From 0df9fe7637dcb8e83b3a8f1faf6917214e235921 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 12:53:52 -0400 Subject: [PATCH 01/24] Many changes to remove encompassing btree MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Phase 1 — New action definitions: - task_msgs/action/TakeoffTask.action — new - task_msgs/action/LandTask.action — new - task_msgs/action/FixedTrajectoryTask.action — goal updated to FixedTrajectory spec Phase 2 — New executables: - takeoff_landing_task.cpp — new takeoff_landing_task executable with TakeoffTask + LandTask action servers (precondition checks, reuses TakeoffTrajectory) - fixed_trajectory_task.cpp — new fixed_trajectory_task executable in trajectory_controller package (ports all 6 trajectory types from Python) - behavior/drone_safety_monitor/ — moved here, adds command topic (pause/resume/rewind) and auto-pause on state estimate timeout Phase 3 — Launch file updates: - local.launch.xml and local_droan_cpu.launch.xml — replaced old nodes with new action server nodes - behavior.launch.xml — replaced BT+BehaviorExecutive with just drone_safety_monitor - Interface bringup and px4_interface launch — removed drone_safety_monitor (now in behavior bringup) Phase 4 — Deleted: behavior_tree/, behavior_executive/, rqt_fixed_trajectory_generator/, interface/drone_safety_monitor/, both copies of fixed_trajectory_generator.py --- .../msgs/task_msgs/CMakeLists.txt | 2 + .../action/FixedTrajectoryTask.action | 6 +- .../msgs/task_msgs/action/LandTask.action | 12 + .../msgs/task_msgs/action/TakeoffTask.action | 15 + .../launch/behavior.launch.xml | 37 +- .../behavior_executive/CMakeLists.txt | 54 -- .../behavior_executive/behavior_executive.hpp | 120 --- .../behavior/behavior_executive/package.xml | 29 - .../src/behavior_executive.cpp | 467 ----------- .../src/behavior/behavior_tree/.gitignore | 2 - .../src/behavior/behavior_tree/CMakeLists.txt | 75 -- .../behavior/behavior_tree/config/drone.tree | 82 -- .../include/behavior_tree/behavior_tree.hpp | 139 ---- .../behavior_tree_implementation.hpp | 194 ----- .../src/behavior/behavior_tree/package.xml | 22 - .../behavior_tree/src/behavior_tree.cpp | 136 ---- .../src/behavior_tree_implementation.cpp | 755 ------------------ .../drone_safety_monitor/CMakeLists.txt | 26 +- .../drone_safety_monitor.hpp | 18 +- .../drone_safety_monitor/package.xml | 10 +- .../src/drone_safety_monitor.cpp | 147 ++++ .../CHANGELOG.rst | 149 ---- .../rqt_fixed_trajectory_generator/README.md | 19 - .../config/fixed_trajectories.yaml | 47 -- .../package.xml | 28 - .../rqt_fixed_trajectory_generator/plugin.xml | 17 - .../resource/py_console_widget.ui | 53 -- .../resource/rqt_fixed_trajectory_generator | 0 .../rqt_fixed_trajectory_generator/setup.cfg | 4 - .../rqt_fixed_trajectory_generator/setup.py | 41 - .../__init__.py | 0 .../rqt_fixed_trajectory_generator/main.py | 12 - .../py_console_text_edit.py | 69 -- .../py_console_widget.py | 59 -- .../spyder_console_widget.py | 60 -- .../template.py | 269 ------- .../gz_behavior_launch.xml | 33 +- .../robot_launch_gazebo/gz_local_launch.xml | 36 +- .../interface/drone_safety_monitor/README.md | 114 --- .../config/takeoff_landing_planner.yaml | 14 - .../launch/takeoff_landing_planner.launch.xml | 18 - .../src/drone_safety_monitor.cpp | 84 -- .../launch/interface.launch.py | 16 +- .../launch/px4_interface.launch.xml | 8 +- .../trajectory_controller/CMakeLists.txt | 16 +- .../trajectory_controller/package.xml | 2 + .../src/fixed_trajectory_task.cpp | 595 ++++++++++++++ .../local_bringup/launch/local.launch.xml | 36 +- .../launch/local_droan_cpu.launch.xml | 36 +- .../takeoff_landing_planner/CMakeLists.txt | 24 +- .../takeoff_landing_task.hpp | 129 +++ .../takeoff_landing_planner/package.xml | 3 + .../src/takeoff_landing_task.cpp | 483 +++++++++++ .../scripts/fixed_trajectory_generator.py | 551 ------------- .../src/fixed_trajectory_generator.py | 453 ----------- scenes/two_drone_RetroNeighborhood.usd | Bin 175503 -> 0 bytes scenes/two_drone_fire_new.usd | Bin 785787 -> 0 bytes 57 files changed, 1528 insertions(+), 4298 deletions(-) create mode 100644 common/ros_packages/msgs/task_msgs/action/LandTask.action create mode 100644 common/ros_packages/msgs/task_msgs/action/TakeoffTask.action delete mode 100644 robot/ros_ws/src/behavior/behavior_executive/CMakeLists.txt delete mode 100644 robot/ros_ws/src/behavior/behavior_executive/include/behavior_executive/behavior_executive.hpp delete mode 100644 robot/ros_ws/src/behavior/behavior_executive/package.xml delete mode 100644 robot/ros_ws/src/behavior/behavior_executive/src/behavior_executive.cpp delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/.gitignore delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/CMakeLists.txt delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/config/drone.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree.hpp delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree_implementation.hpp delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/package.xml delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree.cpp delete mode 100644 robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree_implementation.cpp rename robot/ros_ws/src/{interface => behavior}/drone_safety_monitor/CMakeLists.txt (60%) rename robot/ros_ws/src/{interface => behavior}/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp (83%) rename robot/ros_ws/src/{interface => behavior}/drone_safety_monitor/package.xml (75%) create mode 100644 robot/ros_ws/src/behavior/drone_safety_monitor/src/drone_safety_monitor.cpp delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/CHANGELOG.rst delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/README.md delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/config/fixed_trajectories.yaml delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/package.xml delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/plugin.xml delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/py_console_widget.ui delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/rqt_fixed_trajectory_generator delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.cfg delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.py delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/__init__.py delete mode 100755 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/main.py delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_text_edit.py delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_widget.py delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/spyder_console_widget.py delete mode 100644 robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/template.py delete mode 100644 robot/ros_ws/src/interface/drone_safety_monitor/README.md delete mode 100644 robot/ros_ws/src/interface/drone_safety_monitor/config/takeoff_landing_planner.yaml delete mode 100644 robot/ros_ws/src/interface/drone_safety_monitor/launch/takeoff_landing_planner.launch.xml delete mode 100644 robot/ros_ws/src/interface/drone_safety_monitor/src/drone_safety_monitor.cpp create mode 100644 robot/ros_ws/src/local/controls/trajectory_controller/src/fixed_trajectory_task.cpp create mode 100644 robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp create mode 100644 robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp delete mode 100755 robot/ros_ws/src/local/planners/trajectory_library/scripts/fixed_trajectory_generator.py delete mode 100755 robot/ros_ws/src/local/planners/trajectory_library/src/fixed_trajectory_generator.py delete mode 100644 scenes/two_drone_RetroNeighborhood.usd delete mode 100644 scenes/two_drone_fire_new.usd diff --git a/common/ros_packages/msgs/task_msgs/CMakeLists.txt b/common/ros_packages/msgs/task_msgs/CMakeLists.txt index add09d32e..852f3e2b7 100644 --- a/common/ros_packages/msgs/task_msgs/CMakeLists.txt +++ b/common/ros_packages/msgs/task_msgs/CMakeLists.txt @@ -16,10 +16,12 @@ rosidl_generate_interfaces(${PROJECT_NAME} "action/CoverageTask.action" "action/ExplorationTask.action" "action/FixedTrajectoryTask.action" + "action/LandTask.action" "action/NavigateTask.action" "action/ObjectCountingTask.action" "action/ObjectSearchTask.action" "action/SemanticSearchTask.action" + "action/TakeoffTask.action" DEPENDENCIES action_msgs geometry_msgs nav_msgs airstack_msgs ) diff --git a/common/ros_packages/msgs/task_msgs/action/FixedTrajectoryTask.action b/common/ros_packages/msgs/task_msgs/action/FixedTrajectoryTask.action index d8abff82b..72dfce8cb 100644 --- a/common/ros_packages/msgs/task_msgs/action/FixedTrajectoryTask.action +++ b/common/ros_packages/msgs/task_msgs/action/FixedTrajectoryTask.action @@ -1,8 +1,8 @@ -# Follow a pre-defined trajectory. +# Follow a fixed trajectory specified by type and parameters. # loop: if true, repeat the trajectory indefinitely until cancelled # Goal -airstack_msgs/TrajectoryXYZVYaw trajectory +airstack_msgs/FixedTrajectory trajectory_spec bool loop --- # Result @@ -12,6 +12,4 @@ string message # Feedback string status float32 progress -int32 current_waypoint_index -int32 total_waypoints geometry_msgs/Point current_position diff --git a/common/ros_packages/msgs/task_msgs/action/LandTask.action b/common/ros_packages/msgs/task_msgs/action/LandTask.action new file mode 100644 index 000000000..4e81d5fcd --- /dev/null +++ b/common/ros_packages/msgs/task_msgs/action/LandTask.action @@ -0,0 +1,12 @@ +# Land the robot. + +# Goal +float32 velocity_m_s # 0.0 = use default from config +--- +# Result +bool success +string message +--- +# Feedback +string status +float32 current_altitude_m diff --git a/common/ros_packages/msgs/task_msgs/action/TakeoffTask.action b/common/ros_packages/msgs/task_msgs/action/TakeoffTask.action new file mode 100644 index 000000000..6d78d4daf --- /dev/null +++ b/common/ros_packages/msgs/task_msgs/action/TakeoffTask.action @@ -0,0 +1,15 @@ +# Takeoff to a target altitude. +# Rejects if not armed, no offboard control, or state estimate timed out. + +# Goal +float32 target_altitude_m +float32 velocity_m_s +--- +# Result +bool success +string message +--- +# Feedback +string status +float32 current_altitude_m +float32 target_altitude_m diff --git a/robot/ros_ws/src/behavior/behavior_bringup/launch/behavior.launch.xml b/robot/ros_ws/src/behavior/behavior_bringup/launch/behavior.launch.xml index 7e14ec054..cef093702 100644 --- a/robot/ros_ws/src/behavior/behavior_bringup/launch/behavior.launch.xml +++ b/robot/ros_ws/src/behavior/behavior_bringup/launch/behavior.launch.xml @@ -2,35 +2,14 @@ - - - - + + + + + - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/robot/ros_ws/src/behavior/behavior_executive/CMakeLists.txt b/robot/ros_ws/src/behavior/behavior_executive/CMakeLists.txt deleted file mode 100644 index b84f62f77..000000000 --- a/robot/ros_ws/src/behavior/behavior_executive/CMakeLists.txt +++ /dev/null @@ -1,54 +0,0 @@ -cmake_minimum_required(VERSION 3.8) -project(behavior_executive) - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(rclcpp_action REQUIRED) -find_package(std_msgs REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(task_msgs REQUIRED) -find_package(behavior_tree REQUIRED) -find_package(behavior_tree_msgs REQUIRED) -find_package(airstack_msgs REQUIRED) -find_package(airstack_common REQUIRED) -find_package(mavros_msgs REQUIRED) - -add_executable(behavior_executive src/behavior_executive.cpp) -target_include_directories(behavior_executive PUBLIC - $ - $) -target_compile_features(behavior_executive PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 -ament_target_dependencies(behavior_executive - rclcpp - rclcpp_action - std_msgs - nav_msgs - task_msgs - behavior_tree - behavior_tree_msgs - airstack_msgs - airstack_common - mavros_msgs -) - -install(TARGETS behavior_executive - DESTINATION lib/${PROJECT_NAME}) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # comment the line when a copyright and license is added to all source files - set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # comment the line when this package is in a git repo and when - # a copyright and license is added to all source files - set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/robot/ros_ws/src/behavior/behavior_executive/include/behavior_executive/behavior_executive.hpp b/robot/ros_ws/src/behavior/behavior_executive/include/behavior_executive/behavior_executive.hpp deleted file mode 100644 index b71896cf7..000000000 --- a/robot/ros_ws/src/behavior/behavior_executive/include/behavior_executive/behavior_executive.hpp +++ /dev/null @@ -1,120 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "rclcpp_action/rclcpp_action.hpp" -#include "task_msgs/action/exploration_task.hpp" - -class BehaviorExecutive : public rclcpp::Node { - private: - // parameters - bool ascent_takeoff; - - // variables - std::string takeoff_state, landing_state; - - // Condition variables - bt::Condition* auto_takeoff_commanded_condition; - bt::Condition* takeoff_commanded_condition; - bt::Condition* armed_condition; - bt::Condition* offboard_mode_condition; - bt::Condition* stationary_condition; - bt::Condition* land_commanded_condition; - bt::Condition* pause_commanded_condition; - bt::Condition* rewind_commanded_condition; - bt::Condition* fixed_trajectory_condition; - bt::Condition* global_plan_condition; - bt::Condition* offboard_commanded_condition; - bt::Condition* arm_commanded_condition; - bt::Condition* disarm_commanded_condition; - bt::Condition* takeoff_complete_condition; - bt::Condition* landing_complete_condition; - bt::Condition* in_air_condition; - bt::Condition* state_estimate_timed_out_condition; - bt::Condition* stuck_condition; - bt::Condition* autonomously_explore_condition; - std::vector conditions; - - // Action variables - bt::Action* arm_action; - bt::Action* takeoff_action; - bt::Action* land_action; - bt::Action* pause_action; - bt::Action* rewind_action; - bt::Action* follow_fixed_trajectory_action; - bt::Action* global_plan_action; - bt::Action* request_control_action; - bt::Action* disarm_action; - std::vector actions; - - // subscribers - rclcpp::Subscription::SharedPtr - behavior_tree_commands_sub; - rclcpp::Subscription::SharedPtr is_armed_sub; - rclcpp::Subscription::SharedPtr has_control_sub; - rclcpp::Subscription::SharedPtr takeoff_state_sub; - rclcpp::Subscription::SharedPtr landing_state_sub; - rclcpp::Subscription::SharedPtr state_estimate_timed_out_sub; - rclcpp::Subscription::SharedPtr stuck_sub; - - // publishers - rclcpp::Publisher::SharedPtr recording_pub; - rclcpp::Publisher::SharedPtr reset_stuck_pub; - rclcpp::Publisher::SharedPtr clear_map_pub; - - // services - rclcpp::CallbackGroup::SharedPtr service_callback_group; - rclcpp::Client::SharedPtr robot_command_client; - rclcpp::Client::SharedPtr trajectory_mode_client; - rclcpp::Client::SharedPtr - takeoff_landing_command_client; - - // action clients - using ExplorationTask = task_msgs::action::ExplorationTask; - rclcpp_action::Client::SharedPtr exploration_client_; - rclcpp_action::ClientGoalHandle::SharedPtr exploration_goal_handle_; - bool exploration_goal_done_ = true; - bool exploration_goal_succeeded_ = false; - - // timers - rclcpp::TimerBase::SharedPtr timer; - - // callbacks - void timer_callback(); - void bt_commands_callback(behavior_tree_msgs::msg::BehaviorTreeCommands msg); - void is_armed_callback(const std_msgs::msg::Bool::SharedPtr msg); - void has_control_callback(const std_msgs::msg::Bool::SharedPtr msg); - void takeoff_state_callback(const std_msgs::msg::String::SharedPtr msg); - void landing_state_callback(const std_msgs::msg::String::SharedPtr msg); - void state_estimate_timed_out_callback(const std_msgs::msg::Bool::SharedPtr msg); - void stuck_callback(const std_msgs::msg::Bool::SharedPtr msg); - - public: - BehaviorExecutive(); -}; diff --git a/robot/ros_ws/src/behavior/behavior_executive/package.xml b/robot/ros_ws/src/behavior/behavior_executive/package.xml deleted file mode 100644 index d1ae9fce8..000000000 --- a/robot/ros_ws/src/behavior/behavior_executive/package.xml +++ /dev/null @@ -1,29 +0,0 @@ - - - - behavior_executive - 0.0.0 - TODO: Package description - uav - TODO: License declaration - - ament_cmake - - rclcpp - rclcpp_action - std_msgs - nav_msgs - task_msgs - behavior_tree - behavior_tree_msgs - airstack_msgs - airstack_common - mavros_msgs - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/robot/ros_ws/src/behavior/behavior_executive/src/behavior_executive.cpp b/robot/ros_ws/src/behavior/behavior_executive/src/behavior_executive.cpp deleted file mode 100644 index 9dc0900ba..000000000 --- a/robot/ros_ws/src/behavior/behavior_executive/src/behavior_executive.cpp +++ /dev/null @@ -1,467 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include - -BehaviorExecutive::BehaviorExecutive() : Node("behavior_executive") -{ - // conditions - auto_takeoff_commanded_condition = new bt::Condition("Auto Takeoff Commanded", this); - takeoff_commanded_condition = new bt::Condition("Takeoff Commanded", this); - armed_condition = new bt::Condition("Armed", this); - offboard_mode_condition = new bt::Condition("Offboard Mode", this); - stationary_condition = new bt::Condition("Stationary", this); - land_commanded_condition = new bt::Condition("Land Commanded", this); - pause_commanded_condition = new bt::Condition("Pause Commanded", this); - rewind_commanded_condition = new bt::Condition("Rewind Commanded", this); - fixed_trajectory_condition = new bt::Condition("Fixed Trajectory Commanded", this); - global_plan_condition = new bt::Condition("Global Plan Commanded", this); - offboard_commanded_condition = new bt::Condition("Offboard Commanded", this); - arm_commanded_condition = new bt::Condition("Arm Commanded", this); - disarm_commanded_condition = new bt::Condition("Disarm Commanded", this); - takeoff_complete_condition = new bt::Condition("Takeoff Complete", this); - landing_complete_condition = new bt::Condition("Landing Complete", this); - in_air_condition = new bt::Condition("In Air", this); - state_estimate_timed_out_condition = new bt::Condition("State Estimate Timed Out", this); - stuck_condition = new bt::Condition("Stuck", this); - autonomously_explore_condition = new bt::Condition("Autonomously Explore Commanded", this); - conditions.push_back(auto_takeoff_commanded_condition); - conditions.push_back(takeoff_commanded_condition); - conditions.push_back(armed_condition); - conditions.push_back(offboard_mode_condition); - conditions.push_back(stationary_condition); - conditions.push_back(land_commanded_condition); - conditions.push_back(pause_commanded_condition); - conditions.push_back(rewind_commanded_condition); - conditions.push_back(fixed_trajectory_condition); - conditions.push_back(global_plan_condition); - conditions.push_back(offboard_commanded_condition); - conditions.push_back(arm_commanded_condition); - conditions.push_back(disarm_commanded_condition); - conditions.push_back(takeoff_complete_condition); - conditions.push_back(landing_complete_condition); - conditions.push_back(in_air_condition); - conditions.push_back(state_estimate_timed_out_condition); - conditions.push_back(stuck_condition); - conditions.push_back(autonomously_explore_condition); - - // actions - arm_action = new bt::Action("Arm", this); - takeoff_action = new bt::Action("Takeoff", this); - land_action = new bt::Action("Land", this); - pause_action = new bt::Action("Pause", this); - rewind_action = new bt::Action("Rewind", this); - follow_fixed_trajectory_action = new bt::Action("Follow Fixed Trajectory", this); - global_plan_action = new bt::Action("Follow Global Plan", this); - request_control_action = new bt::Action("Request Control", this); - disarm_action = new bt::Action("Disarm", this); - actions.push_back(arm_action); - actions.push_back(takeoff_action); - actions.push_back(land_action); - actions.push_back(pause_action); - actions.push_back(rewind_action); - actions.push_back(follow_fixed_trajectory_action); - actions.push_back(global_plan_action); - actions.push_back(request_control_action); - actions.push_back(disarm_action); - - // subscribers - behavior_tree_commands_sub = - this->create_subscription( - "behavior_tree_commands", 1, - std::bind(&BehaviorExecutive::bt_commands_callback, this, std::placeholders::_1)); - is_armed_sub = this->create_subscription( - "is_armed", 1, - std::bind(&BehaviorExecutive::is_armed_callback, this, std::placeholders::_1)); - has_control_sub = this->create_subscription( - "has_control", 1, - std::bind(&BehaviorExecutive::has_control_callback, this, std::placeholders::_1)); - takeoff_state_sub = this->create_subscription("takeoff_state", 1, - std::bind(&BehaviorExecutive::takeoff_state_callback, - this, std::placeholders::_1)); - landing_state_sub = this->create_subscription("landing_state", 1, - std::bind(&BehaviorExecutive::landing_state_callback, - this, std::placeholders::_1)); - state_estimate_timed_out_sub = - this->create_subscription("state_estimate_timed_out", 1, - std::bind(&BehaviorExecutive::state_estimate_timed_out_callback, - this, std::placeholders::_1)); - stuck_sub = - this->create_subscription("stuck", 1, - std::bind(&BehaviorExecutive::stuck_callback, - this, std::placeholders::_1)); - - // publishers - recording_pub = this->create_publisher("set_recording_status", 1); - reset_stuck_pub = this->create_publisher("reset_stuck", 1); - clear_map_pub = this->create_publisher("clear_map", 1); - - // services - service_callback_group = - this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); - robot_command_client = this->create_client( - "robot_command", rmw_qos_profile_services_default, service_callback_group); - trajectory_mode_client = this->create_client( - "set_trajectory_mode", rmw_qos_profile_services_default, service_callback_group); - takeoff_landing_command_client = this->create_client( - "set_takeoff_landing_command", rmw_qos_profile_services_default, service_callback_group); - - // action clients - exploration_client_ = rclcpp_action::create_client(this, "exploration_task"); - - // timers - timer = rclcpp::create_timer(this, this->get_clock(), rclcpp::Duration::from_seconds(1. / 20.), - std::bind(&BehaviorExecutive::timer_callback, this)); -} - -void BehaviorExecutive::timer_callback() -{ - if (request_control_action->is_active()) - { - if (request_control_action->active_has_changed()) - { - airstack_msgs::srv::RobotCommand::Request::SharedPtr request = - std::make_shared(); - request->command = airstack_msgs::srv::RobotCommand::Request::REQUEST_CONTROL; - - auto result = robot_command_client->async_send_request(request); - std::cout << "waiting be rc" << std::endl; - result.wait(); - std::cout << "done be rc" << std::endl; - if (result.get()->success) - request_control_action->set_success(); - else - request_control_action->set_failure(); - } - } - - if (arm_action->is_active()) - { - if (arm_action->active_has_changed()) - { - std_msgs::msg::Bool start_msg; - start_msg.data = true; - recording_pub->publish(start_msg); - - airstack_msgs::srv::RobotCommand::Request::SharedPtr request = - std::make_shared(); - request->command = airstack_msgs::srv::RobotCommand::Request::ARM; - - auto result = robot_command_client->async_send_request(request); - std::cout << "waiting be arm" << std::endl; - result.wait(); - std::cout << "done be arm" << std::endl; - if (result.get()->success) - arm_action->set_success(); - else - arm_action->set_failure(); - } - } - - if (disarm_action->is_active()) - { - if (disarm_action->active_has_changed()) - { - std_msgs::msg::Bool stop_msg; - stop_msg.data = false; - recording_pub->publish(stop_msg); - - in_air_condition->set(false); - airstack_msgs::srv::RobotCommand::Request::SharedPtr request = - std::make_shared(); - request->command = airstack_msgs::srv::RobotCommand::Request::DISARM; - - auto result = robot_command_client->async_send_request(request); - std::cout << "waiting be arm" << std::endl; - result.wait(); - std::cout << "done be arm" << std::endl; - if (result.get()->success) - disarm_action->set_success(); - else - disarm_action->set_failure(); - } - } - - if (takeoff_action->is_active()) - { - // std::cout << "takeoff" << std::endl; - takeoff_action->set_running(); - in_air_condition->set(true); - reset_stuck_pub->publish(std_msgs::msg::Empty()); - - if (takeoff_action->active_has_changed()) - { - // clear the local planner's map - clear_map_pub->publish(std_msgs::msg::Empty()); - - // put trajectory controller in track mode - airstack_msgs::srv::TrajectoryMode::Request::SharedPtr mode_request = - std::make_shared(); - mode_request->mode = airstack_msgs::srv::TrajectoryMode::Request::TRACK; - auto mode_result = trajectory_mode_client->async_send_request(mode_request); - std::cout << "trajectory mode request sent" << std::endl; - mode_result.wait(); - std::cout << "trajectory mode request confirmed received" << std::endl; - - if (mode_result.get()->success) - { - // send a takeoff command to ardupilot - // TODO clean up variable names - airstack_msgs::srv::RobotCommand::Request::SharedPtr request = - std::make_shared(); - request->command = airstack_msgs::srv::RobotCommand::Request::TAKEOFF; - - auto result = robot_command_client->async_send_request(request); - std::cout << "waiting robot command takeoff" << std::endl; - result.wait(); - std::cout << "done robot command takeoff" << std::endl; - - // send the takeoff trajectory - if (result.get()->success) - { - airstack_msgs::srv::TakeoffLandingCommand::Request::SharedPtr takeoff_request = - std::make_shared(); - takeoff_request->command = - airstack_msgs::srv::TakeoffLandingCommand::Request::TAKEOFF; - auto takeoff_result = - takeoff_landing_command_client->async_send_request(takeoff_request); - std::cout << "takeoff request sent" << std::endl; - takeoff_result.wait(); - std::cout << "takeoff request confirmed received" << std::endl; - if (!takeoff_result.get()->accepted) - takeoff_action->set_failure(); - } - else - takeoff_action->set_failure(); - } - else - takeoff_action->set_failure(); - } - - if (takeoff_state == "COMPLETE") - { - takeoff_complete_condition->set(true); - takeoff_action->set_success(); - } - } - - if (land_action->is_active()) - { - // std::cout << "land" << std::endl; - land_action->set_running(); - if (land_action->active_has_changed()) - { - // put trajectory controller in track mode - airstack_msgs::srv::TrajectoryMode::Request::SharedPtr mode_request = - std::make_shared(); - mode_request->mode = airstack_msgs::srv::TrajectoryMode::Request::TRACK; - auto mode_result = trajectory_mode_client->async_send_request(mode_request); - std::cout << "trajectory mode request sent" << std::endl; - mode_result.wait(); - std::cout << "trajectory mode request confirmed received" << std::endl; - - if (mode_result.get()->success) - { - airstack_msgs::srv::TakeoffLandingCommand::Request::SharedPtr land_request = - std::make_shared(); - land_request->command = airstack_msgs::srv::TakeoffLandingCommand::Request::LAND; - auto land_result = takeoff_landing_command_client->async_send_request(land_request); - std::cout << "land 1" << std::endl; - land_result.wait(); - std::cout << "land 2" << std::endl; - if (land_result.get()->accepted) - land_action->set_success(); - else - land_action->set_failure(); - } - else - land_action->set_failure(); - } - - if (landing_state == "COMPLETE") - { - landing_complete_condition->set(true); - land_action->set_success(); - } - } - - if (pause_action->is_active()) - { - pause_action->set_running(); - if (pause_action->active_has_changed()) - { - airstack_msgs::srv::TrajectoryMode::Request::SharedPtr mode_request = - std::make_shared(); - mode_request->mode = airstack_msgs::srv::TrajectoryMode::Request::PAUSE; - auto mode_result = trajectory_mode_client->async_send_request(mode_request); - mode_result.wait(); - } - } - - if (rewind_action->is_active()) - { - rewind_action->set_running(); - if (rewind_action->active_has_changed()) - { - airstack_msgs::srv::TrajectoryMode::Request::SharedPtr mode_request = - std::make_shared(); - mode_request->mode = airstack_msgs::srv::TrajectoryMode::Request::REWIND; - auto mode_result = trajectory_mode_client->async_send_request(mode_request); - mode_result.wait(); - } - } - - // follow fixed trajectory action - if (follow_fixed_trajectory_action->is_active()) - { - follow_fixed_trajectory_action->set_running(); - - if (follow_fixed_trajectory_action->active_has_changed()) - { - // put trajectory controller in track mode - airstack_msgs::srv::TrajectoryMode::Request::SharedPtr mode_request = - std::make_shared(); - mode_request->mode = airstack_msgs::srv::TrajectoryMode::Request::TRACK; - auto mode_result = trajectory_mode_client->async_send_request(mode_request); - std::cout << "trajectory mode request sent" << std::endl; - mode_result.wait(); - std::cout << "trajectory mode request confirmed received" << std::endl; - } - } - - if (global_plan_action->is_active()) - { - global_plan_action->set_running(); - if (global_plan_action->active_has_changed()) - { - auto goal = ExplorationTask::Goal(); - goal.min_altitude_agl = 2.0f; - goal.max_altitude_agl = 20.0f; - goal.min_flight_speed = 1.0f; - goal.max_flight_speed = 5.0f; - goal.time_limit_sec = 0.0f; // no limit - - exploration_goal_done_ = false; - exploration_goal_succeeded_ = false; - - auto options = rclcpp_action::Client::SendGoalOptions(); - options.goal_response_callback = - [this](const rclcpp_action::ClientGoalHandle::SharedPtr& gh) { - exploration_goal_handle_ = gh; - if (!gh) { - RCLCPP_WARN(this->get_logger(), "ExplorationTask goal rejected"); - exploration_goal_done_ = true; - } - }; - options.result_callback = - [this](const rclcpp_action::ClientGoalHandle::WrappedResult& result) { - exploration_goal_succeeded_ = - (result.code == rclcpp_action::ResultCode::SUCCEEDED) && result.result->success; - exploration_goal_done_ = true; - }; - exploration_client_->async_send_goal(goal, options); - RCLCPP_INFO(this->get_logger(), "Sent ExplorationTask goal"); - } - - if (exploration_goal_done_) - { - if (exploration_goal_succeeded_) - global_plan_action->set_success(); - else - global_plan_action->set_failure(); - } - } - - for (bt::Condition *condition : conditions) - condition->publish(); - for (bt::Action *action : actions) - action->publish(); -} - -// callbacks - -/** - * @brief Parses behavior tree commands and updates conditions accordingly - * - * @param msg - */ -void BehaviorExecutive::bt_commands_callback(behavior_tree_msgs::msg::BehaviorTreeCommands msg) -{ - for (int i = 0; i < msg.commands.size(); i++) - { - std::string condition_name = msg.commands[i].condition_name; - int status = msg.commands[i].status; - - for (int j = 0; j < conditions.size(); j++) - { - bt::Condition *condition = conditions[j]; - if (condition_name == condition->get_label()) - { - if (status == behavior_tree_msgs::msg::Status::SUCCESS) - condition->set(true); - else if (status == behavior_tree_msgs::msg::Status::FAILURE) - condition->set(false); - } - } - } -} - -void BehaviorExecutive::is_armed_callback(const std_msgs::msg::Bool::SharedPtr msg) -{ - armed_condition->set(msg->data); -} - -void BehaviorExecutive::has_control_callback(const std_msgs::msg::Bool::SharedPtr msg) -{ - offboard_mode_condition->set(msg->data); -} - -void BehaviorExecutive::takeoff_state_callback(const std_msgs::msg::String::SharedPtr msg) -{ - takeoff_state = msg->data; -} - -void BehaviorExecutive::landing_state_callback(const std_msgs::msg::String::SharedPtr msg) -{ - landing_state = msg->data; -} - -void BehaviorExecutive::state_estimate_timed_out_callback(const std_msgs::msg::Bool::SharedPtr msg) -{ - state_estimate_timed_out_condition->set(msg->data); -} - -void BehaviorExecutive::stuck_callback(const std_msgs::msg::Bool::SharedPtr msg) -{ - stuck_condition->set(msg->data); -} - -int main(int argc, char **argv) -{ - rclcpp::init(argc, argv); - std::shared_ptr node = std::make_shared(); - - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(node); - executor.spin(); - rclcpp::shutdown(); - - return 0; -} diff --git a/robot/ros_ws/src/behavior/behavior_tree/.gitignore b/robot/ros_ws/src/behavior/behavior_tree/.gitignore deleted file mode 100644 index e6458330d..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -*~ -*.pyc \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree/CMakeLists.txt b/robot/ros_ws/src/behavior/behavior_tree/CMakeLists.txt deleted file mode 100644 index 00372fad8..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/CMakeLists.txt +++ /dev/null @@ -1,75 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(behavior_tree) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) -find_package(behavior_tree_msgs REQUIRED) -find_package(Boost REQUIRED COMPONENTS iostreams) - -include_directories(include ${rclcpp_INCLUDE_DIRS} ${behavior_tree_msgs_INCLUDE_DIRS}) - -add_executable(behavior_tree_implementation src/behavior_tree_implementation.cpp) -target_compile_features(behavior_tree_implementation PUBLIC c_std_99 cxx_std_17) -target_link_libraries(behavior_tree_implementation - ${Boost_LIBRARIES} - ${rclcpp_LIBRARIES} - ${std_msgs_LIBRARIES} - ${behavior_tree_msgs_LIBRARIES}) -#ament_target_dependencies(behavior_tree_implementation rclcpp std_msgs behavior_tree_msgs) - -add_library(behavior_tree src/behavior_tree.cpp) -ament_target_dependencies(behavior_tree rclcpp std_msgs behavior_tree_msgs) -ament_export_targets(behavior_tree HAS_LIBRARY_TARGET) - -install( - DIRECTORY include/behavior_tree - DESTINATION include - ) - -install( - TARGETS behavior_tree - EXPORT behavior_tree - LIBRARY DESTINATION lib - ARCHIVE DESTINATION lib - RUNTIME DESTINATION bin - INCLUDES DESTINATION include -) - -install(TARGETS - behavior_tree_implementation - DESTINATION lib/${PROJECT_NAME}) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # uncomment the line when a copyright and license is not present in all source files - #set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # uncomment the line when this package is not in a git repo - #set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() -endif() - -# Install files. -# install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) -# install(DIRECTORY rviz DESTINATION share/${PROJECT_NAME}) -install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) -# install(DIRECTORY params DESTINATION share/${PROJECT_NAME}) - -ament_package() diff --git a/robot/ros_ws/src/behavior/behavior_tree/config/drone.tree b/robot/ros_ws/src/behavior/behavior_tree/config/drone.tree deleted file mode 100644 index bf28299ed..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/config/drone.tree +++ /dev/null @@ -1,82 +0,0 @@ -? - -> - (Auto Takeoff Commanded) - -> - - (State Estimate Timed Out) - ? - (In Air) - (Armed) - (Offboard Mode) - [Request Control] - ? - (In Air) - (Armed) - [Arm] - ? - (Takeoff Complete) - [Takeoff] - -> - (Takeoff Commanded) - ? - (Takeoff Complete) - [Takeoff] - -> - (Land Commanded) - ? - (Landing Complete) - [Land] - -> - (Pause Commanded) - ? - [Pause] - -> - (Rewind Commanded) - ? - [Rewind] - -> - (Fixed Trajectory Commanded) - ? - [Follow Fixed Trajectory] - -> - (Global Plan Commanded) - ? - [Follow Global Plan] - -> - (Offboard Commanded) - ? - (Offboard Mode) - [Request Control] - -> - (Arm Commanded) - ? - (Armed) - [Arm] - -> - (Disarm Commanded) - ? - - (Armed) - [Disarm] - -> - (Autonomously Explore Commanded) - -> - - (State Estimate Timed Out) - ? - (In Air) - (Armed) - (Offboard Mode) - [Request Control] - ? - (In Air) - (Armed) - [Arm] - ? - (Takeoff Complete) - [Takeoff] - ? - -> - (Stuck) - [Rewind] - [Follow Global Plan] \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree.hpp b/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree.hpp deleted file mode 100644 index 2c1b9a6ed..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree.hpp +++ /dev/null @@ -1,139 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace bt { - -class Condition { - private: - std_msgs::msg::Bool success; - std::string label; - - rclcpp::Publisher::SharedPtr success_pub; - - public: - Condition(std::string label, rclcpp::Node* node); - void set(bool b); - void publish(); - bool get(); - std::string get_label(); - - static std::string get_published_topic_name(std::string label); -}; - -class Action { - private: - bool active, prev_active, active_changed; - uint64_t current_id; - behavior_tree_msgs::msg::Status status; - std::string label; - - rclcpp::Subscription::SharedPtr active_sub; - rclcpp::Publisher::SharedPtr status_pub; - - void active_callback(const behavior_tree_msgs::msg::Active::SharedPtr msg); - - std::function active_callback_func; - std::function inactive_callback_func; - - void init(std::string label, rclcpp::Node* node); - - public: - Action(std::string label, rclcpp::Node* node); - - // constructor for active and inactive callback that are class members - template - Action(std::string label, rclcpp::Node* node, void (ActiveClassType::*active_callback)(), - ActiveClassType* active_class_object, void (InactiveClassType::*inactive_callback)(), - InactiveClassType* inactive_class_object) { - init(label, node); - active_callback_func = std::bind(active_callback, active_class_object); - inactive_callback_func = std::bind(inactive_callback, inactive_class_object); - } - - // constructor for an active callback that is a class member - template - Action(std::string label, rclcpp::Node* node, void (ActiveClassType::*active_callback)(), - ActiveClassType* active_class_object) { - init(label, node); - active_callback_func = std::bind(active_callback, active_class_object); - } - - // constructor for active and inactive callbacks that are not class members. The inactive - // callback is optional - Action(std::string label, rclcpp::Node* node, void (*active_callback)(), - void (*inactive_callback)() = NULL) { - init(label, node); - active_callback_func = active_callback; - inactive_callback_func = inactive_callback; - } - - // constructor for an active callback that is not a class member and inactive callback that is a - // class member - template - Action(std::string label, rclcpp::Node* node, void (*active_callback)(), - void (InactiveClassType::*inactive_callback)(), - InactiveClassType* inactive_class_object) { - init(label, node); - active_callback_func = active_callback; - inactive_callback_func = std::bind(inactive_callback, inactive_class_object); - } - - // constructor for an active callback that is a class member and inactive callback that is not a - // class member - template - Action(std::string label, rclcpp::Node* node, void (ActiveClassType::*active_callback)(), - ActiveClassType* active_class_object, void (*inactive_callback)()) { - init(label, node); - active_callback_func = std::bind(active_callback, active_class_object); - inactive_callback_func = inactive_callback; - } - - static std::string get_published_topic_name(std::string label); - static std::string get_subscribed_topic_name(std::string label); - - void set_success(); - void set_running(); - void set_failure(); - - bool is_active(); - bool active_has_changed(); - - bool is_success(); - bool is_running(); - bool is_failure(); - - std::string get_label(); - - void publish(); -}; - -}; // namespace bt diff --git a/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree_implementation.hpp b/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree_implementation.hpp deleted file mode 100644 index 8d142abe2..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/include/behavior_tree/behavior_tree_implementation.hpp +++ /dev/null @@ -1,194 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -//=============================================================================================== -// ------------------------------------- Base Node Class ---------------------------------------- -//=============================================================================================== - -class Node { - private: - public: - static double max_wait_time; - - std::string label; - bool is_active; - uint8_t status; - std::vector children; - - virtual void add_child(Node*); - virtual bool tick(bool active, int traversal_count) = 0; -}; - -//=============================================================================================== -// ------------------------------------ Control Flow Nodes ------------------------------------- -//=============================================================================================== - -class ControlFlowNode : public Node { - private: - public: -}; - -class FallbackNode : public ControlFlowNode { - private: - public: - FallbackNode(); - bool tick(bool active, int traversal_count) override; -}; - -class SequenceNode : public ControlFlowNode { - private: - public: - SequenceNode(); - bool tick(bool active, int traversal_count) override; -}; - -class ParallelNode : public ControlFlowNode { - private: - public: - int child_success_threshold; - ParallelNode(int child_success_threshold); - bool tick(bool active, int traversal_count) override; -}; - -//=============================================================================================== -// -------------------------------------- Execution Nodes -------------------------------------- -//=============================================================================================== - -class ExecutionNode : public Node { - private: - public: - rclcpp::Time status_modification_time; - int current_traversal_count; - rclcpp::Node* node; - // rclcpp::Subscription subscriber; - // rclcpp::Publisher publisher; - - ExecutionNode(rclcpp::Node* node); - void init_ros(); - virtual std::string get_publisher_name() = 0; - virtual void init_publisher() = 0; - virtual std::string get_subscriber_name() = 0; - virtual void init_subscriber() = 0; - void set_status(uint8_t status); - double get_status_age(); -}; - -class ConditionNode : public ExecutionNode { - private: - bool callback_status_updated; - // rclcpp::Node* node; - - public: - rclcpp::Subscription::SharedPtr subscriber; - // rclcpp::Publisher<>::SharedPtr publisher; - - ConditionNode(std::string label, rclcpp::Node* node); - bool tick(bool active, int traversal_count) override; - std::string get_publisher_name() override; - void init_publisher() override; - std::string get_subscriber_name() override; - void init_subscriber() override; - void callback(const std_msgs::msg::Bool::SharedPtr msg); -}; - -class ActionNode : public ExecutionNode { - private: - int current_id; - bool publisher_initialized; - bool callback_status_updated; - - public: - bool is_newly_active; - - // rclcpp::Node* node; - - rclcpp::Subscription::SharedPtr subscriber; - rclcpp::Publisher::SharedPtr publisher; - - ActionNode(std::string label, rclcpp::Node* node); - bool tick(bool active, int traversal_count) override; - std::string get_publisher_name() override; - void init_publisher() override; - std::string get_subscriber_name() override; - void init_subscriber() override; - void callback(const behavior_tree_msgs::msg::Status::SharedPtr msg); - void publish_active_msg(int active_id); -}; - -//=============================================================================================== -// -------------------------------------- Decorator Nodes -------------------------------------- -//=============================================================================================== - -class DecoratorNode : public Node { - private: - public: - void add_child(Node* node) override; -}; - -class NotNode : public DecoratorNode { - private: - public: - NotNode(); - void add_child(Node* node) override; - bool tick(bool active, int traversal_count) override; -}; - -//=============================================================================================== -// --------------------------------------- Behavior Tree --------------------------------------- -//=============================================================================================== - -class BehaviorTree { - public: - rclcpp::Node* ros2_node; - std::string config_filename; - std::vector nodes; - Node* root; - int traversal_count; - std::unordered_map active_ids; - rclcpp::Publisher::SharedPtr active_actions_pub; - rclcpp::Publisher::SharedPtr graphviz_pub; - rclcpp::Publisher::SharedPtr compressed_pub; - bool first_tick; - - void parse_config(); - int count_tabs(std::string str); - std::string strip_space(std::string str); - std::string strip_brackets(std::string str); - std::vector get_arguments(std::string str); - std::string get_graphviz(); - // public: - BehaviorTree(std::string config_filename, rclcpp::Node* node); - bool tick(); -}; diff --git a/robot/ros_ws/src/behavior/behavior_tree/package.xml b/robot/ros_ws/src/behavior/behavior_tree/package.xml deleted file mode 100644 index a99a5382d..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - behavior_tree - 0.0.0 - TODO: Package description - john - TODO: License declaration - - ament_cmake - - behavior_tree_msgs - std_msgs - rclcpp - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree.cpp b/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree.cpp deleted file mode 100644 index 0661b90ae..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree.cpp +++ /dev/null @@ -1,136 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include - -namespace bt { - -// ============================================================================== -// -------------------------------- Condition ----------------------------------- -// ============================================================================== - -std::string Condition::get_published_topic_name(std::string label) { - std::string topic_name = label; - std::transform(topic_name.begin(), topic_name.end(), topic_name.begin(), ::tolower); - std::replace(topic_name.begin(), topic_name.end(), ' ', '_'); - topic_name += "_success"; - return topic_name; -} - -Condition::Condition(std::string label, rclcpp::Node* node) { - // ros::NodeHandle nh; - this->label = label; - // success_pub = nh.advertise(Condition::get_published_topic_name(label), 10); - success_pub = - node->create_publisher(Condition::get_published_topic_name(label), 10); - success.data = false; -} - -std::string Condition::get_label() { return label; } - -void Condition::set(bool b) { success.data = b; } - -bool Condition::get() { return success.data; } - -void Condition::publish() { success_pub->publish(success); } - -// ============================================================================== -// --------------------------------- Action ------------------------------------- -// ============================================================================== - -std::string Action::get_published_topic_name(std::string label) { - std::string topic_name = label; - std::transform(topic_name.begin(), topic_name.end(), topic_name.begin(), ::tolower); - std::replace(topic_name.begin(), topic_name.end(), ' ', '_'); - topic_name += "_status"; - return topic_name; -} - -std::string Action::get_subscribed_topic_name(std::string label) { - std::string topic_name = label; - std::transform(topic_name.begin(), topic_name.end(), topic_name.begin(), ::tolower); - std::replace(topic_name.begin(), topic_name.end(), ' ', '_'); - topic_name += "_active"; - return topic_name; -} - -Action::Action(std::string label, rclcpp::Node* node) { init(label, node); } - -void Action::init(std::string label, rclcpp::Node* node) { - // ros::NodeHandle nh; - active_sub = node->create_subscription( - Action::get_subscribed_topic_name(label), 10, - std::bind(&Action::active_callback, this, std::placeholders::_1)); - status_pub = node->create_publisher( - Action::get_published_topic_name(label), 1); - - active = false; - prev_active = false; - active_changed = false; - status.status = behavior_tree_msgs::msg::Status::FAILURE; - - active_callback_func = NULL; - inactive_callback_func = NULL; - - this->label = label; -} - -void Action::active_callback(const behavior_tree_msgs::msg::Active::SharedPtr msg) { - bool active_changed = active != msg->active; - - active = msg->active; - current_id = msg->id; - - if (active_changed && active_callback_func != NULL) { - if (active) - active_callback_func(); - else - inactive_callback_func(); - } -} - -void Action::set_success() { status.status = behavior_tree_msgs::msg::Status::SUCCESS; } - -void Action::set_running() { status.status = behavior_tree_msgs::msg::Status::RUNNING; } - -void Action::set_failure() { status.status = behavior_tree_msgs::msg::Status::FAILURE; } - -bool Action::is_active() { - active_changed = prev_active != active; - prev_active = active; - return active; -} - -bool Action::active_has_changed() { return active_changed; } - -bool Action::is_success() { return status.status == behavior_tree_msgs::msg::Status::SUCCESS; } - -bool Action::is_running() { return status.status == behavior_tree_msgs::msg::Status::RUNNING; } - -bool Action::is_failure() { return status.status == behavior_tree_msgs::msg::Status::FAILURE; } - -std::string Action::get_label() { return label; } - -void Action::publish() { - status.id = current_id; - status_pub->publish(status); -} - -}; // namespace bt diff --git a/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree_implementation.cpp b/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree_implementation.cpp deleted file mode 100644 index 2d0f2c0ba..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree/src/behavior_tree_implementation.cpp +++ /dev/null @@ -1,755 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -//=============================================================================================== -// ------------------------------------- Base Node Class ---------------------------------------- -//=============================================================================================== - -double Node::max_wait_time = 1.0; - -void Node::add_child(Node* node) { children.push_back(node); } - -//=============================================================================================== -// ------------------------------------ Control Flow Nodes ------------------------------------- -//=============================================================================================== - -FallbackNode::FallbackNode() { - label = "?"; - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; -} - -bool FallbackNode::tick(bool active, int traversal_count) { - uint8_t prev_status = status; - bool child_changed = false; - - if (!active) { - // TODO: is ticking children necessary if inactive? - for (int i = 0; i < children.size(); i++) - child_changed |= children[i]->tick(false, traversal_count); - } else { - status = behavior_tree_msgs::msg::Status::FAILURE; - for (int i = 0; i < children.size(); i++) { - Node* child = children[i]; - if (status == behavior_tree_msgs::msg::Status::FAILURE) { - child_changed |= child->tick(true, traversal_count); - status = child->status; - } else - child_changed |= child->tick(false, traversal_count); - } - } - - bool status_changed = (status != prev_status) || child_changed; - bool active_changed = (is_active != active); - - is_active = active; - - return status_changed || active_changed; -} - -SequenceNode::SequenceNode() { - label = "->"; //"\u2192"; // unicode arrow character - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; -} - -bool SequenceNode::tick(bool active, int traversal_count) { - uint8_t prev_status = status; - bool child_changed = false; - - if (!active) { - for (int i = 0; i < children.size(); i++) - child_changed |= children[i]->tick(false, traversal_count); - - } else { - status = behavior_tree_msgs::msg::Status::SUCCESS; - for (int i = 0; i < children.size(); i++) { - Node* child = children[i]; - if (status == behavior_tree_msgs::msg::Status::SUCCESS) { - child_changed |= child->tick(true, traversal_count); - status = child->status; - } else - child_changed |= child->tick(false, traversal_count); - } - } - - bool status_changed = (status != prev_status) || child_changed; - bool active_changed = (is_active != active); - - is_active = active; - - return status_changed || active_changed; -} - -ParallelNode::ParallelNode(int child_success_threshold) { - label = "||"; - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; - this->child_success_threshold = child_success_threshold; -} - -bool ParallelNode::tick(bool active, int traversal_count) { - uint8_t prev_status = status; - bool child_changed = false; - - if (!active) { - for (int i = 0; i < children.size(); i++) - child_changed |= children[i]->tick(false, traversal_count); - } else { - int child_success_count = 0; - int child_failure_count = 0; - for (int i = 0; i < children.size(); i++) { - Node* child = children[i]; - child_changed |= child->tick(true, traversal_count); - - if (child->status == behavior_tree_msgs::msg::Status::SUCCESS) - child_success_count++; - else if (child->status == behavior_tree_msgs::msg::Status::FAILURE) - child_failure_count++; - } - - if (child_success_count >= child_success_threshold) - status = behavior_tree_msgs::msg::Status::SUCCESS; - else if (child_failure_count >= (children.size() - child_success_threshold + 1)) - status = behavior_tree_msgs::msg::Status::FAILURE; - else - status = behavior_tree_msgs::msg::Status::RUNNING; - } - - bool status_changed = (status != prev_status) || child_changed; - bool active_changed = (is_active != active); - - is_active = active; - - return status_changed || active_changed; -} - -//=============================================================================================== -// -------------------------------------- Execution Nodes -------------------------------------- -//=============================================================================================== - -ExecutionNode::ExecutionNode(rclcpp::Node* node) : node(node) {} - -void ExecutionNode::init_ros() { - init_publisher(); - init_subscriber(); -} - -void ExecutionNode::set_status(uint8_t status) { - this->status = status; - status_modification_time = node->get_clock()->now(); // rclcpp::Time::now(); -} - -double ExecutionNode::get_status_age() { - // return (rclcpp::Time::now() - status_modification_time).toSec(); - return (node->get_clock()->now() - status_modification_time).seconds(); -} - -ConditionNode::ConditionNode(std::string label, rclcpp::Node* node) : ExecutionNode(node) { - this->label = label; - status_modification_time = node->get_clock()->now(); // rclcpp::Time::now(); - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; - current_traversal_count = -1; - callback_status_updated = false; -} - -bool ConditionNode::tick(bool active, int traversal_count) { - // if(active) - // ROS_INFO_STREAM("Condition " << label << " active"); - - uint8_t prev_status = status; - bool child_changed = false; - - if (current_traversal_count != traversal_count) - current_traversal_count = traversal_count; - else if (is_active) - return false; // TODO: is this correct? - - if (!is_active && active && status == behavior_tree_msgs::msg::Status::FAILURE) - set_status(behavior_tree_msgs::msg::Status::FAILURE); - - if (get_status_age() > Node::max_wait_time) - set_status(behavior_tree_msgs::msg::Status::FAILURE); - - bool status_changed = (status != prev_status) || callback_status_updated; - bool active_changed = (is_active != active); - - is_active = active; - callback_status_updated = false; - - return status_changed || active_changed; -} - -std::string ConditionNode::get_publisher_name() { return ""; } - -void ConditionNode::init_publisher() {} - -std::string ConditionNode::get_subscriber_name() { - std::string name = label; - std::transform(name.begin(), name.end(), name.begin(), - [](unsigned char c) { return std::tolower(c); }); - std::replace(name.begin(), name.end(), ' ', '_'); - name = name + "_success"; - // ROS_INFO_STREAM("condition get subscriber name: " << name << " " << label); - return name; -} - -void ConditionNode::init_subscriber() { - // ros::NodeHandle nh; - subscriber = node->create_subscription( - get_subscriber_name(), 1, std::bind(&ConditionNode::callback, this, std::placeholders::_1)); -} - -void ConditionNode::callback(const std_msgs::msg::Bool::SharedPtr msg) { - // ROS_INFO_STREAM(label << ": " << (int)msg.data); - // TODO: bug where if status is set here the changed flag won't be set correctly in tick - uint8_t prev_status = status; - - if (msg->data) - set_status(behavior_tree_msgs::msg::Status::SUCCESS); - else - set_status(behavior_tree_msgs::msg::Status::FAILURE); - - if (status != prev_status) callback_status_updated = true; -} - -ActionNode::ActionNode(std::string label, rclcpp::Node* node) : ExecutionNode(node) { - this->label = label; - status_modification_time = node->get_clock()->now(); // rclcpp::Time::now(); - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; - current_traversal_count = -1; - is_newly_active = false; - current_id = 0; - publisher_initialized = false; - callback_status_updated = false; -} - -bool ActionNode::tick(bool active, int traversal_count) { - // if(active) - // ROS_INFO_STREAM("Action " << label << " active"); - - uint8_t prev_status = status; - - if (current_traversal_count != traversal_count) - current_traversal_count = traversal_count; - else if (is_active) - return false; // TOOD: is this correct? - - if (!is_active and active) { - set_status(behavior_tree_msgs::msg::Status::RUNNING); - is_newly_active = true; - } else - is_newly_active = false; - - if (get_status_age() > Node::max_wait_time) - set_status(behavior_tree_msgs::msg::Status::FAILURE); - - bool status_changed = (status != prev_status) || callback_status_updated; - bool active_changed = (is_active != active); - - is_active = active; - callback_status_updated = false; - - return status_changed || active_changed; -} - -std::string ActionNode::get_publisher_name() { - std::string name = label; - std::transform(name.begin(), name.end(), name.begin(), - [](unsigned char c) { return std::tolower(c); }); - std::replace(name.begin(), name.end(), ' ', '_'); - name = name + "_active"; - // ROS_INFO_STREAM("action get publisher name: " << name << " " << label); - return name; -} - -void ActionNode::init_publisher() { - publisher = node->create_publisher(get_publisher_name(), 1); - publisher_initialized = true; -} - -std::string ActionNode::get_subscriber_name() { - std::string name = label; - std::transform(name.begin(), name.end(), name.begin(), - [](unsigned char c) { return std::tolower(c); }); - std::replace(name.begin(), name.end(), ' ', '_'); - name = name + "_status"; - // ROS_INFO_STREAM("action get subscriber name: " << name << " " << label); - return name; -} - -void ActionNode::init_subscriber() { - subscriber = node->create_subscription( - get_subscriber_name(), 1, std::bind(&ActionNode::callback, this, std::placeholders::_1)); -} - -void ActionNode::callback(const behavior_tree_msgs::msg::Status::SharedPtr msg) { - uint8_t prev_status = status; - if (is_active) { - if (msg->id != current_id) { - // ROS_ERROR_STREAM(label << " Incorrect ID " << msg->id << " " << current_id << " " << - // is_active); - std::cout << label << " Incorrect ID " << msg->id << " " << current_id << " " - << is_active << std::endl; - return; - } - set_status(msg->status); - } - - if (status != prev_status) callback_status_updated = true; -} - -void ActionNode::publish_active_msg(int active_id) { - if (publisher_initialized) { - behavior_tree_msgs::msg::Active active_msg; - active_msg.active = is_active; - active_msg.id = active_id; - current_id = active_id; - publisher->publish(active_msg); - } -} - -//=============================================================================================== -// -------------------------------------- Decorator Nodes -------------------------------------- -//=============================================================================================== - -void DecoratorNode::add_child(Node* node) { - if (children.size() == 0) - children.push_back(node); - else { - // ROS_ERROR_STREAM("A decorator node can only have one child."); - std::cout << "A decorator node can only have one child." << std::endl; - exit(1); - } -} - -NotNode::NotNode() { - label = "!"; - is_active = false; - status = behavior_tree_msgs::msg::Status::FAILURE; -} - -void NotNode::add_child(Node* node) { - ConditionNode* condition_node = dynamic_cast(node); - if (condition_node != NULL) - DecoratorNode::add_child(condition_node); - else { - // ROS_ERROR_STREAM("A not decorator node can only have a condition node as a child."); - std::cout << "A not decorator node can only have a condition node as a child." << std::endl; - exit(1); - } -} - -bool NotNode::tick(bool active, int traversal_count) { - uint8_t prev_status = status; - bool child_changed = false; - - if (children.size() > 0) { - Node* child = children[0]; - child_changed |= child->tick(active, traversal_count); - - if (child->status == behavior_tree_msgs::msg::Status::SUCCESS) - status = behavior_tree_msgs::msg::Status::FAILURE; - else if (child->status == behavior_tree_msgs::msg::Status::FAILURE) - status = behavior_tree_msgs::msg::Status::SUCCESS; - } - - bool status_changed = (status != prev_status) || child_changed; - bool active_changed = (is_active != active); - - is_active = active; - - return status_changed || active_changed; -} - -//=============================================================================================== -// --------------------------------------- Behavior Tree --------------------------------------- -//=============================================================================================== - -BehaviorTree::BehaviorTree(std::string config_filename, rclcpp::Node* node) : ros2_node(node) { - this->config_filename = config_filename; - root = NULL; - traversal_count = 0; - first_tick = true; - - active_actions_pub = node->create_publisher("active_actions", 1); - graphviz_pub = node->create_publisher("behavior_tree_graphviz", 1); - compressed_pub = - node->create_publisher("behavior_tree_graphviz_compressed", 1); - - parse_config(); - for (int i = 0; i < nodes.size(); i++) { - ActionNode* action_node = dynamic_cast(nodes[i]); - if (action_node != NULL) action_node->init_ros(); - ConditionNode* condition_node = dynamic_cast(nodes[i]); - if (condition_node != NULL) condition_node->init_ros(); - } -} - -void BehaviorTree::parse_config() { - std::ifstream in(config_filename); - - // ROS_INFO_STREAM("Config file: " << config_filename); - - if (in.is_open()) { - std::vector nodes_worklist; - int prev_tabs = 0; - - std::string line; - while (getline(in, line)) { - // skip empty lines - if (line.size() == 0) continue; - - // ROS_INFO_STREAM("Line: " << line); - - // initialization - int curr_tabs = count_tabs(line); - std::string label = strip_space(line); - Node* node = NULL; - - // ROS_INFO_STREAM("curr tabs: " << curr_tabs << " label: " << label); - - // create a node of the right type - if (label.compare(0, 2, "->") == 0) - node = new SequenceNode(); - else if (label.compare(0, 1, "?") == 0) - node = new FallbackNode(); - else if (label.compare(0, 2, "||") == 0) { - std::vector arguments = get_arguments(label); - int child_success_threshold = 0; - if (arguments.size() > 0) - child_success_threshold = arguments[0]; - else { - // ROS_ERROR_STREAM("Arguments not provided to parallel node"); - std::cout << "Arguments not provided to parallel node" << std::endl; - exit(1); - } - node = new ParallelNode(child_success_threshold); - } else if (label.compare(0, 1, "(") == 0) - node = new ConditionNode(strip_brackets(label), ros2_node); - else if (label.compare(0, 1, "[") == 0) { - node = new ActionNode(strip_brackets(label), ros2_node); - active_ids[node->label] = 0; - } else if (label.compare(0, 1, "<") == 0) { - std::string decorator_label = strip_brackets(label); - if (decorator_label.compare(0, 1, "!") == 0) node = new NotNode(); - } - - if (node != NULL) { - nodes.push_back(node); - - if (root == NULL) { - root = node; - nodes_worklist.push_back(node); - continue; - } - - if (curr_tabs == prev_tabs + 1) { - Node* parent = nodes_worklist[nodes_worklist.size() - 1]; - parent->add_child(node); - } else { - for (int i = 0; i < prev_tabs - curr_tabs + 1; i++) nodes_worklist.pop_back(); - Node* parent = nodes_worklist[nodes_worklist.size() - 1]; - parent->add_child(node); - } - - nodes_worklist.push_back(node); - prev_tabs = curr_tabs; - } - } - in.close(); - } else - std::cout << "Failed to open behavior tree config file: " << config_filename << std::endl; - // ROS_ERROR_STREAM("Failed to open behavior tree config file: " << config_filename); -} - -int BehaviorTree::count_tabs(std::string str) { - int count = 0; - for (int i = 0; i < str.size(); i++) - if (str[i] == '\t') - count++; - else - break; - - return count; -} - -std::string BehaviorTree::strip_space(std::string str) { - std::string result = str; - while (result.size() > 0) - if (std::isspace(result[0])) - result.erase(0, 1); - else - break; - - while (result.size() > 0) - if (std::isspace(result[result.size() - 1])) - result.erase(result.size() - 1, 1); - else - break; - - return result; -} - -std::string BehaviorTree::strip_brackets(std::string str) { - std::string result = str; - while (result.size() > 0) - if (result[0] == '(' || result[0] == '[' || result[0] == '<') - result.erase(0, 1); - else - break; - - while (result.size() > 0) - if (result[result.size() - 1] == ')' || result[result.size() - 1] == ']' || - result[result.size() - 1] == '>') - result.erase(result.size() - 1, 1); - else - break; - - return result; -} - -std::vector BehaviorTree::get_arguments(std::string str) { - std::vector arguments; - - std::istringstream ss(str); - std::string first; - ss >> first; - - int i; - while (ss >> i) arguments.push_back(i); - - return arguments; -} - -bool BehaviorTree::tick() { - bool changed = false || first_tick; - first_tick = false; - - if (root != NULL) { - changed = root->tick(true, traversal_count); - traversal_count++; - - std_msgs::msg::String active_actions; - - std::unordered_map unique_action_nodes; - for (int i = 0; i < nodes.size(); i++) { - ActionNode* action_node = dynamic_cast(nodes[i]); - if (action_node != NULL) { - if (unique_action_nodes.count(action_node->label) == 0 || action_node->is_active) { - unique_action_nodes[action_node->label] = action_node; - if (action_node->is_newly_active) active_ids[action_node->label]++; - } - } - } - - for (auto it = unique_action_nodes.begin(); it != unique_action_nodes.end(); it++) { - ActionNode* action_node = dynamic_cast(it->second); - if (action_node != NULL) { - action_node->publish_active_msg(active_ids[it->first]); - - if (it->second->is_active) active_actions.data += action_node->label + ", "; - } else { - std::cout << "action node is NULL, something went wrong." << std::endl; - // ROS_ERROR_STREAM("action node is NULL, something went wrong."); - } - } - if (active_actions.data.length() >= 2) { - active_actions.data.pop_back(); - active_actions.data.pop_back(); - } - active_actions_pub->publish(active_actions); - } - - return changed; -} - -std::string BehaviorTree::get_graphviz() { - std::string gv = "digraph G {\n"; - - std::vector nodes_worklist; - nodes_worklist.push_back(root); - int count = 0; - std::unordered_map node_names; - - while (!nodes_worklist.empty()) { - Node* node = nodes_worklist.back(); - nodes_worklist.pop_back(); - std::string name = "node_" + std::to_string(count); - count++; - - std::string style = ""; - if (node->is_active) { - style += "penwidth=2 color=black style=filled "; - if (node->status == behavior_tree_msgs::msg::Status::SUCCESS) - style += "fillcolor=chartreuse"; // dark green - else if (node->status == behavior_tree_msgs::msg::Status::RUNNING) - style += "fillcolor=skyblue"; // dark blue - else if (node->status == behavior_tree_msgs::msg::Status::FAILURE) - style += "fillcolor=tomato"; // dark red - } else { - style += "penwidth=2 "; - if (node->status == behavior_tree_msgs::msg::Status::SUCCESS) - style += "color=chartreuse"; // light green - else if (node->status == behavior_tree_msgs::msg::Status::RUNNING) - style += "color=skyblue"; // light blue - else if (node->status == behavior_tree_msgs::msg::Status::FAILURE) - style += "color=tomato"; // light red - } - - if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" " + style + "]\n"; - } else if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" shape=square " + style + "]\n"; - } else if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" shape=square " + style + "]\n"; - } else if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" shape=square " + style + "]\n"; - } else if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" shape=parallelogram " + style + - "]\n"; - } else if (dynamic_cast(node) != NULL) { - gv += "\t" + name + " [label=\"" + node->label + "\" shape=diamond " + style + "]\n"; - } - - node_names[node] = name; - - for (int i = 0; i < node->children.size(); i++) nodes_worklist.push_back(node->children[i]); - } - - gv += "\n\tordering=out;\n\n"; - - nodes_worklist.push_back(root); - while (!nodes_worklist.empty()) { - Node* node = nodes_worklist.back(); - nodes_worklist.pop_back(); - - for (int i = 0; i < node->children.size(); i++) { - gv += "\t" + node_names[node] + " -> " + node_names[node->children[i]] + ";\n"; - nodes_worklist.push_back(node->children[i]); - } - } - - gv += "}\n"; - - return gv; -} - -std::string string_compress_encode(const std::string& data) { - std::stringstream compressed; - std::stringstream original; - original << data; - boost::iostreams::filtering_streambuf out; - out.push(boost::iostreams::zlib_compressor()); - out.push(original); - boost::iostreams::copy(out, compressed); - - /**need to encode here **/ - // std::string compressed_encoded = base64_encode(reinterpret_cast(compressed.c_str()), compressed.length()); - - return compressed.str(); // compressed_encoded; -} - -BehaviorTree* bt; - -behavior_tree_msgs::msg::GraphVizXdot graphviz_msg; -behavior_tree_msgs::msg::GraphVizXdotCompressed compressed_msg; -bool only_publish_on_change; -void timer_callback() { // const rclcpp::TimerEvent& te){ - bool changed = bt->tick(); - // ROS_INFO_STREAM("Changed: " << changed); - - if (changed) { - graphviz_msg.header.stamp = bt->ros2_node->get_clock()->now(); // rclcpp::Time::now(); - graphviz_msg.xdot.data = bt->get_graphviz(); - compressed_msg.header.stamp = graphviz_msg.header.stamp; - compressed_msg.xdot_compressed.data = string_compress_encode(graphviz_msg.xdot.data); - - if (only_publish_on_change) { - bt->graphviz_pub->publish(graphviz_msg); - bt->compressed_pub->publish(compressed_msg); - } - } - - if (!only_publish_on_change) { - bt->graphviz_pub->publish(graphviz_msg); - bt->compressed_pub->publish(compressed_msg); - } -} - -class BehaviorTreeNode : public rclcpp::Node { - private: - rclcpp::TimerBase::SharedPtr timer; - - public: - BehaviorTreeNode() : Node("behavior_tree_node") { - // timer = this->create_timer(std::chrono::milliseconds(50), - // std::bind(&MinimalPublisher::timer_callback, this)); - - this->declare_parameter("config", ""); - std::string config_filename = this->get_parameter("config").as_string(); - - this->declare_parameter("timeout", 1.0); - ::Node::max_wait_time = this->get_parameter("timeout").as_double(); - - bt = new BehaviorTree(config_filename, this); - - timer = rclcpp::create_timer(this, this->get_clock(), std::chrono::milliseconds(50), - &timer_callback); - } -}; - -int main(int argc, char** argv) { - /* - ros::init(argc, argv, "behavior_tree"); - - ros::NodeHandle nh; - ros::NodeHandle pnh("~"); - - std::string config_filename = pnh.param("config", std::string("")); - only_publish_on_change = pnh.param("only_publish_on_change", false); - Node::max_wait_time = pnh.param("timeout", 1.0); - - rclcpp::Timer timer = nh.createTimer(ros::Duration(0.05), timer_callback); - - bt = new BehaviorTree(config_filename); - - ros::spin(); - */ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - - return 0; -} diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/CMakeLists.txt b/robot/ros_ws/src/behavior/drone_safety_monitor/CMakeLists.txt similarity index 60% rename from robot/ros_ws/src/interface/drone_safety_monitor/CMakeLists.txt rename to robot/ros_ws/src/behavior/drone_safety_monitor/CMakeLists.txt index 503f0e46d..d9350e958 100644 --- a/robot/ros_ws/src/interface/drone_safety_monitor/CMakeLists.txt +++ b/robot/ros_ws/src/behavior/drone_safety_monitor/CMakeLists.txt @@ -5,51 +5,33 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -# find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(std_msgs REQUIRED) +find_package(nav_msgs REQUIRED) find_package(airstack_msgs REQUIRED) find_package(airstack_common REQUIRED) -find_package(trajectory_library REQUIRED) -find_package(mavros_msgs REQUIRED) -find_package(std_srvs REQUIRED) add_executable(drone_safety_monitor src/drone_safety_monitor.cpp) target_include_directories(drone_safety_monitor PUBLIC $ $) -target_compile_features(drone_safety_monitor PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 +target_compile_features(drone_safety_monitor PUBLIC c_std_99 cxx_std_17) ament_target_dependencies( drone_safety_monitor + rclcpp std_msgs + nav_msgs airstack_msgs airstack_common - trajectory_library - mavros_msgs - std_srvs ) install(TARGETS drone_safety_monitor DESTINATION lib/${PROJECT_NAME}) -install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/ - ) - -install(DIRECTORY - config - DESTINATION share/${PROJECT_NAME}) - if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # comment the line when a copyright and license is added to all source files set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # comment the line when this package is in a git repo and when - # a copyright and license is added to all source files set(ament_cmake_cpplint_FOUND TRUE) ament_lint_auto_find_test_dependencies() endif() diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp b/robot/ros_ws/src/behavior/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp similarity index 83% rename from robot/ros_ws/src/interface/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp rename to robot/ros_ws/src/behavior/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp index 48e11fc1c..4b25a4abd 100644 --- a/robot/ros_ws/src/interface/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp +++ b/robot/ros_ws/src/behavior/drone_safety_monitor/include/drone_safety_monitor/drone_safety_monitor.hpp @@ -20,17 +20,17 @@ #pragma once -#include -#include -#include -#include #include -// ===================================================================================== -// ---------------------------------- TimeChecker -------------------------------------- -// ===================================================================================== +#include +#include +#include +#include +#include +#include -class TimeChecker{ +class TimeChecker +{ private: rclcpp::Time time; bool time_initialized; @@ -39,4 +39,4 @@ class TimeChecker{ TimeChecker(); void update(rclcpp::Time time); double elapsed_since_last_update(rclcpp::Time time); -}; +}; diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/package.xml b/robot/ros_ws/src/behavior/drone_safety_monitor/package.xml similarity index 75% rename from robot/ros_ws/src/interface/drone_safety_monitor/package.xml rename to robot/ros_ws/src/behavior/drone_safety_monitor/package.xml index 54c32c903..2ac348759 100644 --- a/robot/ros_ws/src/interface/drone_safety_monitor/package.xml +++ b/robot/ros_ws/src/behavior/drone_safety_monitor/package.xml @@ -3,20 +3,18 @@ drone_safety_monitor 0.0.0 - TODO: Package description + Safety monitor: state estimate watchdog and pause/resume/rewind command handling uav - TODO: License declaration + MIT ament_cmake rclcpp std_msgs + nav_msgs airstack_msgs airstack_common - trajectory_library - mavros_msgs - std_srvs - + ament_lint_auto ament_lint_common diff --git a/robot/ros_ws/src/behavior/drone_safety_monitor/src/drone_safety_monitor.cpp b/robot/ros_ws/src/behavior/drone_safety_monitor/src/drone_safety_monitor.cpp new file mode 100644 index 000000000..595724523 --- /dev/null +++ b/robot/ros_ws/src/behavior/drone_safety_monitor/src/drone_safety_monitor.cpp @@ -0,0 +1,147 @@ +// Copyright (c) 2024 Carnegie Mellon University +// +// 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. + +#include + +TimeChecker::TimeChecker() +: time_initialized(false) {} + +void TimeChecker::update(rclcpp::Time time) +{ + this->time = time; + time_initialized = true; +} + +double TimeChecker::elapsed_since_last_update(rclcpp::Time time) +{ + if (!time_initialized) { + return std::numeric_limits::infinity(); + } + return (time - this->time).seconds(); +} + + +class DroneSafetyMonitorNode : public rclcpp::Node +{ +public: + DroneSafetyMonitorNode() + : Node("drone_safety_monitor") + { + state_estimate_timeout_ = airstack::get_param(this, "state_estimate_timeout", 1.0); + + // subscribers + state_estimate_sub_ = this->create_subscription( + "state_estimate", 10, + std::bind(&DroneSafetyMonitorNode::state_estimate_callback, this, std::placeholders::_1)); + + command_sub_ = this->create_subscription( + "command", 10, + std::bind(&DroneSafetyMonitorNode::command_callback, this, std::placeholders::_1)); + + // publishers + state_estimate_timed_out_pub_ = + this->create_publisher("state_estimate_timed_out", 10); + + // service client + traj_mode_client_ = + this->create_client("set_trajectory_mode"); + + // timer at 1 Hz + timer_ = rclcpp::create_timer( + this, this->get_clock(), std::chrono::milliseconds(1000), + std::bind(&DroneSafetyMonitorNode::timer_callback, this)); + + RCLCPP_INFO(this->get_logger(), "DroneSafetyMonitorNode started. " + "Publish to 'command' topic with: pause | resume | rewind"); + } + +private: + float state_estimate_timeout_; + bool was_timed_out_{false}; + + TimeChecker state_estimate_time_checker_; + + rclcpp::Subscription::SharedPtr state_estimate_sub_; + rclcpp::Subscription::SharedPtr command_sub_; + rclcpp::Publisher::SharedPtr state_estimate_timed_out_pub_; + rclcpp::Client::SharedPtr traj_mode_client_; + rclcpp::TimerBase::SharedPtr timer_; + + void set_trajectory_mode(int32_t mode) + { + if (!traj_mode_client_->wait_for_service(std::chrono::seconds(1))) { + RCLCPP_WARN(this->get_logger(), "set_trajectory_mode service not available"); + return; + } + auto req = std::make_shared(); + req->mode = mode; + traj_mode_client_->async_send_request(req); + } + + void state_estimate_callback(const nav_msgs::msg::Odometry::SharedPtr) + { + state_estimate_time_checker_.update(this->get_clock()->now()); + } + + void command_callback(const std_msgs::msg::String::SharedPtr msg) + { + const std::string & cmd = msg->data; + if (cmd == "pause") { + RCLCPP_INFO(this->get_logger(), "Safety command: PAUSE"); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::PAUSE); + } else if (cmd == "resume") { + RCLCPP_INFO(this->get_logger(), "Safety command: RESUME"); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + } else if (cmd == "rewind") { + RCLCPP_INFO(this->get_logger(), "Safety command: REWIND"); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::REWIND); + } else { + RCLCPP_WARN(this->get_logger(), + "Unknown safety command: '%s'. Valid commands: pause | resume | rewind", cmd.c_str()); + } + } + + void timer_callback() + { + bool timed_out = + state_estimate_time_checker_.elapsed_since_last_update(this->get_clock()->now()) > + state_estimate_timeout_; + + std_msgs::msg::Bool msg; + msg.data = timed_out; + state_estimate_timed_out_pub_->publish(msg); + + // auto-pause if state estimate just timed out + if (timed_out && !was_timed_out_) { + RCLCPP_WARN(this->get_logger(), + "State estimate timed out! Auto-pausing trajectory controller."); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::PAUSE); + } + was_timed_out_ = timed_out; + } +}; + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/CHANGELOG.rst b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/CHANGELOG.rst deleted file mode 100644 index 0a789b786..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/CHANGELOG.rst +++ /dev/null @@ -1,149 +0,0 @@ -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Changelog for package rqt_py_console -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -1.0.2 (2021-08-31) ------------------- -* Fix modern setuptools warning about dashes instead of underscores (`#11 `_) -* Contributors: Chris Lalancette - -1.0.1 (2021-04-27) ------------------- -* Changed the build type to ament_python and fixed package to run with ros2 run (`#8 `_) -* Contributors: Alejandro Hernández Cordero - -1.0.0 (2018-12-11) ------------------- -* spyderlib -> spyder (`#5 `_) -* ros2 port (`#3 `_) -* autopep8 (`#2 `_) -* Contributors: Mike Lautman - -0.4.8 (2017-04-28) ------------------- - -0.4.7 (2017-03-02) ------------------- - -0.4.6 (2017-02-27) ------------------- - -0.4.5 (2017-02-03) ------------------- - -0.4.4 (2017-01-24) ------------------- -* use Python 3 compatible syntax (`#421 `_) - -0.4.3 (2016-11-02) ------------------- - -0.4.2 (2016-09-19) ------------------- - -0.4.1 (2016-05-16) ------------------- - -0.4.0 (2016-04-27) ------------------- -* Support Qt 5 (in Kinetic and higher) as well as Qt 4 (in Jade and earlier) (`#359 `_) - -0.3.13 (2016-03-08) -------------------- - -0.3.12 (2015-07-24) -------------------- - -0.3.11 (2015-04-30) -------------------- - -0.3.10 (2014-10-01) -------------------- -* update plugin scripts to use full name to avoid future naming collisions - -0.3.9 (2014-08-18) ------------------- - -0.3.8 (2014-07-15) ------------------- - -0.3.7 (2014-07-11) ------------------- -* export architecture_independent flag in package.xml (`#254 `_) - -0.3.6 (2014-06-02) ------------------- - -0.3.5 (2014-05-07) ------------------- - -0.3.4 (2014-01-28) ------------------- - -0.3.3 (2014-01-08) ------------------- -* add groups for rqt plugins, renamed some plugins (`#167 `_) - -0.3.2 (2013-10-14) ------------------- - -0.3.1 (2013-10-09) ------------------- - -0.3.0 (2013-08-28) ------------------- - -0.2.17 (2013-07-04) -------------------- - -0.2.16 (2013-04-09 13:33) -------------------------- - -0.2.15 (2013-04-09 00:02) -------------------------- - -0.2.14 (2013-03-14) -------------------- - -0.2.13 (2013-03-11 22:14) -------------------------- - -0.2.12 (2013-03-11 13:56) -------------------------- - -0.2.11 (2013-03-08) -------------------- - -0.2.10 (2013-01-22) -------------------- - -0.2.9 (2013-01-17) ------------------- - -0.2.8 (2013-01-11) ------------------- - -0.2.7 (2012-12-24) ------------------- - -0.2.6 (2012-12-23) ------------------- - -0.2.5 (2012-12-21 19:11) ------------------------- - -0.2.4 (2012-12-21 01:13) ------------------------- - -0.2.3 (2012-12-21 00:24) ------------------------- - -0.2.2 (2012-12-20 18:29) ------------------------- - -0.2.1 (2012-12-20 17:47) ------------------------- - -0.2.0 (2012-12-20 17:39) ------------------------- -* first release of this package into groovy diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/README.md b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/README.md deleted file mode 100644 index 82f4ee4c9..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/README.md +++ /dev/null @@ -1,19 +0,0 @@ -# RQT Python FixedTrajectoryGenerator - -If you `colcon build` this package in a workspace and then run "rqt --force-discover" after sourcing the workspace, the plugin should show up as "Fixed Trajectory Generator" in "Miscellaneous Tools" in the "Plugins" menu. - -You can use the `generate_rqt_py_package.sh` script to generate a new package by doing the following from the rqt_fixed_trajectory_generator directory - -``` -./generate_rqt_py_package.sh [package name] [class name] [plugin title] -``` - -[package name] will be the name of the package and a directory with this name will be created above `rqt_fixed_trajectory_generator/`. [class name] is the name of the class in `src/[package name]/template.py`. [plugin title] is what the plugin will be called in the "Miscellaneous Tools" menu. - -For example, - -``` -cd rqt_fixed_trajectory_generator/ -./generate_rqt_py_package.sh new_rqt_package ClassName "Plugin Title" -``` - diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/config/fixed_trajectories.yaml b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/config/fixed_trajectories.yaml deleted file mode 100644 index 0fdeb0af2..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/config/fixed_trajectories.yaml +++ /dev/null @@ -1,47 +0,0 @@ -trajectories: - - Figure8: - attributes: - - frame_id - - velocity - - max_acceleration - - length - - width - - height - - Racetrack: - attributes: - - frame_id - - velocity - - turn_velocity - - max_acceleration - - length - - width - - height - - Circle: - attributes: - - frame_id - - velocity - - radius - - Line: - attributes: - - frame_id - - velocity - - max_acceleration - - length - - width - - height - - Point: - attributes: - - frame_id - - velocity - - max_acceleration - - x - - y - - height - - Lawnmower: - attributes: - - frame_id - - length - - width - - height - - velocity - - vertical diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/package.xml b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/package.xml deleted file mode 100644 index 8f12f2f8d..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/package.xml +++ /dev/null @@ -1,28 +0,0 @@ - - rqt_fixed_trajectory_generator - 1.0.2 - rqt_fixed_trajectory_generator is a Python GUI template. - John Keller - - BSD - - - - - - John Keller - - ament_index_python - python_qt_binding - qt_gui - qt_gui_py_common - rclpy - rqt_gui - rqt_gui_py - - - - - ament_python - - diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/plugin.xml b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/plugin.xml deleted file mode 100644 index ec1f2a2b4..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/plugin.xml +++ /dev/null @@ -1,17 +0,0 @@ - - - - A Python GUI plugin providing an interactive Python console. - - - - - folder - Plugins related to miscellaneous tools. - - - applications-python - A Python RQT GUI template. - - - diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/py_console_widget.ui b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/py_console_widget.ui deleted file mode 100644 index 12810f1c5..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/py_console_widget.ui +++ /dev/null @@ -1,53 +0,0 @@ - - - PyConsole - - - - 0 - 0 - 276 - 212 - - - - PyConsole - - - - 0 - - - 0 - - - 0 - - - 3 - - - 0 - - - - - 0 - - - - - - - - - - - PyConsoleTextEdit - QTextEdit -
rqt_py_console.py_console_text_edit
-
-
- - -
diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/rqt_fixed_trajectory_generator b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/resource/rqt_fixed_trajectory_generator deleted file mode 100644 index e69de29bb..000000000 diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.cfg b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.cfg deleted file mode 100644 index 2394a82ac..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.cfg +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/rqt_fixed_trajectory_generator -[install] -install_scripts=$base/lib/rqt_fixed_trajectory_generator diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.py deleted file mode 100644 index 12c8b1c23..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/setup.py +++ /dev/null @@ -1,41 +0,0 @@ -from setuptools import setup -from glob import glob - -package_name = 'rqt_fixed_trajectory_generator' - -setup( - name=package_name, - version='1.0.2', - packages=[package_name], - package_dir={'': 'src'}, - data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), - ('share/' + package_name + '/resource', - ['resource/py_console_widget.ui']), - ('share/' + package_name, ['package.xml']), - ('share/' + package_name, ['plugin.xml']), - ('share/' + package_name + '/config/', glob('config/*')), - ], - install_requires=['setuptools'], - zip_safe=True, - author='', - maintainer='', - maintainer_email='', - keywords=['ROS'], - classifiers=[ - '', - '', - '', - '', - ], - description=( - 'rqt_fixed_trajectory_generator' - ), - license='BSD', - entry_points={ - 'console_scripts': [ - 'rqt_fixed_trajectory_generator = ' + package_name + '.main:main', - ], - }, -) diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/__init__.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/__init__.py deleted file mode 100644 index e69de29bb..000000000 diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/main.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/main.py deleted file mode 100755 index 9a5c9376e..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/main.py +++ /dev/null @@ -1,12 +0,0 @@ -import sys - -from rqt_gui.main import Main - - -def main(): - main = Main() - sys.exit(main.main(sys.argv, standalone='rqt_py_console.py_console.PyConsole')) - - -if __name__ == '__main__': - main() diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_text_edit.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_text_edit.py deleted file mode 100644 index dc9ce1a0a..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_text_edit.py +++ /dev/null @@ -1,69 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2012, Dorian Scholz -# 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. - -import sys -from code import InteractiveInterpreter - -from python_qt_binding import QT_BINDING, QT_BINDING_VERSION -from python_qt_binding.QtCore import Qt, Signal - -from qt_gui_py_common.console_text_edit import ConsoleTextEdit - - -class PyConsoleTextEdit(ConsoleTextEdit): - _color_stdin = Qt.darkGreen - _multi_line_char = ':' - _multi_line_indent = ' ' - _prompt = ('>>> ', '... ') # prompt for single and multi line - exit = Signal() - - def __init__(self, parent=None): - super(PyConsoleTextEdit, self).__init__(parent) - - self._interpreter_locals = {} - self._interpreter = InteractiveInterpreter(self._interpreter_locals) - - self._comment_writer.write('Python %s on %s\n' % - (sys.version.replace('\n', ''), sys.platform)) - self._comment_writer.write( - 'Qt bindings: %s version %s\n' % (QT_BINDING, QT_BINDING_VERSION)) - - self._add_prompt() - - def update_interpreter_locals(self, newLocals): - self._interpreter_locals.update(newLocals) - - def _exec_code(self, code): - try: - self._interpreter.runsource(code) - except SystemExit: # catch sys.exit() calls, so they don't close the whole gui - self.exit.emit() diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_widget.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_widget.py deleted file mode 100644 index e69bde34c..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/py_console_widget.py +++ /dev/null @@ -1,59 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2012, Dorian Scholz -# 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. - -import os -from ament_index_python.resources import get_resource - -from python_qt_binding import loadUi -from python_qt_binding.QtWidgets import QWidget -from rqt_py_console.py_console_text_edit import PyConsoleTextEdit - - -class PyConsoleWidget(QWidget): - - def __init__(self, context=None): - super(PyConsoleWidget, self).__init__() - - _, package_path = get_resource('packages', 'rqt_py_console') - ui_file = os.path.join( - package_path, 'share', 'rqt_py_console', 'resource', 'py_console_widget.ui') - - loadUi(ui_file, self, {'PyConsoleTextEdit': PyConsoleTextEdit}) - self.setObjectName('PyConsoleWidget') - - my_locals = { - 'context': context - } - self.py_console.update_interpreter_locals(my_locals) - self.py_console.print_message( - 'The variable "context" is set to the PluginContext of this plugin.') - self.py_console.exit.connect(context.close_plugin) diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/spyder_console_widget.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/spyder_console_widget.py deleted file mode 100644 index 374ef7a5d..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/spyder_console_widget.py +++ /dev/null @@ -1,60 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2012, Dorian Scholz -# 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. - -from python_qt_binding.QtGui import QFont - -from spyder.widgets.internalshell import InternalShell -from spyder.utils.module_completion import moduleCompletion - -class SpyderConsoleWidget(InternalShell): - - def __init__(self, context=None): - my_locals = { - 'context': context - } - super(SpyderConsoleWidget, self).__init__(namespace=my_locals) - self.setObjectName('SpyderConsoleWidget') - self.set_pythonshell_font(QFont('Mono')) - self.interpreter.restore_stds() - - def get_module_completion(self, objtxt): - """Return module completion list associated to object name""" - return moduleCompletion(objtxt) - - def run_command(self, *args): - self.interpreter.redirect_stds() - super(SpyderConsoleWidget, self).run_command(*args) - self.flush() - self.interpreter.restore_stds() - - def shutdown(self): - self.exit_interpreter() diff --git a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/template.py b/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/template.py deleted file mode 100644 index 76c60c770..000000000 --- a/robot/ros_ws/src/behavior/rqt_fixed_trajectory_generator/src/rqt_fixed_trajectory_generator/template.py +++ /dev/null @@ -1,269 +0,0 @@ -# Software License Agreement (BSD License) -# -# Copyright (c) 2012, Dorian Scholz -# 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. - -from python_qt_binding.QtWidgets import QVBoxLayout, QWidget -from rqt_gui_py.plugin import Plugin -from qt_gui_py_common.simple_settings_dialog import SimpleSettingsDialog -from rqt_py_console.py_console_widget import PyConsoleWidget - -import python_qt_binding.QtWidgets as qt -import python_qt_binding.QtWidgets as QtWidgets -import python_qt_binding.QtGui as QtGui -import python_qt_binding.QtCore as QtCore - -import os -import time -import numpy as np -import yaml -import collections -import pickle -from ament_index_python.packages import get_package_share_directory - -from std_msgs.msg import Bool -from airstack_msgs.msg import FixedTrajectory -from diagnostic_msgs.msg import KeyValue - -try: - from rqt_py_console.spyder_console_widget import SpyderConsoleWidget - _has_spyderlib = True -except ImportError: - _has_spyderlib = False - - -class FixedTrajectoryGenerator(Plugin): - """ - Plugin providing an interactive Python console - """ - - def __init__(self, context): - super(FixedTrajectoryGenerator, self).__init__(context) - self.setObjectName('FixedTrajectoryGenerator') - - self.context = context - # to access ros2 node use self.context.node - - self.config_filename = '' - - self.button_dct = {} - self.attribute_settings = collections.OrderedDict() - - self.timer = self.context.node.create_timer(1./10., self.timer_callback) - - self.fixed_trajectory_pub = self.context.node.create_publisher(FixedTrajectory, 'fixed_trajectory_command', 1) - self.global_plan_fixed_trajectory_pub = self.context.node.create_publisher(FixedTrajectory, 'global_plan_fixed_trajectory', 1) - - # main layout - self.widget = QWidget() - self.vbox = qt.QVBoxLayout() - self.widget.setLayout(self.vbox) - context.add_widget(self.widget) - - # config widget - self.config_widget = qt.QWidget() - self.config_widget.setStyleSheet('QWidget{margin-left:-1px;}') - self.config_layout = qt.QHBoxLayout() - self.config_widget.setLayout(self.config_layout) - self.config_widget.setFixedHeight(50) - - self.config_button = qt.QPushButton('Open Config...') - self.config_button.clicked.connect(self.select_config_file) - self.config_layout.addWidget(self.config_button) - - self.config_label = qt.QLabel('config filename: ') - self.config_layout.addWidget(self.config_label) - self.vbox.addWidget(self.config_widget) - - # trajectory widget - self.trajectory_widget = qt.QWidget() - self.trajectory_layout = qt.QVBoxLayout() - self.trajectory_widget.setLayout(self.trajectory_layout) - self.vbox.addWidget(self.trajectory_widget) - - self.tab_widget = qt.QTabWidget() - self.trajectory_layout.addWidget(self.tab_widget) - - # button widget - self.button_widget = qt.QWidget() - self.button_layout = qt.QHBoxLayout() - self.button_widget.setLayout(self.button_layout) - self.vbox.addWidget(self.button_widget) - - self.publish_button = qt.QPushButton('Publish') - self.publish_button.clicked.connect(self.publish_trajectory) - self.button_layout.addWidget(self.publish_button) - - self.trajectory_type_label = qt.QLabel('Type: ') - self.button_layout.addWidget(self.trajectory_type_label) - - self.trajectory_type_combo_box = qt.QComboBox() - self.trajectory_type_combo_box.addItem('Fixed Trajectory') - self.trajectory_type_combo_box.addItem('Global Plan') - self.button_layout.addWidget(self.trajectory_type_combo_box) - - def publish_trajectory(self): - trajectory_type = self.trajectory_type_combo_box.currentText() - trajectory_name = self.tab_widget.tabText(self.tab_widget.currentIndex()) - msg = FixedTrajectory() - msg.type = trajectory_name - for attribute, value in iter(self.attribute_settings[trajectory_name].items()): - key_value = KeyValue() - key_value.key = attribute - key_value.value = value - msg.attributes.append(key_value) - if trajectory_type == 'Fixed Trajectory': - self.fixed_trajectory_pub.publish(msg) - elif trajectory_type == 'Global Plan': - self.global_plan_fixed_trajectory_pub.publish(msg) - - def select_config_file(self): - starting_path = get_package_share_directory('rqt_fixed_trajectory_generator') + '/config/' - print(starting_path) - filename = qt.QFileDialog.getOpenFileName(self.widget, 'Open Config File', starting_path, "Config Files (*.yaml)")[0] - self.set_config(filename) - - def set_config(self, filename): - if filename != '': - self.config_filename = filename - if self.config_filename != None: - self.config_label.setText('config filename: ' + os.path.basename(self.config_filename)) - self.init_buttons(filename) - - def init_buttons(self, filename): - y = yaml.load(open(filename, 'r').read(), Loader=yaml.Loader) - print(y) - - def get_attribute_changed_function(trajectory_name, attribute_name): - def attribute_changed(text): - if trajectory_name not in self.attribute_settings: - self.attribute_settings[trajectory_name] = {} - self.attribute_settings[trajectory_name][attribute_name] = text - return attribute_changed - - def get_publish_function(trajectory_name): - def publish_function(): - msg = FixedTrajectory() - msg.type = trajectory_name - for attribute, value in iter(self.attribute_settings[trajectory_name].items()): - key_value = KeyValue() - key_value.key = attribute - key_value.value = value - msg.attributes.append(key_value) - self.fixed_trajectory_pub.publish(msg) - return publish_function - - - for trajectory in y['trajectories']: - trajectory_name = list(trajectory.keys())[0] - attributes = trajectory[trajectory_name]['attributes'] - - trajectory_tab = qt.QWidget() - trajectory_layout = qt.QVBoxLayout() - trajectory_tab.setLayout(trajectory_layout) - - for attribute in attributes: - attribute_widget = qt.QWidget() - attribute_layout = qt.QHBoxLayout() - attribute_widget.setLayout(attribute_layout) - - attribute_label = qt.QLabel() - attribute_label.setText(attribute) - attribute_layout.addWidget(attribute_label) - - attribute_default = '0' - if attribute == 'frame_id': - attribute_default = 'world' - if trajectory_name in self.attribute_settings.keys(): - if attribute in self.attribute_settings[trajectory_name].keys(): - attribute_default = self.attribute_settings[trajectory_name][attribute] - - attribute_edit = qt.QLineEdit() - attribute_edit.textChanged.connect(get_attribute_changed_function(trajectory_name, - attribute)) - attribute_edit.setText(attribute_default) - - attribute_layout.addWidget(attribute_edit) - - trajectory_layout.addWidget(attribute_widget) - - #publish_button = qt.QPushButton('Publish') - #publish_button.clicked.connect(get_publish_function(trajectory_name)) - #trajectory_layout.addWidget(publish_button) - - self.tab_widget.addTab(trajectory_tab, trajectory_name) - - - - def timer_callback(self): - bool_msg = Bool() - for key in self.button_dct.keys(): - bool_msg.data = self.button_dct[key]['data'] - self.button_dct[key]['publisher'].publish(bool_msg) - - def save_settings(self, plugin_settings, instance_settings): - instance_settings.set_value('config_filename', self.config_filename) - instance_settings.set_value('attribute_settings', pickle.dumps(self.attribute_settings)) - - def restore_settings(self, plugin_settings, instance_settings): - attribute_settings = instance_settings.value('attribute_settings') - if attribute_settings != None: - self.attribute_settings = pickle.loads(attribute_settings) - self.set_config(instance_settings.value('config_filename')) - - ''' - def save_settings(self, plugin_settings, instance_settings): - pass - #instance_settings.set_value('some_variable', self.some_variable) - - def restore_settings(self, plugin_settings, instance_settings): - pass - #self.some_variable = instance_settings.value('some_variable', default_value) - ''' - def trigger_configuration(self): - options = [ - {'title': 'Option 1', - 'description': 'Description of option 1.', - 'enabled': True}, - {'title': 'Option 2', - 'description': 'Description of option 2.'}, - ] - dialog = SimpleSettingsDialog(title='Options') - dialog.add_exclusive_option_group(title='List of options:', options=options, selected_index=0) - selected_index = dialog.get_settings()[0] - if selected_index != None: - selected_index = selected_index['selected_index'] - print('selected_index ', selected_index) - - def shutdown_console_widget(self): - pass - - def shutdown_plugin(self): - self.shutdown_console_widget() diff --git a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_behavior_launch.xml b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_behavior_launch.xml index 549a166ca..cef093702 100644 --- a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_behavior_launch.xml +++ b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_behavior_launch.xml @@ -2,31 +2,14 @@ - - - - + + + + + - - - - - - - - - - - - - - - - - - - - diff --git a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml index 0e0c9dd76..d69088e00 100644 --- a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml +++ b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml @@ -8,29 +8,37 @@ - - + + + + + + + + + + + - - - - - + + + - - + diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/README.md b/robot/ros_ws/src/interface/drone_safety_monitor/README.md deleted file mode 100644 index efb46f285..000000000 --- a/robot/ros_ws/src/interface/drone_safety_monitor/README.md +++ /dev/null @@ -1,114 +0,0 @@ -# drone_safety_monitor - -A ROS 2 package that monitors critical drone safety conditions and publishes fault flags to the rest of the autonomy stack. Currently the package watches the state estimate stream and raises a timeout flag whenever odometry stops arriving, allowing downstream nodes (e.g. the behavior executive) to react safely. - -## Overview - -| Item | Value | -|---|---| -| Package name | `drone_safety_monitor` | -| Node name | `odom_timeout_checker` | -| Language | C++ 17 | -| ROS distro | ROS 2 (Humble / Iron) | -| License | MIT | - -## Nodes - -### `drone_safety_monitor` (executable → node name `odom_timeout_checker`) - -Monitors the incoming state estimate (odometry) and publishes a Boolean timeout flag once per second. - -**How it works** - -1. Every time an odometry message is received on `state_estimate`, the internal `TimeChecker` records the current ROS clock time. -2. A 1 Hz timer fires every second and computes how long ago the last odometry message arrived. -3. If that elapsed time exceeds `state_estimate_timeout`, the node publishes `true` on `state_estimate_timed_out`; otherwise it publishes `false`. -4. If no odometry has ever been received (e.g. immediately after startup), the elapsed time is treated as infinite, so the timeout flag is raised immediately. - -#### Subscribed Topics - -| Topic | Type | Description | -|---|---|---| -| `state_estimate` | `nav_msgs/msg/Odometry` | Incoming odometry / state estimate from the localization system | - -#### Published Topics - -| Topic | Type | Description | -|---|---|---| -| `state_estimate_timed_out` | `std_msgs/msg/Bool` | `true` when the state estimate has not been received within `state_estimate_timeout` seconds; `false` otherwise. Published at 1 Hz. | - -#### Parameters - -| Parameter | Type | Default | Description | -|---|---|---|---| -| `state_estimate_timeout` | `double` | `1.0` | Maximum acceptable gap (in seconds) between consecutive state estimate messages before the timeout flag is raised | - -## Dependencies - -| Package | Purpose | -|---|---| -| `rclcpp` | ROS 2 C++ client library | -| `std_msgs` | `Bool` message type for the timeout flag | -| `nav_msgs` | `Odometry` message type for the state estimate | -| `airstack_common` | AirStack helper utilities (`airstack::get_param`) | -| `airstack_msgs` | AirStack custom message types | -| `trajectory_library` | Trajectory utilities (linked at build time) | -| `mavros_msgs` | MAVLink/PX4 bridge message types | -| `std_srvs` | Standard service types | - -## Building - -```bash -# From the workspace root -colcon build --packages-select drone_safety_monitor -source install/setup.bash -``` - -## Running - -```bash -ros2 run drone_safety_monitor drone_safety_monitor -``` - -Override the timeout at the command line: - -```bash -ros2 run drone_safety_monitor drone_safety_monitor \ - --ros-args -p state_estimate_timeout:=0.5 -``` - -## Configuration - -The `config/takeoff_landing_planner.yaml` file is included in the package install. Parameters can be loaded at launch time via `--params-file` or overridden inline with `--ros-args -p :=`. - -## Internal Classes - -### `TimeChecker` - -A lightweight helper that tracks the timestamp of the most recent event and computes the elapsed time since then. - -| Method | Description | -|---|---| -| `TimeChecker()` | Constructs the checker in an uninitialized state | -| `update(rclcpp::Time)` | Records the provided timestamp as the most recent update time | -| `elapsed_since_last_update(rclcpp::Time)` | Returns elapsed seconds since the last `update()` call, or `+∞` if `update()` has never been called | - -## Topic Graph - -``` -[localization / EKF] - │ - │ nav_msgs/Odometry - ▼ - state_estimate - │ - ▼ - drone_safety_monitor - │ - │ std_msgs/Bool - ▼ - state_estimate_timed_out - │ - ▼ - [behavior executive / safety arbiter] -``` diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/config/takeoff_landing_planner.yaml b/robot/ros_ws/src/interface/drone_safety_monitor/config/takeoff_landing_planner.yaml deleted file mode 100644 index 23d11f151..000000000 --- a/robot/ros_ws/src/interface/drone_safety_monitor/config/takeoff_landing_planner.yaml +++ /dev/null @@ -1,14 +0,0 @@ -/**: - ros__parameters: - takeoff_height: 5.0 - high_takeoff_height: 5.0 - takeoff_landing_velocity: 0.3 - takeoff_acceptance_distance: 0.3 - takeoff_acceptance_time: 10.0 - landing_stationary_distance: 0.02 - landing_acceptance_time: 5.0 - landing_tracking_point_ahead_time: 5.0 - - takeoff_path_roll: 0. # in degrees - takeoff_path_pitch: 0. # in degrees - takeoff_path_relative_to_orientation: false diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/launch/takeoff_landing_planner.launch.xml b/robot/ros_ws/src/interface/drone_safety_monitor/launch/takeoff_landing_planner.launch.xml deleted file mode 100644 index 7b4a46a66..000000000 --- a/robot/ros_ws/src/interface/drone_safety_monitor/launch/takeoff_landing_planner.launch.xml +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/robot/ros_ws/src/interface/drone_safety_monitor/src/drone_safety_monitor.cpp b/robot/ros_ws/src/interface/drone_safety_monitor/src/drone_safety_monitor.cpp deleted file mode 100644 index 86c21c94f..000000000 --- a/robot/ros_ws/src/interface/drone_safety_monitor/src/drone_safety_monitor.cpp +++ /dev/null @@ -1,84 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include - -TimeChecker::TimeChecker() - : time_initialized(false){ -} - -void TimeChecker::update(rclcpp::Time time){ - this->time = time; - time_initialized = true; -} - -double TimeChecker::elapsed_since_last_update(rclcpp::Time time){ - if(!time_initialized) - return std::numeric_limits::infinity(); - return (time - this->time).seconds(); -} - - -class DroneSafetyMonitorNode : public rclcpp::Node -{ -public: - rclcpp::Subscription::SharedPtr state_estimate_sub; - rclcpp::Publisher::SharedPtr state_estimate_timeout_pub; - rclcpp::TimerBase::SharedPtr timer; - float state_estimate_timeout; - - TimeChecker state_estimate_time_checker; - - DroneSafetyMonitorNode() : Node("odom_timeout_checker"){ - state_estimate_timeout = airstack::get_param(this, "state_estimate_timeout", 1.); - - // subscribers - state_estimate_sub = this->create_subscription("state_estimate", 10, - std::bind(&DroneSafetyMonitorNode::state_estimate_callback, - this, std::placeholders::_1)); - - // publishers - state_estimate_timeout_pub = this->create_publisher("state_estimate_timed_out", 10); - - // timers - timer = rclcpp::create_timer(this, this->get_clock(), std::chrono::milliseconds(1000), - std::bind(&DroneSafetyMonitorNode::timer_callback, this)); - - } - - void state_estimate_callback(const nav_msgs::msg::Odometry::SharedPtr msg){ - state_estimate_time_checker.update(this->get_clock()->now()); - } - - void timer_callback(){ - std_msgs::msg::Bool state_estimate_timeout_msg; - state_estimate_timeout_msg.data = - state_estimate_time_checker.elapsed_since_last_update(this->get_clock()->now()) > state_estimate_timeout; - state_estimate_timeout_pub->publish(state_estimate_timeout_msg); - } -}; - -int main(int argc, char **argv) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/robot/ros_ws/src/interface/interface_bringup/launch/interface.launch.py b/robot/ros_ws/src/interface/interface_bringup/launch/interface.launch.py index 9e0a1c494..1b1636424 100644 --- a/robot/ros_ws/src/interface/interface_bringup/launch/interface.launch.py +++ b/robot/ros_ws/src/interface/interface_bringup/launch/interface.launch.py @@ -122,21 +122,7 @@ def launch_setup(context, *args, **kwargs): ) actions.append(odometry_conversion_node) - # --- Drone safety monitor ----------------------------------------------- - drone_safety_monitor_node = Node( - package='drone_safety_monitor', - executable='drone_safety_monitor', - namespace='drone_safety_monitor', - output='screen', - parameters=[{ - 'state_estimate_timeout': 1.0, - }], - remappings=[ - ('state_estimate', - f'/{robot_name}/odometry_conversion/odometry'), - ], - ) - actions.append(drone_safety_monitor_node) + # NOTE: drone_safety_monitor is now launched from behavior_bringup return actions diff --git a/robot/ros_ws/src/interface/px4_interface/launch/px4_interface.launch.xml b/robot/ros_ws/src/interface/px4_interface/launch/px4_interface.launch.xml index 2e11a856c..a61891088 100644 --- a/robot/ros_ws/src/interface/px4_interface/launch/px4_interface.launch.xml +++ b/robot/ros_ws/src/interface/px4_interface/launch/px4_interface.launch.xml @@ -63,12 +63,6 @@ - - - - - + diff --git a/robot/ros_ws/src/local/controls/trajectory_controller/CMakeLists.txt b/robot/ros_ws/src/local/controls/trajectory_controller/CMakeLists.txt index 880d79242..f19e0bd6d 100644 --- a/robot/ros_ws/src/local/controls/trajectory_controller/CMakeLists.txt +++ b/robot/ros_ws/src/local/controls/trajectory_controller/CMakeLists.txt @@ -8,6 +8,7 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) find_package(pluginlib REQUIRED) find_package(geometry_msgs REQUIRED) find_package(visualization_msgs REQUIRED) @@ -18,6 +19,7 @@ find_package(tf2_ros REQUIRED) find_package(airstack_msgs REQUIRED) find_package(airstack_common REQUIRED) find_package(trajectory_library REQUIRED) +find_package(task_msgs REQUIRED) add_executable(trajectory_controller src/trajectory_controller.cpp) @@ -35,7 +37,19 @@ ament_target_dependencies(trajectory_controller airstack_msgs airstack_common trajectory_library) -install(TARGETS trajectory_controller + +add_executable(fixed_trajectory_task src/fixed_trajectory_task.cpp) +target_include_directories(fixed_trajectory_task PUBLIC + $ + $) +ament_target_dependencies(fixed_trajectory_task + rclcpp + rclcpp_action + nav_msgs + airstack_msgs + task_msgs) + +install(TARGETS trajectory_controller fixed_trajectory_task DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY diff --git a/robot/ros_ws/src/local/controls/trajectory_controller/package.xml b/robot/ros_ws/src/local/controls/trajectory_controller/package.xml index 4c8876400..6d51bccf9 100644 --- a/robot/ros_ws/src/local/controls/trajectory_controller/package.xml +++ b/robot/ros_ws/src/local/controls/trajectory_controller/package.xml @@ -13,6 +13,7 @@ tf2_ros tf2_tools rclcpp + rclcpp_action pluginlib geometry_msgs visualization_msgs @@ -21,6 +22,7 @@ airstack_msgs airstack_common trajectory_library + task_msgs ament_lint_auto ament_lint_common diff --git a/robot/ros_ws/src/local/controls/trajectory_controller/src/fixed_trajectory_task.cpp b/robot/ros_ws/src/local/controls/trajectory_controller/src/fixed_trajectory_task.cpp new file mode 100644 index 000000000..e89445fe6 --- /dev/null +++ b/robot/ros_ws/src/local/controls/trajectory_controller/src/fixed_trajectory_task.cpp @@ -0,0 +1,595 @@ +// Copyright (c) 2024 Carnegie Mellon University +// +// 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. +// +// Ports fixed_trajectory_generator.py to a ROS 2 action server. + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "task_msgs/action/fixed_trajectory_task.hpp" + +using WaypointXYZVYaw = airstack_msgs::msg::WaypointXYZVYaw; +using TrajectoryXYZVYaw = airstack_msgs::msg::TrajectoryXYZVYaw; + +// ─────────────────────────── trajectory generation helpers ─────────────────── + +static void get_velocities(TrajectoryXYZVYaw & traj, double velocity, double max_acc) +{ + auto & wps = traj.waypoints; + double v_prev = 0.0; + for (size_t i = 0; i < wps.size(); ++i) { + size_t j = (i + 1) % wps.size(); + double dx = wps[j].position.x - wps[i].position.x; + double dy = wps[j].position.y - wps[i].position.y; + double dist = std::sqrt(dx * dx + dy * dy); + double v_limit = std::sqrt(v_prev * v_prev + 2.0 * max_acc * dist); + wps[i].velocity = std::min(velocity, v_limit); + v_prev = wps[i].velocity; + } +} + +static void get_velocities_dual(TrajectoryXYZVYaw & traj, double velocity, double max_acc) +{ + auto & wps = traj.waypoints; + double v_prev = 0.0; + for (size_t i = 0; i < wps.size(); ++i) { + size_t j = (i + 1) % wps.size(); + double dx = wps[j].position.x - wps[i].position.x; + double dy = wps[j].position.y - wps[i].position.y; + double dist = std::sqrt(dx * dx + dy * dy); + double v_limit = std::sqrt(v_prev * v_prev + 2.0 * max_acc * dist); + wps[i].velocity = std::min(velocity, v_limit); + v_prev = wps[i].velocity; + } + + v_prev = 0.0; + size_t tail_start = static_cast(wps.size() * 0.85); + for (size_t i = wps.size() - 1; i > tail_start; --i) { + size_t j = (i - 1 + wps.size()) % wps.size(); + double dx = wps[j].position.x - wps[i].position.x; + double dy = wps[j].position.y - wps[i].position.y; + double dist = std::sqrt(dx * dx + dy * dy); + double v_limit = std::sqrt(v_prev * v_prev + 2.0 * max_acc * dist); + wps[i].velocity = std::min(velocity, v_limit); + v_prev = wps[i].velocity; + } + wps.back().velocity = 0.0; +} + +static void get_accelerations(TrajectoryXYZVYaw & traj) +{ + auto & wps = traj.waypoints; + if (wps.size() < 3) {return;} + + for (size_t i = 0; i + 2 < wps.size(); ++i) { + size_t j = i + 1; + size_t k = i + 2; + + double dx1 = wps[j].position.x - wps[i].position.x; + double dy1 = wps[j].position.y - wps[i].position.y; + double dist1 = std::sqrt(dx1 * dx1 + dy1 * dy1); + if (dist1 < 1e-9) { + wps[i].acceleration.x = 0.0; + wps[i].acceleration.y = 0.0; + wps[i].acceleration.z = 0.0; + continue; + } + + double v_cx = wps[i].velocity * dx1 / dist1; + double v_cy = wps[i].velocity * dy1 / dist1; + + double dx2 = wps[k].position.x - wps[j].position.x; + double dy2 = wps[k].position.y - wps[j].position.y; + double dist2 = std::sqrt(dx2 * dx2 + dy2 * dy2); + if (dist2 < 1e-9) { + wps[i].acceleration.x = 0.0; + wps[i].acceleration.y = 0.0; + wps[i].acceleration.z = 0.0; + continue; + } + + double v_nx = wps[j].velocity * dx2 / dist2; + double v_ny = wps[j].velocity * dy2 / dist2; + + constexpr double acc_limit = 50.0; + wps[i].acceleration.x = (std::abs(dx1) < 1e-6) + ? 0.0 : std::min((v_nx * v_nx - v_cx * v_cx) / (2.0 * dx1), acc_limit); + wps[i].acceleration.y = (std::abs(dy1) < 1e-6) + ? 0.0 : std::min((v_ny * v_ny - v_cy * v_cy) / (2.0 * dy1), acc_limit); + wps[i].acceleration.z = 0.0; + } + + // zero out last two + if (wps.size() >= 2) { + wps[wps.size() - 2].acceleration.x = 0.0; + wps[wps.size() - 2].acceleration.y = 0.0; + wps[wps.size() - 2].acceleration.z = 0.0; + } + wps.back().acceleration.x = 0.0; + wps.back().acceleration.y = 0.0; + wps.back().acceleration.z = 0.0; +} + +static WaypointXYZVYaw make_wp(double x, double y, double z, double yaw, double v = 0.0) +{ + WaypointXYZVYaw wp; + wp.position.x = x; + wp.position.y = y; + wp.position.z = z; + wp.yaw = yaw; + wp.velocity = v; + return wp; +} + +static TrajectoryXYZVYaw generate_circle(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double radius = std::stod(attrs.at("radius")); + double velocity = std::stod(attrs.at("velocity")); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + + traj.waypoints.push_back(make_wp(0.0, 0.0, 0.0, 0.0, velocity)); + traj.waypoints.push_back(make_wp(radius, 0.0, 0.0, 0.0, velocity)); + + for (double angle = 0.0; angle < 2.0 * M_PI; angle += 10.0 * M_PI / 180.0) { + traj.waypoints.push_back( + make_wp(radius * std::cos(angle), radius * std::sin(angle), 0.0, 0.0, velocity)); + } + + traj.waypoints.push_back(make_wp(radius, 0.0, 0.0, 0.0, velocity)); + traj.waypoints.push_back(make_wp(0.0, 0.0, 0.0, 0.0, velocity)); + return traj; +} + +static TrajectoryXYZVYaw generate_figure8(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double length = std::stod(attrs.at("length")); + double width = std::stod(attrs.at("width")); + double height = std::stod(attrs.at("height")); + double velocity = std::stod(attrs.at("velocity")); + double max_acc = std::stod(attrs.at("max_acceleration")); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + + int n = 600; + for (int i = 0; i < n - 1; ++i) { + double t = 2.0 * M_PI * i / n; + double x = std::cos(t) * length - length; + double y = std::cos(t) * std::sin(t) * 2.0 * width; + double xd = -std::sin(t) * length; + double yd = (std::cos(t) * std::cos(t) - std::sin(t) * std::sin(t)) * 2.0 * width; + double yaw = std::atan2(yd, xd); + traj.waypoints.push_back(make_wp(x, y, height, yaw)); + } + + get_velocities_dual(traj, velocity, max_acc); + get_accelerations(traj); + return traj; +} + +static TrajectoryXYZVYaw generate_racetrack(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double length = std::stod(attrs.at("length")); + double width = std::stod(attrs.at("width")); + double height = std::stod(attrs.at("height")); + double velocity = std::stod(attrs.at("velocity")); + double turn_velocity = std::stod(attrs.at("turn_velocity")); + double max_acc = std::stod(attrs.at("max_acceleration")); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + + double sl = length - width; // straightaway length + + // first straightaway + for (int i = 0; i <= 79; ++i) { + double x = sl * i / 79.0; + traj.waypoints.push_back(make_wp(x, 0.0, height, 0.0, velocity)); + } + + // first turn: semi-circle at (sl, width/2), from -pi/2 to pi/2 + int turn_n = 48; // 50 - 2 endpoints already covered + for (int i = 1; i < turn_n + 1; ++i) { + double t = -M_PI / 2.0 + M_PI * i / (turn_n + 1); + double x = width / 2.0 * std::cos(t) + sl; + double y = width / 2.0 * std::sin(t) + width / 2.0; + double xd = -width / 2.0 * std::sin(t); + double yd = width / 2.0 * std::cos(t); + double yaw = std::atan2(yd, xd); + traj.waypoints.push_back(make_wp(x, y, height, yaw, turn_velocity)); + } + + // second straightaway + for (int i = 0; i <= 79; ++i) { + double x = sl * (1.0 - i / 79.0); + traj.waypoints.push_back(make_wp(x, width, height, M_PI, velocity)); + } + + // second turn: semi-circle at (0, width/2), from pi/2 to 3pi/2 + for (int i = 1; i < turn_n + 1; ++i) { + double t = M_PI / 2.0 + M_PI * i / (turn_n + 1); + double x = width / 2.0 * std::cos(t); + double y = width / 2.0 * std::sin(t) + width / 2.0; + double xd = -width / 2.0 * std::sin(t); + double yd = width / 2.0 * std::cos(t); + double yaw = std::atan2(yd, xd) + M_PI; + traj.waypoints.push_back(make_wp(x, y, height, yaw, turn_velocity)); + } + + if (!traj.waypoints.empty()) { + traj.waypoints.front().velocity = 0.0; + traj.waypoints.back().velocity = 0.0; + } + + get_accelerations(traj); + (void)max_acc; + return traj; +} + +static TrajectoryXYZVYaw generate_line(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double length = std::stod(attrs.at("length")); + double height = std::stod(attrs.at("height")); + double velocity = std::stod(attrs.at("velocity")); + double max_acc = std::stod(attrs.at("max_acceleration")); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + + for (double y = 0.0; y > -length; y -= 0.5) { + traj.waypoints.push_back(make_wp(-y, 0.0, height, 0.0)); + } + + get_velocities(traj, velocity, max_acc); + return traj; +} + +static TrajectoryXYZVYaw generate_point(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double x = std::stod(attrs.at("x")); + double y = std::stod(attrs.at("y")); + double height = std::stod(attrs.at("height")); + double velocity = std::stod(attrs.at("velocity")); + double max_acc = std::stod(attrs.at("max_acceleration")); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + traj.waypoints.push_back(make_wp(x, y, height, 0.0)); + + get_velocities(traj, velocity, max_acc); + return traj; +} + +static TrajectoryXYZVYaw generate_lawnmower(const std::map & attrs) +{ + std::string frame_id = attrs.count("frame_id") ? attrs.at("frame_id") : "base_link"; + double length = std::stod(attrs.at("length")); + double width = std::stod(attrs.at("width")); + double height = std::stod(attrs.at("height")); + double velocity = std::stod(attrs.at("velocity")); + bool vertical = (attrs.count("vertical") && std::stoi(attrs.at("vertical")) != 0); + + TrajectoryXYZVYaw traj; + traj.header.frame_id = frame_id; + + int strips = static_cast(std::abs(height / width)); + double h_sign = (height >= 0) ? 1.0 : -1.0; + + for (int i = 0; i < strips; ++i) { + double z = h_sign * (i + 1) * width; + double yaw = std::atan2(length, 0.0); // pointing along y + + if (i % 2 == 0) { + // y goes 0 → length + traj.waypoints.push_back(make_wp(0.0, 0.0, z, vertical ? 0.0 : yaw, 0.1)); + traj.waypoints.push_back(make_wp(0.0, 0.5, z, vertical ? 0.0 : yaw, 0.1)); + traj.waypoints.push_back(make_wp(0.0, 0.5, z, vertical ? 0.0 : yaw, velocity)); + traj.waypoints.push_back(make_wp(0.0, length - 0.5, z, vertical ? 0.0 : yaw, velocity)); + traj.waypoints.push_back(make_wp(0.0, length, z, vertical ? 0.0 : yaw, 0.1)); + } else { + // y goes length → 0 + traj.waypoints.push_back(make_wp(0.0, length, z, vertical ? 0.0 : -yaw, 0.1)); + traj.waypoints.push_back(make_wp(0.0, length - 0.5, z, vertical ? 0.0 : -yaw, 0.1)); + traj.waypoints.push_back(make_wp(0.0, length - 0.5, z, vertical ? 0.0 : -yaw, velocity)); + traj.waypoints.push_back(make_wp(0.0, 0.5, z, vertical ? 0.0 : -yaw, velocity)); + traj.waypoints.push_back(make_wp(0.0, 0.0, z, vertical ? 0.0 : -yaw, 0.1)); + } + } + + // return waypoint + traj.waypoints.push_back(make_wp(0.0, 0.0, 0.0, 0.0, 0.5)); + + // if not vertical, swap x and z + if (!vertical) { + for (auto & wp : traj.waypoints) { + std::swap(wp.position.x, wp.position.z); + } + } + + return traj; +} + +// ─────────────────────────── action server node ─────────────────────────────── + +class FixedTrajectoryTaskNode : public rclcpp::Node +{ +public: + using FixedTrajectoryTask = task_msgs::action::FixedTrajectoryTask; + using GoalHandle = rclcpp_action::ServerGoalHandle; + + FixedTrajectoryTaskNode() + : rclcpp::Node("fixed_trajectory_task") + { + completion_sub_ = this->create_subscription( + "trajectory_completion_percentage", 1, + [this](std_msgs::msg::Float32::SharedPtr msg) { + std::lock_guard lock(completion_mutex_); + completion_percentage_ = msg->data; + }); + + odom_sub_ = this->create_subscription( + "odometry", rclcpp::QoS(1).best_effort(), + [this](nav_msgs::msg::Odometry::SharedPtr msg) { + std::lock_guard lock(odom_mutex_); + current_odom_ = *msg; + }); + + traj_override_pub_ = + this->create_publisher("trajectory_override", 1); + + traj_mode_client_ = + this->create_client("set_trajectory_mode"); + + action_server_ = rclcpp_action::create_server( + this, "~/fixed_trajectory_task", + std::bind(&FixedTrajectoryTaskNode::handle_goal, this, + std::placeholders::_1, std::placeholders::_2), + std::bind(&FixedTrajectoryTaskNode::handle_cancel, this, std::placeholders::_1), + std::bind(&FixedTrajectoryTaskNode::handle_accepted, this, std::placeholders::_1)); + + RCLCPP_INFO(this->get_logger(), "FixedTrajectoryTaskNode started"); + } + +private: + std::atomic task_active_{false}; + std::atomic cancel_requested_{false}; + + std::mutex completion_mutex_; + float completion_percentage_{0.0f}; + + std::mutex odom_mutex_; + nav_msgs::msg::Odometry current_odom_; + + rclcpp::Subscription::SharedPtr completion_sub_; + rclcpp::Subscription::SharedPtr odom_sub_; + rclcpp::Publisher::SharedPtr traj_override_pub_; + rclcpp::Client::SharedPtr traj_mode_client_; + rclcpp_action::Server::SharedPtr action_server_; + + bool set_trajectory_mode(int32_t mode) + { + if (!traj_mode_client_->wait_for_service(std::chrono::seconds(2))) { + RCLCPP_ERROR(this->get_logger(), "set_trajectory_mode service not available"); + return false; + } + auto req = std::make_shared(); + req->mode = mode; + auto future = traj_mode_client_->async_send_request(req); + future.wait(); + return future.get()->success; + } + + rclcpp_action::GoalResponse handle_goal( + const rclcpp_action::GoalUUID &, + std::shared_ptr goal) + { + if (task_active_) { + RCLCPP_WARN(this->get_logger(), "FixedTrajectoryTask rejected: task already active"); + return rclcpp_action::GoalResponse::REJECT; + } + // validate trajectory type + const std::string & type = goal->trajectory_spec.type; + if (type != "Figure8" && type != "Circle" && type != "Racetrack" && + type != "Line" && type != "Point" && type != "Lawnmower") + { + RCLCPP_WARN(this->get_logger(), + "FixedTrajectoryTask rejected: unknown trajectory type '%s'", type.c_str()); + return rclcpp_action::GoalResponse::REJECT; + } + task_active_ = true; + cancel_requested_ = false; + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; + } + + rclcpp_action::CancelResponse handle_cancel(std::shared_ptr) + { + cancel_requested_ = true; + return rclcpp_action::CancelResponse::ACCEPT; + } + + void handle_accepted(std::shared_ptr goal_handle) + { + std::thread{ + std::bind(&FixedTrajectoryTaskNode::execute, this, std::placeholders::_1), + goal_handle}.detach(); + } + + void execute(std::shared_ptr goal_handle) + { + const auto goal = goal_handle->get_goal(); + auto result = std::make_shared(); + auto feedback = std::make_shared(); + + // parse attributes into a map + std::map attrs; + for (const auto & kv : goal->trajectory_spec.attributes) { + attrs[kv.key] = kv.value; + } + + // generate trajectory + TrajectoryXYZVYaw traj; + const std::string & type = goal->trajectory_spec.type; + try { + if (type == "Circle") { + traj = generate_circle(attrs); + } else if (type == "Figure8") { + traj = generate_figure8(attrs); + } else if (type == "Racetrack") { + traj = generate_racetrack(attrs); + } else if (type == "Line") { + traj = generate_line(attrs); + } else if (type == "Point") { + traj = generate_point(attrs); + } else if (type == "Lawnmower") { + traj = generate_lawnmower(attrs); + } + } catch (const std::exception & e) { + RCLCPP_ERROR(this->get_logger(), "FixedTrajectoryTask: trajectory generation failed: %s", + e.what()); + result->success = false; + result->message = std::string("trajectory generation failed: ") + e.what(); + goal_handle->abort(result); + task_active_ = false; + return; + } + + if (traj.waypoints.empty()) { + result->success = false; + result->message = "trajectory generation produced no waypoints"; + goal_handle->abort(result); + task_active_ = false; + return; + } + + traj.header.stamp = this->now(); + + // set trajectory mode to TRACK and publish + if (!set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::TRACK)) { + result->success = false; + result->message = "failed to set trajectory mode"; + goal_handle->abort(result); + task_active_ = false; + return; + } + + traj_override_pub_->publish(traj); + RCLCPP_INFO(this->get_logger(), "FixedTrajectoryTask: executing %s (%zu waypoints)", + type.c_str(), traj.waypoints.size()); + + // reset completion percentage after publishing + { + std::lock_guard lock(completion_mutex_); + completion_percentage_ = 0.0f; + } + + // monitor completion + rclcpp::Rate rate(5); + while (rclcpp::ok()) { + if (cancel_requested_) { + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "cancelled"; + goal_handle->canceled(result); + task_active_ = false; + return; + } + + float completion; + { + std::lock_guard lock(completion_mutex_); + completion = completion_percentage_; + } + + nav_msgs::msg::Odometry odom; + { + std::lock_guard lock(odom_mutex_); + odom = current_odom_; + } + + feedback->progress = completion / 100.0f; + feedback->status = type + " trajectory running"; + feedback->current_position.x = odom.pose.pose.position.x; + feedback->current_position.y = odom.pose.pose.position.y; + feedback->current_position.z = odom.pose.pose.position.z; + goal_handle->publish_feedback(feedback); + + if (completion >= 100.0f) { + if (goal->loop) { + // republish and reset + traj.header.stamp = this->now(); + traj_override_pub_->publish(traj); + { + std::lock_guard lock(completion_mutex_); + completion_percentage_ = 0.0f; + } + RCLCPP_INFO(this->get_logger(), "FixedTrajectoryTask: looping %s", type.c_str()); + } else { + RCLCPP_INFO(this->get_logger(), "FixedTrajectoryTask: %s complete", type.c_str()); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = true; + result->message = type + " trajectory complete"; + goal_handle->succeed(result); + task_active_ = false; + return; + } + } + + rate.sleep(); + } + + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "node shutting down"; + goal_handle->abort(result); + task_active_ = false; + } +}; + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(node); + executor.spin(); + rclcpp::shutdown(); + return 0; +} diff --git a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml index 9c7283035..9c9998792 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml @@ -15,29 +15,37 @@ - - + + + + + + + + + + + - - - - - + + + - - + diff --git a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml index a65d20b96..b3e0a940e 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml @@ -15,29 +15,37 @@ - - + + + + + + + + + + + - - - - - + + + - - + diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt b/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt index 1adb3320b..7066d6af1 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt @@ -8,18 +8,21 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) find_package(std_msgs REQUIRED) find_package(airstack_msgs REQUIRED) find_package(airstack_common REQUIRED) find_package(trajectory_library REQUIRED) find_package(mavros_msgs REQUIRED) find_package(std_srvs REQUIRED) +find_package(task_msgs REQUIRED) +find_package(nav_msgs REQUIRED) add_executable(takeoff_landing_planner src/takeoff_landing_planner.cpp) target_include_directories(takeoff_landing_planner PUBLIC $ $) -target_compile_features(takeoff_landing_planner PUBLIC c_std_99 cxx_std_17) # Require C99 and C++17 +target_compile_features(takeoff_landing_planner PUBLIC c_std_99 cxx_std_17) ament_target_dependencies( takeoff_landing_planner std_msgs @@ -30,7 +33,24 @@ ament_target_dependencies( std_srvs ) -install(TARGETS takeoff_landing_planner +add_executable(takeoff_landing_task src/takeoff_landing_task.cpp) +target_include_directories(takeoff_landing_task PUBLIC + $ + $) +target_compile_features(takeoff_landing_task PUBLIC c_std_99 cxx_std_17) +ament_target_dependencies( + takeoff_landing_task + rclcpp + rclcpp_action + std_msgs + nav_msgs + airstack_msgs + airstack_common + trajectory_library + task_msgs +) + +install(TARGETS takeoff_landing_planner takeoff_landing_task DESTINATION lib/${PROJECT_NAME}) install(DIRECTORY diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp new file mode 100644 index 000000000..fa1cfee91 --- /dev/null +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -0,0 +1,129 @@ +// Copyright (c) 2024 Carnegie Mellon University +// +// 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. + +#pragma once + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "task_msgs/action/land_task.hpp" +#include "task_msgs/action/takeoff_task.hpp" + +class TakeoffLandingTaskNode : public rclcpp::Node +{ +public: + using TakeoffTask = task_msgs::action::TakeoffTask; + using TakeoffGoalHandle = rclcpp_action::ServerGoalHandle; + using LandTask = task_msgs::action::LandTask; + using LandGoalHandle = rclcpp_action::ServerGoalHandle; + + TakeoffLandingTaskNode(); + +private: + // parameters + float default_takeoff_velocity_; + float default_landing_velocity_; + float takeoff_acceptance_distance_; + float takeoff_acceptance_time_; + float landing_stationary_distance_; + float landing_acceptance_time_; + float landing_tracking_point_ahead_time_; + float takeoff_path_roll_; + float takeoff_path_pitch_; + bool takeoff_path_relative_to_orientation_; + + // shared state (protected by mutex) + std::mutex odom_mutex_; + nav_msgs::msg::Odometry robot_odom_; + bool got_robot_odom_{false}; + + std::mutex tracking_point_mutex_; + airstack_msgs::msg::Odometry tracking_point_odom_; + bool got_tracking_point_{false}; + + std::mutex completion_mutex_; + float completion_percentage_{0.0f}; + bool got_completion_percentage_{false}; + + // precondition state (atomic for lock-free reads in handle_goal) + std::atomic is_armed_{false}; + std::atomic has_control_{false}; + std::atomic state_estimate_timed_out_{false}; + + // task exclusion + std::atomic task_active_{false}; + std::atomic cancel_requested_{false}; + + // subscribers + rclcpp::Subscription::SharedPtr robot_odom_sub_; + rclcpp::Subscription::SharedPtr tracking_point_sub_; + rclcpp::Subscription::SharedPtr is_armed_sub_; + rclcpp::Subscription::SharedPtr has_control_sub_; + rclcpp::Subscription::SharedPtr state_estimate_timed_out_sub_; + rclcpp::Subscription::SharedPtr completion_percentage_sub_; + + // publishers + rclcpp::Publisher::SharedPtr traj_override_pub_; + + // service client + rclcpp::Client::SharedPtr traj_mode_client_; + + // action servers + rclcpp_action::Server::SharedPtr takeoff_server_; + rclcpp_action::Server::SharedPtr land_server_; + + // subscription callbacks + void odom_callback(const nav_msgs::msg::Odometry::SharedPtr msg); + void tracking_point_callback(const airstack_msgs::msg::Odometry::SharedPtr msg); + void completion_percentage_callback(const std_msgs::msg::Float32::SharedPtr msg); + + // helpers + bool set_trajectory_mode(int32_t mode); + + // TakeoffTask action server callbacks + rclcpp_action::GoalResponse takeoff_handle_goal( + const rclcpp_action::GoalUUID & uuid, + std::shared_ptr goal); + rclcpp_action::CancelResponse takeoff_handle_cancel( + std::shared_ptr goal_handle); + void takeoff_handle_accepted(std::shared_ptr goal_handle); + void takeoff_execute(std::shared_ptr goal_handle); + + // LandTask action server callbacks + rclcpp_action::GoalResponse land_handle_goal( + const rclcpp_action::GoalUUID & uuid, + std::shared_ptr goal); + rclcpp_action::CancelResponse land_handle_cancel( + std::shared_ptr goal_handle); + void land_handle_accepted(std::shared_ptr goal_handle); + void land_execute(std::shared_ptr goal_handle); +}; diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/package.xml b/robot/ros_ws/src/local/planners/takeoff_landing_planner/package.xml index 410fb2b74..a718f1309 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/package.xml +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/package.xml @@ -10,12 +10,15 @@ ament_cmake rclcpp + rclcpp_action std_msgs + nav_msgs airstack_msgs airstack_common trajectory_library mavros_msgs std_srvs + task_msgs ament_lint_auto ament_lint_common diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp new file mode 100644 index 000000000..cf07299a9 --- /dev/null +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -0,0 +1,483 @@ +// Copyright (c) 2024 Carnegie Mellon University +// +// 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. + +#include + +#include +#include +#include + +TakeoffLandingTaskNode::TakeoffLandingTaskNode() +: rclcpp::Node("takeoff_landing_task") +{ + // parameters + default_takeoff_velocity_ = airstack::get_param(this, "takeoff_velocity", 1.0f); + default_landing_velocity_ = airstack::get_param(this, "landing_velocity", 0.3f); + takeoff_acceptance_distance_ = airstack::get_param(this, "takeoff_acceptance_distance", 0.3f); + takeoff_acceptance_time_ = airstack::get_param(this, "takeoff_acceptance_time", 1.0f); + landing_stationary_distance_ = airstack::get_param(this, "landing_stationary_distance", 0.02f); + landing_acceptance_time_ = airstack::get_param(this, "landing_acceptance_time", 5.0f); + landing_tracking_point_ahead_time_ = + airstack::get_param(this, "landing_tracking_point_ahead_time", 5.0f); + takeoff_path_roll_ = airstack::get_param(this, "takeoff_path_roll", 0.0f) * M_PI / 180.0f; + takeoff_path_pitch_ = airstack::get_param(this, "takeoff_path_pitch", 0.0f) * M_PI / 180.0f; + takeoff_path_relative_to_orientation_ = + airstack::get_param(this, "takeoff_path_relative_to_orientation", false); + + // subscribers + auto sensor_qos = rclcpp::QoS(1); + sensor_qos.reliability(rclcpp::ReliabilityPolicy::BestEffort); + + robot_odom_sub_ = this->create_subscription( + "odometry", sensor_qos, + std::bind(&TakeoffLandingTaskNode::odom_callback, this, std::placeholders::_1)); + + tracking_point_sub_ = this->create_subscription( + "tracking_point", 1, + std::bind(&TakeoffLandingTaskNode::tracking_point_callback, this, std::placeholders::_1)); + + completion_percentage_sub_ = this->create_subscription( + "trajectory_completion_percentage", 1, + std::bind( + &TakeoffLandingTaskNode::completion_percentage_callback, this, std::placeholders::_1)); + + is_armed_sub_ = this->create_subscription( + "is_armed", 1, + [this](std_msgs::msg::Bool::SharedPtr msg) { is_armed_ = msg->data; }); + + has_control_sub_ = this->create_subscription( + "has_control", 1, + [this](std_msgs::msg::Bool::SharedPtr msg) { has_control_ = msg->data; }); + + state_estimate_timed_out_sub_ = this->create_subscription( + "state_estimate_timed_out", 1, + [this](std_msgs::msg::Bool::SharedPtr msg) { state_estimate_timed_out_ = msg->data; }); + + // publishers + traj_override_pub_ = + this->create_publisher("trajectory_override", 1); + + // service client + traj_mode_client_ = + this->create_client("set_trajectory_mode"); + + // action servers + takeoff_server_ = rclcpp_action::create_server( + this, "~/takeoff_task", + std::bind(&TakeoffLandingTaskNode::takeoff_handle_goal, this, + std::placeholders::_1, std::placeholders::_2), + std::bind(&TakeoffLandingTaskNode::takeoff_handle_cancel, this, std::placeholders::_1), + std::bind(&TakeoffLandingTaskNode::takeoff_handle_accepted, this, std::placeholders::_1)); + + land_server_ = rclcpp_action::create_server( + this, "~/land_task", + std::bind(&TakeoffLandingTaskNode::land_handle_goal, this, + std::placeholders::_1, std::placeholders::_2), + std::bind(&TakeoffLandingTaskNode::land_handle_cancel, this, std::placeholders::_1), + std::bind(&TakeoffLandingTaskNode::land_handle_accepted, this, std::placeholders::_1)); + + RCLCPP_INFO(this->get_logger(), "TakeoffLandingTaskNode started"); +} + +// ─────────────────────────── subscription callbacks ─────────────────────────── + +void TakeoffLandingTaskNode::odom_callback(const nav_msgs::msg::Odometry::SharedPtr msg) +{ + std::lock_guard lock(odom_mutex_); + robot_odom_ = *msg; + got_robot_odom_ = true; +} + +void TakeoffLandingTaskNode::tracking_point_callback( + const airstack_msgs::msg::Odometry::SharedPtr msg) +{ + std::lock_guard lock(tracking_point_mutex_); + tracking_point_odom_ = *msg; + got_tracking_point_ = true; +} + +void TakeoffLandingTaskNode::completion_percentage_callback( + const std_msgs::msg::Float32::SharedPtr msg) +{ + std::lock_guard lock(completion_mutex_); + completion_percentage_ = msg->data; + got_completion_percentage_ = true; +} + +// ─────────────────────────── helper ─────────────────────────────────────────── + +bool TakeoffLandingTaskNode::set_trajectory_mode(int32_t mode) +{ + if (!traj_mode_client_->wait_for_service(std::chrono::seconds(2))) { + RCLCPP_ERROR(this->get_logger(), "set_trajectory_mode service not available"); + return false; + } + auto request = std::make_shared(); + request->mode = mode; + auto future = traj_mode_client_->async_send_request(request); + future.wait(); + return future.get()->success; +} + +// ─────────────────────────── TakeoffTask ────────────────────────────────────── + +rclcpp_action::GoalResponse TakeoffLandingTaskNode::takeoff_handle_goal( + const rclcpp_action::GoalUUID &, + std::shared_ptr goal) +{ + if (task_active_) { + RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: another task is already active"); + return rclcpp_action::GoalResponse::REJECT; + } + if (state_estimate_timed_out_) { + RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: state estimate timed out"); + return rclcpp_action::GoalResponse::REJECT; + } + if (!is_armed_) { + RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: not armed"); + return rclcpp_action::GoalResponse::REJECT; + } + if (!has_control_) { + RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: no offboard control"); + return rclcpp_action::GoalResponse::REJECT; + } + if (goal->target_altitude_m <= 0.0f) { + RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: target_altitude_m must be positive"); + return rclcpp_action::GoalResponse::REJECT; + } + task_active_ = true; + cancel_requested_ = false; + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + +rclcpp_action::CancelResponse TakeoffLandingTaskNode::takeoff_handle_cancel( + std::shared_ptr) +{ + cancel_requested_ = true; + return rclcpp_action::CancelResponse::ACCEPT; +} + +void TakeoffLandingTaskNode::takeoff_handle_accepted(std::shared_ptr goal_handle) +{ + std::thread{ + std::bind(&TakeoffLandingTaskNode::takeoff_execute, this, std::placeholders::_1), + goal_handle}.detach(); +} + +void TakeoffLandingTaskNode::takeoff_execute(std::shared_ptr goal_handle) +{ + const auto goal = goal_handle->get_goal(); + float target_altitude = goal->target_altitude_m; + float velocity = (goal->velocity_m_s > 0.0f) ? goal->velocity_m_s : default_takeoff_velocity_; + + auto result = std::make_shared(); + auto feedback = std::make_shared(); + feedback->target_altitude_m = target_altitude; + + // wait for odometry + rclcpp::Rate wait_rate(10); + int wait_count = 0; + while (!got_robot_odom_ && rclcpp::ok()) { + if (wait_count++ > 50) { + RCLCPP_ERROR(this->get_logger(), "TakeoffTask aborted: no odometry received"); + result->success = false; + result->message = "no odometry received"; + goal_handle->abort(result); + task_active_ = false; + return; + } + wait_rate.sleep(); + } + + // set trajectory mode to TRACK + if (!set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::TRACK)) { + result->success = false; + result->message = "failed to set trajectory mode"; + goal_handle->abort(result); + task_active_ = false; + return; + } + + // generate and publish takeoff trajectory + { + std::lock_guard odom_lock(odom_mutex_); + std::lock_guard tp_lock(tracking_point_mutex_); + + airstack_msgs::msg::Odometry start_point; + if (got_tracking_point_) { + start_point = tracking_point_odom_; + } else { + // fall back to current robot odom as start point + start_point.header = robot_odom_.header; + start_point.pose.position.x = robot_odom_.pose.pose.position.x; + start_point.pose.position.y = robot_odom_.pose.pose.position.y; + start_point.pose.position.z = robot_odom_.pose.pose.position.z; + start_point.pose.orientation = robot_odom_.pose.pose.orientation; + } + + // height is relative offset; target_altitude_m is absolute + float current_z = robot_odom_.pose.pose.position.z; + float relative_height = target_altitude - current_z; + if (relative_height <= 0.0f) { + RCLCPP_WARN(this->get_logger(), + "TakeoffTask: target_altitude_m (%.2f) is not above current altitude (%.2f)", + target_altitude, current_z); + relative_height = 0.5f; // minimum ascent + } + + if (takeoff_path_relative_to_orientation_) { + start_point.pose.orientation = robot_odom_.pose.pose.orientation; + } + + TakeoffTrajectory traj_gen( + relative_height, velocity, + takeoff_path_roll_, takeoff_path_pitch_, + takeoff_path_relative_to_orientation_); + traj_override_pub_->publish(traj_gen.get_trajectory(start_point)); + } + + RCLCPP_INFO(this->get_logger(), "TakeoffTask: ascending to %.2fm at %.2f m/s", + target_altitude, velocity); + + // monitor completion + rclcpp::Rate rate(10); // 10 Hz feedback + rclcpp::Time acceptance_start; + bool in_acceptance_window = false; + + while (rclcpp::ok()) { + if (cancel_requested_) { + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "cancelled"; + goal_handle->canceled(result); + task_active_ = false; + return; + } + + float current_z; + { + std::lock_guard lock(odom_mutex_); + current_z = robot_odom_.pose.pose.position.z; + } + + feedback->current_altitude_m = current_z; + goal_handle->publish_feedback(feedback); + + // check completion: within acceptance distance of target for acceptance_time + float dist = std::abs(current_z - target_altitude); + if (dist <= takeoff_acceptance_distance_) { + if (!in_acceptance_window) { + in_acceptance_window = true; + acceptance_start = this->now(); + } + if ((this->now() - acceptance_start).seconds() >= takeoff_acceptance_time_) { + RCLCPP_INFO(this->get_logger(), "TakeoffTask: complete at %.2fm", current_z); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = true; + result->message = "takeoff complete"; + goal_handle->succeed(result); + task_active_ = false; + return; + } + } else { + in_acceptance_window = false; + } + + rate.sleep(); + } + + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "node shutting down"; + goal_handle->abort(result); + task_active_ = false; +} + +// ─────────────────────────── LandTask ───────────────────────────────────────── + +rclcpp_action::GoalResponse TakeoffLandingTaskNode::land_handle_goal( + const rclcpp_action::GoalUUID &, + std::shared_ptr) +{ + if (task_active_) { + RCLCPP_WARN(this->get_logger(), "LandTask rejected: another task is already active"); + return rclcpp_action::GoalResponse::REJECT; + } + task_active_ = true; + cancel_requested_ = false; + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + +rclcpp_action::CancelResponse TakeoffLandingTaskNode::land_handle_cancel( + std::shared_ptr) +{ + cancel_requested_ = true; + return rclcpp_action::CancelResponse::ACCEPT; +} + +void TakeoffLandingTaskNode::land_handle_accepted(std::shared_ptr goal_handle) +{ + std::thread{ + std::bind(&TakeoffLandingTaskNode::land_execute, this, std::placeholders::_1), + goal_handle}.detach(); +} + +void TakeoffLandingTaskNode::land_execute(std::shared_ptr goal_handle) +{ + const auto goal = goal_handle->get_goal(); + float velocity = (goal->velocity_m_s > 0.0f) ? goal->velocity_m_s : default_landing_velocity_; + + auto result = std::make_shared(); + auto feedback = std::make_shared(); + + // wait for odometry + rclcpp::Rate wait_rate(10); + int wait_count = 0; + while (!got_robot_odom_ && rclcpp::ok()) { + if (wait_count++ > 50) { + RCLCPP_ERROR(this->get_logger(), "LandTask aborted: no odometry received"); + result->success = false; + result->message = "no odometry received"; + goal_handle->abort(result); + task_active_ = false; + return; + } + wait_rate.sleep(); + } + + // set trajectory mode to TRACK + if (!set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::TRACK)) { + result->success = false; + result->message = "failed to set trajectory mode"; + goal_handle->abort(result); + task_active_ = false; + return; + } + + // generate and publish landing trajectory + { + std::lock_guard tp_lock(tracking_point_mutex_); + airstack_msgs::msg::Odometry start_point; + if (got_tracking_point_) { + start_point = tracking_point_odom_; + } else { + std::lock_guard odom_lock(odom_mutex_); + start_point.header = robot_odom_.header; + start_point.pose.position.x = robot_odom_.pose.pose.position.x; + start_point.pose.position.y = robot_odom_.pose.pose.position.y; + start_point.pose.position.z = robot_odom_.pose.pose.position.z; + start_point.pose.orientation = robot_odom_.pose.pose.orientation; + } + TakeoffTrajectory land_traj(-10000.0, velocity); + traj_override_pub_->publish(land_traj.get_trajectory(start_point)); + } + + RCLCPP_INFO(this->get_logger(), "LandTask: descending at %.2f m/s", velocity); + + // sliding window of odometry for stationary detection + std::deque odom_window; + + rclcpp::Rate rate(10); + while (rclcpp::ok()) { + if (cancel_requested_) { + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "cancelled"; + goal_handle->canceled(result); + task_active_ = false; + return; + } + + nav_msgs::msg::Odometry current_odom; + { + std::lock_guard lock(odom_mutex_); + current_odom = robot_odom_; + } + + feedback->current_altitude_m = current_odom.pose.pose.position.z; + feedback->status = "landing"; + goal_handle->publish_feedback(feedback); + + odom_window.push_back(current_odom); + + // trim window to landing_acceptance_time seconds + while (!odom_window.empty()) { + double age = (rclcpp::Time(current_odom.header.stamp) - + rclcpp::Time(odom_window.front().header.stamp)).seconds(); + if (age > landing_acceptance_time_) { + odom_window.pop_front(); + } else { + break; + } + } + + // check if we have enough history and the robot has been stationary + if (odom_window.size() >= 2) { + double window_span = (rclcpp::Time(current_odom.header.stamp) - + rclcpp::Time(odom_window.front().header.stamp)).seconds(); + + if (window_span >= landing_acceptance_time_) { + bool stationary = true; + for (const auto & past_odom : odom_window) { + double dx = current_odom.pose.pose.position.x - past_odom.pose.pose.position.x; + double dy = current_odom.pose.pose.position.y - past_odom.pose.pose.position.y; + double dz = current_odom.pose.pose.position.z - past_odom.pose.pose.position.z; + double dist = std::sqrt(dx * dx + dy * dy + dz * dz); + if (dist > landing_stationary_distance_) { + stationary = false; + break; + } + } + + if (stationary) { + RCLCPP_INFO(this->get_logger(), "LandTask: landing detected at %.2fm", + current_odom.pose.pose.position.z); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = true; + result->message = "landing complete"; + goal_handle->succeed(result); + task_active_ = false; + return; + } + } + } + + rate.sleep(); + } + + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = false; + result->message = "node shutting down"; + goal_handle->abort(result); + task_active_ = false; +} + +// ─────────────────────────── main ───────────────────────────────────────────── + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + auto node = std::make_shared(); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(node); + executor.spin(); + rclcpp::shutdown(); + return 0; +} diff --git a/robot/ros_ws/src/local/planners/trajectory_library/scripts/fixed_trajectory_generator.py b/robot/ros_ws/src/local/planners/trajectory_library/scripts/fixed_trajectory_generator.py deleted file mode 100755 index 958a405a1..000000000 --- a/robot/ros_ws/src/local/planners/trajectory_library/scripts/fixed_trajectory_generator.py +++ /dev/null @@ -1,551 +0,0 @@ -#!/usr/bin/python3 -import numpy as np -from nav_msgs.msg import Odometry -from geometry_msgs.msg import Point -from airstack_msgs.msg import WaypointXYZVYaw -from airstack_msgs.msg import TrajectoryXYZVYaw -from airstack_msgs.msg import FixedTrajectory -import time -import copy -import rclpy -from rclpy.node import Node - -logger = None - -def get_velocities(traj, velocity, max_acc): - v_prev = 0.0 - - for i in range(len(traj.waypoints)): - j = (i + 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - -def get_velocities_dual(traj, velocity, max_acc): - v_prev = 0.0 - - for i in range(len(traj.waypoints)): - j = (i + 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - v_prev = 0.0 - for i in range(len(traj.waypoints) - 1, int(len(traj.waypoints) * 0.85), -1): - j = (i - 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - traj.waypoints[len(traj.waypoints) - 1].velocity = 0.0 - -def get_velocities_adjust(traj, max_acc): - slow_down_adjust = [] - speed_up_adjust = [] - - for i in range(len(traj.waypoints)): - if i != len(traj.waypoints)-1: - if traj.waypoints[i].velocity > traj.waypoints[i+1].velocity: - v_start = traj.waypoints[i+1].velocity - v_target = traj.waypoints[i].velocity - slow_down_adjust.append((i+1, v_start, v_target)) - elif traj.waypoints[i].velocity < traj.waypoints[i+1].velocity: - v_start = traj.waypoints[i].velocity - v_target = traj.waypoints[i+1].velocity - speed_up_adjust.append((i, v_start, v_target)) - - for start_index, v_start, v_target in slow_down_adjust: - prev_i = start_index - v_prev = v_start - for i in range(start_index-1, -1, -1): - dx = traj.waypoints[prev_i].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[prev_i].position.y - traj.waypoints[i].position.y - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(v_target, v_limit) - v_prev = traj.waypoints[i].velocity - if v_prev >= v_target: - break - - for start_index, v_start, v_target in speed_up_adjust: - prev_i = start_index - v_prev = v_start - for i in range(start_index+1, len(traj.waypoints)): - dx = traj.waypoints[prev_i].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[prev_i].position.y - traj.waypoints[i].position.y - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - if v_limit > traj.waypoints[i].velocity: - break - traj.waypoints[i].velocity = min(v_target, v_limit) - v_prev = traj.waypoints[i].velocity - if v_prev >= v_target: - break - - -def get_accelerations(traj): - a_prev = 0.0 - - for i in range(len(traj.waypoints) - 2): - j = (i + 1) % len(traj.waypoints) - k = (i + 2) % len(traj.waypoints) - - dx1 = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy1 = traj.waypoints[j].position.y - traj.waypoints[i].position.y - dist1 = np.sqrt(dx1**2 + dy1**2) - - v_currx = traj.waypoints[i].velocity * (dx1) / dist1 - v_curry = traj.waypoints[i].velocity * (dy1) / dist1 - - dx2 = traj.waypoints[k].position.x - traj.waypoints[j].position.x - dy2 = traj.waypoints[k].position.y - traj.waypoints[j].position.y - dist2 = np.sqrt(dx2**2 + dy2**2) - - v_nextx = traj.waypoints[j].velocity * (dx2) / dist2 - v_nexty = traj.waypoints[j].velocity * (dy2) / dist2 - - acc_limit = 50. - if abs(dx1 - 0) < 1e-6: - traj.waypoints[i].acceleration.x = 0.0 - else: - traj.waypoints[i].acceleration.x = min( - (v_nextx**2 - v_currx**2) / (2 * dx1), acc_limit - ) - - if abs(dy1 - 0) < 1e-6: - traj.waypoints[i].acceleration.y = 0.0 - else: - traj.waypoints[i].acceleration.y = min( - (v_nexty**2 - v_curry**2) / (2 * dy1), acc_limit - ) - - traj.waypoints[i].acceleration.z = 0.0 - - traj.waypoints[len(traj.waypoints) - 2].acceleration.x = 0.0 - traj.waypoints[len(traj.waypoints) - 2].acceleration.y = 0.0 - traj.waypoints[len(traj.waypoints) - 2].acceleration.z = 0.0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.x = 0.0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.y = 0.0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.z = 0.0 - - -def get_racetrack_waypoints(attributes): # length, width, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - turn_velocity = float(attributes["turn_velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - straightaway_length = length - width - - # first straightaway - xs1 = np.linspace(0, straightaway_length, 80) - ys1 = np.zeros(xs1.shape) - vs1 = np.ones(xs1.shape)*velocity - yaws1 = np.zeros(xs1.shape) - - # first turn - t = np.linspace(-np.pi / 2, np.pi / 2, 50)[1:-1] - xs2 = width / 2.0 * np.cos(t) + straightaway_length - ys2 = width / 2.0 * np.sin(t) + width / 2.0 - xs2d = -width / 2.0 * np.sin(t) # derivative of xs - ys2d = width / 2.0 * np.cos(t) # derivative of ys - vs2 = np.ones(xs2.shape)*turn_velocity - yaws2 = np.arctan2(ys2d, xs2d) - - # second straightaway - xs3 = np.linspace(straightaway_length, 0, 80) - ys3 = width * np.ones(xs3.shape) - vs3 = np.ones(xs3.shape)*velocity - yaws3 = np.pi * np.ones(xs3.shape) - - # second turn - t = np.linspace(np.pi / 2, 3 * np.pi / 2, 50)[1:-1] - xs4 = width / 2.0 * np.cos(t) - ys4 = width / 2.0 * np.sin(t) + width / 2.0 - vs4 = np.ones(xs4.shape)*turn_velocity - yaws4 = yaws2 + np.pi - - xs = np.hstack((xs1, xs2, xs3, xs4)) - ys = np.hstack((ys1, ys2, ys3, ys4)) - vs = np.hstack((vs1, vs2, vs3, vs4)) - vs[0] = 0. - vs[-1] = 0. - yaws = np.hstack((yaws1, yaws2, yaws3, yaws4)) - - # now = rospy.Time.now() - for i in range(xs.shape[0]): - wp = WaypointXYZVYaw() - wp.position.x = xs[i] - wp.position.y = ys[i] - wp.position.z = height - wp.velocity = vs[i] - - #logger.info(str(i) + ' ' + str(wp.velocity)) - - wp.yaw = yaws[i] - - traj.waypoints.append(wp) - - #get_velocities_dual(traj, velocity, max_acceleration) - get_velocities_adjust(traj, max_acceleration) - get_accelerations(traj) - - return traj - - -def get_figure8_waypoints(attributes): # length, width, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - # now = rospy.Time.now() - - # figure 8 points - t = np.linspace(0, 2 * np.pi, 600) - x = np.cos(t) * length - length - y = np.cos(t) * np.sin(t) * 2 * width - - # derivative of figure 8 curve, used to find yaw - xd = -np.sin(t) * length - yd = (np.cos(t) ** 2 - np.sin(t) ** 2) * 2 * width - - for i in range(t.shape[0] - 1): - x1 = x[i] - y1 = y[i] - x2 = x1 + xd[i] - y2 = y1 + yd[i] - - yaw = np.arctan2(y2 - y1, x2 - x1) - - wp = WaypointXYZVYaw() - wp.position.x = x1 - wp.position.y = y1 - wp.position.z = height - wp.yaw = yaw - - traj.waypoints.append(wp) - - get_velocities_dual(traj, velocity, max_acceleration) - get_accelerations(traj) - - return traj - - -def get_line_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - for y in np.arange(0, -length, -0.5): - wp = WaypointXYZVYaw() - wp.position.x = -y - wp.position.y = 0. - wp.position.z = height - wp.yaw = 0. - - traj.waypoints.append(wp) - - get_velocities(traj, velocity, max_acceleration) - - return traj - - -def get_point_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - x = float(attributes["x"]) - y = float(attributes["y"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - # add first point - wp = WaypointXYZVYaw() - wp.position.x = x - wp.position.y = y - wp.position.z = height - wp.yaw = 0. - - traj.waypoints.append(wp) - - get_velocities(traj, velocity, max_acceleration) - - return traj - - -def get_box_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - wp1 = WaypointXYZVYaw() - wp1.position.x = 0.0 - wp1.position.y = 0.0 - wp1.position.z = height - wp1.yaw = 0 - traj.waypoints.append(wp1) - - wp2 = WaypointXYZVYaw() - wp2.position.x = length - wp2.position.y = 0.0 - wp2.position.z = height - wp2.yaw = 0.0 - traj.waypoints.append(wp2) - - wp3 = WaypointXYZVYaw() - wp3.position.x = length - wp3.position.y = 0.0 - wp3.position.z = height + height - wp3.yaw = 0.0 - traj.waypoints.append(wp3) - - wp4 = WaypointXYZVYaw() - wp4.position.x = 0.0 - wp4.position.y = 0.0 - wp4.position.z = height + height - wp4.yaw = 0.0 - traj.waypoints.append(wp4) - - return traj - - -def get_lawnmower_waypoints(attributes): # length, width, height, velocity): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - vertical = bool(int(attributes["vertical"])) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - for i in range(abs(int(height / width))): - wp1 = WaypointXYZVYaw() - wp1.position.x = 0.0 - wp1.position.y = 0.0 - wp1.position.z = np.sign(height) * (i + 1) * width - wp1.yaw = 0.0 - wp1.velocity = 0.1 - - wp1_ = WaypointXYZVYaw() - wp1_.position.x = 0.0 - wp1_.position.y = 0.5 - wp1_.position.z = np.sign(height) * (i + 1) * width - wp1_.yaw = 0.0 - wp1_.velocity = velocity - - wp2 = WaypointXYZVYaw() - wp2.position.x = 0.0 - wp2.position.y = length - wp2.position.z = np.sign(height) * (i + 1) * width - wp2.yaw = 0.0 - wp2.velocity = 0.1 - - wp2_ = WaypointXYZVYaw() - wp2_.position.x = 0.0 - wp2_.position.y = length - 0.5 - wp2_.position.z = np.sign(height) * (i + 1) * width - wp2_.yaw = 0.0 - wp2_.velocity = velocity - - yaw = np.arctan2(wp2.position.y - wp1.position.y, wp2.position.z - wp1.position.z) - - if i % 2 == 0: - if not vertical: - wp1.yaw = yaw - wp1_.yaw = yaw - wp2_.yaw = yaw - wp2.yaw = yaw - - traj.waypoints.append(wp1) - wp1_slow = copy.deepcopy(wp1_) - wp1_slow.velocity = 0.1 - traj.waypoints.append(wp1_slow) - traj.waypoints.append(wp1_) - traj.waypoints.append(wp2_) - traj.waypoints.append(wp2) - else: - if not vertical: - wp2.yaw = -yaw - wp2_.yaw = -yaw - wp1_.yaw = -yaw - wp1.yaw = -yaw - - traj.waypoints.append(wp2) - wp2_slow = copy.deepcopy(wp2_) - wp2_slow.velocity = 0.1 - traj.waypoints.append(wp2_slow) - traj.waypoints.append(wp2_) - traj.waypoints.append(wp1_) - traj.waypoints.append(wp1) - - wp = WaypointXYZVYaw() - wp.position.x = 0.0 - wp.position.y = 0.0 - wp.position.z = 0.0 - wp.yaw = 0.0 - wp.velocity = 0.5 - traj.waypoints.append(wp) - - if not vertical: - for i, wp in enumerate(traj.waypoints): - wp.position.x, wp.position.y, wp.position.z = wp.position.z, wp.position.y, wp.position.x - - return traj - - -def get_circle_waypoints(attributes): # radius, velocity, frame_id): - frame_id = str(attributes["frame_id"]) - radius = float(attributes["radius"]) - velocity = float(attributes["velocity"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - # traj.header.stamp = rospy.Time.now() - - wp0 = WaypointXYZVYaw() - wp0.position.x = 0.0 - wp0.position.y = 0.0 - wp0.position.z = 0.0 - wp0.yaw = 0.0 - wp0.velocity = velocity - traj.waypoints.append(wp0) - - wp1 = WaypointXYZVYaw() - wp1.position.x = radius - wp1.position.y = 0.0 - wp1.position.z = 0.0 - wp1.yaw = 0.0 - wp1.velocity = velocity - traj.waypoints.append(wp1) - - for angle in np.arange(0, 2 * np.pi, 10.0 * np.pi / 180.0): - wp = WaypointXYZVYaw() - wp.position.x = radius * np.cos(angle) - wp.position.y = radius * np.sin(angle) - wp.position.z = 0.0 - wp.yaw = 0.0 - wp.velocity = velocity - traj.waypoints.append(wp) - - wp_end0 = WaypointXYZVYaw() - wp_end0.position.x = radius - wp_end0.position.y = 0.0 - wp_end0.position.z = 0.0 - wp_end0.yaw = 0.0 - wp_end0.velocity = velocity - traj.waypoints.append(wp_end0) - - wp_end1 = WaypointXYZVYaw() - wp_end1.position.x = 0.0 - wp_end1.position.y = 0.0 - wp_end1.position.z = 0.0 - wp_end1.yaw = 0.0 - wp_end1.velocity = velocity - traj.waypoints.append(wp_end1) - - return traj - - -class FixedTrajectoryGenerator(Node): - def __init__(self): - super().__init__("fixed_trajectory_generator") - self.fixed_trajectory_sub = self.create_subscription( - FixedTrajectory, - "fixed_trajectory_command", - self.fixed_trajectory_callback, - 1, - ) - self.trajectory_override_pub = self.create_publisher( - TrajectoryXYZVYaw, "trajectory_override", 1 - ) - - def fixed_trajectory_callback(self, msg): - print("generating") - attributes = {} - - for key_value in msg.attributes: - attributes[key_value.key] = key_value.value - - trajectory_msg = None - - if msg.type == "Figure8": - trajectory_msg = get_figure8_waypoints(attributes) - elif msg.type == "Circle": - trajectory_msg = get_circle_waypoints(attributes) - elif msg.type == "Racetrack": - trajectory_msg = get_racetrack_waypoints(attributes) - elif msg.type == "Line": - trajectory_msg = get_line_waypoints(attributes) - elif msg.type == "Point": - trajectory_msg = get_point_waypoints(attributes) - elif msg.type == "Lawnmower": - trajectory_msg = get_lawnmower_waypoints(attributes) - - if trajectory_msg != None: - self.trajectory_override_pub.publish(trajectory_msg) - else: - print("No trajectory sent.") - -#import matplotlib.pyplot as plt - -if __name__ == "__main__": - ''' - dct = {'frame_id': 'base_link', 'length': 2, 'width': 1, 'height': 0, 'velocity': 2, 'turn_velocity': 0.5, 'max_acceleration': 0.1} - traj1 = get_racetrack_waypoints(dct) - dct['max_acceleration'] = 100000000. - traj2 = get_racetrack_waypoints(dct) - - v1 = [wp.velocity for wp in traj1.waypoints] - v2 = [wp.velocity for wp in traj2.waypoints] - - plt.plot(v1, '.-') - plt.plot(v2, '.-') - plt.show() - exit() - - ''' - rclpy.init(args=None) - - node = FixedTrajectoryGenerator() - logger = node.get_logger() - - rclpy.spin(node) - node.destroy_node() - rclpy.shutdown() diff --git a/robot/ros_ws/src/local/planners/trajectory_library/src/fixed_trajectory_generator.py b/robot/ros_ws/src/local/planners/trajectory_library/src/fixed_trajectory_generator.py deleted file mode 100755 index b13f7e7c8..000000000 --- a/robot/ros_ws/src/local/planners/trajectory_library/src/fixed_trajectory_generator.py +++ /dev/null @@ -1,453 +0,0 @@ -#!/usr/bin/python -import numpy as np -from nav_msgs.msg import Odometry -from geometry_msgs.msg import Point -import rospy -import tf.transformations as trans -import argparse - -# from at_fcs_mavros.msg import Trajectory -# from at_fcs_mavros.msg import Waypoint -# from ca_nav_msgs.msg import XYZVPsi -# from ca_nav_msgs.msg import PathXYZVPsi -from airstack_msgs.msg import WaypointXYZVYaw -from airstack_msgs.msg import TrajectoryXYZVYaw -from trajectory_controller.msg import Trajectory -from airstack_msgs.msg import FixedTrajectory -import time -import copy - - -def get_velocities(traj, velocity, max_acc): - v_prev = 0.0 - - for i in range(len(traj.waypoints)): - j = (i + 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - -def get_velocities_dual(traj, velocity, max_acc): - v_prev = 0.0 - - for i in range(len(traj.waypoints)): - j = (i + 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - v_prev = 0.0 - for i in range(len(traj.waypoints) - 1, int(len(traj.waypoints) * 0.85), -1): - j = (i - 1) % len(traj.waypoints) - dx = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy = traj.waypoints[j].position.y - traj.waypoints[i].position.y - - dist = np.sqrt(dx**2 + dy**2) - v_limit = np.sqrt(v_prev**2 + 2 * max_acc * dist) - traj.waypoints[i].velocity = min(velocity, v_limit) - v_prev = traj.waypoints[i].velocity - - traj.waypoints[len(traj.waypoints) - 1].velocity = 0 - - -def get_accelerations(traj): - a_prev = 0.0 - - for i in range(len(traj.waypoints) - 2): - j = (i + 1) % len(traj.waypoints) - k = (i + 2) % len(traj.waypoints) - - dx1 = traj.waypoints[j].position.x - traj.waypoints[i].position.x - dy1 = traj.waypoints[j].position.y - traj.waypoints[i].position.y - dist1 = np.sqrt(dx1**2 + dy1**2) - - v_currx = traj.waypoints[i].velocity * (dx1) / dist1 - v_curry = traj.waypoints[i].velocity * (dy1) / dist1 - - dx2 = traj.waypoints[k].position.x - traj.waypoints[j].position.x - dy2 = traj.waypoints[k].position.y - traj.waypoints[j].position.y - dist2 = np.sqrt(dx2**2 + dy2**2) - - v_nextx = traj.waypoints[j].velocity * (dx2) / dist2 - v_nexty = traj.waypoints[j].velocity * (dy2) / dist2 - - acc_limit = 50 - if abs(dx1 - 0) < 1e-6: - traj.waypoints[i].acceleration.x = 0 - else: - traj.waypoints[i].acceleration.x = min( - (v_nextx**2 - v_currx**2) / (2 * dx1), acc_limit - ) - - if abs(dy1 - 0) < 1e-6: - traj.waypoints[i].acceleration.y = 0 - else: - traj.waypoints[i].acceleration.y = min( - (v_nexty**2 - v_curry**2) / (2 * dy1), acc_limit - ) - - traj.waypoints[i].acceleration.z = 0 - - traj.waypoints[len(traj.waypoints) - 2].acceleration.x = 0 - traj.waypoints[len(traj.waypoints) - 2].acceleration.y = 0 - traj.waypoints[len(traj.waypoints) - 2].acceleration.z = 0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.x = 0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.y = 0 - traj.waypoints[len(traj.waypoints) - 1].acceleration.z = 0 - - -def get_racetrack_waypoints(attributes): # length, width, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - straightaway_length = length - width - - # first straightaway - xs1 = np.linspace(0, straightaway_length, 80) - ys1 = np.zeros(xs1.shape) - yaws1 = np.zeros(xs1.shape) - - # first turn - t = np.linspace(-np.pi / 2, np.pi / 2, 50)[1:-1] - xs2 = width / 2.0 * np.cos(t) + straightaway_length - ys2 = width / 2.0 * np.sin(t) + width / 2.0 - xs2d = -width / 2.0 * np.sin(t) # derivative of xs - ys2d = width / 2.0 * np.cos(t) # derivative of ys - yaws2 = np.arctan2(ys2d, xs2d) - - # second straightaway - xs3 = np.linspace(straightaway_length, 0, 80) - ys3 = width * np.ones(xs3.shape) - yaws3 = np.pi * np.ones(xs3.shape) - - # second turn - t = np.linspace(np.pi / 2, 3 * np.pi / 2, 50)[1:-1] - xs4 = width / 2.0 * np.cos(t) - ys4 = width / 2.0 * np.sin(t) + width / 2.0 - yaws4 = yaws2 + np.pi - - xs = np.hstack((xs1, xs2, xs3, xs4)) - ys = np.hstack((ys1, ys2, ys3, ys4)) - yaws = np.hstack((yaws1, yaws2, yaws3, yaws4)) - - now = rospy.Time.now() - for i in range(xs.shape[0]): - wp = WaypointXYZVYaw() - wp.position.x = xs[i] - wp.position.y = ys[i] - wp.position.z = height - wp.yaw = yaws[i] - - traj.waypoints.append(wp) - - get_velocities_dual(traj, velocity, max_acceleration) - get_accelerations(traj) - - return traj - - -def get_figure8_waypoints(attributes): # length, width, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - now = rospy.Time.now() - - # figure 8 points - t = np.linspace(0, 2 * np.pi, 600) - x = np.cos(t) * length - length - y = np.cos(t) * np.sin(t) * 2 * width - - # derivative of figure 8 curve, used to find yaw - xd = -np.sin(t) * length - yd = (np.cos(t) ** 2 - np.sin(t) ** 2) * 2 * width - - for i in range(t.shape[0] - 1): - x1 = x[i] - y1 = y[i] - x2 = x1 + xd[i] - y2 = y1 + yd[i] - - yaw = np.arctan2(y2 - y1, x2 - x1) - - wp = WaypointXYZVYaw() - wp.position.x = x1 - wp.position.y = y1 - wp.position.z = height - wp.yaw = yaw - - traj.waypoints.append(wp) - - get_velocities_dual(traj, velocity, max_acceleration) - get_accelerations(traj) - - return traj - - -def get_line_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - for y in np.arange(0, -length, -0.5): - wp = WaypointXYZVYaw() - wp.position.x = -y - wp.position.y = 0 - wp.position.z = height - wp.yaw = 0 - - traj.waypoints.append(wp) - - get_velocities(traj, velocity, max_acceleration) - - return traj - - -def get_point_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - x = float(attributes["x"]) - y = float(attributes["y"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - # add first point - wp = WaypointXYZVYaw() - wp.position.x = x - wp.position.y = y - wp.position.z = height - wp.yaw = 0 - - traj.waypoints.append(wp) - - get_velocities(traj, velocity, max_acceleration) - - return traj - - -def get_box_waypoints(attributes): # length, height): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - max_acceleration = float(attributes["max_acceleration"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - wp1 = WaypointXYZVYaw() - wp1.position.x = 0.0 - wp1.position.y = 0.0 - wp1.position.z = height - wp1.yaw = 0 - traj.waypoints.append(wp1) - - wp2 = WaypointXYZVYaw() - wp2.position.x = length - wp2.position.y = 0.0 - wp2.position.z = height - wp2.yaw = 0 - traj.waypoints.append(wp2) - - wp3 = WaypointXYZVYaw() - wp3.position.x = length - wp3.position.y = 0.0 - wp3.position.z = height + height - wp3.yaw = 0 - traj.waypoints.append(wp3) - - wp4 = WaypointXYZVYaw() - wp4.position.x = 0.0 - wp4.position.y = 0.0 - wp4.position.z = height + height - wp4.yaw = 0 - traj.waypoints.append(wp4) - - return traj - - -def get_vertical_lawnmower_waypoints(attributes): # length, width, height, velocity): - frame_id = str(attributes["frame_id"]) - length = float(attributes["length"]) - width = float(attributes["width"]) - height = float(attributes["height"]) - velocity = float(attributes["velocity"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - - for i in range(abs(int(height / width))): - wp1 = WaypointXYZVYaw() - wp1.position.x = 0 - wp1.position.y = 0 - wp1.position.z = np.sign(height) * (i + 1) * width - wp1.yaw = 0 - wp1.velocity = 0.1 - - wp1_ = WaypointXYZVYaw() - wp1_.position.x = 0 - wp1_.position.y = 0.5 - wp1_.position.z = np.sign(height) * (i + 1) * width - wp1_.yaw = 0 - wp1_.velocity = velocity - - wp2 = WaypointXYZVYaw() - wp2.position.x = 0 - wp2.position.y = length - wp2.position.z = np.sign(height) * (i + 1) * width - wp2.yaw = 0 - wp2.velocity = 0.1 - - wp2_ = WaypointXYZVYaw() - wp2_.position.x = 0 - wp2_.position.y = length - 0.5 - wp2_.position.z = np.sign(height) * (i + 1) * width - wp2_.yaw = 0 - wp2_.velocity = velocity - - if i % 2 == 0: - traj.waypoints.append(wp1) - wp1_slow = copy.deepcopy(wp1_) - wp1_slow.velocity = 0.1 - traj.waypoints.append(wp1_slow) - traj.waypoints.append(wp1_) - traj.waypoints.append(wp2_) - traj.waypoints.append(wp2) - else: - traj.waypoints.append(wp2) - wp2_slow = copy.deepcopy(wp2_) - wp2_slow.velocity = 0.1 - traj.waypoints.append(wp2_slow) - traj.waypoints.append(wp2_) - traj.waypoints.append(wp1_) - traj.waypoints.append(wp1) - - wp = WaypointXYZVYaw() - wp.position.x = 0 - wp.position.y = 0 - wp.position.z = 0 - wp.yaw = 0 - wp.velocity = 0.5 - traj.waypoints.append(wp) - - return traj - - -def get_circle_waypoints(attributes): # radius, velocity, frame_id): - frame_id = str(attributes["frame_id"]) - radius = float(attributes["radius"]) - velocity = float(attributes["velocity"]) - - traj = TrajectoryXYZVYaw() - traj.header.frame_id = frame_id - traj.header.stamp = rospy.Time.now() - - wp0 = WaypointXYZVYaw() - wp0.position.x = 0 - wp0.position.y = 0 - wp0.position.z = 0 - wp0.yaw = 0 - wp0.velocity = velocity - traj.waypoints.append(wp0) - - wp1 = WaypointXYZVYaw() - wp1.position.x = radius - wp1.position.y = 0 - wp1.position.z = 0 - wp1.yaw = 0 - wp1.velocity = velocity - traj.waypoints.append(wp1) - - for angle in np.arange(0, 2 * np.pi, 10.0 * np.pi / 180.0): - wp = WaypointXYZVYaw() - wp.position.x = radius * np.cos(angle) - wp.position.y = radius * np.sin(angle) - wp.position.z = 0 - wp.yaw = 0 - wp.velocity = velocity - traj.waypoints.append(wp) - - wp_end0 = WaypointXYZVYaw() - wp_end0.position.x = radius - wp_end0.position.y = 0 - wp_end0.position.z = 0 - wp_end0.yaw = 0 - wp_end0.velocity = velocity - traj.waypoints.append(wp_end0) - - wp_end1 = WaypointXYZVYaw() - wp_end1.position.x = 0 - wp_end1.position.y = 0 - wp_end1.position.z = 0 - wp_end1.yaw = 0 - wp_end1.velocity = velocity - traj.waypoints.append(wp_end1) - - return traj - - -def fixed_trajectory_callback(msg): - attributes = {} - - for key_value in msg.attributes: - attributes[key_value.key] = key_value.value - - trajectory_msg = None - - if msg.type == "Figure8": - trajectory_msg = get_figure8_waypoints(attributes) - elif msg.type == "Circle": - trajectory_msg = get_circle_waypoints(attributes) - elif msg.type == "Racetrack": - trajectory_msg = get_racetrack_waypoints(attributes) - elif msg.type == "Line": - trajectory_msg = get_line_waypoints(attributes) - elif msg.type == "Point": - trajectory_msg = get_point_waypoints(attributes) - - if trajectory_msg != None: - trajectory_override_pub.publish(trajectory_msg) - else: - print("No trajectory sent.") - - -if __name__ == "__main__": - rospy.init_node("fixed_trajectory_generator") - - fixed_trajectory_sub = rospy.Subscriber( - "fixed_trajectory", FixedTrajectory, fixed_trajectory_callback - ) - - trajectory_override_pub = rospy.Publisher( - "trajectory_override", TrajectoryXYZVYaw, queue_size=1 - ) - - rospy.spin() diff --git a/scenes/two_drone_RetroNeighborhood.usd b/scenes/two_drone_RetroNeighborhood.usd deleted file mode 100644 index 18bfb335885b9c147afcb192015a8e6015f7a450..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 175503 zcmdSCb+i;$6z+KgBm{yd1b274(%nFC5AJTkArL%-;1+^g0>Og2Ug_?Aakl`0;2PW^ zxZe5BS7+zdWWD!hX3hLFz4+bQr|QT)u2s}&Qm;_M`V}jLBnshg-b{QKr3$MCVeXN(>zt2=Ww?#$1zm!_=oL+^!zEG!!mlBnzyV<99*gJ{;=0{l&$Mpd@2fAUcbbrs zbdx3I6I}mydWXC<7XRmZSEXNBLQMMnZ~dTV|8qYkSU*gfXu3Grn7Hg<6ExB#G5-G7 z|Ictw?HgOLS2hX${`cN}>wnV!$urH*On8>r_yDqM!e@se2cUagbGhU^kWHk`FE7Xk z@`D1PASeV1gRIH$$NY+dVxTxE0YX6-2nP|s#Lf$Rpd=^-N`q9u{JsKZKv_@@lm`_+ zMNkP;230^+Pz_WEHNe-PCa48!gVezM{_CG{W9%7s#xLW}_-n#2VVQ8$f8($5%lKIb z)CKi`CRBZw+z_%;@`X58|V%+z#fpl1wBD8@Ezz4`hdRR-$0VX@V^Tr zud3D`7EMhvzX4z%_#O-bKLAtGRihsv4*^4gYBU`32rv?i0;9ngFcyph|7!FT4C?4- z$P>UsFbSBbP6j5bCd!F``Aq}U!3;1H%mTlFU%_lJ2P6jO_ZyfC=7ITO0ayrr2aCXB zumottmqGqlx#ciuX;=YyC0GSkgEc@M83i=8)sDjehFyHptt-4zLsK0=vN;uovtD`@sQl5F`NR zr+yuRZ1l@yZsMo+O&ksb^Xv%t0~`g%z;W;=H~~(AzrZPQ8k_-V!8vdqTmTorC2$#B z0awA_;2O9N{u}=rxOWrW0=L0`^XU%m-39l+f8E~4y$9eScm)3I_A%}~0snyi=9@`Z z6JK{aK84w&Uov2R&%kr=0=xvTz-#aZyan&Td+-6o0aK7Z0{>0-c(`Zs{&QmoKTUU| zLwr2@Z~nS<(!5OodmjU%pXTo;F#lhbmxQph9d7>X=cl;87x#^Si6EQu@^6Jn0YfVA zfByZCM(k6~i2<-N5PS~?fgiwN5D%E&P|y(|0RBFMpsAAta#D~CBnO{aJ1HQi1gXI1 zz>FMHgGqSa4QNx+6>?(h=1V+J1JZ(YAU((cGJ;GXGgtzy3CV|Od z3YZF}f$3ldm;OB#F0dQy0eitdupb-%2f-n5 z7#snAfTQ3TI1c^J0B!49w!>;k*N92RI6jf#cv$Z~~kJe}Plr zG&lp!f^*=u z+w}Y%@*wa77z};{L%>il3=9V&z(_C(j0R)CSTGL!1jd7(!33b`G!gP7Fd4YhYzoX% zfu@-myr?|Qb$_}`p5c;by5w0d`4^Y`t4p2@S!Z1TO^-Qv_M6MD(N%RZ@l<)POP=SF z=ey(uE_os3yf%G*hy362x(N6FpOo3fu>aq3tL1eGo-GB-z;dtxtOTpTYGBIu8ld^& z&Wp9UuW?-GlGnTB4K8`3OWx#?H@oCWmmCFI+u{FJ+DE(W$3VtE{`?REAP7`Pfvjaa z7V;Lb6>I})XFFug?;ViSf{Y*&$PBUowY$?L?{dkzA!}QteyE#0c&0j-XKugM&R*Qt z^^|>(P5s&r4uFF|?Hz)QfBd=AN1q?YLk;T)u27zhUuzyrL%2TFocpfvajlmTTyIZz%{02M(cP#IJKRY5gS9n=6{ zgPNcgs153Xx}YAY4;p}mpb=;cnt-OD8E6h#fR>;YXbswcwxAto5555%Ku6FCbOv2O zSI`Y~2R*>IpeN`Bz5~5MAJ7-{1O34OFc5qX27w>IVDKXt0)~QNU^o~7MuJgbG#CTM zf^py{FdqC2CV+`x5||98fT>^_m=0!unP3+91^fzTgE`Qfz2QiM1g1!1NWAF(`2tEagKw|J2NCJ|AWFR?60aAig;B)W=NDaOOX+T<#4x|Se zKt_-WWCmG4R*(&32RT4akPGAnc|cx}599|0KtWIl6b3~=QBVvN2PHr#2m|3D0(gKI z_&`Ze3X}$4fij>hCas)HKfYfux^0<}RMP#4q#^+5yB5Htdf zK@-pvGy}~+3(yj@0il3=9V&z(_C(j0R)CSTGL!1jd7(!2~c7Oaha^6fhM` z1Jl6_FcZuIzkpxCY%mA>2Ihi!U_Mv?7J}cwBCr@N0ZYL$upF!aE5RzT8ms|p!8))W zYyca<0(HL2w8h21mdj z;3zl-j)OnJ32+kp1x|s};0!nm&Vlpb0=Nh+fy>|uxC;IT*T8jf1Kb3+z-@2`+y(c* zeeeK01dqUD@C5t=o`PrKId}nHf>+=*cmv*oci=tv0OEidw0#8Pf%qT+_!xWw5(2Yr zk_aRQpMfMGDM$vAgA^boNCiFzUx3u$OOOVn1?fO~kO5=_nLuWc1!M);Kz5J=-4kCaDc!3X;1f@V}@D(Tn%7SvBJg5LF zf=Zw=r~;~jYM?r(0lo$`K`l@l)B$xtJy0Js01ZJS&=@oUO+hoz9JBx}K`YQ2v;l2F zJJ23{13G|?pcCi}x`3{r8|V&tfNw!h&6z;9qK zmHo^}ZP| ztDL}PC!tF&=aNl1Q2XDw?wd5z`(|vTvKeovY{nZZo3f!4SfLO2vYz5oEcCZ8N1iQd)um|h~`+zyLV1D}{9{>lzA#fNR0e^s_ z;21a#{sbq$N$?jq1x|xA;4C-?&Vvi!BDe%DgDc=F_#0dU*TD^N6Wju~!5wfH+ynQ) z1Mm<$0*}EH@DF$jo`L7!1$YTwf!E*-cnjWv_uvDF10k3Ie+1%z_#grJ7<>W}f=@vr zkQjUhl7OTj8AuLNfRrE=_#AuzQiCr+8ju#G1L;8qkP&18nL!qi6=Vb1K@N};r0;R!MpbRJr%7OBr0;mWo zfy$r?s0ylq>YxVr8q@@}Ky6S5)CKiGeb4|j1dTvr&;&FE%|LU|0%#d;2{{i-8QM9> ztw9^m7PJHH!8f1-=mRwAn*ei z41NSdz)&y@3Uw}&ycmPm;kv7bo&}q17_XJtY_5#6Y;Dju9I+`44Oi&3Z_7w3Utj%^_Yfx zDo=OGGhFgampscQ|KgH=b;+|`@*K#8ZF%_(^8cN59s_;Hf^py{@H3bIbe(f9{Fw*l zg9Sk2v=H*|U=dghmVl*T8CVWhfR$hsFzZLFaa{v+{jLk{t%Z3VSPwRUjX=|9lS|(0 zk|SMmluM3w$uTb3?~(&9Ip~rFa!#9Wv5>a_O*^CeR+zVe?O+Gk33h?qU=P>}_JRH2 z05}K^fy3YkFlqJ&u1CQ!a2)&zPJol(FK`N&`k?7!%8yASO^?$st9-^KpM`9OpXPTC z@_BFpTm+YZy1DF@TI5~G_kgDLeaN*D z#|OAR1dqUD@C5t=OuaMp=_zEbd#2u*x@hWME$|G_>fmbXq^W;(K|N3(tOgB$S!1pY zp2O~c*P*pMcfxZ`s~51R@=KTe$|b*c$!4=y?VF8KmEXARymiU%T=ILD`~kA2RUBk< zs`5+bEc}Gr8akTvaHoZdw~41aO-!1av@q!x5ANavji)JJ31I#hd;(P0gf970mz>BY zCw9r7x#T1+IjKud=8}^`&THdR2|AekNP&Br$L=`&H!dcB-T7+r)a*h0H!n?`n*mcM zbbp~G%&mYa11A02fVQ9=aHmN}m`xez3^Ywry7W)wl0SFJUqFTv{!&B!5~Kmz4yT1| z%A@Hw(m_rSOde*yH6zgcG4VHLI}`3@2BvJAd^F|U#NVWeNdpsSlXfk@GGO9l;@ucD z0gZqu6DIykfvE>3y|TbhlV(|Q%?7fA93Usi1vKutA?E>_26`Kz64|sOwpnOAdF*5iZ#SS>1af`+$zE zNbO0Se zC(s#m0bM~i&>i#u--4c?7x)hJ27N$Z&=2$n1HeG=Js1Rj02+Vezse?Tl}$M2+_L!% zhWsNK0)~QNU^o~7MuJgbG#CTMf^py{FdqC2CV+`x5||98fG?0JQ*oUJrh^$^CYS|& z0l$LTU=H{V%mwqne6Rp41iyntU@=$%mV#wqIamQ!f>mHOSOeCAbznW%05*b6U^9pW zQ6L(`06z$TAP^7>wt%f*8`utZfSq6$*bVl8yYa@PU$`6etb80%bs1P!5y_6+lH$2~-AEKvhr; zR0lP{*Pte-1!{vjpf0Ef>VpQLA!q~|gC?LUXa<^t7N8|)1zLkPpe<+z+JkRE2cY%W z=%uo$4=S7Tukv7*Z0fGwH}zI!Q*Tu^>8|o5*L_oW^}b0rJq_OxawpIkbOBvKH_#pQ z0N;Y1pchd0#;(f7y~@TPmCZq0mCXTLmCZq0m9wCMRk?&q4t2@lF1eITF7J{nxMXus zQ~ey_l1I8^bKp|#m;;w8n?saI*qWl9MqGM>KA@Ag9TtA_#G?)i@_4G6f6VF!3wYvtOBdS8n70u1M9&Cun}wmn?WRq0?{A_ z_(1>!fdEa9SjcT`dTfEb6>J0H=v%hqx&!P4yTER+2kZs=z9>f_xx9C;$qALZC3vFp9Y3qAt0Z zOD^t`OSt4vmmKDj!(DQOOZK>AuS@p17uepAC*lysch0qWs`0yoAgup8<*SxvX-lkkUP1ab#}>JTyj^) z>ZTXUP&b(MWwh>)dw_32PtXf|2YQ1(pfBhL`hx*rAov~(0zZJk;76dkx@F^+-Zx>W zY}}}9{8ib6tFrN5WfQ*2Mn{!R_$nLyRW>@SY~rA@iId7EE-ITischn=vPm1Won?MQ zAP)t@z;G}Ej09@e+*8@uRoS>v*|<^J?bi4iUmx^AVE-EWx((IchO%yh8KC^@#;pGR zYbcw;n1K0}1!ED`kGLj2ougDpon2KlSo5wahLrrxf*rK#W%ZevCzmz1@Y8!4AnTf} z-ph!4>W9<6BrbcVym6H!WVgL$Rm**$*}sPVFvK$!@yi0#m#pSSNaC{pcQwcc+y8aj ztb*|)OGssV{Ws9>-5Lya8-}|Lquhq^Zo>q(VUpW01qO|%NhQ_Ex%W}oe|1>rcD2E6 z*yJ`ux(zXIL%?m=;x_DX8+N%3d)$V7Zo@&h;jr6q%x(C~Z8+^VoO2s4xeZs`hHGv^ zDx}cA36k1vNb5Faa2qnY4O!iW9BxBy82+sbrilM*r~<>kf!1@oY2Y?Ab{m?z4K3Y< zHg3asw_ySdTC)A9SDS&Bh5+Os5D*KtfURH~*be^HZ=gH5M!F5#-C^y7;ok_FD)X-) zzuQpDZD<9FE(DFxs>N1?LCp0^~U{0 zIakbFTdsP~=Zhm(@OnhP+-&a8mz(sjf%hfj7wetDYpwN9X>Yjq51MOu<9N*^4I+%Y z_rXKF2BdJPF}DeCMEj8i-|#xfrpH@pR?s}}UhHq)A1Nc5Uh6$SQqPU+p7Z`kvW5N) z3mj!QXQV-K<1RWdhvw$-ben#`6s2_QK9PE_wR~?Zv77d5$PCtxx)GUZ{#qu}+%$AE z&5Ps+!+$Ns3K@SsNYi}g8Y<6dFL72U{6dn7`93ndHr*YPFxLN6GKBY^$UfGiXa1_x z|EMirnh#gxcjoJt-hzCt{`?WukN&-v;ss2&&t+6$bL|@4fcGm0UoahtNMeR_#rrMe z|7TcVKG%F$D5n{ZTmE|V|Ic7yx?5!HX|m8Qw4cSBi_f)uor>yX!*9ay3wqP@`B{HU zUNZ-B^BNNCTWs_??j6GL&r2HS-;rPh!+GGTMSIl>y{3PYJ=1BP8yvysWh0|`zq@BO z?+=#=EYES0dxh~gBsLk_#rU#`^kig$mg_&A+gJ|8h<}X%a!J;>98_#Iqkg+ z>&~m{S2Aic%^|VJnckHmveNvkBxZYbRYp+%p5Dt0_k$#4dF|^9QlE0sEopy-Hym7SuK-#h%MaRUa*%$nT?#p`<(q22s&-9Cwdh{oY zRAatqI4NZ))32HDBK3GJ+1Zb1`W2BReEwdht}@~0Tjnlus`i41X|HjL_UtR*#Yn-&F`#v`R%J}dhFN6~(=a!jk@8A~dH7gM0 z{S6!L(tVC#Hkxlr7N*lb(whBIF3%b2kuEfr_O^Pb(cT%Uw8{9_K{7C0ZSOVwy)xZt z_oO%V`K$PGy4U_=zjSB2aVD6H`n-`1>~{(mcu#v*0#5z@)K`w-)%V?^y(==0`F<$; zE82^(?eq9ef6?sOe2CX19;g2;V*7(7z5#T5zh?>K8{v1# z#mGWVJNZLICsK&@_GJZH+VfH9_GgaJFa^v_{dgQd_>PW!3Kis#1`gil~<+Y=2H(H>sUuXV<^ zFM}6Ze~-(bEYGWKJ5X3su%4a@bNYozQjz6&esnduKjACHZ~{_@@qFz6n&Drv{@#|G zY)85V_tRd9h+K51^`~j^(=^}ocA|dTpUv=3rayV40K@N6>>BM&m9Qw2&MDS9<28>r z1?_1)>|6X4?Y)>Vd&fzcbv0-VO9WXxoYH!5X~ZuIK~W50A;oYbG1-_I6xY&cB!b z>-a3Y=N!%Fg4yW4Rp6nMuD)6{f8?u1^ADRGJ+cLJ(yaaOAn#u^YyUYh{A-4LPBJpx ziv?5i`Ky@63@6s#hu5jTY4rbvw-KK&u=TNlbZ5JBR35NAPL!{iKXU{hGDJE}3r?ZC z+}^D8=ckC|3@^U7l;dyIFq%utQP$&n;Z13NR$@D^adM3Pv5sd?OLOYEK(4Y}wGN)5 z|3S&Y{Ld9O-ErqHOaDV+f0=3Y81I=y^ZAHZyw;4!OncX)1Iuq>Um3P_x8)4yDb*vRXzyTAr@TLvFxLCj(u?J3Z&-gm zFDR*5?!zPfjy{`?@v80EZMn|!yW5WU#}#+lS1ms~?fCUs@GkvX8Cb!1_~Zi9bC0hg z)2E6oV?1tbyh#6bTsB3*nNQw;Q;x%IJKaW#(|rqn6w@oYjHBMAcOYGru9k)O5#iRbs zqsH_8reHgo%gI*8r;# z?ZQb}$nq6mq8ML{BbcsJ{nO}QGXD);Cq%BMJ~t&f(_xFJH}8kUzGFMA?PY6;pq~9@ zKg-WQ(vki7`Ct}?yF1$H2k-mh(|k~>vpw$+x{?0Rkj%`Vy)ujGG(WJ3`K#lZI62Sx zeVf1o-tQ=1GXD94>1e($U08m$MTF453-X%!#!1rUre0Ky$;$f)HvhqE7CV3aHo88| zb0b&s`ZkXy&WT zBfgf2)O%@k6^3`vJBIpS^E70-9`k?0>joR{j=*F-&r;$D?dv=-LhjHX?LT)*G}G*Gy868_p~&kl~RLwnlqekYfy zzs~!$U)OnBv}XY0ukrmnrV!mPv+dArxzG0RD?2VaY{!Q>zpLeY!1(Ao!jzb#bg%P4 zoyWYBjjK)hC~y7g5Z#dWY6adi9=e{P{m@NG%=rJ0dg!c2Xut76LOI_Fmj^5#2|afi zkIvqk^v@SaPP2|TZ~E)g+|{#&SDnW!-*kd{=sJt8zZ{lgEN6@4Aj^r4t5she*R}{e zW_Za9IsL}y68q?1;|eFsZG$sE z)p76Z;Axh}H{QCm7i;^cA0krG-^{_hygx$5Mj7|3ech<={#u%|T%HOHq`gBy zXMONVpgGMIWh3={7QD@L(0&%{Z%pTq*y)*!zh|Ws#~nZU=F$IP*g*QPjLrJnEA_%9%H1u~yYD0yuOB1<=hZqd)^hkxlB_X$ z>3m4%%U>5iLw{!rKGloo>4MJuTIVMtBG>YHe>=V&6kV6*vwXP^S$#vr(d0H z*HaE|cE)RaedU<$pU5hvclJOI#;1O0B>kx?1DFnbOYEY#j2xgjBsMqK3Flh>+DD}0 z^9!Elbl*2}JuDL9LI|8Cc_?@Ey6>YXHFI$o7=bazVnFdYhcPEfB;!+vEruVgOQJ@VUd z)7tf_2N6$c?=#<5)K|jG)BX|f2%1;PZ07&E=t{g_w5YS5`>Ssp^;zrd!fO*dFK!yV zOmldIGml9Y^wFP9(vIchn0F}6Uq@u2fA@R|X#Xc^$M`?@HsSN85gGWrZP-t|zLUZ% zPc5Yk^W%ZkVE^(qat@y-mf6hDw!sthPuHPlN_zTx$=i$m>Nvv}NXB@Vl9TlBK;$C& zqvccAHIB(GwksaFNqcYo73i)^M0VOQy7@4#7v((roj|Y=!@nYPnICt&-!R+?cKz#T zyMHpp&L3j}v-!NFoC!DOJ!fc;{^_`4h@A&&K8}$-tQV2KRt%?}&PVOMY;RyZ{nPPC zO}oCn-H!WK6mZr%^uDhDW4)RAqw|fY;m$h4xAKtTec>xXf4#+=avQ(+1?qXo&f^EI zaK?of7pD| z@#~1_+O((ZcYjE7w(HyF8Lyq~_<4&Rx1RGj>&Mz|{}{QB?lBJL{IZ$fnMXYKIO_*G zPPiqnSl_fgYTHtj8`0{>c2f9B|6rJ2}dBX@^a(O8(s}M{9gt zX|Gn1r*yw7Fp=rJq3B(jw|S?~JlM8(@1+>WLzhLE&brUn-m{VZb?~g`wOhEePJdZ8 z(OyVw!R)4d6|(L1Khlo<{08aC`rRyeiF$nIzeV?FqypQKDZUxJztOvZdNj22@;SlL zykAH@k1+nmNkz^-=Gpa_)WPDk9}?Sw>&)nPSPl{fy!3xj#HWnk30co@qNNh`_$uJ^ ze=|MKx=Tp0TeNpx(y|^VEaA*gt_M>v{7Z6VqY3}C&smS_9g&*$cSa51^_xg%{?yoa zmG%!ryl41hJhORyBzf45=sLqynM(iW$!*q$Zt{-h^>yA4^zX0~X1UUF`Ao?WX2MVP ztJ80$DRz_guF5R>^Gx2eeQzJQ%k$}=nhs`7TSsy;gN{(ZP%g+q|gS6&&?To(_{n!25(K3L~6M1g){^;;p^tX1{1YR3% zbk?)p$~^WX|M;uZUNz4SUQ_ry)cd{UWVwq7CZ>6DU@fm$7i0dHv;A5le}L}dg1f0_ zF}r>|BJc<8>pqU|ckZ_Hg?6@I)A{a7S;+FB>nOM74)f`~IQv1_qyob|7tGFlZDIF! z+Dc)TvmTyR)T5N0H|RX0f$uu)>wbpL|8<_E^Nkn5zv+KhyRPwZpd|fEWcMMl&&P1S z@D_IBYuEGd+kMHGa*FwQNWx2)@}c_;`(zOFGo7?$`Xux_^N$D8f$hsE8N%|m+CP;3 zHj!rG#(h4?MtyQ@I>&sg>~Y!;9iMuG37Niq1Lt_%B(0f#ujD7{F<6$e92A#0>ODSm z4gJY0dFZdUrv-y)=wA0TXWH@c4R06Te<^9W5BRlB7u`qR7MRNCucaBo({-@AYn^?! zLh=RUdtN?aeGiHCb6;(7sI#Ab*I$S6O(@H#&l1^A{j+a?% zOs_oNEPQ@cp0J&0Ddm}Nll{|q|7xHI_4^=6IUda#HiPlsBg^RD2YJT!>w6ook0h4* zF7uD1d!!rv3yICf{jXXv&bpzluZ@gJLH~-`ed~dCT)H*JS#P-{``I4MxAQ06Uq3FV zm>w@|zx-atQa|ly#5-<>I#kM7R~b1*zzU+*i& zSYP(aOzN-uL%I&E`>`Q{9EQIqB#PzkmR*9v7UDPU(X-Q^woJ$!J?1oPRDnh zBo+N#=IcZEW22q^Xm_v@&AOhlF4&poeKLgUe?gv8&wDa~<-4pej?brvhv~XaUeliT z2ZilCWq{o$dny?@-sxn=gUgFup3HhjL+KZ^137k*B&&hz%l zIELr-JL}aS?D|YADb4z$?c5jAm;Sy9p5V2gZ4U?dqN)E~yYF|`+n)J&Q_?Y>TObYh*L7drztM82`|WyuK=(KGyn>!D(DfT#=h5+JYja(3R#WziWkU(mexu$pom&LY z^SPFvC|^sOYuWW7T|ey@Ji_~jB^TZ6K5}ilpQ!6=b)uYcww~*_YUhVKzN#kk7_PRL zet&=JH6UzICX+pK{Uam7Fvg>Bg>^dsuchvV&`JLAr62W?u z)z-g}zGaNJ?tf2@NJ9VC1v~Nn2U*N?j5p6&-}oSfI6u+-o`pf@yy07!Nd50iFV+{W z$MfvI@vrh3+ovV6mHCGLg7xK)l;rs0`39$5(0!L*0s+SFwUp*KxR0Eo`^*vfsoy@k zj$dDT(I2cgFrU}Tm{3!{D%<_!2hxW6=y{h{GNq7t{?gl!{#UX4JI#F;7~h_9pY?NR zuqw^@BLfVtv@M7Aq&LGGVAuOMg)Zase3FCdds^Bv|A)&Y`qO#+KYYH!p7)9M^kIHh z40qb)JF=bnZT7WccwGb6sn-Xo!E|30SVnV%JxABuRnDrQ#$%*H4Stc~>G|S^D!j!Z|-w)a#rFDUg{&Uu=h{+@iE+OAvIi*8E)FGqdH>)q%G z$1K}fAJqR{cD+53-4`8Y_nUgy^;A9o-(GUD91OAh<`1Rp22-wP%SSAyx;_>srI{`n zeFc~vsOM{py$+I|?(arA`)KX#yx_`aXP;=a3}pFv>}^SRIqbecjGbS;kn(Kj8rgNh zYsH=OLa~yT^{ac>SjI0l;JlA8$*zMev*#)v*?qp_F>jepW$d}sj*^!7vq%oG9%Ywu zOxGUr5B1q9pYnd^zzynE-S-d6%@aAw^DG1Gx`(dQl(XyFckOR}+B?+QzpG=7nh{HlK6eMAs=! z+H=n$Sy-<0TwJH%VWvYD+g@#yPJF&feqs60{lYgA&GKF~kZfdnm$c*3=fPWyr`DH6_Whhtc~1Z8$Piw2 zANRdf6ep9SyGf4tAd^m{1P*q&qvI_<_3 zd(NzA*i`yA!mgX|FLsIMl0N7B!4$iGdBVQe6(@Pv{`9ivxE{+xu7ezt%j~CC*z@M0 z_T1qs`H|)GxZS5(74r%GZz7FZ?)J(=>fgq$Kk2!@OLB_inm2Np`JLQbg7MY%b3lG) z|6+*UZ_6Mp7~k7LCmn9dOZJ2N?f%TCvWU;0%Sw)G9!MuXe;AC5F!gO^=yK|{AjTP= z4)HHwcv(EoI%G)f*v!V>c^mFNPd7eqV{LvNYUiWMJMUAHUnOtGJs{Mej`$Yxj zvYmP@t(iWrr548#_o8~z-E7|&=HnJS9;|H7F--EzV7Tw4FxMeHe~Z{>8~Y*8ize zjAq@RU*!9q{{0>9rGHmtGW)^HzI41F8u)_YeiE$6aP-_&U!SwCThaE@m+iiKDf=Ga zQ>n^+AS8Bu4wL>ZZF@T3HIW|$6wn%EcH11F7M?e=NpGSof%Kv7t(!19e)+F?{7SktZXN?2Aua|B5l2G z?>kQYc8j0-jtCr~J{RRI(`TssNg9mAUsYJ7!m9XRQruMvrj_*^*Xx7(v z63uk49dypW{vGYqt10%pa2Gp%TwvE%CqxZrd~d`&XL$8I&bs+)Da3Z=pWqX=e@Epp z+i4wdX#X;M(@DC|Ak7&5HBTe@b4UJU{4Yhkq*(&a{?RDAKef@$SH{|Pi6^p`^;OgB zo*k#{kiVHuf67jV|5nPeU0)ygo#_^9-^=|+X3~9jUk=`H?tQ{5UaaPNQBVI$>Y?lR zIv!0CxrO?twEN}#?7n4d|7P0P{j|El+sudG?0Ws0jn29~&fzj&u`grl;=L<2*gvi#R!++mzESlAQjCzc0g&wC`zZ`mFX0<^9?+oaOth z?RUQmZliuDWjfoD2)W1S_oWB(A-6prbXI(PuH|%nq%&`nV12p|iCw_`P_1u^0!}RUE%sa`#>2d??}uavIOj(b$Oh^e^fjP9MSZCl zPLbkgsn1N`1m53h=Xbg;Fm&@iKA&vIF9StbAK%Ly*8i7snf>n3Uz-P-GS<`26<7gMjV z?K)y&J8u~0civk_A~P7@l`=QdgtI;-0qu|UI_=BM;!Zt%BZ;WL?t@kgd_w(xx982r z$ahi3eMoFSj$3}P=`qc&$Gni<90x7;jG#NbZ@~Q5b4$A3SUQk|&-MKDjNnA3%UkKn z`rB5Du-$!U(Z9oOR}*!PWE!@3YZfrNGB@mwxjR#SZ`$v%fm&v=+ujdf9S4_ zEq8O}A?wdEIY)oeO2-JJ@1!uNy^d$!f7>s;*}qk^>xOZuo%*s}?(=>**}`_WyeYRy&0*`WnWsR&)~obx?dWTknT?T^76i(tJZU% z>+C#J=kY1L#pzFe&tJUic{Dx8^_x6rJhdF^d(xip)(j^kb|~AUxMCM*t{OIx*XlBh z@kqSh8OL;#)J)&E-a6E?g;b*Xyd-D5^nH09r>qG&=iTCD6wf^!m!q_IQ&O@#&xo$U zaCXQo_CM_yN&deo1!Izt>WL^-j+Rc!Qr(&(n4t zWv^Y&x-LGJhvYWhs(N-Z-B!r&Ebn@bbEWNn>V`LCxbMTA^|3E)J*W|ph4-7sWZ<=$ z-|?rdeZOz8XCeJP5iG=fjFt-YU-xZ3_T1z1V|IMqB=C&-h6hsd{wq1m@xe)%$@1CI zca8pN{YYllby7wYvguNa=`uv-us#g&9;bhELs#-S>It9Um!a$*uE-juTS_}`z3%Nw z`*Uo2q3fmBq#^D7X4ez$N`UT9`U+5=SGL?dkS4reMV7GKypfx1hc?)8$b+J{sYjg% zr@xA4=k?j8G~3m%uqk}5=S&jYdGrHmMt_F|ob{s*@;%pUc3OS(9L>w%W%@Hm-m$z7 z@WoKS_p*ikimvO=wfhgzzUF-XgKs0RlkNCEB*w|-_cAxXsjsi>di8O8ZfCgt?nX|D zV0drr`}40P$ov}Xb=twmsP7q{2Aj_CT5pllZrt{EWI9I&o$zycop}+?zp|WbJKfv2 zm3kGim?0XD%WbX!}cR4#Bit@FfJso$K55A-MxEx`*>g~Nq zee^xx4bp?fOq&-z@j8q`ee&KeelGKmCc5CmdIKY(E+&lQSC&W7GGHM#Q9KxJe_N{gfh} z+V&&O?Yi7h&wM_g6#X^b$4N%clkdnerqgb_{!z=bmG<;~%}2qv%#TEV=RD;>sl|4x zofKgC*7Ls!?DryuhmEBF8$5&Q&sh1E^=-8D@B>OY^VtDccF% zU)Asb==^e)e9q^GeIDj>jzD(COUDCWdY$#k@9q5dhJ6n{PWI+8<*$)^!}h$FX9eAj zwCn4AqQ)@%6A{jOw0;-hsHX$%^^oUGulI6?_4cYvV0*3W7~SMO^{NnjL%sf8FY*4( zbg7ohsb{BTAj|jD;C0>!CCB6%_0xT`EOviG*F{g* z_l}o^4W@oOJuJA8GU}`6 zu1eW`_=8e|6Y-+_1`)i^FqV$Uy^x9!Vv-*?Q1Ox`>U=Wn|&{(X2|>fK3_ zvz$iz2k?1&`~Ll4-+H>!^&LI`sq3iv9jSS~;j}l@w*QYL1^a``fu4+?H!_CdJeCla z@6KLlzv4G<6rT^V?^mV|w||gTOiw*8_*_OZJzvU6j$392$13+ShBh90wFZF*dp{x%d2P@INzJHoFScK*`vWI$2 zmEyF&N9Hpfbf59CP;e@C10 z9_mX*ci1;(`rPm|U_NXAdR;28{aE8&LVIU|&i-fffU|z_EUX9PnZce{&~rqar3uSH zqZsGh!5nWi-J>2cUe)aT{yNY7!tO8NJtFEm+B1iG3<)^nuwL>v-JO#R#f{!L&rE&0 z+4=XE_C1Ohk-t%&Ph|Sym{0NE7KF9d;I(U}$@`bmfJKaCqE-#tR z-xYS&@rJB^$LE)W&bn_%Y{vP<{pWTaHJx2Y(f1uH+V(YBz**m47G8z!&-+_2Uiw~A zO51MvB69G#uFHRr1{|l=wR#7m2J-n!d+tcrRS(+zjWK@bJ&m1ma`?z5h@^M|j3A+$G4rqZ7+l7xEf@KvXNZvu7sJgKh~ zuUGB5rmknE^cG`0<3(;`IQQ)N{=Ig8exL0(;{~hIy^eq4#K&>tRl84L%ln?sli2y@ zdg)C)`q}b>|Ez-Z)VaP9)T@F0ZUNS{srPcfvtFX-YiHVXfsO6?sCssN@tovh{nYP9 zyp<_zukzaSv$~FneNdLSUfxU8E5etU*Kg$s%SAo=U8McKGSp|UOl5srXwSh!N^QEw z_cmz1yge^5)_wpHvcIV5x)%f$e@&NaZUi`2F64eI(rb@`R; zc}3aG{%DprNImMvkG%g{`m*22DPgQn`h6SShrhAGnP2LDiq7-a*!@GD-+vP|j{5Ae z?^TbB8bR|#e>0Zjp0@vfVb8M+w)N+|yySfFs-4G{l|9r;&kwh^>smd7J6Ili+i?f> zJ(&N8qypPDotNtOsfOD5j=nE`M(VSC>Uo8Z_8env8OHEB+V3LZd=1UI?)_4pF@5y? zdi@?qW~s&WN@vGEx-a-j=F|Rsxz2KW$(Mn8$JqCfpV)aq?m$+i%g26ay<)A5U^&ur zqa}h)|J%c!BTO$X8D8Um*8z93ALwe|m&UmjhWA?PF#JE4JMB|)`+dL}!AaDki+?S{ zeIcRTr^WXXSpLSzH!S!1Ug;BAz;^z!{eI&x`+dX$fedu7-zj_{`8eJxyVz;J^*!*x zvW)(P#O`M~?r6u=I)2P)zr&{I?eKj|>M_Qi>)sS_-j{qTWs8`4@T(oiU6Tgv7cK;P zJN3za7xiap$nZ`}6Xx@2X~^-wV|l`OJeEYP|Bb?%vRn@L%w;_E{pg0$CESFw*4LTo zl-cWiA5r_=vUXhFJG>s3_r8fW;t8xao*c_E3Md$AM%c(eSHtJh25vp_AyPM zAmeq}?vv^{sra7zysz&`tO_irKl(k*Gj{)8zxSozoe7C;%=6GKr7Y{?U*V;ke6!z! zeQfuKbzS0-ecyP3-JjKUJw0co@8R~@bc+7GlbPIa%xBkkb=|*>XA|}PQ?{@it(K{* zSLHnWc)z2hqds-*x%3ns=N!CVH`?H72yDZug_&s&=5QBV5Qou0$N z_nD}73OoK9VfS&W2SR9nk1S<*Ya&g;jsH8m&i99Q1gkM#+77?)SEl{(G0CX+PFqgi zM?B>Hl6HPNL29y`>wElOpYtB4?vuny8pa>L zZz!FZ4tjn`+h2X(p4TSQl=fdqEZcdV_vrrJ9`DbrUl~G$>4sAZ)I;}y z?#VpHV^erVKG*NvhQwCp`|WS!G0W|0nZk6N>X}CO1?;#mowQ^7(BAgvsxfNEViZ^TjSQob!^B?cCfzB=xH#>lqJyU#+hlN5@HCt|RXAbY-{?qr>Tbs$I`7 zW6wht3UAB%qvS{CgP!}|=PS!}>Le+nP5DY78`+NLSm(^U^&IJPyZ&>?t_LNv^N1C) zgz^3(bP@g6?}1&HIxP3A?Dt*8?&Fs5C1-qef8Z|}!+744NgGV~ahv|2KOY6YVtn*m zQ8K$ue_wji-VC49KfjmmY?t(X>66|c=)ay59pwL={(Kectk2xFs7v7xrYlKGeT0&kk-S5e0mV>d9@+(yJ5bSOxMD}FX(UX z$RPc@>S;`U;v~rRX?+g{=TVvNY3z4a_4_0fv_8uz){`f4hW+z#Us3x1PIfT+8IwPrbCE*UpRrCA5;)O)7w|{ zA=B%Q>|lPMw&#N4+xKU5UrN7^_Ex@QJ$xt0c-8NawzS_7)Oqkz$;b55@5t*u)-ajO zd|eXkPd)XVmcEDD&7OnnZr8E(ec3E_UbrdPmhNiU`NYKFFEnF6i21rQ;uFT_X~Yx8 zd$jiu)1_Isvu}M&F0lW6CZAG2J-_x`rm|htebrue{94eiBj|iEPFit)v!j1K{U0Zt z86UJ8%-<;gK;FL)%tXC*%PN+qP4?W0o@cCV(_P=+((ms~lLAh82n{eEX+4+epPq}3 z_Bj4uk<}b;j<)-xM`Pa6p3bA1dY>}hGlR~#jMa8tw8oxyX=A?+q3@aQwEbKQ`41U=)ZoqbX#;eri<XPl(p zkHwORYeXpTfVdKtgzXO`Y8%F!u zuRpQxvAmP)Ouy28=iEt6nZSHVVf#tl*W4vrS+6{Do$0W_o;%X-8tZrRC)#tmN4>+T zZ;bt}bfnig_j^J%QQrg7j`{yV>Tw?m?>+MWJJ9!A^gC*;?E39I`~Bx0L1$gBj(v}` zf$s*>Tlbv?*>jKh-T?J&X4m2L`!%|5ru!v&F0p}q4{^R-UrMpYS#crINYAIQ zwBL2ma~v6^A?u%>KRqCA82$l&7p8j!&mLY^+wUFfdhpZWL%RFIj{9%RBd1@m{Ze5` z&hnVUelO~P{r?2?y`MGKKV7Hn<#W!_Etb8kpV#g8K6MEZ6(&c`wy3%=N8zx2k$d~2l^M&{Ugc6^wIYS;@N&y=hr$v*8SyHcHK_@ z|CEVRmHO?Cbk3vwV)w~kOUboH4?Ty}Da={N`p))`)1)BVwHcC)?oasJQ6F75)9+*s z3p(SY|AVftjH|MF{x-0?6(lXNFcA;~WY$JS#cu2tJ)v}WgMeLdE<~j3&~Q<=-C`GF zch|FL=J5ag-aPjkzsx;5yE{8OJG(o3ordp`T~(%F{~GRff27_;y>C^&BVf52DCdvT z0_S-{T!TW=5)UIg;ax z{H@e}so_4o;d|4zxj)c;BGu=lQEx8CqwZH>Ii zD2K-dSnjZ?AJ%(ADaUbac-Qh>y|2zQr99V$^S_37Sq=AC%as<`j)wb&Ec3&V|Nm%f|S@ZP*${k?+j z>ie>j>ipD+>T?TQr31+0V)vTu&Ol*Kkq! z4)w83eV+Twygl|SQ5lK$P^fNa!#mhNxi(l|rgA3Q<3jcKSsT8y^-cK~=bwINB(~?V z`uymvawzUk8s>FF9?@3iC!B}Z)xUrA*=!NY=ieR0`oAhSV!Y$5&VT&R+#K6inM3ba z8sevhb~oIYH=OHenh!yFEloCJdqygMqCUo(P@c?fG`vIAX!yM-^?T`FS!+>V zmXe`9$17{FpAGNmu9}knJF3oqYxs_h>6pG)u3G)QX>av+J{$aD!}ksTDHAY{WoGVQ z>_@}*BmRuIh~>-G_XqKL^nII`YPzw`$F#rhh4N9ecm9s1$Nxm!?vLpvMp7cMHl;wu1GiNw{-Id#L9s8%;hy87cYZ~%M`FR4$X~-XKl;08a{U@vAmWJ<(@i+nF04@jp zal^QVo&AXI@1dUWxBHQw_EYECzRmlKmLCKM*^HzBkZSy}y^J-+xV2=l{GkZ;pBhGb=)UHpD~x z{0jB-N12ZC-)!~0z%2FmDE=xf(C;^VAGTp%m8Xu^Zz-pve|)6$L;YPihF{ zdG!9emHPd3XdZokvC3ou>MJ%U5cSZouWHEi{i`&@d#C{Q?;AAy-bBY-$^&lbS3|s3 zl1KNr%hcbYZg@Xhs~n7W@_pEItnZ%sUTbc84gTHmeOnE4hI+AA>f`)MQEtO=;eG_y z^#tV^{Ck}Goac+u3H{m*b)Hwld;W&sRcnaP4VC?H-2bTaTrMcv;kwdMwV%z-TZH{;$S-I(SNW^VM!Tz5 zKEpV(rTYB3R^9He{AJ{H2lYZ@z7%Q9*5EV-+~63>R;>p7?VbgTpND$y-|V2 z=pv(LqyO)3;#K|shTla@YL^Wz<;G&!>L-eT2U)Q4jESf>w4?CiZ#q<`jTD!*YAP&m znE`=X#^RNbdy2<%4#C5jC&g{PTZDz*kHAZv6XK8VtA)JbM9R@fLF37&mVh_j}w7N*-pLK-_EzS^@!Fo|@9s~6)%|9Ni0?9-lbZqEsEXScON zSiD@Vc1+!NlGM~GVEG8J9h`hj;ygm@@8RpDIh3GrXU z#97Ou6rH#FLeZ=+G2^bE;*Q)GET2b-lb+Wq<{$KdUt)xqF)LHC^t2CrO`0sW9=b#b zYU~ZNgOf$8XN!eTgY)1;lW1|&rMrqjp*e7USd1t;(OCE_&w|;V;zY^F&O+Jd4(#E# z^P+yDt>T4Ydp0KTyclLQO>yXGTQ>9DIWcUBks_mIJGQ<4qF5Fhpg8%xJsUgbvZy$9 zT;Y(~ma)}W#I=*M72@D-OuIN%yt%G}@U}@;c46BAQ8GbCsCVkZY&IMc$0r#JZ^ukx zS*MSP_8(FO?OB%W`qblMynVb75^u>~O*k&vhsFyQnG0B4?iaCJakXGOdjb0s_C=i1 zsakk3Vj)Y>`YAT} zjzzxsC+eqv6`Bv5&wLI4i3?VI5-#1C&#YYki5nh&7Tik~u-%h?iz80g35T}ZvEFZf zicQlW3fC0#nZuQz;>vLkg#-ZaL#-2Aq9yme0@L+NMj z9dld!30lI#;epmY&F+h1wXB6k^A1|ujJqc;+B#O~{wBn_X2t_i=ip2s+A9hUAL}ow zEPd6-2pE)NBp%N{qc|ysL!qRv_|@7)(ap#e{+13$o@vFQaCM%c=w5bA(f6toBrGsM z`nwhGFxhwmVwZwc7^l=lY^aQaiu8WskWhbx-32db*JBLQAG8XGsjW@K<;&X%-IAi< z^_-F7{bh}Xb|=Chd~RQH&MilU*ZNS%UNul$ekSlx_oph-dPRdySe{|Nue+zaGEb0qv( zH&h&NcT*uxh=9lDL&T4N&M8{HiGqT6BgNs}HH5klHyER}4dv%{tcHMZlMpMiL!je~ zVdBm9^$KZPAmpyl69;u4qxf_;6r#`e7pIMnPy}7`0@tf6k>Bq}3UoW&2k~MfKd906 zK^*?N2I8HUBknud7rq{xk9fYDUcOtSNWT!S6RKXIQcT;EOg?y{+ZoQa-DUwg_oVYfF0ruu0kef=w6*kWyrSbnAu0uxC7%_*K>m9iD-9ez4P z%dV>t2Ym4Wn~sFHuH|DFJV2cCE=~~}=>=OpN|DE+jXzxIIS;XEnFq{!x*M^6oQSw*N)A|eBikrARtRNTGzVi0Y9O?V^zVMt1-5G~Mt<+yFz7I77-IJ?ZZQ08 zU&NEMydmgMU$ONRPld&JZ@8O4I+?u17mm;HMxN`F%VDe35pmW-Px#bqG~)Z|CR|{dRWDAzv z?G*-AdNg*sANxU3xW1S_afU*;8w^R#hT`>6Cls$57sCx5@`sO2J)lC{7t40o5&|1u z_ZEk)`kav7*%PYT4?w!(Js0R5MssKNQ$KLOO8((PRWPImlkYV;?*X?5Q5&MIqTp(b zK9=3+;||R|$zL5m6%2vFgOL7cS~1-EMfN{6vjn1s()_B3iU7BJG`WV%*>r+b6v5evlYay+2bOB#!Ad0y~KPIA0H`oQ{T zkUfK61WcSfP`v#iP0`CJ8$6B39>(1Bhm`}( zk^jw#ATTW$kN5>2Uw1yf;fA@2faF5(&!P3*dwMt@_X)^zJ*E=AE+^mqJ>(8&R`ok9r4=%CGfBbwe9Ta0FZUFM*8mwzF;5WiTIUK36$ECZS2o?hXZq{ zUn|EIL9c(LpKEau@OLiRN$WMvaO<=YmhHgfoM;~BsBEUrI2Ep*pt0*@6$qBkh+lfk z2gXb%IhWdmLdsh$ao5_*364(TU^bTOU19A9moC$M*}2XcdXJT(%r|d>pjCldpW_N3 zw4UVL9Z&>E=a4-dSGt06FPaOMoBx9;lRd;s^4=4SCBdNVr6<0#8lm7@LU^z67Bvnx zP3)273qkA2w>WEhf$w%|!?17o>-akRJ&R&3&3hiOQytGd8pZi5X#T#^iGy7w-YEZZkQa1aM*M>v z+~Hye($6Nob|mq&W8bcrgdLW?(7BjwZ13JIc-q-R+`jRfAZ+u4nNB)l_0?{Q6ww<3 z2hTv6eGl%3GzrQ7732dyZj%4M-J<|9=aEk{tndY)b`J6{kFJEo!x~vc#Y=WvhAJ_*TWX+f67W>Q#J8NpG$(yO+3XM-(Nzl zK?z81Qyg`EbrHOcCA*sbyc`nM@!r>Cez5!w>GNbpFr=R(d%M~q7PbJ*$MJo`A^$A( zH{qE#9Q;5&Fx0vTE^Q*+PUe2kn)^MK4%f8I1&jBj&tqRbq1wp~={?)$L0JfmwPsQ= zEcc`_t&xXUki(bu|D+*3i7} zznZUuhe@{v=klSx55=Fu>I=YjAH~)ClTyH4lYGL|qGC8QfX40vlz`TMD^R9|V<~8K z+)ee~3W9UlX);x7no+!9I-RZgTaX;b4RZncszvG-_`TIp|39SOlg!4 zOMX(Dw@15z+d-NO11y!$`V7teKXK*Ia@%68x5_C1mO7CSNm>^Ii(e4WH6Ay5^0-ky zc#PuWgbEn-g<_AgkvwL&y9vwcN7n!(%tkz+bRRs}MmqFa5&$cwQ@uNcDk$GTV{x-K z4Vqk|HAU}dAPnnCbJ>1T38dMrMmg_~_<(qb#`3+$Rh zvB68j5||fCdx}AP{Tf(Ic2%6@1X~KJZJw_yAo?Qp_wa6i7^O-6wwCWVoALdo%9gTb zr$e`UnuuS#@B$B0vYAb1l+bJvjm5pTWw7$23-XLx<^eqery&lu-w$@W2IA0<^A%oe z{Gt5@eR0~Xsfxioeh%jGbJr)06o;ml!W|P+<66J8}1fO|Juv!=)R!&bp}cqr@)sP)2mg!YH{wdt zfS))aUGsGYe7;OJ^E03TDuT#|jGj^sjy))LIy1Ex4s0TO&iq{jEq8CnvcGl9Atuui z@yRj8P&AlqV7z7k+_xe-Ik&AGdfg(rjkFY+zFC9(hwuA9@ob8>TRK$02}23elTHOf z|EAQot^CZvgr7O6Y{S;f53VYyJD!Xir@@mOjnMP7I)Y+OdR9l2D5x|igWyX#iL z@%KBiY!@RpSa_23nc6WD+ASL(YM8|;RxGN7Chy2!HJP6e=NzUZ|I!6#AxFzyywv}b z5VOe(P83jkdUBmt>5={Djwps*Z)hx@E~tPe$7n8;x>rEEUsP{uuTY4)GYMsWT%HRu zH`4#Ni{DF^C1kiQx+GY9Staz_5;i^@Rv zJK29_n<~%_*?{!xqddWND2;`cLn`#$;VO==dL^7W#mDz2jm4OZAb4U(HnyDaG0*Zn zrb@TpTUSEYfi#ci{q%y>Bj+Lg{JnDMSVX?mE2k88gl$6leO3)(NmJ18d(mcAz&!Fu18I-C$QAz2* zHv5R>)0!m?JQe_T8Z__nM`y$AT3V-?C%QvRD{B9JRt@rH49j+VQVB&i6oeF?ISgzwgb8`s9d!ag(>wqsl% z@&c_9FOyTC&u@~iljH`UJp8Z?$!5M#^Kv)h+x`CohuijupWID@ybI*tI_%2;^Vt;Z z{wd6b>$-qEtujg=;u`te`fim_TJ4Q=%L{=}a-96Y&PDFf?7cS9ovjO@v4rN%tp)zD z{sQ@ydwa@3)`NU_@CjEKqD6K!>}Lfmb(n)?H#X0QDSOF2yFJK*_l;tSTH18J z5!%li92dAFe|t#Tw|mE}768=liJw>>f}X24;G2J@-cWsc~+w<&YlYRULewWn1z^clFC4V;~SR9-tQIxw+xA2Yl1&~oH!ZV>^UP4e*WEwc)-v==;BV}JE&bOyqr(= zc1Em*)2`Gu`vo5GpBat&i`Y_V6H0z5=U^#Z{YCbia+9AiE+-$jho2!Rvb0eC<@8Dj zen4&8xWXTzAChffe8bOP9LYbtw+Vp})@0j`OFZGbJ+=S(b3f>=Mf$AcXQ!|D*{N!t zzB!o>^B+;atQ@jI({VV`Q`QxMNf?dGx7=Vz6iH5_RX$)*PIGhKvk%$K z7k-``$Ip{hWm{_ILS6;g_F=71m{m+|bGcgxJ!Vi}0GA@_rx__M#IqQ}M>Fu6&-;{3V-*j`F=|96ifsA9B#fuwTKIk*z# zoa1Mz`ut2))dqMJ3R)k>A%3+e3Q{K%{?f@C+IJ-VUp8`vVK-JG&wHnQ=$}SBNg>t1 zdXaCB+!6+kal~)N_hq5;NY6X@nSbN;)P`0~iePsP*^d`LdtAxS9#w5vCa;763OB?D zxt^zUJzub&r5JkE6MlAHi1b|WgWI~~hhzEq#-(x^yE{j!z;-X$?Y7Z=V30yF%szg< zP{;2VRPqni=EECDikDjRyM_{e*Px=WXz2+9<5wg0;OC<2__=6G)W?MF{H!d2pOvY2 zJ~#0JyBoA#^dHC9uXc-&zIb&G)b1rcFLI59;=sLxoI zMEb(+KT<5Kbubv(#gTtVRFRWXgT=;L95F50L|_;r2Q5$piUW*%p3Q zrs8@0MuZOzfcO!=8=9#;PaEA1ces7Z8R<*7 z9?H2MR5Fk8GlVJp3?bukxMEkn62?c8ZMU&h`2?EFPVXGy==r(G@17A2(tdqJM~w}N zFFy((`p62TZ*lX5%Q2+Sf&7lfCzJZP=tlsob)+%c_oV=qDaa02WcWdXEzKA6o*~dP zgXZaVI}ygkQ`-jed$AgRFQ#f|`sy(7_-ZK5w@Xlb_!|j7y)2NfaVi|nm}!aG+jA0x z!C9aa<1Xe-{~`?D5)J_=+G6Xh7K+(!j!@r)Ck7dW5E`m-#?Xl%&Rt6)< zCSNKF;7%j*Gj)SJVaah?>wQ}JL&pO0lP-t&S%-pb^711exK>SbXOyG>KKpD%`5(U5 zz_#VIcK>6Q;MsWx(z9;5!R%;SBlMq^LsB%gr|%dKxbl^3^}>x{c(RRbPbjT~s(^i1 zc9KsiG~PjVwa-llJ@s6+pI8VZb7?GMx>Ue016p@#r})9K^|YqjtPg-T0W=l^>x-dl z8|u5at`gcVT88qyhkHTvI$y*#vjXAhFq%_??q)%b3HAMP-!jn4r1@o#7zC`C#(g~B z*BiKP!?N}xJi)P^boii8F`H!h zFW(RTxHk%AewdyQ|NfACUGH$H-$iTOiv20@?-c2$Fro~0myv&1{3aXPr&&`U_Z7ns z_4!pX_uG|22OwR)dp3+YKz5#$kPp`%jYs+}zP^m$>r2~vaS5AzOQF7+>U|rV0hyK5 zugyzR;Fme|%k>wJ$!8g1*}HeM;Xonr4pB#Z4r&p(}Up<@``kubs-OQ zj}ZSY-)cDOMfTHgUpAy%CZBA$un>HK?733A9JU*6#=0Kbgu;y^vb_V5x!_w)di#)G z1lQ(~ek_0GLSzu>Ct*Myh_Ah{?DF?HFjswM?ix`FE7nk7uG$qs?|Paqx;aJAbPmNx z$Hx@G%bV24n7A@HYEF6^Jt_mXwkQ20izVPcn&dB?nG0X@s9zlx6@o_?tp(4oR6t%o z>Wl5fAkcB4IBnj9LU7+izAJWP5ft~`Li+SCgx_w&zw3J?q&}nhyQmN6(IfsVyV9V> z+Dn`p*eG#*R0XWQvK-6W&M1S;XQ&Nb@411Uglz9uR2qCwb{9QTz6g)vgW&ce>TmM1 zBA9-J>}}YR9Qe?k?BVk160pBT{T*@r44Bloibv+Z5x(*Bw~!j*|65rB3$BwdO}UZ` zH3OyM>!mk@?6)P*`4zRn>}fI>M!Aaqn_ml4N>d<4a20dJ*Fv8Jenw$LZTlTu3RcE6 zj-z#)AnYvpSZ;%09xB6rJ$kH!1qbAav*uKT#Fy%g2;k#VOEzO+>jiWA4MCpV1b;}@ zp?0p1tcIc89gyDXelYCrJ{qy^eLvWHg!(u)y%f?G(fYM&VKr=Xw@04ddA?9~gVvz+ zw^Bh*>Ly0aelMiNq{F%Hp5oxAzXbQaPS8TR82LYTDuVIvX)W8?t{QIqq_Lj(P6;{l zX)S(!paQ1-U55OvBLiX8LGu4&q*_duX01SCWetXE*0w{jJ z63fo{k_oSWx{GK2eHF|sT_NuZLwbTv6>RgMxM;W}7>f8EifVmlf4t!2ce1gg--E$C zne-W1>jze=_ae`^=H<{`kMz0Qz!h$)&lb+kISc*uJ;dpXZ-R!FD_r|SdXDJGMnF!`tl#1136u)P!xIj=%F`Y#J$ z+Bwqa_ueUR)L0Yg!~2wi(fav_`)S2Oy`7I(tKBTIe1Hd(&GJV2nf0#F)`sTG;Rh~I ztxfG5ofHeEJQu=q^lxEZj}X{<&jk7Z+>V8L{9MA@s!`&$q5g2ZeSh&~YLH@f?=w)! z=XL+hjS}~Sroz)lKH`qq%@cQUo_Nlq(&zR5Y4C3!#R=0iDnWZb+0S!+r?ZXU>GZtT zG%@VFD@;8{e&)7oCR{N07CW78lK9_`BuE=)|BMR zVwk&QDbh{6iXr|QjcL*I3eYJepSg5J31lUbP7e3u=em2zUoARR3G3sj-m}@|uuFqt z{)_ycVgtXYc$)fKNbgY&U%QiE?aJ?Hmh(HB_G6kS>hU|HWPWEf%(!V{fn61}K1;gQ zNIDDCB0a@N?fwb_`2M<%@2|V3HA;MJ9thsMXuc166${a8J;l2d{s=E02Y|&zvH`z< zRPf(Ne*0P@FL?ie^#6k2&6(eMjCp`05IP_>tWl#2v z1A|dMV*kq;iBGTia$Oms&Oi8t!w&tih&MDZgXWIZN0&jRkgPt-HQpQnANP{X9X3JG zt%}y!uJ3#RqG?`S<#)RVNmSPley8xQfc($bXdg&gNP1}Gnhk*?DaKf_E*yjpq=#Kk zieZEf>3`DcK=>h*%!j7Ia5j?Wey~v)JV>Cu$(hOsXtRyh?k$6h;f?{>VO(r5 z+-^rP#`DWw;9Nrcnl!^8&@>}C2Iu&_e->fe*I}^us|D6IqS_A{zc5F<@@z2ZYLHIm zcjtHdUsogD!rdEs*^EQ{ARz}%W|I$G{mKW1UZ;9fyhFginCQ(NazU|?^!a{i01U{{ z!LqHV`$MD)VUu$~Ft?WMFzclc4DLue$+hr?f-R)apEf?QFNnr*$f+{0%phOn;adjI zHVaUuYm;Koo7M+${pn0djwAgfD+1xYFOBtGonok(+aGyuYVw%Vej(zSuKDok5%u?e zQ~~snk>0+Vd%@Mdy^$xaTOk}?O!0r0(sH=v+YjmeqIk@+#t8BDSS1{9MzKoQwMwvW zOTK8+=zK80PCno2dm!w)uZ{ebI>8VgNB;2NoP3x$igXp~;tT0nq@VTKg$T=Fzaq3b&G zKTY5AJ3IBA@4MVeaM(N<`Tq_Op^pc}@MS!PPaZ)1iXBz~-eF`j=bQ3-lc}VK)uXB* zJ(IBE)+#9SA^9hC{b0v0YFo<`4=DMM+CQSF2WZbBow&MIK$8DltoPv_5su8VLL4-v z9JaifkGRRR5_qH}{lv!>fOY9$q}Tlk2AxKvLrtE~Had#hJmhc@>^Wr}8 zyg02JFA|n!xj^UU1F+3LZ!4gS`kW;6OfamJxg-6?zC!rhi|PvC^TpeZ;-#L!eqj4% zJMy#}k_qB=k~67E0gO)Gi1d!$q401B`HkM&D`B-!FQiY=PXYa1q?3>QoXVD;Q*8)Y ztw@sc9CD2v$deiu1UdGktBu-Ta5S1?%R!$C;P&@D$WwMF4-D2&+aB!72cyl@<^{J3 zq1>M4sceNCwBJGYY5dt8G8_!B>@)*6&}%_+?d{tPzTVNC8c|jbiahcy`_C4_l*T)e zf9td&n0Ck+@rz9%;5Ez(@yfVTFyBM=Il&_jH10bgy-~O~jIEL&*4SPMvW?pi3mv@R z!hx-bGqx7PS$(p3jq)gXU`*q+{%8>l+Ha3M%ip_0a!OysX*-KyPTeHL$^35X@L!r! z0s8~slsblww(x_s>RhbWUw90!=_cCdycHTr{GfirE-Y)z*ZnxY?yKUW>M_9}9ZNQL zljqHz;CZtux>ZyqjB+GjYR&UNN{gwkg9|)CKi&>`dL51ex3xZqhw@zOuYGB*)fpGT z@)!M)e(p~oxKPUKiH|e4CzP9UB(sS`34x2q ze$1*0VczhG$m8Qx2%6_-BAz-&1gB)u)rvDgV3|mLnf}oarb%cnceiwd5x;1k`>{zF zd{v)4rt_R(CC?dFwWo4^Dg1Yi=40<1cNp50A>HA4062Z6`Pfua2J0?Jkv{QWI=tLS z{q1zV8k8$0BYo&!KZx8#zP;JCayY2=UHLjGP-x>JN_Ku1{@f3Md6%he?z&|#Qhm03 z{Zk;^AGjXnoU1E?^)<9^1}iK1nYIJcE6;lIToLNapv*Lotnm?j%$o6!^HzX-*HYxs zsuv+%Npq*EQ4!qDB;0?R4_qEdb7Y=*Hq7Ar7ggVFntH-0J&F^irDZ|8pIS)I;Q8E41XVy9X9Te2K_8a|FNSo;n`~PQB!XP!&p1==ZQz0VecriAG`Mz@b|+?l<(8p zABN_Wub8ve14?_44b)p?g8evmajo)`@VML$<}RYKxVSY4mb*A&*){ylf-!%yplavR zmF4i?1@aaBY(<#J_lYXHGmje=J1j^1Uu`xxjUZof{h=R>a$AFRBYwuEXGncH^u-ru z45s)zo#zof`9|&E*DeU&c##fG%!}cd;Vdj$SmX{LUC3A899;$D8(+YWZ zwJwKHAAQ7|H)MfiJ+;Az@26h#{gkSm4*XvA`#KB6*?e!MnMPx(z0eWH-z2*|dpZ;p zlMRt)iWbkEh@Xdea!3hmyFxPWSCxTjHm#4-R{BBdUc#>zlt5oUYICD;Ik4psjr$p% z*X&u3r9N7(qS6aGy`(ir`(+-4TG3d4no&^JOSA?0Y!`?I7QEwY4|AR^K~o_4b9O#(j_{!GY(f z7!%K{Nlq|x1@+~YpC5?ReUZmL+zsNQXg)%}V5mf`t!-sn$C(1h*g1VER z9J4tbTKW;L>t7AKThSQ(lLf%Gu`96bzC=IR?nLWCU~Uz-cc68@OKLf++20d+Ci8az zS^QnV>ZI!lgTLiMR`On?cVAozpC{6~=JmoIE`uED#!IRoFKrRx06Tv;YeM$??35df z>q_(beV!v!bRxgK>~Sz0>q!3d8rQ>+lVmeZxxdnDx*p}!rv`##0<^{Sj4>y0Hglo$3D9T^D}LV z2`APELUg|oSnsR8LE!V6>`=nrK9q%1T?cvI{#Ks1Z~JMHVll>uV-5vyYKN*X=HJ&Lv`8$_3{GH3zS9OY( z{ETiHKcmYCU9LF8{oYCL_Xf>6rWno3KH#}Pi=VXex} zfiP#~5OMmH3ySf)zu~;U)~miN*rou`>^n#-3(ix#;C=VteQ!MIu%aK&dFa4%9#%AW zRdnEIn>+Z~rpv%q!eAaVgz}hSLHyL3jSXV3po0#cA%7ow-k5VO6LYan%c!xeXN`jlZR^ z=VxdVeug%zlkuiX)mnhZ?!g98;d=@-&eTtvF^;r+9kZL@SX3erF>6) zYt~D}MgA744}Xhfs@YqpZ{ZI&94*9VmyLu^o%lTB_v{;d`Un*~@2HID9sLS27CP~_ z2^IWp!s0R7!cHDL$$9MbbfkvRn7@gr;%_1f^r{qd*ZYF0I7oEvU92eJdy{i~Z}Q2x zi;&85lQ#3*r0X6Z6!ZAIzgGO+pI)QRf(L)6u!g@=`1;>n#d`jRq7#2Z;W*qv=#u9J z-}qaGV;Nn9Q#?mP;5ibz_4I{FJU5^R&kcAxVVJO=-?^XTckZ|Ub`=cyJ*)@6hux{{ zDg<8igW3G;z;^v+!dK2SioZJu+0j%Oea|13^7y$;xUNu{$Nj@TQ!%K2PhmaJAqjst zQ8YImCus9CUL$_S`*7Gl#TdRe1@fGM!87!P%{))$2hWqy_3bIxaX<5PwW+u)r-yKc zzXjOc%~~8hf4Wf0-xQSdHwB$cmIGS2)Y}i5YyK7*x7ic*pO-zw&!))0*$>XSke_UFGzXq_AYXd%MG%BFqPnIx z=5N-5ERp{upI^0neyQrcZ@3R`>>-{*+p3}0XTr_-{eCLH-&gTmc5{QfN?HqcUMK<2 zNZOahggJpm=5XYh_|g-SPEJMqg6GMc;dwGGW)BgLe9eQuU1_Zx$n%|QlKhb8>=AxO zt&XXVrB=YAYdw%|JKGZspHtj;d{7pM3n>Qcc-I?#pQf1SN?rj-8uCE=%AkEF^-KG` zCoBk~w!QrB2umWVkBzrF!L<^K!D4?F!?Ly1uf@H1F4mLTSa0_e*%01`)(*W%E|9EG zF~gZ2`B0l+j66!d7Chu@fl4P=j;Fz5^&7*V?)-gIKCSPg-n+t+FSJM4&wc4D?n_nt z>#D2a+#`xnCx!9*(?qg|sk_Ud=pU`)kq>iWmijDo)viFe=tO$!s8tA+ex!$?L7wpI zB*j!C%>2RTHjS6Jg75Kx=Jm>NN?3oB`rGexK5TL5g>Bfh#Sc#YrgmQZm;>HZb&>vb zvnxb?-hjAuM=$uioMM>TxJt18OEIQ_+{% zmqUD)<%pB{d!=i+GZ8=UPzqjMY2VSOiszg>9FKI#novlyAYCo1DhJK}6z`?;vpXGa z8tYpzMbIym`to^h1*CMKd6&uaaC~?kj;h|5UA*DvNZNlTJ*|QfC*~tPmB$zcr!^6e z+Ug0*`%&EJQRfDIAJJK*K}spCOQX5wIoA`Mnk__r8-6!YlTKr|`CA%v)-Xr9C%;?S z$McR<_0H$(sRdt8Rk)h3Sr7P{rNZrZxj}6!vOQMr3l-{|Ky97}vZ;>~@@(L84)Z%2 z6@MEqU$9z3ZLay|0Y+Y=&v!mNN9ZZVjm`XvA@Vfoa1ww2HJQKvy3XH!{r_;o8!;8n zPKA^`oiVb^vPaBB{|p)1R5coL;&~|x6=oxTrYmLI!;d4@vyd=X{gASWod5oD3G07n zF49*nm9YASwutXdmN7lk2*kJdNtuOZCkBS{)+h$=A+jYc~XW-*|~s}QdK*bHj%OMlTDCk&M_%_FI$df9cJ=+%ao-m zIbUL>>?oYJRPks2k+P|Kimg;_)_*8rOZE0xspy&oGUmJe49aZ%dJn6Tx5lzI8dBEP zHU$IKU8f7ggQPJPOkh0f_Cs4lI1+FWn z#0e_8$y6zu2(yvDAXmopkDW%IY5Ed&XJRH|M_ma!Zc>c6;D(fa-Z%-{d^t(NX1OOK z{Z*=jJ$l)Cl1k>lEfRKReF@SJ$mNV3NJZ>iEM>=+u0ozx=2BKQe+S~c4-(ela&N?c z9!i;c+hF8BF>+t$k_YM3z0u;p`5MzYm9WSaZ)y{{}QAR z`z2*NUxp&?WFu$gUh5D)pCn`EzdIrSjDvFKd}}SzeZ3^?@xa4~H3!OB!mwDxg*_x} zUazf)_XbEQ-@jGDdOW?4xQ~~NP3&?4%eKpsGV9k(tW{&wcA1pjn)Dud%Cuz6 zfBYT97dmqL-&KX!riGkc>(C7ON1Dl4Ck63e2$iu9wvDY-ZAWgSb>y%sxwFYb+wco8m*7* zU)f2{&i!nI^q62d`+2hmVhPt_&9;8X(`K-oRUaFIbj1caJK0JP@dIxu+jL0}+iY=H z%C>cGFniy@NPj+C&gSnOfOteJDLZ_A z3gU|!rEGT|AP&AJVddK=BQ`IPFy#y4xs}3w>D0+6b6=f=C1z3|ou12>*4E+3zwo|{ zt&5^IBrTJ%n&k_Te_*Jb^}8|`c?``Z>{a|s#4$@`Y-6i6h<9I>Fqgkekl&B@eb}y5 zNDmn;VZJ8I5C`hto5RKi2FqHvG}$VQs(9ChHd!oyo3o_?np1?{#HN61Lily z>E)DZj!IA860ptQU&yvGb6#0B@3C!27tuDHM5{CCb^7wtk5Bf040y(S(m)moooI zZ=^roBx9{VdLo{3T*@kPiKk$!oCz(1k?!$c&TMs~5dYXIXWa*eAU=>UXJvaLunpQ< zWX$LFVZ{40c-cD#u>CC$O4wHG{fI}qNm$^?IOI9oU&gL|h(jC$;5=F<5w~hCXRF>OBfrO635ya*=9~mMyZ`41(g(eguz{M? zw%`9r*p#d@*e@&YD<+f^y$2uDh_a)|Uth+3`}HKm2d79_F(e=^=Ht8iVm9KpL2~xr zO$B1JRdP0I)+xmIT1eTtH|Z$f?5>QJJDo+kXKy~oHBu1YZpp{jIt_VBlcg;78Ob-| zHW?9{hCEkvq|B^YD&j`Q5~lMc2XT13lr>K!o}c}tY*MFkr1wmfvd%U+C{wj|Z|z)+ z`dM!yWe;kpY)}gs3%4spe!JHamJybLcz3RpZHHXM|Jumdr5zQBgSF&r(V=R@bsuDG zeJRQLEJ)a!{=|Q%kdO6xlKD4N%69F&h;8_>SI(BjS7F(tw=&i>pa|)=O8A-!i`TJmOvh_!_;i4Ewd)O2XE=5zoSAGG_Ah zKJv8YdN>h&1F>}|U*8?5u8mzJEVYj0^t>x!{RU9K=3kYt-V3O#8=oT;FD_%*aBlP0 zI$S|qZZ2n|w%)_GX`0H|oRo)1Kir=C=P2Tz_f5)vONc(PwTx|vx`sS4ucd6{>N>=8 z{>j)XX)WS*e67!`C!Q`mzOuYWc+7qYGjX|xJnL6Une^UW!aJqx%!hi!iewop?tTZc zjN8@EO}7x&43V+qcApUY4U@BD!yh0%-jv&0;Zwv@d0f45G0C~jh462x?V;epe z*GPV7h>V?mNBA6{``K^)V%hT!GPVYqf-1J@z~iyRp5Kw)eXER}FCZSn4ie`4tr5zc z&h1&>urcxbj@3@`&Yk(?_D&xK)-?A;z%lX{5jiUa} z?J8#-=eIz*oVPPKq9wL-yF|_k4pCj%vnA~7_cq9LjK|x`hg4TkCmv%wCVI|zIa^;$ zI6qRxr0u9)I~O^dsof6CY6nQz$XcrF%SQ?ObH5eRPdZE3=j@J%_wSRj!^2x6ezHc& zZd7zeyll6O4PDa(+xCg?eO{HeN4mvIDZ8NC1+i39%KmHI6|quZ#v;wSVBe?zld{X@ z#NSFPW7Dq?eqbeM$Jca5o=+($ZxGFXBO>yVO`}frA+T^ccky+ zG4KUzYQOzhDYG#ldi_l9HzKr==k41)?9hEp)Pw&?DLXIILwuF5Uu#TBzMF-NDISrW zL>>!8H={Ou+QZkH-y~=4B_0=zApRy#Wi0Ou^)d0ilr8^2INVUq6&|_tiDBWq=z=+wltM=D3$U(np*xL?yrXJp|Ycs1_eubKR7a zuFmoJw#ilMOP?lkw&{2$lzHTcjFsKcL0r%K^`te)>B{}d+HjJy{4S3r?vZU9ER`{6 zs)KFIeJo?9Z>a2YzP{+~A>8eNoNXv3Iq;6}HFi+@*#bFxqe(i^sM*8reK}jE@(D|7 zBy4Pc3S#~4T%XQGi2Hc(_4Kn6_wSYoJO(q#LVD#C?vuwQBfidcdv_bjY0USM{-zma zs`+TpO3vEnmmzL@hwp3d(;3D0qcV2AjW?Fvag6&$(>aK5n>}uTe zW^a+RX}`^pUbs=t_UJT1+~&5NeVqQFRMq}pr{qlI$0Ed9claFK)ERkB^^meD*}swA zh_5598I@I?b+B+>k9+tnol*PV5tlURz~NwId}AwlE7BzFD$adE89N#WRgE4I}1n8>tF3oCY5u`6GX zh<{I|2=LO1g-H&Jn;~21dculr(l{zM-IO9+s&De1i@|hB-ZZI z5wZQ8RKf4TB-X1}yyzVjB|QCT$bK%17Z0zE6zuL8vWaWr#l<#}!oZvXEZ}~;xM*m& z;5uRe(^(QPTI`AxMhx%IuJIe5ftMl$vu%CZ47~)=ylt2;ba5Z%Ga+95{wh+)*kr)^ zhQy1hfe}LU|MXdlGYR6fBf&!WDLqyYksv;3A0m9V*Ja)N#*1y%MhW|N=(16p6U3a7 z5TVvqm&Hrs#j@`aLbD^6_!aN_P5 zcH8-ss69SL$gMDCSNp^W^~qRa!Ywmq&FMEd z{qk#bmZBFgw%Q#fWUjDa+BK)d79XPpvp(Zk`stHm$)f{;V~_D{!KG7T$c<=WRMmK< z_v@5c(JNYbSv!Hf+kHyByD>(%nmv*G)l*{mxH#cVs3n_w{G_PY=AbZlycOI3>7*EP zGEP|XpA~c9dbX*J5qiy^#L`XT#n+vqgk{l_xZjHxuXT+Q+GrZF2hH}1?Ka+3bogw@ z;}{;#?QKK$;y*WW_ZJ^UQ%fVZ?SixTdPJI{t)n5kFvvs9 zUb{kZIM0x2o%a+k-|44F>}$kYwDJ~fVm>Em_B3LH_PdKSpE@XxTsCBT#(9eK63rAD zEsWUBo8IDyP-Vj3r-p2PxUX2-wQ0iTsYWcTzrQ$fSIfk-VMc7lCx5Xhxq0GaF8|cD zATi0aabjFsBPO;F7XKyu6Kv}Y*~aKVaeC*biN_lmvFxH?(fYt|VNr}BGZRC^Exo=A zhoTMHBnTB9pMDXt?i;c-p`l{a*w4a%mqtv(I#m4q;)^i%?f_QOHbh)F`Ij*4#{jnF zc(CZv`;XA+>j36r9xQfv{#WRD-k8-+v=c8i^%e~77_)7kY{j=Tf`rAM!`RXL^Y}M` z{RIDfbJk_=BGK=HlMvHnEDN4vCw{%}CA=sZ%bYvgi9I%X3+GZSn7#f&G5LX;u(;(o zwoN=VUHzUN?`gMZKn9*#|gGkY8|0AJu`e?SZU9=do>aH-Oa5NkJBV63|?ScbHC<^pSH|rjvB$@itGP`&uiv0?+&5j{>xv5T|eiuH8aA+ zA0J)|&F9!LvsaN~=hcq{9cMdcv@==^7ixvaZM{JIdaQUwx1;d)qX%@A9~AFz86bqu z_JYM@4~Y|WhYDtMy6xJ ze!O0%NcztM#@HVgpD#8QCVz2xJWX9i-na7FJqg{l= z8W%WsB36vr(q4GObDN(v+Am(7^HwqEfEzURiV{Kpnxe}jci7WA;{Q=}-BC?^O%!|o zsbE1xMMb4ZQ7njxh>l`G!2*K4p`suv*g!f+hlD_Y6hcVIo6tcJ1w_hV$FA7L-g~d# z`~KULvu8KEuk6g7JNHsa7P2s>aA>v>(6Kqu%;{}7+&+;=&$dry3WErkV4F;Ze%>r- zXapqxCnS&dVs@n~=l^g7#pwD47AOe;@5)Rn`_dmRh6O|RQz<1`o8bxw0=*9sV%5WO zLwpGIoRCfnPqjgZ;9zhFNTvS%SGaz7FqBM_P-%hz?w%I{2B(D7?m`Y5`ClmX`Y56k z|4y^puR>wM@nrg_31*>7L*TV>5*aqlVf!bB!qZ)e)VIKbg_?)K)gOs;f6fdhnI8s! zW(nzGVcvgw^BIgtN8C4qE~v}1qX2SeG(WZD-H!uIV5 zhQ9^z#QYv;T!KS*pJ@`!zP5-t{|$lcJIU1gI+ShR9s)JjV(I>_shV=PF!LD9?{qu@bvBHdmwh5e93g2*zN68>ys(|$+ueuQK)D%r+r*2KYox&rztiDVsv zV_>&|kPiJ2v+eVu;HHj%#%_;b;hC}Ub+d>P51e4%MNyC`6_CD368ri!2Hq`ArPhlV znX&v3_=Kd;_=sX=sTU2t)gs#I)Wl+T#K6fzarAU?lBT0aB+Rc#q;c$a|nl<0(_ns+q7b2AJoEui~le!4I0NM|thiIFFc?&L2Hv>OtyfY?@wZWwQ+D^jfhHK*0L*H`=Zl9 z5&6EYW2Ti!AgD{B_if7AOY>Op-7cgV2W3ogC<*f2#FXyznH6z9!1qsS)Z+byUAr3( z+oHrIjQYl01o5CP_=tNsFRquMsY&>J2%P=ubh!nSvO-rJw`$+zYW5iiwO{&mO;vI zJy6#<0cwt?)2c%qaoo>1Fg>41=kxV((c>tHEJ~we<stiJzDl!4i)+f=6KPy>YbsWHqBzik+KHD`Z3C^sDr+_o3HTj82 z;J->h7n);PD(Bl@Z%LrA9Rt|fK8awMoJga~$1#z064ZW5CWFXu*1tI!9Lo}EEZ6-T zq(}yTN+$EAA*?1z085>PG&@1Uf=q-kxK3JZLlU{^uVTk5MPRm5KuxCc zOqcf{tTYso$}XMhJQhN8HUHM{4Q5YA2;payi1tGh+k7<{_6bBZ)vba3dXoa5rl!!Y zyLoKu)KpM8h^Y7T8n$^x3M}fKMtSG&vW;s5Fyo?-x~x&LS8Ih3W12!c(zPtlED>H? zr_p|^2P`Xv_qBzlQn$NTm;rycCMc$=S3lU!yg2yqDvqXp)M{?KB*L;gV?DGQX2{_$C1?H;y5pVHa($fdcsD97Qj0 zx77|5iNIq)99?;EP-7!XgWi2&iRR|ys@JALN?I(%WDU?P{LJ}Rq46}M?^Vrzm0Z95 z!XauM-BFv+KLt8Gjv*)E%G}-q)8K4r938NdXqxAX;6+6|NnSnFycecH+m<-0+O5`n znj?nkL*pn{XOm_IrGm+pWLkQ5H)|c83W~c4RH8qSjrl2r^+8GGk+g&v?Ma8_u8H)n z#*~Gdroe37WRiT^%=EPBuyA`U9a+>?vsj%0z7yi<@T6Le{R0WiY>K0~NeYeAelg7Q zOr)3Z#;`UZ27^5bboX*Mmi{LbYFEdRce@CUbwfHlo}EYmQe)=WRt(A86Un66oSiVp z0=rL%v}&zA6Yj}?+Fg8J&G2V8(qv#%!S}=XAa+*w%1AqgKGIcAGnhB ze=h^yj!E>e!%Sv!Kmy)lgmhjngT)kO!m?r^HJd5fo@omBQ!JvB;XK7F$b>WdQ)qF| zVs`bZ9DW80$m3T$+v_ZYuw4R5c8F)IYoxHLgvUIw#2PoqU{zfzJ($!gs8d~R_hDjK(N0dw+E2jE>NIHFDyJUtHh2kBVbb#q ziagZ|=eY|(U?`=RYm88)D+KG_nKXKwE0=-GrXT@)o(6BI(Sg8qfKcRx-d>vJDeWCdN3P^h*pscYX zwt8<4IQ16N_z7b6ElLR!SESI%PX)}gMG1L#Qb_oqf~B^}2D?Q`)Y8+5rQhSneFc<$ zHIi+~Qb0M+9ezbuFl&1?=e>()n(P!)%vVA=pU>=TJR5mQ0g8h{`k60hS)EmoW0_7T z(%azL#cJ?~Ngr=s^U9;hfTN<6rf5;mDQ$ff< zF$rFLWvw4`AY747mjgTCL{B9ge>`^b12b?TU= zczP!1NygEOwA~u%aXI`@#?geUX__Fue*Jj7x5fE^=3l)O-tUU0^~s&IZHgsOrxQoN zESGBRb}K+XA(osy`)EFSXF-=M(d4GgWakFkhybzB&sA z>c$c$+T=QEdUG6UB~R7j-E(06-B_|#+H3B`<-oR+F?2O_aPH6x zN*Lb~O95A=Y2Man!{$@*w7&M4Ciy$(HU}>2CejU`Va%vQE*$53 z)XmxP?8|f|bljdygO>WSVp$$sJeo%Tw!L5_$q2rKQfOr&GLHZ)y#1X*{RSRo5fgL4 zc5)g8Cq7_nT{N(!tC%W&@c6__0|$2Se9gUxz1gGzQzH=tHdnF0YAy6MN~Np2&a=Q% z`S5;k3VnQA#QJ&{LT>wXIyhJdlh5bD)pdMK+k9btvI^jVB!z6Yma<#Z3gKzFi1Ka` zbADO`cr1m)(TCaUCnca)C!+6JO{`*W5yY=bp~-^_*}|8_P}d})vF%SX?VJL5DG*cJ z#ot-~-}&Io_gL$n_t;uhF?6^sriCm2Fl&QS_}G`P5p!hKZ;K##VJhjayU3P?YT?D4 zG^!M|vL!nambZu~!uAxiGR%aoL&PLq`kvjsln&#SY1H=YGZq}Jft9ipatSYGg0KPz zD;JPUYcl(8tc80&QmFIeN;bYLLfkVU`Ttb24~S6dCZr*~r0m1<5_oe@NKxz6Os~@s z$g>dAwJ8})S6l+HQb>ZeQWnH}TWm&(Xl82_3+Yk;b61Jz&hc87eD^T?AOUr3FJ$L# zltM+UkZeU+Y+Pd*G}!Y0ysC!XT3P{p_ljtAR2@q{TMqwzq|*6uci6LehoMujh}?DS z*=7SZJmI;?0c8Zce?JF~O->}MbEEiPln?6;CQ;+|CCvFiKE&m5>}9MT>u^I0mV7U= z{jix0>5gzOB94*|C2EfPG1xqo$1{VDYu4)LL)u^- zlSIeD*RrN{#Sqjpi3ZJ{#WrWFCanhD5jcO0s*h%$+PT(hK(N;!Q<|n(TLeDwF_byxw(8f6LU_M0mR8w6&XuPX zz@C5cG~nG=&G&1?pgo^Jlb`ly9;GFaelwOXX4q*`g36%9Igv_#o3OK%Wl%XbfsSu# z%Pzetg&W@!Ny>E*@l*+%sEDCchd!v2+LnTuWddotwPiEbAAvB_1ajZphV9>S7zSCy z(?jbTjcrvKe7qk=U2-*=-($+*RcIppJYmHI|4N~3X95ki>Bb@sm&1on0y2LY!7Lvh zfsfsi$n^9~_TBRc7(Gg)%f@!BHMtVHACIM_TP-y@lPbZzDxT(yeysVrgmlT)VIIk*OJc>=}OcVcJ%tAefL6KP@ZQEbir<1i{Xjs|>)*Idxy z`UX7K{at@h6WLk|J2ofM7JYNpQhyu{YvSohn{VHUS%Z|hFW&xR{2wB%d_w~wWE4+OcVPgMfD5liD^rfK8_<=|NsO}RrlYlqra!i}%dw6m>&u_!h>*~0dmXK-Y`cu+T(-oRF z7iQ4WGyma$A`NJ?5=vTRh;=Op3$AC7z_b@`kI=xt{&G4}I)V2(F$fqZC5yjC`2DjA z${%J>*YsX!-QAZ8N2Qp~KpY9kg z%?5cV9^>8Zjc#34aH@-(MopW5epV`I@s-kkqtSTKQpIyvDQ(|rjQ(qK;K2+T^>nwu zz8WPg{3oNr2jek$t^%g(WKq}ZX?Uw|4lMMS(X$~|DE%q}=`X;w-rNpPVjk zoq#uev$!^tgg(zPK(8S@9~>wl+ogkWZ-f-Oj+M~dAqF_4V-`41$)v|>J#>!AfTZhE z`ldF;E0;5&?aNH^&l`aL^VIOIB8v`oo`vUbWx-%wIVqziprVT$qQ_@bvZV{k&dRxe zN*3wZ&BDJsWpKecoBEq9#=GN`P_!|N){L8h`I(tey+uiLF08=c557Pxrtem-@ zV>%qTl1(GDuK4&?8XW7TpnZmO@WromNdBXs-SZY%}$1s208Sn-FlpSTL4#f{G)%C}j$|_#6R8E6dPR4;bLa?=wbI;9**twGs)|{8q&!1D!nfEQaoX)1z&aT)rDh75rX4BC7 zE@=0MYe(G4p~G2QaIi-_eEyV8S*P64vC$YL|;!W7=C!j$x&{c6;E7y%`_)MTmHgC4Pwa59*`+mlN$YkU}d7@kdo zM9x?j7Yd^ms;PLDKL!jAflGarwEWX@9JMtJ*7Nt!TE7~PZw!NbM%coC z-!LwRB6)wJS`-Z4Ulioib`cH_3j+Nz{_IB=;KTjArqfnQ>*p`W^Qj@=<1MGL`8F6m zGytNV6m->QF8=DsYb&?1=+893qIN>))=5nA<8RqxUiYcnAfeQ|gRxK}fGO+JY1+be z*dr+f=6p+~w{7mQH>KQXvt1m$OjrL`I5VXyU zprFX=Vs`rYBNOi#2P<0%6CoMCuxA!`3Vo!iaYnB<#=|4?PNn zzYcM9=kPv_@y1ZFofS)`Hnil9{Td3eODdLSg0MUh*1JMEE#P%vJ`HTRyh z)%Nrafw252I;U=@-OTGjcg;e{sr@_be~XW=V-Vf@?jIt z!oT-;pXrQjIxKTR&n?_b_lk-R8|}o*7l)w#ZWU=RdgHQ=k?_e`MIJfZ(L06fVV+Xa zw+3Id_K$+z#!A{Ha>rrKTubLpHf8*B#gJXe5M-<(U%PGiGa?zzxT>kA)*mmrB|u0U zHF+N0g}N2or|f4g-Tp5O<4OdOEzY5V_MUi-`{0b)tRk1q{JvTNY;LEf$!B)q)q)gw z(U?t%Ca(DYz6i>CXh^Xs3}>wnK@jHB!MqT3-INNQE3@gJ`B{2aq+YN|Nths~ZjAif<< zj(a<61&5SSeVA7VGne7Cw{qAzMoE8;xnrw^1|I#3qRXq=YuDe)fZg`d^p9WjjVKqC zUi=&PU&&4Y7}Tyrv2M;o`H?3WBuioH#3m)F&U48-=&CzoFK}G%x zcVcQvGOX9%Mjwt<;d8x0xH~wQqMtrP|HTYGoK=(V;r-Z$Yc_gZ*-NJ`-oTD>4fs6F zp_Ny+p#Dt+L9v=5>i6OIH^tE9OC$~N-Bx?VfWfXW;q=}47y9#j`Cfhw)&KIu^>)Qz zc*~zG_gultVOmI?8b+s%d_uQLMbO7fO)*RN;7O+<*s)Yi(W(CE%zF~|q^s%vo4we( zpcFFgbI8+v1CCo!3N7t5RA?85LDvyJuL+};C7)4HRtno+X47>)H@x5bFr4qmIX_ha zIOoJ+u=t>)TrMT7Kq;&daPPiZ;-CvhJx*ia6?=cq`% zbUSt*!Q*FCQGMwS%+5Ou`_Cy!HGK_spML~g!&H>!=7XJMdHzzFLu${>`1@`pd~2^J z*Opy)@x&4MI!;MCU)<3Ux|u{U`+9(vbU`NL;-27+jshxj>`*v3GGbI9IAEq~m@(n^FxjzINX7we#yn z6?haVDPhcNtSYX7uU*wd-FIU~-=pw*or(->z0sHDL5D38N^ds=|9(LD7bT&$eTL$J zWd$&6yo`FZnq!k;9^7p&CAMt@8uZq}q?}B;XWJiFzbOLg{tPPn-W~s#m%@{&nbeMJ zBkYbSgl_vJ)Lt+IrKd}v&{#@M8Y3*UErX1t3~D&m1B*g=zIIwdA!~-F9 z&Nr%pwf9vl{XX>508Q}PflrUV{4hq2QVkXs}*2hs?8*RoWIr(k0!NXe% z;j~&#k7c%aKdcCjpOBLBi3xV>R{{r@$;tKRBpk4Zd!xLRlE0f74mYWVvng5Be8~Z2 zZK~mcwS;T28sOD#HBj(4lgt7Kp!i)4e3E5SkM8~Pqkk1_3*ck7%nAp-I|h^9O6X0_ za6EUq3g%Cj&;^MBzVbN%ZTK@jaT$r(`t@+%T~68mCSl0jdieQMMz+Vslzq0DgYXNIYJC0wT*K6eKgmB?c!TV7ZjWI*r1gXY0Yzg6A?fj1YKV|L0K> z(xXAx=T1EYzs{nJ2Y_Fvoqz@7rSz}|kCVge;OS)vZ7v;#QL9eCsCja_>o*An4t4O3 z-`6V527kP&h8f8+^6EYoSE-M~HboXqnlTeY3u>YMY&Kop~SqkN&vgvraGvc};=-W$4BkPvq3rz_qgR)6gvjjiLE8(&{haLud z;tqbi?YN9UH4drAF?bo8O?YbwPR!+F)KN}8!zN(jn`2=ANI@~{7h=2BW#F_zL8nXS zqFt9#xN=!R5tp3s0pC|=9m=N5U6$gxm}1zlKZ~qh%)no&Bk;Wo&qHSL5cA1~~JHe=EJW;?8~z@VY*Wj_sU<`seDPxP1;eS+2wGsyfIw%BBrD&Nxcj z2uuHE)8{eEamS?wu-MFF$hsBiZb-2Cj*_mPU4xUk7Th>H1*Mia;%8m1;n{}&x9y9t z-TEf3qnktRFR#avB!WJl)%3G(0PfvU3r^nIrO9BP1&2@1Nh(Gjg8PQu?tDP8PpiqGu`0v1WA+H^3UE5$D&=2g$1i(@P$1wGJo`f2ENE0ym4xyecj zPeQMC8B{;CJMMqk0Nc-qNj>p5dlqyWChkwC^TXO>IrlWI+Q;jRqOYv4^fVlEPotc( z54m?d!M@HS8ujET8=Y|qzPwJQkMnP{-4O)MztX7R_c!eE>67rMzlij|9b;N?BmD9e zk#;~G`)N&J7n@4jgIAgMA3?-bA@$R$*oNUJp{g>8k~3GZzs@J&$fRVtXW-4uUz~>a z5klHJIEx){Z-myhLb5E8@|s8^I4}WS`kKUadNo1x>}0wydI$5VI|KVUw%MRl#D4EO z1Bv0{l?Iq-z-eQ)e;9irR#WeobTPFQk3#o3Ybl~4b*71BDyyx%GXLNUb62m=`HfPYM zW!*8#>jd<^!ryb)O*X=>7WUPOIdAY6n_hVWbd+Km>-~dqkt0~$BZKs(b-}e9Bb~BZ zOg-yAvo}6fU_@eCe(M+e-1RsV?#!f3k$o|oYqW0d#`&U^8M)VbH-hWBDEjfQt+wKA z11#eD$q%cYa+7`Q;j+Ua^7_zT8_)G`V^_wJm1nrddNiZ6_HgSdxX3ZyGLG@;wrzsV-(tvL6Q0W@LE+@#cpAC%p{Am# z5iHvAx}-;m#^+||@}zib>eHfWopKUh&P=8QXMLES>=b0b63`2Yh(%))bTN^VKx>4tpPRsYj+AOE zMq)LeOHW<1D7?}hc>^ZgIhjQsvRP;@AgJw^MeD=t@cX}$AUK~*xBXo)tdQ%(u2Is% z{VPzj>NuRgl0`Wk0d)o)h1-H`TDo~D;;5r=Q>~!S`&g>iEbL**ab}s4 z=QykI>-}=LUY$zof8AhHiYs8m)O4EIsVzR-cMOhS7t*xLDpo9)La}icJv5w-PN5l~ zn4_SN?dM{aZ#E1$m_@(4IH0S3HtbH$rb>^c_*|-iq#bfvRBM9~n=;{P&Ne#rwi>_i zn&8BdS+u;9nJ3{R{NQf9#; zJh?RydYWve-0o%QFi`_4ZyqO~--wrc6hqr{0hF8a02h0yU~%(MdezgMy_MvE@05{b z>lMZNnJU4qvmp)sZ!DX{F;BWYi1Ok%>3?+&ygo6Mwv8CW&J}6kL(LGn;5d+xKn;sc z45;P6O^v;&3glTM$j;Z7&2-C!zB7grEE&PZ`DsAdZ6rNvh+xASlrZXrA%!N{vzj}( zoJ%&8rb&$0tlcW`@El6tACF{%uI7M&W+bgQjAg@*=0Ks!MYacI$ zOUFmi?#2|Rub&BvpP7=)o=P@9L<}#cjii>~C{}4HfwqfA(5zN3mNF|7=H-tjz0VT% zlY3efdm7WzwMzExUnV^AA4BV{o7fG0zM0`@N*^j_GfFdI?qEx*k>6!qCuTqgD@*D; z>mIA>nhxt6OepOWva7o3;4s^azE)K++LsPLznhWnlRDP&UnWFMFe7{8Dz^5u7~HQ} z(x^IBtG`X4Yh8PA+XON6x3Hp~9iK6K7cunEwIRupemE*P0}kg*r19-~VaR|C z7|~}Uorvjyc9SyU#cOMlbZO5yv=X>A*Op!z7~mD)0^jD(Hk+0yJ|+NXC4Qu=xk_mq*X4A9xuDCxs9eM`N zqO${>@Yq)|^xEM_8Bwdz$4>^qoo18dXA+q>arVa^<@yS)R9*7UX4lXWuPBEpHzdk&U#j^8bGohx!gnYghut~dQT*KUi`WNQ2+Af(;f76P7 zy?@P;E#+Km-IBibe8hU}mVlMOiln|TSwGJEa`YWbONV{re!Ehrw;xL%4!&nIBr@nf zWgN91`h!hgnFYs<#u7!nV^^Xw;r@pSl=87V_8%*S-LJ=y!PI~3mxl~?9WbY(78ls9 zkGwXau%I}nn{0YV8PwbxO^ZroOtn%DrcS2xZe$tTE|SA}xd|6yFJNtLWbpHeIpsXM z%*_5N!2Rwh>U>$m`h{gdCmmxNd_&IK^~!+@DoZ*)?;*=#*Kb)+d};zcpV}Q`UMfK6(o|YC%M697GPu<;i5%Vf;`0_c z+=;NEsSEXSa=HxGJ5HjOo4WWgLIG#vCeym>1{j^04M`iu(S(SfY}PgfSnirYQ)|28 zJ;NMWYiCa>8*DMVC<`_nokSt$`k=X2Hr(qtg+8wyf$ke}Ahxp|eN|eaSFs#c@3$q{ zTSGi^F$-?>m_fh4PDAUpa@ZejPy4k~cu!CcT>LPTUL2W+-3ycuJ8w4a)m?^Ncgg{M zXHvT$N4y@bfcws~XwixV=x{X)CI!r($eYvgz=o=!o4c^IB+68()7Sg zelIi4BHWZ|_|rZIGA>V~ahH4Hl07P@jI*XYE8C*;ITc*89!Fp9edh!W6(qE` zBxU0rX4x+Xg2|Yw)oNyLodaY1%*e&1hGiefg{@U4bZ=-OJ0w#A>oJxFR=s74<4U+) zIf3-PbweLV6`1s#MrzkF_%4!x^V_LZM`oCs$zaUu2^4p;J8o^(fX#tPbfsJm#rVm#0mj} ziDlC%?aw59dRYY}_A_alb`E}+tA*}C_9P6Pg3kvrC|1s-s~&T4Cx6}{&mBlIVm3~E z#XuZ9f%9tkT++*hg?VQ5a8fOs`d$N4JuAvJc*?HaVQ_co7z&x%z*4f+&{<F8iAg6^rd?(aW(|aus2!%7z+R^zrFz1ix&j@F4Mw-b=Fj!-3CuK=0V3MV~WwL*}#4IuzRf;`Q%iy zfel(%GRcJ8gvjL0TIk|7j&An-$qdHlL)eTlXwD9ckXj*A6W#iT{IGt@o zo2Qa4`2KH8lMhtW1y2R6f>bDYu#kY4RUjdElm=;#h1AD{o&76|W(p0xSAhTEA!KFKlMNo70|7@3$YI4B&BG-* zus+*>@;krO*eSChY_mR9RGMhk3{^t!hCwuA-C0dO$E8PA520q`fh>QA0vYr_ZA($-&^XLqI0CdYvG%y_9;VIqS8(}&UrOCFb2NMT>4 z0S%e-Mw3<~<@)*j{5wB1dQItYe$HUhKd8g5sW=Bda1O<|dEgRrA*Ah?O=rrN;YrUV zSerYW!ZfaU&?yDNJI|#ovvqi7XA+q1n@hI(8_>in5k`yV(eyu?QFxqtur69mJ$gi9 z&;;&ld4CZ}+=FpaXfn)kUO=~1J5YLubN*k=qthW<(erTv?EO2RZcp(+8@*(RQn`?! zC>-T-ULTA8&9y*P}Yo(voNET%WH5nRKTduLByN@teDpmcE}{7qR( zpL@jOzY#*H*|LIO56!@;!$SD2>rNAYq~L(v$LN!Z1CHQ zs4)=0nU8_gGWZed?@xfo?e^0_-&<&2DFn(0q&@Br@xj0Z=xnv0?q0fuJ7Waky(p9% zv)|#A{sOR=5ymxpKcV{={(mThbK~D&upk-q`vz0bE6>n=m=G2l22zw$D;~%dz^D!W zl)B?G7RiL%i)TNtrQXIiv$@vmhu!qR{sQI=5rFQMU1W9Y9M(@v28V%u^e^KA>hBQ1 z$2ecAsXK{|kCMUFa1VX%brrukiQvj`Pa1Wm80QrT;CS&GY7r~R5>j!J_)N!uu|t{Q#+6GC+SHX2)1jjkdwBo_PA+JRTFuuK3en*B+C zTROZD1`|Gij;X7}U>Ore#a+H&L}4mK z*N2eO`VD?BN(YPnVU(}?3G-S-5W6azRHfh1n%Cy$nugG$l$Y55|L;U^FU>Z&jy-3m zagT%DbTj-sYWcI*m+qy8=o_dRn+|r@chGaICd~bo&chFH+U8z|ZRV$dmzy`m6`jDP z-O^xQ_I7FeHRP17 z#DOX?l+Ia8kMHH6{kRn9e0d$+n5DtV&(gr=_(t+OQh>n!zfac<)cGr-?(TH3{kn$C z%yKYfxfpaU*3zon94wqGhDn}oWvdzc3DO%LHKDe>tho3-Cc7A@sPu zgx+~YWBhzAi|C_bIb!tShh2{uaUO(B))(REU*b)8NCu)pVs>HZCs_a}8~Gs(;A) z^ha~w-fU0OJ}kkYbD7{$??YA>8_>)_3~v{C(FvVnC}~IoAN@cYIklDR21vkSP6&DG zy+Yq!QXX%IP=)?0{E?Lo7w!j=&gX}yH$lw%6A#k*Wqi%@yg17;gnaW};_j1T2%Eg0 zEFWN)ndR;>g<4hQ@yN{NyXu$;m+;8q$AoaTY5C<2g!@a@&RDb;v8rx;U z#ZUaW@CtV8l>s65wo*jLqgWJ`3JZNasnE9sSD?bW3r!73VlPY$gvV!wtNC z`k4D=Wd6~j;mI`E$GzT;Y$(O=SH-Yn$!eOBl!YmiQXyiA2YFPdVK)mgG>5v9*P=u$ zeItUXH_o(OCk!XJir~hOr4-dI2H*RMAo=`U>MhuaL-l$7JAOXRsq?}*&V9;PEuu%u zg0SP;blCsii5xHO!T9=Au-XpfIL!qwJQ0C~uOo%Tt;X2V8PN0fT*CgF@T;vDY)>tu zsWAtz?vxmm0gLH~PbAXubg1Ox6~xC&yim&L@M3C!D2(sM^ZK72bYM(6E}SNV%HHm@ z=W7bC6iZ;(*%j33M+S~tlMcVPxl?M52=}>*VR@+=&3u=PE~-ojn7x`xc4c9NQUc=} zHc)Xw9`^6UbBfDrXx<$qdYEQ{<&O0v$YNNKE`gQ3H;`KgExvP+LPwX4Bx=gXeen|5 z=&^=2T*=08jwy9^*-28r)7ZTe$9#_NprZGLhgZm8yyH$9wC*$peN#Z&N?&R>;uH=T zA%|Dx+sS!;E&f@p0GFXYB;8Vv#lI9_amkyeRo7uF&s$>?cTla6uwA+e{5Bn=#{(Z@ z{SOt~@d~HFH{WqI=0NJiP&#h?4&VLEg&zT-^m@~K^uDD8AHPt_n)M#HNps+dFpyTy zdx*jPHBh=Rlt#(l;kNNgh)WEo7qLGuf1DORedL~odpc_8>Z#%3%&) z>5H(Vb~)#1>o**t{oOligP$`;pXs})PY{-q-Ocz_ra3ms*8`d!#TgVIxJ) zFF^l*YxN3|H+H~?D zv0fTRPmqBiZ5i!#jK@Uz9@2jm2bU8-;VvO5q3h z1T?5QfOjNP=#bz_W?K?5famp{3pUZRrXno*lm!oVZl*N_W%!NHfr{%JsJ=1}PhHN1 zjmrYpcH!V$*f}+nGM(O`s0+fK$WTfYyvOjJ1@Iy%hO8XB zt4}=Fg3i7}bjh=W_SP5`cv=S1J)c%|E6#<~+5j5A?*WcnuY^b5-elE!0{1@41jQIH zx?g$}Z9HX=xN-+^SP}zvaJ)#nhhExW!@@%n=xeZpY||PsK1~jL8V=H|myhveM>z<0 z9iWhmyBK{*3hD^~)H3Hj1`St0?u7$%%kv(tIw*(cJAt(M%|lE*%(0j9J)C!X4a4oT zAo14$I(+gT8rvu##4(JPzy5>+=jVX+(g^DO={M%qWkEnv7=?`dg35k!2w5IQ(XZQT zU#(Qakjar0vr9)irENA`E8#q=z&2Xn8U-9*6i%1?zhl)NKCfm+P-Eq9R7_I9L+%CE zw(oCDO;v!E%%6(hUB-X*+3+~~06lMW4{dp0SWet7(wd&b;TdYs`Lvhf`*GrKUj{F) zg;NXtMD_Yy_-YVFc4I!Fl5=;Htb-`C^$8xFhoHOcAT@q{gvrD6;7r2-I=0{*PHNI{ z>@k22+djao=LiN-yUB4$Grk&x@OIg5`t|%gHU_F-dA1)7Y`lm&pR3?**>-B4U5g{9 zs$q5C&E(WtihqMuV4Sj%LY5cc{;fHnbn&F1u_ZXV7lY+iTWMv~5wu*Y0^9RE9&;$g zr97v;DDk36>=@pxRl>I^TWI38avXXj8)A>GAit{_=p&tp9c-^D8>T@8fyDL@xUx&nj;~0CEP_g(B zPRUZj`4P_KKQjdP^;g2k1Fn={mx!juN(g=BN;x)3IDfka&VE`(=KT_|%W5Sb>*X|l zxe#lrmGCEWImZoz81O|6m#(g)i8G}zhP=1O|%B*lxUg3Sxokl=7OzWuBMgPUvV z#85TX`7pRuyPCp+6zF*gK`mWFvQ2#K79n^|UPZ>kWO(suE?hP8AfIJvSTQ-5cT#%L z5m_2;+^Gd;8!xIpcNFt>aM>jjPkMN>7>kVxAa>|xzR#DU`)Y&|(FPhZIu9is8GP>L zMUVZD;@Zmyhu`qyl~pLS*TUmp>u7ei2A^8z!Hfmo)KPo_?<~%TkYT>m{zen(eJz67 zyLV8YE1|%;5Io-RqNknD;|ZfYcyQ61q*Zm8@-H8{-`h=d`(8l$qlNaB+i1$58g!QD z!`|N8d4FXMb`36sT~-IEu+v?fYf%DUBLb<&>>(N&mBHFo{Cjt`6=M_1Ai*z?f;v6K zHggVx%jbPGZ{aO0`X6g|0aaDkwtL*}?(TZ*PUN<>B8sipf!M8xt(1tAh?I(o1ug{z zR7AvP*#U~(g@}lXU3jj0K5NdG6Ym)3jB(yEe&g@w$D^>_d#|--tX<%sY1pgz`qmFu zw0egQ;(cR*9+`1fdyCI*KGX@Xk(^Olp~DfT%o#SiL(m@0zgD=(!eWXZHt?WUy~IA# zu+ua2%gv5!)LTRBUmtK~7zkQRnH*I#C?3eY@Uk)CrMULHVGVf)f=ejdS zTaX!QDwjS`uh`N>%XK@dUn17;`Jr zrk`Ft$6_sQeYojjgOPgEu>sndJbO$l8;#b(uWr)r9}F`kHn-M&lh$b~C+x$%jG?+) zxTm(nW1lHk6B|9W=pJo%-*D6Nr6cv3r2@6EyO^gdFjimjW~=sjIM$)P9sdn zJ7D^$L_wG*j?PYrXy0_1X>WPjp`}Qm>Rd zP`f%qGsTqYt%ppQpjCXZ%jEX4mws#XXl*whTem9~dac^ywOi*fUTR~hd)J(zrDg3k zjr6tD-M&o0dmx@awFl~}?VYqJf6eshx|QzH)n41vHQY3!!VtaRA2;pJtVmO>?!$D_ zy|hw~511w#9jXua_tdhmC-JYtQ2l)cPi^yv{iYvI!}YDle6@&}y{6JhL-b@ncP-b4 zXw!*bBlRuKaBnE=6G?qFN^jA6lST(4O~t}T=mq-tYYxRDFuy-sfAeL%HaGf^sjuaD z{mjdq+VaR~Q-<9neYfQSEuzt3Q`?c_^=J8aX}|X!H02pKNNUPaXjgU|GhJ|-rH`+2T6@wf&J-OpPyaLIl9uj#%rx0-wjQ$QjAm0Z)?^znPd`%h zlIBZsriK@1>Du1Y+V@4rO>KM6(rf$Rwck9(Q;Y`Ya9C?#5J<5UgmU!cCKZt$u4xFKC$0EZEyqZGtJpgzfon8R^daWsp!|i zx)$Z8#ZNt8`drppw+>jR`K*pG{YoFCKc4EUZ7j0ibSJ65KECQI&Bi^#RH(>6{eE{R z&2f`vI`^X=*2FH;?rg_+Z+={xT%E7ky}&qd_uhJHQyZ=K`UunD3%&GmVWYGkbHhw| zUiQ#8z3itw!|%6Fwa_iLjMrKW2{-i_(?|bhH$$5rve$HARZl(7pP^cNIeFN$Xzd97c$S}b8EZJ} zoEWY*GT)$mOF3xTuwsy2ZNX}7U$?`imZwMQ9bRnI!aw0N&ay`7pQdlpa+Nz|^6NKB zAC(fMSz5)K<}Mws-`wM?O*$WIntXetZvH4xTUGdosm!hsx?Klmh6L zpiMnuG7lN6-)SGBRe68NRCeJ|Ju1sXTQVxv6f$R+KCiyFcI(4o)5*$1^t*Z1YTG)- znjY9&>kVf5XaN?7Of}D0>ZR^a)u?ThY02ikdg_O{+6+9O7rPD8>w2u#TJ?=G<-6He z&zCY!YjrZ()Xd#NUzs&lTlsju$)>tV4^Hc^{VgAE`kmQJA2@Ne79P0Y^vk=a?$KqK zHpD&BWV&amuWC9?tI%VgX|6Nr$qn0S%f?5TMp$*#yA>y`{T0o0%dv}Y^6I3G-w;~2Nw95yA#4AjHpowb~cXw*3rI_zG1#Ii02b3_=D*TBsMb_(~_ubw{^Ua7d z{cO=i|I@gm7D0zi2Ww!wH(-KREFl{ADr1zL_0vDQF43&p9yKNG7^FAX zS8L0U$C}#BvC_=~?Xf?=)5OTcuBUo2peWzSGoyz%o7B>4`RdT)3(H z);W6B!@5?#@&VJ>b#wJ;7td=2R~|5#m7Js7tW3~CnnjxSf1ImZ?YN*NxF0ly9-gO% z4!Wd8HjXkS&R?L%H@K$VD0SHMy5xMlS+&brG(MB`^UVc%vA@@}!)GE*5!Ywyr{A5` zGJ0(@{hGN%pECS`w*McjkvO?h?^yP=)^}sDsr`_p`kG;nw33H5n#S&1teZvL(`xVA zW|~*XRUh0X*WRgJLQI!_xL{7?uePy1_A*bw`X&4Pdk@XoY|g%}e>VF+eVzQh?0=X1J??+|{p?@! z|N86y_GkXL-_QQ%XMe1+e|`2}|F@qv``2XuGqe9X3y%}a{(JvFf1Ul$&;ING_IG6e zdH>tj{NMas|LtqCKTop%dfxC5lAe6=C#in$c#_6sTp%_IPL^<0wk>od$^G|IVjgg9 z&>p4fo?XP6!eVD&NZLhGr}=wHnwK|?q*3N;NV<7Efuwh>?1_DV{Pn&mvG>0bI{`oLy;PcC zd_}A&9Q-yyID|(0zM$ClSV?Rmlzr$SltXKD+p84&b(Ew*m%5SkvgAEtsSvfsQ+aNd zMbfWMYf0K&I)bEYW~Yf=g?ssCE1lOQ5Ho|wPOp`~zORV|!H-VBMy;N3eO?N&!r~x zOZW#Z;BiFhappKl4~85gb|0oJ@f4<_{+TP4hLv4O+L{qc(&6#Dh#iFI&prw-&)~ghaI5!$76XyLghmU-BnuC|-|J-OjNj#Wo8j76ZA* zUsKMMw;}0cv#lfzF204>APDU8TL?f~ExRYQK;vpW7UI#~nUTt*uzMu!2-k@1ge#5% zh3jbY2wk{^`t5q5)OPEQ3(pXOl%V@ubU#QK=WL5R{YDp zAm#@#j;9sh#x}&(L&*kNLTS{zwyrq0979rFymv`~At#6hK*a$3j8FmMbNedor#O&g z8{UtkA*c5c8w!~VgN66#UHlucJHS7`r1f1xl0SY<76>0L#w*u{Z6S68cFj&wI)8sa z%na5>{Sv&l*Il@l>Pc3m(-``py z9t6DmqinTvA+`;EPU$K9K=YnDrBv8@nOJ$qxJt^p_(jBgVA}l8!Xz|*^dRLX&Tm*U z9K!d_`1?<7eo$!?5=X2tOxzWvWIw-pTXrk4bU0ciN%1W4hnNo}4lr~CyuEiu3Nm@dZI>XtN4wciSJva0!F(aC`UNHH$Rv`iycUoYcYi5KEgQBb)&}N>O;uJ|;eEqU z-7=A+c}=DhTL9PEI4CdA+Yx&K+0VUOh2AI0eD@n-X0WK=9A&fj6_S40_9vEWQh%Dd zGgz38K1+93BFYUX$^PC>VvAr@j-|qA)S|q-&=>W(u}!&i`x~*lV7K{~uo(4yA1L^v z*^enZ@O~@Ra(Y9oHq5I2SgCCLnWUbL4iGcJz@MSYjfhpml3;e%bYU)Pmho2Tj1H*i zsL1zYuD5@P;#Q?6F?UF9f#b3v>3M5nH=tYXAYTm7)ejJ4I=4Ez-N*|LWdID1vx|SD%}S@ zC)NXsXl_DL^mPYsbT`ERtHjnMl&RyD=p3b*A*mD~=@d?S90%K(DqR1q*a_ zu{6O2of>{nn1-H7k5DF+I7!SFuHd|xU4@D}y@X1rJii@+^V|D1ZYp&{R}-rTm*4jl zuAsB7CJHmrgX1^Pt_YZXt@aG!9JoX&3~Nwc3#EDXl{KB_FS z_8@6XuP-FoI0cf_>B$t5e7Y?mwjR#4%2I5jj+1mW{SC2W&<*1T((0u*iLHf=bsq?u z(2KRBg$wA2Zf?RTbalXbW#Y|#B;A|;o!EVdZtS28`E!k=g*l#*)VBU(VjZAs=2K+{ z#u``%M1BtxqR@W^?GPHFHw$ROE%ZrNh(g1+lJq?7H%VXc9FvlMo+Wk@e&@0gexbo< zrYHwyn-PnGtC#O74cohuw89icY&qPyKS%j`Aeq=V$bPJx7c$AG(bHp1!YOo?*8t^!;~!%C!F9wn z1v?vvwS(f}$x6lIBZ*apCD8|zS_unD3U3lYY%grAcSYEQwl4NSk>fF3+ugl|NvJ;e zk21F6ZDM1<&U&`65G`OoKv_KX0yv}p%OI)wLG#_zX_S7OY;Fz#6pu?gT8fiVpTgzT^PQ{B=@N}qC_r0#hkKvpW*A2YFu1?YAjd+0!S0m~Mzlc2ruizg_M#p8u-a|CTJy{Ga2pb^GN3S3KBqXBs zr(96Z4SGq^V2mfTL6H6R`(o5fV$Z=U(^}|`&S?6SovHxrRwm-ytAa)YQz#$Ii);_Q7?P*Pt z9LwYu*?^B|G33J>1Ir6>cYT!77#Ed-Fh<5ULdKm(!aH>3(+|qN=vyQ`88VF6Q}D%n z3FG;br#P3B+SD0HtRw9I*>BI{bXJx(?o85WyPm{8L2x5)9g&=;WtdTv%)t+hQl_8VOl%fJJbJFAo;X8Ndh9o1@1S+lP$knF^O*1nnpD8N5;THN-?s^7=$9sa zl&P0Dl5`d0RE)=~#>|XVj{i7H>;xRxFkkt&{3x-nFn)J{Faa%b*Ig)uzQJ*YrNW9S zCxumL_Txe)jLS0~pSLo@aS-~0{(7l$cKZ)vXCVLg^+F+ZUMCkNY`HJ7Q0QnLqqM0T zM$*7*3y2MdoArE!TWCM8yFy=7pC71XAEVCxS`KmgNo+UBF*$DbaqJ5V?-08PsS~dW zZ_o#2W+>UmyGlKIL98TvEdE5P|&Bh%GKdM zu{@B5IS$5i9sP=IRQ}1cpQOM2ClSjzU=lgK)RbQ-A4r;ZqXV%S@TbsjAq#D__Jq=> zXlG)Ua5`(7^0U};lFF~TO467|Pe=;xgt>m$42dhYD0voQuE5Yd*C}ExA@Jb`Aqeen zpDGMSi+1o;Mpw)rHU>70JuL*IdH<|aPTqb@>=;B%?JC5ersr5p@{lpiDolk<=pp3X*u9kJX2dWyc5~&`sm4l$O&T5NiuP69W{>7z4MmIS9Uhaz3v^@rFw zXcK=}XpKI)-a#4uJc6Wc3tp4t`TH9&cc@-o6RM%721E#F&{~y!m9d!@N$R%bJW0cg zg%BGFD<@wQ9MA_p9xF$Z!$=y4YY)cPAfF%N9LeC1=cx3!Vh3VRpvrT}9grkBzS`TwM(u1FCNOFI< zo}_=q;r+^Rrf)Bj{`9*?(w(0jNt!tJ1xXvMmytAo&|H!VEsP~r1iBTtpzwIBbOrMh zQt0|vVqp-3V*uL-+0R4L-N%sB^Vu+By&(Jbb@s7^EQ|}V->`q=N8tdPeSY>>-~y7i zMq;c0wn3YN|FLM&V3MX!A4pOYoQp6%CwVf*O?lk>7qO?%!aP%Gi5?xeS2@(jome#d z4ty>AMQ`D_#%@EgyPcJpzRn~$TZNI7a9{^X>&@2^^MzrJmMIq(zQFPGUj=>-Bvufr z4t_0ELw9Gk6++R5dy=`La5oEcLJefLv|^XK71lJ1=d)s7TnN^ z1F(JtD#7X)2j#(lp(J&7PbSs{+NR)I$xyd_Z({Y}_URM7Ji3l|MhY)T<+(1`N^;F8`I!UZ7EX47H*+JoyZ9)-rK%XPRK(yd?C{} zF+u4SwToC!xLD$~a2efI`H51@b{nzc;CStt@-8u$SOz4G`&S}bAUs_OTbfK#75@b! zx%@MhqyhUhVnd*RuK#!!>_bw1vovA_;C${+!bSAKg9s)2&mj%91e(MWmb(MX@T;bP&iHclf%dOVcx~LVBARlwRSdCfka}{n(xb>lVm+br`-jS|tQeAb{VU_KsWR7( zDcRRejc;|E*aYA)J1Gt0Q;f%}S`BQibZYBDQu_vHiFJT>S>DRa?@=TjNSaMj9{bZI zm5IDa(x-GAVwn)NE?S60v#&$@vHc*iKM;XA8^&`tGXth5Y3?b+UW4@uS7A8XVcBWr z^tmx4Rc(BhSaqmB<-0O-TU%l?Ap7;czTTfCTm3$*1w7 zS$Bx_g&)U$DYK8e5Ss({aZbi~>>;E4JK+QByJ)O(X8Svgul$SGiAuqrS`pg<8MW6b z%TqInt$?GK#tQLhP{mV3_CcbSYB%!(2 z%@FdSW#)7d%A$D^1_*i4xpmhoe9bTA`F)L8Uik3xjqo15u?O=nhHo{uleDjE21y-m zVJ(iKi**t)0-uR5g!O1_UQ){2M3Ho;xg)U{@Y|WCY;U5Ilo#vFr9n6^VSIja@IBUv z8{}FTZppRBg)*q0WxO%~>*b_oSOXyiHMSwP5z?N17T%)6iyjk3qQQeUDL02=p90(f zTa1S@9usd?x2@0uU4pgI%pMZ3#zy*|)}kBpLOeH=iTPmm37VI_r)N4z z8PC7Z?YK>thyM9|Tv?WUk=SxDRUa($LJvnB5)PuCxk|x%8K+G17O&KkmKx<9fBGg8^j~ga*L$_>tAZ$hDoDcW) z!%spgstqv{!qH0o?<-BcgGgGtES#joL}!vVJj)8MXSv3MwX&RRKe5YH1s%ZLdio&Ix{Q3R@ousN^n}}6| z>0eGOyYMmBwqHm4n+@vm#|*&(I#{I?|BFk4P$u{Vl9CY{1wY>-l8uy2BSgWu(q0 z+(G`_74R6yH4j`fjBQH(I9Fgn&=CLDk{{-brD^ZNNRoR8(lM?civ0yr_V;A77ww6e zgDb|+q=BdR5E}#;*rUbL!4Ch%QX^bTv&Qfpdyu3&^RAPWv;Jpdxu9(^j1wDpPXe0< z3vtfG_}s|@dm)$)+?s;(Qb-03*CZ?)F5sG3I*)yS>>Om@r@(tB*lM_nJq%3jX~5cu zYliG=1LT~0Jm%ap^N$xkp}c26I^y-2SPV469tPGJUQHq;9BW6U(HP^EDq+ol6z`Ts zQd<5u#M0p-_5iR?@CbVe*mH2l{s+eUAhMrN*1{Mis|oV_i!0aHad|$E*@K)@<7Q%g zixi9XEmA+MOJP>fA8VVX?CaC+;_cEN zkQe(aSbpe%{TGrQu45%%>|2pa;CLeKjGaMj2UNj1w$u*ucC0;o#(o^h4A+TL_PMho zSbN0cplbbpRYS9nJ1sFEOcIarNf+?CW*1??h*!dR)HLO|5{@;~Y#(&NT&*;wxjV73 zuqm;%a^b>mVi)1D{Viq4D6JH0L-wu57|FjPn;$0@0T<8q6E2~#Bd;nC z*Zd^*0KAXA6+F>TX1+?vb#5f(U!s#Vs!Ik*zZ-ZH%K~TnuYxODsP|)~yhAiegK;ci zgP;S}Q!-vx`MCcx;R$-!H%mB#&cu7E#E-AkI=vmSHV|5PjgtHOM`Af)>ZL1+--^q` z{K2{R2*CwycP&ilh$d#>SYdd)@Ha`rtKsoCl%6y9KojF%PIPmXsNRj>M+JsPoCfXtb~QMrF#+$s}zI@+8SB zb~LfUVBP$NGU-GVF>P|3l3=4 zS%ZZx=!6n01sgQ;*=ps~$Da6JdeUha>a$2Gw|W;zcDBce*~1$@Zy^nBTxFHe0`2o| zo?wYq{(fJmg3b)XxG2nkR}D5QxywBumJ3Fio(dz;n3Wi3G8~DtCl&`^Uq4ey{Mt^^ z$0%pVwPy7q*!selAL-mi;E_^h-QP z3_q=3lGJ(D43f4@2_|Wn|6XE4VORMZN|W1vh&6>A6}*%w)9(|T3VADQO8T~kq^xwN zba)4Im+e#P6f=>O6nBVNB9!vQJuwW|e&O2D@L}s)lJb8#ORNBVfBs9Uaep*PC1=bb zRtj2wnXF7bg=-^&TmQ!-Syx$2QnbxqlKQ<1B`NTj2T3JD@O(Dpdw+(cx8C-|(xIB$ z9wowKF0uV^z&1)5aq=9okuYa?tS}c1%!9obumN&(j~24JMbq<*c)l5?&i+emGPu5Y zsC-|J`)?RdU@k;jXuqA9JtWTaRtDEOOKcE){pXl6$=iz9RLBa+RC>*MPpl{GY`IU^ zfyUA`1z>D+fG{47X@z@Sz+w0^ZIY0Mnr)dbbV9QZ^il5D>_qG#)Y^!#O~atYP9%-l zZb57;l*qtyz_9kiB9eAbnnf%OS~c_%TBDT?-c#zG3@2&XEIc*_`wX048QKPTlhnS{ zLy|r%x=GTUi)V?=hT@sCl=TZQ67z+7PX{S+YtNGO2K$AT3_E%QX|N`8wBU+bxn&A{ z(FN6a2#Zkb(c!{yw59odp*4CXeYo_w@EG0Zy+_!JHucAQiD8fSlcXHSQbJJ@>mr(zWdyiCuvemtF}g(X~I0D0Xj; zlC(1O1WA0qDrr%rcw¬Iuvln-D=P48Hhe2w%~f9*cxpsLhCvip%{kBt2b(V~t^4 zi5JAi!^Wu_mAt>c5X%SixB4nAuoi^znvk!P-U*-4ReKH!4(RTkzRJzyV4TzbYwJvJ zVq4%=<`(7N=y$~KL$#Jpio;Z_Uo|8aIYZKsG@REPe8c|`^MiW*T@`s>so%K2RH=uFZq`y^s>VC4Cy%7*cl#Qb1e>RDksIY{lO$fH}=Fn<$wLivLN;yIyyZT%+RZe2Zd{B>13QQ7`#?R5c7tZ z*RHEd-`@HY2m35 zVs>z$RFu-Y%Wz_rP`z7>Py@}sMHBL&MKiG0zz{I(GD$g)w<4+O3QLk^?292b3yzM( z+DJGC7GtA@KIr*wk&0869WiHkS!b8<98GP1RY*ZkM{ZCqmBe+8;rR`BlBRY#L{iHh z8%e6w%Y~$>KDaNQA%6B_l16mK`G#S}B7FZa6A~BpQ#K`IojGiVmQS#z9$LdBv%ZS| zdrM*g(71%H&=j3Dqpgy;_b0K>pktkuja-d)(I!%)tD2tl~538A*Y*p2UJ+n;p*W4ZV8@5wnB>D{+50!>!)yiQR^L&9@1K z&|;(%PL{h`E8h z&*3ZF=g_ruqEhPeP?F3&eMu^4iFKk-0IqbMtT_GMgn8h9J$^Ejr1uM!5X*!s`*DtA z7~Tf=_b|9S_!9Gg5%tdtBT@VQX2N1Lqbl~+8PYC&A*tikuOwM_eL`$F&rkbv4duPj(}g0F(V+3sccuuW`Kzq2M!bnNl)vC`pr>o+3$}YjB^G zx~+uWaV4osv!^88-}{W%LrD7_Dx{*X-k%U&qMPZpunDysig5S+ zI26FVJgkBVD|-v$(S^luon`P`_k*M&8)jm^@V`2rjU(0#_CLC z2bEPCH7rZ4AvoR+HJ4u0{%Fpg!()#OrLFTObJhknwaY zm3X@GBz10+hnN|R-21~^YX39MoSDIgVUHE_p~>c~8=PMJ zQ#gbE{nmn57F?cu*_>U10>AK>LVh?u{b{8JZ zsVO`}=am|y%&6@|(w#4PNLt%*F)?>ocz>o~hg!JL6D-m5QD}=MrQ_e< zkk+*ru{SWbO0O1Oq@d5G&#*a~K?@R~Mw zCY2&-cPBiD4KHnjNb2a1ztb?_EXHhM5ERX~L2<0Vk(dK4Ux&xl5K=ZbNeMG?j51U! z-i@T0HcliBu)w{-46{f0kd*3Cl%xl_@{_c#C$5RW2hxTv6yBm4wl2a4w0nn|%I1=- zh;4$a&Xa{}=*Vf~g;8i~iDJSV^j>4!qsb8XdpR*bSTt{qV2@5~+eVmy+CRbCAH%-u zvq{Rc!iiWum~7>##B?r3Qt6RvNjj9TK1puNok^;xcOzB<{Bkx|Jen>e<^%P1;sEsvAa-j2L3L?Nk?Cj zI^U>5tRpn3gnKg>&Ocd8(%>u3#D+lQ-sOZQ=$=`)2ZG^Tl@-J;z@RVdgdylZZUI75 zbk)}df)l#6a)0G&R1RX-V0Z~%#s9r(2U$*efqdr=Q^-S#S!j*tJwDzAr+o5?JP{C-g&NL88U>J z25-nwDG-Uz2!MjHKBAeh0d?Mu@g#78*w_Y2?h(_7<%4&3aIRvo?^Bbcc4=6LWmr0Y z7)hs3H6eBeF4|NOE}_M8`3c2Q%Myi!-e|EaHI!ysElIK}<3LK~E@Wjed)kgzX9(NW zL2(UVN76@J3$skf(-r&I3=>DSAW7RjnAjeevfo>nj_$2%CWNC$p4kbp=&n-O>u=Dm zZy>e@az1qsa-lQgstB`Cx7_xEE9#DQcG7@{BS{+V--M*5VarKcQQni-N=RKcN=QTB zm0cucpm$;iD*h|W6AOStgBBo)+?S+K3%srk8@?$MbY(f*;`ghA-j z(QB3bzD~sQ!Jx?;&$?W;U|Sc9a7BQYOjh$uRY zSU9xYTR|E5&6lJZ)z*>J_@@O)S#xl|aYLVb<|I9g#ba-voz+QlZi%(FhD}c@k~Fgm z_Nc-v=()1C&#Pr z&RU@{8a;2La0m_Y?XUE(@F!`ampd^Vus??L8CV2`Vld8Q7&dY}Nkd<+BQ^wf_0K1S zqTN@|61t(jZ<-40(MG$L360UKmsTl*%Qhr71bUSY5PG6r26s^Qe;!7X?R$4(6QNW+ zH=!hYx3jM@*s%n$AyDK#9xFrZE*NuzHeluKDfC4@HN@BvWWvP;&4u%5ji%j|-L>)( z+XYpd6c?(Y?FLp>p8FIc$zd(VLJaj^k0Yt|p^79W^e9WxrLikX%Gz3iq)7XDB>nNM zNGyj}MJjSLuhMehB$9qkUrthN*X~$v+@0cJZt`?xPrDk#!XQs$e3lL5hx#q?JU9IK zR+gkM2XLNa2>(-nq+uB*Vk5vd)K=*?yFRi0&}9E|p((1DZ}uMqxtQL#erq95kg-ycRME`FB-E2YbFitI=3d)7HoHWDARB*%lMpj?wGv7 zJhX<5i%=V#yriO%au(OShE`uI5o-%g1Ih_a&_b_V6sPwKNZK|P=RXhvIf}GW9?r&C zilMbdE0RitWBlH*=o&ts0+vGaMz+d7^_CH92!ZZ67lk0`J{n_OhBl`iNV+owQGr+sh#W^kG#@`?Y66!2d-sf3Q(zLt%h)stg zv#TrJw-+GR15$H432A7YE9NHPD7;udLP$Z=7C9=xHeMv73eeIEBd24Bc*i*?cP5gaY;1Sd4< z+B)GTdb$kORKO`HoVr>lg1RPk6|occDhcsTNqWE2h1dtE7CTDWeF>la2cgiQqMuUjm?KGL z-eS$Lp`=@FVr9Ur?lhqz>VF;QIp7DD*Xk%|7T{XnklMl#pOb=d2k=b7{DfinEsT8` zK9yQS>@zfuX)ZKHXXL@Pvmq`OpMhd%P@pNXe_+xOPhm3ZFbl^WL#LZq^9g3KJ++Du zg3ipjUYLUhjSW(K4&gOrXgx3oNvVS|_HKBTV<@r55HM+l;E#TabQM0M{g2_j9|pkZ zAB~micGw$Xs1oNz(xGx2iA6&&?qMZ)TaG8`SQO6v442-xlhp5%CrMM+;r=a#szpZ< zs|=3rMFl7H#7cW14$T>Zb2IpRcoNnq;Qlj^0H^-Jb)4aT@=TH*;60o1d-tNs{>qFf zT#vv^;QwCQ&=GT0hOFlvB-IIBM65Pk7#FB)vhpIf87f%RRg!+;b9>+#tQogXa7BN7 zogjQi6Q5L4+P0}olBt&&v7V5SzEp`Xww@%r%Ns~KdK|}DI0k1E)+kpB;QG|C$pzO+ zhUlEQf4gDgaf~B@EhPTaMo2<)eaWG?l{I%vg< z^@K{OYq*`@f(CxaI0FR11_%86f*%w}sVWpiTkpZzc*E^+)kt!?hp{Dti!bIt4P6Uh z>;<|&<+Krst3N(>#*l*bF;ec|ZHX0tk8evVH!P{#`6U}fNqZIr;h*(khde%>AkTH%}ec1cOPpMa+G)d>Klp}T?(*9s>4$|SC zGuBSSU8w%CxKIO4X^3l8gZE^-_6>VHI}i(n+xKwYZP@>EElCTOtR^-eoUdd27F@vR zK~rHpI(rx9qYYo}){xY&yCt!vkas%nRSWqbV7a>z?TzP@A?PFi{S6N3^GPc7J}zm6xS$*%tg4SF^ns+mZUFfrAfNB7V}MpdUJXbs}BoTW6vYlLA_wi@fl1N3X=2= z*Xt|;iY8$$7>Yru1GSW1bpnZ5z`gIQmD*o=5UT@+$~q`lnqV!E!LA|xe#6ykSXX0+ z3&u5#;dz}pBsEVePtuLjRY-alhtKDQ40vkMS$KxJb#JJAzimV82c+2Gd1z>kF+6E) zw~{2y8q=THOc?4sMhV)7IWm?AV{!4Jb4X*Xf4E-S8QLhAJK-NlKoD`5?ovUAV@Ap^&3Au1ySEic}_P zVy{WWY{7aI_VU1RSaEWmuoCSORb6Rei}PqhvqjB`HH9EQjAt6;dJXQaD>y$lSY5>R zxMAJ{e8wNlg{k{nDPFM~h{9czIg1cq+I<8PSX74HEs59SQUJ-Q4na(fbM37!6N z7CNG{F18V7qTPStGXSewB32i6m`_)ttm=|f=_bbJ4av=YNLu4)Pf|#p zsw9;uk2x8Gb1r<|F06rKxISfkof?vFy08OnJ04>OhWak9BsH&#>qJ9J_b$XW+$z)Z4SP!tQ=_&L@OWe*U6hmLG^iW!l!}-451zKO7M`OeMy(Nwqm4^pEju)YE54P4>u8IPc&{*2ZQ6jO(iyc#YFukM zNjI=xMmpYVEJ;;cc#{4AIx#U9_a3hu@M80Z%V5Q)+go&^HcH&bI~5P-IPDO zY)RT(!j)JkJo+Yg(*nVe)22!sSkxRRO40SQPa5W)?C1Ox$k{5Dki~nUGuF85rg@5BG5FxRttuZvp12yeJsQW2!?9lf=(xLE=X1cGeQ3IsVV~?Pu!3D(wJ>o zrRaQLk*WxO04s|URj!77u)R{{0mz4H2dF#@sqYsq#=hZ8AMB-aIb>s2V~i)(V63ZA zav1B^8oM4xKL~CBbR)(pfPrgwBmWwinadPGcaW3aKSs|_`YJm6%u^JdZAaHAI*+Y@ zZIZ^IhcXmF33vdyW`WQ-?_81*t>Bq_^syS}dR>L@ zc0v~;+lcX`L?K z-aJ6159G$lZj~*N8%E;!XnfRjm?Ag@_MVbeZh{;+4Rc0N3GS`JcOk(2;DIBvW4v*1 zjUspp{N?_H7>`a{s0bbb_ncf8qay{nER8#^#ord!P~Kgk==h%RqUhXH9#wRH{poT= z@C$ghachi$@h(MYWyuIdN32!oJd+RIm&OatSQ7*%0Bu^V^4rG6%6)GPkCFTP3PsQd zj2VHwhhQvtCKdLf8gq&+Q*>JTV0^FPnZHgE6oVJXEme6L@`)7eQ36ka{9mt*aq`<@ zMerIpaKxapAM*CR3sjCkzR%!FizGuQG|K1#*|~QxzQMYyiC!l*cwy><>1S%*xRYm|BDnw z&=36We&|rZo8X6Yqg1|!ymC-QjA4iI4MmO0XNM>{KODt3?KOM{FINP0V8?^l+X!}o z$>fMJqWfk=PzfH+x=Q5{$d^wQ#rV553*URmQr-k_bt{Xp;zg{FgXLh>D`;~xj1y7E zfEoN|z}{qy=Z2>%f)gM)IZmYuP3wu0#=- z!PmVorqWoGJ5tdZc*CWNpg)*jg0*rD+s#;O)_7>^Rf^yda1OdSojJ8#6rFCjlq)*F zmaS2AhPb*bf}!BI`(f9rp^uA&y!Nw=G0M9@cc`)5utX8;0KcvCsQeCT{X6sn8prZr z3#XB(#49@9veAm*Vo>5o|En==X_X?F39@UkA6DbXl~}{kDE+#dA}9ktzK|ND=I2~R zPz~1X+^BL5^TmpepOeGEcoCv1q3IkR06bO({NER`rE-90|Wj7Rz_g6Tl$ zc6H2#<%*8GeX*j`uN?L>U;waP3%fOqB|EY2Potz`siM=64;urG+DgppH8#wH?YG8` z>#%O3ap14mE2gov6yLznsQ4OxzX_Cseji|N2>OF%@iSGHLJmHO?|o?;J&iSMa2GgV zN4Mpot%{EQDfCMki*D5;aD)2p3jr5s{qO;{y*wSho>nK-rX1{^I zxdY|^xwdPJQFg1M6aBqb5p;l=O_*nBWEIX=bdL8&+pJOKTBqoIIwz_KJ_koO<-{0y zGuF016&Nt=Cx-2c z;A8Oi;HfI_LLLvG+-lr=WjxxJPF_i!s0dyL&Z{p}=>kb-uokZ28=j^J>Oj@ft7D|B zxmwZ5`s=ldP8#$%0-@6x|BtZB1ju*Jz`j)D$oF_Y8ap$W;+uh;to#MG&0rPy+YYRu zXjFbxtLSuFc#$IL4)i@bLS8#NUu8Yyf!~*_?1QwrgDN)2SI?nc(3sw|Q4!1p%NFLw z$np161lfRILEY5Y*LQ`YQ*kfW!ZflK^ffvc<2;Rrf4EW+JOFAhhMkwj8$Ge6q!E9+ zNf9`}{MG2AHR@JwR|Jh<=rrtu)A$DK)B>?y{m9SW7~RL_DLR|qzFZM(0Vh&0R@Io^ zWuYRN0ah#hV~oPsR3OHvP8qh88vUWy5(wSa;Xa#Vys^rl=sf9$eH3^M%sMk##S3{& z$5k=bZS*OE^LFMg(m2$JJrEib>g|eP zBFNs0xw6LL$A>67$0xTdI#0ZW{A=9!Y>6V+1O9%+V3ju@mu|;+11te!mq53s(XSi! zk!w7BVuhmf(bsW`PO%SjAdTGTu+|6ifcXOKZP)mG_%cQC1$b=8Xq6`*4;7eVY`3G$ z)L2)!NfE3E{d2M3S!4AHd?ypE1mjKzt)6`dLGIf`H=C|-_du2Gmoiq4f+ z+7-c4V5r7727nQKk^YgL)eh%-2R|d(K)_vsUo-+ zte%ZFPvgbWOB9{>mwPAzJLullS0xK_LIreR8b5!FeS8{oXCes@?bQRC)!O^VK; zH(M0J&7kM}gc!G#WGjNh;KQGDVw^dNI-#-e4cGvH{UB6>ef}T}`i#f=zQ+A`V&8_w zsK4hZg3(~zUkAkKH)oZib96Y?Ks8o7QGdbJATJYkXrM1x``dyT$L6k61b2gpz0m$? zTsO9hBG?F;ucsJ49ABgez6a68Sohbs@?o?Y8b$k>6hR3{JGMr}33SI<1A8Jg`oFvif8$^k{>H&7<)w{0?$W}#A2ky#%O%XT--uPf}jOC|choW)uoj!a=v6EkWW4^C3spT3)Pz^3VmLKDz zWxW-hi{=hgbneUOtLXH~y;#xtv>~GCe6r7`2tEeo2VqOE@#6^CIcPjH0eUlyBW~E} zY7FTDyFpL}vcF1*arUE;ir^ghZ5Q+s8fWa7_h}sZ0)3yxj)$*Mbh75RD}wG|;!F6u z3>vMi)rwBnhH^z`&I^kbK?9gsiLs={3i(<^=gf}l6u~(#ZER(XdmqCXTw~GM)r#OU z@bo*E#hCi>d`0K{HIyGe@F_Z*uEPF$4cl+nQv%|_KjH?coP#`g2H(a3hk$(Sni#qb zsgULESt=Ef6K3{S83)-mrhAOv6znqwzk>CbVjn-)05;FSH^DS+88}rD90pUrzcNN( z?j%JJ1lyk+r?L(5hYwMw!1v$-thEWmdfVXkNh+m~SGbiJw|jdjI=8mqnF*Nd?9jNF$e_))V^W+`a2LYY} zkLVnyfi+cqnLr@+0?)eD5q-Z22*(E~YfYmakR> zb>Kkx6qWsu2j9njWDV!baf;5TXKjk$6Y$jOtt!t!Zv7VDQv};UQ4{vdfI`rmS)vkz zyz5bv1&urKt!=@bU{e>=S&cXE#@It6@A9h@K`!|HP`V1;oUUBA593UYiHFfPfhl12 zwZ0fDSFFdr;Pu!Syk7Zy(ls&8y^6L+V*u=&1j62_*Bkv+dP80vK|cvrgUdcgJESo& z6aAvbzAjjo)L8#4#?czhS1eI~YW#)0oRSk5%~v zGHnC;O5g-D?}H7Y#>h3;(+8@+tSI&cfQ!L(>+tsiG%mgcdj>Uz++3{)hJwvUT`_)~ z27Rx_tEI5h&=595I$zd8=cjS&PteV39B6<&1vm)C+IzJLr#4fHf|c9_D25*J^{B$*yjR{0O!}+RMH`bv|gez6!QE% zjPVCxF9aMQ@g;mO5hR1xeCt(CLcTZA6629i@y!p78~RLCbT(M<_qf4zp!sIJUyW16 z<%-}FFl!Cw{2I?!6)J)kz=zrRPPNWh>@U_>G_p<6S%2qBMdxcL?07Zi&Bj<%<68ep zMX(;U&&S`Z(ztlzrHW41pZh2})xWO8e)&#{7C`?D3c*^%r?MWhf7&ROJjkm~J7V1Q z$|Z`9)x81wqE24h&`r^)Y(hJ%ai9Zsz8bGUH=y(CD%d${ocTw8MQ{$xX~p;3HJ*C4 zPSH8B)34}^J9?oa7z;8-<*Iapw5*1XTH~sb9g1KTm}wuSauKBQmSz#uRu4oY{jt{u*Ed8SPfi~(iqOJaC8 zc2NX#K<(9iRcas~{bZEN6OeblkNvzFx8~F;f}25ICH@Ak#@^CFiq2wuvO{nMSod9( z$~BN}cMXc+I^0DO^WJ2LL;`>7gkq2OuY2fw_qWY5%^Fixq+X`#;Mw%Inui5AFVL)dMdKxuS8`?vEeV zrD;}5VV?sVhF+R-WYh6Er|$nwI%$NzM_9oyA^e+vIH?aQlL*6dX} zkKgyFd=3z~0zmMp@b*Y_i7Wu$GRmSoobp}!paxS=5`_2Cle*SL} z=WAx1GR+%EhCx(!G^HEmFj&h{;;pcAB_fD zn<7*d4z)(9Effhv1EE$5`x*l65yE96ZT|XbV7{MlohCn03^X-IsW#L`b)ojwh7qIa zEK$LvmR7_GNBrXgQSTr+8&4sGc!R!$xOy;DKiA(tE$vZ%t3MK<@K!QhPHpw=k!Yx8 ze1G~etI`+s5j6)I{N6yT7q`^p_jaIT3UyFx$lKr#;-*OCB+wW@f*oYEQ{AXwsLmJs zg$#ZgG0hi_Brrn?EsZX0^H0RR4WXhb(FN%wRnR}86%F%!t@Zwfis~_5cW;uqR`;f} zlCLdLQ{U`w@kQ`xLJjTpQ45_jw)w-+fImW`7dC`_wf+Us_OL&a!@e=j#jSM&8t@Rj z^8@~lwoo|gon|4aAHD8%;Yqgz1NFXWC>%$nUY9$b(mkLM6vb0=aU4sk-bc2#DKsL~ z(h_R@ovdA_{6w^dnMN?1lSw^jcXcQd9T5tK!lUYW-`1v?jAhdM&EZgsFB+(?sPl)z zzH7L>7riq)7z(viH!qCfiox#m-~?YZ>Yr4130_q<^56oexnmL01(l&j7iCQdEu{&= zgYDt2w77Qu#84pOchb*1)QVeg8x!^|oZ=6(Hv7T~r;n(%(qGr!)WR*p$&o=c2R9!I zwy&aZBnsgThw+X^1OshTe63CXr=_J73ZsDe8%}dtARR3WM;DaU`ReC3g%3#Al|@4B z;d*~rbRn0`R51YscR6PCdZVSoJ* zl4p{mjN&_Lk<|&lHV?U?Wx;^#tM}oxl^Ln6p{xPLc8Z-XnU8wW+87MXk_=zd9c|IF z7TOPHsk%C_z#r^o_;?Dg9cmr9pbg2lMhDQ*aJ0Dsp*wtnJR$pDv-{2zCi?lS-hS%c@j(Ce4 zCn=5+KO|*EYBo_K zy<(V5m7x~@3>Kya)MmfiMBhpt3beMhMbwmDfc5ZL7HSH`AH? zI$X>f47ARr>5ZXq3+3k*;D2SPzP$x+AyR2D}NO^g(@`I~%^_DFst(9$04 zYLt_xOFstZAk2?rtt0XX^Xkp|puBT6W$e}opyBiE$1Nuy=iPOh?0 zSdt75I%|xEeXWro-V;?%FPhLEj0VD?=yQg7ZOt@uWaWq&^AA>-G%x zx?RnSyk2jy+v9yko?I7dSV$L8lFLL%c<4zU6YVaf=4iAnQdUs#uEZ`hy9U;Wy6~Ln zz^SHli70gWk-~xPk%1llNOYhl-`C<>6l(Q#MDpuHEd>?d)5b9opRc~4INxoh-8Fb` zp>U*NQu`Bfc>(evlj8{4Sbrux#n+=f4m1o$4wi5!g*Ku22nHg!LJIX*kVLFJgr@f$ z^9OjzW#}*F`xlIE4+bmA(VcivrN91GV?n4jm)J{Dl+o6vpnrlt(ws%?j8q>CMVnEn z&>ExcP%zN2O=65Kp(<3LhOr?h-Zl+FiAW;ZB&iR<^$e#}iQ*|0&EHjM_I*J#X-F-J zhD-@X;o@frm8kyxbz#46ZdC{^#6`rCX8GIKzjd;X-FfZGkpF%A~*ML96T{H%@3Z zB{W?~)n)U2;Xp5AR#|wfw9|`P;rAk>JKflTCK?@Apdpjk74!Ygf%>4oJIUC}IWOXk zhS~!43h}w*c6%$Q()=-%Q~bULe;OrCn?wdDSx!j_-rW+1`Nb%Iv>Ls1wJ+M7LQhts z{}iohZJ>T`D)9%{9Gq7ZXxU{mq*L{jNj07kFG_tEL{n%DUWk#xey?v)D`L{kk3mXXZyAvx+s;0;For)`EO;~XdCc)EO^QyvlMq?Vr%V_lzs9h>YTUo!~;&4;ahAHi>lkkkuN>T-d+M_0OyMKYd zeo}ihfp~Ge^d+$+Ty9`&fswXwgWD`Evq(LO#!{~_t(lb7>_2J2HA~PXk0p9rO7+j9 zDHtk5eb<{(BdL_oXlI6aN{F80GKN*Jn&bB1tEhu?z0Lx|ED5R6ZPSXN5z~ zpk-|fiYnTpp`gtsji4s{stkm4Ncu&lJ%*HE8u7u_it!kPy-m^(DsOFXneweUC6Y_7 z_O^zV5~W(C9AYMlPHJq#&AIxJ39W}ag~;@?)i4x;m^@m92ZTD&G?}DSvQAOm8sQph zsb-Ns9IE~@acV`l#osW4>=|UZSas`#n_8G9@yQZ2D3S1X>?5IkJemCbqYnw3)k8 zAu{Wc zY8)}9wJ~(J!H(xN*)$o=Lx=B)ID0nD@s9U5Myno@<>w9YIg~IZ!{F#eHX23Q6C-w` zV>ro<9%SOr67piA+2nZB$l?P;{m3(A)bKc~qYE>zZ^>KfZ;LkPp`HGT91AI#^(PF; z94LYDmy)T9Q(>a9hk>`rf33kVtQ7;i@xD3?bmjC&7fPso&BA(1(hN=~Y}x)$M3%4O z$@42xeJA%RAjjbg4a|{-St~ zcRGD+s`UnOV>U_%-_DchEk+4kiX(mpEvv_Pt_|-tFFB#{4%-N z<7rf!2%{bzgUp1_kmd0{Z;`&2q{%W*AwzC7!!(h{kr|EqFv=Ra;GI-=DD2HirKi*5Qz_AXg5vr? zyh=8-Pj3h}VbBgCdX%Q3ns^oyUXboM`l6A{1N(`weYCME80zqchx;3@WhNBCQq{eM zj0u$GcD+O*>?IKvS5DpB<-{H!lZ)7K^}sRV#vP^p?!illd705gaaT}R&+RJRJotG# z@lDL+6&^i2ZW6`)N^uh?Zal?}qqv`l{Ya0F@`dX#IUMe5in!k-b0V>~NWug4jxf$c z4~*{JJ)K04#eB4TbO>#M*EQHXZ9;NRYqTflcs5hSLt-Oo{e(~?f|*iXXcI&0!*jUN zL2Nq-cckiOGvWV}Yh6LSD>rr*hcJ4yb`W=Ryglna;$1|z@TBOTByK>+5VF2Y)>5** zP1d)FUC+>JvcHqB+J~YNbs1s9{x;!S z1`|&($hE}h8AY^*NJhv5YUKM>_qcE^_mCw-(iA53C25j4(b|tJuMj`Y5C zu!WLKEmZDy(U_~c(wJWBt3ts5N^3>^GdT&>Z<+UuM+uG46wI;=bhIYW)Ec3h3EtuU zhq7b~C3uo)`-m_~Wrr^~*ADdn9!xh?dyr5ZPfIGp(6C(STUaDp9dxO;CKzh-H$a!s zg$mp*CwiqSlGzqA1xXr3>_&=5VLv2X+Z`m0q#h+}Na`^t4bEUV>7{8D_a4RljWXOX zf~UYk;2v-U900q(7E!=6JXf*|&py=6fueK^@4vH|tTV_uovas!ZU7dl%M)qO>{{54_^*=Vec zmzr4TinE}$3?cNX)SXOalpHxA@z>*WBi_-J9q~R!RGr~Md*ETx2Xf)?(1JnYLadCW z1nTP@?jmv!ruIu~!@fu}8Wf4iMI@tLG&9jUzM{5~uT#RPYr538j>6c(e-j=s$q^DA zFxtBUVjDzz=l0eFZtZ6qOtO=BIc-FGk?MfI-rp|n)s{{CLXPf>{~+NfZy{qP@qbEY zgy7cUmN4XtdsH`Hb^8gIN!-+^#)O}Vb8WYv=lGhqB%2Gx4{nl?iW-U^-DDF&=c9_< zEt~N;@275s_fuwJCD|I7@OCTIWvAcfr*1{?o=0ZURQ1I3g2Z84Ep;nK%s-G>+^EJr zFW5GMx|Ja2dDyNZ+X`aKiG6F4`WPe|u^A-XTGh2MZX@nSM@?*p2r&&Mo-Ly0&bVMEzzQO~vI55zJ0vE`|u~Q^L8XG{PJZy*o#=Z^<=g{=zE_Zn!S09`EaDov_SG z7^2#V9aQW2Ez~x_7YL$2K#{W>MX8(U+PPbdg_>ltJb`WbRGoUZUHP(3hbS zA(tPj?kUwhO$pT}`;;%l1Yl}h9Lgw~W4zKc1`FohJ4m>@Rri4E-m1EHs_t>seMq?W zC&+#+ajVf>jQm&;5?@00CyB=!EuEeOqotP`lB9X;mlIDF@e>P2a*+gLJJn;W8PCu? z-E>cPBksaJmw1-ZlA}h>Ru9=3@1@7-qsGC}Pso0l**_w7GovC0y(NhTHo`;$JCqVG z^yk;r`r4?bd2FWX`qX(;6AkM`BjHRHVRXHXh5 zoykb@qT|KrhEDe9&twn=q0pp{6D~B4$sVNjtmyA)Izv!$Q6?0zX6ju+t21~zp=&Uv zQx`W1!r}~D0@-__j%A~+B%)#jFX;34TD^0Y_1 zW4lt{M4|P`@=(5;8BlzT#Bo1ajEB0KW+cK-K1Nq0Za`B3%{?Z6BgphVPxM~H>d^X+ zToCQTsHd54v=?H0WhKc($!?K(GxaQ_U##31(<;f8xQG7gJtUVP${;Wpl$xoRTjb2i z_!UH%+%Pqsc8hW^4ecsl6-PZe9hKPKl9su|LK`I&?G%?vLf4X1Vj{LoLc1o_+1WIr z2_*Hg;IT>hlr*@Ql1fdK<94AS6cIm0^i_PKt487pL>DH@Bjal^8uPmEN@krZZ}tJn z14-T)Z^$OY>10!-n5;6ioalwquwcR^p29AY6EB=UxXtS>8tko!Zh#(`%)-eNELx_eFyQ{bhRB|iAAW} z!_Dlo40|7Pe8_muB6q8i`x%Bx80Fr^FkQpgQo5C9)U;r*n?!Vwk(1Fk=~OOfy9y(c zAs^L#FqDSU`;1K`lY#XpIb<-R0qNnsOfp@86|0t3|H9#9mTtjNr}$|D-cuDNI8;xX zA;IA@nAr7Q9e%v51ST&rIFKivOG$%PGRK>;t%rLZaYwBz@uS^sGkKExKJ_K6%M`Do zAD8cEe80s46;VHq%9=D7qlZM2_Hx5^&K|c*@348UQWCR;&dSYJT38CYsqFJADqD>? z0j7Uf^`Ichg;uuCz&2Z@U$_L-0fwHfV#JwMNOyHlpl{+>f@DNJe^DqWr0^G>bRlSYo=Fz-3YVVH6Za}{?pV->&d~rO=13RY9V45W1&u7BjWf1OQ8E(Yo z_G0;@6+;LN1e3`WAbxK=FC@unU;~KX7B70&D~aFHO?WVuIV?O545>}u62Gq-N2K*e z^mS$%GhrsP%ZYn1p%iRaPk?6`=P03{IdC5p@q)d(M!Ng7V6!A3I z4#uGm#vc4-N*w%wNu-GgnCo^jN0UKF!IzzsE}*pkN|18ht`Znoq?K{HYgFeDBXR5!RcO1mRtkxW#!`$;5S$r4VDoG z{$)>$cg;A-V@PtpoF?TG|65NCe@v@cp4+pN%!3eqZ<>gd!T4=yP%@gAk@*4x^*0+H zHA+@9FCs&$(R>+H!kpez7_|zk<)f z7vM{4u4m9Di_`P7)#?5RI0MdFbKQg9$J2gKcuul(cZ0?JHT;7gLttkNr~4dYeu5;f z#QWZfH}=25fG0YVrF$@pjZ(-zlj|wH4Ou?#Kq379k&{Me;VeVvvEGPtx9ltw z61WGW*nh-h6uypQGjQyAO+E~{QS-0VWUVGgLwXQ*sBBI#@h!RhH3WQ&fO1@{0kRIi zXMu6>Yq;&?ES!$tJx$I+KctQb6Z|V~Zeh_}BqRcoxwCK(JO7~Yrxym9`CsunZ)zQG zR_8;UF33%E7XAZL$0|7stx`HLS0VUbWbqfsIe#LzaPT~&_vZu7!Wu*t3;;dOBME+u zBFO&*QbGp*Uiw$ecV%bMADN6W!H<7JB8z#REGobXi@8lL>F``8Jf;j0ZrWlN?g~q8 zk!J=ui`FAkIv2yQ^A(N>{|AthA^)mL;TPOv|5se$$GiD|LcdPJ|8Smuo&PM&Gvsvl zX~}#E&i*5_5%%9WYIPPJwdNL;zK4j*fe6?DsUv>x!tasjFCdHmXQTqz>{XkmCv4)G zS31n|L|bBd!7d*1QuTo!lbyvmMkhY1+bN6VI;9BvFBJAhDc2|-i@3n!Kv7kAdZCk> zy=G_eVgw8Rj$Ho#vIyDI&uu=>uZIcQ@IUa9)mc0b$Nn2*kmhv6*@*o5Av;MgZsX=K ze*QNmNY3I3QaVth7UJjm(P#eq?-CpX6|N%h=zr$Rw_44&qXYNgDZa%s3LoXBT^46C z8nge%6Lx2DBaVR*G=hKPE~G7ETqflImbHj0z}>5ikensB`~PoN^M9SYFXqp772oDE zOv)5pYbJ8P3RhTVkOq)B!Oka8^M&86em*^xry@<1+hEeVAi z`U%BLgX&HiDg2XFw?=hW4nRoP(m6zL8jxXQw-U3Tuoi7a&+jDj$Ey2|>VBlUUkTT- zo($$+#X#QC0rly8&<>&i>Hu>G!+gMum5($suMjS+Wzt{zPj-99hoZfO@`v?O-5k}0 z+7uyQsfyH_j8J>A=VjsEAzb@t*bE3A7B3Tr?7N9s%~&nuud6Xv+eP4y#4}7H&W~yw zoWe~)we}hDkAxyD{-0!ry6Ib^xrF$8YMhrC|4h}9xf%aP^(=;lPrcB0YJ`s%|6L8= zOPNKB82>`m+CllVTa7eRjT9t)p&IE$&TG~18EW{Cj8D@OouhizGCokv;#s3PiMVVR z?j93zAHSFEm5e{DX6{Ax^plLgp`P_Q@eg&+m#SwkCN=7XE>Q0rKS$Zct->=|_grKb z&!S3=(9C$X8jfMuOx0tQ_=Tzm_u>;VC8e)5nd}%s4(n^}L-t;b&xnJHl+TG5nY0R5 zI;h5Zm!$1#oVAklQ;LYZQ|{qzgJLY*ZYhOk&n{Bhfhj(+{!E<6r7=##cu=TE9h{N~n&lSY=MHS<;VzP9> zIDV{3I%p9y&kj}beWy@i^8jNulHTRQ-#MM$qJ~dUpdQ? ztMr{>N7GQ#?H9sWsM#N$=4-ufkX;^6jvofg%sMEU$_LT=!WMxtOB{GjY)rf@gGq;a zunFXN7U^Tj;7y`9GCd?Lcle{_PFFhPB=K~XT}amt^0)`V{8?9Z$xbLm6UcDIkd(n? z1Pj3w&xRo>o{8WXXu|JrA)ASw9nMb;fu7hf49hx0Q#^@7vps`%U651^b?8`!4N8p7 zM#pSMwB3k1BmRDh>AE3~>6~-lMYc=G(Z$P?Tx+J=2N0Vj^SO*}A8bsQ_y!4vlgUK` zr)9Z{nkwn{XwOh<2V+ku%t~jHVZ7YorVbBv6jDbKbre%a33Uvjj=|JXibF0+xPTfZ zdWjhP$qi0UpR;|27|&?OyiM8@qt%jgM~)G@>W6HNMw8FGdul@v%co^zGjr z*_AX2;qE6Z><%`}D9eoBEIU3WlRSB>BOATJO2+uau3ROdFD%wB}S9<4R_41 zlG$}8M-IiYZ6t&Pb%;JIalmG!hdUn~z-}`ym8FwJH!}3%j&mkPH`yI?&{%AMj`Qp+ z$;;S1vgt^>`6Ubr99rTvD_q&Ajj<^O;R>F8el>+SfOJh9EYeE)c2B~9M55uvT&Lu zJJ>LMHhXayi=#Am8l`!lk~7JUO?V+;a@<2!$E`-mF@Z~t0VFvFNs{?`;tky$KatgZ zkL2jeBvx&9RFah);P#W;@r6-hPjM7h$2fz`wlR=iz`ViLaGym#`j1!x)#&+SwRW zAGd3%*>R(RIrG> zNY4oEx-=(3!+eH`KF78RRN(dWp(M5`&alKMT_M3(g^iV9(-DXA^MM7H8vL7V5%`7( zWIvmPdy5h7byyc}jR=F}O~W1Oc;G)vu!ZMwbIAmIl*cfgqqr9+ZZ@%XMk6}+DoG5O z3Jh@LVCZ>6wkeC^RuP|=Dm>#Ef3>UdtfxdzUyCsd3&A$_@MMl+54G)P3{^0$QQd&* zZeSv0t?D+35dNG{?HVy)xu6T{LVN%hCte{U@Y|Baq4C5A_7aEgQ!23&%^_XP=O@o~hjkq`p4Wc(J?{fszx z4wJM?wqX3ja$y`PwUZ;jh(97(bIEZzmMT05oJj0`Zoy6jEC?f!L4*OK^b?733Jfp` z46uE1`~aIHytvCaTcp0SrK)DWki?7dbrJ3(cJVrPNbG+qE_E^Zdxk(u zs${HEA6mI^nU}}I7U?yz5-g(aBVnt<#mdDT;i3%|9qu`XHqr4hs;^15j8uK- z1>$FQ`mT1`(bR1ci%udAzr~5z#!_xRj!X%^;{*&2{-*m(YeXk*+RBjw$58`pH@n(# z4QIM`zUeD&iKr>{D8h+7ibR?-)9q01`}H{d(sYsTooKI@cGZ0|bA(UCKAEkDEy)pi zJJnaDEn@Fcjm0bO=>-El-ra>4X7U)h!!Byt^Ct09 z$Mh6$akj~H#AHY&F}E>Z$PN9-(Sq}C?S(>aeqH7X9wcR)#tbk{!@e-%EzE%Bvgufo zGWL#dBCMxjIkh(~A|l*_t}U-OY+H|fHOja@Tk|Zgocl-j(jN(+oxCcA!;||f33BK0m zP~J?8yjX#-Xb{$wpQ*+b9|~IwR;0R}#tyHG2#)8;z-q~HJ(h9NMOq~+r#L>sI{I0Q zObfa>>QJe^?G?X>_~#yREypd`8gRd4d61cYuoyRSBi2k&58s6$Fqu-xc#m+|c4q5G zY_G7qG2TWd1=b;I$b+ga&Qq%Ul5icbVv%YMGcG36qBxwX{>F+e&VH4sf4j>&sr7{@ z-4~BhB1>wZ*Jf70#>(5>iG{Up^B4^BF@Z!Ai^_+;E{GPpilJGyg<#qsJZunSSkqoY zHq`fWCRa9DLUnf7-J=BvHDQ|$zm{xx@talmdez+{T*r2T;RCbpfHfksBgXA&1-(Oc zZ%i|lHS-BhF?lUdhigZh5bOqv1~yy`yg+q-?jj--s(vn_v0t5-o(s#qBa6(cNe?g0 z7IqN#6EDy_-8?Y2(csT6GQognK4w?5wD^Brg!p#Y07V&pcag9g!nvnKpzwUY2nI;7 z1LC$UE&g6-=ONV+D9SpGgLIkCVF{F2Jg}Q-n`R8;*%KE$#{bJmqsjC z8Cx)`P7#Sbqb{93C|u*$n7Jg0s{KQv_*oAnKqBG@&(pf+cHuGAlW`Q|YZ6&c;u~^A z7GIQS>{BM?7RV5vc3UYvMmLgCsZapuMkfw5;4~&h?sjBKcq&8$BaXb zkihwD)q_JXm5Wo}CVrq$oRXuSf~>|RXlXv_&^)*4p3M#s^J=kjYs8dto*E8Mevyc| z5R1KPn(&l)w2-gW2eRIY$7n>=D~IwV9?cOS7AF!JM`x(iMO9Nqj`WV2Fv2?_6rI2N zoC*74!u~*u51VxS4PKZId)q?6g}HRrG{GOP_l_1D3G01fniz;ge68N9)2q*SVVXK}} zoUGb>8hXP7G)Xm`5MIn@Q#}`hQc5k&B!e)j$i=8PlU$g)6=O#O>}^o6jnu{aPf9Pb zQHuLfc825Dy`j2Gyf8uc!H(J6GA{2U>>7macoTkMV^-u6GCoRZ{0u)K$rG?!x{qLo zl!`fCCmAf&GZg-=kX6*B@H;Y8WAjBHmWm;FYGE#91LPkl!tX!uN>MR|f(>{>-m2l# zuVm~v=e;l=$) zCBDHPe^GsXiMyewvB6#FDfKqiEudjHjSySro{r3o*LWHk3^j!?;|oBGQAa%++LI;d7+`XRo~dUvF!dmV{e8zw zYUuDbA^Q_)c|#}^p4%F#OQ4)U>#lXuFrpEdsAQrPc-vq@@5AWpJM8$V^VS91k6|K; z%@NP7EbdOqgH3T%)J4%xwW?*3kC#+F=))?+gWwPVv?NfG&W@S%(fdq0MKYA?!i(o5&4+1w#R!2T!vv*l3_R@F6{!vP+7f z1x!-octjl7{Sd4Vwvc$0eF?k7a28=ZbNDGrEO_d0QbFPVE(HVjL7klD!I0usVqZYn z6Nrp_h4H^o78Sf|tS-Q|&4J&u_wi2A8Z`M9`RhUh>#vYpfqHN5KA7K~VYrpH5VC;! z6>4vwhDlp{dYc~FQ0|R}+lSqd&~orFjoQD2#1@%?df({nKJ3eC4AH*Ln38-L#7?WQ zH&XAz#`vZ>ym=!`wc6^JT+g>}Zu3U`P1vk@X{0FBO43#dUMbuWes35|1ZOY+Xxl2Fi_K^+puN*GiXRw)y9 zXc)FZ&F)x$F%}dh<^@8DA+b49V*Z#t3He8N^^D}dlv|8_dUN)?77%+zu`w2#NW*?i zp`PC2IJTQPuq&4hygDKJVOCyiQ;2BSO*63nbW&^EUPG(c_a5=&*M-O4mXM#hHSW{h zhCD1&l6z89>vl3M+fAbmdhnv#3+>*6+4EoxzIDM& zVa06zb*p15R3y+*47o|Vj_Bc?#sOse0)w*@1^ah<#0~g^e^1yEdCqK<4|quE{QJ zjL1?t?P$dA_G+pfRWob9@$b9ke9FFP_BLZ_;YG7o9?Gh3UUg^+HtL4`xrdYUk4P2y zt@HEmz`z@-qX(I;`+lUT_oG2M&Tm;AU_OI1G+}qu>s37dQs)2KRt_!J_~+tn?V94cC1f(hm6q zeN&NhIy$esnzLF%2UrC zDaEjuOfk}a>*@n5ssh!!CsXy!sN&@;0rx#Jj}ppZj9tzuN7C8kgaon%XkT6)HSZzH z!#-z>-|$a@exH5il=vx`stu={hJV`W$IQ_Wo|^NQkDP|zel=XO0imCE<)<=FWsdmE zN13PQJb0=r#HChfytaMUY?bK)^ZM^1R_WX}xZlNn2jkrMb3JKJ=2-_$vQp)?@8(-= z^nT{4U*v7yt+1Z@o&C-->xf}jR@?d!K^`S;SHs^lQ+Z$NhXRhnS0UY62YRo#^6L^Pd6${^HY$uO zzaKxQ;gsjpQ(jk-`W?wMWl>ffHkH6e7FM80V6>SM+mO*5+7361o^V0c_9c7J^S|rCuNUH#K9UhTXWQG1#$E;unKGfA}`{y z$WJn^l>9c%q@+2NJODq0C3Phbna1fNJ8C|6LLLIgz#}-pmW&ge_|Xf9d=CYq!5^=J z)RR92-{K^5N;4&=;D>(F3HWjM$)~{?@Qayp%&DVEfdVa~UF? zf6w|AwA95dWt-C%P;xg!%md|MJOZESmG^I#P@fR>MxYHb{%<$60CARsW8z8lX{PL1 zBJF1Uvh_uE&`{psotEqi)@Jmm%)Xaj$|*IN;G96SMD#-*DF zO#k;34&eZDC`wH73GfCu4bA}d!3;zxO2LmTFaQh%`jh(-{vVO5oIje96YxWSf<^Fa zPceBq{374afIpm=D4#W<3jXoTw-NJG@GX)i*U`?$Ew2AQh+Pv)P_b)j8OtV5-k)F2 z`5Dol(-IV8Dx9tsV<%GW1zbSf-Dpq?=71nTTv5T$M9n!re)b!prTMpKH5dUYh@AyQ zmIi}LPz`1Qq>{W790JF{Bj5yh1Duyoj=6OGf30B6h#v*Fg5!8d50v30Jp)hmP?Rij zB|V17`&#fHu9$7R0A=C-cJm8x@^bLM$a*#n+uix}yWxa9Pz1`skD`nyXa*DTpP| zJg$7T6`f#Q`C2CxrO=uL_3f`iylcS!VeCr)sw(=v|1zVm}ho0ws z-|u~&_xm37{N~(q=FH5QGs}Pe+pIub*39$Mz~oBC6@#luTD0%d~g3%5O`1b zNFht|>U>g4yd!vWl6Ozy$!nVtyJv~VjSuQEtR6498&@W}_XNHhN9-BcT3IHMzbTWl zOv$&icCN(`Jc)RoXPhay(LKz&mgL4LM0sz*OJ$Oltn{=PZ)MD3xDg*_O#1l!CL(Rb z@iC6Caa7|#{rEH)Sf9r4Xqb^WKEhJrC~M1-KgQI2w;3gektH?ONT2~8h{6$%qdSfa z9L5(Mhhqwkxj2k32*SX>0>`HyJV3PV-O2p-BH_ch1X{%ZPaMX_WoaA9_vk(ruOzoT zNNttmPkuD4F!@HGh?%LND)#24q0@MyQ8vUAMr$=}P0A;lpU|3Q-qWMJBV3@<4YXh;W&olB92>l_omfk)OG_815ejKyrLeHEXD_W z5(j#v_|umu+$|lnh)1zOCVf@^S~Gk4fU2pFd)mDTSw3+$9*FBi5ltuwMz}=1>XUv9 zR;c9{HzWOl_1MwPC|ozZR{Oa6X2<@%@@6slgA(%Zi>uEVJ!hK_>g4i|EFM&Ko}d3u zxPA!tf5u@{EEAD~dNDOutVRPE*?C7G% z?Oi19OIz{$w>W;shr5Cg0tsCZf485ZA!wxd}G5DAWb+?n=Bbt;XX%bPGlL3>O(IrnU`| zZ=-Z4QIZCPAtPL|Bpaup$f6yNemKVBm<_5Kyo?6PcQR2+i0x6l&5erpT8xE`NAYnD z0sd;R{;B^P^((`Ahf#+%}ie@wz(FU!8Lz+HVTyXLnL@GC!((&snD!r+!vZ|_} zs&ai)bh(wnD+(*=Kt)AWVO0fiePQ7)qHkz&B`!cR%&6AW;fA$Rods(p*JF!XYZ0)9 zw3yi=X1Qagn$aG&EgrWlo{$UPw0PgJSlM-pFJo6N0aq+GJb2M!Qy6=C$r8%WG`kYU z*r}E$Es=~Jv&7);VN0a>RLet_80{xZjQOA?#_dN-jC-{u#`1$D#^ZZSjOTZj7_S4C z81Ma-80$VujL+T#s13Sj6wA22fJe zldscDav4pPZ_tZ!IZcr(XtFG!NpdAkl&k0k`6f+}tEotq((`f+70S1$K(3{HxsINb z>uJ1vo5slvG*-St&&qdcjC_wq%Z-#L%V?C`L?h+MOsbK5{4Z zmS0gX`8B1>ZzxUfqExw?ddhF9hulLcaxZ%IK1!1Nsk=Nt-Q;(aD8Hw!@(1c7tEsd6 zkvhqP)KUIK9poWuFMpWgU6QM`V$Y z$z47nH|Zd=bdn}rq{^qHNS#bl5I06Y{3pqn6r2fRV!BY+Q=u}K(3n%0nM1g-C&HaQ z78dqMc(6L*$sP(X_CR>E`@+g|4>3?G~wQmq=sZh;;U~ z=*7Mgz1dFDhkYsfvM)pi`&{&6pNanLQ!#+;5ChqEk;%4+EcS^Q#I}mT>|>G5J`#5J zp~zuX;u%&chOjMSDEmO|OCJdq<3A z8^k#FwiwUWi|5!nkkGfM=V=>%m$0C zY>@bbWr=MpQ*37g#SS(=e9HQZ&sab4Im-}Vu)g9;)<^7Qy~S6om-w2ci*Hz(*u_%C zZq`$L%X)}CEJf^P$zmU4-2uECz?2A3x&qWL0If5?+({h7sNY`v%vf7-h?x=qN<2V~ z6UP{9Elx1jQk-J4r9eCuV<3-42YRYDF;I&Tn&NN^L)Ura5o(}kLvfwmZ7FWWT<#3G z)CF*{E8s#R;9PgW`EJ5f3lf@F1EF~bqDKV?8}}DBlb@)I@)hthCv2Kk*v#I-=H?|> zBTvB^dk77xhe8WwX7nRfL}}K-}JhXr}er~zv^{)r}VnfC-ui|MO}N56m&vQ3O=rDgOBN2 z_EBB4|DtO-M|AC(!+Ko-JEYe=&kh3kk9ty6wXTi)LDxoouWNbV>2*^M=-Qb5y7ufo zT^qYs*T(J9wejET+H<@0x*5B4t>7D7EBsp5p8ra(du69yH|I;;Gye4a4~HKzD6Gdm(WMRrSu{2b*cg`qe|c#v<0}FJ^-$u z3SbG916R^!;3|4whp~95fTBr5!0b)>KIlP}0pFvIz>V}Cu#DbC72cW({fs@&xA@UfG+@;=Ie7fdlkTo0j9Yq z*rRYv!}#eo3gA9cf1evO@bLQZ8V%DobJye#lFKt$#6c5eK#hvIJdsS)SxXShG z$5*u`YC|<^lzG_V_Qm8B~tSl{0rFeT`A=u69D|6N~r?|?>f;h+%sK%#s z{hAy*A2QUQJJjBs*5F5>eTluausnAt=;3v3D57+IcdF6s_KKXU$~Beis!*y*JMJUj z?G#_Se!ZERkFSETs{`i#@``eMDdpsp;=d&ijuhx``g2X2;^=ZsI%?G9$bILnG5623 zj|}H#{JELU?rt>7Y;N5CVIU2U?+_WbfHbTU7QjEWZ%oaZ?<2d(bJwGNm9soF#^3Av zGaA)SIT{V~R%kaXerH=o{>Hf%yt#P&a3(HNO7k|IIoCfj#G_$jzm|=?{R2EK zepVk_vqbG&Wn>^ja6R%2A;^fL`=QNovL`C>9oP@)P598WogzCnOgTo8i6vq^oj=zn zGQ=~qk#DO;-U0r0y4(`6DWKFDx^d>Coy^5MoK+)z6wlpUQQh4wUU$w|Y18}BBhTJNln3~13GYQKwd^5JJ?m(K zZ)Wu{dwM-QBb(r2?SSrQ6C!7@#Bk-&S<%FFAvCf}qr_v>JaM^LOLga#M~1S*hUb2c zyhsSDq7qk;+XLOkXPj*n8Pm9-kGWYxZ=0Vr$lJFM?oWyA#1a>a)#pR-y&CiOUG6dD zQPU_0Iz2ol@l6`k;q3cHMfXU|6o<~AjQo{QyXk!1*~gJQ@NG&QAP+xJHNMNp?V%pP z=bmjF8P1+bOc7_#H;wF-)6hH3eIl}XwbZMO{4NZS>Ytb_ z&Y$;;>>AbX7F*ok@0}3r9q41HN$H3^E3&nn-uOE5 zo{>gle5>BZw~C7K=bmkYyaTy+Gafn&-|7%PMBv$3U$GwfXHPV_&x$lp&C9Eym1@|O z=oM$HqrJSs&wgR)>;B~7^G*LTAmth3Q2|!wK3OVdW@CJ@fpwFn5>zm2-0f*YH`z-u z8rcf6$L07IEG)E_Vh|~hrtsX@_B1)oUYb*G&sC|+UT(+Ta=Se@ocwa3xlo#8FQ6s` z1!jt{+f%75Eo5k^J-5`ZWqQ#L`#O7SZW#u!^72Ru&#|N-`)o+Sp^?&yUc{XOB-|5D zQ(?$PJReGff2Xo-WqQuIQv7FQ*Oe3WI!h#=Q5H?IrQvU3AoPcQ*q|yqUIen|FyvB@&U|vCnF*ri z7SNG~+?Nt6b8KHzkMdl5_5*@56>BuL_MA>x0XF*+b7j-%NjJuj*%YBjr){4bamR$)eA8> z^hqsE&4zba4h;xKD>m8lZMjIzOaXcJe0!OF;djjHPQDwrR8^I)%Ne)6phBY>H!wcR z?dz(la;vHe3+xqDRcms_;j{s@#c2@PDj=$;ST{bFrd8PSRBmYu1+Is0qVB|F=}miu zy$`-ncDb3tz@*`MxmlHkOP2bZCY7#Tn}r!_Ik+X9G)y*?RZA(eDhEwt8gH9Zx|UJ& zkR^=r)~(%AwWaDH)snqn=(>W+Dr3IF+)|!I;Z=juh>jYnvB5J9XP@j+;5OCB1Y<;lm6R?wMz)^!I@iG|zO zouOoV>DnPrjdWWTR8HVNg*7}RA8lp}Oa<1N*eJ!&?d24oYquRDC{00_3{T7^==QNz zGO+Z++rjvccKygA>#^|7}1?XzUblBG+RR^^XtP5VdZ zjH@i)JZ8))q_u%XM90=gdaA}oN5{l8Z{ECWQ%=R0<`tVZ;S5?3Iel{1Ek)%lt=h5` zPAn)hH@b3c)ijl+nAvi(PwpFLTd7s?vs>un(y^;hNipljuEH0p41k6#(bvZ3VSh2- zJ_S&Gph(u0d{-?|!mA1zYooK%(=ZCXNl2C&Ym%W|28D!F6^_YXT~(M}T8QD$jlwsGv3F@r`A8ojA(^n49bn{F!eGE_Fa zV4aA76>nmx_JFi3_-^;HonWZeXR~Z6_LPDkdZ3}Z+ibxTEU(rz*xkdz-x9LUA{iCw z+>__8@uQXnrGUcKfal)?6s_{3i1BOv=*5Q~QaJ>X5`Ft8V_@?t)?38u$k7lSaHxhqoY z?spJ5Q9k*;jtG3QUo@Iw_B} z2$yMWPDg6@8r!~^wk^XV-A{fXuujJ?`XQ~{fz^CvfB8iEk#yTHyGi-oNVyTW{p2Pr z;{9X=dj@?u;T<-1HpTB|{h(gdpOQXjgIgF}_cAQ@{p9;t>ifw`mW`Nk@3K)1S@_Og zeaXRgV`-n%L~aHfz)v<{O&77^+f+^_{hGc9yt>7-f_0kCu3Bl-St#^)?qeg8uChR^ z^AoNxWhoc}>?u|xDJp-00Okzc(^&FZ_5eTHd-0CAwAUEX+L?HVaXjuz7QK(f#qy}; zj7?=p7g!4n`jQT@C}e(^H31%DEsdA?k#(L;?QgIMyvb$Oto}`YW|4?+ghc>PvRFjx zc96B($C7?w;rm#0P2|-O8Ohf&zLohraeJ!hCc$N`)v3AE2VM_7>pUJ=9=qQsvm*-} z4K8_-*lnh`WUfX?k9=E?0zzyy`KWc$^9PUCw9Ll_$v2P#gFWM zny6;?)5Q<$elPs=skI8cXs!1HuO~(+{>jHwpDK6#FZx^WF>c42nveAn-?QkS<7<6tn$QY&*8}hS&BXWPDIh6U9OwZHhvs5` z5P}wBpAobadySx#*kc5(#hy)w*+zWZ96_AeZ3OXRmk}h0Z;YU=_}U2CiLZ>Hz1V34 z9mJPL&{2G01f9g^M$lP&dY$p4E@Fp~bXP1MxOdV>u??13Nu$IkMvx~y`2jJL#8%^h zWbx5&h?ycj>Old?Jy4rbYJ4jJiP%Pi*Tk{nJr0e2pGN^y`>MmO>X{A0+_yZlVYvGT z&ukdsUh&L^JahRo8*=<^2K^cGSA)L-Z`*DM96d1MXnaXhTuE}9l9bjZJzACYY*~`p zq9m<(NqTHauVy8^o0jy6Dd`(sk`YzXEuo}eWJ&)fB?BT#28NdmYE&{fv}9;tNr9+i zrpU422nIb>kH)`>jN>6Ym?DQK%#lVoBHoDr^^lqHiUX369ivSiAH zEZL(dOZI#|OQsfP$+UtjnVz2|dp(yWdymhOea2$G;hP1?g-;el7uGDuF1)kk^CFd3u=uZa$l2q+(ILr= z-=(Jjck9W(Z}lYL9v!0P_`P~J;66POxL@xIJfL?0ey4W^ey?`|{-AdRR_h&rKkAST z#~;)orHlVbZwox6CjfueklqqDQsArB6sC{K&_(_IHe1Nw@X!MudC%IHSwe=wpqbR)5wA?(1U^fR#B~ zVeKF2W0z6V1ASCW+J~W)#yY%5x4IJi4 z?Vswoo|L5PSPQ{qN?@BYp2WmpBNZ+NO{F9*vchpq5t+sR`bQArG z37CP5+(qAJcnJ^D|0y{Xi*T~)b}(*I7tZQHHjKSQoJ{3G;QqpOXtg#FG%_~nR8|36Wh zN&kNdf{LkDHgS8hjDd+N`u#T%=mSWQHm|fin)AqlFfhA8M>HDp0|t04@!Qw?d*?P`dF zZdF4b^jEbwNe>s(&1#TgH>x4UdA43``W$nY)sPMSr{MHwl0D>ueE4P>A9`>g+`19l9o7Z9h*dyUvXg~U^&=V;l4 zRi4U&)D=@>@tuDuU_Gzas{glqRR-LKh*jma^p`hIQD6Ru`QI5J|GY$KHi3UNxEXX~Fds8eUcW`chaR_! zJ{NPg>6vD~#hz~dYoYu&z!21T*)n#6Ay4~HDS4i(@n-);QvOdl`Dl4Bn5FSYp8ph* zca);B9?AZzs62>mHYCc+p0;8cG8Eg~?V|rF_8YZ}-#P5NWOaMB4quv&EHQb5wl1+XjE zfrucV;olSuHhuW=|3^634E|H3 z99a6m$_pTJ9w%D!cf>LJPibKrz5yNVKP84HJ@)?Me^YAM>h8*aQ*PM$&fEV&a(IAs z6W_5!5R_d(banx;+8Jc3Ar|ZiI<^A{T0=P44kT_{(7FjAdgDR;8p6RgqRs6u>m`J( z#L0RgVGHpqYc5Xz3nBVAd28RlAx9rC|N7})iqZqcEoKw9At=1V{6)ge6U z`G{I(6%Qw=^ot=}E|BsELwNosrbM%J-19A-omLv6vby@;>YCvZb(lsB2)X`a2K;*hJgA?2kuOspnT+}GC;iMT95Y~(i;)+i&aYDM2OiRYTg-oL zfw8RBiPp#49E&>||4YJ=wugV#Pp{-Zw?EY3r;Z0ZwKLWEA7Ymv8n~!8A9-87dQ3mQheLPh zxPI)GGh;4=xBGbpefJE8iLOkq7Qc|A7d05tliG&Lp5XMwYcaz!yv_fD=tnAdR17dILDwvL3+e!(2+hb44_g(iU?@RijOLgZTJ00x!Q->K~1srPs zbGyTBk0ksOf4udXre|Z$MW2tF47H{Ukr$g>intv9d)Sr6R~uam{iEUakSS1k`ZM@O z&`m6MFvR_}X%9LUz&25B>)HPtxqku1V8eHOH+UdAftMQBUShE~-p z(5{*TEvva$DNThI)l1N(ng*?^;$nJr?z}nkU)kUNM5_g}7tUHVbMcJVUOw4!$@J%; zNVRm@>n|;v`o@dPr>vM;))iZ601etRnY=p<9MjK2w$Rq5Y%mqj3|V zxb^Yit%E+v+LpO};En;G_W!Kkfo{jzOb6xidBzugzwEQK_gB5XPX8|Po3vf2yL&El z&Q@bw=agvIc_qqqL5Xx-RGPRhDG{#AO1SHHCCqh2Y3#bHG;&>2LS26-4PDoj5Z9kd zu+l!#isJv&SessMtdX_C&ok_$_x&tolf(zAcFYy0%*&;e zVR6c*41=OlYx##jzYJ<)JixV12^!#9uQV9odZ{6veOsxU=-Qw>oalN-c`(uS zuHrwy^`7E40L7@8=-RCO=<2LgySga*UEU#xK0O%lau8rf1HjCVNOo2Sz$@(l7sM&m z*W=Njt_!A!r(R0%^@e4xpcYD_)~-`Ztn0V}IH8zgT_+VD>&ksaY43vIVYbo^uRdb7 z(iTD9OeNtDs+sYr($6(PdlnB&eGcvHrSX6-m9SXXPNi|IYo8Jl<=U?VN4dUN0;60% zC_b^SY9%1b^`qh)>pG}-#kzh{e4|{46pvWf&x$41^_9{n)^%9%j&gmigvPqQQ5wd& zb}1pTuH8y-tm|7PDAu({35{~?RT@UQE()Q}bD13Tl{TAM+`Ji(!lvjOV{3j zncFT2lQtVM-c-W2Qq5baSd{&3@^-l2JN8Gzx%jl3gp8$Gp1*CoqNc#wo{vn`O6`*%- z)P0{VIP3cXAR`SwyM2bUe&vAvn*jsf2MpW<_+5DgC0(n8R8iboC3pw}1`T0JYn28= z*sPMvB2XKP5AFRC#cfu+KBD-|if4pUqc|0_-R0NC{a!m|o-6bX#r=_awW%h4`W#yoWfH}0RZR8B7qNt`3hT~;KQ0cM+^S{{N-?G*4?D6fC_eLw zXs!)fO!vKZD%u_AGaEuw?KXmjs&)%OsH**iU_873egZzna>YGhl54G!@A9u%q|`Vk ze4xyA6-htU_q?-#`WwE@mx?^^3{p?ybf+TDJCm}DWb)u5nKGzI_Q)!dJu{1B>cAqI zHlRqRUr^3Fd-W@ly)%krpR@SUw@;DG=v^ecImq2doe%UyJ1dfn)akCdN-@s7)y&^0!ut;ct{HIEfGfXIn^TK_ zqv-cy)PpGFx5|^Nl%L?GW?iKS|H}qkGT@>C7p@XTn5^Hh4TG+V0a~lG6qm5iImay} zL`~R>QKX@ou*aQ>+p2lUubsNhTr+wk&N|?CnKB$_oz!8#&T1~Oi#in8RUHCMRG$HM zQ*(gbRXZ?A%?2i`gMlgPAYczQ3)oZ51g5G3fobXhV7l5L*h}pP?5&>i+XO!DwZqN{ z2aLWI(P8&ngyMDBRbRXg-?+mEA5DGeHeI}+^|~j%@lg&rJE&t^Ed=&CeM+y}YTW#5 zeT>!MUH_Y2kHJp(Q+3rZn=KLTyzjd$3dmgO7;L85{@5Ixuk)wzwuEsK#>h1ka9alc z<$d3$#_w*>jj-Q)(*8zQ&7?Wqo>(4vJ`ABL4Q>YiiKLo&^IoJ&dFKc%b58J4X`XXJ z0QR7BE>LNfGf<p z09VYa1lrVEV4zw9tWqWJeylzPwoy;xN}T#D@POLWi0Z4>0qyE`;2?GX9OnUb8%~F) zTY+w>0J^I>(4syCdZ;d-r|JX-sWj8sP%D%(ouOI*u(9?Wu!;68Fj5->jM7E}TWLdp z&9o7~MJiyiDrP!YsSjp4zfeyjFy?om^md(~v;J~hetiaOu9U+s?9 z?}kDpI=@%DqFh~2tj^9K)lSZXYDec!Y6s^bwY~FawVm^@+SYkQO>q9A#ygLyan56E z8|QJgwey79%6U?4={%*jaL!TZIe%4~J5Q^z&fnB#&NFIL=UFwzc}|UXo>!xs7t~1S zMYW0Zk{aQhtG?>ItcE*(SHqlF)W*)MY9r@0HPrcs+R%Aj4RQXd20L%4LC%|M1Lte% z%g(>lK<6#h=De*2IPa+b&bz9g^PcMKtWkZOwW`&5U-foAP`#W>)alMAs+-fHnw<|- zPiLL#;e4c8oR3v^r&HCOE>(3tRTZbMnw(43X-=VXr&JjTk?V6)l zrT?P+?hK?Sflv59_1*tN;T_)o>?U|WjEClaN`v<|6YYHRvYDhl&0^^j zu(7^1MXO{Xw^@GfZwB*HQ&`|vz7!Jvxvw6xH3K zux^3kx`%|0M+*?G53u*x6R-mu&_s7amDVLPY0Y5hS`UKGH8~s5VbY@fweBHSIP+?8 zIU>(5tod*_$!#~pug3IK#~(Xacd733ed2fB4s<^N=O%MVDW>qpP{82lso3C4*7(-= z&W_;K6e&z!ktG`&d9gMRyc?36M{9rUWb8z-SS8KYj8)Prnz2fn zqZzBDxtg&`D%Olu(yN-WN}8t`tEBlFR!Q*-G}t7@FVq$T7ilngi(jlQ1iq#%04~vB z9u~h;gXMSp>)NZpWm+-t4Q(!Pxdxl4_!Sz2GVvuE%zNTjYO{c=w3)y+HCQyouhw1$ zmTJ?1YqV*=x3rglYqhDsb=r%-_1YBR+nT|e-=KjtAODUv5%{k50`NU;0&t^N1T52@ z2X4{|f$wVtz|C4duv~i%SfPyvex&6AKh|JZ6~9#*3H(4C2mC}E0oje-i}su{40&p9j)oucN%qd?AMAM z#|~)EJC1#$iFC&<&DqDXTYH-B_*Q$;$KhfAsJFx0T-n?4z4kEOaY(zF;rLvW8IB(` z(bZ9{J?A*~qc+}g?4UNzaqK7UUb@3--qPFgvvw!laag;Z?l_{|N_Y5}Kj`h)qt#_N ze$oEOa2(Yhc6A)nu4XunYk#IYPH5ND9VfLv(jBL?Yw3<(wTl^!)7pg$w4C!9j=kE$ z496L0`Z>;Om(m^Qv@;ow^V)A2jtko9497+7*9^xc?No;2vUW1VVKIM_?)Y6hk>S{< zJ;-oe(T-<0u4>0J9M`m?8IC`+UosrmwG-)%KeglOjvLysbjMBYXu9Js?U!`NE$v9U z!_)j>Z^v!zaJu7;_H(-9u9oaLc27%k9IMg3%W%|c2QnP@wfz~62im?2$3tyzhNDi~ zli~0(SM_#0(!R~W(ra6W7Gcd+|lHt(ITQeMH^T!zuH}kHp4tMi6 zT^(O*GTq^8-jeQ!5x3n`k0HfgG#@7%bI34J%Hyhjvd~{t2=MW$foi@cheiZPq z&dWpoC4=ST`@!u5g_@U0LYR};_j11MyOESNiCMaX(R1D?uk*+ z$u<2C-m||}6HQ(p>yXOQJNEDD4N9Ev*D5g`Xk=Wv$7(od0HCGYdJN^Dt9+-H?i6Nz6&3A z@Ue$GJ+kcuso469WoN4P%(N_MocLy?rKV}W^ zfs_3#`PrW}l;QfKf+8py$}+}#^N3X2B(g%k%_nsWWA)l?{^7p%R^(^Xh<31uY~Q(z zy2C*gr)bzx8eX}zCU}eNI1Xnc3~qg}VFh%(>UG&Dg{NhuW!ubT>O?SG_U-G(=vC&M zJ&hqVPjv<}r<+iRY1utEF7#*HnNKRz1uf*4w$mujWb6@-AlQ8Z^Pa%j9p<4@c&VS& zxR`+5^O(PV6s#pk>26|PMQlHd?VxMAL!7)lk&WLKW$tO&NE)q9(=?w3zH6 zgW%TD$iw7cxm$(al27(RI88QcCLyiV4{llqQBs=ShIy`Owrw7f(5&Ap?oG1BeMOCJ z(bNO&BF&FA&VCn4Ps}G9+N&r{V?zaurx@u%S=k7hP!}!AH*0f!R?z>m`)0)&=ZXBL z5>}v77|x%kNp5q|_)wK;f2s<-%GG$N3fogt10>88rqna90^pIC+6bFJWwc;yvQaM^ z1yo-cbeB9Hd(%U73YZ!#z%^30aY&dtUzhJ#ZyrXDwx+fdQPksEHTV@sZVEkz%ti2>2x`M*I(Au&CaaZV;poX^ z4WxtC*383N#=Nb#58vv+9v_nx{xzfAU9gxn>k92D0ryaGb3h+ZXmB?=kH;yB`LOD? zkfR9g=`bHyv{q3TlNMol9Agd@3yIbc-)OSFj$Nr4gztGUKlF(3cr*spE)>fXZ0y}i z;nwlwZVg56b&$4-SuHe*zz9s;yjPsG*TKH&Jw6Kd17RM^Lc7Xs9XiI@jP1L^H4E683_;a za`orb4CjCz_6%FS14qmC&EY8F^dtiKj8yXYX9I^^WTEA~PvW+IMU*Q;1?! zC}I?ot=MTN4aAdS1DVYFv;+C!;)}~ojoo~#F>cSE_3_kbozX`5hm7rIG~dXx z8=at0E%-9gf4G;KzeY_JWtb`6!v%RizO;1>b+cw-R#7HX(q2lfq~_M`G%}1`V^-@B zHhJJ5w0z|oXy>mnHc&&!;QkAV#!_oP>=ob-^Rpqu#u*+7|8c`qNZUN?FhEEXlN}H5 zGlp%3Hu?qNeLAeDsIo*XWprH>VMj?GA&`YFjI-DKOTWNEJS;b3hxWhFW^NJ!|wG37Wt> zoi#m!!AS9ip$KJSJoA3gkQTyomK^y$=0{JYXN_aht5L&nMXm^?KwD5uWe~pdM)=4w z!MFvjXb5ImDAc0Z_T2PpU-km8G`!714{ zD;4#Pj}wyy&3eB~OzL=#3h3i=wf+s8)vzJ%#kuQg?GXD=yL)jJ`OI)f+00>_QAkZ% zsO+`{w#41P?`}Gf^e(K9lMf`DFbwc*y2lfbp8T5Lh~L%~&4UYFk?d=or}5c>n-p$p z4xLc{T5j^@CNI8K?*Mb!4y+-Z{lnMS-+wN%5oW6(KcMrD1G?~bUzT0pLoL2oL`B$b zc;z1T`tk9!7;&=FZ1!w?csS;6LM#G$FGSOfITV8;231g6tQmoruxDw8GccoFHZrP0 zg~M9VEqmbE*ci*3b7nG7Py zo?Ne_Pnd=xX`hX%a*G$HRaWJ0S%~k!(}w1Zw&8zyl|6=5^WsH}w7HdqRqLxNs?21Y zSXfn6Sykaq4JKEW=a%Lc!ev{HdsS6cPC1nE*W<)q3FY?OQk)i64JN;;Ac`uiY(mL} zmE~(1)3nMQJXVObS#Q$t+RwsPjNZpnLu0nAA2$zqSh4$dW>pn*ml=hZl|eKCdM2QZ zkqryZfmLN?RZx4zwKnWUqECn~BvU;>Gl{1dox~t$*hLOq=b!>FW8M#|$fID~@Mv5a zMqd=>*mKKl_-~``Cch!rz+rWHPX0ozxT=uNWZOsQmczmT_d}{o1nsW38P>;<_VQL( zb5-S{8|G0&2;9LTz5mczKd=r76qW{VoM#EyXoK|@>>SqMQciwaWnrm1roD}e>mLXo zJ@h_JEzhl@jal}dbY(oEEL>Aq$&1tN1^H+wYoW0I$wI?uu2c)iG`?n&(K-8Qf3CeM z*Af`gJb%l^(V(fzKy8D5DpP6F=+UFg0&@%U=|0QJw^tU%4ndrO#C#?7+v6Suz5c6m}hCOk}04pgy8ZMceR5m?lyMcX3R|>lJLWvXNR$fJ!GgU z3C*G@nQ<))K9eUFZeE!lQlL`%%tgT=AvR6{wgtQs&g%P&7q+PI%F40Bb%u%B*zEZ2^a!PnO((`L&A$!1Holil}Ex7sEkfCAF+-OSM1wjuW*T&k?9^z42Jz>U`8CRDi@?uh(`37iG6NV@n=6omZNQWZ{$DaU{pSqNf z;T6Nxg)OMXnDQ3XI`3i&n&_#*0!$dxcQEBEm}B`PtnfYgeG{el@VkDTA_9cjX!lmQ ze}6rY-w3)9!mptw8(#?~ZBsbE*yLi=lWQ?&5d*uJ4{XNoUsI^jj+Xp*>*H}p_I_kk1AwpN|Bw_ZSmk>vYgI^WqF|IC!tmw(ppGnHhM0eoBLwn4wP z{P9}OalnwHfZQX1;XeaLZpzy@=H0Oy#%>tDe*F6UwS_xSh?ccMMc1~yuxe7tl;u-D zL#$~#GB;nFxfL+`BfuP9Y^d!a6kCwSiZ~f%kecN zWnsMwv6Q=YsXi95e z_@Rs?cMC(#W-EqR#0gVo624BDHGw)Q*w+Kmj5PgOEqzPh%|YS!Vrgc$`q-se11NUd z55zmc(?@-I7p?e-css+theAB-D2j_WOg7wmC^W7MSm7p;E|_7Ag1v73`*J)gf?7o;WnZo2JY2= z+IKw9*Z;m^Q0+*MPLhHfZrG^3CD#8%#`C^N2GqQD0VE_>I9jn6%7)v)v;c&TQ4Wr* zk%=1;POi`QHFSF83bI9aVhTw4`U0_d6W)ly;E!~!g&L~@4eNP$3u;FiD8bj^2{gc1 z10X4oTkgoEoAN9}0Z?3;O?1i7Lq$2^sEP10aYnjE5fL%XIvYieB5N_;__z9EpaAu2 z31)4EYmm}cP07Tb z-bRfZ&kR8YwKH<}qGbl%`gb~B)Q_wikX@)z1U%}FGh}SN!I)dP@i?xbiDDxi_(nAn zwf=z=unhf=iXEyHYo3)H)oXm)we@8{Wn$^28YO}uD3V}Eg7S>&KnYZ~1Qz{7*fc{y zgTVp_vjxrKsE$6jp<3-1U-Sj=ac_AarI51Q+=uY< z58k>$^9Mh{#^W-iK@ES3){HJL;Hn1W2eD?b9^ov;Oi36^q8o%-gBvgubKBSr*prGs zfe)C*BPh<3g_^0vn@y3$hVvJN;^F%RE7Sb7hVPd^NF>l+vrB$RnxqPWJ)Vy6A!(0O!1*Z5i#gFDuQ7{-Ckz=o%k=5R<81^2%V;M09z zOJt-{L+qx52BoDC3!u@)&^U6F2Z4>F#TuK+bb`y7 zYhBnCl{O}#gm~lb>@UMmhTSkzLJxNR9HkiUe>%VhhW&;%4AvRa#CAH!s~(M?!T-39 z0fWIx2A8m92CyWZ^_6?K^=6k>QCwek5efHW=Ya#*S#NkSt%ADLJ_56|2Nin)M;oJLLJ%`^;mMa*+sF2&7cThSP1vyVno;ITU?lfxgiQgK0EGA@uT`MsXY1XNL_#u%$aGZXAr@o|%Sh80F5>D3$!^dfRcJ0;xVM7Aj{+CIr&tTbO*+kD6-v18 zbq0==y32ELtJGayU`gWIC8(%g`yK9-x=RepU<|pz0K(HSn?;fy7*;%ZBC*#DQ(D~h z9d#8dtY}zmd011>s3!*g!5X5?^^xpP7A$TuZmU-&g(9hfH4C&z6w5h#Hx5;l<~GC_L@`5R9^0#Omu}_`-JL(y&smLm5W_R3MGOkz z#`vow8?8VI^i1{ObzqGpdGQBup`T>swU~3=Mu$_N*F<=FxTE7Of<7_a=iEbit~CQQ ze{>B6b2!Dh)(B;|7KTC$Zj~H?3ze){H=o7`ys_CbSv9jEhx9H|CRCYk34l8@vkD zN5Z(`;n9)UR07$eu>@n##}mNFXsqgM+8@^2^QXV)9XYSoyK;U2UUv8%y(j12=)L&E z@AW>Mf3ElEe7io7^H21_{PsR*hGI7~{((M>^Y;ynS6`|r>%@QiUe7?>frx78y0+(s z>UCW^@`Lrdu7kmUc^;asZTVp&zq?-BwHN=YUfZ<~|FT}&wLkx~UfcC0{yO}?EYVX? zlo@=nK8r8ZU*Yrhx%^fARX$gr&tK6O@>%*~K0{x^r^BzyOL{ky{SE%2zJgEISMrJa zn|uNsw>%HOEd_cON*>RD(L3WMllVS8jeqkQl}y4CV6EG})eK+r^@8K!>KAxl>;NA4^c~`xfch(Q` zj`|_qUO&uvync+g(NFMJ`YGN*Kh0zHGrXyO4x3EDMq7ag43kO2LKWMjk*Q0V^H?;*yAu@vW0A7LK|Re1!*YW}nX&s_^wZiL+otwuQoO5_-ArLrv-G6FZp6iwi4J{C&Ie{ zCeuR^ahFW`E|FuVbU!$Xn+ttv;wr^|XzdGj`g=4P4_rXI@u0keT}%g(_tujh$ik;q zqrF(gDNmIr1}H=6AAgxfsH(<_|8LhZU~hraWk0(G`gj=b5uz1P5w`y`K`xLAJyFJ5 z23}xa89e%E1RTTR1U2=53v7VH2qEnMnSKKM2eIW9nIS3GN^K|ubK}a*C`a)p*KOe%% z{O!ncOpt>e{xLaWT3of9f{$QsM_5h}($76#2^b=PNT4K83MdWO>6Zm^?_GJw6@c9H zRdUF$JLJlc?RsG!Re@@NZHvr}SRG34$!kKc1=I$jfI5I(ICX(~KyIA+kY6Pb4JG#s z4ItZB8w=#-v?1h1z^e$2q2yNWCXkx~&4A`W3m`XQE6A;ZR}tGlvG13Cv;*1$9e{YC zBhU%36SEVt6SfnL%*~n|xigRe( z^aOeVy@5VJUmy{9b&?P$|F4r&$jwbZINHyTeb`yIv)vyU01O0@f!u-`1bHx!>+j5= zT^2)tp+IhKhd~|=i~vRgqkz%C7+@^$D!1dH*vIm<0THLI3?=F*XHZ_QUly zFb$Xv%m8Krvw+z^Ucf%)0CRzPz3$co$d%EC!YUOM%?NSq}MCCRac)0Q*=8 ztO8a8Yk;*tZX`P+xh1q7@&;fdunE`H{Jb^4*&;&_kcsdVc-aG6gUPP2TlO*13F+IxoMq* zZ09e+HsZ*&+t+Xku)|IRXMnT7IUo&42Qq;3zy;tU@BwfM_z<`ZTme1;J_a&@Pk^hy zr@&{x=fE}K3*b8N-{tTnY+nIi1K$AueZRhi?K|N6{}FZrwwu7M{}J{BY(E0Gf&adD zcG=q3>@3SW(Csn|2JGW5a1ZzixDPx4eg=L49s<7tzX6Yc$H4Ev6X3tg{twtvf&74d zu#dq&7a-TaDdZ+VGoU#z1Q-hBK7}tK z=f<@ldmUi{azVg8B%o{o5eeXc2IznRn1Bli0P+BVKoF1@$Oi-ilMp>OA9kMXyt!e= zU(OK$D?`fYLx2pe#@hC=b{# zlZrqk!1m2K>?)d@*gq!FfA0K0HrGE~74fP8)qxs7O`sM~8?X=UZ(?siuL}%<9{6qP zXx8BayBJ^HYo(@7cR)eT!9U65l-JJKzY{C1KuW5Wj)A;bF3B(Q!j1S+HRHRFMc!I`^ZOhAc zUr}~%zal+W0txYjljF;EZ^}GP^RmeB1UCx{>&oIQtxqX3 zumsaX*^t7k;|s4z(%2`-DXVAg> zyZf`(-HEKNdn-7WjfgDQeG>0iDK(|izU`nIj z>o9Od#pLaI7=<%Rrie(ze*eOFn2l1(_vmpx%K^irs}CFMLuVT zb`2exI&@!Z%QXWu78qA1dEfd<%w3HY>$ESaT=x}Uv%dTKZCJk{nFTE!&~nX?T`MYe zsmzK_4^N0MvVM7CjSc#|z`z7(2?_CC5)wSTI4@4?%AveAq@dLPAa`C?q;!FSD9P50 zyK|Zask>8oQND)77wNvD(!jc`*4~aq!kMv#nI+J>&|H-mN2g&6CGG83X;(^N6UDr1 zd8O2jMK+j>Y8gg6bLYWZ_ZP+o6ADAA0^#8r%h!M>mP665Uw$v34KXwIV&Xr)hn=Z!eOX zw21|{L$&b8T}kU%!s?E={WY1{pT(?63V)BeLs_wsMN<1S&#oGQuzHg78~i$RzsCx> zr!W^T)qR9jHM)?y9|iF-EVgiJQh63;bhUfVbcBT#Fc}YJo`mxzE6M^*HaP*6Dj}hB zI15Ha2xWPTHSNmEg(tilgj&Jf@hq>qB%A8Kn%8viVMV~YJBacIOm?B?6w$F7f>**^ znN@F`nmS~I#`5o7kuRt#tGX+x5F1#zNVCO^mN9oBRJ4IC#<2%-PffBcV_OotW=5RE$p)C zM7RMT<|p?|T(V_eqT=M%x$?P!^@t(IwPKY9E^p6Wty#XtMnu_Zni;t~ymTP17?{Uo z?pj8Sdxoxs?;4rcU0N^d_A}GnoK#8oAw!w&RlFcA;kLna_s^?QUowiakqPs#v5)aS7OgZtUev9z;>LNiAWD`` zF?k5%c^OBo2`mkPMV0wm4O>0gLvMI67{n71Kxi(@*adG3$HU{+FAra>F`kDRp)4Q| zI!58RFFIb#>v6a20iBVTQ7GdpJo+#ex;(Q8P7ogcO_9>wSN!0y6EyZS1IptAEcT_YhcI_mMpi(;!vN2Hz0f^g>@Jm9E_pY; zv&+6-+KZy}K;{V{x+f!u{*c*1b8C-;7Op)IT2bw`&`N6G3$48NrO+yCp9-y}c137) zwF^Rv)y@j7sdhqWt+hi!i`VuFt*f>}XuY+~LhG-s71|JOxzI*x?+R_4HdkmL5rC-Tn(U2awR&%v|bJ-s-^}ZU_H~4KwFvC6SRwI384LK-<}DS#R4?a zf>C@_GOJEE%ir05-0$ij4!BZH+G`!&YZ3{XYSnLRs!5iwvG~yEZzaU4d&4e_C*hCd@WOTwY2f#9nD}_KizNB?47&(f{NiKcBh!76!D_CCsdmlO2(?P7QEG)!W7IOG-cn1H8m|^9 zHBr5z)MT|lsi|t7Qq$BNrDiZSOQ~5*%}{C%gH5S<4B<*GVDMGy9fo*HEn-MRsU-~Q zDYc9tZKYN)oJXlu4Chp84a51BTF2B-rLM5+YB2tvHfwnw$SS8zs%u@WOIM9P);ZOf z?=V+;=g1~IOd4n%pGt2U1Ffp|iQ80D^Cq&YL@qWRX{oaxvWv*Zhirwp#=AkrtT1Vc zbt0LD8dEIom}+evQEjzv(~7tMcEU}m$`IGSm#Qpj+P6}b2YoG7MbMX0y$1S1s>-0x zrK$@0RI2KrPo$~|`dF&kpes_<0evV{UC;+o)dyXWssSiNs#s8(R1HCArD_a1Emc#{ zNvWEHPDs@fbWEz&pd(VX1s#&AJ?NlR@u2-ubpq{`Dgm@xs;;12QgsLIkg6vrMXKJQ zty1+RZRaf+kwiNOua;^ku5YDOZz62DRKr0_r5XuZEY)bxyHbq>EtF~;Xuec2;=nk3a+&;+UGgT_g<5Hwb*cR{12S_~Q~)l$%K zsg{G@lxihth*YaVgQQvu8YtCzP=Bd5f|8`#4C*V@R#0!LQb0YW+5ze=)h=A$8X2*h zc21B_$sZz#{vr_!dQKuQ=p~6jke5UN$WOuqNfJ7Ualt{H3kK4;kb=nM!Ve1I!V3!I z;w30A7tcY#T>J&{aPbrr%0(6^jEg6r0$e->72@JIP!TR3f{JnRGpGa?_d$_d+yj;3 z;tr?`$8$_nj*DBM3S8U(RpNNAiC*X88&DN4z7llz59)JW+$~vy`@ev(78jp^qPVyU zdV`BhP(3a_0!4Fi85G0CB~Tm}7eS46qd!Q~{8~}CWVjrjn7kfaxxJU){;bJE!k&Er1eq3w=4d7x6D4B~* zput>h01f409cUOAYd|BoScU7W%KNMkcdye0=5MIDc7cglg@?vT;cVa1of)i8tlHV{ z4ql^6XJjyGJEyzYGd$;u@K`a~2+__l*%)+|$tIvPOg06bX0jRR6qC(CCz)&kdY{Rb zpc72C0v%_vHRu?VZ9qqvYzsQVWINDdCfkD!G1&q19+UB)gG_b=9bmE(Xg`ykLHn3Y z0PSV63uq6MT|v8<>;_6@vO8!OlRZE?nd}ML!DKJcb|!m+Qkd+cG+by*UtH)`CX;Z9 zTWr#_%}n+KZDO)NXd{yYKpU7G2wKl%GH4x>gFtJU91L2+LkT3}5wX`A@j7ofgi+szd5*!z|%+N!In8ol`9mnzIKfAK!V zu)+IR>T?Va(VWvQvY+lDy} z+GfK$*gL_MY}Hq@j34Nom#0~}Sx)x%7NcG!m6LD#`kKeAar(DJn=O5|ZjSX8&?o5L zcYVKTi*<9Tuedf@_b&9^(bni@lCQM(w(gzhyP<8>yQlzv#dG2M0XEy$G^hKb<#bB| z?LKeAY2pO)w^jTA%PU%|1I!yP{_=WDh(}&;d2!GC7!8>G{xR{+)^qJ7S9xW%U=`>; zrF-j&YhG_7amDLxEz-T-&fdNGMg#i z42o5LyeEY5KDysBoz*85EYC902wta{XbL*PL8u_H}87$s!)@Dw@?fb zhVNIeCJGv^2cV*c_CKi@>#If;HRum zNjAD$Ke0Z_R&K|WcS@$1)W>Q;Jq+686+O|bY(?FS{a*3D>|(y~9+L?s z?Xx3{RF<Dh>Li(}Ss$wd-ZrzGEzqIIPnPSw}NV3Wnr89E3xy^e;KCOHcUF@l5 zU#sj?Vn(91-Bjqz-%K#~TV<=7bj?oT3#+opuiHtwEF@VSC-~f=nxIcDstx+YqB@|D zEvgH;Vo`n2hZZ#eePB^6=z>KJK^Yb`2Blfl6m-_2=AhFSwFI5Cs5R(>MQuUHENTxr zVo^NkkVTz92Q5kf?YF2aE^n_zJ#cxc)`zRi-4MDX!`qK z#7#5$r=8|`;itx&E(pbAIPHSghtno#{W%?l7SCxfv@V=JhE|VLCbZhTWFJd$)YF5O zKn`dk!rtXH31Ra%t%o+0(=uoyIZd*^3xzrE1?bJ)E)71Mu&@ zlRiQ!Ft!C9waHKKo750mx=nt%Xg`aJ=RA^915JRoz$U4IX5oA@IjupKhMDvZ!jR9! zpfM)(Mkcm%8h}&~Z#Za;Nkd>?B23h)}>MnRHsE6RYKs^OVDPeko?*R1{_U%`F1Wy6=6&LS-A_c$A z??#jqJe?nvQfk!0{+ROV2rBNuUG-1T@2eK$#6s0f@!<3M^F5@`AE7gaxClc8% zd;|C&GK4mZc%tl_X!gHH_P;`I=6PT+PYK{QPzLxOs04foR0BQ*qJS$vG;jfE1e^t0 z04IQUz#*VBuovh7>;Mvh%|J4+78nLB2gU&J0uzC`z%+wJPFE(2oP)WxkV$!2$UDGT zU|C+4UFHj>4hdgZzDW+CeIlDte@r^5*|Hty>!hlo>fkyr3nPkGQ`guhVgS*g7#6Y# zNJ0|Zfu6t~AOUqKVKR-3Ahk+d{GIA%J?5yTDp7D$U6myG7EnLIQ4>{v!8d^h2)+?C zQ1A_)WWiBA)gZx9XVqZA*Mf!!`$1Jh1z!z%Q}9)wVS=v&4HtX`XoTR)K_dlU1{x*o zCsd6Vdf6MDLSGRKV*G2%Y4f+grCRRsh%6i zJk1kX;{C5xB_0vTJU`-Alm)&6UNhLU8I8=9mXxD$-ep!)ee=8(XI{j48=2}|>*X|< zXIo9`fi77h&J@}OD|3u#sENXugUq}wA_suh3*T_$X_dG?mm8{!pr6r>af|$GUzZ&vY0w%Qgcg)49v4#HPB(j zw63~h##k1=0+V#B46_eTuh9;(x25!Ln0R{=@AH~OU&xJSlBLl`nB=E&n@J-q3RsAV zwxPyEt2oima;`bi;&?Ny@yeg%LUWq+hUUSnWa76K)i->?VMcD|HrTY0JA0`eeDF55 z$TKjFd-O*X0k3I&x2xWq!y3}Gx)zzncC(OXiAH2PYe^AUjZ-Znf0jM8$l{n-anB&T z=QOD%SCW|_=TNhogU^Cn0B3-fz-gcra0+M*oCMkc?*nat698J(kmEpm;26*WI10oA zM}UsNVW1Om2;Mu0JhA*--jEcC{gD1PaDQMc;u(sWqXlL;V`$(ESIA}rCzrvq zju@VNAsgW}7^V&2A;5ZID6kHA6Icrj1J(e;fz`kWU==VDSP6^*Rsf@c<-iyKtq}h) zU&vC3Zz1_5;BmlWU_7u0m;k&BOa#z)@fyJ)3n5O1`vUM3U_LMvm=X+5VG2dI@)u;0e`&se$Ul7#10(b6 zNJcBfW@!3fDlh%!E5lSmn2rt_AHdagQOG|O6AXjRRj9v%%&kJ*pT_xo)bH_l2;a4| zvF0|B$d_0iohR`=7D;UfPZ522AJK?5`7WW}-=It8P9ZP)Hkqlyt4xx1;sJpyJ*!kx z-v)E2<)aN|X-wq$@MdphQ8|4rFDGx%P;rLwo9JSY)(t1yYiS8)A(mC>fHg^{TcqZQ z%Ki>$qS~78Svs{bD@vKDCh_f-U+J_^uS}yC`~1Xd^hOF9x0^y%qCio;IrqW7m7Ad3 z1v>$ZN|GJ$46{-yLGj;xP1IR_LGP^8e#Sp)7@8gLM-K*z1vMsu7FrLrWoVa1i~D=f zF3qsS99ZABj(iEKVwF3HcB!-V`rByFdWjppPhgF*Mq=7P?Xteq79!?EaX$qyH(6pZ ztn00F2VMl9H})f57pqy4IZe#qAxGv1h58mSPoDWfp6p576N*;$Ay5>!4U|EXR{J9g zlXAWfJt?)px~8q=_2gxg+h>dy^&K$RTW9E?*-}uk4P2qKRLwuw%qv^?=!DK=)Ki8w zi_WpOcu517kY+4!7H9z+1>%9dKo4LW&>vU}3R)Bf66bvsqtlU&Bo9eSXv0Fp0Tz;{8w>Fw!+C)hfE)M=2nDi%aNr402zUe( z1s(z=fCoTH;2uy0xDAvCZUL2m?}5s|H$XMuOQ0rj4Tu6h1?mEsKs0a#hy^YIjerXP z-U?_qvRn(~8K#;knnE)qy-mD6wZi31%AZwuu<&i+O~g6gAI140dx`q9jgdtkO1Vj< z;QAAVv4IE678G&{7uyc7UkdTS(Y&nGPHE~PeXmpGb?;Sj$9p_8iWr6v^sDy|8e77! z`zN^0SiGV0vhVnW5cWxML_j?hZWw}?41+e^4Ew}=dM8Pwxul1 zt8e$JJ_haZ_BF(IFTbvL)!&pZX>nIodsV)H3fG0;@hM)+5z=;Vq9Ibeyr02*3R|Se zM}}ZNerySLrC!yu0>~h!hEQIPm-UwH^dV{$4sefA6i?6fSpm>UuM^fLh{8KoVWQnza3mifUWF>fVp?CD6^! zyPmFGRGs!!)xPwJ*IZv_&Xr|)R=(N4L{`B$PLznCH<|k6rQ*`B{ zQR~MtPtDDF62E?_0;qZ?JuAH0Rx*2#+Fh;E^(tTa`R9o{{FL;ql$8~Ib*<;YKUF?@ ztp>{que4uVutj3T*`66rZyjS8&#EPD&48DAS;F1Xv(Dx;{MisR>{9_K%=V~XKCW*sJtyc8FG{?e8w ztZvr1iz;0Wkvb~lNga}%aZ$1>dO8xtmMVLb+94B3ZIk^;ZI;P+ z$IBt4*2-ZRg36Jkmdi1umdJ7Fh{=hh7RV{2=E`ZfWI2-&wh_uXps7mE2TfA)9ng3s zu?I?xRdN|U@-H84wy3tGw7O0U_oG#jZt7sk5 z-a3tUU9g)g_vGNkvmB_2Z?!q*7!*Qd@Ks7Vm?(1b&YW^IoKO@}B4i z@#oOGqi%4l3hd#5m?Y^!Y9AgvwV#)O)``?X-jURMyau!mqz>azR7ZF-Xl+Ry<84SC z=RKgcBK1CRN$MmY0S#N0PV;7@&hS}WCGjSt&hf@~Bhq-O`-INXC5o2x0X2|xkzyoW zpjb)gDNa%bHI$T&Yos)4Ea@CIk#v@tN;*T$B%P+_l1@1{Kl=Cl;RZuJqaoxwr+gWC(k=dpTtEJd+YAfCQ$lF_HA15;*$F`rkNOuZ(lV$dP zGW+D%wqtVCy^b(5p1qySK{>YdG+4Tql6RuaUQgyI*#1~XqosQudB@0QWKK$eWj;-o z?zhQ1Mb0O4mTj4awH5bUg!$rWWWH-#rjU1$biYaSQDe+iwq*=?S4(WoTZSrSZniB$ z$h$?lyJLG!e=<{TOCou9OLqs_j!J1BvMpW7dst#~*nZSn^As$qO*`_QmhKqBWK#<= zu_>b+9k;h+V3$T4df(oofo&VD>?!<~Xx&r`OmSlu2R3#zqjUDQ4(#-3f;Lh$CT#s^ zMCYYyND}?K#>69;nMD_*ibH=7yFxyY7{6V*QBM{BP@=M3w)c%(kqQm7y^#caOWq*u zvaCZgO}ZP<3v4~f#=S8Z8lBh3{9I<&BmD#Eu0`H2yRe#yN|E`U%&t!QRq1|>yti_U zg~_}tvn!DPwRD#v?}Hqphs@t(b_D4^N_S!MKFKk<$ox}g7a;u?>GqKKg>B>*So>vm zKKe_#UF6M@9z~V0$3U@X3}b?9orH8t=C$nGOOKfutg?N~RPJZY%hdr^vqSb%W)^(T z+COIApw6sz+^@`x?9AH##Jpj)dWV@6q26HL;SxTX5A`GFtqL`( z+=t9;qOw0`Z>Y~$4Mm^YSAEq!^CzsfqD&Tr=@M2)(MRy0E3B@f%dB3nI90yBqDw4V z(Ff>H(M1-cu0MV2sux*P~ zNz}c4%@p3jR zuQc9By;d-1GB9-$^Yp0_Lfwic4t$~V&<-TfvoGaL77j$~8^*FdDbeKVeU~Dav$&?` zxt}y2=~(fxsAp5x+7S1{X5=e@4RYAm!bzaRuhS!s@hF^rD?q;%q`R&{Jya8ZPU=nk z=XBmgojG@ zFauAYNUc_$jfxKlJ*0St40T2hb$jGAU>7LpYxQy}+M{!~y8#do1m@2TRNO;VRaJk5agu90zZXwr8C zR^!yDFpD@Jhz-!)2P##Pln045?YyTOx+oXdvO!qET*nS5?AD-tXE)fT!UEm>n7unU zUU}-wSGWfCPSYBhQP^{Haoj?p@t-M)dUo~f#Kq~XL{`u=6{pVA9CjX0bS3r8`8P?e zmLo{5$az%^wZ~!~=g%VSXjbd^AdHT+fuuI^U-El+>Ci-;L~1Md<&WT%Ln~L+;!B5` z!|z6%;FT8s80N06oAgt-3V!U-iGB;?4|#!KsL+gB{HoMz`LF7{mb{8v+H>T!TGg&z zn{l3D;rBC@DeIEDBBL=EDPu`pkd0_Zc)L6P87Qt9eEKhiXI6_^pR9SJ25`@3(=|^u z;5uG@HBeI50@+7*wqWj<23%9ssF=Ec?Od2gUJLW!YTTE@ip61`ou9_bt|2-&9NKyQ zDYO_;7kL9xAMm@-&?Wm2{Y!P3KcgS`8>Bwsb$%)QF)y~UIoGndI~aQ)i()%Cir%QU|rzI1m-4T!CU=J1YWCzL7q?XFJNG+16OAF;> zQu8nh$E1Cw;H+Rd8@J_cCFg-AE4dIfLCHlRto2wShej*80?G)?Zic$E>d2i?dMUXZ z)Lp&AM5@Bhr1#kElARQPhm}fDO1=kUC)I55hU7IG9Y2Qh5prJ?Bz_(TJ&_tfG|{D}59?U@aEN~-_(3OFMsaGOVC3V3TG7-y5@iG`NNYP^3?q_pUTpMrOL_^3Cgzz`zzyc&KEG+O z2DdNBm#xWvS_aTdyNk{J{j7jET2)rLVo6_X4b$`u)(}nKY$a>@Hmkp;@30azJ=N;1 z>3gjnnts6Qs_BQU&YFJIir4fLRy$2UWwqAyvsMdDPq&(C`UR_zreCsRHT{Yejcu7$ zEY)2gU1TZB`G*_Cp1Ma;=6UHFL3*Y?3Nz#lrYA~kG(~lv$pW@MDzJqzmrK{?nXK{j z>eAXqQI%}_{o^NTvOHvfv0uFui z+G{*hm##{f5NSXi*z}#ks?4L1bimfnYxLlmUkevb+IadnVfErsBW(Lebr!fWjD6BI)%46HlH2;NXwh*qLVPE>tZ~e-n?&7YxwjOI& zK+7yFT;X%{7@EtcpY~gYw5X$YoC66>wanlAt|oR`@A$3eTGVXYzN^<;TIN~5YpiYW z>9@vfQJro377Q~p7x`V=ZTstfYnK*P*0!%5dR@!x?RR})pBwuozS5$e`{r_2%CgZY z+bVt+(`$3AOf;DOna|Sns4I4)g%hjknfMN&s-4(YpH)MTT4&p5P4BB`Uh}#7*!EFA zD@l(U0(-_3Y)D?BXQudEi)SOGq0d^TN7b8+khj!gmZoQp@wv{~A)!7iLyrowLxy8B z^kY4+@u_krg#E!+fqHMjkEat{nGT#f_+gcErAFJ8NZR zKJdC)+DXp!T5XJ|X?93AwUj@LDy5 zwj|39eBcI^Oey{4X5MeJ>Q6fpDd4jh(fkDVQ`)$|!6viJJP32kM z$O||%ZEb6J5CZBH2Fx7O6&oO6OYMRMs zS#O(amc?h9b1a1qT;^JnO*Plz(@dldYl5j3Sorn@`##2*{9WrUdkvLOG_e6> zjESX}(WY8rVMoX^ON})7a%+UCmRr~wveHt+Ouou`(^RW0KGIxcsUap`i^UwZ*5bpk zJfMqS#OC_3oo7LA;+brJS+-|AfCf{N8GSv=? zCz`t~)x+ee7S@teE#BM2Zj-Ji-)nU-u~x%-V4YcYHu(Xolc^3^{7KGUN4>-Ba6OEL z>D^nkN9UYl;ffuq>dLc>S~Awn{+tmT!;_izI-}|=2+Oj0-W`U?hP8}_qa%Vh`)JS- zM&s12sBDdH3Mx;x6faG;6_2EQYWkR`eR*%%ihU?F1rZl8!uJy#Qyve6UXXTSM-k2R z6Q*tOtp&%t$P=N5P^usEbn~%0hVWSi$K1(%sTHLgLN7~;{WPBDC_aTwD9klrZiF^5 z8Von&2|L1Db!JZ|ZNd&EI;Jow@g~C21IOnX91|HW#>^wU^)U~&eZfADu1VWW5=Et1+;+9>n^w8&2rXfbyF z&=EoLe@|Avi;XU1_q)PaBYRS@25Y`l@lj#yDJ_=T7+jRlaZ%f(*0&PNsy+-VGIu~> zmZbvvb>A|o1Jg&0-ovgaN`eXVKga#lp3sfL)@OJL9bT`4zGPIh?w_p)V+-u5rkXHa zWi(T2)2I_n2N>0Z=|e`dr1mz|faz04tzkOOF!7*Gq{c9vV-y3^1%_1zZ8}B4^fAM< zzv530*Ug%=Rp^OS0HyFdqx=Ya%&0ruF@8z$Q$H$*5SYRc@`zCfgdAeD(odtP5JF%I zN62rC8X+W&QB!DV80pY_j2hr17a6@HwQ*SBm)c!Mg%R>IzW;)T6V`^7iR@#?)n0bg zkEIXn_Eh{lOQ!4+k?^^Vd4Bj{gFqbY8E{qnZ8UaL`<_urg#5_f!AQ|q`F&lF{!87g zabuMJF7~gESAVWzhWcJFL+S?&L#sPl38DS;tgNAS2n=gB-IOQ614uufOQLJjrcc{x%ykB!Cn%QsbM zb9)st)cZ&63B3Wz=+S1z5Y+*bj_+r6W`}(Pe8%SdtzGK)sj2m{3l3HWY9wX>TVXQo zcs4rcDWbp6*y3sHQb*Hq|M9tzvFupA!%fhgKl&8&lG{WRmgsKpQim^X>XTJ^lrk2< zYn-ZrslIK$qwl`hJ74*9#_yRIMKGVl>XOkGduF!qc@g3u1! z8fU1*8oK?+{F%@|M zAq`cdzZkwUxPg%J%7@-frj$ zV|Tw4RF$qOUXyM~t#k$UtkrMou3n7P1FbNrhgt!lJ$hE$P`~RQQrTKQY#rAEh4$iE zh@ox<6(#j^Kz>q>{6&QJOIA5U-4&%t{phi6qOi~&zC_&b#cQO#DHO&IXWM-{TM)>fPXAw8uBxK8&?D*uRnr(zWNJ(Yfr&|nI`MP+}+2UbNX&rK@zoPNRB zq{xp{^jEAs1{1!MjeJ25e=CAB+H(f@?g?iUg@Wz~1GDG&;t6NOd2f)24EjzOMV@65 za_}7?y`M-_&|u3?kBG{v@9mv?_eqqcAB2$?JEN(rx=B{h(npz-cw`6%1iATfcoOKLsnke@nJs=~TMG<&LVmRdhL?59rHQml8u%asN-Y5z3p zh@U!QJx))+?p_*6ixeM=Pgb@5v|s3*X%qJS(q_f`(I6R%t*}^OuO|LEe#J?t zVP0JErg&JcNbL>0#m_3<1e(1bxQ{hFC$+{E*quz3qN9o4g+)fSN1GZ}^;z#u!P-;4 zF{tOcCaK}n_=3Ed`~f!Flugc}h8NTySX(;a>v1W1cTpZwBs_~QMQV)&Vf%oA9FWxXDAN8|s9Cg`P8E@cYDHfgOI*!ceC)Ec=|zk6B?+ft`5V(om;0thAjA z4P#mKI~>krV~J^hD3*lM&;&$1X+CfZcR%4uUH1fj7EC_|XPDCOQeFyBFHzfr;;aDI z%RfxcT!~(;lV#@qAV)ZUIV0eoU(aZsV+@MR4a4{QEbgDMTw5{dW&X=n9C~gVMow5@ zTy6VTR9FNn`48Ja>XLKVKS}dSspnK0I2H7u|Km2=sk{XxGB>ryPR0J&9{Z<3>?0D$ z%~MI+fLY-Guh&!Rf5bI%eu*T4W&d+MuX2zL=U2)Lr(*vG&Z`hV6dd@3|8Kksu*>3= zg1sC6QCv>N{_z|9ODg?Vu{-acOD)ukGymGUD{^gYt zsdRNJ-JMD=r!v{8;A@lrT+cM8GQ+8? zbSi6{%6g}=$*F8{Dk)B7r&HMttdBr+2(-6w5;`qD0V7i^kzm6I9qw>%3f0uKA0cg*)Nf{s2-=7wF ztX+C0f$z<$xJmwsa1%e1qQFCA%@o*(g@ayslshxJVV zYIT*gQ;?UP?wj5@xco6^I!=G5k5jhOIf-=IuddSI0^}7qSG{`s|0VB&JsSC;^)DM- zgM6uaiF8%1M2s^XXI!U`Q?{?Y3$DG5UN2@ZWXaozcjwELHA-@BA`FB?=g>&2Xg zytzh+m{EW;9cNspk5k@>xE+y3d6c1@|7%Cv#SDwy|1bF<>`#aHjCpfyl?Epve|WlY z%qR0BYdO<##&!BQ^W*e)`Z#6#Tz}wP-nCWI>^d+L*L|3lH%C3(2DyLD z5;0Y4l}LA{etxvwzvT0ILpWB@APrjAE&?5$N79Y{hdC}=iTY=^s(#S#+6mlM&Np#{!X8| z8(YTo6xZrM@lDP!ADjKG3CA*`7gWE-zkUk;psEu=EXdPzccQ%mCa-7 zEUq5g``zjpH#7RhjH^&HcKD6T84Et|m;PR*nz6UO`M11uL-X{P?^KU1y106VGw$h) z&0~K2utV&)=|TUpJN=#Vrj5dT-!V*sNj^?W{(q&JMB(?r+j`* z^Yn1|-#&QtxHIlOr1Klnzn#@M#%Xu@JLUYykL`a0{?52%|0y3<`TW1^PJgF71L*{z zd;;O`j9VG$D3t%y=|QnhyVKt(hpum)PM81ocgFn&*HwB^_1Kbt)9&-pK0=QqZk(WT6!)bT=JLP0t*DUy(@OQ=?gLLe&$%kup+MWJRxi8Z3zkWW(4S#3c z%19?2W&bPgfz$5vcgi)8&c%QHopGO_d>($A_k@8u;j}ybo$_6jk7xC#$4&S<3I_!D)B;JLS**u0I*Y;qQ!#Iu>JG?vODab;4

Hmp3;j}ybopK+f zlMVkY_&ehoXyrCDb`b+#iSbj%j-;Ib&YjzwJ(c zryQ8rJALoT%p(Gp=u8%NXBlhtC~-@^5<;hrd%!SlBXsYn8+2PQ%|BHx=*qeRsQ`>xuWZ z)9&0I_-J8SnhoOY+bQ+^-)gi+$!S-ZdCjB7gjDo(r8 z-zmf2*`ImU&-vimq}Wqm9k2cUslMrRAg@|qrNRDDJ=2dsPOiVd!Bq4io$_wj^R9i_ zARS{B+n$Af`Y$y~{7XikHZ}!)+E3QLOhaEQb~O6oFVXLHrsIt3^l{3Y5I1{7&zR_S zRnpKejrC%T^3M9!$DQ(K+YX;=>#8((5Ar#j>n-HlnU2%n>Eo1bpP!KDAY9ugkVjQ7 z5px@G%3EQtfj+j|RWIf%$RE_*-=Nyzb}`O$oc>N9XMUXiP9LX?v0iKg^wno!++@pL zx0Q_2F;;QPNncEg4PH_uZE;f1m=o|B5WPPwFRuT;)5(qN^l{2|o(Eve*Z^Zj^zCE! zV66Nz#vx9*8|)PW>!qLE_Ob!S8nNS1FTTeZ!mN=qkdiOO| z8l*t3eztFV*peB?ow8lWhQfz1wzA8!KJrtx!TvO7I!=G5k5e9pxW@wOrN6iNW!gf> zr7-q7Si3~JQ^uG&_8iKmHs%vvK<(0N=#c!& z)1IjD87Z^gs6S%qymY5LL5|P(eNj@a3Y+Go|KH+1nmaMW`fY5?Hz~hGcc4ib4SF@M zfA{3@bf@f0(|KNJ+?Ic~$;f!4aO@A&AD@d?$r&|9e;V^a-ID1}*_oy@?#CbYi@EX1 zh}fT2E>C}`504o*J1N%F`^)r!7-t=aJfYXW<=g4~(l1^e5xZmA@^ok1lr0luv!;%T zS@+JJ=z4roY~{&6)w{KSczWI+l4FPU{48emrig#Z19|J%u#}>)^Qx6fbH=TmFg`cc$r-|8H?W9xy%jR+WfTQ9mw9nQ>|1oGPxxU7A??>g@vcdfl< z&Hg;knR#Z;oI|)bS~8Qhop%p7p4m<(UHWZ=c`G?Wj7aQ}IAv9|WF~8l%U;%#agE!e zi<&;a^)!<|M2Jo$&BU&oq9tpNW#_$LeWb`+=92k)=4R%!JVQj!Q}fJI?ZPE%W^&wK zi@S^aHO|R~jaNBx{^KcvbJkFQe!S#&Wn6dRzhR%88rD#xu5F_lC3b z+Am8TdrFT~OK&HbtGBE)y=rz>je8%IZ*$g_tV3p0Q-MF$Qa7*f@MCY=&?t2@rl^@C zrl_)Ows@Jz zvDjNExxcEuvzkmf8ZFCC>8g4)8z~>HNVG7SZ|6PZ*-ssrHdvNzHbTxj7OEb2Zj!6c z%(F0=&vDu7U;by6b+4;xzapL7l{Y}l$|n%YNj%lcxchStvaZ5!#~NN zuf8xbfh0FF#22yO|}9nXK)+>A=~Ee9F4}8xz2ZL_Yq_ zg~3eL9GAV@!5J=lsZ)*j8*9M%5Y<@)uS~QsnQ!NP1kR`OtyQ=E*~M&dYF=opT6kv? z%w)}R*;@sidSTwGR+x7xCu2}$mE69vg~@z7uO~SD_h(lh%eNNs$S243n9R5H-bekcMD3u4#6oZqQ9Jzx^s_LT&vDs% z3Y_O<{Nt`xh!VTOS^Ky~TuAvr7AEuUyoIx@Hlt8G+mX+7aJHj%1|T11vgWw#t&DtL zpmv5}dxwIb$Ykj?3QO;QWi)X;^4N>@sjdQ9HL9ER1C)Ydde{ulaOCO-}`9 z5b{}xnr0?zj?3Qt7-#H1;%ejlavM0WF+Kya#+b?4&if1M`7LUvFV_4{aH?Rw+G5Q! zlQqX>@5j!oO*5ajXne?9JsLbuKAT@bEa_drTIDhM!tkI{d*j6ssH(i;V z79DfHzvz@)C((D&a>?FvY5R+ev2Pu-Gc1;4kA;eaZOx3w7mrz(%(wG?zSLI4ZM|u1 z{WwRu-DzhOO{gqhzxPsG_DW;m^E|?PV{MBLSrH^QMV~clE?Ow+j&obqxaP}*jHDB^9tiL8v80US#wCj?3O#;H>(3j+zIKL@kFSA7-+)^H#z*XTZ6xAI7H-IKN|U zy~Fr0lQqX>Z`CjJr9PmB;=s}O9KGh5$=c4Fg6l&4D1B}j4URsS>iS_OYmUp_&B({4 zLTl9(H53aDYDWd2hM39P&btI0{akSD%elqCnOFUc8e%4Ej?3O_xGw#i;)fa zdDIXyS=)K*H(Bk-k7vodc$Vy+W1g|%U5M&;YLA73?3>@^^DS|g3=ruTMw&5I7vbOQx`|o+H=3XDZp4nmv0jsx&mnwPVJ2%k z@ALans?D5)gss1w@%ueEO6@N*)vJ`pbjKgi!-fVYW$QP^qMzN1QvO@#C8kY(&X2t< zA4aL=Z_nAq$|KNaejt12( zr;e4A$$XB>-cc$_tt{zjPCb+(mD3+{)dX|KOxAYZCEz@X_Ays19=}8Pzgum(!~1xG zm)6X5YL3g^h2Uh*>S=CSmpwIy0mx@_WN>P3%yeoy?_zK+#FsPAKAV)viNg3Cta>?> z!%U~+fz5wH}*?Cmn;_MC|KCt)YrvKr?&IzcKqD7Il7}u>Rhiz?W9Bnn0k(! zOx7Hiz5058+i^H)_EWc1PDRwS%XeX^`8b(6H>bAqYR>k@lak8EmP_T-LG82+7?;Xn zrc-lV_G&$QP4=XS%$}*7_~F5Rqxwxrnpf6voNe);0Qj8A6N&aAKF!%U~a|?Q_#{`koVph=)2TTwd-eE_dE(~ixczYI z*m_~UKI49&$Hd8GZRgz?7p08VnH|^jW=X9X1GTf~>;22g{2ffE=D6$)`#VZ~{As)2 zo{#BL_pV)q+|4xD6ZKd*nXK)+Pg0^(!t-Ob0>cw)>;9uqJC(3U>uYf`S#wtZHrJ8$-rQR2s;v3?)3yXg56J+MY!V4RuB zn&Yzfd0douUptGVNuJDlz65SsW~-=x)O?&w=G%EARg`%4z|E1j=aHo4;M^_}W>zSa zT8H15%;&i5T?kHltc&hg7droI*i(<=-os4Rc3!L(@jcdQu9(zyD(+#O#$uf^lQqX> zuh!kMZ)9&?rkd{G!DG5P|IJfRJtj^jYdf!Qzk_@xe%Z%Ty>Zybn8}*svRCVZ7#|b+ zs_uUqC8v-?Y#5B`T3=rqv-C#ek;M*iuoFbwaQG^9GAViy%NqW&pNp1 zwJCg1Kd(jxn9O8t=hd77I71c1y+_B*TGZW~i@l7QtT`@wmw?mw@g%>TIJaodQLL|m zjmM>4my^kSJFm_&c71lghhNSK;u*&BH`LJoGM#*m%U;d@F)}>%GHOVBR~(<=nHe>t z=g7%qZRcGG&XM)mlip?Xbm;o;F*Mlk$G%_kaWa|DaoMZ$?D2F`(z6}q981A@jeAZl zj1Mze+j%wTm$<`8u3zWtF77!eF<;DN&2ibQwF<%>hI7jzMAomY>4 z(QKY(9@LQL%*DOJ=j(cRGMUeD*{kz>Hr~g~^`Vx2ZW5>+NABIjz5bW!0~mWA)*P3;n(ur+ zqsJjfolHjeeDMxuvbOW;cIP`EJr3W67BB{$jdU=RHOFPI*3Ne_5#Zd7FK+xRQ~a38 z+Rm%no$qA&f-@Vn)2P*CPiC^_xa`&1`A#MroEE5^v#392vbOW;cIP`8oqu_ZPt~)L zCNo)cT=wd5bH1M$1Wreh$!MQ9-ee|gJFjkczLSXrr+(61N4liDCNo)cT=r`1d?%yV z=A^vwj&PAlGLyBPSGPOg$!Jb%)J}%b0+N}mIWBv(cD|F*ujV`7&**v^fqI^Zdl)lW z+j(`n^PNv9IN8rfn(ew4Fqp}j|F}|Ez zL{ji1pJd$6Fh1Wj#^>8vi@mzt`Oc>u`j@#BX*TUvz+fh8JFjkczMts{&TWiy8H_VC zS#wVlQqX>uWom~^U<8U7@y%^_SJ7p=G%Gsoea)hq6Fq^9QOJDWjgsB zm%Vx(o$q|GuEi_V&yV;pleL{!^PTT!27_ZFmpsUcnXEZ3d$o4HlhO0?@?50(3VSOv zS=)K_xH;d?;65%sn<+_qaZX?+YmUoa-R^upgZqLgI(dsvFz!9fWNqiwb?$uUqu0?i z+;eK7hM38k_O$^G~EBAI687tnIv-?|eTq1e`8;;vMxcU(969aoMY%sh#h9 zbpEc`d&Z!Cn917Ct2xehGP>SEa1Q@3PwF}R8UQTlAHC01+gaS0 zxHrX*nXEZ3d$o4HlhNzwK$ikWi8GN7X0o>P@;ezk&x-80cfG~43Nu-AT=wemcfOy& zIY<1A`nie^Gg;et`JD`&(?xo`2WW`*0L)~~aoMZ$biR`r3r^otk&a_{FTqUKc3yrb zqv!gGnc~+9HN;HT9GAVi-TBUk&nL`eZRf4G{_qqbEo!KTF&n*KZS@pQ zTGmi)`(>4R>Q=Sr@#vo=G^^a>QB|;aY)B225}MUG=vh^`!Ry^GtI-r*X0o>PE(T{s z!UW^jOl8C~!IxiKrBs5#}3g~@z7?`!0f6=O3J zW3&SKOu^V}z!));HOFP|esD%%u5xzGYODfhBj&0||Ev}!^X^e!GaKX6Z~p`f z)552??A?L(L8zTY!w$)_;8aHK44!hx!eqXkS6{C}?fmJ&J$P&?nx&Zn5k+RnQOob#xi4w=fR0pM&x?MSyW7AEsKE_*Yeo-?6# z{5-2FJ)WN7S&fBtt6G@MxAU$!!2*zhPIKxmo3gg2})*P3;dLJl++9`(lItI>c)J|2* z7c*JgdH+H_r%^k*@tFzEY1GbLe3;3aMWX*BeTN0cw z)J`()VQs-_fZ7>@J&~EL?Y!%7T@z3{*ndP?+y_gccKonMGm|yPWiOvY_^iTA)^^^> zztj-HxaaJ|d8Sv(8X^W~o@aHc3XF+(pJz_oS=`T9V||G#Lr3@=!+D9lr$TCoI9yj* zTvrObHE~_OxGrY0w)0j7zYfOvGsbxuI3KZZw8uCzlQqX>?+S3@G4CBP@0D;}B{A=( zb|f3jWNqi&gzFlNI^2Xh?1+2@p$^-j4w=cC>d{KXXEZ)Xz?p*jiN=SStnIuwhlm--r7Lp!1kMQ5bMmZwikYlA zE_=1!iLt4HF&YKV0*p;8#)z4$?YtwwX@$8uggM&_PGQW|Qp_1MS#wj%ihdbU*S0ShJ3A`xwz*2cpKD^iG1o~FPwoI(lz5`vgWw#eFsi1?9FXaLx&WNnE{-niP0)^^_A;55Ma=x6UM;QWm7>5dv=CTot%UV-a+hkI8p)Q}JEJ7@5m zTLLx2OxAYZbI7MJ>gN?cCBVTiVHx@GVJ2&i%igre=UL<-qbX`=G_Fe`m*J=(X0o>P z;yFk(#MrdN7!^l8PxehP%3_R|$(rM`cPuzvu-^Az&hWe@zQoqIy*<*NcWmzyq5P-Mj9ap8lKeg_LbV&v)=?t;1dBd`{*{izBwe_9 z+QHtVXg_o`#xEZ2*TE?>u&tTjb%JCjYdh~ra0bpO?RdNTkmCh7s{_uMKb06InaP^t zvRCut?}j-p9^CHu51h({3(L*RyGdrUw(}kX$1m#whsv_Ru@{`1rRvMa_%M?-$7Szf za4H_&?x_7J%<&YQNq=;cA;^iDtnIwIy<*HE$FH+WJ5Gc1eaTUBZ{ss2Gg)(7_Wlh{ zbIet1%$Xj~LYS)v%o#IT+j;f4wM~EC(KX8suYbV_+d4^>HBNdllQqX>?{RR#zT}gn z`xit$j)83*%w%on)%>Mv4mm<+mQEd$VARg>fHSEz>0~mW> z0&_b)y8fS)tZ(eVhncMPx^Tv2?`gCbMlKHI^bnkPe{?f)ASY(Bw)1L!8H~-M8Kuqp z;PgQ4+-Q8p!A#a1m%aah)9(6dbHHCQN$0`ogt=;oIb$YkJFjkUl>WT=yy;A@OW=$_ z?VR5_*^`;9IWBv3dk5s>{#T5j=CnXQ2T{|^WNqg?0Zs;t&uOeNoqrg{XFc}k|7AM) z9GAWNK62&YcJtpmVX0&L0`ujHHP1}ec3wS? zWNqigJ}FKdjY<0L)@jGJJ`th?YOoCMJsY79--)aKH_k$=&!T_8WYb6Cyu@Dc#kN_c z&B3^?JMdm;bjFc@>tZHrJ1@pxoWL6Gjd4B)P8E!EgB9H*Gg)(7_F{a*aDC6gygvqK zKjwWi?mf(8ZRfoLPRjo6W&-LE`;17!9`?9UVaZI^9GAU1&z)EopJ$eK+y-YI*2N3l zdzi`E&Wk!1Yj2!3TOE$^I}6SbtkVxzr_5x{aoLOd6pe7t@wuCKhvsa;z7bHpNUC-+ znQ!O42u|f|r_Emv#U$ze;mGGXYUqENPCmzFug-G|#%DQd2=`yH6XSCWYvX^JPQIO2 z&*LQQ8`bZH>HCGaf%$r0sIb1je`B)dxa`&Q=!5#nhmX$TFzz`sac*HIYdf#zcYPFQ z4#vIb0yz0l&%dnbW-yaA$7Qe9gD^HNFh={qNx?m5D(=h7WNqiw>#hLS`_fydQ^$EQ z<|-HFjG3%CE_-#J2hJ_>If)uNhI|qlRH%LvHKfPZ$z*Nk)pa%MNQ|EsY8vNl(R@%_ za}4rfCTot%UY+NS>7^a}Fh1BnMeD#b=6KW)Gg;etHK)}5Fh_ZuGyehS0`58Pm@j6s z=D6(Dc^1RDw<79C=a1TvLs37>WNqigeOBzlIeanpM7=-Y%qzR1hM38klQqX>ub#(jsGlG4i36uY>H2awKFnlo=RF6` zd)&MH4sCbndRvZM>fnCLOx7Hiy}BN%VSW9BG17Ii9b+>WHN;HTc3zx^#Sd8T@2{VB z;QTKhV7<>m4Kb57$7L^{LpFlrJgYF1wVk*3`<$w?@8{|fn_8*rUb)myH!oE$8r@3W z@yMk%<}PE5jA&-jd*9_$&8n3#RxfF$*n0}?^{bVUi_l&QoMXAl$jyVAS(wbX^P1pv zNVh^hno&=6^30`vy}ewn?Oo5pWIo4b?-6j?dq0#d(o|Dp!1+7VL%HZ$RST2(cHY4l zpG}+cD}_&4TvxhT`PJ2#`7KQ5b6oc30w)b}S%I7yfs+=wtV2%BWNqiI56&WtO%9CF zOI%k7#%9Z{H}O?c8#yCKiG-7PYhDT2%{^`F38tUL2^MTQlm39JsC&)Q)fOdKM=0IWBv3 zoqJ=w|FNW*@CIi%YG=WqW)>#%?YtYnIovx--1|+fL``tiux4>ZqFY&*%;&i5-387- z)J`1osR7Ph)Xoaz!%Wt8-UHy2O1Hvzh4IM%&OfM~K#UJFS#wVD7LCgSPA$~Vy|Wu*naP^tvRAL)@yKUHl`_%|oL$H#3imK(vbOWiL_RMtK9{h@ zj$)j{Fg~xb#+b>P+2l$XlAnJ zxa{R~2%lA$$=c2fj#!QJ4E8Zq-z%5+h#H)Ydrvdy{I{-F&xZRM>sjw}3J=#^)q`-) zWA80+hT^(XaPOJznM)kQbuGtrF_X2O_XRk&y&f8EG0q2&Lz|2bjl8(`Fq1XMW$!d_ z1m-&=8ZY=Ju5jO$v8I_!WtWF~8l%iimf_FkkmjLp#Blg!ziZT4g3{j?3Os;M~AH=PEvW96sTmBk^G-Ydh~f%zH5Qjatab z2b|u>r2=wdCTot%-bdj4hq2M;mNMWB$JjK$7%`KzofqeP(GB;U?U=JbaMob1W?{~l z$(rM`_ar!ziWaP{?>##I+6`a$V6U(+nQ!OCIZfopIcg5_X#-9Z)bbeQ!%Ws3m%X?@ zil(^doW%IxoGjAgxv3(?hncMHyf?tXJ}+xxzObJQZ>;qnFkj4M&2ia#4Vu`rp>aoMZu>Tldb^8M5*7UvvM8TXkZV;cM5 z+2k9OwVhY*Z%dHRYV3zN%ZV+>CmU*rnXEZ3dmR|(1sI=dsG-Zq;b)AGCu)e9tnIud z!TID;O^rhhEe0nX^OY;}LkpAn9GAWGz&V8Hriu9I`^!_@yH4Z7OxAW@eP1hyTMxa`GwSX9Q?T*VlTz;%7by(}#?hw%A?nXK)+W!pv@-!J~hx2fx3RU#nTsJn4v)#aH7t6%pwGBOS`;u_%h zTUobGY-9|}e#*DS2mDqOd20kj%adk_s!QR`4c%WI_YKT6SS?FzB)hnr@(o0P)|K`* zl52dc`1pg*-VJ9a8{7R``&~35EPRg3dd3mtbETbM%Bx7lUe2M}@yW8~<+gsSM1*fe-@E^W{;WAS_GW7}(s=M-u(7*HKMSAZvYz)Y*yz%GkWsyCf5l$T!Kd3u8TZd% z<29I%-UZ7k=wB86S#xge<=@xf-|3i}Si|Vh!CPEAi2qYT`q;2QV@imJSlP)#v3G5s znsU?+-oiXnRq=1E@b9*;UNbOI9_i#E?uU3N_VRChFrVYHei9LAT%XxotnZLjv6o}< zZ_r$c2$a{*e>3{C=6u-8zxTm>j>~$&&_E;2p6=pwvXboO9Qe0&1`iFC>Cyif`m^TT z*vr2g!hDX)dIR#Q=NciRR6WUF&Vhe3=r`ok0R1D-pEc*kUjF?N=5t)umj(wKz850J zm8H9Ou$Ob--$JT6Bv95s|G>(9Vp(%;?B(AvVLr!Y9X}+{XoBnAr|KE(-HsxY79 zvR;RL{=|Bj(IKl~FXzC&$rX)!j-dZ^^k>bvv6p|Jh4~zp^&i-ORs?&9nfS1mb4ZKv zasI|x^sqp=9DV2DW6_i+d--=>n9p%pzeWAb#f4#<7b8hVA->+dl$7S6_ulG020#pykWHRr}& z{v90Vb6nOdkxvTt+CW?{dpQUGjlvGd=MDNdMSs?u8+-ZpbePX^S>J;Hqtg@Pqx&kKV)i2j?Y)^O9iAxv`gjZ;1IEm-QUn-wW*Nt{z}dVK3*f z9r-waQ#EmLpv;f{kI|ns=f+b4Z7LoWB*j9rM);{imWo zYtD_m{QF1DpF?q3`=K3siSqf-KaRbegT6mHe*?D*^6^Ih)`{KXSaWXd<=;_aKF4J} z5$mfiu6Gyq6!vlsJMkNo&foUcbz2Ah_o6>*&W*kNdrZvdxUAEop69CW>OhK;?ByKz zw}U6*{$2s~GxnpBtT{LKCg-eeOuo}yeY&$>@^3tGEY_Tl#Y?}H%)f)&vP&&_;azv- zw`;#-&AD;@>dsQ*`&JFj-QEM#zT`ee!*X+Et%N=*`^!+H>vwbIgzv&E`sP24jE}?9 zn-S+D6?;qX>MeUG&ymH}_fZbHRK|_3YnB%S)QW!^$v;MnATlWmE8{fzRHY zMzry$%ci94_)T)=b6nP=jyEzsmD`%s^kJl8FX!;95iKu(nFh=|#~aBK=-&waS#xge z4X+<<6zbO|X>R(#7Cy&ijptm${c5`;{XEWI&S6CTXn70F*|q~y79m*T$Fx2Q?j?fhhVu)hKe8e|0R3*{2&9@^%19HR!WaUg=N0u z;UdU?u0=m6UPH2=$ss45BF>d|Q5*#FT-@--IC z4vqHRaixf2?@_d8JvBOUE84Yp@T1X*+RIGVcHUR{8;in$8Iyu86j8NjRy)>$3;7{UaTn6bsJ+p<$d^@iTI4#~~P=6KLY$o-s zFAh8|uI9z0k%Jny7PpLSYKzMalXbJkKZz-SW>Z-YhneiXeLPTPxtm?3Db`DN+S^EU znUh=HaD>}(I2Lvy3)NH%2k(fKVu?6p{CvgWw#y${Y3B&QRb_0(HIHNkLRyS@AFqJ zOy+Z3_9lWedi{FYs#l6}8S}ozZHv5{KAm7DYdf#Y-+`iU(O&Y!o$TUwiD;%8t`L`H>m@j6sw)2h!=LBl!FMM>}`k{8J;loVU9GAWO!D)nCdLXADaDGKD zmyi=PEt=x8cLUmk?q(OciuE!CIF;w*7FE2%EllRyc@Kbd6t%Mt>s_zw?wG62Sntea z&2ia#9h~n`J6-A&_12s*sGW@Ix1{bxPA2p1yqmyzhq)e&o+nXEZ3dk-E96rb>~ zR-rx@Wp{AoxvNID3s)^n=G%Fhv!rT$F@HsNak^rRyt%oJxZ?TDD7*b;@ND6JGyh@iLQRv9~Wc*-mFP);-CnPU7t05|Ghv63!kqarUU# zC!=3(oIP0k6l^IXZoP0Ea?7dM%jY6KJF%BF$71iUe2vw^37oZ|~X7uyLwJ?*lop*QL zHtPAQjD`=!r+LAas?F^ej>WikX0qnE>^)wmjgpwJX2XMJT-Exj;HvDRUfCGAZgU%D z_&hVh&8Zf>us}=obD2zH@%x`7dygFtR9mozovVIPHs9MwjXiVKa9q7=@iLQRv3CkM z$FVNfU|kg6*GR3xx@eAd!A#b6UfgF@DXi1Kuuf-za|Y|QFxDwES#w>JEvZRfoSPC4vjs`nVZk13p^M2p=2#4?jL$7Syoa5f;H`Pf&n&!|br zXWo}{)Hf#c?Y!&3`32+i0r$d=;AF)^%ieY0Os;?mIofX^Z(ffcp+J zS=)I>fpZP@^Cv!|!Ks6LpeH`eWX*Bei~V2e`|=OS>1S|UaHi{woS4bl&WroCYKgIV zjdQ{(a4KMIOwJfsO2%JA)E(Pdz|Znkq>_4oHkfnyY#(~ zn5;Q2d$)trA8UOu=1XGV*n+j5Cqp_5llgYu%ivVTIlLI^N9X?w&fzstKg?v!aoPJ1 zIA!r%&;&J<3!F`OF6e?9VkT=l?|g#i5OK_GT zAM8ISGg;etbAxl>UUqe^KrdMtoaPuGg&JZeYmUoa*1z|yuO{HRJN=e4a%tn%syCjy z?`FPXvgTOqEs(RF5_o=>`8S(a1AbCX{>r9WB;of5Z8#i@y@$YQi}wk=@jfBAcw@C- zSTlP2K2Q5olrD?KtM6~}o4??%2cS=)KH;QZq_Fgo!J&Og35^Srq~ zI&n7MBQcXT$7L^{i}<|6OxAYZCLW>cbEr@4`?>GQM85&5&J(pean&+8V(9?2X}ZTa$ke>L&sNOM=%?-nNW?YxC<^jFbG z-uKTLGug_Wfb03d+P1L@Q*;KFlVU|AZ z-QZJE4XRd6U3)oQa)0hqdu}c@tbA?dwf9fS{khMxJ5AN(i+NSgtq)D+aDUcKE|ybU z<~Y=gGj5W-r*AY>&Hr>$dlwds<96=P`pJcIDxq;*Rb_dlIQDA2`g&e9rR75hw{w5i zZ@{^Ue3H+(8SK3XPJt#_RpH~^EbZK%^?%^xn(L{`KA&x{HxZoaNgrg}i7}RT?$6o; zr`^utYVx1w4E7!b=eX}#xzqQorJeh;egRIy&6!l4&6xyy6*!$I#>hcQ9}I5i{;b=A zbLr1>a_!FIg1tw<`SEx+S++@5OFQ>xJq?_$&u7afb3FxnwSLp`p}GEgUQ0XoXMF^m zj_2KEhPjT^{!XtR^N3$Mde{Hc&C<^OS>FO@;HjChdmGmk?7afcM%2y%L-pz3c_WlJ<7u3%87$0uu{;X?aUAUrl_RaAW?A@n1sGXjeFK*}ltY0IaHmDu^ z)`(#5NpRv(I~(!gcJ9wQ9rE!)?fBut-aFuwKrUsG6Ss4J)=9_*^^EuU=M47hvCW6E z@x~Z&JNIXO7M%R39pmfza(eZeU5U9mi#cN^_h)?)oHVE%AIuqhbse@x?KJ9KE0){2 zKWn{*#G!V|guU6pUcIK`kk3}sG`Dkq)@Q)^fZ7?0nr5%QmOL0A18a=ixj*Zx;AF%2 z)WRBLZ`c2ts-c@c7$I9@EbZK%b%X!PsqveOi;*YKN%mIE(NwKHe9jOztnJ*N^&ibD zswz`mMMR{lVlQj%W9-POW(;%{{)wejV!uE&KV^r}#QlTh{@f?iLswPmPFj(2sIsL$ z_c{K)yV`J}x$!yHlq2?qtNuIE<6Z9}$$aj^?aYr^(@BZ$@y3v=nKFsGn@$Ey^ z#AOwX`6bU=&RX1``|ufz&uQEze%t^d-w$!5oL(dsI0lGq)70+BWy|D`9--n{RiD}) zao%HHWOb+r=(5Z4cII`--pn8Ri6HkJ#t-9{TH3k)(Zrr&)x*)o(=AIS_vb$QK6Ms_ z`*|9N{Vz-I&wbd-eFhy25;KBgj5V!~$i06y7FkB_HoA^}Yl+2u`ZmufKBvzhJT6vL z+@JeIv~40j|8drMx$}~R$=*tS6~&1-S23-ptK$CL=W-mQKLfD;u=gf7wXh$Ke_YLz+qpmM^ti57*bjR(D!qff55O6R zd{$t8=63GS`Y!T$jC@LCe`c@qTJqz5!R_3iwa)E5#>Wfy3--Q6KF<8aDz|fg))~MN$fYcD zVy~W~h zcJ9x5F*xB^TXk?xW$zhq0&#w>gZbii?$5d>IA?Kwo`?BjuO8b!aGsxv`r&r&&pHR@ zs~XPp`b_q}-XJ_*lt&G5JNIXeGlK}k^F>$GkdEv0K7w|^^UfL65Vu?UllLfeDLn7E zV|}q#ukk5({t7`2aXa^CogLS863<`P@%+VJeJujdgExaK#c@0LXYB&cIy?_f*zr>w zdrMqvD()knD*rt+xt;s7UURjam^RI!-ad1a?49q~RE(*dP5oK^S4%thXPv%bMSM>? zp0CTyknCm6eF{9xDMDNNs<|x>%I9mFh_buWC{^+gi zuOi8Ft<3p+y!`pkaIrO^pS>~R7=P7IAz0l85V?*=WAMaar2Ef8%!U z&$@cOZmRO`8^wRxDV@j$3oQu&rNdG znR$}E{QipHoB6itpwbQhB!9m8(qug-Wv9%cnyHK>9!mD|`!R0k{@G&h%QeX@)bJ5o zCHLn(5ym`O@pg#1;<{IIf9~_C(sNm2SV!eoqnf1;dsz?aHd_uH&`&*UE+l)aRDLc` zp87?(UnvsD?cAUBcyPLxAEf%-%o4}mC~%%dc2xc~s~OzR{aH@{CldMiHx~wb2Y~a# z^5*Kdvl}h#+@JLta6UwJR>3P14fbZP@?1XL=Zn8N_+V-0{;X$%Q}aS&)xtZIU~dZY znYzhcP2c2hY3Kg`t1|{wR>|!v3-;axXZeE<^2t75OS|?u`?HQmdysb~Rp~-w!QQ2~ zuD)kC%IAMHx3qJA)_uW=UYRIAMs*hK^#-R$&1y0!vZJM)`?FpMP9kcj-++FCy%TX= zNADMoOE~q5rJeh;-VM&$$2HW4|@eTn^8NB zmN&PwbAQ%@!RdRBKtfzuA2>Gl;O|y3%I5jao6S2m)o%^%i2F`1Y&p@m(_U^{K55jy^!kXuH z?$3HBI8`uTZL#LryYIq%>3`l`Y^zz)($4)^KN>twKAT@bEa{Ek`Xn#E2jh0`&+o6e zKleE?P0Fzs^9a{twH5d0KJy*zRi=CY7(Irrl>DxY`?F>yd-=@6@4L=i>Z~5sZD(Y7 za$2(Hvk-f`?FkiYb4bVeTh}DNgW_`+>l%H!if!eBebbe>DcQ^KwV1)k9>w;Kje1q&pP^RJ|nRovUe~zz8Ig?*q^zb`?FpR&MS=1 zXzb7I?F&vW%-0s&FSwoiv(~xk`$c=)FW7q@^ZwV@`xm!!f7ZBn82bK|79aKwLO!v` zB`b2`cJ9wQ3>L<96=PdI&g^F*ffpM(lkJP65o-Da;wSbAQ&e zz!8|Mp{ODD&H$%!iF|Rfs3C6W{;aWA8<`F?+OE$(>}^ryxzP=^9EW_ko%^$%2aZH7 zha(^Mt^;QX?p+UYKIC@p&$>UYCT|8e5Lk)2| z_h*eWjDfSW`WZFE-l5>==bdJ#A#UgXtjB^g1kXD?bq$d>Bj#%^p1;hEzH!{n{aNd4 z{1wk%uL5SovG+OFX=ywU`rvtx+qpmMf#6_2ROeAc?45G)zVS9oOEoOxR!ckgXWc)? zJY&VX5Y_M09?4#Q@5JrgpWhd8f9~`2)K24ZTr-um>qE)?xzC6@?M3>%DRN-z9FpHn zaevm#WG}xL;`dA4lRAsxLu2La_(hWS>&ackv8E$szEz2mz5I@d+qpmMV)eR-$;lOE zhUtGx_VPO-Zs-22msRN|X7%4_e!_bj_VRg#&pF(OHFMaTCv6`&x=yt5;!Iz)xpe{M zdBESu(f&tuXI&}v)4?aT$I5 z(I@NrQX*~t&&FeLSWjqEKs1*AMuv7jD)wGhosB`?dx<`mDys@j3k&xSdBwg#+11Q_ z1x4mZ)x^c4Cnf6H32`4(s%@w@Fm2;I<_qyTo3Hp4zmMpjKE2thl ztR`-P!+Kwf!fJS@ydtD;cE#Q-Asywqgl=jp{;tetL;-c>fuTliSt1MV&Z~O74pgq? z%2@QA4WTmqvVkgBu?CX8S9^9en(XYRqU-FDdDe#-h0v!g`sCc5SM&oXGdQeYMHLWF z5o^+_C6c`!m9`imn?vPqYkR2n)7?cxSg0KTpHRyddx&Mbv#9U>eIZ%*?1eLCn(tKm z7FiT~t5n(|fBnko+bfT%_O;LI#U5%QI7Pr=9Wvcr4Mwanh{fJUFY$Mg~jR|_}=Nr{*t}-()TgCj{QaC z>iCcRwRHh;zPm%5=)X$xT42pv{^KcvbJkFQe!S$D=J6$CX4?*`OZZfoq3&Gc`)R#Zuoz*{ z%iLcZYh;K@H^?=Ky;sI{7ycXe$*ExtW#2Yg#e(T=)B(@DX27~+i#6|c>@C`*qdW}G^GhCyyl2|&t6icBsLqHrb;`v=_CBq$ zMaEa?tJZ%wZf=_4u11>;)a#Y+P2Rg$^Ipf^VO6#mCOB0-A2)f=eBvB@~Ln|N6q0YETdFBo7p1T+SRc*%lWMSQwpnm%HpO1An%!07 z-UsE|oONZ>ou$>NJ-^8!-ZfQ)b;aZy4kaa-ktg6kVHfq+woF;oGdEj@7gD#sN zqnewXGhYkqhMq&!_95Q#50ziC_pRFy^{DoIGu|a!x;kp9MOe#&v6lH-So5{B_l##h zb!6ILS+>~-$+0*G*5jl4;{QWTl@DSy-G>E zYIJ%xLl(Fnq$bULWh|QFCp(TAqIP9447WT*EqX)z0QIJsm(g&-D9PSW^ZKg~@o9|Z z#pg-xW5;>tJ6!c}iE*6$tB_>xxwQR7#@M%x*%=ng=vu=?V8|Lr6Ys*Z)tDi|%hfO@ zBOlfcQo=>6pSSv=fu& zr&HH_Q%v4_?e^#R3E|@3qZ4H5eLqU}zPiv)JZL*q{?RjBavwVm-<#OW-#6=CH?P<^ zskPxZEkHdw=qC2ZXAr;tSInXhF6wH$@+%>tLJY-T{;t|-`O6uVw^b59Hmzy7hw}ZD z@44*d@3!SL5}%z|-^yQ3dLWj8SnTER!d<(lt9VBoBMYmg@!+0}ch%yfPOZM`2RlS**U3Q!?MCD2GmqW*%kmbQ?4-V@c_tU7R zFB_`|`PN##=Ze3>itpWgPiH-0SS6#}zPhT`x)QeEe>E+(mk~G6SDndUTJ0WQSUg%# zNIe|jYSDxDJoCBwh=wdF`;5zmJR8Ag@i`*$_9&_jmDkZ5=z{ zCT60~(GhOaZr|X&g}wY8U%W>J*gU83vkZIrJHhyw$nLo*|NX6w;yEH!og6-$b3HHthv zA=%5{ky1Ubo%q3RvvFz4aohJK{4RyP{GBHp%Pt>2v$2=IM}^;2^1B+=oHKj*J4X17 z#CtO9k%?`UKgQ?4lM|A?{M{xyV%w>a1veWdryiGf?|=ARE_?aAN;nqhz?$zV?B(x2 z;df1T`Ebtc<^MCzdlc_otP9QTpz=)HFSlcTv6ug^y3r;?Jy^I)uE6@@XMfiGu7JJ# zf6qA<=fIlJNbKeR&(7~oIS1C9Gkf`O8nZv`psKGwE5F-2)AE0i`TrVoAO5>X{=3BY zX>u!{V1IS~!$iyf`Q`ts)x$Nns@k}is6Ho~;=dc=zx~Max}%bvrW&<6p0WI&DgM7v z+=u_(ga3A7#_|GAdKG)hZZoxZ~+qpmMFmN91cp~#6C-x?Sb6{IjnHOWk?cASrCvc7|O|Say z4wCGZ;B3dZo|#+4UGQ2 zvH$B$Kt9dpR&j7U_h;P~oJ+{Z$aKx2<2t>2p=V)yYS-RiY3Kf|8-a5V<1=S>kip*7 z;P_#_(ky)E;CAlMdN4TYP&;bmGK0M*!8zdZolL3rou!@ov)%?yLdp^8pK`=tudcl| zsOP}+wJq)3pLI2GvZ8iQ#y&CFyAGVDsGagVnp)bqKkMe;T-y~SUoA~9*sIs(ka<k>6+R9uWW+7Tfuohrk0Q2?qGx4xj*aG;4JiC>AiANPVv9qO{kq< zFZW+7)Ch!uYUP?>WmCymM4` zt!;2S_h-EToPSX}kvpCk?A-;$UbL#%40ch`pP@dC@1x=rzBJgWI`3YrRG; zV6OIJ&e)p(&cR*5#?kS`y}6zHvmOG@9n?q^>A=bBcDju zYo?Ct^y5Kg3 zyGb6R$W#x@-xu-U9kD*&!&P}@D=cQ_DXiGb*RpG|zj5^-{$@5Rs~U^z%K5#ISmpLY zvgYe$?~=v-@)o>(;blI@WjzY{-H$|9e)?sQh(&hGnQ=(VQoH^J09o z_Y%C!=eVr%VSFMmKEuIhFXvF^YyG%X-eVL;K0`3SCHJneXwH+pqmWNl)K3<8na^=q zmq$JWz|RLhdpU>7$R`DBWO!6o(FOTrMg6~adttEVJlUIPp}$OX=!=*69G7(msG-foz$G4Q&=%Y2T@ItTKp4Zaun?ByK#BOhHm*-;0- zA)gGG+gg}o)|?xAgON{ir9DPYc$v>}S?j$hWzQNzfX`mep)&H3SRePXPFf(JpHTZP zum)IjZtV3$KKs6Una^=qw?aN$z;6yddpU#o*%Nk5o z5qxj(*~>YEAfIU5pVMQF^#9dW>@V;_4nh61=G@pj2lMg{xtB} z%Q?iOekx7zP(`qZRK)mf&RJM(#2&$#b7Sw{U-lnW3|{7QT-Kf#AFxyRAog+&*vE_v zhnlMh>?8LvK5f4DQKhj*u;$#@i@jPpz0BvhtY2V!nu1>reD-n<$(XN9AG)ij*hdOr zd`1T}Qkk&_vF6;^>yCUf!uuFr=5yTtBket-tE#^5?;s`gPUv5XG?AJ@OYS);AiWo9 zQlu$OX#qnAL8M7lsz?n;hlG}U&jvxHD!qw-NJom)AZVU>z?U&wQEj@3o1Ut{7{hEljv_1TnRd+eGc>y12{5rG5G( zZXiAH$$l9($AL=?$JBn5Kg^Sm?(rJ?>>?Lin|f_a2ViO=H&N{;mAGg7b&02a`XxT7 z_tjSR3+&7tPcAjoke&y6#s|tH$JKtOOMi5l(gBz{$!#w^e~NogT-v8!;$Nj_vg{9% zeR8QGwdV87^gX-A<#ssh6rWsm^xgJ7%L6cVk~?!&EhkRxXIAMQ0ru&ac#q!KcWOTw zo#hU>{96P5{Q~dk67zm9xqKFu^Y0pn`Ml%?Xuva4KQaGCgIxaYL;2BltStRf`M&-o z#(1j->wl_W@%FCPIso(ho!q-e(#CBmlF7U`tA+XhgUgMsnLHiq>mq&SPYX5zvYv^4=1?$KeSK3 z#B-&m-_y8+j@thrmm1PYkAH89`%c8}{*PbVf4IqeP_$3K#N3;b-(>Et!=Kt)kH{5A*KJXvp0lJKZ8zd4_5~ljW>WoI!TJ)_!Iq?Pro3D?1s#PV_iBb7DE` z6PJJ5%B+AB-sd`Va{ckI=>)yt?YOep8;w^EN6XUkL;vYeBM?YBG=XMyWUp@wIPl+4?vp%uT=InV}+gcy!Ood#X;o2UZ7mU{VAj?^w*vQUpy{nJhGbeCe z{NA@kDy7ny6U$kj_-EOf{Xw%z-PDH2?WEk5c}h9ok+qqb@pM_UL?><*ZMl1$~JN0y5;|X#xeW=a0!YS)VvUc0x5)G}M?u?jmt3CUkIe zP8k`;a@HsAEjv#%c3mo1IGkKJm-djJ6gsbDIqMVa%+Wrev9X`>A-Qg@h*W%vdtT;e zzfIOBj+7nuzQh3CxgmF;>}*O~%~`u3(Z_PuC$26#xAnfBX}lo!3)v~Ev&uCQ{|hK* zed0EieXHtq9o(}?*u;NJoS65P$>rZ@vz+Ix#5|KFm(Rj--q9uI-^i1@ z=$pazy`lZA*%K~C@$bI*_u$0*dp&abx8BuW`_wKQ^Lw>(t9m=TA4J(5`=^ciD!z;% z4*0t^{Eay^&?f%|hnRoALvBQi5%$Ony`xror~0Uqf7?jB<4BA>Zu|c{p&@k~a``Ox zpGMn*ergvvc>6e~YuX6=_x{@=QwK#DVm>3e`?`#<&y_2*wbJ=XKH8^W;*)uX*jLQE z+uHW8<&aAa!~co4(_Zcv_iWxcXY9jp`{#Ly8#^k`5K|ku*?NtzmluD}Tj|0$AMMjG zafaqY?3u&!_{u)99CE3lvh-x~T-;u3!8oUe^!$C~tAu4aBMdRMk-I~BLNgxqo*g^P zNBi_ke6ZCJyWqx|zFO159CE4Q^7CkWSi(mMla`KiKD`%ir>s!WTT<~MrZ#dX>V0h( zSHKrBwug`Q>6dtQt|9iIuYdKuTfBrrE;T&=E81>f)R)k8%{XVrAK`W}d${*mwg^K^ zZRGMB2((YX#QZx}a`_Demh&43#QZ)0xqKFu^Lq=#d`5El4FrByfq(N$%x^4^%WojC zoPS$H%)d(_m)}5OIsaypnBQ0+m(Rj-#*>&aCzszq;CB_cA4|+VTXOjg1eWuA3&i}p z333m$><~AtV>gqb<^{*aQ-w4Bi&;+m|Ej}h;dd4IH%i3(1_inN1_HmU!0#;(^Y8J= zy8Uza=E*-yxFQs>=v-Ahv)nb8HVEzpKD+ zAP~QuYlul){i`oasS*yk{FcIpa``OhpGTYHdp=5t(|9rTUbxvG zR?u5a;{`FFk=zQ>)8Xru-b%;E`DmYhi5oW`VoDXt<7@HQa>%8IP^~o@6~DN>r^eGr zts@TX{VHLN##3TyBbRF&+NWP)u6@X*2CiSYt|6v2a(}wk&&<#ARzk03i=5+O{Y<_s z{XOZD7CT(y5K|AikLL9^om<8D=2o8Tu$=XY`HbY6HT_NZ9(R22zd6leIqMVi-I1I3 zc|TKWYXv9iz&MBHtWV4~NiM%J!gAIpW}hXO-^ph=zg0q9vV0eF+Bxd{IO-jT+-*7P zI@vs3O!(Hr4!>K%{7K9l`zkKK!%x4&)JDJj=1HEPT04o;%Gz@Zg&VFziMduKm)|I6 zIlrAk+<#&R)9JnC*73w`4!LZ@{EiCO>BMZ?uj2B1$n;B0ZSac<@b|W&TqmHmpa_pp0jhIRlmb`4!I#$ zTU!OTl(io{4Kw^c4A-H=T&uo{%kMMOFEO>zFTX8QI%8d{Ww9LM@8S)aH@r~al;=CRJS>SY~rW4CC(H*ct~?>E!D zEN6Yv+D z?~$FdgT{FFOAonjOm^Iz5S25&q=)6KPwckI0{4QfI{(JU&vlSI0D&wUnh8%s;-_m%p6#iOJ0`falQ zfAL_wtMAp{-8lHUE^e>3leS^!jVyP${`&vLr3bCBPOdGq>A&3U((|6$G|OGCzdrFH zm478YEeDP9x%K^A_Zk0De5U?6;e{Q4IqMUH3SJ0YI;H}3PYob`#n zSAJfaZIV^7Zlpu**7y;|T9(f9TaNTTma{%_`6r*4N&N;`i^dLc$nEpf2=lDP#;6_7 zQubDwZZ}|F$t-*P7IK-!V z4zuHaz8aM+XJ&`ovq?I4_^0=_ac$B^vYhpaCw?4b516#VlW^r7hulnuN7%JLjf;Ag zDagli)+bJ%x4(U7bc9v3{bvrjf5wlnpH@rnX^=ggkL9dS{7vE~_K-URtc&;iJLJZg z5%#^CA)XvP_Ip{*`oxdDeeJZtldOI*kq)_P!*(0>i|*pq1d|GzetDjbQ*-w+XuAT168<`pxuRxouPpq%k+mAHn6dOO+ z%^LyStJ3p@@)*lmpIBp}T}yhFzszGcxp@>H-^;w3T+aH$?lb07e13a5Z?XN{ucht1 z2O*vU+h5FElFM12_;=Y^sXTwLe5CbXZW+y4?zIc@u$=XYFUZbpjX4|ibK~IWx;VGy zPz5yhu$=XYH8-=HYs^XUavV(NDtFoSZcm8HqInB#vOclKdfThmWKfLAb)O~fyG&8H zG*4hT>k}W8oy~ezEA-CDbv4wE=^OWp+7QcGpZL1$jGbY{ZGAa!N#?q3c>i~qyoniK z%v+MnS)bT_cSkjk@<E3{`1rZ5olf!lylGy} zTas|W*{X%DtH>E@F(jz16 zU#A86GH+PvWjX5;_iWkUZt?wRPOF0D9da)xjj-d({ay9@JeRAnob`#z42aSHBhKS& zPLsnS_v4!*?8d)#ib`2+LlnzdpLl$;VfM~$u|Ch64}9eIyrrDhr(jgUnZ78Nvp#X? zJHzZ@L%aAI7fA1r+eUV_e)Mf*?G5{)SkC&yC#w&$vqaqR?*1^lLoVkkEN6XU&SA(M zuxY3{>m+%LZz*i`6u$9KnTV&qzHUA5-^G-u+%n=(`fCCBFO?sw7v~!__mcH0ZhzUS zXp*8lviVr`_t%T_OjUhi+NWP~N6XHTqcNUcALO>4%1+S}6|95-Cju~SzKZ*q?5xVR z*%M}^wF(XBVp6voY4y&xBLLGr{gT^Tb}~EHJaN8jp5xLJ*I|jZR6k1FMOq;Lb_LZF`YC9*? zE|V0W{%Sivsm&47CjFA@>U=}-DSslyS5SJw6rbhCD>%fo`6})}*?HeiYqiO-*>_ud zO6A{Sz1MD}Lrk0WOKyzp)bL*Or1W0%x$U-_+D@4cOB`a_d==O2cN21K_GqTuPQ~Z8+D?N3Cjv0-zl!U|?Wy|vTU!b{&!ne8{W#B% zxt9Vk?b9#0!(^w#nt~Cv&%N$cke)ti>O_=Ge=Pvh{;Rld|2>tEHKm<1xPMiccQdnW?tp#)p{pU&ZYvJMlR;`=Z}U>tvRlOlmt@^}dK{ zlYYr{pSOqans2s#nPexO+D-=jh-vdxTsQtL)pk0nJ-hvSptPirCSuy8Uvk}k*Fv!= zrv8;%c4{d$zbZz=wD~Ho+s+?tF6>k{NnZE;j#k_GQ16VGHtCmKH*QhCzV6g2J#J%m z=~oQ&j)Fo~xLii%9}xCjFAzOLqQN-l(N^m_>HJRXePxc1TQ{uj0DT`>1nn zC(}udJ+d=M{o+H-?TBfUe#!k%cEYz7b{_0ViqgBbH79jiY3w1U%~x@|%g#sVUw2Nv z*Eml3!A?@%`0D2+0hl)Fmt3_&Tk~k=h}w|rw}bS&r#3`P`>*1D`+B4{L`<8n;;R4J57mBZ>!)$beya9!R6k6cuM*Y-cY zB=1hm6O@PT?Rr;kekZ2QS870GDr@G#ko3EOx zufLIhM*ybHS8-jPX_R|LtNm!6Y@bl>xv2I-O#AdpuG_9UY94+e`(|GT+4({1rgUmU z#I*S;u3Mf*>w>|W+da{9?bo`%owpFvCjFA@;<6em-qpOtjl(6ao4!yRBBsq(aW$^l zBhSBXeID^)xaRG4dW|jfn=c8#v`N3@y7{ES*22~oJCmZW%Z^WD*J`yPV%mQd*X=L6 zJLk5F9FOt1`6^cNc~|+Fm^SH`T&-K}Od7kMXsx38q`g}2tDM>pF>StztND!mp4!iO z{dP&uX04kZ=|@bP^h>VR<8~_T1H7w!fE?2EnzXExCSuxr6?cs6e0(Ivb5Q#d*<@#& z`qu!(h?q9%mt6Nf-ti?xHB%eXde-i*Ic9ymGh*6&6_@i6&QFMGlYUEgs%*ZSaV%`d zx1sju!s)wYaCTHIZ*%TM%zYbj8#JwKT78ni$^LeEyJM5e=2q6h4D=lb`T$fbr5X$$`(gVj*l z{*>SDl~;PQtUYcKQyaPSq-XJ#@z#fFi`%qMzr@@}B9|KODL!xR8gDfWDQ+*8p0}xs4+N>WjwUJv>@wquR zr(IAnqJ8=$=KdJD)KFaQ=hF0?c9ltctkKf*ZNoTg{=-iKFtw5UNb$*_wliF9i1z81 z*o~Ec?~Yt*SgiO=QrlUjHZ)dxR;%q4d0IRGQzyB*q-Ui1R+g?AEZV1EV$C;__XEkL zhNaT8T74^jzYNwK=^3)_xV5s%N)Iu0l6z5lGA;_WpBHNvLHqPe%zZy{slm0sLAhtj zwNeqEOV5C_r>)7w=Yl@V)fRQhdJbo55KvJrRn} z&B`l%#MDOa9oa0T_EU4qc!&1smzevIj>6xMS^U1F9&X>|NQ|-q|EFOTVjoeMr zGf=r_?vOnW?b9zY_cO_*h7;0LR=H=;q&?0|>G?$cE5pN20x)%w>$VxA-1F-<&mG#Q zUt%{``}bYRrG{tH(^$EuV%&3Qob+r{?pe@sP5`D(a*gziR_^IPE~lY=`X%Q6D!J5f zM0%zx_mrBE)6ABh^2$BU8pb)q)Jg7K={cp`(=KgsL;Lhg%zavNsiD90tWoZ9LW&!A zT-d7dE2`CAhnU*PO|AT#R=FoCw7j8x`X$!PpY& z>yJCc)JEU7r6=s&+YyV_hnj8Dlcmg85#OFU?GRHN zxuc|~d)ExkPQ{1z>6e)M&*W0WV(F=(+_PQriItwkRaW}mT6f$brZ#eyO3yUqo{nli zv`@dp+{Y%D8iq>G5ak}D_T#pbWy(E0)P9Jmja+w*kyp8=p!yf>(=Rdi!^x$FgVHlY zxu?AP*AnU3{ooVFqy9xqZRGA%e2yyjY}b$W>6e)M>f}hJFjofR}^FOtn z0cu0EPrt<6=O>pMR!YwlwH>z&xf+_Q?Tk_z`Y-nDBzK?m^jF`Sr9MXc^h@maegAm` zxzw;rdgiKcrBNSqHFQwlny9tSf3aUDxmTnot#Z%BF74xJpMHsX?m#XzY?hvHlzZ}D z{ArUrPDPzP?WCMACXATc$o*S--d22SDM!;j{Sv!#Gyjm3vxh4m3l0hAa0>(;SGHI>{|6J$;mWo@)(8`}9l9^Br=jp_TO1 zRPGtAIiiuC0m?l;Hi)x`sg2x~dSBy}do=&CX`g6e&$FXU1K_fNR5LQHMsPV7|K?x3~KR_*y{{Ibh^IxOO#_JX)~ zM9gz5a@7Xxr`c!5pU}FiXVc1dtoDNLy;a_BbgjF+U%7C-_IZdSRo*zZW}KsaA##s& ztZc{YeU;GrqJ8=$o}&Fg|M?oZ)Q}`?RrJ0h^}fE6-{1AVy6SxqQyaNu6_dBrp8rvM zrhWP)<~bU<)G$SQo@u_(M(z2S^z>AF?x^-mOl{;YmY&V(@9oszX`gcj$n;K7F*LX_%^h?ZhMslga#Zxt&X4818eHHshji=`|o)S|Vx!I)W?6;xj%J@Gv z(mwqXYwnSJ9!f4X?2(>{ns3}Xur_>x^z_zzR(|RQ#VS_74@$l zl!J(=joi!9L_eu*`gPCf@Gml}3TPd@dn1?pp(m)cvk zpYW0T7%{bxdq{ek_w5`}SZf~Ir{Di#|9LvO)Zpfm@8;!=_*^+CPI|5e*N%wSehV?R zk^8yytWj>>s`${ptHJM=nCIr?Qo{u4(O$3hv*P2Eo@3ez|84DYhnU*Pb);vA#;&?* zKeSK3#5{i|mm1bfPd$xYU#k6Vm7Yu*yZ(A_uR~02}9x zo~)WXw^9zGeflNl{RDEUVW0Gj(%dK(0)iVmm1bd&r+SITv87DSsK38S?gV>O`N}`v=toR#6;`HB=6weflNl zy%ch(VU*sNqu2~p4$?WhT}Sr;GBBLt(|| z&iCW35^6&mr03d`;#MKGA!6zzcZ~FO*7&|deT??$mzeit$fX9Iui2&4x7w?ZWx3wn zPN%*#dd+c*nA*tY9t-W$FERIC$fXAEpKxD=nA*raHEXzu8PX%X;%lco`-RKwkM*AZ z{ivs%_O<-?bBHaK`|tCRTdGgAY2Ck-r%0;t&c@!+rq-9!;^%Le;Dk?aWEM9sP-*mu zT!wg?%6pu>;o0^eyCL_0H0(JL8?{*)XrF$Gc~6F1YWPihiVtYz%avxl6C}Tf&))ED zf0*46QyaO5rDwp@VxA|<_IPNYeu>?4M*n>ta;f3I^en4;+}EPWNT;OqG-}(`+0#3{ zA*MER-I#2?*2i<^hm9WEr(a_Ai{$$}0=_#8ppR;yRHz&9BOdY!1`Kt8O08DM< z9+aM_46{8Z{p=U-%dd@oiFr?kTx!@UJ-@$R!?~?r1?lxbKgc! zwLkiJXrF$GM=L)5`#j`Q!(Hi_@NGAzqhj=~^!)n9Q^!$^h^dWSSHqjJdpsXbFXo|r z`X%N)8FH!NsPvR7I?~x$@3^n1^z2pJ`C4s=nA*twNqQQqZ#7pRqkZ}%<~kM`-8*geBaOm;?Ol{=4eQL1sPmT<; zU+D2`qhDg)lOdNHevuxhXbmUV>ou$r(&JO^xqjtX0H#iI-FFmntB>c+y&HYBPrt<4 zCrQ4~LoPM^EG@mZ*V<)!UbG*-Hu@!Y#}5B} z9&)MSf%NRw_~j`w(kdrCm6dyZz0=#o)Jd+JbKX(zx&Hf6AMMjGaVzQZ-{&Eh8r=N< zx^hown(&AT6^z;$AQ=jtDKK&B&o(#Fv;KqMxc$@HH>nB)A z(;AucomYn*Jdw*LrZ#e24GS~}yQ%olKK&Bw93=TZ54qHEPI~$%_f%GVUQ>L!EBEYF ze2A%yT({2#DfdiUzUM`J{MzW3*lkPx`#j`Q!(r+9zW#Af;i4n0UlgB*ZM#|}`=qyt zsV#sjJs&9d%>QxYi~jD{M!&>bHznWaar3#KOAT&*tD)R8PW{XEdqcTrap|W4nA*s7 z-%;E2vwa)&qkZ}%o+>^5`#j`QgPZ^F6|G@y($8%t<*y#IPAUHoQzyAcr6-?a<57%g zpMHt8ua$hChg@p7B|VAXcC#`oMzy6UlVbCcVnj@B>8zh?v^QJtjS^e>>{yzc=>9`0m%{YViC0FZSQ(A(t9X zNl$zAt)}W@<)vr1`c_q~ZHTFjT=yC4q&nsMv*ENb+IKbh{Sv!lng2cyxzuo0dPXbv zoLWCIG_CY}uiVr8!k9Q>Y9rUx&`$9wv^O@2_UV^c`!>n)deu+0pkN-Xoxzymc&-?0MY5rYb6jJ}{^zZt@kExAZw~v=p?(zP+ z{_<<1Ut*o>CEw>Eml~c(&%+`$tb`&poIe$xPn3UBTs;Yr_!}Pz9_9v zX`gw`U`bm2}7loTB7Z%r==lQfoc8*_ec#PIO z#091|veWlIU1^EdX5=a+_J--je1r79XrF$Gc~6F1YPc#rr|TT|YhHwVM(#Q3N!qp1 zw?+Ao_UV_H_hiVW2F+(|ujXR6^X7A+6o*R6haW2+5>p$w?mOD5@#3Fp#XPi6zr@N# z$@h84rG_igvr^;5eXV&OD?WuZUTkU8)gh)fay3TSD=r=NHQN^(Mf>zi%zHBAQo{-9 z8LaX2FO8?w6`%GRPp4?jLriVtDks}@wAP8ZmSYp`(=V~R&+os_LoPMAc#Y;8bt~oH zqpoTL0Qx)qXB(%xED!^EF@XtQYVeI>nTOh^dWSH|Aac=;IrtH4p96FEQ`QkV_4xr6;HI zbEm~G)`Rvk#pbYLq%~JErZ#e2n*-H$ny3xYKK&AFt(ttFhg@pdB|S-6>rB>q`GoRM zN3C_omCg0~Fmm1vmFi3qXtNNHbF3i(@!Z!6W zVrnDTeMh@b&W$*%97Ox{OB^RX{`)-SQo}*%*;2D~rQel)i7qr#M4P5%NnCE-7 zAKIs1;;qu-zt2N1HE8~6H?M!(_qlSA_PuSd);jx?gNUh(T-WC7H~M(q(0(TE(=W06 z?)>+8$fbs3(sNpCokHqgI_I(8czQ zrudZ8+;Ek05HYopt20WwuFji6wP#2Bt_Htf;vOpZ-{&Eh8ni!Y@6p_Oi*nF)#iv}K z^yW3?AYy7G*Bv7!Up(q*urJn2`}9lvv-J4y^N>poN2F(>))t>A2f6e1{aRaeQw}1g zHgerQ6{hp1>V6A(tBb_BUyMn8DSf_>9wj3o&()>-O0pT6FR^^ye4nlylumkY-iOtO9iq9i9PskF0S3YTGzDax0^Veu%r{5K||)gVcW3tjT4JezZ@&#Jnd%E;W?U`${=ImpMNz zm#HZ|3xf_gh4dq)HgdB{PYT6mv0_B~^h?ZpGUQT29qD;Zv014Y^^u;No9;L{6eD74 zBe#b1%vIaTtTsgZ^h;b+@5_Imhg@oSp!d~LZD-x(MNWI^*}ou_`FMNV08DM<-ckFR zq`tMGd~t{N>6cjZ@Z|eELmA9y|3rWJ!#hFvT2`wiAzY2|2_}7)Nn=dDXjdHG%c6CL3*|%?RRP= z?YD@jliaq7&s)kpmxC(Uv`@dp1Et4*pNCv(m?J%7lzSFmEN@qko(#%8hvV*8#MDNv zJ7#&5doE9{Zqq*f67!x6xzvzZ?<+~UC$d*{yRr0K+}754xFA&krZ#fjF(O>!`?vEO z*|bl;#O}QU|9u{EsUci?hAQ{W9@xl^lb$wdFZ%lJ%@}~GliXF(v#(eB_@`@{*|bl; z#Jnd%E;Uq<9y6p-eExCG>}Aq3r`D42B@?m)VCp1yoAeA&?ul1?XrF$GweOdFpNCv( zs4P9RlzSE{K92NUPIJ-INAV%1PI7lk&+91{TMyNKXrF$Gc~6F1YDg_T$CP{OtNl!t zo)O#HT65KYh^dX-?b7p|a?iUdD%iA7zr?OK|9u{EsUg4gj8yKatp4TB1AkTSiP?0= zBBnNSFGx>G<(@NZa@n*`zr=1^^55qnml|ALaC$ELkn)e~_pEZy4*iI!jocKsc#ijAESNxCFVUDatlF2Ug1q{ z-%=lQ$A#1CTRYXqhy%2N>*l}<$~`@QFAz`r^h>OLiRAk{C#0^c+=uV$xjn5mOtv z(-fckYCmT+hS5I#67!x6xzun#?YWQI&m)at^`z&T+RqftpNXlB+~?90uKs0djHiA2 zC3ffb{(CayQp0fRS*ZSXKx2Gf>G?|i>%7KzVrnC|v-G^H{8MplE<^kDOU!#RpD!{r}TOzr>aGzWn!j$fbssdS5Fvex1}D`jXb~ zPc(NPt@S%GwUNs`7TTv@V(z_=OAXvV;l2tnwUH~E_A>4HXg+49Kh0uSOtY<0Tdl{q zcSOv4GUPT2%WCJke7;gft-ERnKT|H8p*4@z#ddYAb@J}Z7=U-HeE*h}l?G^SM($O=Hgcy(kFEZmN&TJn>6e)IWXPok z?GM-~)ZdNzdtb#TyZZZct$B#4jodfXX3{DjHc>vLeflMiQhfaPdB~-PwR&F*ln>h} zAHF9&)szqODjyP48@Z7wzXg~p4r(o^J{RCX?n z7sS*?Zf(VxX9gwsC#5^L`+`92T1)KF7;vT44tExt;a_MPlUns1aH5E(~IZRFOMo)(JFrEf+nA*sFU3xBQt#e*K+NWP)tu>PG^N>poZhQD!YaK_wDbjODYn`3?5mOtv z*VW%UXueTZF`|9?CDvLj`3?`c)DR&(y%d|$iqR42X{Gr_u-1db)JEjTYMiK&fToe|jGwAR_EK1TcWOYDvv{`)-S zQbT>|S+2e{U46_*&u#UskJQJAsg2yj(lenzo=WbThxX~0nD=DJr3N?t)!w}yp}B|s zv-HgVpjoAE%0a}`My~eg>|EN9nyL8EKK&B&o(#Fv&{BFDC^wH*d=^QMyB{@8@gb%* za6ci0 zsDIHu{SxaeEcreUxzwQfxgD;t{T=nMz0%WU_(G?&`WG>^k$X{kGHCAeQ2B@U>6e)I zWXPokt?%rN+V8!r{4-v9QfaNTLivZ7+Q`kJe3)5t!%vliXrF$Gc~6F1YG^J!Sv5E8 zsT}mJ^wiUN({tq@VrnBdPVq_9-1%+ox6nTQ67!x6xzuo8qA(t9-9$}x++TvoC;#P$8glcWkP-_fg>Ll0Afj?<| zle0y$INGOQV&0P>mm0JeWS7;tXaDGW5xu47iPkii3KkA0rZ#fjIpKW8XPM@Qv`@dp zyeC60HE93MUZ?nER1VTUhJ8TiP5m@KB&IfUJ!;Rh)qW}{2hl$L61%zDf1ih3YWPL( z>piufQ01UV>2c4S2I$P2nA*rKDm{M(RWP3^2hl$L5=Tgn|2_}7)G$wa`l^3rO?S(w zEDrekDD7bl&uZezZ@&#D%5Df1ih3YH-&tceVC9s$U!FNz&S@yK)dQ zwUO(t0gEa&)s=&2pMHsXPljA-ST8+qC_kUoeoIZQPxC52&)IOtA*MERwdZV?RogkQ zHbndMOYH6~`0w+OOAW*HzW&kLD^_i2gyIvT@oTZ#5HYop>-MRq>RS`l$7r8^iFr?k zTxxLV4~^BgCa8~1m!6^OTdUN^h^dWS?y=B5{Sv#{{P%gtr3UVwa9@R(+Q=eb~Jr5j{Qv>IoXns+R+VVXgvYuX6=_x{@=QwK!^;IR+G?Vsl*ZtR#V!jRiMp^h~q z(~-y~f5n&&ch#|ihgk77pT(Hf9fR$9wbR9|eYbT0&e18@o_9Yk(yrOskejXUIH#XE z6j?v*AX8cRu&+q@1=2R+VYoRsU|HCQ@=Ltn?{E{kVo_wN3=xLhGP~+H%OlH0)RKmU z33Z&#K}RC%OIzAb!RE#vagnv;mw0@~U{iPQoUk9HlU&AR)$xhe##+sz&RF{X!GkEf zWB;^KU&WURz>FKYQ}-)A=UPW4J&Xx>UdDmAN|#`}(^pYZ?d;Zu+(w5cI!%9R6}8lk z4tQS1fjH~aD6_9~k*I!a%NTMQlePQnIL&@*9rd@gwd)dWTFi}#sv*C`j1{>Vn+>;a z-W+6Y&;N<}DzSsrxz|9eQi*=%hq+y?hfziB5gn}nJSA62tL%m{cI}2$47rRg%fsrH zwf8*!)LOE;q9JDd$)yIyjqxNd^mYz=>xAZ3)Rejb`XjmxcjAu?vL5NV7&pd~c)&+x zO^NVNEo)0fL+&4m9h^yuNqNPD<(G4nbSf$imf}FXVy^zK?BBSN%Xh@`GH>TFWhXYb zN=rX6-yONL5-MBm+J)N}e<*K4uC}%cY$<==p;w~Rh-`U^3 zqJ5)dMRQ?uTC+8MUOP?3yaCwvN08}ywU9mgK%M}| zo#IKD9X8^gLoPL(i>~inl+CrWnJ+%AaqHJsePZe)cl@XItrR=D+ee?90Q>Yy9HBVJ zJ+5W%j$P)EOAUiQt?#6g&4aR8PVw=o{ub3IrZ#d{Nl*1O(e?;aJ-|Nw691w2T(8yK zZgH)YLoPLpm7bci87-Sv6rbCw-$C_>sg2yTgX&w6r(^7M3$|^deflN-ReF|u(#k$E z)7nHXHB=c~->EE{^~?5-OO&2zs$X{C!A-=}M(*ap^{obamhVkVEAzUu#|`oz>m?o_?6B-7nK``iTBr(fcW(sNPmAI+lbWw2?Veu>{ud+zr*%$_j(o<%M-jFX=I zviYTK7FBy5r211-pP1Un{Z@HwafgcbH2r9weu?u)&x#Cr?S1-@OAX_O)OQxi-c0>+ zNzW?P{ZT(+Y9sfF+RqF<#}Pdb?b9#uNxd(xo^`RFnOthPr1mpMHh+@M6MA0OH&foA&9KxTWH=H+GpdUu}Y1YRI7Xbze5!yw+6l@u~hI)hDJla_1^O z`_vEIK1TcWOI%y=Ijg?%UhU>Kxzx}~@i`%zZXau^_+-9T%4(?k0T?>TZQ%Cz$BpAF zDPPb&{SvF6+TXsJIo{1F4{t&7VqYuXVNpf!Lhh0s!vR93K~yQ>*>h(sM}lSE)WRwUIkf?OD0U>{VZ&eflN7ruTJZ_&sNe`U|<# zut@EBrfj--O=FGO^>2M*Y9qIl;^Xa5(QHw!pndu!ekwhOGvqbfl~2f}hET=FwYgO` zQz$+MRey`>6H^KrjOJAKe8p#< z>hDv1VrnCIrpEW&JM;}x~ko zkvmiGOL@XfSH7Tq`X$ck_ODva&6mnS%y{|^HIaxOI>3tnn{h_K)Ol{;wNssb` ziTJBuJnhpjvHR|nd(6^KE#k?ghR)IxE}P90y2Vdde2%GpwvVkRIV_}J!Yip6H_O-snnil8GQpT$pqM^U*hww zo=3Gz#_yInI8sAH+{fv2LoQu-a;YlsiV)3#7Ol{dkSZcG1>Rjc3#D$PU|bI;Ru$O|fmeoNYPkI@vs3O!(Hr&dtf2d_O(@)Qn526M!Fok;!>~>R^*Ssg^@7 zW5V)HH&U2}59*nlIafHuj2pS%Kkse5TXLpTbxUt!t}d`jHG9{$J-olUGN-wHen+ft zdge?4c*>08_M?ZRoX!QS7;-Z`=wfyK-z;bR|M~=!j~`OTD*64}rs~QfhImR`Pb+>v zq&c3em?8J~V|A=&LsR*pPsIe3584%CPwqL=d2ekEL!6;Uusx!~74MftTN`qVZR_Rq zdOp)B_+4*v=YAKbp|nkrwgYiJolWxlv-}bd8d}E5FP)X8lU$Fpz={9-ZQmPq|A6v_ zTZ@^IJH|Ts!>btL136lln%idh@~qEj$fbtG$LcuW4ol@5tY^&FBiK~zc*Q$K`iaNw z3NhLBydCwtTaUgD`_}rKi<*lWCJaUKC80TD;h8fbp=Vcs- zhu#Y}`@;%)i%BQBjLBr}A2vAC+MD80jA^9(!!t9Yy!GUln6V<4F?m{NoYii}p@fFo z`>mmU=D&}8m9Q*lL;z;2$nB{8=Nmys5*lldm(R;M5a-nXbBeoh3GV(gxv911{BZkA z4SZh4fjCn8(g*f_m9R!S$z@DtY5(~~#v=*-{pUu1#wGaopZ%DzB9}4YemnQ!i5WL? zxhK!(WgLjPZ%;1w#1j{>w0jc<&eK?OSb|+nqd_ z9CGtK>R_!jUF^4Z>C^5QjKS^R&9N+L?YEodj~X$J$neo@>^I*PP=|x>%*9 zZP1iA9L|@BIj15wZg*yD*nnZ?O!?VfmVewbgFXApmS%To4j=KtLXWKFPDhh+U>YyE zL8q!%T@DN}HKzPhjpdvt6LVfoE}wAtX_6u>v`@dpoKulY4No4{wNC}N^|t?8HfsmlwP{rQYj*~(#URJ)K)8TpwL;Lhg%(V}>RqD5}e~(Y?)cP`=VR?mV?d+|ScR8`;RyoAsEj!v7 z=WcU0^j++b%V%MEn=cF5(S5o&pI@*IF`t)Q@5eRl-M0&yuVPa;L3+j}iK)%rylZ{z z*Tn4mPVO$)qUQ)1gkT_ldbDKrWx9{mwde=b72eB~M>x-A8Hc zTy^T0pgqe2@WTGirK4W1YAd_lDwA z!E%6CFb58xzsR5dO9gSxo$u5yemCz6rb?ar7dD= zBiGdsqV_YhKu?SI>6e&$o8(f1M|vu&{X7WkYvq=nQFZH>bUT*^U}_`xjPw-lndDUa z?mLV2>6e&$zvNOwF6mjFDy69xvd+4p_S3RdgejK$egLLUa$OC1DxYz3Rz73VKK&BA z@6NwJPcAhKm!8_E&O70!&RcIPK5Mh&Gpn=Yvx%vb+yvmCY$!@m)OGj4!P9u zjpEZbtgmBcWV6R8KG}CJcdFE_6M(6c+y{!!b>*HfmWJ50Prt<4r%gWpB9|H_Nl%P& zPt%F{?B>!lBXwz~!TJ^fm^#UIb6}HR%i~_3o!6#)`X%Ps9J$mmLV5;QS`{~RdO^FQ z^pr1GI6nWy)&ZD0$^Arnrf$9KiC7k5(?0zY^X!sbYWP}uynj6M)KYw!NKXspo+gS9 zF?EvbzN6mCJ#PDOBndI|#a;c%O^z6#D&Z@8eRaANkEBBOD|01R~a>q!|&&oY}^`m|ICFb1#a;d@1 zw^7PH74!>}o>=9cb@~xg8@aorr;cLtkzz#q^h?aU69HUkXe<1oVsln8>MT7O6q`pO z_X9AsQU5CGX?rb`owZ<3i}vZ4n0HIar3PDi%FfJYmkaM}6_%dCYCA>MhKQ+?+}+Z1 zK)L68jqkKizr@$oe*E`;$fX8%yzZ{P^?}CsveMICeQSvN7%{bx`uXh75wUN6Ym3D}!lic&tlSl36vc@plr(a^;Z6lW&21?HZckI#_)>nGoQTxfQ zF^rhn$Q>#@Pt?B>G{)0D{Sx!;AGy?!QF`Lkzuwmv?~YSh)W4R7+z-IiM(z&>>)U_p z#&eg5GY;+3FY#%Or~Z4M2Xe;w=$kS@BAS>g|p_fr)SP*h^dp@`Q>ZaUoXyN zAAK{{p?&%#<{eaWsp0pvE$wrm_pE$7COf4Y=Ccd6%VB>%Fq0vsHge0n-O`>nEXY1S zsDnfM+>a&Zo-MiGgfz9^Dw)U70?D+-PTlw$)>=0LqZ*9L5ver5~>5xM% zpM~WgHqULJ>h7_B?zhw-uG=J^y)3i7uM*SGA@{KMZG!3sM@`Va&BuDij7Nj5m3M*- z?@JR`!F_ddBl0x0qc7k0>R+8 z-MY3Rml{~kI1n>d{kjL)>zS-! zZR780FOg>-#Jq=3?!>2cP2)uy;!>q3U|tvg;^xb}#GVa;O{ynxkt4KUN8DZIHHR$R zv{w6y%K8Pq7B`7LX8d&?*N0`Q;G`9(L6eKdNhLoPM2 zoN*v#tjIlhsJ>aJx$4PEXB_I}eS2cwdncFA(s*YbGv@et%X9v`bLyisCM;tA9-; z*c#2pXrF$GdGDQEYUn0C!!#eOqxo2b^n9fG>YtjA5mOtvze`U^%~wsY(c!dDzr`X%PQcXFwrhxD{k|JtqfU_0r_s{Zv<>p@~_BX^|q zTvYz~Q9s(JUt->SCzl#VNzYqaD~IY=MtZ*ccfCwZZRBdrW!(LQcN8Pqr(a^;dncC~ z-jkjn?PY$T7-g28YT8c-Q;dkIja=<%n5JqwkF?)H`}9l9JNe{N!&2!ft+wM+4s!EM z(vIbptu{nVZR8G8e9~>Z>nW@KDB7pr0IdG*zn@PoHB6SC%<5as)yJAiPiOV5#_D6l z)JE=E={Z|?Xk4gr5bg86Ju&aSlS>U+PnqrYAB2uq4k|A_CpI^W`=4?UF}0DKC_S;t z&7+lrXrF$GdGDQEYS8|PX`}tj4vJ4p=^6L$ekL)sk^4}3CTi?TQv0EO`X%PQcXFv= ziS)G8*tN}FGfU5#8oR>Peu$}!+>O%HPhSCzl!=%{SI*Y|oxLrQJ^B z#b)h?Pf`COrZ#eak)E7b(|%n+#b?;R=S{@aMy~e2%_5!0Rnz!R`}9l9d++2@gZ8&g zH=W0&Qx0k%J@4r}u8eXJF}0B!D?I~sUOE4lu5q+azr?)vPA)Z6mY&l(uWUT!{kVgA zUu|_>Szu@Gcw%ZJ_mK3Mf6sGipMHsTmXUlvpImBaDn0WRAI*P!ze>+!#b=PtbBU>q z+-%ab`+6pGGIvjh_UV_H_sq$qhO*MrSnbCs2kp`O`cCa9qq95!QyaP8d|bnf*S&&N z>ryzhPrt;x15YkBEU4Gq^wPb8Yw0feB8KHQ=WbeNu!USYpsv= zdB2O8cfiO!U$=#6pl@0<@%HhtJnyu2Ci|3K&PLteAhud|G&kpLa~A9V2Dy9|mamyw z$c)mxh(}AF`iMJ^$ZbB*J&MVb&LoiAp>RDjd-ziCHrY3nuZM@lZABj4tpP2Wk$>p=?K931W-PYSq_mO_79c=1Nn(Zy3`$)um zMskm8|K~yNVDEVC|Ij}D67$|Nxztcr`#NkvnWbe>4AVw5M;4xlTe`Y;nT`G&WDm+S$U_UV`0yqEf!aR(mz zdVM*|DfG@Tvv6w{-@rWS12FBsiaW1Ne{;QCsI&UqXU@$Q!%T@KOMQd-JoFLMKK+v0 zCaAC3S$c@mJ8f@g&PY%02KpArp>EbG>8Y`Fp7YDypa2}86Z$VmPu5wX zro^8!0_@W-@oDL~;k;vVwOC}4OAQIK|E2dYr_~p+);{S8$uY^9RUt9}QzyAT>1n;S zu$lPd$pHKGOPodRr$mkNW<}+j7P-{$gY+DVJmGAOJYgM>p89qlr-|Js08=Nq_oe6E zwQ0>;Yt!1aPrt-vr00!HxlBl=TsFDXV5H}RFJhg6-oIYNWLSkrr)Z8z0hl_;Z6!Tt ze>~}|*jhNiKK&AZtoPNh%1viLjq*0R)Nnw0Y9H$6lxUE_KBxGcyBp*bSUS%lcH`sM zN$wQs>H6mkr@^ey0Q>YyTtV^4-9q19bKbGZr3M#2ZhFi2-ETSUGxED3dW^4QwPhAD zwUN7Ddfq=3;-sGC39wJU#D%1%&hTQ+P+vov+yD*I6W!_k@ESjc*cYYe;EA%~7ot~K z#MDOaW$77kWLn(LdT$5Vr(fa&dSCG~&c!JQ+2p!?#INC;@M`6r*^18|=_&jFG540y zRb5}-HZH;4A-G!vLXxuhqyLI}kv)}lp2v2D&pqBR?+3=XnB(`GYwmT{o_p_gBqPQxazR==GDHpGtbq!MR>;`8h5* zh18Q#de3oLKlHMOgRXj{_w!8$gPI^x@IlsuPjovphKS9!aD#`i9{2Z5jUtX{0 z(t9e)`9&{lI4kw+lHRjf{#}xK?x_Llt^6aiHhPoG{CG?636y`#&vD6Xq@J$QdxGU3 zy{zHB)KggIri9GVHL2%v*6AvX%n_Nj(Hkf8BmG%Evwlf2Kgazyx0AWa=J#09%Nks3 zJG-nMA6Y{eq@HH7c3#W%i_F^Sy(snMklv$Y4Kcr~hJ%3jxj&SB|ngQR>`^LE9V%!tijb!+DY%J z*R5K#tA;Wo)~icf3q}2#6Y8Ybb&nAvy{Gtqw^7W`amlW=Jy3ej(Vz<6^s)xm^(aQ> zXS?+1Q&P`-nV+B$17SB`OhlrN69tJ zHEt7GKQHAPMrNJ#-jaIK%lfG%*D&VixMWvvbgiFqat))GHFUq-*oJNSpt@{dXAa8! z^Xe?qRpt5tZp_-~t#!MkoxIgkk2!nEEkDO4yVmwCIlrb>d2Hxq4P`Snw(E~yQu^0R zrsBInc6#VgwPNB>H)fsmE^kuSR+y1W4BO4$|Sj4^_Xs9OA~z&vEJ9`Jl0Wv+RSK zw|Jd-8#h>|Nj+VKjtX#N=BGE))si|`t~&#cTr%YX%jz>Rsr1Y~@?LkUEV_`aH$Pc# zcjwXuHPFr6+aedCrHtn*3Vcqn~?%sT0ndwcz-+_U&d-(Y@@ zOMWHwoR_{)O!@}Btl_5AGf(>JTS1gM8IWDds#o;a^J%I9GCp^pY>Bj?px?( z4ew-rp2vPrx#Yg?H>qcX+}Ay?7~saNjowpIPi;BBT+iLi&vD6eP1JSd{K_Erb@Z}^ zU!|Uza?d+K{@s>(evo_K9rBONI_b?N>!+;T^Hz|5%+GPjaZ*o^-1D}PfAq43>rziu znVSH)_m%w+-BRv(lge`enYGcIQtHt%Hzj0_n4ja4)5-ezS)L2>${f+l8eHegUnhI0 zY;x}+&ucnP)=oNELuA%QZ$qi)@$)$69CAbMHDbE#*VoLi&h z96KrX?2>b9y_{oY)<&<~%jvXoZatK9jQKe(xr)^DF`}3nDCZcxtiiQDYY#~tQ$l*s zL#b!t92LDsdJvhl(fd*A88f(D%qHnU%+GPjzsvfmRQQ{iG17zRWevYbJ+GuUe<$Ohs@gOm3u|qR(kU*nIGooxMXjcpZe09`^o&!%Nkr~8ZJmZ4P{@ex}0BUq#oCP zQ4%@7$gGpzK2py`+1Hvc=NI#HTym(qUcs`j)kn@RdRc>OeJ+=MzZueh&PqL{W#6x? z?E8^f8@(Cj{Hi4Tey(S4=I6NN`Z7P+W#2E8^dEXzgDZb~*%vJ>J;+rn|{m%Ll%r;Y53y7ngIx#qvTtl_EDlSKB7FGvrP=WAV6_Kjnt z2a#DDy+29LqOxyXNUmSZ&vD7}%&XtYzHxfFe$mSsT-WRAvajAndXVft=zg-V-cx!I znYGcIL0+%3vafze_SKo6orgI)n7;tqL($e=3mSE4!?CS7vmZ?xxDX?DaXEO zGHatZiPW<}-glT1)hdShIWD<{)Z;JjJ1qQ|BZgkqQ23X|`jN~}h1*Y@DW#qYjx}b( zvhi-r+UQ+-tE8Se(_!B|&uN&S@Hsso&Fom1z|GhQ_!bj0WoXVd&1Zp@qxnX}Q77KN(^l zdu=hRFU&V3D~8xB=Da!jO$|5B@J9z*W#dIt@WA(m-hdVzZ1T~cOzT^(oTa|Bx52aS zoAsU}4fSN^r#F4{BeV9eW_EPMcJry+3sX3}qYbQD$z+p#u!Q#|$$TF(F>i(PFU;9< zU2UNo`C|B99+^2gF1?YG=lQ6PwvJyV#rNRI%$b;Xh~%lUqN$yDakJukXJqE&xb&v2 z@WMPf7$DyT`k?rp7nwN|^L~+fW^5^BXKg8@`Cb*7IXN!94#uNdpcz1Ow2n~j_apKd1H2;>#F%) z44FAOF1>$Ap2o6vPDwp{4~5K}iFvi;*(z(N-ioH$wKtpa{tKBoIWE1OB+n69JLwMv zXufAbX3oUCx8*$jN!E^2{<-!Z6W;G2GbhKTx3|=jMQYh9HMzY1)B6R?nV2_J@+g^` z#WF|S+b1(W$E7z$^4yZwYK**Q+><9WXJX!sl4q-|ol;vpqh0fvu%Az6PL4}&JIV7_ z>RBjjntR}6=1j~xU-J0L{7jW|jCCGJ@~1c&O69U9j|lU zj6WHockgJTo?Sg@N}UbX3lA()4LfgiQY}wiHuQE`*TkWHi^+X*!oDS$IXN!9rzOv2 zsb{2|@7(JnGiPGn5t1iB=4XxcAMVkSnUmwvJ5cgume*^W^h55gk(o0w?<0BLkNwl1 zxhFEjC)69 z=1k1{o#ZKBID1UAtRe3CkeQR?(%Y=U3)Mr`a*WjDE$c90zlhA7iFr3jo{`dWh))4nJ$jr%c>Fp?a3LFZs3uFy( zFM`aRiFwCJp0DKoIs8A@_y5|*;C=#ga$I`DB#-NUzKN_MKKqlIGcj*!dA;Vz^M!MB zKuinl8<3fk=>xNy{IvV-pHT3dtC`|eNlKH+`N8394OjG)+dB$^QKRZcBxG{fEm|p&EzRJyC zs#?o@b%QM_ZR;fK)WZ7p_1yC*+?c;>O)vjO9)DN4L6UW5x#XECdB|&)y)l08eRRk4 zDc%0Q9{=_Pe_uD{SMyXUIj+ufT;!zBuBq?abg;pLT^(CrfA{%!L*{SG(97R);cvWr ze=xUB`?Qk2`qNoM=5O85%inO|Z&0KOJ7I48QxBQH?LaSolYzh0u>D|e`}9dA{hQQ7 z=I>X~%kMPtyHsK0&zREkdbN|+i_Gsj(aY}^@jFL(_GPoZ<@HJ>uNRr$y`pzmkB3qF zpAWaIl1x@JH#nn~1dOy3TZ~c{o^Fo%QMli~cxd;5(FaApK=kw$86Fw+WS;J}sEhobrvZ zV|Ugtfs?$PS#pHC@vTN*n-s@8I#SEu$ne`S+$mn=@-h#-)Q}HWujlx^U`FK{YuwHn zN=@=|WRkI%hk9zRH~Lyh4Ng}L)KepKY`fK2?S1ugAuksfZm`_@+j)B{CB#2}`Lg=o z++FmHyS%Rd7m3)u*!4Oku=xI0?DE!X+1%STUfFYt*Cp`QU8@&2d)d_6r`Z@AJ@B!E zocG+j9j^Fki6`h?-h?&dv3^rYiT}Me7R41Ul@Kp`E?>$2iMQ=qoi8Eo^15nz(E8F& zIi_N+<9QCgo(P*#2Y0?n6R?xs#-m2tT%CUO-Y)C#&z<4+;F2^x-m(r|$I3Y;C%i87 z@_0E9iJf0O2kA{XMjkKc#C5JEXk5&5Dk1Ljy5=O|cwL+@Cp_24Jg4YQonoN6`QV-8- zGS6jt)1J<%Gq%3tNGbJXESp&eo;&5-F7@ynC-WSqH}E^F0=8$jr?XYllc!|U0Y5x4 zesjv}RYTXRAT!Y{+T2TX9yr#Q?1l8UfCXl3d^PLFKA%((-%lpZ`zn^+Mnl({V9B{& za*jHa&GsL1$81VoNnftG*PNP@-F`mmuUmbS%+5~}YbJNEV^7siZU4Hyz&u#pz;X`B zd`;eCOlzH!69K zLUv2Q0ySFZDvQibX5UXLwagD+Q!>{Wy?nj+8gXvPoLhPs=WC(A$!)*tP}>%o-A0ik z2jsJbqrbM#f9k$(1BU@u34-sRN}biR*v{X0EyhJ)UMACgANap`}K>u+`)SMSCry`+BaIxcdwPX+JM5_cUJ zy|3k%UdgfjzNlp71iqLeX0^orj<+vf$&36_;%`O2D|aog1ij14b;b3@^-Sim(93np z_3U>3;=JbhPH*pe>9zmB8avk(4bpvtL-W-Bo4F>*>@D>2T;}=CHBaVwK`+-Z*MHY~ z>Fv-4aXy=+PI3>4*UNU+XM@D){c4nt4Um5^K}#J2!YbK9;ePf;)B?vld0qaHe{G9z z_xd;gF7Z9NS zSsVYwFaF_75+_shFYkY?E3UVD2fXcr1M;_9d%SRvQ?&E9FCUiEKSaE6a80rgus?9F z$ea^;dEW7SWc_3w3%#5-&L`I!nLUtR9xvyCJ)F#Qie8>Cy!P?Fg3N0)y}Yh*o%6ne z%zGGmdA{)a!utv`?_ucW^^tvm_Z4K`!_ezl{zgw6??x;eC#@I9^k2`+aUm<$LxY2gb zgi_|t>TD`{-$?6Iw7MIAZE~xXS4Z0l1FJjey*X?0&dM@B{xUyb+D?qxFY_~5=7%+t zIVbc|!#r<`6pRXxxeAuKBJ)`2rDoc}>QO!anIFy-nR)1K`PI^>f-*m8Wqzuj&F7Oa zKb$Kv=Y-zEJsjqndkyW!k6Cof2Ng_2>Xx?LiZpI>#pC6iB<3v;Ucq?&ZLd756bW`2`3!?_|eC%rtz!+Ua@eX=$J=2dsxSf0&nkoD8HWOYO49MW6n zQ*zbhW`qvvYW7|#KhnqbOm%bI?tCRSj_@fxGE&btG2TIL@b01GId9BKK6xaQIXpZ+7U3Q5)LoLt&}(+dUr6tB-5xX)TNB zA<6s2k?rojde4@lYUj$Var8!hGg?nwoK98D>2%)A)I&dic3b^eIkl5H$%%Qlhezmi z7Zy9KbbIa`zjdh2)OoJ*jBMzZlleI=y)~*0(y<4(IIB+EWP)!F)@_o>-*yP^ZJ3js zm^b^S$vgKQD{AUSkG8{;74rTnWifSr$7uU=fi$YahCFKJsZnm6`)NkidVUTwV$Uc` z@6$2YcOH{GbtF&snGd`Y@-QbkF)#B>s+`F*^Uh(m>>Xtfc1dHt)XSriopEQ5MQ^=A zgKW^s_0B*0Z#HdbMA*Vr7C9@Mr_RiWhuRx+=c@Omio0>O>w|6Mwtdy`<^xS)-jZ8K z+mL!`)i1}RonJTYZoB>Ys|u`;#*LYubXR=2v?cQDY zto56kfBdGiR7g*~;{MNW{8#n+>75>2w=&$lr(gZ|~FVyLOI|JclLE&E>Pb6Y?-8 zIWaHu96x!_(QaNNUGaPlJ@eWPNArO_b$I;Gip;U-<^AWU`FmCR&kbzl(eG6DWl<{U zrZP5nyHc7QRPA?1t57d{vyiW*m-mx{`oDIxY|z^_IdEK6%`-`T^G!F~C@9{Io9thq zejHiB_W4-K?f#SZji*;GP_@SlwRydo1tykRb?vl zuoDk#cjH|3ma25$53o7Es^NAY%X_Lu)qZ!nj{TM#d$DCvCWp*VHklvtp8R{wM*oI( zN2Yg*Ufw%7>lsTlA_gBvzM>z)h zjnHK(k5ac^2B|vhhUis=ySwqhOJS;x=SUq~CWV7u-v9jNH(Q+=IYb97ec|*@779 zlA7t|HMDp5Ri|q#r;JrD*;tcY>d7JXkUvhIZMJtGqDu~Z<)oL_$L3#Z>V>mB^`SOz z9Ua5E=#gJPRG*U-RpjTXM(TOrbXQfEUv|*TYwoh&0<{0O@_K%Y|s_NRq z(!25Sw>~;uTG>}=GtBLJ&FkRC#(ngGAFG>J-FKNI{k!T5Z)=<0jc&T})1}?@`6Sn! z4_03{^zs@y;D-Eu`H74wBwrf)?X6}y+uSqiZl*Jad^|}T-Ed4weXC$Hx9cyjkFRzt zR09Uycjk=@mHi;g}iR;c__2ivQW zqm|dj8S4Du{%-7B={t4k^GnCm{X^WY*SvT$-9+@t`b(hHXH>dobTG`MSjsj;*W%4}@~ZPPmXWb8#e}O)|I|Zn6BwaZtqjuPoBvew^4k4Z$suaPq#pYI zd@N(j1((re=H$4%-{AhtvVrTOs-Nj)>pZ`p$h=RWmo+fX`x7#2qnG>xPA5u>~J7=R=lf10;Z(T;y z%X?17sVDQEmR`QrjPu@=%-4%v-n;U3q@K*2^zz=7ao#7Bd2dWF*9_ylPbPCM(aU{B z-VgIWnLOvjc(tZ(uv*heq#?HQ+@%x4FB6ZW`Vdw`7dIf6WA za9^KKH$rv(hb!FnV>!18?Ak}I67bR6HP5+Zp2?i^1ikBZNvOxQUzfnH+BhzGuGI7S zU-h`Wd}iT(qxWy)Ow}TY zGsKcvTVh`BTh3^)}xm-FwW;bGHauk`<#5f z<8vSR?SnBow#0fzbn!1mpm=0h0S1g&&jP$Yw#`*k6<})n4+;?T2 zte?E+e55XTc6!{352+mV@>sa9>${_c&T%i3F1uk|9GS;RFZXYmpW~9tWQx#7duB05 zQnqx^%Nn>p+$w#rzCG-ziuk%j9GSJz%V%fie{nff-<=p~JnPpnWImhI%ja&!`J7JX zvpKyy7RLFUPUbPv%YA7+kMlX5yv!>@)bE>Dm@D@~-S)%z{LX#vJFk~`=XVdV1ABE=H3Op z+*@Fr`xs>IUC_&8VVwIIWF8~E-1FyN2lp|^KVJ;Btx}COm5E*HTJ&u!eTG@HoGU$9Qr^JzYjP&xo4Cd#!;A`vo?CU7sUJ=m(0B;dbtTd57aX*Uh2l2j(%zHC>Sp(zTzan!Fjb6TI#A9Ur18yiRFJp;Y$IqaEfQ-sM zUfwy*jMfwKjE-7gzOW%L_KMJxn@);qmnWB@mvQPBoeS6BW*r{YteKx7Cs{f|dv$6N zmH*W@hF-?0uXiU>hqn58XTaePapVGvBXzTV!8>162zJuTIQ6cYpZk~b+WKtM-^WYN z`SVGy`F}0)rdRZKb*91I<3{w0k~(d#tUq|mu`4-7J0aNsZ~%g=X!sM@)(}ezA4Z|pAT;C zllC9ZHeinFem}i!w5+Zse@xfJv@4j!t{>b`(>vwkP9N8CeQq_lbfoa#b2PeY>2Lmt zFZ;>gjVJ%38M9_+X?j2Z^F1>0|F6C~_HR8u&-4F3i)QXDUYbkx~PbuZ|yo)b6{C9ZUayz_r z@^9ZcdwVd*+s(J{^2#k8-?3TJTa#CpVz|f z3Y?wry4V4QW=FZcGa=t+v1yyk{~x(x=e1N`<2u6U=XLv=>j}5c z_R?#y#L4v~zNO|TuO$+v*R=*^{plROv!h&`RJf1S<6>E7I(gUm{|CGD<)j{ZBksn> z4!#s(+D#0zzsxui>-%$vnIc?aM11VB%OR%0zc}FA!?8JUhnQa`gxL)T<73si5VKx1 z-?x&}IFe>!QKIbgqfx?}InUkED_rkiCI>ibP-L6Lp zb4ED5aA#rWBy(JPvmN%)j|NrJzt$^ZQV72jek9DCN4a$?@jrRo`14HLXOo6N#xg=YveCz<2Y8#(W=$tQDS zKQ%R5gtH4r2{R`-G4JpR8Erm!jqX{0GhR5G@C{++By(JPbJp~=$p*`JzFQVBd4)gA z`Z+7ioaDs3!_v31nPm;%jD6({6LziVQ^L$i=D76UTiwr&lyfT2pjFOC!o7sk3Nt4; zF|T*=aO)-Kc&WX4oE3%p3ilFbPBO=(S9*edaVR)CaQle>D?DuAW1nqXPXsV0IWh00 zq~W&no*E{7zXpyA!pnu52{R{|~l;MUMD<9m^sObc`vPNX_K$; zuq}I}Q0Ij`ggXi|Cz<2Y`{oL6|RFmsYQF1@>JA2Ru;^sxIcwNk5uJ%yzgx#eX3#Juaf)HdF+Lv7W~UDY4L zm4tnTnUlAhSx#$Wo69d$88J!|kE4ijcha$?@&CF`k*Qo~g5&Z?@d4d0g(!J0aO0NxP=Md@5LH61mz!I}2Q;`4 zqDG5`Ecdhla!;$|o>p&}9v?7G^2l?UTOR7EA%B}cJ|L%zRYb<>(>Fd~tc(>VdC1+O z;{yUtgebYk)}!TE?#NiJM8iDPQ$s$I_E^AcXNZcEJYkKF1jL*RQOhI`Icx310n2WL zsFV`FJ0U*cnv4}B%skXn!+NNvhU^h^I3QYH3wdtR!&}A&M9Wxh|HYmk_6J-%6QX{S zc#gU80Y8aG?*H9tqn8@;yCX*fPRr}%l-H|uSbRWQ=|h7h5BcoyBLT(l$oz;VY<7IW zEE%i)zs9AW8XgzNrH0(3Xneqr@|vcT*P`5a@d3|e9;(V%WJko2fEO_#%6D>@4jCUG z5GwV!)++N*PYt=U|Dk|#FGJMH@nL%7qWFLklBcueA>Yb#I3V<9i25MMekUS6;OIZ| z%skXn!+NNvhVw%`HC#W`Q^RwXdTMySQ%_Bm{D%V?U;WRVQ%}wQRL_)m*F$F1nTGae z)JIj}-5fKyL36u(pqGBIc%DhQvZNc^tfjQad9XUWHq^^o^s_=S$dOaYhY$%E@2&c0^Q=&lU3Xdv-EgFo323` zOYeu?v(11WdF_g2$}LVkd0NI(CQXw-d*xO-OK&c-*ZjEE!(Pr;!!1rdd3*h2_PVT} zD@QY1dP}FdX41-fuGF)(Tbz3G{p@*cOIgpmF6XrLhG%?fR&+UJ_O@!^7N?&4GEEs< zU(T;7rwdqmD-KIyedXMou}gkO7&)mYH~z-QwvqF^n8)UA-cMDjQ`6GBCSafW zGmWR3lcTR&oO*J*HOXwoYMYhskM%9RgOklMHQ#npo~H)5#i=Jxy?4qCn{!3|aJz}6 z_s)QZ=GeJOYRb~VZgJ|#Ew{`x6Q{pd)vmO#^zI6|??^WoomX_W*S!bw-hn>{6odezC z)RT9`9#he?uc(wonpt|M^o>@z<+p6sRq5vzr=Gm5a1!06>SmR?YC}u!`+XNw)TgzM zflqq6#i=LPd6rXmZzb!wRBcP|_Nb@opkH`w#FuVvaq7vXZkN=LUfppN_tuu)y$e68 zH$CE=tLArfi&IZ-+{R1SI=D7&=iI86-U7{%=n~R@p1p4E7N?$^^r5`Zl*ZG%U0%`B z%X<~ZsVDP(hTa_OTkG@bnmS6fOlu?GwAZmm9yluu`(o%Nvo?BzCUw-)k34Yf|LeU{ zerr$*hgueeq-TDbq$Xg^-cX`x@6%Jdc)Don#|hht>W`a?Rl0%H!oVsGC#*9^W3MGH5_gERz1Dl zL`Rp|pjKr%rKU9r)CX^-(`430Z?7|JRi{&>^{0{LEc0_*GJ6`mtRd*-29@hTu+BMc zxteTdDF2@tYLB{UG?}&08~(DSI+Ll2u9UQ*WqyuJX0N7~HO#75L6u1&f8)IWVzsAW zRyF=bkiJ?bl_s+`dLtW8i*;1=*UxuWw9L*v&uE7hBJ-@5$+94LfT!u(Ra)^9T=O=fNMZkf>0p84s4vstnahWR-zna@!4 zvW6OO+S>!i9ylHi`=a(d@U-YIEYe7fVDQ%Soq>!dfngrBwJvfEFq4jJa>xMV)d)5{v}&97pAED~ex z-OsBVJj-dfwd!Xoma6T>tdrh|_4)1b0=~9GvKYhs9GA>J3VK;Xu3Y)-fHrSUW8WgW za^WPli{ECGqiRDpW}WmdZ1L7~kZ0D)6*m~>=eT6_>jwR#E5Mx-p<=dk^afZtcdb zlirf8%BZqQ2H71EOAPaKTr&4I>17Qa=T=g|8LQZFqble*xw9+tIF+3r9OTBVlivBS z)~O-~gKe$FD-H8=Tr&4;>17R%vu#puW&OxKl|Hd~rdmJ!y{U7hg&VU@dL#W_tF3Z= zeeJW^Fh9p7b1#}+)-a&`J5}j<4m*2s30?HjDV1*F6{Bx9abwm=@0yAE^a|-eGk)7+ zn4ja4xyMc~Ye<{Dfc`9fq+@+g?IFM0QmyJ{bLz+XZp=FAE%~g9?k@egN2Ozi`8h6` z?;X&~8j?l&Y5$@zCfoAdx>u(>`fX4@bD>sEH)fsm-l^3HY0UYaM!ThM8RIsbPMOOXfZay{zH4 z)@}8jOii8ZSEthbfAGoIu>dD+sp!bSr1GO_}3H?jfK+QPyWbOmddusmAjsdmH>*;g-HRIHi z`TS0A@3wOSR8&QMt%AR1oO&{!yXk$O_kgo)t@3))J%7zO^<+LT(|h3XS0*lN3GEpj zs2Qi8%;#KsCvBf$O7zUDlaJS$aq7u@KBYJ4d9+!x%|ovX{8}?kJ(*7Xb?RrPY1c!l5A6(~MJ3=5qnP^K#EHZ9aA~G1~`f z#;GUsexBYsGn0%@V5nxCdNS|B=`B#lIFI|zGmrKS(Tr11=KV9htHTZi)X%=i zT=X2O8K<7i`(AoWw7=xITYjD?*l&ntoO&|vSLsdHx1qXnZjy;zI#@GKJ(>5J^oAv$ zqmsSpWYV1)pc$v0%=<%ngTCIU(&Y6t&9n8@j8jkMeI31dLa(XmpVvD3&hMcar=HCF zF?vt5f2lnCjtrynb8e{wQ zJ?q#zsZuO8j2{n>{CK2Q({2X-_UunL&3?ppU5>OxL)yi8oJ-+k z9>&W}kF=3f+BuI8yyTXL@p_NP*fNLqIVY^I;ih4H_xlLjs%R4PG=pa#$71}~_|f)A z?*e95@4Rkv$au<*;kIZ7A9HKmcWxTSOPvX`A8UVY%AC69reXZIawBcmZS~FAq1hGd zVZ33{5q3mHA9JUS+!JGMFurPOu$^$&!xTGpTRoNEX`kAEhuYace;n5a*An?@u8y{C zuWPFCq^XH|nKSlms6BA;M>VVaJSUlJjN>v+eV=;6Y)rZFYQ>>shRk(HFXPm=tuex; zd|6u+7+2AdxmM|Aoce<6N7^(ezc_mMHZf$bXL=c@{%yZ7o6Fh6@n&roL*|;NmvQQw zObxTn%4g%ImkBmxo)`2oPJRBrM%sOEPdW3f3o>M$JM=P6y*)9)p8r_U`2P@K$UML3 zWt{q?Nr&5`exW8hbv8rhIY=+#)c4*##EzOX&-C(eI>|gw>1CYyV}A^?Z|ZM0t6C&+ zl6fxE%Q*Eu*ZSMu!Exrrv|J7{&v$wmr#{)tJ~l$do3SBx9Ax$cdKsraxO-1~=U}`! z77(b&>>Kp5hfqT=IYXP4w&ne0W^A5kir(2D+uJ*BlIVVA&p6pP-1-c9PT3{(Y?^I3 zbZo~uDlsqPuRnCQPZs{Bl0?@uWcC)0%Q*E-rUl!-N;=h`Bi|Y_dkejcQ$HZMhy8l+ zEcGtUCPQX#p_g&$b_9)Y{O$omW^bXFaq5eX?`?A*o9E~{^0Xndx6sQt^@TV0 zwq-nXI#1L&Ysl;^^fFHUkY9S)Cz09B@)}1CnZ1Qx#;MO;s;8Y9A7Q@UA7#kwE%Y)@ zeag8Zw(y#*=HS@*hRohVFXPmYb9A+tcU(4E>vc6`_7-{>r+!eaj@D<$pC&}5He~h| zdKstw-1#84ZY+e?*r}I`fp5h=~s&0I+5DGx?4my%k`CE-(a61*NiJ~=l80n7ybI) zk(ifpj}(JK8!~$fy^K@8 zcSeBiugcjuJ@D;%PJNO|zP4^_A3OfgUx8%y7J3<{J|wK7oj=0YdIpzKWcCnx z*-xmUm#j7wutl1C+O%=66}^2A<+F>*XuW6ZRKvc(K0{tG$HOK&6QsxY@8C$x%lOgr zh3(>orFH)Urwy6Ch2t_#eQM8=_F`0e-6k}pC9}8C%Q*EV+n2TB-7l)ug9}(Pdkejc zQ@^=g1>3XIR8>B-f+e%J(91aWNt0Hxi!R=BBtKQvlG$76Wt{pKj!O1Oi_Xq3#j9B| zdkejcQ~xMqMf>Dw2UB2>mnE~e(91aW4IZ9s~)VYV%NjC!3%!g}?~ymNtvS1ejel1)j?CUdFXPm|d6ULIe%{hP9-d2)*+b}MKcR+R z^3yJVnEB1Mt+4BbqSvebT~o4XOC4Nei(%hjpCMn#a>)2>>!)uleHNRTm+=)RUYPlp z1N6ci9}Jnjh2t_#{r;Js%<=sB^$$G@S~7bJy^K@u7na=4KKxY8PhHKD*<0vkocgUN zQ`ziQe^8h1Hn3#&7J3<{Uj7!ZedBoN$WmLrn+IlZp_g&$x86--i^Pv`zCGO9lG$76 zWt{r>xv6cxLc`3)=1nb`y@g)Jsek88VHXWLXD;|vw`BGfdKssF(C8%gc9G0BI7cZ< zW^bXFaq8c_dSm>Pds**GX)Kw&gLob<{>5*5Qet8r~Y#NO6L9gl*;dQm?g8f(91aWQ3EQQ3@;}-eP)MSGJ6ZXj8mWMKv^?p z`~>-}&LNh}-a;?q)aM#i$jlk?tC^g?ndh`jkk=a%nGJ6ZX zj8lJe^WM0YXCmx{<;e}1y@g)Jsn2o5H_#_M(hh1m)dkg6>)zXL zDSk%L%U;1gb9-Gy6)N{Rg*}oOa-Tn+I9{dgs{37jYUm|XlV!+Ghg0r$L?3gU~KSR!RvSjuadKsra?(~bmYI6UR;(Vwj zv$xR8IQ4I~M+Lqvm|QKs5MjyeE%Y)@eZ4~)1HY5|pKX02Et$QAUdE}P(du&GS-Jl? zF=2!yv$xR8IQ8+j@;Sog{%6Uc9+u4BLNDXg-^vx@7$f&T=`S_3WcC(%8K-{#iRF%H zx&L{+y{sj(x6sQt^-F`VI8w>|&w)BAESbH9UdE|k-a4I%mHVH`0ox6ky@g)Jsjso7 zoU(HNb7g)}LuPNGmvQP}hBa2%R*$lISN#@9W)Gp4{e&8N$tQbEP-_;1SiLDu(aT=J zJ`?y?j9M=HJl$8MH{_9DFII(RzbNb7=Z0P~HF>wpP@`r4C;DnZOJ;AOmvQRnKKe%e zCi_42s#LdR_7-{>r~Yob!Rm|b|ENptESbH9UdE|k=nPi*W&h`gsQ#AB-a;?q)IaRg zLDda-=lCW2NK0mKp_g&$Jvy{ky^oA=9-I?q$?PrkGEV*RC0$et+5eeWIMkBaTj*t+ z`ls*usuqLKnc1nkSu%SIy^K>|@XKhmP4<5V+^uKH>@D;%PW|KwQ&m;j|0%Ynj3u+T z(91aWXP3@beP#crO+-pdW^bXFaq8DLTBE#W|7SzYZbN2op_g&$!;{3QPO|?K*4|;r z>@D;%PQBOX!)l4_|5O>2I*!a9LT}P!zo;?ogKYPU>lAwn^04@#y#Li;RuxNT zZ=siQ>X)^-q{hhmUma#Pwq*7edKsraL%Xx8i@g7Jb!KNvW^bXFaq2f`IHfkq`(HaB z^|EC47J3<{e)*h}%D-7>=d~JrESbH9UdE}v_2RS|An$*jo*rz;>@D;%PW{wO7gQyA z|LaQHR+h}(LNDXgcaOcUzLEF8rqtDz%-%vTr+#VwRJxYD|JCee6GLWip_g&$ zU$4!e@5=jM4a)mC$?O~ScK?hQdnUh}j3ig?F&&umNJ*(-D!7rTT z3WJL3Z1;-j9lLHCddbujELTw9m(Tw!X_?-V*<0vkocfmQ^5`@2`JZ)fid!;!3%!g} zzcpP>JzGBi)25I7ZX}q!gW|;aqL;Q;&ReOQTQYkKy^K?z@orXqR6hUHyGcV!W^bXFaq5R<&7o)BUv4fv z*OtuQLNDXgPimc8{~(|LncuyM(7J3<{{_`+z zJwrbKbLsvvCz*YN-tbgPPp;)@eHIN>>?hQdnUh}j3ig?+5smeb%{g?|&pVvt``2sf z^YVG=6~&Jlddbw(U-y;XweUCfe8n3>W^bXFaq5%iQo3U)r}`yTCQD{-p_g&$->Cro zTt5Gtr&J+JW^bXFaq6G=SJSfx_^GP%%UCjd3%!g}|D~Xxjyp2Xk@uHMmdxHlFXPl# zds|f>&y&;n;Amw_W^bXFaq6QF`01_RWH(;5%3Csf3%!g}pKFxA{!u>v{Aqkq*?<0T zW^bXFaq3k@hps7~e|Fr>ZprK|^fFHUsgUaWukDvj{PMfctEb85pQ{gDZOH5`^fFHUrSBSP*XN(dr|D?O>@D;%PJOn~&Gl*d z{PU3mx1D764SM6swAY>$-dDMWFM9?1%&ofez2A1%)Xb7zPV(NAk$nGaNws^1%-%vT@x6sQt^^1ROt=GLd<@|nLYD;Esp_g&$e?8qsZ;r{3pL2VGXa|201E&xXw2LNDXgAKTDb&zA3hZT&UM zkl9=4Wt{qcwwsj?gZ=siQ>Q|)ep%=*azw&+xGGz7^dKsraaB6Su`u^AD zZRre|eS_Y^*#_xR=a-o$Kjc&FC)AUflV0`;_L(Z-b`KygPCrclB;RWe znl{wXOQvSqy1_bLzT;fI;#@;!Z=siQ>hr5XdZT;~x?7c1hRohVFXPk?$u>}b=yTQ) z9l6br*<0vkocdu^2Iy(oCOg&)*<;A;E%Y)@{ko|Bdj8~_fy?JR4Vk@#UdE}I_MXX~8NhRohVFXPm2 z8b44smhXUfNWH^am2Ul^n>^(tV#j$dTR>@D;%PW|Psp}I?YALIXJsv)zt z(91aWetCxKK>5CTveyF)nZ1Qx#;H&CV3_VK-$@ToQP+^!Tj*t+`ewPpblJ*2rpWc& zhRnV}?}MzP_4Iui%wLnPI@nLBCo?C#*>^|k-4p#BtG9*3v2U>FP{W=;JvBVvsi%hL zGWFE(Jf)r*o`cj=!}E)JYIyEYPYurt>Z#$Hr=A+FXX>fpTBV*Eu0!gn;Tof!8m3@Ab9L!!=bhtWI(e!#W_I#H&hg)k(c`i%3heE9(U~uFw7$E&unC&h z+(|t(2e(D&fx}Xp9M5CosHdjN_AxqL>NCz11JC(WPmSprsf%Wq^ho;HqhbB_g5PtD6e#^@_PdmXPw zln$hxnomi_=$HDlZ#$H;o7j}2I;+JcbF0zJp#!m;`{5jot-B2o!B^f$KDFn$!7g%h7X_Xpq@F&Tx0a+ z3L2)ryclPSc_mYfQ%~kPq_i1;se^WUf_u>qU*!VQs!RTaRn37^j}h z^-S;S5n;MnyC%-{PdY2csV8&I)0=N@m|p+$nZW)1yD7%0C-c0Zw^(ZVJA6N!a!h#M zN-<77ndc6@buW$3`L|S5&z|`!#;GUs{GzvYhT(eY$-(N~fUJsf>d8C@={@Tlq8l`w zr|zYRb1+Ulndd3JeLoMZJlJ5I)_C$lHeyL5O@UA=a^TJtK1mMwcj^!9N_)#E)Oh8i;S z(93?pzR@aW2fa2ZiB0wBq=W2#y^Ve!lG?_9-O534-b`Ke_AbAfwvB2k>Y0x6s?gzo&jODMAH|j8cqKPiAkS_s_Kk!+X`rX9$*9wp9%QH? zGY`G&C+r&@leM1nx`-`vOe^y29Rd1i?y`2!tR#xwq>`-kcE<7ve>^fN@DaNTMv$xQDGo*=bXnUK2fgYN1>dEXa z^o~B+RFAssbWZZgsu`!A%-%xp7o{A5?XqdcsVB3y&>Q->iOy3cP_0~#(h9^ujS) z6ywyB*<0xSQuiypc~Ak};+I~Eaq7wJE%g4e=Ko>uy`!uux^-`w43aZQ&KWua!ma{A za**6)kSG}>OArJU$ypQ;1<6Y2fJpaR1QS`5pdcU!q5^^>2@3aFEt~V(oOhq&d&m9m zxZfD(j~?S;@;tNVs#R;Q3TszYw+~8`w?#G+1`z`ANe9|-kpCX&`v%v za|^Y5CRVZ|I!4-MACz-wC!d%(gj(jD4AJH6`9=}8O`D+(ImGlsE%OQU%&0G(wqy0p zSNvD68{+xnbK4E|>$~$$*EQ5G{JDtz%a(CRtvVRMr%z($7HU^Vma?I1Gq_`3NM&g! zpP0FY+L?pP*&VHqIv;f@U}-0xn7M`84+mAWr%Oz8d|fJ9+Q}zoZlU&g&dN6Xr>7IU zZ>wTyC!d(Ph1vxzD%*!uy7iTj+JNd-SE!6I*o!bsh(a;`0R?g5)J~49(wZ70ScKW22wqC!e8nly7 z%-llloV#i5oKvlA(VKZ3+Q}zo4xyGgXKwqH_Ds%}_DJh~4mrg1LoM?O^Grtj8w_!=4kyjPvz^>pUraL8ro8gIdGl~}w_WOc0et!-W^SQ&)~3Hq#yt7mZJi5R z+Q}zoZlN~a8!2qM#LLc852{+)$tPxRp|;Jb)OL30o6dJ98d=)OCuVM;_U7ia_PxkI z5+_%0V`(R!n7M`8X}8ka;#)`hT7A;i(oQ}xa|^ZgK1gGK%Qf6gum8NIoqS^E7HU5{ zn9{!0_pte;Voggs`NYgE)aII*%-Vuk?0XqXTiVGdW^SR@&3W6b{VUYgIhfYcPChYn z3$^#}|7?Cr)x^Ho>?#G4d32t{)q2u*Hn-8 z(M~=wa|^XSr+s4PRqt=V8IsJQoqS^E5NeroCjY+4+&lB4E%izVha6)1p_ciCdFEi7 z*G)q8Zf>T9dkk@k>J!Yu!u{Ng)!s4G4mi8WJZK9JoG+)%;(oQ}xa|^Z4AO6^!?(wScjq(F6?c@_Pw@@3IHr`}NHpzTgx0j`zd}8Jn zYNL{GGB1=mZDxeEwzQK^%-lllwR@|~%jfdga&K0*w3AQF+(PY&hHsl{hilkLFXgke zlTXatLhXVcGfn&P?QH#=KN;G|CuVM;_M;Uqo0EqI*o?bo8rsPxW^SQ2yiI#^;IC2E zZII}roqS^E7HS)puWG)1Ym9CC^yi7RlTXYXLM?Mnp?)RI=ch*6bfarK%-lk4l?Qpvs}CPK39Z{(+Q}zoZlU(;uBFZX`751>?E@|C?#GI|hZC?ANFGO3!=Q(oQ}xa|^Yv?JQ@KO`dGRr@Ulo zC!d(Ph1wU#6f((&oily%zhG%6pP0FY+Rw9QG@l=T+O|$n-_lM#F>?#Gw_g6$_ra)| zw#_poE$!qJGq+IN@bG5e`It_&Wd1)5?c@_Pw@~}-@*cjBzC&$H_V*3#Kv~aBbx@>WW z9Af&Rmbv2M?#qeaSL^0Jo8z*%+bg9ry+}WIdpkD(GcQpa?`}yftp3lgiiIrwkVDMe zLT&NmuO!Y=|0i+ovzB)9iJ4odjd~cG*jfFb*@rq?+Q}zoZlU)3>^BnDsQ+{O@K8%T z`NYgE)aHE{n-EeYh12ZFI7>VE#LO+!W=ORm!Ss67H=*wYOFQ|*%q`TWSn_Q`LG^#$ zo~-Xo;gft~<`!zh#^z6KsQ%BG!M!Z)@`!S*LzL_>IP^|JuXyhQE1uV*?FHUIPCw*@WzkVDMe zLT&!clbpM`^Sf8WYg*dLCuVM;wtL$l&S=g5?#G2iJ9QGHoB}8$ElprJa0Y<`!!A{@T^qpJ%uk zQ(&m2oqS^E7HaQ3*WZcO{7;^gFId{iCuVM;wp*idPK4%v)|_o%X(ykUxrN%w>!vv? zHUHCfMOjNb`NYgE)TaG(k#kt{KYxx*Woaj$n7M`8AwxfKvS|LN=hm%;cJhgtTd4iG zc${-b^FMEP_ZiyBCuVM;c3#cToQ0bI2|NCMb=t`%W)7j2cIKa|hxREKy=e2jv@Vf2 zn3lQX0j=5X4)>kPF4C^+Q}zoZlN|^$wN+Wt$+PIvAd<6 zd}8JnYU|WK;=H2uufHC)vb2*=%-lk4@~bDELt6i8SkqeC$tPxRq4v`E7o6|4{^jH; zW@#s%n7M`8%Ikl3PHFvX`LYljU`KwVmbr!6R6jj%x@-OGP~^vkcJhgtTd18oCAI6V ze=WM#%+O9gF>?#GKkUuu&e!_av#TrmXeXbTd4pQonP`qL zdBL?zmUi-qnOms+vqN=vY?IkeiA;qo?c@_Pw@^DVx|%z~R&~tivX*x8iJ4odE#s@| z7F)G2vEa_imUi-qnOms!<*4fZ@JCMHwKbuZcJhgtTc~x7I&QAWJ7(hkV}^F-B4XwiYFqwN-+e>hKez6+($G#mF>?#Gudi+5F4p(Y zKd0_wXeXbTxrN$FOIx@__5JhNjHi9HlTXaNK`rgfGnq=aa;NKC=qBNm6r7@;!!r$RTEKq4teF9o)nE z{a46?^M-cviJ4odT|Bs*+y1S(&Z{l%8`{YyW^SQ2`l)F5P}_%zY38T0w3AQF+(PZi zx^3Mh-I^tKxsuM(PChYn3$;_rwskvycc{j#ndvR< zPt4pxZL^=F-S0M3GDkj4W@#s%n7M`8mYdtVjSdVk+45g8w3AQF+(PZQ$vU~`nk_UH zE`DujC!d(Ph1!T6UEGTL{a4w<7(+Yx#LO+!4m$FJdq%(i>i*RnLp%Az%q`TGFVxE| zq~CuXx!%UmPChYn3$viyZpy)A8{}( zb4B-JBi!p-iaT}c^e}Tz403z_+13f)GAjTxFH!r`$3xubHWzVf-#$?c@_Pw@`aBVSxMe!RQ+2_a>SEJMtT~%q`RwOFq!;5*zK? z{pKfzcJhgtTd1wPW}y3W#5P~uPBDgd@`;&SsLix`kh}cZ2fh-6))?B!CuVM;w&3-_ z?nV7hd{FDR4DI9-Gq+INW%N+@1^t#h^|on-cJhgtTd3Voc9=U?zc&wy8E9xHpP0FY z+B!FeyD#cD=|B8g&(KajF>?#Gucsd4)}K+vRLz~i&`v%v^9HrFGtV3iAMU=?c$nFr zrnn&vre&UC-ni9bl>4mqPxztmsDOOJoInokeBQ~SozF5kwDUP7hju=L*NuNj`UxY1nzFr8ZyB6watm>Y7z|N7>ZN zcbiwbEjFEscMb4K|G~8M&lr9xw9V}MB+5*w)7KKGj!o%2xS443_3me>Wjsgo{hoO2 zsXu%z+l;jXpN}(J@%D?7E6r#(&W!r1YXD}P)Y3o8E%U~krhcV#X4}mnmUxvfK5zV>Zt5O(>At{`74VOYH{@zVVIedOGpr{Nrr8X|+tH z`2A+jTRj6}W1NhETKZ?XIgeL133<->-kdYW5?5G|$;`-`SL6MLmfGK@R5m-3T}$lO zb&Sowv#5Dv>;bdlQm=s67$;+(mi}38hr3x#;hX1u@9cir5+B{x+N?^J+s16EXQ@qj zV}v@KbPR2m(;6`Umy*-Jh%cbT4{#h>Z?G48gdT)<1Q3qbO)UNGt!L*OM?d!S! z1^ey2bcwI5UTxmkJ|rME#>p6{%`oGFc{q59Ikd2CfPa=t95JG$pQd+;A2?%vUX{z8HZ;`N?4zcZm_AwV<=mazc70Bm zB2%Xs`e(Vs*Fv+ohu-tBL@z5 zW_;e(5;Hbx>m*cg7xk%T-#T~KNB=CB_-@W~&eN?zZO=cmT51^s&vVb4Vvn;m-Bu^` zw`fbu*r?^%?)1-ciEp?0(0R3f0~^~SrKOfJ@OzV#p zF7amrIyzNbb+8p~Ts71(2A=oYG9sU2)~9h#t!!=xf_v-D{|23_K5R{jkht z+@RcU-a3seF=L~aXU5S#%OyT^xQmIN*~`AuafhLnG4MR84&~;X!Gp596)x4b#Egwv zo*_m5ESGrItZk-ZbO-yxp6!NO#=!GsQfxS3@~lbYj+tHE5;Hbxd8Q2gvs~h?ZT>Pp zH)&w=^-MI>G6tSE(PMl@TfEaR&WCS@Sz^XUEzg*sf0j#JyGVZ9tzD>H{?uoNTE@Wr z=f|%rZMTMObp{M8V~H6XwcK-_{#h>Zv@79u!G}5Q@FrgyY8eCfqb|GEXU}yS?rfV= z*b*}~YPknB{j*%+g;`HQN;#!@aU<&%zX=3;y1_D zwNrXMXZqaCYpKm(dfSva7n!v^mmAv2C$5p8`(E~alj3RyOD$s<^FwEQYILa6KJk*t zU(nj#6?-Qxiz{P^85^~krnI#=HeNKj=Pfey&vJ?H6s=~{PdsZnR8DKDWemRYjqEE? zOPz#gQ`>@zD%yObiaL8giweMujoSCG)U@mS<+fS&%ro@Qa*4N8Drs#~)lHf-mRiQp zU~j1X=I&9a*wvhNYR|mdZ)A*PiqsCkjFZ|kLyFtB*COrd@8=o%XSu}1&u6kk&vE13#wP^rmoYWqxm%@HDs;Qm1bdjNdmP=e` z>(AzP`6yeXL^?|?WBBFEGp1mr>~4#!p?1w@d(58Kw>inxk0NHA)TU{fXhwGLYFF=j z$Iw5^CElNIqq#f1wtcH;21_ktD3g1ESv9eMJ3FDeZM1%tdFA6To!B8=12AKw_F}^> z#@Dc)ZIEV-p?{W3JpXQ+GrteCpWcWy^v`mMOMdpXuX6LI_FbFPQp*@>)c7c&!0ZBU^DPbR`Gfg< zU&emveBG>H0A`%jzED0f@sqm!?57n!HT2JNiF4PUnb6|BMs`!qr!BRN;Y@s(GqiSg zchiE#c2)T5#1fOXIdwJ-2*8Y!+RDR5Iwd=GwFRC%YUrQk5?{`e&N()>w(Y&7h^3Y> z3_7*K`KEbtx9*I_cKT2Co#r){I|=6p1YpKV?Mqj7Ic0`4wdFp%Xy~8i64zfe+KCU3 zviaAPw$w6)@2^~R#??ON%$U-^mO1&BQ~S*^&O1l?1z^TW?ZX-&?$S$<_VfcbofVsk*%xwa|0-x1!^w$R-R0w!I(uf;wl@pxbE>s1>NM4UvBZp%+Tnjb?e0{5 zj;@?0z(30+PVw7G=i^ox?AiD#mRiP8zj+zgtq|t4`Rp0n|JrqDV1+)3sn2!|z>JOB zCJQRNue^8B6y2I7z(30+e)pFLPTJ_R=2l~Csbvh`6nMt%Tl>R=3!5t09!pZYH4`TJ zN|tCBfEg#XnV0(9DK9KCTQ}zm@XvCI8&*i~?l`{OL|?0CsbvhOy4QB^KAXzyNm0~R zyO_$YU9Ews)T~tiW}Lya^v`mM>7V6t9g6EmoMR#8ybZNntKvEr`#i+#w@}NqC;Df( z#GJRGmN9T`i+vtq#zrmcgzH(H^C4zkQOmV6UN7r`nEfbfxfaIjWjzpc9*J7k3D?@# z2P0-(QOi2v`Wok;h*?+EaxIV7%X%PYzm8h2&GC9!55%0;qLy{SwLkU=iCI_FvQD_( z$2l=#))lo}Tjce!9*Eh`q?YT3yk6D=G3VK+Wu0(cl6_QS))lp^6RtmUj*gghMJ?Al zdA+O$V)lEfm-Rr*c|U4dCtN3GpP86-MJ?-u>!F-8BxYSv%eB{l>kTqaVLzN& zuB-BTSr5dVhoqKu!gX8r;fYyS)Ur;vKFc{wV%8P4Tnpy)vL1*zE})j{yu4o412N}C zsb!sT9hqYaV%8P4tP`#mb550*bww@Lrg^=r2V#y>sO7pdub1^e%z0XBStnfA<`{>V zbww@fgzMLw<0WQYQOmV*UN7r`nByjDxem_jWjzpc-k4g}3D?;<<|1ZYQOi2vdOGKv ziCI_Fa_yei%X%Q@IF4Gb%kz3!55%0urj~V57~dyw3`oqnqLy{S^?lBP6SJw%c_>eRAM_#Fbrq{OT%YFQ`zK7n)c#H=f7`3(cFm-Rr*aW1v| zZh_a!dLZUJKeenAeiy+pGBN9lTGk1_$KV zK+L+LmUY5!OSpzY%(|kM-=gq(Sr5dVm!Ov4necj955!!Tp_X;R?^rmeLCm_MmUY7K zUbr?y%(|kM-`MbaSr5dVZ=sek@OoJf#Egwv)(QQyTw>N0wGSUou*WKliXAs@bHtPQ zgPSd5w>KaD*gpOraOlU+r=L3I_Qjp}H9GRYDl5`i6%kwOtyqskKK&eB=0;qev?<2p zkWUV=ca0AoJ}mC>_ZwgQ>ifmwp2SYMoLfgXe>>i@x658I_M6YPgnO8Ns3pgblO=n_ zUd*;4erm(4TRrWLUN6LD__0EgPh!UNAjg^T#V>bGs%O8SC$;1-9`eZ{UQl6qT$Ss^ zs(3zgZJQqXLah@?*Y3w&%*RnbQwr~iII$`rss8E5&-eV0L+rmU`Xu(WevXH4mOZd# z_npY3diMKyl1~of@$;Yb!}=kgeux0=Gu`zri`>HQ$@Oin|&OyOt`)Lusx4E6`v}t~ zaWL(c?prrM_-(i8@oInfRCK4%R9APK7li4PnB`L2rEay#g+H%nw&i%)eSK-cuyT(u zeG&)Lx|J)gK3=`5_uh63zEwB$$MWg7c$hwkSuVBjovpU9(C76WFP>4Qk8LXQ2-7EV zFzumzSvIFs+wtloWZ=ooX@$E9(@r8ar}LR(I#y{HYj)Au84VfIa~Tb#Mi>vh3S)+XtrMRUzEpxdT`_TggN`XF<=0G@#)v1=A~`!jg{Qq zZx@cMU%5quhv|n}a{O5L()}Xail~?V9)G#McRNQk{ouExIEfpD+sLr%E0W4uKBsed zwdB{5>csEIE0=t77!Ud65PNm#wO`NYzrtS38h<_Jd>x-G_S>38lVT3$ha6)1e`edZ zxV1;uCix+bIbNztXz0YG`p>c9P{h&L*-6(F1)e|GO+xK=c8=WTJ`7pF;BcDLB^Y;Jnpcj9GDL)|nLLfz5%pEuOD)%|*~?0qMh z>X~H)i-&ED+GdwlI7Qxl-zhCWb5+)|+;yCbx)+Rrm@!kkdsTOLd+17Y?EWgld&;^c z=Dnac{p#*+;fgDri+`;$ymrPw%$TWd=XA7J?@oxH_d$qFv!kP3IW9gj?)?zkRO7Ia z^2Os9r-}@~IrQ&=&NK0c_5ak?k)KS7^W(P45AEa=*OH&K+24p;B|p^ulGxFvFT60W z<*JYXJNd*R@-v~xYjNl0huR-)$X;b6hl^<%Ei)bgGnC+0-TZ*Ubv=BG_s5J?+^I0SQ?RdBymM+TO_|%mI zYG2a54z2sZIsEG0MB2$G-jX)lrXLaR*8DY-L+vHS^ZAUc&Zk4_2H43b-kB!c?#fig z?U`|gL+uN?UlZOs?i|cAC%{fV@pSnKE1AcQX|d0tHdgWMkKXF+X}dMRPCoH)`RUgq z#I378Y7Z-(BAMqnrYBSVuR64oPkcr7 zvnS&WGh6jTZG`;n&NRnNdh@tLJNd-3Ihks0SWw3APqPJYIf%wykfxzC~YPx%=%{HQBJ~8_()V`?e%2_F{%1GsB+SxZFuA{u1|7yJ|?<-GJdtU8% ztlk$L^}e8;eBxx%zqIr9h@a$-+F+P`V$FNn=f+iv_2xkTmA1X&p`H9-*w3f-NgPc3 zhvF#SrESzz#N%lf>A6Tfs%zB975@>BXD6RHz4WVQWR3b>*GKIJ`H2c?6WdCDXeXbz zxct1aFg9YR{7}oj3hm?*vp+-aU(5Ag4}Cx8shu5d`}aa@@xdJ-nrc zs&AwhkB9xS1&e{tKDC}te+oImM8r@TjWEbS?DHa*6B6 zuRkAB%NXXUuaHowNY&rv^IgRgStWUuy3!FdHflNMrGJ)7%v?<^$Go(2%uCGiDYd*7 z+Bp^@<~33~U(adF*&S_MhAfF3NAo>J%y(IU7US+`-V1Sa&Fg6QCT31d_ieb_F zD&3U?VvYwn?q&?MvmS_9SJaxdA=ZwIwrQiwJB*X@6Z2h9Ew81J+H&q*y~=&a|xuzW6%&y|X&yZX0lyN3i|#z}1p)z60dx6JD4 zRb2XKxy0;CQ_C3gtO#*a%4gacRonro!`)pi_nER9XAv__YWFCfuWqa{JAQBE(m%^3 z<`{um#xPUyMBQ9t4$J3vil=C%8D^fwBgBl2+LoGI`KC^J({567j8JF=L~4i}F~biqqrkIUQa4XSu`yV>)OV!>f9}(!4$` zs=ItXqxMsI=A@{S8b1;7V5ia|})`V_2*9^Rsf#SMqsI?dNOdp10I~h#4ET z4HVDI^=~=b^?cDk%O&RA0=0~xnc{g*KG)0VXvH%_^BCW1TujW^sGX_&(^PrF=#Tzc zE-~j!sAUX4t`2br=gjZ6&6VHnoG#ow_dG{f{ zw$n~NZz`TQHJ=uyHbl(Ws7-F=!@#8eb^L>w!aeEXG{j*%+5Y21&*Dt8``}ATct^VPjfzOAB2>Uet z+EV<3*!8MgVsAX?kB!<%il^_~T5;a^l>S*Rv99a!x(v09VXESpelT6!UimDha<>+} z5wlzI5HmJvODUcbT?@r|*Fyg+mzZlt)G~(6iYH~%=dqg=Pn6=BS>wIfO^Sz@u~9o$ z`Df}k8{=a%=R^N2mzeWN)G`MD{E0W8Q&RD?**P`FRXoIujatq@(Lc*2E-t_R`7vr4 z12N}$h#4FCIn;++`>=IHTHQAf$ED~K>tXVV>GMgg=O^7GKYpL&2g80pe(lAv6(iHb zk7p022`F#em%r?dwER)?VQIT z<~#tk19o(D!|OgU)28fAq@8?Xj^C+Wr)z99^Qt-ZQeB63@`*X_ruKdL3Dx>ezD#o* z+Q}#8c$wPGx~`h7wwg~{Y;|ZSpP1uZYJH05O2#?nn%2K)C!d((Q)(y3j~!Ome5Lg` z+Q}#8xRTnR5<9w0+wAo{-~53?JNd*M4^rDq?I*==eWI?Z4^BJz#2m*_drk37iQb!- zMe)#1J~78%)J{?TtWeuIq57end}5B9sEw4LPt|rN>VDBqJ~78T)J|6YRMlGLQ2o(P zJ~78B)PACPDlb0nOwf8I?c@`4d_iqv#nW&4RcDdD2cVsNVvY-_J+F9(0V29 zoWgT{%0yAGJXFnLgQ1 zCidrQuP;q4-x0KvPt5)ywH`L}I>&kMFWSi`X1|Wwyz=wgu+8Dg^e(2Id}8*;sLdfi z36J_1w3AQFeiXGH_V-n2C!d&o7;5#+WWew5^v&es-$k|?IX`ydluX_?la_ejl(4N$ zT5R>c-L*p(XN<})BX<(VkG=1w`TN0>x$Z~%V^5f@we#jwaJpUc`%1u>ebVTEm zzkAYp-KdCI-3;GO(-`LVU=C9$Gl72r(pXB>FPsT&OpX0^gub(IRf|gJ}=XD;_anR~g%4nY9O;qcN`v zHx;H&VwOv7x83FA@@#Bj*YwY7uSOS+%PqW4m_CVvX%`gO5>vg?AiHf=oGF*FPee80 z-NN)q%yOw++Id7og`(r_^pm%Jemp~%K8gQEt_Y> zIhBRYBkb4GC$W46XxrGv5jp>^TbGzViCHfBU+KP&|NFkXxEBFF$tR|^g4$j-wY~Zu zzTk!n=M{cVm_CVvX~Xm^eE#>d;8qttB)oq1r~sez&vL1~TdGv48|8|J=~;CD*nWD| zm0Gtqdze0ngK1@tQ9Mpk48nUJVfrLyxzr}C|0!nGwJS~$)d_Jpd=dxKUYJ)rcHyov zu32VXV)_h*$!~5O$7b2s!j0*l)%D|8VRC|DKi|_vW$Y7Mr_&&Jn%eVkIWI@l6n9<;X&p!U0)MvkDk1g2#o21{}5R>yyaDjz+ z;?j2c%<))Prb5~imC%M;$bd&pPMSRpLXPk%W$IpL~ z!|NiSeux>*zl;A*`3Y8TgH98}ue_8dshd!Z{lTVy^L6|LlE0-JA>nlU;Rrz_j z|8=ME*(w2c@`+>QXXwOoZl7F}47I95JL}F?acC!>c#-@Jom9@PlY5dwZ3V?s zr{__}*LZ$_oqXaA@)M_ezTERGhg$D9Ako*?I}y2e1=z_a{!Hy^d)*sOl_u$ueplkx z9#uRaJs9lNS#%-kcO`y1`NVA&hS@Y~hi|-C)TOqD*1cwh-bws@`+bLY@`<N)XFuBhIcr=^{I;)A;Hb$2X|JJ7$1OYJX;=ZA84e3!S~cW5V{xSaf~ zSXjy2&lBcS`blm9U1xsiThygCx$3#|_4TGvu3Zl8o@0oM&3b2z;9Hn^r>%L!Zl+IFnO!d?6!C=#5(FH?0`NZC{|C!oh1-&n* zZLR0xN~Jr#ZQJh~+Q}z=PktINs$|CI4YSnV^X~iM`4JQK-4^ZS6F1j&wJvf$vhIK? zmRi31XeXbT??h^!()WJh&$l$K+O)BYH3z--a*L=oiji7k#zyTTee;uU*2s9xh1;U~ z-fvEemZq5JbAFiHdT}K)O!YwAenFVKr|P0OpRSAA^s1K;&0efl!qPv>C1zWqmNERM?nv z^*kQY^GM9tsC`QJD^>5N_SDR!hW=SDF`s>E8AAqr|C~lXkIH9y)z4k!&nV>?V#Y@8 zJ;k%3Xb1b?`y)R3XSu}8Y1A?X+1>T>8GY)A@1*LdtMX?DxyTSeE#|Uk;LzaFZ8wwRnWTL9wfbGejE&mrdS7g6-qI9q)5Z<( zulJq5|Hc^D$D@`pG*kY0PVb-!^0{eVm^(=C&A$1<0x)Bvc8Q*^K8^au>z(D&Kg%U% z-<4X%;JuH&tv@WvTi5NZ`icDf{m5zqssv!hNv*IQ@qA0Cw62BzSuXK5)tkRRPc38c z-bbTbv~-GlKGmM9dgEO6|A`qVwKrCW*k8*YaBja;+ogY&OU$tbwTvN!-lw0IIp9LpzIXSu{2Ls82Z67;+`md}#%xlipUZ@n8% zN{!cu87H-U)qX0hk90%#-E-)l6Sa)~*XrV`-0^IO3y! zmP^bz3Thd{Rj>W%8mp<#@S5u6eZ|w~$4vp4u~C~(?Wb0+rtXWgmKyqJxx}1%p_VaB zQ-0ndpYN&vb6D|2=zdxCe~1|;wWrj6(rt)zf7y4>&_By1&aCl;e?E#@#*jtzQ%63} zs()Bc@f=Wl?%MmS0L<8^U8#7U*0b5WdI?MaESH#bWz;f;KlDC5)is;@qx$3@sr`Ik z=Y}&&{bypvN$q^a6IK3z^SZ_t^v`mMN9+0W&mU6D7^bRzM#|@S`MjSAegWAgHZRNvRnlCD*dC>rjIH~0rkp5XN zF~^3~G6s(CIPN26Y}D#E&+g_GHKO#}UmLA&+h&K|NlfkDH{=u3C$$=DyW=X{@txE7 zop$nxIUb~Tp1xzekbH=Fxa5MNoqS@BhP1G)zpKY4|nfgN&Lp%Az9Pd#3vF_JZ%|~rYKgLHp`NSNjP`gon?)^Ql zl}J1J#2jBxt2s>f8(mjX&DYURJ~77y)Si`}gsw-;^7`|=dC|u{$tPxip4!#At})lv zn>0ChIkb~c%zikvlN3Y7zXqF}3obaclTVyUdD7p{r}hiQb1UqQ@BWVa4(;R3Wqt@uYZ_|3p)N@rF+Q}zoKZ;uK z+u&cdzSHBWF^RO3Pt5)gwHM@Pt^8EgdK2yB6SLn!t#_{v47%k~^ z`bpOPsMA3CkaqHk*-xPMRmJnowe?QdoVyI|bfd+q1&-NgPa@`iq_6WmNt}oqJL5`S|b(!smqPlbGdF`)i+0;m@f)W~g4~ z{+T9bxbRw?he4mj!L(m?%o5|>pGLY*Im%xN`#|`>7xe;s(m%_kwq@hrH+%Q6+M;@~ zP4@Ij`gTA4^4KW)Bo3y{(Es%zNGuHS=p>>nED z?c1mQ*aCdge=zN+GkL?j_I&F^D>wVF>y<-=Zwu2WG0UZPNWEzv9o6%dTxVc>rf2OB z;d_(%2l%A_VA|t)#%HSS#OmCO6o+cZw%t|F{31-B#4MNEbZu?y@ZBqt&HPwczOMG-#nXIy&DhSuTZQS9nB`L2;;M};@cVA(y6PlPsiv_}!oLaA zCvhC6)PBxbqPc3x6EMs3FR+DtoP618^_UyT< z-uuG+N$-es{m&<1@7+P4#4MNEQNLu4_*w1cq4G}J5~suW3+LB6j6R8jY5%;CHX^Os zb2jC{!?jC9DF3+1KLI}JpXE~9{zjFEVQMc8m6y-<$R6RHlcV!^0({bcFl}t=vJub! z{ft|)?%3w_yXrX?^vy_@t;GNCGxhJbpJ4o8_F(rY82wKF*lF6Y;7#p$K|A@x zH5Jd;5_#OtE%q5|Tg&HzH?BG7uWP@xjoO2r+PjKpiuNlw*>rlM6CanK*R{7|uXhheQtQ>pSB)Mx>ssthq@8@? zujOZy;t5ropmwPIq|km2mj>4ju#->ROMa4RFT;#F!+_eQx~_t{Uv0JL1?}V$Tls0G zefIijpFL``E1nWM+hK+NXeXa|iu?>y`zfVAYUipwpG!Z-={NVdLp%Az+Ka>9)L9ef z6%)0MbzS+jH-EC(R~_2PCoZpcSVepFbx<3kHb#C@x7(Z8yXgamcJhgTk)PLeuR3e5 zJ!%`s&*7bgqBiIo2inOe-XK2V8ps zTGzFz?N(DzXN1sBKJo9m@1HC8tWf)*_KvQr_mbo0l-e`x??CN(#nW85 zd7<`{p`CotJTSxB>`kPdeBy=j^URX-mM zts7t`pSYI%6jA+@*Pgu8-q8Iz_2zN&b>=w%cJhgf%FheBU+<_5QM*?0REpkemg|pp z@`<(AjeSe)XNdl&O;CI8onemoTJKZZ$tOOlc9>bQTvANb=2Sdm^zM3P_EkeW`NZLR zzNYBiRY!YXQ`<=Kq|OU0FyDLKd2WoFCo`yd~$4_0UeTCtZeBxt@ zr*6-KaWn5nS!&r=p`CnU_F<@Pqwf#PJX_w3o)B$&2#0L?Ft(oB0=2}9joNP7llIex zBjOrJ`=P%7S!>IiWUoY9Z%?gmdor0s)dTTh?aNwq_pqo-dN!!tqZrm|KWcNek)?l@ zOUyc_mNAsj_doZvAN8-=)4Za}U7`EiO3wf>W21JKz8CGFy|o+9sAB1#p(v?{ie>itL6&ocFqwP{WO zW^B}UP(00apTl*(>7V5iGpA9@7#`}}fpj+-*%E4(pQwJcm$}a9nh}5*C$;+(&ow;< zZM6S5{j*$R=4xsgLml0($cfQ*y!J^yt$4bQ4!7x)Yls;qwd(g+ufMWuY4LdaXSu|D z2T{uyGN>=*<>(R{Zgi)R#7~E>b-ePXMGVfPHLZ5JOk8z_G<5F`e(Vs>@!fy73X+5Q0{3ZpSM&ebM^k3sQy1OW1}|pnh<-tR(X?SLbOZ&ESH#L z4Qd&~O6BLW^7*@bPSX3mxpL1Z8rKjrHfpmfp5#rJho95FgY?gGi8rYK;~#%f%NXjb z{rHNM-|BsLvsCwM)5crz+y9CRz>JOBYKkYX^2E*Y(JuY7Tw;z5sbvh=b-%u~@8`=YsppHB zu~9oo`6pYR{BE>z1^u&JV&(bA^BdGMhB9hD$>mdd&3#MpWbGN^9#sAzW^B|d7g^;} z*UP2!&vJ=5_d+dWSf%`2T|V>4=XS+&Q)Bez%Fo1%jaubuyG3UoOwzlC{#h^M4<)2N;J>Gc=#EgyFysDpe6QkV^bY=(p88{NzY^^l_2uZF#QYrnd;~0-b?|Q zaZ>w<+Rr()pDude&_By1=A13HjNv0aUz_Ap{U4)y?Iu_5`AhFGV#Z1BJNmun$J45~ z<21gYf0j$kxoBz`!y?_Un>qs}tKRWV70(0BdzaB!r^Jkn+A?ZCN0cX?Qh$a1SuU{` zn}2?uTEd(w zh1yRp`TSJ<&Y`NGJDS&hMtwwL#zt)ey}v&DUFWW7{7(NYmzZlJ)G~&-dY|^VzQ$Q8 zpQlwP?X~`LK?2K}>KV$PFL%NU9%p1G#H^QC-_R6ITRW^zty zeuJ2?QOh|N`e(VsoO_{`G04y3xfjl>5HmJv&#E6b_z32|Dk1hxVYS zoqS@>Z%{i_eloS&YQE5XChg=Cb6$elEBc+nJk5t+P)xLwPt5rQYAdUL2CHtoIZfKh zC+0i=wcc;1w={cTT&>5^PChZm@6;}opR#&~buXVc>G#-vpX3v(FZ6hRfZAE|lUngi z*Ze%~bh=6 z@AW;W^)K4VC+7HzTCL@|Ase2FU$1u#?c@`4+(fO`&fHI0?@b*0_xj*tpX3vByhCk1 z`DrzxuJf(VqoWqcB&6cT913|lYCKK*`YEXI0n+K7(M~=w`_I&V zq%D8%sO|LB8V~K{6SKcct=4qhczq90OYbn+$tPw% zliDMSXU3xA&Pjd0K|A@x>>pCQTYj`2=M+#5qMdwV_UowaAU~nMKt{U3OCuTp2TJ}|FC!d&o7;5#skj*;f#fV9798dZ!1b^3aXWPf&g<~5g zeN#_7@j<1iI|pkd{idR2&is+P&-F{<__4ku2V)0$}Bu~2b z{Dr=V*!4}bq~AIaGoFmYx5u<@lRl|_=!bki=gD};_j9~>{PpuBpB&nUv;K?o3;sK;caDJH=j*_pPrsd*<$7A4DM0Mk(kJngTK_o$8?-+> zF?|NZ{d}Ey;i5eRU_Zz6`LFPkTK_o$-gyDqw>(_u1tgtc5X?XA z)ZQtzvE=n~D?{}hxxZ~6QR+gi5lQ=n(bGR@?ha=NB~A z`31Rz?>#!pz|ZlYkKmO>{G>KY=NIhz`z#NOb2kEf(m%_kmhUyb@92{_nAUsFPyMzg zeB|ynUcbW4SF%8)exK*Pf88b@z81b=+u!E}5UUUH_>6;pf)mfq2p`jXviA-S@JTH> z#931`i^~0X-`FjhBV|O%>`RjT__6v7Ze)={@hhI+niT)nO%}&IeSTexR~G&F`JSB| zUKjb~5Hsf6aX-f-AD$|yT;k)^QpT=3P}}RTYA@53;g@zaN{X3&$R~%GW&IP}KRk1I z8(So)tYCh~VLarM!}=kg9Ad^yx);P6@5F1olT>dNDh`T0*my`1hknQ> zhw+e44smRul<`&eCH48;+5>;vQY1RVe`<&1lf&nN<@z~Z+tYblkDmqd{hTxUj;Xx% zjkns5TIX`w-a5bFh|Vttd zvME|0kv`Rqy3}Y+d991 zcJhf=%g;>tnW*y%sC`z~byoZBysq;LXeXa|lKf28etq?{zaq6M6i=-7|5>E{e`qJ4 zc#iz+Q$1(UzLC@()c3C)wI5M6?MFmA`NUh)t`6w@g1XudlUnZ^^+FE^J74Jh0@}$Z zer92qEu?n%fzB_WHmiQe5u-iXMkL%%`X1izlYHVgbzLuLKe~z9zm(boif7}0! zc1k<>#5L7^hV*+gu8sC(r8b-5*;Db3FHZ5$PCoHc#ZyK5&3f@ryG!w$*S_&%RX?J@saj#xeQM9t&Qm<0G0AKV?H@%u z`NX^AXQcM29;SUhshuW2HRR{6&M%;yeB%A`Gf;k}YyWL(y%;*^x|(bMI@-x6{#kws z=(?(FUrlPW$N%J8!=!eL?)z%p_Ype3fOhhU)9Jpi(S3hP z`I*`cs-IhGhX?h(pq+eT@7X`6{haIQeL-y*Jr|=Y-|^K=xNm4DpLnwT^wM*&So`)< zdr0w&9xylJOMMqWJNd+3o4h;Xeq?v;^G_|`eYBHL%y%NS-Zzl{>ihy~i5VNU+N;_9 z^4w@|A8FfI-?Mes`2`uYf97=Uli5(`7rdf+AogiLy#*nQCqxSQm_V!Puvj*s&X@{9obXSu}8)zmTu?US5zenD>SDgA}w(YaA}gWe0o zjE!2J5kUVemzeJ$Y8gXH#p6G}KzskXId#8^>3v7c*r<(C`{}Lr9Qnlg1uU1C?^bFV zgSY>`_l)Q~4yTRc*`)SdsP|U^n6XiNL(ls(J@279zkvQ(F0q#z{rwGU8H2a~|1tUe zwOR>Rd+ECq^t}J3^9zU>C$-hpp2sU6rqo#j^v`mM`|G{q??+L~7?j7{A@Zp+V%&+U zpUmoaHBi5cn6Xjooe_|L^9%g3v0P&I@u+1C-v0l6pKoc(YJdJk+IMlQ-kalfegQFK zqn2j`&_By1X5W?CfEe^H8}eT7r0-?KcYphRa-`Q!CT48Z@{9obXSu|0>VEnA^VE8K zKKo-4;* z*M8=MpE$pOoAAK8DS!WGY(pdxa&vJ>qcfEgH zNiAdG{{PE$ztq2V%V-=y%-E>ysrqTJvj*zu`~v!Cxx|wckAJ*OEo0#R|LQxr6E(hW zr2I_G*r@HI{F739`ybc4hW=SDF~{=MG6wGde_!$VG;feo^9IC>jat1s9-m)8|16jI zyz0k4zda2mmPn=)Ca)~+jLM>x>L-~1^e7>VT zRh;5!ru*gfe~1|ywXteHI^W7ot^OhXvs_}%DN)N9y#4=c$>%ls%%pgJRC|6+<27Q& zM(qm4Q%ui$7oA@a;9vK}KM%$jddTjdXQP%ec>DkBOfmP0`sDeQe#PGd5~@1_AxETw;z5sbvg$4?Z3na@~S=)Rv#R8OJ2jPChZm7t{{Zb@kJA zS|4gm-EqB_8JH915ljffv`y`*3{a$K!%Fmv1Rpa%Xy0nu|%>F91<@B6> zuJa29YyO#b@`>5cq_&Uhxn+tW&MR+SaA+r=nEgX)SIW_ltJ&iP^8C_P+f5 zuJw!ITEC#3d}8*;sLiQ%SWD|fS9E>>?c@_r*89lc-=lW6?pIh$GWV+HpJ^wbnEfAW zb!M)6UF$?&YQ2ee@`>4Rq1LcYONdEu19{x%ECGu}7SF7dL6tdX1l7klR&-9@#&dwLg;-fL*m^G!lCGlJ5k z_o9L{5s|K-^d>bRAYBm%MLMY`zT%U);+2_VWpS z@3~^iUj8M8FA856x~eiYiCHeW=G)JI>f6s<@!dB+Y;nXDd#jU@)uCrU; zdoEbU3hyGkQ@HG-YT?u*X1U~!yFbFbOJrZ2+bz88rZ>$yShi>Og)nLo`{IsNd)clS zGLFa_-c4BF54WT9<@C~|KFcMyv)WD*)yWUJJmEEkTM4JR9^j=(eP7(~)Lw#gkMeG5 z7`|KB7Jf9Ks+T79SuVNf)n1b8d*Mr3yc~W*__qE&vRim*Qr{QXqwigoVAF$Q`INw&j7iRD(;jD+#duf`o z67^Xwxv#5Evg#R&O1?5oeS#e%y!GeY;nYlu6U!yHxbD$4J?H*$XTlQd)9v1VtCuGA zeR0iir>OsNAJ%OiX1+mxLHN72ODa>7nB|hYL+z!e`oWvCKJ!m#Z|*O`)Fk%Bb<`jC zRlmGEIIZWj@LR$&g{eu*a>=cu_M-mB^*pNPX(g=t>Q)q{Cb2K>)vA-?$Cb--yLqa< zl_yg7)s3pu)k~B5ESKC7YA@zD3vT8f?RhH!zcOTumnQXnaXYEKsQ+=7y&dAIC9M9( zjVn0SOOyI6m)zv~eSqA$UjtUp@FYvXCF)P}(xkpG?k%+!^Y>=v5YGesH)G5j!qg;Y zx#U(;ECigoFwzFH~RzQ!@9*te@IpOxFMtNycpXHKk z+K%p}Gpkn@&mQ3*;jZgid1+GL7uU3x#CeFpiSrX`60=-#wMOvMx+%Z0C1TBKpJLko zDy9yxFCF^$!q38`4|Qn&JNWNt{vGb$iTST`87J|x==@dxzpD9H_5Y5)FYdG0efjWu z|EiBK|7WrL^7%iBr`5!3P9c4J{)XO*e67JFXPSP$;JWa7eQ)k3eV67leIJha{&QvA z-uiyddfCbSbLJ7JZpP`(PvX)}f8qlAX40x=an4TZkh{56v=gPj-O{0*{=}c?TStBL zXTGsVZfC`EKr#Iy9op$noKN2CjGp;t+j%zJ|X4)=N6%_SU!O*XVv- zl@9InCw@V{Gf`dl%Ul<^`C3I=dDVW>=zUn)=}+9NOLF^dwV$u0L+(+1H~by7p`R5G z?er(ktZxh-S9{(e9df5myk^Z-8#*Z++UZYx=D9NV$7(~abjTgw;E{Dj&*oX_&`y8i z4f>u`HnpL7(joVd-j8awyJf_E>CjGpVn^Q%zuIG9gua<%liNV?q){6(_nmh76Mw3B zQtR9E8>B;SPt{Kwee2>^>CjGp;;X8kA!o2X^5AF0PR^Ma4qrd&qA-9a$v-$S?HN`_a{fSRCi?eDgrkT)p?ft$_bgI65zML!ZjyaeRN*w&`y8i6B@hJ|5$saLvB8eT>)xCreCF< z{=}batjMA^WX20}MOYe;jd@B-Dt_ZmCH^qoIq zqZvEld2?MZxoh>E)Ta7&W~gGIKFcL$os-KLvgzBIt)-b-@f6h9n@r!%?5lE#85_B$ z^qtEab?#WU;-NmvC1zV9mobc&=2~g~sCe?L-F~BX`=#O`W^ClH(04A+>pPb_6%X}U zE-{}Gav4KveUCGPzQa$#8_G#oYhS&5x=?eP({P%iyB24|K zzkb`Kx8fmYY~-46==ak1`S&Ou>a$#8_SNJvhKKrYZ(4nye~;psr8UYOjSC$V4>4mS zw?tggs2`LAv`z18QJ>`!a||MvG3@)YO;inO>KffN?N>$|(Repm@engMa{o|2(NFcW zQuRZ9mP^dBm0ZRUrSJBRmgWk@^St_=p{kz~iieo7ksGLfVv^d=ImJVLmP^bz1G$Xh zkTf%@{an!fy05XtPwnR&#Y4>4$o)b6#6dj^ofQxDSuQc>LgX@rl=>EMm^25eehO<2 z7_4zz>j*E**vQ?jz9;@q@lc=T5_676E@Rjr&1n5yQ#>E5?|EN;D-{nh<0N;dt|Lg- z^NQl3KFcNM+?8C$@Rl?$sosB4JSkK+r`11ee(Qx98@a31b_(i#Z&p0iXSu|jlatFB zjz}||G&M%MH#B$Cvu&+bJj9HX+>v??+UObkOz}{km;SKdYuSv7I-lLzTzUP`>9`}agA!eN9wo^Y*Q1jjE8sDkU za*4U8L@s0a`sPY&k>=$;tA0Lwvc7h;e)PhOjogJAi}jql>r_9~XSu}OD`!a}SVQ#*nIRheS=cO^Tp^MOxcv zU)KvWHgbd2PrRjT*{gV{&vJ>mw@EHzXeiB|(lqV4l=_~fsvoV3y)fe>S91(U^B>pD zf2hxLi8re+N!;%xmocQ5=6q@DnRUm@U;8ue5yeByILR%feqxoLg#n6(`Ye~2d(q@F zhCb3<_~e;&8>#Opp*7ev#Y4>4$UUTfV)K)}!lpjUCFUMGxr||(^tR~lu zjTDronU87QbPs9`rhOhS%-G1~9t-tZE;09B$Yl)NKjFR#G2 zN9Pxo&M#cr=}*l44RTj%KXaeN z*M9F~#X~#&iMbCzZWEoQEUW*>Dy@2^o&LmJzmr?z=juVPFHLTTDjwSDPt0{Uxna#> zgMUyw+V6E~r#~^*%jDit+sUc=(fNf-JN=2d&L!7Y+u8Tz{KBQ3{={6LlKYd|&U*cA zQ~l6Re`2mH$$g+$%z2*93tZaiPt5foxusP%#dM~k^IVs9`V(^3?XaKQZUw4vEb^32>KmW;i^!?!Y@AIA-9ld~f`m9><@6xaCu%$Hd zj0F3~R~D9{|GZtp-M;Jh1?TqncxDUN+ORJ;TkeXUEE`9-qaV}@UfHczCE^^ir@vD# zc*K_x9&)$nUGB7d>RP$>dE)cJ9OVY|`e37%CiQ)B(>xgHHvW8;b)d{zPjcY_!i{Eo zYbuY!P1I+(e-Yd(>SK2$Kag8U*{^~rAd8X+_}3uyT7!*VfD^c*t1x8ukfd{ z7kOz?pXHKUOYh!qS1!k}L9;z3pCb`dlh_xxz`5G)&>qF?-e)Fz?wqadej)7c9UV?h zVwOwpA>|X~RDP3R#f{+yg!2ej?72Cdn#8`iAN45aW;<8g&Yu43@R7oKg*y!T(@T^3 zESFr9qoAAtd%&>gBfb)@Av`K|&IoD}`{L^UIG^wCY%e^YJECTX8_o#ftbKC(QZJ^Y17eE&S`5CY7m4?28)~voEICuHkmEZ{}2rO2F05PpwQ%VwOwp z<8`kGnDH&={kbLE9G(!5)0X^XIW>uWaes~37i{9Gbbji_`w7@{_|8UZ60=-#hpO+1 zP@Pm8*gY%}zxvuMVbmn{#Wj78`U3m)T(iO&B;ZB`n|o_?0kf60=-#m2+e(r^)W}FkN^;{+j(lBP*Pm z#J;$XRQ~6RBiXP<;RY`fu9&QamnQXDF1gAD)^{8;+jru+g(u=1_d0oLQr{QX+^es3 zpW03A6}~|DxbWQBg}pSXpNLJlCBi2p8Dr@zSKeFRtbQcD*NajBw2XY>(z1 zGkUc4(xg7iB{%a%{eIQMdci5ao3cT35RXXKep%@%*=4`@ge({+(t0JL~yhRn~v9 zemdV>Y8B7F&}sZ>H~Uy*J?rgGmE6;d{q0_F=dxP|W^u#U8z3t@w!d*oGB`6qIAeDeQ2d~u6P$W zPpM@VeaI!QxKH`c&zE=YvGpx-2OeDM43*602%xwX^waGMpM;k589vse~mAm+7`+etcpe|O%x z5>BYfVhqHLncPchd)PV4&2Vn3et0i@-LHoG0__v3pYvntTjYM9riZ<^*bJvZ&@!ix zd@`$kJ{?ov`JiVmyN~K;wCacWon`u+h>#La$;JLIxyuf&w05eV+mv2ru`FNlu#J&> z^T0~0y>!}^UFPgqUC%n!xsqF2WibX~#!T)T50*M<3NLi7F6id+p0aLF4&xqL=`t(!W+e9N-ewvP6^o3RlcwSJzc^)oT+hg{De$?RsQ8V0|+ zQ+bhiX4wXaOBD^Yi@Z85xJ>E*o7_!}9$C9v#RlKhJB+l`pE%1nf7?l)*~*(Lz$Q0& z;d@r@3ArqzLp%M6(^sfqFK*ky$|xOjx9WF=y9}sf9hDC4^e0|ernEh=$z?2lw{f6@$>CjGp;{I)N+efWfD?mEr zUhTclnmshsDy+O4+UZX`Gdz=>=Eeox5F^^HI; zJN=0dwQFJ3R-4`;9daA$**dIe>^JGqPJiNKdbXzO8CxhFa?Txn>CD?s(3O>hj#iC z+h2yne5-isNr&A0tz%;%R6nNQpq>82XVPbOQmcN7ONZP?ALVjBDs<1vp?GMgKXJBp zEt~?nU)NO6VGW7LvFWs_c%?Cd?er&}SEjVvTz$|T>5#j*&^@P{#?w@4&$QE@_)+-^?(^z{o>Tph`&Oez zPO8?i!D*#KJN=0ZjPrM2&XCzkCmnLPr%LYjXxcFNhU$lQ`V+?%4Rm{_ofh0#^9^!2 zx2K){#GF5q%efQnTq6*3PDL))2oruO6*)ui1q@UFNPl8#lFKy$?OY=eb3RY*r~67p zuG0JAne=Wa?VP(3=YKptqE+fZce>_|GG6)xDGf zUYN0wTYh~lH+SJf)@H>+eU?kizL8wUaA;jEcYdKm)*#i-%j$} zA95P5uVufc`tj1oJdiPPu1GFpXeG^W*4460tNop4mSH#E=Mn8E8i*zYSI>a$#8uEoe@3}5718#7dz`aLK&`Ie9vSL?p^ ziieo7k^6i9l2PXOfJ1e^sLyhVxyB@yG4wA~GblmR{pR}tfv-PV&w63TM(+3d)&>uI zaxFIXSuQcx&g3$NlX=z#50U13s-JhYPES}Ddtt^&?h4IQMviW4msR~xpXCyBPk>y; za73D>O(s`7548Va*4M>!zla$pxgTksvP;iGPsKxhmP^dN4ssboZ)t9l<`_L+`8D^+ zt>^2uo-bm?M($e8Q>r}aD{ShsTw?CwkjofWNwbVJe^fkQYVI>Z{m*s9L(JI7Ev327 zd+MKGQTYpp>ei{Ea)IVz<)eAE=a^o~l`D$_%`#C-D)MvTG z+;bzBF^rYwuhLATcz)L0XOzaTQi_L|agv)XVqAL_GQV(ul9%NX`)?o(Qt zxfRcg+P9pn@%^Um7cpZaH^1g7-)jDILGe(Zpu6> z{eD61hx#m+n0wmfGKMYE94E~>x?iU4JX9Mhr1~LdoaCO+a}cfPp{?SfKFcNMUOl;t z;h;3{O0&7*vGi03iYQq6c6=TE-}wm$Yl((q?uWoTJyST)Hfe{a*pGL87H~-G|tr4 zc%x_2rasFh=9v+>j3J-K!zt1{ta!?5?7FQnO#883m~oO@Zfys9xArvds(z@?a*25s zMlNHB`=WzgBXn(W=~cuBb5ECc`V({ihulq5t~vdmoaef<)1R38Hsnsw{(KFc=blwOw9}uM`z_=S(|N(; zOw+ADq(eLXiMdZg?!(^uoHaVn&13e9p-F#Y?r)HLp-r@NK<6pux@f0AG500N&8G96 zvO3?6o)16d0Zz`edqMiQ4+y@}H+Q5O%U7dgJQ9QKMpP1`+a`O+U z;|$Pw+*Rq&PJd#qyUFb^A(u1g$@!p5JN=2dUM6=ytJs*0I!RcCR{)qZrY=h9ApVy>IWEjVbPbx7^ml@9In zC+2#G+|lZLnwWP=bX~O5pP1_ua$|IMxrqj+eiKQY%Apu=}*jgFS%RPmRmnL&vj|1KQZU4-xB371-0f$%M*0xz z9rFKe{rK|tW%s4|SN)$whnmE`xU~OOe{y}{XVLsSK1sREi6)+tkT>nO?C1htnEoFt zhx)?CeZj}>MtD9Eep|Utd2?*`WLMsF3FS>+Iqx4poI&;+$?6BE+4wk=T=TnX&6Q)d zt=xJ~jPNz#h#U_?sY&dMtDG!1w{pHxJh&bDyl@(m3$`Z4pPIxhmt6CEX!_kUYeCsX zl^Y886>iqQQ8+b;eQ`fl4t1&yH>_5LBEx40KT>{NaN$Ma)FfuP9^HFLR0B? z=yD1V$ra?KNqt}3Fy&J(Qy$~%g$jF)2rm@wJ%5#ln#3%ZT>TE9qu+9~GmV(!StdM4 z_`&LeUYgYR#ZAm>t`d6HKPVxe`edOs{?sI9x#Z^6@6PQtIgN8W`jJ>y?9ttOi;ogEIholDmkXyRu`h07Uh|{;gTrg8 z?=kuBKh6#erzSDWCHFVwznb674G4WVJVv;maQbU6`%#nF7k88Tn^3jklpXr{Z5B3d z+hA%Evs`i?slUmiXR1i`5WmL>xTr8SiG6V$^*0yvjQ`kUiJvQcE&)@MnB|gtSN)Co z9og)uBmEL_4q<8%`{G_w`I{9-s&l*j4318~)ci--luK?Q)y+NCi|54me)?X_M)<-HnZl?^?2D^8iM>eklTpd5txwFSZjvD+jGDwOmt0?S zq>~AG)4i29?F*Cpe?vaC=8#Wwy`KeZuKU!Vm|WWb4yGpYvuOSu|G&e1me~G|&tHx0 z@09ib1NT|#^RN0mi$Cl3ulkew&+ua9W>!%?wXJ;Wx0FvkTsh9)D#v+{@~P)35Be?T zK@-2KeCpnjC7hJT4ha^ z4!OOQPkmf@wKxDxPf0r+!8G z)GJgLV<2YC*nLSN-r_@E#G@Qm*t}bfQbE^~BUb`{mn z{n7QEF3P9gullL2`XOGtO!@Q5r@pS3$vvceYFG7KQ~A^^i!l(hjgfmo`P6Snr?K*> zb10wsw(_Y9D4&`!5Hn_SKUY5W$wCXAOUi@hJ!Rbz^IniULiyBrlux}_I=ptqK+KrE zxOl!UD4#l$-T^WB)C-YMP0ae?^OaBe)GJOj3?89;YTDTbh&w8uI$OhO!FQD>MebSc z&o|Znyv}pI?DQutt@l+5Dc?lzSKH*qD))4{a!|jJ4(;?OHhcc*^sZ!D#Y66FonLg- z8JNyNyzKNRHo1&f8c(*eONU&O%a~00aaoi{Mmzn9hv~hk7`-=jU)M$MN}cbF*7?pU z#X~#&iKpp(u-VGj`$anB`s?iL4V{7gDjnMCPrOj?xt-K|ZhCLrCbzQ5rEVQ<)zEd( zPJiNydUx-U{ytYcd53p(oTQksj8a^ zsw2IBZt^{!a);|)71KS-pzETY{=_Di(Y)tx^0LY8qPBB>@-?f7bZDnP@jH4q&9noP zw@z*!oqa9W8CW{$&`y8iLwcvIoZ7U>>nHb~o~=kdV>%!7veTcqqMogMdd4#7y2#Dc zykT%~YQ3{89op$nJbQCU@L0bcVQzCLY@9 zPdt78YNv_Xb9r4CxucX%y+Y5I>3?XaKXF^-kef~K{|r?hWS%eD=}&xI`BUfA|CqdNa)XplT}*wD-b?Ya)1P>^^1|w> z585Uja(n1qro8G$^nR3=o&Lm|l0UUvEuXRlDft*`M^c?UMR z7xjLfIe$0fJMHu*Zl`?G^?D!mTj`K{Q~A`n8tZ*O>CjGp;yucz9-nSn@EgjfCYN)2 z+UZZs`7^nkJJHTH0x{=Q%}U z&!?uHb64Wx%BOCfkWWo+cI8u_T(dTKl=7*$?qGcqv(CxoTBEx1sVnQ<#DEz zKS^V-zSH7`d5z>QQSNhYy;~lmc&N{EiTSLN%NRyUGph7ROF5fvCOy|PG`G()P&&TSohN{2P_aD44<0Q9)@~JB%NR1S_Cs(!ffg4I@};vr_7%2@#?AeT zhnTUE`+lARuC1J+8;g_M)MvTG9HYr)41UtABu&-18>RWcDa{8?Djs6SMsB!rpIa#Z z$K*RupXCyB?m;eN*ecBm(k!UwD^ByA!J6mz>G>jNY~-$0?(%sCag zUNJ~BN}9@1a$9Qt)<^TV9EyjSv5~v6&>`oJ@_zyp5A|6tG3ScpDwpkP440+(n>3Z< z?{3w+w1(!T`aYN!_KFSM+RA-yto)xnx?j|1xx}0Ulgk*w^;>qYNYmu&{nmK0WAcBr zZ{UR)C%G+@`y8SCpBajW`Ye~2b9-_b!}HQCD9t&FXP?#)KbNmyS5Q2}jFa5$`W?I+ z%KtI>P1I+(#9XtG%NUj^pZd=yIoj^b44Iv@S|8<7Jj9HR+_lPm&bXn2JwWkLpXCyB zEk-V5XrFs+Oc80mspq}^=8zb(4xOjxotUwayY9>WLDSWPjxp^Sv9VlYt})4F45L42 zAEDoEvqvhP^GCxxXSANxy4VXdHgd};_c@)eTmP^b%0dg6`8T~$N2DM3(PaUGUzuAAts`f+7*vKuYxlg#B z1@nCp>a$#8?sbsM7)IxhTz}if57LK9em;;yJ55)VUhp&G$Em87H}IHBVWrzh#>LP@m-z zbB~l<#;{C!&7WwxDI$~E=b!AydSS*!uE`z#R@b9zv8m5;iMjVnE@Nmc&EKS{I*-qx z&ae5Q_I155<0SWz?(zNHstY~(gjKXFUHDQ@!d zsn2qWc?Ll)V=!}{m(&O88)B}R`}nI5GT*ZzW}M`d#5`LemoZ$F z=0j<=P&}R0H~+5n={m(j%-G1is(DHejbVO@hx#m+m}f@hGKTZgyedue{U1M#UH)3X zKTyOTE+9ohJ~d+?=H4B-wUtjjXm7*dv&yHYo%?CT+>avn znD%=^wBLJ9dx*5tpP2hdUfja>oNPMJ{a!k>)1R38KefTlIpvy@Li^z+@0fP_6La5& z+#cGW&#(NrD~gA9`V(`%h1?-JFG%y`yuhWM{>0oTA-9yyFBe~QLgx*outoubf{fW6=Cih&M*qAV# zSL!?MF75Ou<~o<$P<@ZOy3SAazJyCV{fW6gCAVeIa{&qGxi0PWC+516+m}3X2wC<=}*jgCb_Su?-`|h>QL#>PJd#~>&WH1ZM4&$m~%yPId`I+^EYD7smT4G zeCq%1d}_UWY$x6$y~F$uF@1bta((&yRr|AO{#Bo6@qd;$|5Z9H>+fj(RqkK)XPo~I zyji)%rIm}c?!&wO$`x{7RgO~7)>a;s?S@BY3V8KaSud>Xao5De1;)-j?@z9NN78+$ z9IHWl{XOl4^}DuKw^awdG^y{4TSU3Nx0E|pr(q@k^1?p~r%JcfpPIxhm)wW?&c6A* z(fPlRt(;Nsi5wU1P;{o3CiQ)BZz`|0sPfr@#>Q2SOZc7Q_HPagqb4!SC3j0gK5W6U z_rgvKzpb3KTVw8pQIpsgS2^O2`HjpYT?4|qCHyY%h4N#)G^x*W$$f3(XW^!O*$d8v z-JX&r(BP)R)Fk%Becj}=DW2tP@`uk;I|>)Ry>d=CHHld+x#st}Uss)kzqBzt)U+ev zje941X;R-8SM_G=UfPZ4eiD8}*k3sFvG=_+sn2rBP5cenqd$!c&#K@0`a$jIcJCQp zn$-8j^{D*AiethD)51##UlHC^c(9iy^;s^tZ>l~Xt6sh+&>_6O@DSD4ohfO(G^y{4 zo0uDTdGpP%J-SyW|29MT1TRhMvs`jbd#P0_wP*h9?(ywtW$T=gGlZ#0?2BuD*Sdq+ zal=DZ!cDGXO||c4!K1^BexhbloLDZo=J%HC>UX;rkL$Lvv2ah}6@l}^s7dULYwAt+ z)%|Y%i($ouuL*bV`Arx#iCHeW3BNn+R+!N}EQQ*Sz7^n}xHonqHHm$3L)BhdsUI92 z5#axwaDedU9qByOBxbqfDlgvTP`hio`+Fi2@UAPFJk%ui#ciqfV!jzMu~2o-hY2{K zOl>bs>a$#O?^K->Kd$^%t(Rxw^x*j4-n~D!o0lf_eQ}jb?kHE?E%WDiPk-SZW;_$7 zCNaw;x2@VsQ`OJqKR@wQ6>cN^t1vZ*eQ{Ij+Y7mLk5bfF;#5^yc#nvmC5FH1|16sSP9Mfk{46p2RsUzv z{Hs3C5(9mReU+8eCwAgB=exdjoc(%d>&*s_oVqPyW3CH-^1jDCADh{UPUrE$C!Qi2+jXs17Muei+4EZu`J>5v;`y%<$p=k`tXJ{;}zCtlQcbinC{LGBpokbAd9 zZ15Vzb5!xrPJiOyxXji@#WPnrSv{N$gP%Py5-I| z;Qr{MB8SVH!O|h#1%^9vDd3ToBKs>^@-Q4Fts7`Owmq%;xC^oW6xI`Ix8J=?=*O1eX2IJTRODU zpLpK;9=n;^&<5#{`=Z{H7?j!*)mZgIJN=3KJPfi|-C7oTS32a5S3HAT#s;5JJhaoF zSZ&$SvDH&=%>C`={<#-Hg+%pQJ-O{fR5-er-`3 zGVzc*u2r=4nf?w-hj#iCf1&oHe#AD<7r7}EOK-*Woa&i&`V$8XMM8n*B`nr+UZZ6U*knZ-LDzaA-Ar^uF7gZ_oYKS{fW1z z?^&Yu(@Q$!{;IL-4YeWje9=yS;-cyc)2R(Dl@7Vh)Hm1B^L0}?w9}tBN9HoFX$O;} zL$063isEWRDOAt2)1P>o#){H<-i;2qaT>dRUQ^!lK=IH{f8wPYyUKNXG0>F`xty!e zPJd#~XUGj7+1A~l_or>;R9DwoT8*)X0`~}$OU&5Foha_c9t#3%>33B7Ni(H1w+fqb z59nF?GM&c@pVD=`_v^aAak7*9=kZ%Oz%8B9}27lxAyb`Y9fd+O0?JR{et)W^CjJ>bD*5 z=PF=73QcZPpXCzs86lT3?9Nrd-7d}jil?`pNB!AxiienSl3Sqe9Vcc|6}ye`!a||MvF_g(RHb8xcy-)Eh4;&V0<~^D( zd11y$?$w&*tn{iMSM@`EmP^dBm0ZS9UGLJqq59dOc($kyUZVP0qL*U>S;(z;sLyhVITs?A zG2EuH-U?AEjAa^{zU1TWF5cNd0q9#Y4>4 z$X&1dd{6f~M)6Re!Pi<$7+R#wNL(JI7?X2gZu$~7!3pVvx zE-}{{bibklfu&K{-iMfU%moe0k=Fyt7 z!gnj4{px!zty~c~Pw@~lHgdb@T5hR7RbOi6KTl(0xx`!>lFJx|OEbJ?IY({M{Xq5e zyyosdDIQ|RMs8Q#>lZYJ`7KXwQ=jD$bInUGW4J8M-O?l5YiMaSj4p+~Jo33?^fJIu{nEsHMaguvmeb0NkmL;km>a$#8?roCG z7}`p+hcx#po&e1cKUe*%Qar?rjod)>6QgynHP^MN&vJ>mXG<<)NG8ph()>m7e4xH( zx7yEX#Y4>4$Tf5LReBcQQ#{mXxy0OyCYLd^ljeMB_E9|L)%TcvRPB3vVa7)859)jN z>TiSMp+3tc<{mq_jNzd4qV;Fy&nwjTypz!X5Hn74r|3E^tACDAJk)2o#5_A7moc=L z=Eu@3rT!;{sT-}kPN{x~85_AHb)VO3y;Mm3Gxb?6G0#NEWele8NvAfnQ1x?FZKsdg zkl9ZlW^Ck|=b(X}hd9*_^;s@4_escQ3_GORQJU)W-55PvY4nVRC>~m_d+gX;Qk5sRfriIxnF5Ns=?)ff!dF9OK6X)g!b6A$K`b`zB?er(+J^;Bjb)S#w3`6H} zF75Ou=K7u77bcc7=W({q<6PS5Pt0{UxtG;;)+!#I$GNoApP1`qawqkxW4$`*nl)cK zw9}uM>s)essqH*B>xgwkI<(WDnCnw=M`k&Qh90y%MGK6qk1T6LZ}} z?rz2Nvd&aWDjwSDPt5fWxm8p@MfHrC{*ZS16LXzH?pEEeFZ9go{KBQ3{={5gkb6OW zPgD1`x{C@|}uQ0^UH=$C*ciY~!^sbV9r2OCr^A4llXR^)j)g{GQn|^3dTQVS` zQ0A8{a{tkLk9;SJ??L@DY&hn6q!%iEcjw3b0u-C0a@}w4mI(06{IVCOKXK=on>_D! zb*wg_z3ooIy@gu~C)!&j!Ceyk>0`JPs~7eRx>Uyf`2*W+S!MK7Jo2545ypN_cH)rD zeoyV>vaVQ%2G8%9H6p+2lXz{);daS1d&Ap(@+g?xzjLq2Wqq=qRj&K}h1s6&pFD~o z&aC=xpD(|sRFe8PZN${O+Tnt~gL%EI2h%3snzb+7v@c?n`P5D>ukr6-UN7sxTJrWPr6=mc`c0dMP1(j z{l)1Ti3g|-*6HuNB=wMLM?3r6&X=t-dmdPurnI+{r0diS2yuxms6w|qS;{}x$o z;`YBau-_>4mR0rVtTwrflkuDUnv1HZ)4Gquk6|0VB2PifsOe*Bty>Jv|mUo0~Qx$71+Ec0H~6DFU>T|TN<0C8fU(6?{z0CJ6Q z$&1+{`u4pN&-*{c^?tET|6|u1zWR#>!lsW1UljL+u^U|b#yBtha)STHMGfQaiCpu) z$&J{633Hd4>$4}0NE_HMPnA^$9~d(qlxlwQBiG1vF<8$NQ zX;eL`%C1F0#%JD+F%h3!xgYOOZ0abne|x{|p2*mdjRQ^WiP&&A6^M*l+wR+V%>&6t zMJ!(3(Mu<(KYfT3%QBk(J8U$wmOtUC9o^)~wWHibE`5lT>c2cFYv98YE8^oP-r6)g z@WnQ3s#t%JhBfkqsszd)oAETdmT}l1vL!211;Z}RNJ0i0BocMT%)3Un5o{z6*Upn+*JoKjz@u3V`qnc*U9BHoQ z)Q!r4nVcH&*G|kh_s2#BTt1aL-iJE$rw?%r)nQ2bDe?ETyXtvw^*Qn760@w$wLc2~ zBx8~IYo`wV>BD&FPaoC~{ppj~ev;l_`tUiWKYjST)1N-PUiv5c6h7F^zuB(3)*+Ky zdGLJYb_uv}?YApGPP03{4H7qf@8=aAt{;x?3s4#>(Y|+X+*X z*cZ3y_sRTkD{s)`#1d1JnB~&{?(fC@lWV*?r*V&%KE5#hYaDpVznWtCN->STvWA%UI~$F6MW#^&7a#iG?OH z%O!W^&prH2`^&U!P+0%vjpN6jtbx}9s7dULdvkXy&sN27S9x(Kt3{gM0=G{JQQt7XJKj*vs`k& zT)QJ6agH@qZE2_4k>;UZn$-8jt*rKZUF}6V`EDZi6Q(9H%T4q*+?VuB6;j*js9Z*a zizeViAEWt?a8ho{TLG1u=o$Y;xs17mn?HHpy)>!Ma>?D8CA369#8)Qo*?q0{+Z#WA zyfz+Flh_xx(!p+Fop#lA)c?3yL+giiOu*D6X1V0fyni4}eU76($DPu#dYJkmr-Lvx ziG6WP9~mEJzGYy(ui*cEvalP%rVgn|%yP*+^Lz0y^*`=;&E3CF!0L;68qwADK;Zq^C$Pg`0Ifyf9Vn5c3Slv9Y{@LmP_uzbt5A-Du(a%Er+1J zE5bJk*AS*Au`llWQ`I9ntA5hzxw@?S(Qm=K+m&}tO=6ZyZdctS<;lCs!?)Fk$7A#S zQST4C<^AOBcyfmTji);F?v@3>3RJ~f$ z%)OuP0UG?(#bFU0-|{na$fww}S?yKE?-M5V*Ier#+Dq*(5OE@=l$lFC)k(^w53w&z zU-q`=zpPa9>{sz+`O={e@r8?7s%$xOKFVBU+FmJwo^M~+3nz{F<@Ff@@}6iGUsj?H zxyGM9j3?1QsSo`VuaR|5%y^R86Lo0!g{kvbF*W}g_aDXc&-@dw{lC#C*H;5P)tXj} ze=dB*`B!}s>nG{;Qitt_{`BE9OMm+Cd8a>p-paf-@c1hM(Iy`HC;FIt+KtLd+plxf zDKQ=GsU2fusyBaRZA z@e9%!(IU?2R5FiEZVJ8A`&+wcCq?^ci+1`G?@Qy+H<|RiC|#4=S=L3y`zLaDNvEyiY1k?@ zhMM#z-XtBh1$V#N1iAViu^pvvE=TvP<7KBm@mA@?Drc|bb5k60yQ%Gk&OhQz%{tx7 zPJiOD(y3iCkNdIS2PF4|bb{MQJ8$cccKQ?FQ~UW!?PrGm$StWhd_wK{@+U_e+UZXm zpm;t|dv2we$lW8IX{wvmI!C3Q{=}xP@~du6sE){;uj_hO-vX}J{Eq0R zo{_8XKHITxz86(5RJj|_G~7gg;tZ;vYD2A{S04qruk_2Q zEss<@Jd4uYQ+~Lx>rFSL@>VDBqf8wgr8Py`rYO4E1 z?h9(qpR|j%=Bp2)o&LnPR6nlzo|S4psWJ9op$nd`CJ{)E9168zQ&0 zbh?LJvuX^i<7KBmaa~UpP~{=^HVvq*h^<*zb3Eg+pXYCm~3e$h^U z;z!a6SNjRoAGvR-J$K49-KwbZly>?PH_&x;RxGb5CUQ+*F--5+ZPfTqJN=1QN+*x% z=Bmbbau?`%|FBJLa2?GJXs18%Zs{b`z4}1+j9h)k+>Tk?IA~6&^2VS^f8sw@m+E~hX|9y!8O3u<{imb*OUyXQEu?s&^;`!v#%zXF(}v9 z{YsiArMXJ+%+Rw{RDBIGVi2=FIMK zjdynz7V^T3jokf;=dP|LwSH5P`Ye~2V=K9gp_A%ou{5VB=V6cH`B3$9OmjhE#!2o` z#ZyA}dW`ZnsLyhVIcFf3F_c$4e<-K%MQQd>JX#;w?`nQR%-G2NLC@DbJzr7E0ir(3 zB{pq4aUMl3WB6FlS3%`8c2&+yRpo&!RZe3Hts{sT8@b(7KONOqG*|v1^;s@4=Xm5Y zh6-vwMsuVz{Zv1ryDIli^GRaHMs9J{&qMX4YbRH6sn2qWId>(OG2~YN94pPe(tJ(v z)KULjRr6$G#ztp8+|~HCPxF6b#zyYX z8s7(LEIvD;txJ8DOT1U}mc(@mxs2h0+Rs?^J)5PuQ}JBa_&(IEYk(OWxu-r)ZlA50 ztV+S{9bM|PTw<=F$Yl&>{!n;g^62E!{L{=UQr3#nyuu4JHgb2XeioU0D_slqSuXJ= z)lcF&kzB@*Rr8-W>~hXNX>L`WnD?irs(y$WC%NhMd<|DW@rCX+^;vFGoVZ>lmoe;D z`?(>_Ez&%ucus2nYOmT4F=HdQf!gz8{oe3;Jqy$~F(j5t%(XnZjG?9C`9YdKs-XS7<{H0<85_CP6wemrANJ5QMtzn`Y}!)dJ{!4= zLEnCI&9|1!_h4MbGeXZ+TCLNG85_A5)P5Z0G`{_IbRhLvF7X(}lem9KE@Svj_v=e( zK6fM}aDw9bLHmu6&n{^e(|0t6 zDV`mwpCXzc5;IP6lPR7;>LpU$vhG>L<*6 zh59U)n0xHxGKL&#KkcPCTbj94KV#MRM08E=g&7;UW({~neQAW|h}37f#4o7*B%V8v z%NVXGKWU#d&F>b!s(2cz@2Rgf7%}4{ce&z8q2HuGpgA=4SuXJ}iYM_rg8LN0wsPFkoYcOKQMs9%>$?XvuiyiGnP@m-zbDxA<#&BQlXP5e()zZ{ngqucv z&k(IKh#4EX8tb3#u~47o5_9i`T*hGL4~cs(+*cuHY~-5X)mt6bGb&*}%3Y;BcC*Jt ze`0Eq`*BQ1w@$~{;IiV>`_HSj|4cjmiC3weC+;(l`-OBeYRs5Ad3zY`^e5I>_H=)MT%D=8 zuPL64+MlPL{={4_liNx<4YVJAPUi)*)1SD9;z?YOll!T3hH5{2pMIZ{cKQ=@eM)Wz z>FjMAZ4JpY)9h z+UZZs`53wS&bu3-=WDpWkxe`Oi8+rVS7&EW=PI<*pO|wPa`oP;y+-f7M&)?uSMiVc z?W|2|J7by@ac&+NYHtoa8!@D@H`aSZ_PUXMBg&o197b-@d%<>|lDVA{T}!#&KA*v! z8F?aR**C3RYfmQoQs|n9RY~x#8*17E#vO_%Ab)a8X7smyS@~Sd{Tm;;Rf^5Dau$0# zX5Y?%ZtqmHt>vfsMQlleyH5zTKCJkA_+9yv8#ScAefRQ9&Zpm%AG!O_*;w?FUqen9gJV;yoErdVlJTstnNvfa;a+9J{#Q+s;MYhS)= z-}-5jRpPNYD;d(~&o}^v0#!>TrtQS7De~6vxZ2f?To=z6I^82Ux zr$#T)#}_uw+&0CqPBC0R7w#W(b%4DoXDuhig8t6A$ia40@7Ds#F7n1k>+>7EBccmd z*hp^Cb_cA?6+&a0cIoMETDRS5k#BxXh05=^M~CdTa=mdTyhak-r`xwy`y0PRJbtsM zOYWlK1MI}eJZR;5}f;&OV*onH%5$;Ke?%o zwswzSf5F=NVJi3jjDGI;z?ZCmkjc)B#_zdzUtJQBGYQW7TnG1HnyV4-4Nc{eyKDAg zYuDCQF^Bs1a5IhEW-Ti-FJ?f$cieHccUfUK->aMyXNWs)Wto*J{Gj~Fr9X9kjGbkr z+Vf6K+ED{t;{1_wtmr{S!;PI>+UcL7T4yWP-xKrW2SZ%qSxdTEF%1TWpOT$i+UcKS zLT-xbx4c}62)b?r{&3muPhp?3o;Vf^P zAz<&^p7!Li+nsDpi#Qzbh&is2JLjgqz0#WHB-5CcF-ruAz88J>)jcXk5 zh&is2d!^QA)))CxI%do&d|;JzZp3p=JB@1`?}$0Bk=y2eSG&Z97$?0o(z;cqr@gE6 zcBjdvvR>mI$3Bj0H7DR*B_B?F^U3Ihi%Cal9kuxJK@JyRIFWb(wQg zV^;s5nsz|e&z;>G*Err0b6g{L?BGAGK@XcbX3Uy-;ieT{t-fQ%HI8@09M{P8j4NYz z=rhIXsxj+o>EibA7d~?4Yh2@aN6c}J+-t`otHp^5 zZuY_Uj#K2b{tm}GVvcL%*6X~(`ZR4(Cxgbg_xnXz+5K`mbu_MVyd&ngMsAkZyV=W9 zI?nb3L!94gcelfKI?l0GJ-x;|j(r^0$nBEqnDxd!k8?s})~mhhZvD!$EPjmRct^}} zjoibX8n`D`tgyb<7EYuix;B0w2y3<8xq1JI6?}$0Bk=vorIcw}YbDa|!<95zJZWVfdhO=B_ z9LGCij%(z;IbG*uXW|^QF1va-n|;0dE@!jGIF5J39M{Ml|HV=(S5$jvu*SHR1CCf{ z?o4xPYK-G}N6c}J+#DO5*aP=uaIB!zW3vJN6c}J+`lufk((I9nO}Yl zcjFq{waRC3KhQdk;~g=_HFBq1TW1~F)6*%fF>Zb3Q0qaj4o*{zaUAc6Ij)g=@twx@ z!7J(ATpHs(2yS9m9FoDkqIDd{J7SJ&a(};*&eos%v&Oi+Irmz7a_)^E<2c?C zb6g|$WXELIk&elndm7^=X|D2isg_Qh#yF05#2nYi{rpe`d-0(P?$27s{an1FeY|)@ z_alvQ9PfxZu95pr&Hk4DoJtzw#(X*2`smBiPFsy}9PfxZu93Uju4o^yE4n*1#%&qs zZ-)=`cWY~m<9J8RagAJOR%(04tkiCKjd2u!r9g)X9 zpfPUrne6t&GuhpF8sj+L5p!H4ckSct)|$uLozoiQ)?M6e&AqtU3DFqG@s60|8o65? zz0>aKcYHO*)!KgFdU5-GXOtP^INkwsTqF0}3X`p`D@=AqX^bmYJ=!W*J=&?NF^=OM zF~>D>7kysI{`B)oZfpNemTBj=5}uL7@xqLE#2nYid{&?5A*0b*GKC;%C{kiV){oav1mV2i5 zSng*WHTgv^zjOR&v8_B#Tq|EiF^-!2qL<$}o{UpIwe|PlZmK-F@Qp#~>_%0Zx^HM5 zN8VABYxEwe7;kk*SHR7ty~;^FzOj1cyy0gYc}GpI(c2(qzo*rm0LScA9$H`2YCkB# z*(Ao1chuw>y%#>v|8`Gl;O5sluHn4YcK5pt++kuIc}GpI(fg!@Wqr|WvVR@-$)^ph zL!0L~VPYJ4M@_ELTV+FPyJD7x?p-miZiRIAnD{1caxsp)qbAqr9eM4zRWNH_x0o1r zr29@wJaf$%9C=4guF>0dae}qHiE10fxH}!LS-#7q{EQ>-sL3^YyY`%I<ifV==CBmEG3c@mbvAVjOu#O|H@VT}*4M)XMLi zDPr7}2UDz={_&1EgCp;#$u)Wh$EC3|Z)oIZ);jKz{zlXf&GqST7lU z8oj6WZwS`E!ToAVbh%P#>`ez7x;@1>@{an|zs)d_-urRgt)&TTokC*Vp&o6l;pLV% zZNxb8j+$Jf_ZR*D&BLAz-PMO8oKg{K>|UNm?pI7oLx+eBk!omHF~v%v%-Im@iXpdw$|3% za^E@OTE~%7)Z`ky9K(4AeHCc=Y7g-WkyrU-9==EANtl{^9-0Wgp_Mt7UOc|583$<5C-cgfl z^me%u={df!m}B-TZ!Ny+NjWFdal|0I=2WZl_|mTbJnqIA>+NL)-1K4`c}GpI(Hod)skO?k?OxaaRvpZ=$f{eh znma=4IP#8~T%-4+r%kNUgPu9}w2nJgxsJ8$*L%)vF^;^WCfDfg+WSkZ=$PVeFEK8> z#5n6pU?F#@7)RbwlWX+$Sr%ZOJ`>}7A;xWJTFYA9CBX?3rCqCWTvxZe z7?)jtBOj`F-#-0~kayJN8ojSL#rq`x+p{_2&6W6XNZ#sr)V0=*)oE`Rcgy^K4tYmS zuF)Hls(>~8qn(bqL(-yfcI$B8jZUx_N8VABYxFKp?pV3ob#b2_j&Nq~a;!sPUEMUg zXF}dllWX)Q+aGMbmGX?UQj9BJap|@yy=#Y>J168FHMvIb(dEmX_zrdLAH}$nqhp;D zlRNntN8VABYxE|B7qhhg=p5HxWyMMX)`9n9{EQ=~sL3^YIfnC8t$fXMB=Aee+%2Id zzv$(6j<2y}ooAEwxD4Z{$uD~Oo#Uqz8R6Aff$j<2r6ljD$u)X6^vG(pf3LEeTI;wq6W+9L z&MoPdFz0dL9W}W|Z;ASWR^*sw?rt$|a&RH*N!|wT5HXItqbAqrU6JFIXG7#0?lm#) zV2Q(?^0$+?(PA8VM@_ELd#6lBtMS8NH%yG{c`UUxw|psgg&0TPQIl)*zB_l0XGr=T z&R{XFRQUs*-i6gWPK+b(sL3^Y&)=+W1wRXSTZnP$w`;lj8_B4@5%P|jT%-3Db5@Oq|-XCOs=_}rfYXNHN`mc zj+$JfcYbU&D{feScdYg*`;Mq?9SRS3`)M6V-cgfl^geI6$$uD~Oo#Pkn?-iOWaHemu7)MQh(aY}~ zPsW8reBkeyJ8f3Xyns3vyw~D~xC^vbN#0SDYxLe+Kh+zsp_+R`jO)>+~s7he+JWv*hMPAj+<+uY=8<>Qdl-r1PGP*yDtXapWB}xkj)1MHBD+8iU+)M<_tSTyxBhy=e;zmJTHWa47h3umN8VABYxI71;A(XH^lj{vss*U9a#8Tqh6C)P zX0H;wqbAqrjcL*$I@!Uq{=G`?hE(1WVY~f|Bd4gzHF`OQ^E`RhH9AMkEI;F@$uD~O zo#O}Jy|ZEB;x7L4IBN2XUVi8J1%*>bzu^n?uj8o6FM9c%D*{N;SuKP>iD{zv$(6jwj<5tLDbM6HzN}?{^OyhB-yFj+>`-9C=60zZZI| zs5Y+ZpC0#x7`H;TaeK9nTP?y`GineSNi#Gv{#!R2w%@>o`+8K;BW4YxHhX zZQN3=)?Knz)WztJ=8cTF12&)D zGE007wT?5j19?>&S6%BkQ#(N3QIl)*E>vyYUajMLY8}^FwQ>;aRjuRhX&u*2wQ*0ijx+Zv$vbLtjo#C$ zjoYksoT(jHtJ=6XwT?6AapV*=xkfL?aGs}odiu^KuH&f5FM9c%;}5GgE@|bD{EVX} zzv$(6j<-}BmppMDM@@dw%kLcjlWOC1r{B*wYVwO-e&_fvF7=8%lVYatz8FVMe$mVC z98bn+zr`_U4V@BdESag=xZOIB%Pz)|chuw>y)#rBH$vxexpf|wOto>jbRIWbj3e); z$u)XYsWxt?&f}hnaUU$c>f1j%(lIsQfN40T5I*$tyy=nIcJMZW`Zm}45vE0%sL%O{@k0bA> z$u)Yfs5b7j&f^Y=aTiq^_k+&k3W; W}W|uc?juMCWm)cA%1K+U zt1Z)aV2%H((F}sR&Cr- z-K(rA#*uf_|pe+&S5<+PHJN zS84j3kayJN8of(Y8+TauDpzP7ms_=Q3BQzbFRBKdyrU-9=fMzwKGbgy!})^T~O>~^x~UgZ=qj=ZBL*XTVE)7q)0dzEG#cR;mq z({-=1t{6w&QIl)*4pMDg4&AGCw2nKU_&4&R^5iAt9W}W|@4sT!|Mt7?db#HQ^O3I> zM~A33E?W00`|DmMc}GpI(VKa1cW0aKRp!w;?y_p*=ICB!3o(woqbAqr{YkZPw{)+v zofuaxB8}Tm_bS7*jwA1=$u)ZOs5UOF@h)ek7+3UCLY0amUf!!D@2JT&dJlKGZ!Ofl z%GBDcG_`T}bg#0w7)RbwlWX)AP;H#*0sM?Rt=hPGx>so!_Zp|bK5~s-j^{j|t2S;+ z;=M|0@{3-6=Xg^aS1IvcB{lg)FTZpA@noE-jeDqH#*{Hj#;7)KqJHPZIP#8~T%-4Q)yCb^ z@2(hkP_=PC=(kLaBk!omHF|fcHg2bWrk7Wh!1tYs`kC4R@{XEZqj#2Ss1@))o-{Mry2prPOOh3@2JT&dUuwd=S=v)!zttM@_EL`@dz`zZ!p6|Myi7 z;O;K7A-b2Tjngk!eNM(8}sy5E2pIOI|chuw>y{ZLp&F{1r_pWN= zs_HjQj3e);$u)ZSsW$F_e$&Oc^^0&@noFIhUV{~_D?64)Y2Nx^f|d9#*uf_4O4-u*taj;o|K+sJ&_!zC>QfV#sz8FW|QIl)*R?!+ROl!H#TF0r@+ci9k6644_YI2R< zx3q@qrnOupG47_;a2K?e%Ob{+chuw>z1y^g8>6+HsR7@u+PLRh%S{yH$UACsjowOH z!wt|{?l&>+{@k-pRjuWwi*e)~HMvG_FRkG|&|1!%$7R(Tu9((xleCT_@2JT&daG#- zw_V(tAjX;6xL>rEGkcZf9W}W|Zx*fLBD9vvqPy|0+{@6Os@ zjrmvmmc|>Te}m~qbozXY=;d0&mDF19YwcB%chuw>y^pkp>#4PzxmS5aYq-Ka+c@uu zapWB}xkm4ATEi(HxtGPb&$NaM(poNy7)RbwlWX)Q(HidFh*8e>V%*Ik!J%)TOYryd zBJZflHF{TT4R=jzxtn5~S;MJLz+XE+-cgfl^!C;oE{oQ3KWMLVj@EDow3bV(kNXFw z$SiV=UXI~Bv0B4@rnQ`@9iS$^=;e2ge^+a`!dlCj8gOdzi(Y=`_+(ncJ(vy z{GylN=^dsuobL4d8AnZi(aY}~-!A1a-vDoM-#{^rn*5@d-#MO)GiPyT|FP%jn@jfT zEKYR-&U7)3yrU-9=>1Y>aa(jI_omL{QtB)&iO%FqPiFFtnp~szsLtX#=}gYl$KBOg z+)kaz?GWS0J8E)`-kds%`(0;p&vYJ_ptHCDoynyaZCpO} ztIQk zP&8l_A1FcYI2R^7`IesabY@>GxsXVJ8E)`-T?az3Mq>|EM#$Q(~Msi@TsR zxj?Ps$UACsjouzQi!=L=<~(k{&f;wCOPak(a*CQE%UDe$mVC z9KT*?aSe1PXBbCKe$mVC93QXRxM_*~DyhjYdikB>H|Q+xgwEv5I*ywBqL<$}K1q&A zzIMLrv5{gNHTgv^zjHhpXYPv~)Saz8Z#`X7T6Zen(Ypg9#5nSfnp~r|?4KUDw(eGD z7UK@;PUQ*Rtz0g~k$2SO8ol*&r?QytR+_!acDhs9Lw73;I@TW>x2g z7*|$zD);GbWo|K!yrU-9=&h|gl>v$G4vf;B%JsTiY2F$j@2JT&davqEg@2JT&dM(|lyr{dC6SP-p z?lW%H-$iFgXyOri%C3#0puF<<+cPe9ax3ZZSXKLg6>uzPZ)^X$=HMvG_Ro$uFp}Upl zUgghQnuSJv7U=I+N#0SDYxF+Woyt|ZTX|fJd!{>;wRN|$h!{uSQIl)*n%X#5cPmW| zxOyWya}wVjAg8FwHF`OQ^PJb6$}75CY1VPn(WQI*z=fCfDeFvA&u+*SjwyxfoYZwQ-#%t_xXg_A0?UYI2R< zcU2qrmXkHuFs{04;}XVX4A~{dk$2SO8ok?98&`11jo=j8tJHfsZm-#Hh}POk^OgWl0P?%~DF&ZbXtg_w05c}GpI(feGrapkTa4p}b7-BWE``t@IX|I%J1 zc}GpI(K|%7amO#__nLc^i&Pue;ExQ^rk59aM@_EL+e@`^I~FVri4o%t6=>p?Tfe+~ zobH^Echuw>y#rMncj}GB8%zy&^3RgH1BW)$v@@jXR(GN^~JHj=ZBL*XT91ahZC0qaSM>r?r;* z$p>S-=5K_&qbAqr{byYJPxdX%zo9_0u_43CC-uI$agh6Ahv<+?TE~%h)Z`kyX;m9{ zwPd5<>|&g$jjMj{&tUVO4tYmSuF-31k+ukkn!vc}GpI(Yr;p zaSs=D4mSNN@2WPgPUWFNrq2m^M@_EL+gG)54ad!i{#A@KwQ<(KHC|IYK;BW4YxJ7h zxR#3oLd-hu3)RLYO_MRitmDWjYI2QUj^R9}Hf~U@oFRsB)Z`bv{Lb-HR2z4GO_~t1 zj-w{O=;e2gPp;ay2QO|1o4rbE@{3-6=lDp~#@*{58)Rz0smU*T`JLmV*3b5xKaeeW zo)||>e$mVC98boXzlH7Up`iEUmb{~NoT>L-D8`X@)Z`kyL4SJOchu`7lNfhET$`s} zC+0kkyrU-9=xwZZT!?y|n7zsnt>X%**GZfhN8VABYxL@^9QX0fs@6AJ$LS3nH(tF? z65o&e2k*!}a*f`GTF2#AuM=|~H%aTbX!SZVj3e);$u)W}YaKUHy-wzeae70?9id() zcf~mJj+$Jfw}#enAFJ0%X)*4OYU7ru*GZrlN8VABYxGXnI_`13Kx>m2r#E!m-0F2= z>f^{eYI2R<-CD<)y6&IFxR14tOIPx+XNDL@-ci5CHFyha9k)TfP6mo`%e9W{rCujy zuadl@CfDd~qjg+%^*S+c>nzneZjySPR1xFIJ8E)`-XN{xZmZWxTQSb}a<9Yk>TiU+ zqbAqreZ{zc#WjAX*4+Pii^qI7e`}ldcY0FmxY=6AO;@jz2(9DDJ8E)`-sW1zRZ*`K z)04TL)^P>Y>m*E!Bk!omHG21G9k*V+PQta0GqrKu)axWvj3e);$u)YbYaMq+y-v(J z?$6E5LN|s7ZZkcZ$vbLtjot@Z$L&(Dlapecsg3Kd+V6M7IP#8~T%&iV)^Qiq>%=fF zqtUClmM@~_bYxHsq=P^A_9;w%fVH`F2MK8Z|{1dI?&a2mn>E%UDe$mVC9RFPF zxYp`*Vi-qFe$mVC9DiBsxNYinV)iPj$uD~Oo#T6G9T!`tSEyOXQIlWv@;k?qafy2x zRz00HnA*6n)w9yPA4lF%lWX+O)p^`D^{jlNJ16ON9+yTvE58-v$UACsjoxgVia9B6 zM|#XUE|q#!wo%VYQ#(N3QIl)*=F@rHIrXgkQ;gFaI&M1ktW2$S9C=4guF<<*=W!#| zv$BF1S5N10snoNwkr+qbQIl)*cF=iTdG)MZC&oR}dE7zutTes6$UACsjoxxPkE^eq zmF2{^^g54ArXF5J#5nSfnp~szkj~?3sAuImF|KQcYHk_ztURN29C=4guF<`;ByrU-9=xwI+IK3Zd_LA-YzRD;dVwPdtA)Uw7RL@GoIC6@bT%(s`IFIR78K$0< zhH=#77rp$>@uoH|Og$?NO>Nv)>RD+RM@@dw%kLZ?rSmwwALlWQqb9%T z<#&!xsq?tDzU!eA#W-s6i(Y=`crq^W4vDR|LYBOzdzGgD@<6TQ$UACsjou!*S9wEk z5175m{<>HBmEImOwFBfGHMvIb^hW_sDrdiEhB=QL7~vGr+XF|%IP#8~T%&jVlm_lS zy*&^m#tqWF%658t;1~7sBJZflHF_KAUgg>rmQ`MiTcLZE6+dlYH4x*-J8E)`-Ws}B zSyOKhOcdj$=w4-2y*==~7)RbwlWX*vHwQk}+XH4DcTx8$9lbqZ`kat=)Z`ky`*g3e zzuq1&{VFf%US+)A9vG-~9C=4guF?BWzAH{2y*==|82427Dpi1JnR}Jw9W}W|uinaW zJ$ic}LX1nVdzCr$_P|Urj=ZBL*XV7bdzC-Lw6;v`z#84F{7G*QnD^tzJ8E)`UcHs$ z>isx7wHTLpf5XnDzY%i=_lkGaf zQ1>d|7&*!^HQ*P91&7Z6Il<33@{XEZqj#O|RbK3J-?<^i-O;^D)d{$z#W?bgnp~sT z)W#Lg)88`hdN0(yO5Nl4Gmf01CfDfY7|vsA<3{Q20mC?I@{3-6=lIIHSE)Pwe#TLg zU-a@j$D7(X(<|99j+*?Um)|*lsP0vc)7t~)JdT?DqL<$}zLxG)e&sFhG50E|$uD~O zo#V+kQ*)zw09$W`ESaF%xG(gETn4S<$UACsjo#l>8+TQ2$UWCOE?%{9Kk5xR^A0$9 zM@_ELd%t56=WfR&*4JWOS7nvNwqW2NnEI*+@o+PEuvL(bHI zlXukQ8ohl~8~2gkkTZLgt5qAPpJm=1An&NjHG1_{j=NiL$UPL}wx~8vKl`#6N8VAB zYxHhYZQNG9Ay-k1`>W3*=V_luR)82s-cgfl^e$0t+;Y7kw?m8@r`ou$^@iLyF^;^W zCfDeluG+Y-^oE>a+|p}X9K9cBO%vnDJ8E)`UPrZYdOyxK@5hx>ZCok6A!lj_$UACs zjow|QCpvL@L(VYnN##vW@^?2`wZu5`j+$JfcZO=?=I9N%5@MXWhp##T`?&r_$UACs zjo$w&#=ZJmTfDV`ca&=5^s{e@apWB}xkm34)y7TJ8*+wm%T*hjj4qbAqr zy`kE;>v}`3uNYTdwQ<$-7g9uwGj}Op@s65Yqj$Axf5xe#Vhg)Z`ky z9K(4MR2%nHZ^#+OQIlWv@;k@3Q*GSGdPB~f$5E4C^zu8$A5v}HQN1B&7)MQh(aY}~ zKS{N5=FJsvZaT!{9Onn?R`9&|kb37S$QZ+XrdgnMwJsd8mHmm>IP#AA)!&O@BE2_N8>e~z+q?rlOSN%>^%l6P9U$+h$u)X6IQxC=9|c%5#kfqW zjjKH{!ummsBk!omHF~eAHqN|zT2PE@s@k|-dJDX+7)RbwlWX*zQEgmry#-!Mj4Pzt zxUcmVxVcwJ-cgfl^lA-f`kdHn#kgv!jhmpizyo!!lDwlP*XSLr+PLC+3p~FVw@MigqVw~1+ z>YsVmGUsvR9W}W|Z*A4ab<y|+~xr+NU(ydU@V`GhL5LxcT{Bk!omHG1!=Hg2Qd0{=;j3sr601HA=q z-W?$CsL3^Y15_K=Pj7)6#+lkU^*Qk~j+~+<*XZRK&ND!@ae6<_GPMKLdcBFr=lDwlP*XaF4wQ+g6b+(g=aT!z_r#b=K zoX3%O)Z`kyU#K=t^#GQskISLjxLQY6`Oo9XJ8E)`UR$+sA3pAEoAbDxs*QVGyt{ow z>p1d`np~r|x@zM>#+SCuy~@n0jmxvFfSpy0Bk!omHF`r-8@J1@ZM$Mz3f0DaTA`Y4 z&f~~CYI2Rcz}|9KpFM@_ELn^v`PE#tb{w^cikMs;c0`?D98 zKKKt_7~Z{NhtcF3y{{Pe_w%(^-~YZR`Om%^uc?jGIe}fZbtmr?)yB2o+r_@8^EmR3 z`qjV9Fp=K9s*U^Vqn*|hoyR>Zl-+68ccaxvj3e);$u)XSZCrtNUFc({{=G_S@{3-6=lIO(QMs(@ zBu{QJj+*?Um)|*_j60y38=X(vMfU9dE=09)x?f_?*E){8qbAqrZLZq5kUu?k8lA@- zefjQyy-JKD@2JT&djD9L-gi7}ke_jJ1wQfJDlpx@jwA1=$u)Y<-mL0;AJNbLUFUJG zYUAFy)z7XX#*uf_=0XOzSxEj+$JfcfM-lE@ka+PZi^I zr_#~=68o7LN8VABYxE9OZCthYD%+*RxRt7nyFIt0T~v%C@2JT&dW)zwZq}G)wz+e% zI;fEIFi!*ft{6w&QIl)*Zc%NV?vdE$US%%T#_4{EZPsz*9W}W|?;6#{6@3`&->dAd z+PLq_m$GMxapWB}xkhhB)yB0=zr(+d8>-s4C54|`=3XUvM@_ELdq=f#dOyx?rFGnq z#J`bZ`WqqdsL3^Y{~5FXr(C0VU*f;v;)@a9d8&=m{Sv#s7)RbwlWX*rfBEi!W$NQf zt2WMByTdYlPRKiIa*f`#FW()oKhd3&9;%Hy93F1B)?OufM@_ELYkDk)b^6u%MvSYg zcLzS$+AP-Gt0eEJ$u)YHs5b6Nd<)mq$C=tVy&vbAp3LMOHMvHwsg2t`^OR-ko{_Xnp~roV>r)6)yC;gzkeM^O@7hK?;Ibc+PLJEKl1NYQj=fw@;k?esy6P$ zup)lOQIlWv@;k?y+Bn_m_wQ9wlV9}mJI8m`y8~xa%=FyXy93nZ7rp$>@noE-jWap% z{HRU2O>La&1Z-0uN8VABYxLH58XKZ|0NdO-8Czm`NZq(}wyBRJ@2JT&dROK>81&oJ z@|L-C;#;07e@2JT&dM}j88=`su`&%(CU*@&m`|XF=e~5A99W}W| zuhn|2SM>n?b)56YSnt9|rEOCmN8VABYxLGEJiyy;RZBnPj=#Uot2zPO)W?x`)Z`ky zo$~aFRy}}i>f<{7;*D0FfNkpI$UACsjox%2CA_K!uuU(ow#R08JI^g^PZQ(FJ8E)` z-q5EtykDN&ZH>}8E^GK~@46{T?O-vEyrU-9=)IU}xL5T6wyBRh-}|7~a4E&K$+^ip zYI2QUa_W`-Pu6seXSEA4|Ax^~!@X~I+7yy%;~@KY?NyR@)Z`ky{WcE^Ry}}a>f<)O z^Jd7Yh&`6+b3)!xlWX)YEM6)^^#FEy)yH{@j15tpfSpc^Bk!omHG0#AhX-%`^@e5Y z<8rO<7j*7IOaD5KyrU-9=q)s0OK|V>ZCq0ySE$s7-pLIIxFy6m@{XEZqjzbUWx+2F zob|8cT5VktJUVQ*pK;_AHMvGF$8es_=f?-@PQQO0M@@dw%kLcjQ}$1SXDsgGU&m3C zU-a@j#~00>JUE3f(9bw(@{3-6=lJRAl9ipX`=+09)Z`bv{Lb;wsq$|sm1>UXpcqF@ ze$mVC98borSIv!C$Gso7w@_i##;M-h{#J}5@2JT&dQELyMXlq~iE-0a8@DfW8vicz}|2mGmqbAqrO=I0+PDQ;$AyY<}hjZ-~RO$>dPB!jy|-=pRg!nqBkx|*U?RQeRU4;z06*i_sW$G_I*y#8CfDfY7|xS4uBXSWE$|(n*5@d-#NanYU7d(f4PpMCco(AcaHyBwQ;{CuH&f5FM9c% zS9x`KdaJn3p1d`np~rI zk!s`W>O9W$WR5PB-Fn_ldBJeWdd^@{XEZ zqxY0*<99%owU!KR2chuw>y(d%~w@c@7=8aTS8+SDEJdV7hCfDdquG+X> ziRW?ERU2o{<4k=VIYmvb(aSNMr>1J-^nRS5an$4&z5LGcbyXYp>O78`{GylNIew;U zly<@5lMiMd*Q{kX!vsWz^r?p5B>I*z=fCfDfwRkd+lbg$C%WL~J+xRJV7X==d9J8E)` z-sRi(d%O<={ETa-+PJd1S9x5FBk!omHF|$jZJhcn+xcJKtF*i7Ugc0Rj=ZBL*XX^g z+PLw$R~abA<^HsRH6!s}C3#0puF9RJCzI zx>uQ9j60>;IQ3ul-#H=gsL3^YyQ?M)E=aX;7j>_4o)|~oQIl)*zOUN2Pj#=->{XUjZQNVBS7~Yo$UACsjo!GJ)>d8J zt2A$<-c@bf5#6h-AjXk*)Z`kyrZz6U?p00@<9<&38%d(S5%P|jT%-4Y!?J(1jx+4L znD}qF;2q&DtJ*l#3D|##apWB}xkhh3)yD1By~>+jwA1=$u)ZQ=79C6(aU?4DbFWtYdkF2e;)T5@4!BCjox_G z#;wu4%KKtmb=Ah*)xFB1TE~%h)Z`kyB~=^ux$adS(Rtj@*;-q=$M0txIYmvb(aSNM zXSizPHtAlaS;tY6U-a@j$Cp%XoO&hu_bRE$FM9c%;~%Ov?s@%}_bRE$FM9c%<7cTh z?lax1G_?cN0@*ljTCfDfgrP{cU6YJx~sWxtueyy~QBk!om zHF}S!Htq-g28eMns*O{ffE^&lk$2SO8ohf}8+S;*x5cRE9C=4guF?Cg zYUAeUcS8SL_3)zlo9K5!>p1d`np~r|f6|@S68+MMag$XWH`DyYIP#8~T%&ipYU6h5 zXYN(%?KsQ)Mv8Id9W}W|uilQc_UmW*Rc2LfTq^xc4LEs6O|H@VjcVg&>$g|;Dj(_Z zBSF7x`WqqdsL3^Y|2xKU?e_1q`5RR|fNhtl?;WYyxY7D0h;if{HMvIbRMp0PnOGk; zO|@~8^=l)>k$2SO8ohce$2Py8#JJkp<*22fsU0BisL3^Yr>iz@ntsc)R~ez&xY>#I zapWB}xkm3v)yAnFz}+auHC1g~J^jjvapWB}xkm2+)yD19&(wh5Q*E62nROgFMNO{J z%Q2kifokLQew_c#2{rjeFTZoVsg2W}e*c{lYVwO-e&_f&)yBQ5kE15P=;e2gAEny3 z$@-bv0c!G#UVi8J`LV4$^Ws{0DvEK`y?O)OzO1!eQ8CWc#x)b$Obs}BM@_E1=G7YRvet5@C-Z)-;ks%q7beD$chuxs zFL=!wPVb)Dcf>fo0d9M=mRl&sk$2SO8oi~ph8w4~Tuw3Wsn&3}w3bUI#*uf_ew;N;>p1d`np~r|i`H=ATFadmc-d$S5Rnl5+$h>|Ic}GpI(fhI1aGT<~ zTV=J5%N?}DnxwT{uoy?)QIl)*p3xdk@1EKp>pX6N)^L{AaR_<3;bqcd8|>0TvyM@_ELYu0erwU)as#_0_m*VbCDm>5UiQIl)*4%8a1P-35x zMOwoh(^}3jj+~+<*XZRK&SPrh25Bv4>f@-%FM9c%<87_s@+bB=p(elR<#&!xrP{bV ziG5C}$uD~Oo#VsJ8cu6DvyP)Czv$(6j=!5Q%oEkFgeQ*}M@@dw%kLad#+h>l)dN_1 z8>{ePoyE=5nOr6@j=ZBL*XaFPXK^cZCYMZ%OQy59`$Jk)lw)vhTd? zSGiwjasAYavzFuHRn>gBVBNQIl)*uGCpvNuA04uK%5CP_df5OZ_TGh;if{HMvIbD4oT1)S28pG44B^ z#huofoViy?-cgfl^cK-soazCrUSgcy(6LA9Ozs;oj=ZBL*XZ4>v$#;5$xRgF(&{X( ztj^>HX&p!2QIl)*>a83*yUyftYOm7NrJ27Gy|GxByrU-9=>5N9oH>hAt%B7oGQGEx z&f>1=OzwN#IU(<;$u)XQ=`60V&g9+_kN*dikB>&+07B^s6-Ian$4&z5LGcUY*71{W$-595wkx zFTZnq$<>oQX?NZTeN&91Cco(AcaA6H%$>?O-PyX;Eh?&v?o^i7-O2%C9C=4guF;!E zcPcCEZe?*X?wIaWCg^UZ>E%Vy=!%+@_XH_{9TMIr#qEfN*wlh#W?bg znp~r|vF=pf(cQ{0F>Z_QR1VYKO0$k5@2JT&dN->!E>d?ZKNaH^7kX|T3_0K#C&rO? z)Z`ky)pVya&8_NI1?^Ru|3B9oipT(7&8 z#k7ti@2JT&dILW=VtrFucPquXmAX?IuDg{%VjOu#O|H>9Uw0~_b+_`?u?XiE-KjM9 zO9HfxBk!omHF__0{MA~oyOo>7xcc5^u`zuE{p&dLj+$JfH_ho5?hM_n+$P4E+PE5t z?+%c6)Z`kyTXm;$uI^Tz5aZISHg2NsR{Cqe!8Odg8kS)Z`bv{Lb+=bf;2x`a?~>N^0_pUVi8Jd7sSm zr0Uc=^jYoUE;ac@FTZm<8E4J_){f}oedm0JsC%l7+fx3rH=<#FhrFXE*XX^j+PMB> zj(PKlah7W1ZY=rUYxXM1J8E)`-mc@zTc4MC6m9k@KTR>yT6Vs#cbgbT-cgfl^lnmZ z+@ih%Lz-%@Qg7(k$NyUAHSfofchuw>y?QIhiafP-LrF32zG~x&yeRB7y}ZafYI2R< zXR3{BS15hVDlzVfYU9%6TOHk1j3e);$u)Yrt2XX*y{0xU#pOC7PqmIScR>nNIc?rpEKJ@}lWX+8VjS<2Q2)C#IC_m|(cMqI zoAQ?4a3yAtz46lzLrN~}=a6^QT_~hwQ&LMFGZX8K(%on-#k#Rl-6SLZ74G|O}PHJ$3MZgwR%MNCxg(+<4_w2sT6UMEGwI5LalsX0Hr zIR74)6nqFN9Bw&LY`;$$DkQ*(ZL z$=QlpS7y_@E_8R*>8o9E4xPD>DAjk_QRW1o%vc?-z+>e(EtXo=T!OqgvqjCH(C^qt;2TIcpwFBn@HfK2Cj zYR*sZ-}A#L^_01(EYWTCNA}K1!Oo$67hls&vv;*4Ba)Zvtnc*Z)Oxvk|npR+N($AbY`6>^qOwDv8J7V(pS+#^_|`UT6bTl7wG(^ zOu~%8@zk83UgjCSon&X%`|qo@e)oP*%HDM|wKJ_;<=1p}r>y0rjyRgXOEe9Ao`fT z(_3Eq06z7~>7tCpyu|U;oS$CiE1&igK3312@yc3r2c))7>;0Hfm0P@~pB77JH~*`% zH&Wl}-I;EO6+LH;?^|UpW+#rP=KS_-4^w1+O>c^6 zXpb7YEI5D4?5}0K{MwgDcB{HGEJQsGkl#3-n)A~;)op86Tf3$FsPB^6-A1&s$5(&H z*}gQX{n?l@cJbwDok|%hzNYU!2(m{9r!Aja-{~z{|GC~3IpFK2`3fvfYQG2>_Zux$Txyt(@URKu(M}v z>)oL5^!C($OQXd9mUo@Dwv%UsH%|Xu98b;p>1F=(X}@K&dJ-kme#?+N)$H8MaynhV zDdbXby;9R2lcrYiR(+?pfc9H5lwRU%to;^dOOB`Job)osZq~j{GxatqtxQ{^p=D3~ zM7{i;7ky2SN?qMPd7@xUhi64!%fJh@Z!<`}jqYgQh8dOPsX0Hr%)=M7|1(iNlCo+4 zXYs=@d)TPF&a8oXUFvS}b?i&)W<^KqJH3~+|1()Vl1vXkW?hb_=A860SKp6n7JI)> zU=?#8AlKWEo$VFkJX>nDdrdEV@yuB>YEATC`c7|3?IWF4uccV+BQY~`JT>R1_wI_~ z?%uLZV(xiuH?Uh#H|NJGtX9!4^_8wEtTunscQn32>rVdh^v-*c#EGnRI5hCmQ1{x{ z;dui4*tl?nIiEPJB*y_&Zd`*d$%Us<@p zsiAyG&0I(Cte0omP7>uq<~@$5=A8606QVfR1vr87l2kea!UUQ_34dhI<@ zK4jkGcxui`FEgRu)w0v7k8LL9!^&k!+mZFBI<=GoshR8Oy`?kymFi<__I8-}IG&nw z(#uTvw$A#m3{UTTpnOK>^nD;oInsd@?_K{v? zLQ}uHTYYsK>CV99>F?X$8?{Pde=cJdJu!!y+q)~rf zbN3*Nue?2b@=PaOIgpyUj^1^;dr)5edCw^yGVgIbHRq(4nb6b|hp5l*9_@Xds#D1R zJ#3saUpbJPxsKj1bcf+H_4ze>U(9J{q6J9=A_>Jj#L8 z%yskz>n?<9v7FAzhs=8%Pt7^$WhT6>I~Bv!cX+PyVg8{>?ecnWqn>ggHFF)k3A$4; zN_~e-Uw!61j;H3F^fD7R=$c^VZC1<4s(kpnuI>BEFL0JBA5t^d(QE3Y^_Hj;sy#jC zJ&vd5ob)miM&7Asr@6nv`9nGCM)M-}UysH+G0K6|%ysm(oRDAz_o?OFQ9fke<9KS$ zNiQ?u!LJgmMgwa(Reh=@&sf|(l>SR6d8**oG;V_c)%K^V7>r z*im;*j;b$n{ssMugsJq-L(8x0CA8+pACXPs)ePdmK;AIq794tly({?4jVL{(Lxh)eUFt z$JMR<%7N6(b@ZBZ!=Kb|`h@Z!^B%`jb544h3CFv6+~sFSS~ZjvCrEFXw*RKhc;?1e zd2+&=_kF)Luj48Bx4g$3NNvVHNgPivGhvwS^Iz4QH+QsuSou*^dvrn)H@)&9HFF)k zeRZGzf!@6FzjuSI$nn&ilU`=Rk5v~iS#RfQ}mzl7O>J;ABTRx`V{LaoicFm#3ovzA<)Xa7CMyl4}Rtw89_2$fb98b+T>18Gy zt9pmzdK1X>X6cyvZF}yx6HbKkAvJRyz2#N!VCzkw+uA>5-s5;`&PnfUnNW2T74^1I zRprC5#Efk`B$h^n#)SQ!EX2PFUf3Zhz6q$Es=S(SN zcbb0IsjhrT&0I(C1=U|n&>KbHC?7KKaXdBWq?eiSi0U{tb-3nyqy58g9%QlOI_-95 zX#bF!xsKj8s^j=VZyo)le8{}V@zk7?US`5wst3uZHmkOkea!U zUcK>W*Vmg#=8TnjkK?I1C%w#sw@+oU@4UO)*`j3h!*+J)!_6ez(>*(FA|CY41U;ei+?{Pde=cJdJ&{f?{ zb-hhBSo??VHx{ys?mg>NRz9R=uA}!$)!oF$b$0@l51IEko|<#g%S^aVJs6(!XyY_i zJ{;Y=fc^cPcqfDMAvJRyz1LK~b5w6!1t=df?{Pde=cJdJaIort%0#4bZ)yMVy&sF& z?P^_gzEnP>X0D^RhTh03FmjYLTltWAkK?I1C%w#s*HurH?QB97b4Gu%+>g$Jypyc$ z%7@gD}Lo+CQ9^tFS#YS7A4~@*y>I9lej# z&pGch|~MQCLiWMHpa?#Y>Yo2QZv`ldro~3;@c*1{!~6> z-s5;`&PgvbVWjS#f1-DY4=Nwt&6~`=oHv=fR{4;cxsKjN>aXzavC{4@+COC8<9KS$ zNiQ?uFY429R__^)Q$8HkIHf(JaZ2}dXb`-t8}-lcrVyvOm>oRi+k$b{R}HzHc^D~Bl` z-iaz`{~A@$9iV(j&0I&XqrMS4XQXt^dnL?!98b+T>18G~{U=iNedOOi+@B+@eK<#2 zx4rTqHFF)kE7X5tw%%zzqI}4_$MMvhlU`=RQF`Zjg5G!DB1ggU9~!WoqU+ zde`Wk=kN92^9AKY<~@$5=A8606RuT1480lcOjbS|-r%A&zQIK&M){DMxsKjg^~2Dc z(XPpd%zGS9%{l31CakW$8lifB+Vs|#Tp`YySRu}-u6#(%Tu1K@>Z@_M^h9T*@*(pc z$5V4odYK6es%AOwyPKR!%7>duWU;*^vbgJ%52=~!=v}D(9P{;#bqn2lXWrv@YR*Y7 zGvT6uJofy6JZ^zyN$vgFo>|+oJ#)TSKBQ)@qjy^KP1eNbo19bHKV;tHcxui`FEiop zHk+*2Hk+K9%7+I#C$-OYPU`MbKBQ)@qxZS~TW;#VrHQgG^B%`jb544h3BOd|5!GP3 zpR4!C@ycmcubtMdpnOQpTu1MB>N~Pp?{lYCK4jkGcxui`FEil^^)FedcfQ|OK1>yo z+I}M>wOc^>kea!UUQ@4qPVaoTP(Ebd<9KS$NiQ>D4fR2>^D#k&d4yLS_;c%3Q#E6v?loea(|?_2)z8J?22_ z_cgwD;&^(Q32&$uNTVuE-8Zyj00=R-HFsdc^8e5a!J52=~!=xv~$BCYNOIOcqrd5`0%IVZi$goo6d zr2U`>XOr^btpSIuPDygQbCeIMnd|7ipxz{-rZjL(pGoFDj;H3F^fD7RRF9MHcN@6F zln-kRJ#O9FnaAy>d`Qh)NADB$IQgR2WdHsl^B%`jb544h2|rPbX)dYhJgQ@*(pc$5V4odYK82sCSDppKEF&vQ0m0wVqPQou_x0$MMvhlU`=RJL&=ByIjhj4-a?RZ4G;n#a*raLu%$adb_FzO#XaV{O8Ne zdmK;AIq794?518aMdzJ$Mk^mC4_$A4bTPR*TltWhxsKj;rkBjr9Iok^#=OVz)SQ!E zX2QzqN%MAm7I(Pvq4o}~Rave(?UWCxnd|8NPCaQ#t^CfJqI}4_$MMvhlU`;*y@6}R z^pAH;%}DUNtJd5LCEaVvht$k<^bS^Uo6H*;xtXI9liI}vuA0-TBnfmA@d%`Q*%ywnF$Z|Xk!g8x5P0$?tF9Nt(DCSxR-U$kea!U zUeh<~Vb6x{>O&C@^B%`jb544h2}`MmP%lp-_bcVYEVV9L`FV@hX0D_6u6hVP zYqZN*qkPD`$MMvhlU`=Rlj=ouU~sTMAO4Vcl9NB^M{BwAAvJRyy?MIccTNFp}oKg=>F);ac1G{;kG@6e}Q=+B4Dd(45aX^sCgaXh`u zgx{!-&d%B0-F(_VJhyOz)wz2McZBv2shR8O^{S7~@OwdScI89nJ&vd5ob)miW*^$p z%9JsgyHNXwx_f9HIJwq;|B#xwj@~Zn$8&sRF~^)QGw*RcHRq)FwM?kKJ}Ku!I*#&T zi&I}(9g~)Dk0>8fGuP33M}2*gcI)geQ9fke<9KS$NiQ>@>6dW*L}xcx`EY3csaAn9 zrQMH|52=~!=v}D(Ku4=Da7_OM<~@$5=A8606J{Ne-l~6OmD5o9@JQ!rR;!I=-44o! z)Xa7CR#TrLoh!RPD<3lNaXdBWq?eg+zxoy3D&E~aq*#Hu zenpkXmv+tlL*_k>r{!rlAFi1^)5_p0?|!CyNX=YFZ=m`ft+H#o z*Y&^C%zGS9%{l31COnvFkyW>1HP`e|T3BnGb+T?DcdqgwHFF)kAE|%R=t0jM(?f}Q zkK?I1C%w#s$JB>u*{}DU*~*6#_w}=M9_*U?ht$k<^mbJrrlMntyQUWt^B%`jb544h z3B%RT=}KTBcd7DW2K6z0I3%h2vGO4`a~-{X)X(YknHc8_-s5;`&Pgvbq3L&}-XHE3^}K2qHPb41t-RY! z`H-5qj@}scyBhw{PRG-I2PI{RMi&tE_txE6Op{71%;>XpU&8u!$yOa;9nd|61sy<%v9qQUY zDjzcMaXdBWq?eiS&$A<)%WfX~mi7;m{4~zBfSlp*YW+B>b|F_&X<|@-bW6k zHseoeys2BEmzl7vdQcVkYoNPc`EXyZ@>cByo!s8aht$k<^mbGas<1yj?n9j~Gw*Rc zHRq(4nQ*UqS#8gp#$Bg;c=`M3o=J1JIF+=2NX=YFZyoir8k082d7ymAyvOm>oRi*L z$b|dU6Kin6>Hd6pY<5O#;NTFqqw*m&a~-|e^xo*^h<@$}oi8)*aXdBWq?eiSqIHrC% zM~!UO)!9{CTltWhxsKjd>d|#GYk#+@@*(pc$5V4odYK8M)az^P*n#c|)h{QT9Bh5N z`Xl#Z-;1wl<~n*esMlBf_bR)ol@FQsIG&pG)B9Q`RL`)Rb4$9WZ`h%cIj!BdtGb^m zA5t^d(QA5!sZWY)`i3#@aXdBWq?eg+vU-oH4~siQ`LN)v)Yj$?O1Tr152=~!=v|@S zV;dshaLwE0%zGS9%{l31COoJfX60`uaif(FgCie#9!}2fdX*2Und|5^J32ATl@FQsIG&nw z(#uR(O7GS7F8ti7r+j#=VFBw=Y+W~#>XfOO>*zhN_iBTmXLu%$adh0hk;OSWRxxYSzd5`0%IVZi$gbA$=cn&ms z?!2vhIQ38l>%)j(_l)u(HFF)k;ree;U5e}IzlC{^FRi~MM|FCa`INz`N9$WjA52=~!=v}BD zc)!KBuoILInfExJnsd_2OqjcC3TNQQMeV1`hqV&*Q}mzl6frz&3ctZ~;UAMR*+E2^2t=Y%RBQZv`l`$y>D;Pm6mJEq?$^B%`j zb544h2}_K~6&;>prek`_Wh}YUJ281B_cP@~YUVn6XXa}gbExt_H(L3Sd5`0%IVZi$ zgqQ2>jh?w~pzHP=Y0cXGTXfM0p>AX4Lu%$adYgKyc-Pfm?NrhJA@d%`Q*%ywnF;%( z9v9W_(q<=A`EY5vfS8kEwp&X1kea!UUeB)`W7OBiH9hW__c)%KbJEL9nEF}`@8kAE z+yTmm`=-y1RzDiIllBj(nd|87?c@$oUmMr-%46Q+cxui`?;2#n8v)*E^{nxqFW>!P ztyleMT+_#fnz@eN&)?b*(rQ&p_l)u(^B%`jb544h3ENfO7qX*Z6Ss%*VgBM%LW;U& z-7(6C)Xa7C4)`Nul=|AZrhb`ukK?I1C%w#sdpax%R?iyO)Gz0|em7eEXk63BhMKvK z-egl+Mr|BY(G6EVWZvU=YR*Y7GvQx*9|gZZx2*fE^5OksDMH>2Oy_>2d`Qh)N3T`$ zVerC}yPe_6hs=8%Pt7^$WhP8myEWwal%#Hc<-<~+*db?Q8oCMEKcr@^qj%?}uyyKd z<0doxZIBf?o|<#g%S`yoXRAV{IBneu%2czyuNo5hAjs{Zd`Qh)NAIo1-k?K^le$lI zzRbMG@zk7?US`7NZ$)^!El=u(DIZ>`-Q3&dSq1lj@*y>I9lgh1H212njca<^Fz<0Z zHRq(4neayIg3*^_2Dug0Yw`Mp4nf^|B!i)I9lh=sO}zJO406*Qjc}OvIG&nw(#uSk z@AJ{#b5?|#Liw;$izeQP_&V-<Q}mzi+TwYt&8 zFSPXM!yWhLN9RoP+&Zm%NX=YF?{^2TMz>Gj#!jgolFWM?Pt7^$WhQ(P9v1AZEN**r zzPx46uqgMRXy!(GhrbsU)O=iW%hWG3?=c5bXRm%Is72y__7BbdL*_k>r{>oZ> zK6KRkQ2l6J)Bli~xsKlE>V2rbHm>P^$h^n#)SQ!EX2R9#eW;!_uBl&MsNRQ*w0}5P z`H-5qj@~Egeb`I;hj)|@nfExJnsd_2OxRn!56^1{7Lvws+=d`Qh)NAEKA zK8)A?q3M6fyvOm>oReN=!gK0<*j)RE3zQG@s`ud??H`){ht$k<^sZCy!w~Hsns>>W z_c)%KbJEL9*hjq&)mPdz?P`*qA68a<3iBSvQ*%ywnF$B0U!d7@ zi&dsds@{jiwSPED`H-5qj^1O<4)`u<|8T$ZA@d%`Q*%ywnF;T-KH$5l{lfs|!`|wB z*j4+7KPVqkGuP4EQU5JH^xtB7IWq5YJT>Q}mzi*mdLPcx{$aTG4|AyZVL$C3_ESEj zX0D?*LzyMMhT1hHThr_ggm|FRenz@eNh3b8{ zSNn%OwSUOG$MMvhlU`=R*6MwDO#6q`ln)1}_u+KyAFfh9q-L(8_oR9s+S)&yZ_byI z6*-=obJEL9*mYoFmFC-;`OlX>Q}4qo+CMb?ZK#>+=v}PdhgY?Kcu)I>%zGS9%{l31 zCakP}hn=;5m{$2PmvkrT41d$ijr4w3`*3K>#Qi|#J?21aWyR3u8gKF>z08C&)%$R_ z?jL4XK0Kn{haGhPaIW$pHFF)kGprfT2;D!-t^0?}dmK;AIq794Os3w4xpe<Qt!i6x_>xC z`H-5qj^3y0efW;S`7Wc5BQS*EmW`eRcw*U`IF zy$=&~|IqY5WZvU=YR*Y7Ghv<)>78M^e`xAczESVP7P^1fL;Hu+%ysk@Q}4qTx__8S z{STSHc9`-9MbG-iH%(|8RoxAvJRyy>-<4Fi7_ggOm@M_c)%K zbJEL9_~iN+aiV~mNBQt8^*&6g`-fwc52=~!=zUwg4_7DNKV;tHcxui`FEimz^*#*K z{liG*!^O46IX~+D;XLI-YUVn6`>Xfi*SddrQ~8j2kK?I1C%w#s@#=lJTK5lUDIX43 z@52tdf9O*_q-L(8x1)L=>g_B4{X^zGj;H3F^fD8USMNjhta0ZkAEr?6!#@-6A5t^d z(c4445BKQ);dtdk<~@$5=A8606YgkQ%h|5`hqm(J1ob}Lru&C?ln<$y>*&p>-iLaN z%MI4~GV>nCQ*%ywnF&8o@53UxfB2j3A6ENwyi-T_51T0;QZv`ln^V0HgLVJ#FXcn# zJ&vd5ob)mi7E$lR_5Y8qvyPJLTHZDU2s*ekxVy~Y(`VxZ*ARlcd+^{MT!Tvz+-1;A zpA#gw1`F;Q0>LE#zIRW^Z#~U-`QxnnuD?(G57&qfYiajk7WE&t7avlS>*(F2-G{?I z^dFM<7*EZd^pXi$UqZgZd9As{fF@$9QVy zq?b%MRl5)Os{e4X`VX6H_u)(RAHESEQj_cGje8)(&7=OqAH|2{J;qZrC%t6Cs|A;o z9MJCH{=$ddY~r;(n}^>r`?CcHNQMhe0W~F5C7Kuav|{{HMx%7&$Rn6 zx#pMc`7(Kr@zl&oFPU(rb{{6v{IVxLysF)YUuu4Nh4_$~Tu1M1?LO3f(q2l{56OFs zr)Exi$%GBH`>>tnm#c~o3v2h`8O<*b6CYBO>*yV?-G{j~ziiK!$$N~aW=?v^gsrsu z@R;V8%ZU$Jnhq^!8D=j`e zr`?COHNV_id`L~Mqqm!OA7;_~vYk&M?=ha5Iq4-6{-WK77d5|Z?@y_!-G`$!zuZWC zNKLMzcd>RK9?|^ra@7yXdyJ=MPI}3NX|((B(e=FERqe~r;(n}@`)$YShnqU4#^UEo<`>>+sm+RU3AvC#; z-bDM_yFY7wIau{W@*d-G{3w^d`L~Mqc>Q)56jow?S3ylB=0ev znmOqu6K1>isASP0|IROW((c1)1y4qvFH@82=snW$oXaR9yyS@zT#hgh^IGz3AOuhoSuu~!+EK* zcysi;Q2!w{xsKjHwEOUhp2y-t@*d-P*U`IM zyAOBic`ZI9?=ha5Iq4-6mdsJtEvm=vxA{lA52L30%$p!Sq$bzVJ5#$4=j%x$J|yok zo|-x7B@YWLxEJ$AnhHMx%7*4lm8jEEcxvXPmrR&KyAM<8i6%Zgrrn2oKkPrGCfCtBXK+eyp`J71L-HQu zshN{rGGPntJ{+%Si|U6bpS^bDYX9L1)eou3b@cAg?!%w;oD(0C_ZUyjob-|jS8Dg+ zc0FTk{ZP9PN9fsV>xawfk_Gp334w zYH}UDyR`doj~+X}Ox|NWHFE}d!Gu|~`!I)|qT<69+I?uBJ>o-Zavgcn?mnEUXNUNZ zyvKNI=A@TQcue~Ock9_9rn;%!htKs)5g$^M>*#H#-G{C8+z}s=_ZUyjob(1Tp>`iW z)Dt2;^tAhMyPlikLuzszz5Db&?EBfK_d?!dJT-IDOD61McOU8r(fuh4wfk^^o@wGk zYH}UD%eDJ(*@yjyh`hNAE4|KD5v8;zRNt zn{pw`z#C|B#woNACdD4lNgE6d#iJ7*EZd^pXkf z?!%g@A@&s?URUkV@?2l>AvL*<-d3s|?o|!Z?#CwYF`k+^=_M16RP8XPYKV2khrLug z)IJ)wsrZnZTt{z7)eg(6hPX}jL-HQushN{rGNJZedzSe&iVy3kcKAp�ug=YH}UD zNmV;+ry620@gaGS@zl&oFPZRxYKK=;Lrg3_9IV>mSE?b}{n*sxI(mOr?Qo=Oh;~0V zd5`hb%to-fTOGOe~P_duc2y($y7sJCO)Jl*U|e(wZnF* zAzl_AlJ^)-&7Ab!024OQ?!)G)A=>-(rmJ>%P&LH6;zMe39lc}qUjEQ~*{b(K-eWv9 zbJ9yDT&CJ#Zq*QH=zO`LYKMRBJ@57vA5xR+=zXc$VJFoP?ff!%kMY#ZNiUi3sA`8< zIyH2^5FgG_?QolFh)>0b)Z{vP@2GaD&!*lD@gaGS@zl&oFPX5HYKMhXLrg3_EU4OH zcGVEKiw~*Eb@WD2?eNKvVeV@2A$cz#9?Z#{^pXi53jEEcxvXPmrPhEagdpzx?zNvu#)up|Dnl^^sZAaFso{Uc3%xy zksL_9M)4Ux#0Pl6g!|QdsGT+LH1T0S^&bAE9>k>LLuzszd2+mZ54WoaF_!ud$$N~a zW=?v^gfY~67-isB?h^6ge)S%X`*8mOCB-9>hZ8L-HQushN{rGGRsa9@;bGn&QJI>OI_`9z?tUkeXaa zZ+-P1mQ@ep5%D2;kMY#ZNiUi3k$Mlest56i&X>ol_i%%H5Ic(xsmXQpR#fj{Q}rMw z7ax-M7*EZd^pXkf?!$Dte>tJ}FoSvz!_|Y>OngX9uA_IGdJl`L2k|%YA$gDS)XYgQ znXr_454WoaafbNN?mnEa9z@%JNKLMzcfNWL$EXL<@*#PT@zl&oFPU(SdJhk)2hsK) zHd625BK07;;zMe39le>_wbQ=5MPK7smXQpj?;U2`QiR$@*d-^&r+3A5xR+=*^_w!=CCvOfEho?=ha5Iq4-6E>Z7cdG#RL`Q=CIJxr}0 z#5>|cYH}UD$<=$fNj-?cnol9`F`k+^=_M1MSMT9Z>Op+3`}K15FX1gz58@i}AvL*< z-el@Me6RbLmx~X{dyJ=MPI}3N{*D#Hx`zIH|MHLOJ?#78{$*-%9lg3!&zw{b;u-NF zd5`hb%tn~{OozM((dhsDOxsKifnq97_8RkUdL-HQushN{rGT|Z3E}zm2 z^D^<_0L?DH&2c_Km;zRNtozavi-D zHM^W#Gt72BHhGWn)XYgQnQ)k9m)C2CxwiQ5vSybPmQCi`{zGbV9lf_SyF5!X%)`Wo zA;zPUpaI0pRyNVB~$#wJ&((H1ysySS{--f)$cxvXPmrQt1v&&y=hS~Dr zQq3;M(G2rE@gX(2j^1^eU7oBN=6m8p@*d-|%`n^f zK(ou6HN#v-d`RA7JT-IDOD43t55Lh2b5GR|$7^=EmS&j4#fQ}7I(kcKc6p~}nC<*B zd5`hb%t*#&0+2xg*VLl-~B=0evnmOqu z6WV#@0-9Tnr~bp%(ut()EHgD(k={(2MJ}qDWV`>6y!SB&{>Oxw6`%e?JiTN>yZbOC zqED!;AHGb|&MPqF`_OmlKcptt(ffXVX>U&W{?KURL-HQushN{rGGP_%K5R8^UFeVE z!%^CO*kDAt&=Bz_ zbwhs=A5xR+=>0{z4>Jw89}->X%j7-AQ!^*MWWwRveb{A|7g}F@m|VLL7kM2*TZj*- z$#wL`uC~hU^1N%IJmN$09^uq*tsPQ_+WO%p?LM4z|8!_=@gX(2j^20L zeOU0;k|ya zS1^2<_^_IGA9hNbA-t~mkeXaa?*#2W%z80lxUC@G+09^tKEmUa@Pn+ zAwDGUF`k+^=_M1|-G^l^z6vQRKD4_J%^I3e`wz)`jHhN! zddY+rwfnGd)`_99#fQDM`><4t??UZ-3N^Wo-tF3b_+nA35PSbJd5`hb%tprgk4rS#+kL-H%O8uA{fRb{|$BJ$ut_@gaGS@zl&oFPZR(_8qqT#lOk! zw6S_yuC(C^KGI}Gdedr`;TI)ZZL)kw-XjN6XHfj&KD8p_=_M29QT@>Fyk00itf%_n z4&9-WSM@_`avi;eR6oq4J5&;i56OFsr)Exi$%F@0Kb)&ORBZp@5Y-P)=?;~W;zMe3 z9lbSGKMd6!D)xMtyvKNI=A@TQ7^?bVX5FE(SA1Ai^}`3cLuI`9keXaa?-tb$Uq2}2 z%v1f4yvKNI=A@TQSV;B5v${hiruZ;I^}}+yL#3|xkeXaaZ*|oVGw2Q#+kZ&jV>~r; z(n}_sp!(q^-JxRn@S^I6*UKbxs)`S($#wMJQ2lV6?ogQ{J|yoko|-x7B@>QO{cwox zPvo^~2XyayVPXhvYrRQ!^*MWWvj;AEwbADt7;)gH(h-Ahw6vLbcc#PU#2G4(VIo}!wtGa zrH}ZKyvKOzfSmA>374sU*hP1!*z@JnsvqXj9V!jPht%XcdK;>Km_m1`3=toa_ZUyj zob-|jm#BU?L3gN>6dwkue)w69jLuW>AvL*<-a@J$KGa_9M&d*A9^Y!O?*h+V>~r;(n}_^yAR*#4i&rq(C$9$ zsXJ8c{zGbV9ldssV{^S1dw&XfkMY#ZNiUgjmgP8o<0~&d9IE=^ZQY^rx%iNpTu1M(svoY`9V$Il zKP2xlo|-x7B@^1+hwXHSN|^X?hU$ksb%%=Ge@IQPqqmIehv#&Mime}#_ZUyjob-|j zUu~-swxwr|pKFK@qo{tkTz9D0`XM#Bj^5|0AMVy2DyPMVwT-e>{2feH7yvKNI=A@TQ7*lsIH`IN5cE8O+^&j@v9n6*wsmXQprc?jn zMcu*tN_~r;(n}`%OZ|uObO&>6@u9tYc}UgCj=g`Gnp{Wkdi5U;)g8=5#E0ZP z##1vVy=1~F>OYLBJD6*T58JE%FkE*q+xj6jxsKju>OU;3JDAsr56OFsr)Exi$%HS} ze|SiDFx&g}rmO#OmF{4+d`L~Mqqm^?53A}9=7Qow@*d-K4 z>fYk!Vye{YKTM%Jm`92asmXQpW>EiO(ry);&wgoS$a{>ZW=?v^go~y;a?|M!=4#@@ z#p*wdqC1$6i4UpCb@X1;dnuy#(n9ZryvKNI=A@TQ*joLE7jy^nX7OQm^&i&P9n7u7 zht%XcddH~$aF6a_{zvzxkoOo*&7Aa-3GME~=(>a1&MzNV|6wfM!5l|?NKLMzH<|hm zSL+VuGU7w>9^hUF#fO>Ie>g{XFmDkbQj_cGO|JgKH~T{zd;cxe70dP$z01$UhgNHUjr;T?O>U(3g!&1;)Sb$s{fhLG3BS;+%Kg6a zOdr(`9nCL~eiX&L(fKkpxsKkBnqR(O^sHmgm&tpKr)Exi$%Nl%etAmAd5+z0Q?${1 zH)G}6PUp*=12nmg-f1tByD{AZzUksa@*d-?tEY^eF=hb!JYdBlg* z?EJFbedv{3@BAV@q$bzV+d}ipzH5h^e&R#&9^-+#AQl79W!L7*EZd^pXkZYUcMwh3C$XVyYgRU(R%HuQN$}NKLMzcfaPBtHhn` zJXHOVyvKNI=A@TQ7^?Z@3JE7i^5Kt~Uw&TakaI$ONKLMzcZ=Rjii*#jHhM4QJ;qZr zC%t6CwVGefpEr(qrSoM+^ULw~op+jv52?v@^j_2aa_N2Toy4jilJ^)-&7Aa-3Abo| zIZ3C6k$gB!^ULdIpLO18K82cGNAHK36mv!M%K^Oi3C?6rddY-#-XveYIL6+eQbhC1 zg(_Ti){76R$#wK*(){x0Lx(wbKQ?)f@zl&oFPZSlppdZnmmfv)VT9(FzfU{Cwdc#! z!=WG9*#X{$#wMps@;csOn&o1d`RA7JT-IDOD5djQ#18F3z-|@!{^$4_+Vou(?EPk zO|GN&XYD@RF+GMUs`?>$kMY#ZNiUi3pKdSRzq`G3lH2oT?LO2#8q?68FGG{-=v_QG zrMGNwO0!dZNZw;SHFMHSCLFEZhcm7vF{8zYDYW}A{`1$)6!9T7xsKjx+I=|X{mw`} zB=0evnmOqu6E3;C-JNxJyE9dMI959k2Uff4*#1Lmavi;{b{}qaqndBThvYrRQ!^*M zWWs{leVBLWYsc=lX{_CcO^fVx>Z^W8O|GMNw{{=y%{MNR56OFsr)Exi$%Jo;Z*`-U z*y>aeACA@T!%4Xko4>_})Z{vPr)&4&>_r7kF7Y9GkMY#ZNiUi3nf3)fPabS)i>cx! zf9obr{xM>WBU)!X!qf%R#DAP z@gX(2j$XYFPw&Un(t9EAF`k+^=_L~m)9yn(=7IR|7wtaWQ9Q0`B0i)h*U>vkyAP-S zIz5sP$$N~aW=?v^gv+%1aOscZoI0u>rqk}j456{j3-KW}xsKlZ+I@I$e16kid`RA7 zJT-IDOC~I%-G`<1FHlzTVM*KCi2tAdm>d7&$*WO!_%27?5m^r;?|saH|1see#mf`PhxC#OuW0vS<&w3{AF3Y? z((Xg;qcJJOht%XcdLL-_q4wICSK>qR9^T-z=!+Y9&ST{;4vs`>gO|GN& zmUbTwnpDkX5+9QH7*EZd^pXi{YxiN7$JI<_@uAV~!xy`PO-u11HMx%7bJ~5_waY{& zulSI>$9QVyq?b&XS-THsY@6-a`Q<~}eb_&CdQ(SyNKLMzSG7ZXe~MWvJ|yoko|-x7 zB@>p`?!)iS)-pLXzkEl#55KHwOhxe_HMx%7{@Q(*Gf7&LL3~KwV>~r;(n}`Xuib|? z`X@5!#fQbU`%pY*?EEq{xsKj%wfpdJtq|iEACmVNPtBb4k_q=Uz3V2uk=LBo`SLQ| zpR)5=VlzqS%hcpLdIxFuVOYAG&P~-1$$N~aW=?v^gsL6te(Lj%?LR!A-G^naMl;*R zht%XcdMj%8VY|sGO*io&d5`hb%t)ID6<}W9?iI(lnp_u<}YXCv!}h`hNADZGmkoL^{q$bQdyJ=MPI}3Nx&FOB#r!QkjH5eK zN^i+*nu-sp$#wLW)9yoYp_54UL-HQushN{rGGUN*A8sqS*r_f)T&mrNxh`hNAE-JKGa?t zXN~xfyvKNI=A@TQIOEczk`V(#BKdHp-F;Z_WaRlWHMx%7$J%|kB~uaag7}cU$9QVy zq?b(CNc#@cCl2y#{jkX=G`W%9wAy93aohRG`XPCb97vt+L%gjY(n}_s_3!=5CW-2Y zkG1=-Py2c%SbRuLuA_Iab|3!mq>yh?OK_r;zRNtEQ z?=ha5Iq4-6rqu4k3P)E)_8v`*7B@y2kb&Qj_cGEu-Csp=0tHJHJfcV>~r;(n}^xq}_+XOEa1z z;=>i%eVE2y*x30LYH}UDq1t`8+f+23_>jEEcxvXPmrNL4yAL}TDQ#^3;jZ$dU7ZJ; z#o|M1avi<>wfj)#%8~tt8)|YLz0I}z zF!#uu#?CL3_ZUyjob-|jCusNK+Z>tAIPqad?LG_|7}b0&KBOks(c4nH509MN?2Oj= zGI@{j)XYgQnQ*msA8Kb!WdGp|?LOS`+A)8M52?v@^v2ch!>{(XF%PxhhP=mkYUZSu zOc-Cg4>$f*#cUK)MbqxXIQ6ocS>i)#avi-jwEOVu?;bgiR6iu|F`k+^=_M0}YWLyl zDUTd`|8ms$)UVjmBkwVunmOqu6aH9qNy&oUDn{~QGwnVcxAMMwT=he0avi<9wEJ*>v&!CI z;zRNtnc72f_n~G^%zV`kf7R~8uNSm58O4Xx^UeE4SFG=Jj-+npY&A5xR+=zX>>$bTY9p-4U??=ha5Iq4-6?#siXSgi!#aF-)EIHHB>*OCfCtB zU%L;lCHclo79W!L7*EZd^pXiRyX~)xfEmPm&tpKr)Exi$%Lu3`%p6{ z#?}u*wEIx=B*xCCP?PKEU8CKH**!6O-G_~Wc1G3@$$N~aW=?v^gaftvaB-G*j-6kQqTPqF{gur#@gX(2j^4kt z`!M8fPg7s@L-HQushN{rGGTA+3!E^dz8N8=y0bK{`+7uvvr&9VO|GMNN9}|Dd6nKd zxiz0c-eWv9bJ9yDEU4Xwcj~-z?Eb?++I`rfUx+y^KBOks(c3`pMRO^}&M%Yq7*EZd z^pXkZYWJaLPRuuUK1I6^djyv@-Nc8~F#?CKOlk4a`t=)&^Ti$l&i4VzpjHhN!ddY;9`{XG3^^Q6bc7C~^b|1z_|Jt?l z%hcpLdKYW=;hVGdJiGspyvKNI=A@TQSWEj3XSB`cT@fGVlb$7g=_5^Ur1x=!BVm8O zkK)>TAbF1*NPSB2e|?CjmrQ7PA8KcfvHK63XP+4QB1t>*Uh^r`jEEcxvXPmrR&0(c18*O$V4~;=>s$ zmxk9&(Z<;Qht%XcdYuNN!nM~XvVKV3V>~r;(z^mo=zcybeBsM{#_m77KY2)ar!D1- zonNLV*U?)pOYiU=E5C~5L-HQushN{rGU183>%z6O#@PLbrM@c@9;DkACyNiM$#wL$ z4DPl`du@!}e@NbAJT-IDOD1f2J$#dP))>40@Xyt^Hf5We&e;A#YH}UD@j`QjYp;#5 z_v?}O7*EZd^pXi19iJZFYEA(&ReX5$<+yO|qcL?LzB46akuCNAJ~ygTuAg#@PLb1&x{42}$#wMR+nFm|du_}=svnZ~7*EZd^pXi6}NS}!zwW7R>oKK-9*U_7~_x6yk zK@B~-|B$@LcxvXPmrPh=@`O#=U*p-Ghs7U`{GXcKNN=UW12$=|jcfNGlK04g)PF2* zy(!&?czVf%S+x65JFm?T;=>i%eQ4{4nN&ZdCfCtxcOMp2{V<;Rki5ruYUZSuOgK%u z5BGnlAKq9u&DUD>!|vikYH}UDiPi`CE_|pTlJ^)-&7Aa-2~TG1;Jc*y;TiQG?$qwX zFH}FAB0i)h*U_8!&r*)|Vw+>CACmVNPtBb4k_m5V_hCNO4}-;rIkfw5v+9S9b-qkZ zuA?`*b|02i{m`B-llK@;&7Aa-3GMDf?W~FHKRl`3hi6qkw0uZSuA_IZb{}3*{qQI8 zA$gDS)XYgQnXspJAKLn1JoO)*((c0{svou%A5xR+=W9lzKP2xlo|-x7B@^x~l-YT$`r#w- zq0#Qc`Kli-6dzKP>*$@O-G>KMKRhQsB=0evnmGf!V8Sfgeb`?0Lpz_6O}h_m{m||| zq$byqC%0<%VFuL??ff!%kMY#ZNiUhOn|2>+XH8`PVGiv+wDm)~--eo8N3Y#|_+R~y zyvKNI=A@TQ*ju{~7pQ(1CO(X<-G{MMKeYGjQIqTFeWl%p+G}I#i4VzpjHhN!ddY-S zwJ&h0YHt0-RB^QXF!RX#X0-T_np{V3GwnV!mESpbKQ?)f@zl&oFPX4m!-KxKb>BI0 z#fQDL`>>1Zhlj<7)Z{vPTj;&~S3e~0F`k+^=_M1+*6u^?yf*g!?1y; zCM(jLQM(WSs~?j07*EZd^pXkf?!&sOAC?gxzS8c)L8>3x{fE@#I(mQ5?!!H*A5KyI zki5ruYUZSuOxRqz54E$#*!_ncwEOUT)emj|AvL*<-c#CrSXT8zJD)<{V>~r;(n}_M zpxuW9w%3W|!v)%X_}Pd0AvL*<-U#hJe5v}O-G4~lV>~r;(n}_^`wpjns2Nt5{{BNP zk(%5{@8=bdMEqAjB=3;}sqbj_;X~CA?S312$%NCi`*829_9lh;5C7Ee!*A7pm|A>D zO|GN&fOa3wRsZ2L^&gV=7*EZd^pXj6_p%d3{fG8^dCa+lPFwXK+W8b}avi;QUySu_ zRR5u!UncJ{o|-x7B@@2=;g+wr`VTE1cGm90G3q~DEIyOZve%hcpLdS_|(;VJbW+WBSj9^NoPQ}H1+ zxsKj2?LItdDw^fuL-HQushN{rGU2NPi<}Mq$bzV`>l2#?o8jrA@L!3kMY#ZNiUf&gZ2fkSI^#h%ZJ*181qB_ zVSolV(pyEl59@yDKP2yw0|PYj(@Q2CqTPqOGf#i78kxsI%EZo7*EZd^pXi5Yxkk<%rkRUKWwethvn3NSVnwEO|GMNk#-+eR{vo<)ep&g zjHhPK056zuQ|1)TyKY;Y7UILVL#I2t)qj{qd`L~MBTsIQ<~kYFe>hS7hvYrRQ!^*M zWWx2kUFW*`51Xt1aEW#w7W~kENKLMz_l$NQ-ucjfNZw;SHFMHSCVWtA$cKYSuSB=0evnmOqu6UNrQ!z=1Jw0ABi`Gh7b(rb4a zYL8*${4#lu97z2&;^`$5-qG&Ea++WMQ}x5)+I^T$^UEd0ht%XcdT(p@VQbAV$5Q=} zyvKNI=A@TQxKO(fhiZP=?#FJR-G{Fl&Ubo=52?v@^e+45fG_+-@<=`;?=ha5Iq4-6 zHqq|G0-9ewAwE3Y`><0*^ULAlLuzszy?3YWHCw z%`c}AACmVNPtBb4k_pdf_u&K0FWdQ)vf6#vQ}fH+#fQ}7I(pk{_n}|&%V))hW4(M0{94yAQwD{PH95 zAvL*OUm!F`k+^=_M0ZOE}r7_+ftej&>hT%9hgH5g$^M>*&3&J&tqqUKZ=UkoOo* z&7Aa-2@7cVp?21oXaCMGJB2mBZ0A!nSMqv+9S`oIUtnu&sGI@{j)XYgQnJ~tsM?cpb6cX8gXm=m}p!wya z;zMe39ld9@`*4lsm!FCc$$N~aW=?v^gt@iv@P48oFSE{<6WcwA|3i}->CL2FhT3Hl zxvz%2M-HU6yAsza-qsK4B@>R-?!!@f&WjJnX!qebJ&nbO)Z{vPPignzB|XW-hvYrR zQ!^*MWWw{w_Bl87ED|5aK0ea1Pnhmcp(fYS8@+K9r+=d;j=evHyvKNI=A@TQ7&}K@ z$378uzm0Yu-qEvOd`L~Mqj!pSAKLwgb;XC|J;qZrC%t6Ci<$GAD|$wV4~J;?;b1)j z#fQ}7I(oZk_hH))`wz)`jHhN!ddY;Nwfk_Gp8BdEMky83yw(0gd%qqvxsKlB+I{$& zp5Ed^@*d-q_! z((c3ldTNRfsmXQpeiL<KkPpw?=ha5 zIq4-6PSx(iiFz7}4`XWgVJtmqRX?OA*U@`RyASPiL3~KwV>~r;(n}_+sMD(odhC9i zGTY;u;(BcVAvL*<-f7x>I91P5oiCI37*EZd^pXktY4_o*5Bm?>X!oJ^(YR~Hht%Xc zdQWTjq4wH%Tf~RtJ;qZrC%t6C(%N@ucOITr{jj9|w}>9Q3z3@KNUwI+`0YN!k9m(A zNNwZ)+m}c$nXr;-huT?VZio*#8Bz`XPCb@zl&oFPX5j zYKJ3LL$v41f7YMxtSevJDJnjsCfCv1@UP@f$;}6RFT{uBJ;qZrC%t6Cczydh6IDa} zMSS?BYKJ#fL$v!3smXQp4p!~(hH8k}#E0ZP##1vVy<|eW`>>8`h;~2r6V(pOsD{`^ zd`L~M3-GFTctbVBJgOg(_ZUyjoL%506CP0Qu#IYn<;916R6E?E8e${yAvL*SO_>h`hM{hpW4o9nom`Z#|-eWv9 zbJ9yD{9CodKUG8gOnf+4wZl59A+{7BQj_cG-Jsf`y+7r;_>jEEcxvXPmrUrYcKA*; z#Hp$u&QtAhyK0Ct#fQ}7I(l2HcGy!j#7p8s@*d-?l4Y?=ha5Iq4-6rc~|FGT(RNL%aJh_J{jZsL6Ho)==&6h-!%T ze3`t*cxvXPmrS@xwZn(1A=>`KnW`O@Pz}-UKcptt(VIZE!vP=ePa*Fyo|-x7B@=E` zy)CV3h;7AG?NmF=sT$%8@gX(2j^4Ve9lnV(*-57QA$gDS)XYgQnXtNQhZR*rwEMBQ zsCF1s_mHzgd`L~MqxYEJOJ=o-Zavis5J=9(sr;GTIyvKNI=A@TQ_&~jf!_W9?iI(oOM_b^O7 zh~vbE@*d-< znUh{J;Vkv*y;9%abum>A^&Z;$m-~tjsmXQp790D>N!PuCvqben@*d-ODNF9>mx&Ljp9pj^5dNFE{jFZtJ~}_ZUyj{PdCuTdMc)u6htxYd$5G zdJoI12XUI6*#x?ETm;FkZA?iVVEIyU%Dcjx)P_;CL+d5;`OeNyoiKit1eFPSjE zW|s?VhPk)+u%c#{FKULlh3bdYQOz)S5+72N>*yUjvX0568D@L`GI@{j)XYgQnea{8YNlOC zW@nK2aP!xBP0BxGI}^l*)Z{vP*J^fowPu*@{mbM%##1vVy=20InqA(W>xeI0eE3qc z%hff*Z1>wxlk4cMsoCYfG{an8d`RA7JT-IDOD5c|+2ui+VYcW!bF+FzC!6??np{V3Y0WOj z`Lm2uMCZ%oJ;qZrC%t6C?HhXXac9JDl*(^`B;O|GLi$Ja-ldHFQMEIuUfF`k+^=_M1c(Cl(g z&8rj=AC}bY@|IJzs_<*U`IGyAKz2?-N>E=gZ_h##1vVy=21S z+I@K9pLOB&#fQnY`|!n26~kMI52?v@^v15X${BlR$A;YEL-HQushN{rGT~G0KFs<) zOSrvXZ?kqER*!JQYl#o3$#wL;)$YS4nS(a36d#iJ7*EZd^pXkRX!l{9bgMSC5g*pp z?!&SDq7`hV`XM#Bj^6g#efWFLo}rb*hvYrRQ!^*MWWpb``|!!LqZ{q~@>kk@7&KwZ zrh(!^YH}UDO||>*K;Mz!hs1~EJ;qZrC%t6Ci`sqIEbaH3*Qoz6g*(F4 z-G{Zl2@SXN%j7-AQ!^*MWWxH|eHb(5y6}bK!@sk~GhhDGDtxT?keXaaZx-!7Of|k| z=uFFpU`57LGbg=d!iCy>n5dRN)F(dNs@;df1}+WBAU>of*U@WtA4b1XDfDmE56OFs zr)Exi$%K~r;(n}`%UAqsHH@&v0 zr1)@H>@w!`sZ5)jseVXJuA?`9xxVIg-LE!(b*P_9-eWv9bJ9yDJgD7=Z66#gm{;|~ zcG`V-ZQaaGo5Y9IlF zCO6W1cT_aD)7se~SwG^vk2&x^CcLBg(~E|OSU#jTd&?WX*R}8X_U##9YOemnziaCq z-|NK#Oe$$_>mC1_k92g!r>b+uzhCk69t|$`S1p3s9piO%E%gSn@*LTdwQMT8c&}2W^8Wbovv`&x!(70f6Mo6ym#YHI`s~xa>EaG z^-?|hAwZ8Pp2m3^+|`RWbBROm%s<*58I_~Ew>Khl&UyV=4}!azRQj`a>FZf_sH-WWuZQ~8fWQ4O z-?cGAC!BQX^>1orN*#OQueIos6S|_aIo&dq+a<@^NZq$(DyRQPdaUBBop|AUuXuWA zts3E9{(F#_(z~u#Xzd7JUg@jSC8ic}GUbY5a$TtJF@~?_KOE2L6BN(5&Fcij@bwqN zNr26^W`kMC|!%qD#;H>MVGTYi+2F$>;ybX#6+WJWZ#jhZTk*ZKbaID|zvR-}JMZt#ieo|E-Sy&}_i;_^U(UOoYZWu8;-7W~Jw5AQC|=#v z{_TR>B+5BATdt~Ra^yrqeYk9slDTS3!TEIO_X?M+t%~W_&UXmFYE74 z{Nq6;=BA?Ne9&oU?bEZ)CFOa4;(|Lr$~h;m@>H62*?rwRzByQ`uo?3f&5)a3-5L4UDYL~mvwwmbD+ar=j8cBUjOVq6Swd-XH^lOm$H6h^SI5H z0R7$5VqVD9&rQN-w;Xy)CoXK_^^0MOwtwbKT3W(fx{<(4dbrPt-YlUx@k}XgbKo{AR*&X&nGSg;B6^~vrRqvg_ zPLXuU%<)E5z5LrBIS=AKbAIjX1n5JF6PqG^(mSI%RuAAYvfMVs6zY@SovxU3J03a9 zVm))K^m77q@Ty=ZZg4WMchjn$19QHcP3L+{-! zoYBp#_fCc+i5_xsC5>*WnvGtP~F zYpk0jd1J5nlyh#;cK6&P`x<$(D>o0&PyZh8)>zZiYq0X9pI&#?HecL^y}Tm}$GUfG zOma%c?&VDxKGR?A{#~bZ(I#HptyNs=hjm9fCp$LwuC2b{(o2p_)1scYv)u|e?Y7I# z@uNQP{&x%9xNTAz>T&&RdRu4S_kX=4k)f9iJYF#oGw=IsOuAz}Z`zmzPITp=POU%d zT)P!c0{vO^=F0kwS7Wv3dwO}6yLoK`uT;HJ&Y~l?+#S~&db@wQ<1Fy?3eYK&_w;Tg zo9Ha=`q)oze&u<#()0hNJP8%EGucGI$10cy5DH?!4`{ zTzbjpV-u`&^Bt;dT9mr!+&Q>Vj8M`v)c2jb#jg+i6N*$f)%3GLFWJ7Re#SanuV%*R zXY6PF9Cl7w()^*HL+YsumO4Rq>zK{@S*6#n?|a*Zy-eNtW8J;_o;K>#*c@4T!CiFk zuCumi6SH+=l>nWr<|OCK*u6|d-W8FK+8k~|6Ja?+{P_NUUwY=ssH+^UA>A`2E zwn_S!FVpYz4~pL3&39G|kzlNwYvNJ&$X`v&pmF!zOFfGO=p?;*nfZApx<^{~^wZm2 zc}@rK^wm?IM2g9nccRn%%bxzL%9C#VeJ4Y=A})0;{aHB^jCEE`IO@{N&qU3itaR5t zS?Oe2+1yKOF1QnX7o1_+ss!lsL;UXMF$qoji(vturw&)`>ofP3_*bqQ>I zf6C?2%g>nEThwq(;o@fLvmD+rC%Tt3Pju7tQoaD4WQgZRIp{et3V!X;%g>Dbn)zO+ zC+mIh9pZON>%G&vpv6jmg_7U;-z*yB{geNR|3dd6Zj$G{yx!mC4m_uRad{!vH1^&MF_$cwvrq<`rz{lg|HCg$p#VdX0>@omi(sPmk8 z?7v-ai1Ye&FOOb+j@~gkp^2fNvm}?oywmy_Z0uZcm+1RN-9+E7F#Wt1)z2!u{H&d0 zh2QDf)b9?{_v`JnsHSUpRPV*gLIJvK!6IgG*{W{$u6aCq`5FAX0!2*0u&T~q-SPx{ zulX~;pACBXnVMfS-wSndeXnwjN$73V_lw>K+4}e|`xg1C>+eO+bA8?S11|YK-`Cqa z_;jH^=hq`5?B5IOX_xy)yqek1XaDZd`=Ux;-(Po^_}1v}X`S;O!s36|&u9M*2ECZ? zt1@X!g#CL;eJYE#?kK147xj95ua@db zs_z%QtVPTm?7349dhTcXnSWC%x;HLIbg#qZd;xk?#~N;yBE`KYPjYzlvPQA`ZZ#+R zuA<($#km5$*Zdja&j!7$Iq+-dd!c@<_kCul-(7VfETCSoz4vTi&W$~M6;BQFW)HaT zOV;>XC)xPk-s-;oh`mo{`VJN!9H563YUTUp^A2GnrVaM!4ec}Aw|ip`e+A{Kp_t_{ zIz-r*%KiNjGoQ@#A5tFbEEBK$y0!Y&Z8Wa8M=$Fz5A`)i(eK0+`hI=t_dNeCpqI58 z{*L<8@3HB7N_cUL)pA0TXZPr34QKoA65i?jwcNugvIl&x`7^+u4SHF_$@*1#ugjct zrq8u!?x(&U{_drhwWEOF;h*?Df3a>F6O=R9yy^3qM=$G6<@TjEw~hsy^z}ar_-w+@ zEc`4(FY8qNO!TSGO??w)@M;uHXO;#%bLnNBieEE-cTw|q9lfk^@pmTwPEp^hmd1=L z9PCx;{+UNFYimair#7#T1$(_}eHQSUi=V~#8I4}n<@i~T|81%Hy`Y!%H-620FVy_q zLN9A~{2j%gVd^+d(tCv_rt^wEdKOUkW6kjQI2pXF`O|s98J@YH`drD+p7gTb$j`9+ zZ%fVZ1-+~*@@wXMq2}LZdRdd??}ShNJ>}nJdRYtQ&-|zUUa;msFYBoMZ2qbL&ir1` z%lc}Zx#OHm!_#?phlK@vX6NVk0kNJs+nQ$bf{O(kdRd$8IwXUck^8y3xn|mc&lLQ8 zQLlTjso8acJNlOIlXcz0Y3@4r<4klbo>R}mC+bm!vW|CttoMgoty29@)`WlAIN2Rm z^MM;)?yG>B59>cAhd**>Uzq5=SYPjx_2hL~GJ4f(O>~FvEFSQgouA)lKhNT=F89(c zc_76nYtdg;eeG7rnb|9GD`h}UgSC!qDJHwWrAhCt$yxG~b?m)8g3XQY6P(L8d;y;U z`FXJThzzDes^`w@I%z*y1K;)LiSuiVOr~;)z|YA1yxd#h{K7AtMTb%Z)L2+=@$|FN ztky)Qr+zkgUeGw+mthYFCUeS#4fImvI_Dpr|2rpLmQR1KG;J*>ntic9&akj`>E`KLe^LO~C&L#P80soDl=2;TYGSilj3`!Ci~ILvt}|Rzt_|}OQLt(glb-u z_n&(k%1m^5=EAcW>Yazndp{2k^1eN`(53fG&RAZOT-Cj~aYniQO2zjY-K^kEo;Wk$ z?2Kn>JZqyj-szYoW9FJ(s!qLJo{{nFjCz0L_-6KrFT9^8k9X<4y{e|E`zn_Apm|HT z@cBw+f6@eAc=zD}XAL}q$cM8DdUdDcene0|?*<*IJt>HE$zDV|kP7u3(j#+wz)sR=V(dRL9F=Kb{c zb91%&MAy;JSlXdMrs{=-0cVRmbL3ehz3f}ynH~SFq2^~9dfD^9&qVyUn3`v8^k!dO z)69Pr%k*y8(&d>H&#I`0>Sr}mvIM3@m*FnGmrunsUuLdpUUlf@9@EeK^b=ng`!oNk zb4H#;(#zfn_G6HRsL2WRvhRYglNqS_?#W^Tv+hSPdnfohYh2Wu@BoliZ_ztw5AsG(`D?<2kJonSu( z`!uN8n?Wz%3;W4C>*u!H<3^^her~Dx?b0xj(QRnMq80u@^H84Lk z+Unk#w=oxKz6$6%iZHG4DY<$JMT+kZXtNA&0JX|&ZzH-D!?&3{knWp6xtIauSO zzIb(#+oXJ26XTb#fS!5wPOu+?eHzs4&7hZk7wqRBcVUwAwv7JV-C-Uz>rwQwcY?38 z=Yg8%@AR^Fg0J(8kDBL$^zy$gU*{PpHP27!pXL$=6NN( z{BO(G`Ex?epCx(&<|Z&7!P*^l{Zo^iex=iT%kqV%$Ng0HjZftu&<^s;w?uk#F)n&+nhUi`P^>-;&P=FbxQWH@`m zUJllfsi&7u>(#$L$(`zj1oRG*1?ML@MfCfSn&%Gm zvUh^7^Y;uje;3iq-U+_WGg)e$=hDmnwtSsGC)E5|qL;lB?8o5mVQT)arkA}Fe4RZH z)a(bKm%S5wou6x{`PqkFz8AjEGiz#|chk$>3HD>~_Z~HWH`2@A3BJyr2Ws{M(97Nl zzRu5U)cj0GFW(Da=l6x0-#dEQcfo!P{+^-c?;?8HJHgl4^FYmh0D9Rw!PogYl$xJa z>E(Oj>-@e@^Ls}xdneeB!N1qk{JT#tdnfohe{QMyvrR91C-^!)UsLllIK6x?e4XDH zYJTtNW#0w+F<6tNW<8T$&eQRAo`q5K9F1On4Sbz7c52q=>E#?B=lgh;LCtdzdN~8g z*I8qyW__Msehqw`XBpHy2ceg}6P!t8O_G}ROnTWn!Pj{6$yXM=yIPIIqgjYt;NqM=xhu`8q!r zQ}eSkz5E*ZdYRvonvu7YnhQTB@~9hcNNOG)Olr2?P82Y2%iamj*pic}$)@nZM2y^f$shJHfvT=6a3HH66A5+hK-tT}wYp7|!=EWWJ-JmS-n;9)sgKnPWb+JUhW~?#Gh3XG<;5PB5I~ zIhkWVwag2{`Cf_4cTd#v>;%taa6Bh-%%_%TCm7ECd@}d^spZ)ThI4*G<{XAv=7r&W zUqXw zJdeS7AenPTYWZyehV#7%neSGp<#!1fex+wcclNxB?oXc%v&c@Zitf%f72UxPjqv=A z0e$kl8=3FsSPuMl0l#U`Dq}hOp<`v;kIFB#$cvK7+Jj#y>-L!XTF`e7cy@w5`JRHz zcNx_3>;%KPt|4>nLoM^daJ~m5^IajeJUhYj7@U`qId`Qt=vxr@Mg-q0k@@Z^NQ>`C zFnoV(MYn6;iuU{`hg;-_hF5gIpIgyheb+GW?@quc-%FDD?vmxevlBdz!F3IpYaeR) zjSGhJy%L%4o~Y&bF&O^Y{<3zTMP==(1z)qsPUdoU|BGeq1M8P~eouow`CgLDcb6=O zmYW7wt(fnJq?T)bd=#8S92!kTD&4MlyBU;8CLAYcM6&C+u?RSe-1zW zUP8owz-;`ItQb(NqxGv(~%hc@H^ zs`F8*d!wzRwoqGbB9sI1n*3UIXGgfsDPNt^54E&mdT37@GUE!cNzZ@Ap=rC7J?o2n zJN}K$M&-Mm@=yCvKeX}67j0NRw5JW*5AA8gK1+Mru)ouuHY_*V)5gj3yuD{vU90Rp zAB7v40GB~~u065!rrF8FK$ zKIz{}TlJIX_L1t@?FOG54I|U%t=Pm%`^)Jf?JN4_NS_>L_(wm}#*3-_NNEXInyy!$ z9%eW~d`(QBp&W>p+MFtzjw++J7as}B?dJ?Di-yx@C_KQ0m zQ$E|ie;dq2~s7gMV;bWOP>RG%Ji*wmL{`V8ejywv`XF48q^=1{uic-60u4~ywD zlmqcnTk(_T?x$)u`9C=tZ}^m->67fG?KGyhn_2DVu`w6o4QKT;eTH%%UTRfWdM97k zTA%0Fc*F0A&#RBqXDA2arPhp;;dH{&Ek0gHpP?Lxms(?ULT#w| zXKj+yuH7@@p>=B{(Ptlno<2F=@K5>~HZ}pDp&W>p+JlO}nlzWyh7CvgnLa~V?ba6;wO7C2>2y;W z#a?_Q-f(w6(`P6L;-z-F>Sw#^smks>%cuFdvY0+YIS?iR>C5Mq|6Vey+&)wl6~fsGj&*Uzm}s-U$W_k_Ou}f;xgLX;X)_tCVjcTNusg$ z@lXq4 zp?+>r54A;y)N$6$yy(=IABNMOyf)iZr?1KTYWr6i$0`TD6_KR9}nbhuScm@&82a$J9H+X-{6KwzERN-;^(EA646Fs`gw*ei%-B z@^q!;XQk;2`JuL{%I56gI!-tFVL0u{OH?++vrlzCkRNKlYj(pa-ezw~Uio1-?aAF# zS2I*+hvkRbr(Rdvi71w2^2Ko4lb5LN^vc;JaijcDTSw^``Q+Xhq2Cy!Qo2B}Ra z%MZ0{RX$~P=dx)(45vLgUgdL5_c9-nA8LPm<+xK^eZI5&Fr4<}`Kqt8&GuQJ%MZ2P z)pmMm40=j_7*2cgF14NA8iP*C54Bfv%y9B(Of>0XIPJ-s)pizXO#DWEsC~U(9p}WP zi`H(9$qc7GdA`QxZ?cuPH)wpO_L*jTQ)27iuzr>whSQ#$U1PtaXTVhXq4w1=cSY>i z-8sL=55s9s9u`wQ^7CJ-+GFI0+FWh+#@yZPhSf^t!*JS@zuK4G>M}Ik{#5;)+U#mO zvvhBFQ~6;y?a9$(c20h%jZxbvr21+mKMbcm`I6d>+JXJC>WkVwYCGNZ>mff3 zr#<;tm$de2{mQC*sC`UnsiicT{>5bwAYXPhLsVcxY1_cCmr|{tv6H=}Hg%GhQ;w zoLZ*gW!+7m<;p7SbEW5L-E04Y>NkVZLuT5jT{tnyPE-4;b$oSNm;M(WTuVUB6Y7?Z%>Z0pHZ8kf5uB@-=~&o$SR+k<+Gd8^QFq>HI>nEwG%Sa zMs4oPtE|y#Lud4yr+>yv=9oq;(-5n+^OM?8Ri!7t=C^OF4ed~R$V?lxL)Ev+k7#9o zsr1l4<0W&frj}_~r@ob-^hJ0RCdS+;T@}=e{DM}BS z>7+JO-K)+<^@Scv5B)Pc{bBgNO`Hs>Xoz^$b5!ipY4}7wtH`IRue8}qyGyc8 zwH7NqWTuVjcSg2yU(t9`QR$(7#!Kc}gIcDc?&wzTYmbz(CTSjgVraOVqIu5KdR~y3 zHfm=%ZQV={d|O3*)1`mLOXeDiTBf1YHq8-dS4tYC^xXKZs{6vp*Am+)J!GbhT0QIC z(HbutrHB3*FPUpYYMF+gN40X_e59O{S#v#C<&#tE(BVoCnQ5c;it4)ll~qoZ(nJ4@ zm&`RUwM@fPmm9b*{kX~*qw-0w_2WwIK@3uQ$V?lxtJD`R)VbC3BC0TBc!p{=#mGemzxR zm9?IY(C;m!hs?B5`@Qm!e`=IF=QYj8kT%9k=H3gnOv8urSxP=9t9~dGL1psF4MiYdcNOKAFHMGkeN1W2cGU4c}`={5~YX!884Z8 zfYdS#Ppy3=a;V0jYf8`YW33{8(-_oV=^-<1)SlAV{Dj7!ld3QJXT0Pi*cYXiY3L=N zJ>}D^zlLdS{%%OP+eXg|GSfzFHa%x1sQqZJ;?h6kC3DY~TBafMKYiLe^z2Hf_A^K6 zAv0~%KA`7tqQ;=7lpgwLykzc0Q_D1zlg~Bs*;D0Hrs+Pbs-E$alpZqEM(r5QeY&fk zkJI==|BRQ+J$7oDhUew;8TlN$QvFMFpNBLD%AZ;N3(T}pyIpfbGd`R7A^kI6GT$9g z%QU5cotTD(uPwAiWlKD=ATBc#Wd>%{nX*bgT z%t_6m>nlBErj1&&mXFdHv|Z_;f5uDZJ_)ro!#SpjSc@scXn6S`>%#A_NH`k+Xm%@TKc4Rp7ywY zYP~n+g_O27!)Z_Eehalzv|p$9B35(xVL0u{+$W*7k@gScQuhyShSQ$R{S9jSYA>^M z>VBrpaN3i(FF~!PwA`mOnS3#v_GIoSP@79-WA-1l-)l3R_GIn@P`grlnYFb4to>D+ z;j|}n{Z8%o#S)UcYah$_VL0u{Tz6ADSo`y>v_F5vv_1HwJ(=reYM1DJfvfig2jqw0 zv?p_&OYLuZAJ=^LaVzh(wl>3QPv-iR+B3~JIOm&hu!_h}P`Jmso9jwy8_YiLq`PN^ zl}~;cPJ1%fgVdIrbkQl?ua5P*%7@{!CvzP~ZA|?ePQzwcQ5!lUKMbcmnd=>DKbm;a`Jitdr=ZH2;j|}nokHyr)mP*_ zGaQpIhSQ$R^#!$4T5NC@=yz0p7*2aK*9FwhS9?y<`{l;U7sF{!=6s&obn0If)rL&_ zVL0u{oQG4puj$^DSL@wy$|*ezr#+eTXKK^F6&vxO+E54iVL0u{ocB`OvBln)q7832 zPbpsvr#+eTRcf0(TgU1%`Jyvhei%-BGUu7p4p(3QN^R&<`C&Ni$($cjTffBytGwEe z-h0{%r#+eTI%?n0Soom7Ju{s4WX{K^?XB}R<8|Jqq0+-}+LJktqLyf4^_5WDNV}`t}9+g{DgR^ znBinE8=dL${au*OXx;MfbQn(7S*btlP51$oO?%~`)WLPj{|qZVf1JtuGd!wyQ+LGG zOHOk2cx!K-oNk3(joe4N##t@iyXai4R@VLUgWNXx{Wc}t#-|rMOO{l&sXcz_8F%T= zVb-;3@z&MhQEsJl(_I(zc}A z?bKptgKR47x#$#?ucilb2k~{~y^o2neVjw>=a-(bH(d{NGN^oh86IVqNk2VhuJZLu zwX*j8?_YGLC|~4!yBgUA^X7CbDqqwV{NWk<MlIm}t6 zx__`nyp?eG^px*Z_o|DaHpBMAHb(91*TS4r^7BOXc!zc2RbLN&KP^RN zXImn(9a76@2gBKC$?WgcGA|70*huEMN-duqd>(O3BXc~Ymd_4`v+t8RZcxi-2gBJ% z$n0O#GA|5gTO#w>O)Z}td>*kp$t-hf`Rrgg$9yu!Lu&c#U^wfA%(|nNd0{yFESdeC zT0T4YJYu^gvu#t$X9vSM=94)dQp;xt!`a@*Y?IV7FAQhBkXd)s^4Y=X5yuBI#}I1y z>|i*@d@{#FYWeJ7IQtQqeT`b?h2g9hGV6|7K0Ek4;y6s^SWPXT9Smo?C9`c)%V!6} zIX;j%hEU7AFr4*5X5CS1*05&1{9(xuY;LtiR=l_MH+|H$(;V}|pDsDWHP1}Y{BeNhk#A~#SVn8yX7h_k5uQFF{UHP;*=KO?pFnk>76o#Lz}T6?{vHP}}9A)nMd>hfLFV^S0swPiKO zoT>HlOPW8Y(_FrX=JdxkpMO?s!I!lr4A**){FdT6qPP}n?Mdx6<*R`5wMc%Z>EC}> znkTf5bJ8j;o3vg|)cTaX*Q_nH#@ME~s9mi!+(E4gFIA7XipxiOt#fN?E!;?Db3p6d zWaW#zQR~G_X{M)~SH7tIN`8LSnlO{rgJwf6|T54 zX|I6V+S&(Lt99<`8u88^t?^$|{*z^MMLw#ijGD_2xq|iz_J6Y2dSPj0m)f&WH+9?m zbjg|<9d8xZI&a+>ZUE8B&%Pm)n}_LcHQUZl8`Ci}edPHir;N20v7R=u-ru+5MM zr=1@2fY!Ost9+=fpgIrNUdbTUSImWJF->J-*14=BGV7GuMOuHA(>iyK{ICpJw&b`^ z7d!8%jI;;hQrlANue~bk=ajDp&MbD;s*JSu4619^JKF}e&9pwPuC;C!tt;8am=`kh zPVJ*Hjx}4p!sTb9_5sGLz5b{)voDa@cc?wBHEsv3b-&m8oo$0{hFt2>w3KG*hr<;Y zwcC`Z6%ncHWtJh!mdrL!?P#^-E$XWiwXS4eW?sn5JGCX%mfOnD2=&ux+PfI6vFtO| z7snhj$0%w)`X$Ucp|R{0)jQif`vSSD_RmU~aY}JfTTo+0UX5k(YKJUCmMximncCu7 zpZ=<~0~=(J0UY(YWeJ7d9uvOUe7E( zJ2)P4JSQ_=YWeJ7y|C`cURtJ;{hj@h%y_BgvxDuHZJX@%%;K|y;~~d$GUKI|&knXX zwn?&=mg!`@usqDDF6(E8lf7&L>td6)Td{on5$?rCYku~OGUhvk z@rGl-3@6{p#^?jz{P{CHzG}SHv{YC3$?$lqgw{*rwXW*XBF@@x)`416zPvxTO^#_9 zXEm11!^RfcYMSq^*IYhFq~@zym!8!8da`UDl854o9qMC#X9{-`Z1Kk4Kr zqt=y0_3vg)xw4(sx$-kqexkG8=E!c3?5ORiv@MaJPMWX2qBycHtL*AslDk~_ zDj{EA>qq`p^IemsrCN7W`)O3Xb*yApJ2@iWY9v4A-SQRXD@^%WDqrXHU-D=Aw-060 zPi08$Hu)(bKW{02Yh*J^HmeoaZ}Oph+0~RU@@mD^RCbk>CTh1-jdw=KkE47YP~PuZ zrgSS`$5b}EB&_+^2tgyJeiyQ~za~A+wE9`=ruRTz-nEd{`H(Bl2;@k+oHv zvr_q^cC7qVP~Df4pEI)A^hBIx-a)f$$*c=%t14g36#W=*R&%h<3lklA;rtt3CoR6diGFZMx}Etz#e?d0%y zXQqCK)gGB<=7r3$m)fT^zBiYjGxEbRoPCqbzD#XT`RP+7-pcw=SDS5~eSyp|liDUq zO9PehW~GN?3(J5NYT0T1%&bCBmJEWG+4u-SOlG)#>WnLK0v60Mi zm0CVK_&nm6Mpirg{5*}te|UKq}{L}ojrmd_48k64~$ zmN~V2b}*b{KAGbowS0Ckob^Ix-BHWDFr0ms%>GU-pB;Q2vE7o{wyEW_gW+b}3p}Sn zIq+ z>}%9AFAO(z6sVU_4%8#He0K18#BrF+v6@;wI~dM(OJ>`qmd_4`b9^9k455~JVK|>t zp&XcRQ2S@rZvQW|X005Em#nqyAK_knr}kcc{=0?$Pt6z0nRz7B#*6=q{h!f#rRRS_ zxbonhFO@#A-2T!L=KJu+^gaAxo0f!|Z;BVt_rzbQnK^=N>_W4qkU46zA0W`-xFWIYI7o)KE1RL={x=U z*1DZ9?Q==`{<+gi{6q6GK}?^Fm)fUx*L9Nh4e^PY=O;B0ZxCn8KP`yq-%H!>sfoV( zFLI?@nA9t|%PpDy885Yc)n3*s4U?3f-X2W7VgZ+gS0xqjYr9 z_vah=xpN59rc&Xi@_R>#d^tZLgMjR7AEl%I8Wf0S+m-czJmmPXe%=>m?L}&3%ak@`u z2QmFKUTPOLN=h=%l{d~m5YaBN$$HhRTP)qeAf|sW?MAg1bFaywndz%c(s-C8p42uX zf=vI6m)a6)FKtyO&+4ua({@zHZst;JtB~o_OM64lhytpk*CWq|e<3a}zN^Occrtx5 zUTSltk93cy&D6^noQ%u)!y7~;`LqJAf|uDOKoqJ z$A`NAqD54W2y?f|&*I;@EeI#mzn9jum#0)`s}7fpFg!y1Qsx3dOrMOGTGMs{^AN+F zp9DD6e;{71L41GjX>@;c@O_A;9|p?Ai@nN?_FgvsKZgIEufO|?zuo>@@6FYI{@CB} zV)_5W#*3--viUpwuQ}Tg*r)oRTAsJlmS{u%Gi7q8e(u!%&!p|YN-Mwa7adB66^)Cl8eKKBZb$_E>L3Om?jR%r` z7vCq|VwFoI)4!MYOSPADYClEOO-lMrd_liveToDzeKKBZ&E2QRl#ZqE^iDGE=vGYs zURrY(tGP#Zd`&CK@V(**Ax!^_ms-!uHM`lV2@Rkq`^&f~gU~jZ$Z2F)1D>KKfBhx?Qr8aM~N6p=CZq?qoBD5dt+k2^z^ubCp zeR^p}`S)11kA5{`v)Yc?d--Z*kszi|#!GEAwHLF;((j>{BcjDE#p`Cx4`TZF(wg?7 zdUZD!ED>>6jqGkd@z_0+f|&jpFSXaycFf*=>%`098XsJZKkl9vaz~Kq-%DFl@xQAy z4Y$fgXiRW5{@Z`eeM+nzj>|hZyGkB*64ZZD2pa=mM;H-5<>GzxnUA_TO#be@`3u zPsV|NYrjS9=Re&``LD3yT9wSWZYP{JWcs;NzEeMUYJWTFxgDRhA>WRF+E7dOvhfP1 zmQ4FQ<-f`g7Vh^-ptu_w!=U;~C_GD_!TIaIX zIY+Cv2{-#8X1%;9W`7kjeR^q6Xntzev9D>r#mrR=FAHJ%WW3axJrHxgbo!%{sP;_FKsG$#|*NnHNkjF;NL z9>~2qgJjx~>ebz67tNJ6~cbptfW7f9B5|S9zCM_3E0jkxZXnT5~2)3~xZl+QdgP1-UFSU1Tk0r0_XuqBjX~g-(`RnYhLZ*K&t@e7|(|T@wr)QSV z*14aE&+A!6rccI8t!X>vSyIpc4AmJX_k3jPvo*l<>7{*2<#ASfEJO8t?iTxt$(`EVj=fiU82(rJq0c|Vcbc9%wf{3|^V0rDX>e|guxl@0o|s|Y-Yu>; z$Kip=dq?iwV#52slsn>$H~y8gm9Mcr_w3a0ISU3Q9q`)(*!X#TOyjDTHm2IdH<()` zcJ06V3D}#sXcJ)LCw5rH4NtF1)i&vnr)s%%|H_kIXtv?oQ>p3i^6=E;&Po3oZ$N8& z25dsPRF9(Tt0~PUJn4}Fkw=#Yvq|TX#v|5OyOJHcr)@doS-2W-eD z-pRS|TYqG3s{g+GE+w{lGnjq(%95sPet+3c`p3A4cl~urpVS6ym@md_IA9aXGna;K zczktg8qTfAUUjU$-pPe`SR0-?nQGJT#Z1Y|5>uHzX-^ySf+xCF{X*^8q;uNoDG`sa z31*YFfq8qZpZ;xXc(>)7!|zo&oA7|2P%Ukk9@+LsY90gjv?=iZ&ggVw$6D*+hS+8ICP$YYaK;)izneYm;v6e| z|4*%FpL;Th8&z3u9sXvNb!=}>+e@2m_tNN9#|znw3pB8k-WzBAGNpk1K=)cfO#h6R z+SeD1i{3r7rv1_T581QxJ#9VwNQ`|nTd^Rfe=qI0*Xl>#NNi_Uzj4zVQ=zt1wtgG? zM1!kAO#h6R+SS%w(HDF6w>!_)H%}7sSS@ouYj^CrFo@~jOS^J%vl=Zve9`{k_4HQC zhnr$r*L%@E8GbH?O#h6R+H|#!ZhC9L2>YEM#-;4){PV+MX-C+@nyn6E`t;If|KiZ* z@9U`k$BcD)H@_=o$Zvz}Cr?ccV)|#i)Lv^EzGc9IZuX4+XPizSZAp17rS|?y?v?^`;;kJ$ z`n#_@HQM?3orTt^o4taV{=KvpufDhC(8}~y$pbIC`A8BT+yMOK- z#PrX2scp13c}vZKXPgT2ySdGKzT~_ed&1edwrvp8znAvJfu&pGj~8;A7HHtM=rqx} zt8!kq&g9xbO#h6R+Gkn=OG5s@MYA@HmYs=le`n%_6>DyLO6`Y2<`nX+ZtqNlL_tIL+ znr&|O;frqZRq35aU;QCv*f8z0Z^{$I^v`&yE%4yc>TeGi;eP+axR|urdZZ*a9O1?e zuNB1f@1+etd8o$6b%wY*$Bea}ZWQ_Ogy)C4SMD7g#PrX2sr{~Dc=R(1y17gGpRpFd zxFY7_jqYyY_fG^d{d;Nqzc)C#U%>|M#$$!-Q675E40cN#PrX2sSWEkKYF^_ z&UZs<+T~|9x88XCA$QKx)q|M+y|h;+t&M*8=1u2%LOZ))<*|A`|L%OzvUw2GKjWn~ z?2;Rue@?uk@yC8~-hAs|?bn=aqq+w%{d;M@xcXl7nAPc>90y*sOVwX#4gKhDC+f4l zK}`RQm)d5v_C{B{GA>5rk6m=)8`gotqhszp+AoOd-%HDR2|$j~ z+25`oVv*_7OUpUQ&6Wl2HqX|x4}6#3BGV`1rIvG&#I)a8+lqFv=XHvSA=9UqmUEI< zV-{K$2Mw^d9~qoNrccI8E$1W`GGw#fyY!qrd{-HVOrKs_&PgJ&rb)>&e6XGNu}Kb@ zJ{d2yoRgdzRo^*0vZuZI*anA8pI%zdNs=F1@4WbKGkeD5&m1y+GG1yqCutg$#_jNA zRr?p`SBFfWURusc9-RE3yL(tJdr+f{E}1?VFSVSL6#A`(d+yp{Yg7MwTrz!nX*nku zHm|XJSIhwGwVqjAGJP^$YB?wQXxWqQT_-!lOzfA=CDW&umUEKVSG0FabxH4ZOu6Ea z>67tN%Q?xqp-;N4^DlAkt$WNN)2Ek~bCNT5WB2IAt4_}0>l`wDGG1yqC)wVshWljJ zV(z#};~g@6dTBW)IlcA)w_D3c+?g%PJ7oG~ywq||GAHc~Xa1~qZlPM!Qpoh_rRAI? z;%0*L%UgZjEuUtOA=4-0rIvG&qkChW!JiIw7bIr0$n@!@<(%Y&Mz3$ZwtA@h%k%v$ zGJP^$YB?ua_Thb&bMqNDPpg#{nLfR=oRd7hc)9g!#kOvf+50RqeKKBZIVTx+80hI z$Dp_GdB4DJ#dFv&i)6rR6+?^Aj?CGG5wnPSPS} zm|bmVHS2hjO)2CeAC0i>`5U)Pe==8!mzHyq-%ItjW9n_R?mwN~A=4-0rIvG&b1yfy zoue7-?{n2~$n@!@<($Mh7GY-}Q_fzvwVgwzPsU3v=Oo#)XSbUyYG5zl^_)YdPcJR! zB-6XC;QgImx1Fk?!2cvUY|6T^%xgGG1yqC)rq_g*&fPdizwvScgoXURusc zRt)a#F3*u{t-UM1L#9v0OD*Rl8IBBdn>MU$b*sNWg-oAbTFyx>tQp~sy0^pDxg+YN zkm-~0Qp-6>jpM`I^Zgq-hr7QYO{PyTE$1Z9KiAv+V&-Khkg$n@!@<(%YHzeqQEN=3Kh>!mF+eKKBZIVUN&J-a(^X(PA(;3q6HeR^p* zCz*TUU8mvaUECH8hFN6#WW3aJPO?5%J?E>ZpLN?jH_0N?r$!JX*I()E&O9*ABGV`1rIvG&=hNk| zdz^0IrVZ<3k?GS*%Q;D-Gm-X{LFL^Sr`EE_^vQUs<(wqrt1awJV>7uo`ewJt^y#JL zoTPV}K6an)w>ksrtcoGiC*!4-bCT25p0|5Uc*Hr@bMwPw`t;Ir9>VzvnLZhBg{OB$ z*VMk_e!c&ybl0Bf-^Y!$x`?~HvNO7#!uN*ov{gH!H!FOL!q0En8Qos*&f-J({dIey zn=Kq`jjJ`pE`D-nbT!$$5#onh+K?C3-x(eA!dNRs?`8@e+8MoI{8+1%{E*w}{oUya zW393Z@BiV>=*ddk4l(`Eo;KwD_ed*0(b76f^Ucv?ts^0P;hT4(D~}v&RZ@C-T-X`? ztm1k%BwlK1!}Ks-+K?*@+#P*()L84X{BNrEZnW7O-Wb9Y@81($SY^^);S2Zdj6Nuv zO=9|?mNw*HUQeyltNcVwOY_ri40-3%9W z2aE1laaXj7vv3E8OR^ zr&K!j|M*`Z(F1G$4(clg+u^)qEi?I!8XeK!fp-)jB)Z25TWHt)Nk zmUjg3yY9R@gKX}DF?X=M5^~>-?&5IDC_Srnx5w|YsVAEXO7mjfcT-h&-JH~q+(h@- zd@dVvcQCc)+y3{-*F*ASz6qa0cZjTz4azx)1LbVWhuYTibHDtAseA%9rY_(osJ{69 zd1}oa0p;)Dz8lsBwT3IpPg&)Qb?Q~`r znRf?J%R2)2y?VA8GTRunyd!{j3h<5_GVczcmfyx_nwb|e#{_B(o4cTAslGV2c#S_M zuA&;J%>C5V=9iy#@?q{f4wR4X3<~NC>=*1i)Eb|&)#n$fJ+lw8Y{`MR%-uuO9+v(S z{l3*bs!X$2zBu+$yH@!zY0-#^GIg-P|Ifr!`YU|Y=_kHxx;YwSu*=Owag2{IX2#k z&A3V}pB;Q2aZDp~JfxP-9fq^-lR0is%V!6}*+xIm^qn3GLIQuM_{heAqJNP_eyCt)2Q_E)u!%e>q z+>;W@fqPY`<+Fp~Y;R@Xa-yN%-mnPUjGq0f%Mvy5YYD4X&z z<6)>a@Z4cI`w^Lajn5tCh2bU*fqDt$Ks{2+X9u509EZsqtEuI)gW+tqWVUT;`Rrgg z#|JXU5Neqhh6l>T)JrG_<{Q-hRqMF_TYk)1IS?1wteXSjUVJo(s2F@H`D2#=cX+XYZvo z->x&?vV2?L)z|j~+FCQQrpnvD<tC4u885YODh-wQ z)O99pT9RbG(eaVK6|g|*A&2@8#7nKd!)({qcN~tXoXxjhYKYgio)N_K>7}iwIx_um zO!;X^=9?<6xYvm1f|&jpFSX`7s2YFV!)iap)sA+GD_8BAM5cc)?MG@a=37PUs!tC) z;^%ilm_8XVwR_ZFp3%5`t>oH-jbig%%bwpq5=N$fFKytPsPA6jqJ9pBwIGt&n# zeKKBZCseHCyW^(j%nR$9&S~c3%FX{#hD`rnTHS%==)NsC=bk;w2a9zVn0tKAh00|5 zWW3ax_M&=qC+NN#FQ!i~?K!oVhg4tbyV~KW#QLtTdqd9-vX_5qZ>qhV({GLLXw!GZ zUGrV<{W*pNF@1Vzn<)M@O2=+Jmm7=U5*Mx7Gl=P*@ltE?W!fZUsRdbqiR=72a| z_XR;r|6W>s7sx%KKCbT(#Ru-AN!DF>Wcp{k)M`xlV-Cal37I~r)x5`d-;J>iu<;jQ zhLdS?r~Fs>xzl)W$NqNGb~`q=6W8B1e}7ZuzoHG?PWz+{*(*J_u=z{go11l4u@~Q2 zsCfU=eUJanHY%S#((lE$lYVM%$NsOfxt(}vL%y9f(B6ybhc;f}v?0^}PWi9$bEolo z+23h;?$q8Z-v6p_`E{R+9+fmBLsAtp580%7bF$_?<_?-K#TO>NS%s|pxc#b5id7^amC2f7EfREhrPW0o zH7P?Pnf@6swFlK+bSH?tVBNbLKw{vVsBOEy7R2<=c&Rn* zMRjR?H?eG@x%1boV>|y47R2=Lr8Q$*zy70=8b6#X(QxaDm6Be{5D~=m&v>ad_hZ-B zI=M@^%;6dz?7PJ?8%;F#aQ(rd{sZw+YxafAcP+~wjt*}jw#7XsjSph_^wL&U9ckae zt=o8L6^#k@H{#=uP7Wv2KjWqLyxNNy3--RWw6ysqYG$pOXT_usC)1~w_5-ySbEoj3 z-?vxUD}Gq~aR}2V{)jXVfy#d>YL2I`)+2h9u+=YY`(>M zU*X9?O#h6R+PQDcHT!h#BQ0JJ@0;|lkK5PS7{v7NrA?>yvRP^Py5f%T!eVoWeNx!* zAf|uDOYOsIFREAftxWHR$BE57YTr#h7{v7NrM;~7@}TOd&;Gk2&Zj;v+;YF|2q)7& z$%mS-NJBl2TeV3;-D2lZ1!6M{uwW| zoQG(9_+x%TrhjS!`zprAov`tJC-!&h|8M)--;4OWE^fc9{%%))O<7%?U)JqAF_V?? zObz!_@vq|i;+0n`xUw@vh2x95&z>7+6_oY?aZho95TEq# zr7iN@z3%f*?eJ+I5DyTW^w1}n@lt!E&o$@UKG%HO49{G1z7pp%e&`eIrJerN4(Gn- z?zK%CCWs6AnLf#km)iR0#yLgfi`s?dr?I%W_`VRI^zWt3HZhZPVSZUVm$cU>WOB}l zP1@*_%y_Atw>Khk#MKIR5oy0_+RMieg!rU?FYON#GFc`)d8FMX{=uI%`Xn=6YTK*5 z6jPa)yz~_p5*G^bN&jBj9%?VeR7XbJR$NwW>YYBxjF(!|cJ6*Awat7d{@LG_=#%WF zReQ5LDIKPq9~8F`n{uX4GUKJTh{~gb%Eh!FwST*p*t8$|BztMURsCF0J(<2~+Ri0E z(r+H^5#4c8DC4e?3;jF;NHDwARA zS0)XnpLG?RJkn<<2jZo+km_iZ`nl1Xem~OB^hx&89#VVBp>fC5(I?`2#GyXvpYc-L zQ|;v;jZ?YhXQ;T8*z|q+BztMQtG$%exNQ79Aub^{eT_cJjF;Na)m~JWuF1=8vFg}0 zZGb+>UfTHMqmxyat|^~pDWj9eh)tiRPcq}Bwx-(4X{EvRi!$P~{`Al%*-JZC?d3j| ziOJU}Fny94FSS!ldr=*ke7z*jEjIb0PqLTxik@F*^)vaptp9%PXZj>FUTRHyX`*x( zKc*ek_cMKxy|kviM5$bSR;6v?{rN+ z#7^^O&rNpE@fMjr885XB&JMPlTS+P1>x^*fh_}Zir5va;!XncrwF4Inbo%Qz=t@5~ zuIYFuYpIqsMr0b|=4(3MdOWOUjqxG8VZlJFqwJrRy_a@$oAFLZX|0Sy+{8BHt*8fE z)`$vW`e(e5^i7}7S$oeww?(xH)^zde5T<`>_g?PjZd3UusQg!E9^(Eyu;-?q zRYw=o4ROD!)T{a;)g4)N^w_FmfJs_O@TlQz>3TlM06arlYNs`ntKf5uB~Gu6@9)H<@OsP3K-zkScZ zAf|t6d#&znuSvJp*)Xx1^JJ$k_RLpKI^S)q;tUd(6|dV^#Uei~`%SX%JF%KYZMruH zIblVMx=pLbxRoc5bV|Ni#GO*scGFEBY2_0y3*lpL46-6+A18Zi<=@>Z|Lx?zOQ$Yw zXQd(krYb(}D!!?-neYJjmc1+c3Q9kX+{WFGn})k%R#RWv^p#v=;IOM#}*H?On87Fmwg4< zSE@9_qIOvG$xgOK#hm5$4R9;Z8|bW@H_+OszFbKEb@ba1!VQ{FwjPoFYS~l!#F_!_ zyh7Jg3dsLC^_?tA!+52^Z~^f!rHyRtbI87`(ogN%O(t7w<`#2$6dGU`SNucu+j6C! zy>;$DXN-7T2!GsUvNKioU1U$~8vSi$LH!-kFZw&n>-rm#6Z(75Q=Q_h>H2%@vHDy3 zSM)dMO@G5J$|&#D@_8L59~o31ugi{YhRilbEuZzQ3)T_&(Z%{ZYQ;5DbxJLt>80xF zEdK|WQ{Jgq#qGGOqTQqCI_KKr;z6ALL|=Pom0?c7EF&FiIS0rpo8KxAbHcKWvmDM)p#(n7g zcCCX=E$2CP)W$~1=B8{|wq(`?wVcoVmQ=zXH9x1DC)3?QeUs^7U#6CGA&v=N?YZsx z6852aIo(1T?{=x>9IR!Q()NuadEA=Ct~%R?SF(?u+h1+<0ku_XIcL6>xwP9s<WsZxQ1zdNG;bvOf&OBW?!b3YbcHhY{TSMb|v>@;c`wzl@GOCyPek@ z>G{+&2hEu|m*yOsTCV#zS4a5-l{xEzTCVSyX6A*=zDzCGh8z>vhRMBRD!H$!{iIV{ zrIu^b<0_wFDxWE;Q?3QbTsu(9H7wU4EL$?`f?BRynP%pN%)U%5*Ss7P*f+`S%hYnM z%{GsE59$|OGg8ZSI@eY#TQci{TCSbB9_Jj7%=sa;Tst$Ib7?Z?;nZ^N%y6z*$XxGG z%e*k0YeO>EmDFf)$ zJ^eFY@{gG!?JjGJ)VPo)(xsMZ;Jbj_N=M}hMK*t^bdi}hYPq*S|BRQ+^)j{GTVOcX zEM%^CsAXOl&NUsGd8C$m3*4_@zb3QqQ_FW54CkHz`I{RNZur|pYW%GBLoL(5cO|TA zGTS7zd?!NxjF4b1YCqI64SeUqx+XJi)N=2I{uwWs`w7%??}g!9(~-Fz zq?UPMINL3md8C$mFWk=wdcJ6X@`Qe7ADGV|YWdEH;oLJJr(}+F2Tm-qxrF*LwM+xw zNwKcUY?IXT-4p#YUUFWwo3BR|+5CaV6Ka_TzT0A5lbJSZv8QCwKjS5HzlB;b-@92{ z^OCt?v)z)JM{2ou$NfM) zH_3dqQp5{8`L34X+!F}pz}_IW%nQT0XF}$F3$@(4<9;BY3uHb!sO7#N z!@1{1=6+O=7Vo1O&OHG#_Y=79$Gk9{^+IOdQOmtM?gw(*BXew|mivAT=bjsx`%%<# z?~dWz6CiUxfm-H;;j9-j>yBFP-ElvV{hG|aPc8TT7|wP}X4|Hgdv^@yo&cHq3Dhz# z3}?NNS$EWO?~eO{+$Rj>!21Gfxp&8K?zxeF_~*;YMB>?bI*j#{T6Du zcgOue_G>cxKDFGtV>tKR$lQ;jmV0*$=X#&aJppQ&7lyN5$gDeRxp&9?K=x}g`#!bY zyJI-_+{oOIqLzDi4Cg)unR^}7GA|5gy^vXV)N=2R`+@A&WcGb(xp&8Kwp%jWHnrTl zV>tI`$lSxBmU&?~>xIm^qxR375e?Da(HT*%Go^_-i#1edpjzp?=+8PYI&WC&dC^3j z7fo}v=ca`^i%8xe`);z2T{_V6(iYNr(b5NcR-dgihcD>7=$D`L+%&t#c#BM*jF(!o z-!f6>MRoqrX)ivcvxx2EMp$I}q&APvewuxa=XFl3w$2K^QzG@e=%YGAc%@j&8pCy7 zl)PH!MQa<4?7g%JIxpHn=S8dOjHuX}R z+jMSiy~@9{&WpaI^P&&E*mKhg)sgnx+?49QsyEPiQL?e$Ap7<@FY2W=>(kR2du^)j zKQ9{9;GgG315BTcm)b{lUi6siXpYW{))yZYzpT0=o3&)XC$)8SUi7Nk;0tPBpXt14 z8=V&ooDt3U^S|;ZvMs0cq9bJQrM>$2c&p#RedGtjA*}q)?Eg8+&a%m?R1?NZKv~}i*^3*s7nO$XIwQJSX`3uI=S9ii>AdKtvTvvJ zqSSt-^MZMFuJSvb7fsRGslqx(RZC|=r}@u|F4EaS^2azYO6}dckHef7y+`Lo=jt4m z*#|NA_>9rH%=!AwmLKwZ?f>PM%{TH#Z3g+tC_fo=UUZ{u^2+91r#R=L&M~H!pH2Fa zpHy6C&(6FPr}iiRc~PausiX6vO=UAgHW`(#kL7E>{E*lA^RDzb)Hc^S&uKbWc~Jgh z^zPK0&wNPlPxC21_59~5$(jq)KVoV}#Bjr>ecJ)h~AId;!f8z=8S{kUWkmpPxQ zxLj)M>YV3Gsp)Y_>kMbC-v;j%UGl3cLvwyr>2av#J0{NGpbdIQY~rew8duPHQ9iGK z(!aM<`JK^!*=ERWW7P6l&$?h8kxS`(!T`m!R^>x2pXuDMeoE&&Tj)IGRh<_lYyECt z&{@7h{_~=@nh*STysw=me3+9*=SA<6pI3Bl@I{>)BsbA{(M&p9I8$c}Ie*}DpJ`@Z z$ZV_Ba?Zdu&%Qvm)ZX7v-x#a%p_X%laP7^0yEpYb?PEF*X{mhj>%1s=uFmpx(^=50 zIxk9X;2nXPSD5{xY5wz~EL$?`f?CcWm}cgM%rSvl&OJD`aLgfR)wpt6O3U1oP$-@8O|a)@7Gx8A zSZ4wg<>$gXN1drUH%Kn5xT-0x_Wtvtf%zWiX-qTo zLS|p4mUBFg32ejU>N+p_yUHh@%7Mc zQ927sE$5{jbtdp(|9MfCEtz#eE$5$1GxI`bU#6Dx-hho66WE5yzbBP&$EmI6^q&_E z%zHU!uAuTMp*n4)I(=E?lTGEbLiJ8wqqCsp)30z|)LCL`Imb3OsF?jc_FheQ_D3k#{~9GGW#;MTx+w< zvoDajW~7#DbFQsWK0)Qox}cV8XRgON$0KuoNG;dS4Ch>$%y~GqTst$IYZfxsJJd2S z4CmUA%ylKTTsw0;&M}S5@sL`sof*!)Pv*EmE!W))XCEQ6e^JZ4Fr00P%yvjE*Unsz zvpmTxb85NA&Ty`I$(e6P*w1V&Qsacq`%%j@a1Z~e&QX=qdC}}?B5g9)Db#YWp8gpx z`Cj>tSyH6NL7m&8mTBO-fEr3ikwrx|zb+k_X``0=67b^g%N`DfF9sAU@X&V_YNX40Q z+?(Ql7w0)-&V{JuyE%sQ`9kJ6Pc75HcYmyFGTS7ze8)%sjF-&unOdfS?+{tnWTuT; z?%mNp<0bRiK`r<07|uNbGWQdxWnLK0c1va+spZ}s_XGLdB=gxyE%*Hx&OJ9W_oJxg zyIO{GPk_w*1ZtTVhI7w^%>5Q>xp&9?Kt319e0EUFy*q|;&yCFeC~CQP$8hcmkhz~g zE%U-~)(e?+M=kgLxE~l81I@U1D>i$B)N=2R;oNg0b3ck&?%gq*djg>x*c+sld0{x~ zh0MC6mV0;H4`jb4v+q;Oy*q}p-ICe1spZ}s!?`Cw=6(XT%nQR=FJ#sowcNYoejxib znSGyH?%gq*dv0XzM^VeYJBD*zOy=5|TIPk}+%q9_zlB=v-ElvV{hG|aPc8TE7|uO6 zGWVmX<=!2`x!xypPk>tHh2g9hGV6|7?%i=eko$z89C%+qE%)vi&OJ9W_oJxg-W|ia zk3r^M2er%#!&xt6)*ZFnyW@T!`!$(;pIYwSF`Vs|%(hJ}_wE?Z{TVX%aHwTo7|wbj zv+k(X-3tFB?xEB7_W!tt&anCZ{`qHe`|d0MQTKS5J8?hKJ>Xt!?ALvl?T`D-Z>4SC z@>}1T*z@&w6)IFEO{9ruT-Nu3*vmh)zbY-}o~(lDlf!ghjgRjOVfy#dn)s(Rypm+@ z$1uFJ-PM0#`e(e=hTaO7kCWz%c7Kz^1+e{;B<+dgsX9Y15?sFR%Xd$NwqC|I?8Fr#=7A&AZa1 zX*HncrkBo+ufBTTg!KXLJLjJ~4P0yPKf?zvov^;8w9}L;mAP)BK6;tK$!V&?XC0WV5H43^Zy^7 zoUvN-^sh$Uldv=;x@pF0yI)@v6)RqMZ^mkES}*d2CqA38+LA99MP*RdM(2Pht7;G*LAj!8y-g7__(p`GrgDKW8-K0jEz1v{+GO#;^T`2TE}kNx829ZkCcgx`tsdcLltk&=pSk> z*t^@u5AB~=vvl7*K3?+tC_51TUH(kl0`?Q@A1zG2nfK2Yg5{EWh9Dqn^>%Kl5`ch!llH81$f#BhIqnHX;1 zFB8Lu{AFS|pTA53;igOsn=&+IV%YdGX)|p6FIAd->@Sn03V+aFCWbru%fxUof0-Db z=r0q)KlsaJzIckiObmDRmxn{_-gZ*V<_%1uOObkEkFB8L^{blmt;Y`~T zdY!FVzVf76#l%&Vo)4Bz^zqAXl3h;WVG3`u>`gc2)MOt&Sb6BST(hV7xL~cF+eTEM zS*xUMK3nzsw)|^e_Hl^`dA8r@zT)FeUl!f|YR#oS-q^k5_Ccy6WA7-uanhSUt|I$G zk?VYXLw-JbbiL1iZTauBWwVdRE8dfx93Pi>?M=5*f$hF@E_0IX?K^k)xU|w=wE50j zCSPwTUnbme-`M+OE6e_V@zj%bVvQfek3Z8Z*7z?hK5=kNtcllzS9)W5>|v$Hgb!`? za_nPDr{SL#%=7h;K==~nD_~z(`3?9fsB#GSAF1*&Y~szUax>}auk<)7&!jn-V$1r= z-0&KIT^R1?x7jG3?AID@s5F~0H+)QKHgOrQpfsB_7#^fFo3t7J(Vu3+gB5PdJYa9i z+_3R;RCzaS{F^c{JkeiPCOy6VWoUSXzibT`SNb1RnH!$$uM5KutBxwF%-<2u^w*u? zhWDPu+6uwCLGF;l<#teV$Z+nJ|%Kvbc zkKwZZwrbMzl)nud9Jbw4&nn{_**J`5h%U9;vdlhat z?2QZVlu;9FH5K<=J!jj^7pBx&v;Ok7m)v`|k0~;zR;vM*w=HhmEOwSXrPdeK)5VVT z`#CE<;rBn|`VTc<@!K4XzFc#*UwcY6L;OCCwzfYm!^iz;xN$Ab_T4LfsF~@)xLSj+ zrrG}V<;gXt*Bw`D*5x$YSMHr|m;P>CtvceG&)#&W9hgw7q->f@Ubrpur;}@)c>d(J zruFk}@33KZt%3DVZtJk4()O<&UEt#)r|j(~MlJDiudB6vADi+2 zT8TYAzVO7QnkKxr?6X`c9Xn67R6>z zdb*0=XdWM%Tj@06jZd%i^-UALO5qhQIcgp<(kJ zxvsLEA@1)la}z$-Ul%6)tm^1Xm9630{<<@K(qE^B`}*tJa0#`6dzDVZ&!}yfaog~N z{x)N{qwK#{ey^uFS@Q{h8+&I%n%I_Vds)=>jwYpv?VvU}_5Uz+=3zN)UmTAHWxD2> zn>lmlG`(kUsmvrKQ{oarlHnSQP$87&Bq}n`uK7LN7}t;~<0bQyd8YV%*LnBx{Qg_d zem>{B*IsMwwRf-gyik)3_L{M!vQ|e;EmHgPcS;Mph5W|9h3c7_@0A-5!+E9npX#;= zZ!}c^` zA?AyD!TUn>=YeMI`?*EDd32$A%D*}LSqnZm{Z!v)HDwd}EapKrN7buwKCG4n{H&v@ z6D@q$=;BfQW3i)Zm-PeL^|O)O?%g3ZA#4yEQa_3pZZoR?r1-Kk!@*b ze1Fjowe*FL>WaUk`KT_1YJmHDHNiZZ+lLgXe9kMiYPD$Y?EF*pe)>jz9U0A+o;adz z`%qmRag61*?~H2ssnvyJn^<0Yr%~PcxQ2L;9m@;%98#Olt07!Q#`4)Cj;KA>R2Q4R z#&CPA_tD05HK=hE&qv(aRLM}sy^7>p5TEpJX{xgy#siDg%vRRw!#@`DJ7AV9E~WOq zxQLgY_ftLi%tCG6dogc5p-6o?GR)wQ_!ATVd6t3Ve*;W~L*a(y;}`OBp9__idi?tq zDlKHpZU6YGjZ-dGd@oeGA&>G#1Ak2B)b2~6;v;ipTdGL$MUJK*M}5>H z<+aR(PsKvzxXe+t8HLIZnY--hBg$o&BkN3~G9Eel3puiHXH@ng7iW4%Q)zhFSD^S zjo-cJ%Z@oj@$9Zgl$|n1)f^8gEoCn3IvABbGDpfZqf!aE>xA5;KRK-QMvgWjM=Kn5 z8Cn(A5c`J3@^Yn)7+R&&5OyPA=WR0#vZ*PCfG^h}!?3A+EpcgpX?*v}n&Qi%SZ=+f zP%{DRp|S_H@c^}9XYo@xi+X5=dLSlQ)`=&W3$ix8g86#TR1d^VK%HDiodh)a zp$3c|tkioRs_jRz+f)hTf&IQ}yK#=c?R^atP6<_)^DnOVdgjGHs<<>xor1-R|4c*xnsU5O{9L#ug}UZId8=L z?~14Nf5nY2N(1TtjHf@8vC{t)8^0@?WE_YYC*weSOgmSKC*|dGOcPhqA?Az0Rdq!?NhhSct4i@CW^{8`wMR1(Q#SjM zdIvEiodG)!sbh*vjC0~4^@Up)|GNFVvbv*{c*VnbC^Y|gXdx)Zx~@dN-flCr4Qwm|`ohM3@t2JKoo$AKj}67AR$)9SFT?O?mYvwz7CIQu z>1-#w!^3bl`>u||T-7mG$m}0#cg$4*`djk8t1eQ%)~he7pVWNT^oN>^b-l*ARKM?P zuJk_$b(l%!8(YTe28}Yqm+^7$?mvIXO^IpcEm~k@x)MH1; z_!E;2J4g_ZRag#ZBXleHQZv(`-aX>uf^^bQ@vqTkYa~C0xzZXfR1F80ay#feJ33#z z{$VLEZf+w!ge_Kc!W%zFht>trJa z%(N75YR73z?+fN)CyV0+e%7M4RS9voa1}q=)nu!qebd4$P*HXLFHiggU{F`ew zG0AQ0HJfzupi}9|W=+Q*I-728)^vhM=iO#ar|#pLVrs%pjmd&PHRkQqm=>#Qi_=?o zYRtK*mLf54pT-Qsx;pLNr!fb=S&5?0`!uFr9`U)s4{6NjT9?$SNr$)< z{Q3AXTrJkYs4=yS^VQ15j2biS$09X!v{7TCOPw$lm><*fwcz6sW1TaC`(j~u_Hw)V(2SR6gBF`;8N8{+02=RRQOhh!N#emTx9FcMla9jd)4s6Ab$waYVwbc#bKwO3vC8vfJ+b7+YzBYy^9F1up&82Lj?rbl;X zfprnHzj-%C>+%M3t6L8ihIN^NIZ{4|QG9H{WNn7;Fvw5l7xUQ3jIwa-{bU5lz*O`VoB&IR^nTC2M z<~jVijCv+!EBtAQdM1X}HK0zM#?ZQUV_y(M>v~hPigWCX6MqCTuZ1f#hT>Bh`>UWU zKA#ydnS~8m!M8YK4|eO$f{!lM;(QQszJY!Eaj3OO?AwDiShkd>4!05JgX=N_?v0cS zBl4At{eD7Ni>!L}*pD5N{Oo2k@hIq}n)5xH`_&2 zMqp07Z^HIpSiP4W5vyO)sb5BPb)*Q8Dg&sBIq_t+-p)c(p zZlitfLH)|v$%b8#y^hAG%Km1ZW6j>7@9l$TyLvY4r*B=Rz-MBp#>nR(;nr*|eEtrf z-HNQ4tz7$IF#E9fn^^l&TWhuoYj23P-}z+CR2f5J)*^;g5X11&_*_E9F!if7nT)agth-rwNPDf6Od5WA~K~9O;EOScCeAL)=)CMu9Q5&668^rXc z8bfUmvl=x6eV=oi42XU@~ zy-Z9V_VRq}WztEOJ%RGIU-pCoFb&ZYa?ulr`4hdx61|0(3CMdqdK59u&|4hPTZo~* zZF{0e5kqz+dK58auR)I@CLX;`*9kzc({%#T>quu6m>uYuuh64NCsX!J()lC(jFJ2y zrVzciIM%fXOat^@TGul$V`T3orWtxT#fO;hvWFA%Q}%FTF5@hqI1@8Uo(06HI17HF zM-kHyXUa6>i~56;|R^eCU7*34I)-Nf{h zXZMWy$b~$+mtvo`kaqxLF3LN=kcHN4oxB6|K~LC#yM%(f1TpXAU1A0LL!rD&_;s>j zpXHr|@^uz>l8e~y*2huj@=g*0#uj&*skqw^Geq8P9Kh_r-R3j;#^DKOOhu16fFAYn zxEb?DUvfZS@=<>&`RG^m!T3xxV+FF;sV9FaA7y_lIA+EUqwhUK-+S8tpOeqsqdYJq zYMm)|ip5nXVxXk~PM6VRK_*rBsaxzFgf{)G1Z_{Csc`GiEZzW#+prQPkYf`vuRz8pcB0}TVptM zoHu9x))^zRHJx1elhc2*#DK4PoJ{KC3kXKdBhwG-0-rX9r3VCl4wp(NRAn!?U zO^iM2rfr)I#h?c4%MOV zPear*`STP0_@kb6f1aV9iJ^6+VPEL$GV7c6dtDE(FNmS|Bw&B(@%f4UrN@W%7crv| zXWFO4^hcZvuuqBUhB!~fKBfKci+s_3Cng;EqWw;c9rCpY`#t<=3Dy8LK)r?j{h}dk z>L;nHl{QX&CKSvT*`sJYPWC0@JIa1V%mB=F9&-^BD(51m!T-(WFMUo2;{~5z!DnLJ zrOy%2SuWR3j2~)))=vLs^apBV1J+K=0mN`MVn|E@YJ*}(Oa^M>K4M7g%13Q9KrV>+ zA#*`6pqvu31+_srC8nIL4PrjY+92kZtPNd!O<1*F`n2$7cZc4lxuT+B6DPYj&ugeUPsI&^tw*yEyN^$J?Tp8 zB4&fHsb>;ni=IjAnhj>C?7fL#LeP8PAU^bOb^)^YlFlO8!%4?>+d<NvzvMg z#b>uXyNOwivzzu8F@xkCfOKZbI{?MGguDX~6M%f_`~9fAOAymW-X$pSYvi4T@_ts{ zNr;J*cao!*%*Bv3yOhwpM4tD^LR50wtsGgG$Q5^UG2y{ZF;4cM zmlF96@N^ftJUmfjd_KEqI>fXMGHA~d^Jt5+au}MVGqwC}!`7rEP3OPc`G&+xNt(_# zi#)^2fF!Ph*_Kttke-*UF(0PZF?_U6(U_y(id@xA$r^Jnq~K_auvCrl$reYyZBEsg zyAQ05cLt~OW6%j!vy87J(zqM^iEoxq$ERsJ%Zol5pWRH?m?OoX z8q2>+*O-s-X6oLP=^7LDsDkP}G(%&a%qXSSADf{umxokWt@~wY%-p&)wR;ZDmA;~) zX46~_2kUA!t!o8zk`l5towv|AyChrFxdWZYYqK?-{qV=4=4R7e@aMMqW{t58`kw}{8o**jCBp~wpC+3U|oG9w`w{grWG7jr)<~a^LnE=`oVL%7N6{g*2Z#4 z+coB4W*I||Iy*I{65{;zvD8T{F(aP#uzvUVEgY*JK;1 zQzh?~!lXa5N8VKWOMg04zoVGLpTmf=`uLa96YC9v@m1PtkV#W_H&nh53#JDf4&CCL~YRsnhH5tX3m|l&M7qwu?$U89;H{-s9yc097K`TaiCnh$om3Ge|X2{MKnoZ0xr`DRS z>rfr)It@^Vx{eL%keDa%=Q-+`n5FQi0_vHV5Af$7)H5-(F4`Bw(7KjmUl2p2PJM=${-}+4=utEtAp24P_&;R7BBr98itzf{ zr<;r+F^^>~h>4Q9Am**i1u^|l8=VxG(1OUwn?!-;t>dpI!_59~1ZL7a)X zj!N)@%szSM5|by-Twb>Iwywy4W&YJ(>U4H zeM~(4d&=q80y|!r|E3i|G@BM?K+KV_xN8!rpVCds#Pw}F!yqX z#&oM;G)&o&p)nVY`wX*gWNM7{5@D!tKT~6xHrr^}c0N;Mo~CR!&}Z7TcF)xZHJf~H zetfNF)7nWVxYmZ>I(I5=_^qQf-k|B&!XJ;e*(L`5Osa>!>7dgA{><{s)|gjLuMMo- zMr~cQu&(npH)=YuSeJFbjT+Mi@tIe7lcv)h@frSkqo(t|pAG&7-=r}Geod7@7fehP z;%wZwNz*YP&H;rc#u@qAGjOw}(;N9Ji8G!2`F7JoxgWJz)2V>GciUoO9!;32{269q zdLZwsAD9^WUeoOy6GQg3R1-tCi`f=U=Lzai*O`Ob({*xCle$hf-z~rW5j{5l_GjGI zt(rd}i1U-NhZSGBuJ{KB6&33upPdIB)z(GK$vJ10P#K?tOL7!H8K2Q_&uQ@?W^}1M zh2l&(Jt3|r6lYDR0N+=Wajw1guA=8_WR*LLp068M?kjq}roMQn=y}iXcwf1VypzuA z-cJ=h?}57?D|-D@{_sGviAinpT(hZuNJp>3_0Xw^I@ERaI;;VI*2{YKhd)%$#N@#r zs%L#&v@i5^(Y_$Y73-pXLCh({XQJF+hY=rre+3{uw7-aXia6{0G!b#8eX8jo&iX#} zM85R>eiZrA_j>^HMf=^l3qI>c4OB#LX*V2yN5kHMesW@cNmds&^%-LBpf)nmTWEZW z>`V6GRn$gb^ebYxoQs(KnClUG3u%t}zq#(h=T+z}#6-jA7Vw#v_R{Cl&{5^ubHMD8 zYbRy|*4`OwC&mx8K`|ueFlvKhNK6MAL-MDR%mvNmi(Je>E{M4xb3sfXaylEmg_t!m zr^F~A!h#4Ylm6%-k zGZVc+3p)nkR_M7qsoaCaw2^y| z7>0c9MQ>`|m+hhC@qAb+YXkQRBMV`5|t`+jkC8i7FGXcGYm?84)CZ;&fZrWeO{6d`deYzTP z*7vEmyaN#9DDM)a(-Zm9_xpF`i+T&?y}i7XP~NTOorLC^jJ)?o-#B-bnUlJ8!tLvO{v&!oyHGqXszt2iO*QTTP-(N zTAF8Q<6jQHGx(TgYU9pJo*JgUF^#(y+%*J$HH}}ae$|loCR5|@th}M!JxHfUsPrqclNsr}qE{(8`4C8-oX=YhUI z;`y+{W{s!sMVmJ?jnh4$QD4*eOyo=FU6C)HuRbaJxBkF68ChFV|d?onl2|t4{K0*3PIy>dMi2o1kYJobZ z@%o4Z)j5sF$T-k=AH;16;zr|dWZY={g^V+e*N}0h@xI_^A}=~md7<$}GLJOAO6HNq zcgVcc_#K&d-Ty4qx$ZyJIq^ZVu82P+>x#z9B0d99=QK|7p*p1TV8k;Kbxz|Q5zhyx za~h|ALobdxr*Zl`nd+S8y^DQ8Jk9HkeWCNw*hjj4Ik}HWXP?}6q*D_6j_RDo=U|_b z|1^G9?o%4)*w>Dza~gjs_chIX5`BQ`oaX%leP9Oq0FBp2-=I3D@tv}7(D-rLXK1{b z>@zfOC;O7lUqhYK_)XczXuQ7cW8{w){GmE0f4;*Xy&e+bKh+P7KaqWs_^Vhi)j5sZ zVZBsuG@c^+Fpb;FK1}nLk$s!yT_F3m*^xlwwKk*Jih+?_sXM^9FLx9x=pM=aRs`3@`$(SuIKXgOK5N^}%dkg(_P|7gQ8ML*%NU-%G0><#n~wF; zvp#q>bV;yLXLdXeH)hLcX*^VF1~u4YY$?D0{}%5Zw3Offe=Bwv_3!zc)ypz&l;8iS zae6OcFy0GL)&(11kMm|ThRoCAe6?zSHlfKpZaXj7n4Hj`^*lO{`%MZrmKxZPJ>F^> zANP+J8($ChzY`5_@$76oOL5M_vs3YG{)UN$@nAy0+G z>+enEKip=RTQ!W0W6|8N?h(VQE1|46-T}{d%P=gB3S%1@VEp0^qs|1`XBqYJx226n z;_01n(s_D%C3}kZQ-YwQzbpL~I`+L|STF1y($N_|=;-65Gey2zO**SurZG_;@0&wM zfA^epo}5Ty_LY(}9i1Var*b?WIyz4}QJ1pVi-~J^D0Jw(^;LMko7Pol@_P1T^cqcP ziDXFUPdQFHzj^4a|I75AJLy!lGTEdv#CoIlZz!}bogp24oOJYeCBJ}=_FvB;$sV)H#!fU7vtBesmK@UES0}GKsvLpty3vqr1MNN z>Cl-a$4Mtj=b^Ld_W6gv@p}dI8xf?Fzx<<0^^*=AogtmOa-4Mh=sf9|t!OKnV}Fs(MEvdn{dPn;bTSXO z6STib=ht!*Lpu66=}gdh=sdl~MRDw9(wQoMV}W!kRCW{ZvENDOiDXEpyc{PT{dX$J zpE^H1wD0BGLdOih&p`jSLOKzhyP9n1)CNQEypzr%jFU||#B1Zwd4Rc|q92k!LGrg9 zNT)RB{f2%>{@j-g>FDF6qw_nU^8sr&qCeY1X9U(uzm>5AI*Eu+OY~>bc`q5#Nx*mu zjFXQ3+ZuF!-JM`18e8MNIh?0S@?ENQoSRE#Sc${;Lb)x@L1OH{tibuDkC*#$)R+kV zG2SU7os9<$so9TB=b*QI$BK0BoIa#>I)Zoippz{bItOpbaXJURzz5)6HhM=)?eD76 zc}o6Fk?&!VPVX_UDxIgKb3`(v(?gDvPLSkDC%?a)E8P=Fr;2=6i*#ySZ0t(+1kx!v zz|NJvbj76JlW=D=V^DR*SG4sl1@JEv=5flcco{E*)yVnD{0dG%KoLRI{vANng7XE zeesWpS%1@2?df1*!rL5HPu0LZ5IVOU53Ai?ni%f}ht;g{ru*CR94qm4ICwB6E?SAX z_Vaij%vJTMmB`%zCUK&{VwsB=vHjIOr5!6$R zZHBWO%=2cwgxUyo3#L!&9%4{ijDvY_-b<@(Vty^{r`g0zkLYU}2QwQwVP|mWf_V*{ zW*4v@!FWMurNB6tD)47ze|!%O%m(}W_n2*N#!g<&MjkzTLOS6@1u(wJkfYN$oMa0bDj%Gax^11p}=m@5y48GPI4a1}bP z(L)TUd*ob{8~`}tQBL-wHkCg#SGPl~QH-uknWBX#m!KPjYR zmNd~Y#n6fsz#p0`KB5)V{dsY$B_n@`$q66MJh3ifzPujJ8e(1K^RJ7;*fgw*m{Kpo zS!2YqyUs-eG$Nv96{8H{=+W(@r4hED|$|$lP7CKl{!=#?p|eS#4vFb4 z&nD6_muDO?aX3@jqn?QwAaOhrGouMXXQnlmBh@KXD%_<<(W%NFL~w? z(-LQQAbJ8Zq4MmeeVQrHZemK`Hr)Y;DU^2rVy@y2K>NK?)%WUK3rAtOVGZAs@=3k5 z+d%|uU&Ct+c&)Z?<|Ov4LEi)8$eW1^E0eh0;MZ!k0nNpt1xeg3=)Ky(r>Su7i|^Sc zd{P~)nu_M@k~GavW(MsnCQY}EE}Bi6KbtF>P4j-lybpVB(dNC2dFOZ8qRs1wc{}vq zqUo4n-fAOvY0M0ZrecHFE{$n3u(_B#d6&j?>snEC{P_>h##{@VRS<)o{G%}^cqLJ$ z;(m?sD)U6G{p_&D@WzkS!)Fd_Oy=IF>bl}bH0JBX1U2}rsxg(`#i<9+sTwo%aH5+2 zhv4PlbMcR#jgfDT^GwWj^7?z@jnl_@HLNQ(>btR3g%cWc*(Vx*W1rL*m&q#(Cs&`; zn5E%M4Lb`?^3u?u@A(9bIi)dV2RonA7_y%)J*6=Pm z*9z%aLnnK4V-^K}h^c4Sn2|r_z|5>;$L!$`F&o0Y*%YiR70lj~{n!Dlix}T#{nyy#~ zbD3i<1$-Q0OKZ6S%}asess0Oo&+|V?skRx4(a-{o1dsFv^a!m}ymU6AffoevN1J#Tkhd)p=#9WrON6Z;nd&K;Z zwMTPhqK0X260=j*FwHeU)-dU;mwSPjKjmH^of+5*t+5w~se(QA410>0A9G$Qr?97p zX^cI!3ww$fdS96KW)2v#X>Srk_6zJydoX+D9w)|D?r{e&LD=J@Lri7#iU{mYVjjv~ zK|1TvD`;;LV>T&4os4y7CLMXNm{T6b1XD z2F{wr*r!pR79#uH1NCaya_zVE9G2fxulHTf>kY6J*5~f2&9ayCM_=)-#DmA`zTL}t zo`;246w{auTNuHuzL<-<@lDwE^a$*IOHnMV5o>xVg7=tiA!dg)WC?*0Jg}q%n-6|C zc=|2A85obpczQKUR+MStQxBN4TT-W5DGRm({#=7UL5Iv)Hs;-ndAEQsC;g${nO8m@q8sk<_Mp@;Uq1kg{e;U#% zXKJ?VvI0YQ^DND7HvNhAJp|J1gz=1b>$UNT;QQR$VB(?UdobH%Lx14Rjhg*-btmOn z)lHh+1O5~)HQ5Dwf|V-QOg4RIVB#y2{oRoGd;CO=4I2Lf^N#*^&u<;}uc{1!K8?F& zp8Y-V(odHZ-JcrM^OQ{K=jy`i+P~wI|1_?zD+)ZVSJ%EOp4Y%C^unf^_X z?1|F$zSTyoU4zd$!02}9pbD(C%ZhKgk|~xRL+#tRvPHhjr1o z3*tuWB|A*Uf$R#1PdDV9?06YBvMXYo@=kWRj5FD!LwVQreUKL#_m%k~oBW}?ll@-i zmu&hsbjmwDdk^(c8TCNp4zf^7(?UB9WUH+r@=>aaKJkn9?=KFO{i>z3?4 zF;43udz7qm((EYfpX^@H*W+V`{X%i0aX0w$9{Z^IV^#IM)gS+^5y`*4C{%~#bY(p~ z@HruJwCd$ZcByQnmiL(dvx~JDz<$oheH+Zr<^$L_*nZrZfqz?TqmRrx) zYUwk}wBN`Ix@RuB{T0S%JjU;O89u999isV;0;6Ixs+u@(Acp6-7AbAUHx#>K!gw|1 zyVAN9-bo&V-;%=TW8d#L67|pF-;Oaa*$t$9CcmAyS>5z+qi12?fW2yrs+N$Nqx^oT z3g+5|xhxKSS6fKU{RfKFmU1rojVWj8C)t70&l52})fx>7)Y`+M`H)RT>g;PD)PMKj zH{#NY)DItG{6xx6wdgN9Hpg`_e{1_w`3`$F>>2fol(%5kg9&O?q=e(yvv~GK z)t^c|sY(A9e4%$&)~qm;C*rriE=oI~-&ZwP+PV0gQy(XuUGZhn15CfUr`zx}CGz!cg$!!FS(6qAB>v8c=CasY^ByYB@ylLEe zN;j5(&zxyI+p90TI2m=0&!4U2xGnx3r18^oJW=YtSZ_1Ql7g5;rZ=U%$PpR-y5fyTNu7ou!0c zd8zgcddE(WKB;cpkg3`EQ)jEeE&o$!{O!vVN^0?V%_jf7k2Mh`;eT!{?!a=5w3cA! zH|kuhMfa2Zr+IDV+V2gmB)sr!89W=G(Q`riWb5%HoANaWai*B-{*X=n{6JpF*7HR+#ded7 z`6I-9E^^TWF+YV|td=ovha82-T-aJyP`(~m$tn!TZ>7S%RB|3`Q7oFPMHN(iob1bT zT$!3-_`K^M)~ZSb*KHAx+Lq(#EvNAyzbxYy$>_EUMz`03$#uJ^95qj4pH3%o&vHUp z|6(=USTBj^C;zJ)v`lBI%@X;Hb61q`x~c43dHf~}d?O|s4B4j!q_8Q|P2*$trn74c z6M44773FMR46ENdmOE^|q`0++XWkoPc%LRGlrM6P_Me~`8p^gDTgG?HzN+L+Ucj1{ zSccDsPbgQg#^zW%>Dvw)#u6JuY4(!#L)gH}5t^O(VHB&>VF@?O$W=}~8P2+wi{eVe zF{Q5L9lWn9-Wh+fxtF8(+sD_GQM<;l!yE8Bw|`w!LMshtGw3{pe%G7BS;gmLHG9?4 z0Cv2U$xePggq5fqh?oQ@r`<=e0=IG8E~(pZ-lySICFbAZY@Jmg?_(FJEL#}BT%V2Q zImnS7L$XgJJ|Tz?+2dq<$kx|I_EN0N2kRm`3+t+kb&>4}-zvd3vSZ-e3HU~KlJqUp zcv01JS8a*V=B2#!@VKh#`PxzWoT}$BWcL;IUzr!%%oAE&RYbj6H@d8LkvTF8x~eXe zdC5I-LZw_#9fp3ns_Hp9SNoEx$K2xLRh8mA4{!Y@z#3-LdM z_&>88tLDgfeyuT0T_t0f8{Pf)df(Qbpe~p3d^;>q8LaGMe$%4)v*(kPnF0G)f**cc z{@ENQe%Kz?!e=?Rx9p(=eA|cLtBU41!IP9n{`<6jQSFk4qVJKV*Ta>a!Mj*XxnIUg zp7x7+ZV#KDhtDYF-uY2)8Mm%JQTf$(AEW)E>yT~HV7^kL)h=z^c1fUey30OB`$%WV z4k$NQas0Vc8_(%JMp?OZFY{K$@%`5(DDH0iSi~QJ8t;vDQGRKBSiw%V>fu<;2Yp=k zrzGl->~YU_YBfOnSNA^@wvhho`G{M5I-I|RObN!LFyA3t07(sRf-Sw zll`YWRlRRScu!D$p)&&UkGL14>haJ0-a{QHW2pW&SB*n1nj;tKWhbd-UZ%KRO`EUk zvC=guhWkS&s5vrj)>iXWJytqHG4x{rsCgMT_@l3-&%YB@4;e$U^|<8@Iicu#?FQ@& zxsM`B9#NuX-w1l=rRe)Q^ZE%jNA@nV^?u^B@W}7|Sng@R-+N8ZFU3~3DKEOuG_Kn; zUhec2<#1RUyOtl%b5AZ*ibw8ZRpkQs#ioCXmGkO}*qVRyQ5`FZeXkd~ zrtDb4M@#$aolH*8{;K!RWlO5*S+ZmC>;*h~g>3n3;_w1Rf0k@|w(MGWZQdi8_YY~) zvuC~SwRvOk?646H#U?qgpS1O7ZR?xnrDw?|pL6i+C(NrqtItc%>hu0JtA{9Arl|<| zqa4?5dbVz>4#Fv`mbTt~PR+#0R9gf2ykFXpbu;-WJln`(?or!{rf12fXKm?O*tA}H zwqR4fwqAOcYGD_!tJvgs~2s>AB`9&o-FLb@^4u2mr+B+$jUw0;c8ZV&5OaJ!O5O%;|ME$ zYl*)ww)JM~cUkhD=Kf;CFK=e{-IB-M9xJ>``Lf*Mmi+ysv0}h$Uv@vslDBLVEY|rC zV-xCI@c z`py@_zxuQ7j+XqSci2%&G<~Z!mb~7!B_bF4Bd1$(*FDQc zKlo!c)slNXTdw&t_K+nn926^5_@92>lFvAj<3)X} z_imUKpSmJZxFbHJc3SaOPZPyc#Ai#P6@T(7NsIH@wk7a?F(iu$6z8xK{Dgn9Xo5JW zA1uMEiDa<@aW*Sy&0}6939HLZ*g?gbm-I*$y*@W#_A%D{b!4I_UA!*)pjz_}`H5nt zd0pmT$%c>W6)#>tsKy3&u;Fp3@xtXqHI}l(hQI0=D^{K;&nBkYaMu;F;$UQX=Jvsc z|FM3#_*GDfb$MgMU*23UN~M%y!#qmzV>6eCZE^UWqh=*}-LxfQMVk_APk2dQ^3x*W z^W1{<>0Od9vRW*%XW^ap?2`O1HeYlpZo#hll;obud{KNQejj01N#3Z|Ea40OKWM5S zXKMU_wI%t63c+F*^vl*R$-_@i7OS9te`-nI-Z)kie^rW=zh%Sg_Zut9!k-(hOY#F# z{6!r64+*p3=UnnCtfQ&KzKb|$Sx!~ z@sYIxM32(+JG4%G&#fTTZ3G)V)QNwN4H8jG1RHMQ#2Y;MTQvGBk{$2l#G4-fTl`Fk zWG(U?`9JH!#P%DJ%*Eb`U)c~Qyvj$husla@?Yl_h+d=d2ghj$EHIf~C>d15MMrr!R z0-d<8#S%@wO+_ajW{vuXKgG8@@hI2jnm>*Mow%|sMnu8?H6@(+zV|WWBmD2M(}~yJ z5-0Xxy+Ogwd_rNI7=!ihsO`-6KS~hsh|h?Z&itH9qOe1J<|I1vraVckL7Y!caN!y0 zNunRcxt0sJ{wGO`bLvMI-luA^c#k+=&T`>-u1R9hvcc@YOjq7{b&^5M$X4M!yDk!&GCQ#DkqSRLWRZBD)t>ElQ+Re8gM}N`o7Ts`FD&pC3$fldB@DdR z_5orP;`$y?+t5*8RQDqE5VxhxTb!Fv|i@J&6I zi;2*gzSD-kxE&)lK|j|If7j>4i7J>ku*jNk`j{XVz@HjRthr5(B+&qV8p>Mp@&fg6 zsSVq@qy%^Gog}^=abkYfCAig(1d;0H#>Pil@lluJL`kO}Y*R%mp8YgNOl{JSWpB3R zGkuqfoi}}$Uw=z}rpFR-vf@xyzmg@N{$!D;y=^!Pd11jX;7qBt+>gDzX~DDR%+kg? zJhb3-wg+qcOG`_>dBr%f8#)IROWr(qq?itU|CJa|8Y*ls@9B@Ql|dp6{!|}h#ow$P zAPV8jckpDFs>i(u7eI`NlTVIsG8B)b&k#8-7%q>T>Uw`jOn3hc$>3(U^DXCTCv1SAwvGKRs++_{epMVh;T5yvBv&JFJ@j(e+$; zqcw>l8|$i@<;rtB5`@)=eyp&rfqT@96Uj5WvtFwV+^SWKXddOpc78GN(`%x|`3w!8~|IfgKS_~0sm^Wamfj7T3P?Uy0*}q)*ab=Bo`hFVA znd8apPFN#s_fBP>e|d1X*fl~_4`G*MJ^1dOYeb@bFk9r}!8@N`Bc_!OV*X|x-1f>E z5pZk*J95{Z=UrVRJ_d|u4{y5je&^PR_EpC+i}&ul;J_MT_GmO~*T{o=r>zlRAK^?1 z@!+dxLchgGcKD_TZ`fyzaK1Q#HTCl3%WT((`+0t>)=f{o`Bj>5?B&PCjP1&&97x0a zJ$`If5$tcPg~OUqR#?S@ckh!XrlJoYv~}lilGE@L6th@`o?UooUYdCPYC3C@>Bje( ztr4Y;OkuN|yYbgm*N87{5?lA8Gk32EAF{`>hW9)3w32H?R-MtzznmLSd;*=^5iDYw z8&BAgCMrA|$~OJcg>M^|CPpvyWsk0P;n7vo#DKd4S&DGy0S8wL=db;l@r(!09k5!Q zF7ReeA9?cRx2eMAlsEfn*^Q?qq=*4S7c!@vU3g;URM9?p0W03ajo%GR6&=08*pF)P z=SHeX={SdduFrXB<<-Kg{&eO$jdA;qtA%ey5W8H3@siG~#kMbFSq1#OLVo?#;wj#1 zOX$h?nm4Jq+YeBK9D^%a-Q#$DsCovv1#`@^KQpeMEc%d?63A+cvI&T zG5ce8wqlPv-?ceega&nEoqBol2{?n29lEhi@4NETZ4!mc!btosfEzD;B~kS8Sj^7G za{lj-Br(JQ`4jy>qg#x;dFundi#0x+aSS zL&mb$39kG}(`0e?haXckF|iPS57+1(U{8_ko1?b_~amks9w z$0Z80?e1*P;m&;0(FF0LMQ7GDvkT9#N)TQOT-)lwi+76`?Y=3@=|opPq##x_d%cvk z`?E7Yp1n%U?Hw>VMb!6J6X#lQ>xjT5V`%x42Hy6{&iubY z@uK$iV0PWvng2N=UbOx%KCb!vUHI0&<3wVco^0iQ zS8o1bm56)Zg{>W}@U1OY3H#~_GaJo$!pK;W`rV0@%y8q2mc)pm`#Q1xB|Lb})|KLz zeXFn)AKJ<)T^SQnv1(fhSE_As!r!U<(hs@Mh*KMO~M0Hld+2 ze;BY*%=eqizT;kWJAI|dkDbEYMmzGC*(*iL+yM4hZ%2MIbfq}7Y$#KNBmdB3rFhi5 z9}D`&iJ#lBLf9Yc%EIkjc<*1!1>eM2cPj(`++n#m*v^TKc4a(dK(uJEwga;`)R~VT zy-bAHYR9&XbmtX=mWoVcTjo%wD}OgOQk1Y-$<{YxypCs-82w@y%iQbAE0kCwf*(b) z#<=s$Sc4D6YA$3J&m4JhsiorR+Y0jFLR&b$Y;7P5j8SBSjitweC?7baiX+=wfXGAKktha%Ue4z zm%jL~m~tY-tNv|Su}_@eKC@VC-e}LlPj}%%Pb?A@J?xp~R!`nIZh^S9bS3jxgd9x| z7n?>zv$y81e3;`xvC<=o-M#I^k6v3SUW{JIy4H8(*E%l}qwdXPwO=~$F`tdI zV{qVgBNvI?_5m!pkptg0bdd-iG=yDT>%jl{wNO;3)0Zh*u*P86uiV*oCnrAtaJbmt z)Ri4qT==$!3q;En9a-`Q1K;;{zUb7c4U6~T{B=Q?h@aPrId96{^K~=O_pMtwg96XUlP&c>0gITAa_mbL6k%=4f$#SK!PO3ucLE z#JSMJz`y@7QxqW1;w9rFD$LO0>~_?Rk1jDyi}SGz4}MFXB=(@5FPSTR`pC&zJ@?q< z!j*r6wR*PSl=N# z;qH+Yp!JRWw;j3F(6J&5eZ%=iCw@kZ6}8YeMs)4Od*+T6ZP7Q*w(G>LBF2i6=o=m> zo%n&50b1Xl>_+8(%xtPaH?zu!?l&Z(9x)uISI{i3*=FX^7UJn_PC~pXU$N`g2To7k+uz zF!2ig`9?+L@%u1Qfd2fWgA?!5XSgVV{yg=FBi}e=xCldke!tm~H~(|E_z(TLp1Biu zNFJv3=XFLW{^;^hk%s>4ddr#L%^jlk=L(*#ylmQFQ5^lb;t%-j?kk?7KSw@be0`pe z@J4?=@Uk->J#?UGkN%uo+?`+j>LvQ)930@zcnHgX|SR8kLALfn!=g5o2hT#6wr=M7hb1?L*!e22jF$?G5rmmb9 z+V<7X!GRAu^N_E-MIz3@lZ(6XZgD-d`-W3X&cE}XVjAunUpq3+ZuG=&YtLeRM=5+{ z?_S~&?i&I4JLP;vFJXiG#=*{r$>m<+EAAWl#SHw-4ZM$n`^G4ok7@t(5}CMfti|7G zv6Fgf_l;A_419%oFYUhZyph7y={?05+&3D(Qh4a49>NFrjoUXEZ&$U4cHj7w&w24a z-L?D1*dLvF!h&wX755G2+Ff|p&Yt2i?sWkkoq35=Pf-W=y2LY_cYEe3jJVfL8_Ky| z!>%F;_d2^081I93zi_WBewJ~IfUaUR?sb0Ij0cVHD&FH>wK8Jw5#_Y^L;*PX4|ncpq$DIVZnr>^VF ztF89X?se8}-FS9853vOIx;m%b_!pics?M6qj^G~XF*Zf)3o_O%~Q7K}E{yBz96p{kedf+*9!e3L z7K~+PMeaO)bBgG{dJHSy)Po<7O%Y`u{l(Ty@Zc{)QpDK+_={|K7TO08pxJpb>$VRC5n%I z7qC8$yYLnZamV{NjJ@9O#y>nr6i?R8W0vbX^Rq3W^L8e?aEbF=|0H3zWh%p;O}uDc zk}xk7#P&X8yfyA@#oflSvv(NpJPCh?E+56}RpY!E<|@&6IQttv&)no^qVRY1W%qnK zbMN(u!rN*9d)e2GKgMSx{@Grv?949wznlcIsY@UB;-ou2(mg?Be(J>z*?IDQ|Hcc4 zlfBrTRb6@Y#&M#{t3^y4LY?f46F+{0v+u1t^S({uh4YO0Eb1QPD#iQ zo{JYh*$h^p0zQ9u7cWj!oy<;U8+g>`crob6SeBe*;7@MHi%PTnS^dWb-eX<77@jzo z&5ls``|k1Li%);%Gl%gecjAQC_ukC=Am=UvA?RIRH__D#1t-jfXTi0JD zx)r*!4y!$Q;=EX~`KUYF7}%9J3|=WL9!9cZn{aon93$M4@&7K}X8iQp7||muocZ-s zcux6P(XMV7JN<`&*B=op8jiqsr(3%6^Gjoe*T>214bIJKv9Thr*H~70tqVUjB~~0g z>BpXZ!{>7LvBG?-5Bqk&mCrjHBl>vvWzTLJco~lv@x;74%k0Itx@o0&_N@!MWz(6b z{8%9#kKt^=cQ-yzSs{J~DQsaG4{jH_TtwO_Y);Frd~5AxqFfdHviTv->s(p(Kc=oc zuE*^Ahmb7^3E8uZ2{C3$rO&-ji&V(IjGZB5Z|qA_BqT|)48|nc8vCx#bCY#^?fW*y zlE#`n>-^69y0_QwzxV6?I-Td-bKd7X_qjI`T^7vaP4`niM<)m$zd8KVS6?Ig34J5~ z9L+1OZf*SOw@4g*GnJQ3^D%yiTqJ%>9mgkC^D$aXT_pB?4(I75e2hUo7Kx)#{dm`5 zK1Q8#i^SGh-MH!7+Gw{bLA>eSo@dVRH7unQ#DmUl_!SpsB==q@;tp`$f%gCJmM;+b z*{$jCEBhPwPtF(hlf8M%nSn+RI-C04&zm2*6=Z~Vi4&*CEaVpoxbbhLd7_jxo~O}y zSLA_tqOLKQ|5U`+Nb-#rLtSR`8g0r(lqW$-~NBnc~{*p<9L-9UPkq+bPjMT zoR_-cWqh|IUZn5q%g-9#hTp(=v73HRxDV~Ur$3%2{AY#oVv}1NV>-+e$@T#})7@fJ zSQaOqx>)!$Z*ELFF;^VR^`gI@m;d%QhNs2~cRrmrKksEc zI~^-p)*8>-_;?vJF2#xp`@{LA242R6%ve$B*S>uHVlSh2pIFg)Ul+c9lDFY=KSp%9 z7sB%|_!tcWVnk@LKlfZh=ZEuVi%VX$rkb1ti-peRib%OYl^xS?boppQsD)sDh(8utvNPAS$^DjMp zji-CZiMgcbI|0nt(PFH4L3-XZ(lFwaMhjQca~93C36DmKwWQ}ZRofVy&xMO(G&c&W zaU;)ZxSSg=LM+CzW+UX>C^$^}qVf@PZuE=tF*;^O2v?dLJ=S;|X~jp1&NMgX)T8~I z<48F-{;WXfT^A$7VVWD!!|CijG(y!;=jC~P9O=sb4lKslfL{pM?&sXs`>(R^;Rh;qJVkoZFL`O#S)qwM=Z;t0*>6+?UsYmvdC z7tQBU-Rb-B^dLE(->>sA0(uS-{b@e83v6vH+A>hQqxtOS?Q48JJwVRqMw2W?{UiNF zAkF7WFPY)Hyq_qb`8;l!VI1z&SI*~BwCBH7v5(k9^LcvXKx2b{Px&4k?O+&pYW5Po z^d2m8lNrNr^b!y0Jy`d=#c&?;vnWgN!6%=6jruo!7T?i(FmZ^lF{4s%VN379%N6NN z!=<+K#>qL86+Hb6~HH@Dwb`j-izcHT9g2KGIiaE632t3G)-m|-kinQO@*_qB2H+L07 zX}__z8Z&xq?qf{BKaeKt&VrhQ$h^@icHHcXVG zeO+pvVT>FYCiivr%+IJ)HB9d7%4YZ(4~}&Z8);vc?BZ_}8{I){qJ7=>%l(Z@m58T( zUFoU;hEv@&!Y*$Ff3mQx(K2eaD5w;{z33z1*sL|eBV`1?5!BY$d}_6rHfAEtwPW}1j z%E3n8UcZU5ZnOA@yf(%XE1mVxe&9TPM~})`CHj`1MZa4WWF&N0B^J!@$`{-YHe#|? ziaoB~_~&=QMvWb-M6hjFp1UU4czAh*@cv;APb~;EVq2^fD_YLsJ+{$aG<1c?`Y)D` zuHVLZ+-bQ;hzQ{?c!=@-T&lSAV<_L&E5tawdAT_DS1_Ms8)Dq(woFV|5zjx_1sZQN zmWiD8@%+Z&0He&`DdLyT@!ZKf(D-9GontRD_`Yc&#)(hKqG_}rAGb8b__BAY`0G07 zPL>ek{(nj0%ufkCs9u0!8@NQAYn#ARX&-xcRgx(9dm*>bK6b$2MByCb&G*j_F)j^G z6tDaGaJ%&(hV9ox@ixYbuWT1$WPMsFnm35A13o-Hfn1${%4S^SG`t-vFZ3AahB>;`vEt~gbfxS zs9t-gQ=D{G;6(LWOy5MW|L!MVQN3oI2r@Q#^po|f-#f_oI-{4=&(}_dF(IUv)X&df zxv{GH&tfp?XHkk_B&2tf`Z;*4jZwL4cd4J}`E86j!@7x6q@SfT+ZbincM@KtXXllM zaiJ&87Si+2ZDnskFp3`p`MwK-k#6r^Z$OnPOxUpeU&yOp#F<58^ah&u#Wo4l8 zd2OgDL;WS}{fxn!{vQbHuL+0fTRx_p=tKS0vz?#OXMV6)Nd48VSfJ5xa){VV{Z*!A zpfR~Yun3|4O4vu=Tz>|M>D2FEH~JaVco3bZP2~IOyT&Pl{y!D!_m2<#47b&7L<;r$ zd$#~%BzX4z{r>8&Qg8%V0YH584?hJZYZPqVIQC#~?Xp zwnqCKZ>Fpid+SZ$SJHxv2LG)Ti|0(>7cT`FN4-~ygL{7EeR~BN|Ls~SE|rMj$NRK3 zq9?4R{oV+Ewp?4|bl@s6!!3fhPiSj&F1k`IyElM8_}JFimqWitv3~$B*i0Ijy;3Ay z8o;}@2sXYpC!WqZTij`5tlPFir1?bg4W)vNnQxYh4;^Omu_$UR8*EIc`^s0tWB4U|`Zf=z-vc=x!{@YYWAr^l=k|^< zJoQu{{XN+fv8!nZKJ8Ypku@wu!~}QXXXAs7nx&SB)jQksGgU&2h-=BBc8@q7XbCh{ zcrO)2FB9$;Xw2G}EL>jBF2^ZB%iG-rYri-ENlaHpgIBk)F|_|IiN@8lI=2)YNqeV1|9Mj=MQ-wC9D z&P!aOcv>$KFYOtR9~5H5%vm5hy;U7xL<{{>J}8 z;>A}dA3m-^2%SyEi_lp<{DC#t_K0PltpU!`ICflSVD#&1(1?6%Ni7cPb_F zb4~q?{NLw_+{X$00qG~zKUNs7t$0P66-C;`icTwA@ucWrBf3MZh^p(!HcG&cv5Qw8xBjy$ovd{XBaIj(fvN<=L*e6`;ueDb;^(95yMzpD?;Yy2)#Fb z*G0(u-1rh?yo(tj=2Cu6PHJmp{xnq9YY3fdU79&W)~mu(x7O zEvi@9#X-hLIwM8BCItlI=D1~Jd~^O^ zb}6HO#9@htzbYm9pDH($d^qvIn*VXRH~*sSfi?g1w!h@ZkUcQ?{^bAnFQJ9}I>MSC zlF_-42iE+$RXrq+=dLFVep~aSmh$Pn_%GYO`K-64XW`E_e9=o{JZsgPUfg$FDdX;} z59JX}Z-kX0v|1Ecze%!K^eh07gpnRU%c}+{SI6Nc$(HI&6hj_V)aeQXHYHPv73@d&cj`9%I5-CJ$ys* zZ*p9uJ>t(<<5Fn<-3>?SAH3&c$3p+V?4iG#OYwl85n4*dgY_ouEF$9vf6A?hj32x$ zdCXDkEp7XjVZGq9r#@vmKMB>JFysgPjET8S=W}_HhYb0=M)}Vj`G6t+sg(cbukJDA zKZEL+W%q~;r#gmFz0ybIGEVh^_7W!KGUy6?>gPO(QPX64)@S0OD`4mWHjWe$c ztogIF7Vyvyu+~)!tzG+xB@8~C{PlZL489Zb zo>U{v18aNTFP+I=_Y3TGzjPvA_X~LR2>gK8{Q_S13wYfx(q8ooc-=1_$Cni7m%)^0 z*yw%%);$7y-8(kKPgVUgaY_k+erZhg8gjU#(EW0462+tX1w8s?9rX+Nbk#55b-!FC zKAigH1nCDn`lU1V3wW&SIrYmg#Or>!LOk-2MEwF@_X~L4FN2AntojAK?icX7U%=~r zfgjy3;B~)%*Zl(CL-h-I-7ny0s(t~l`vpAu<%NpBIQ0wW1J;FpIZNw>eU9oE@QX;d z-&4OJ4^h-FWoZ5&Z|Ii@>KEi+_sb;8Kl%mv|3r1v{es$|UohW*(Ie0;>bOw#4*12Y zU%&%veWFLSz3vy-qenEa`vp4J{Q{i>Yd!0J0k8W7e$XRY|GHoD#{N(C4r0zH40~Yk z@ToDLt1UP{6xITWlNX7<-m2{V`yAt>AR*?_eeOuxH+ZsHn^(|=+{cO*=DRF}a%_Wa# zIb8DM!f2Ib*ncki?>8+G|3Tqm)9hs3@ho7>J&n(irR2cs1og zW1XKO@K1SLOnJl4BA=V7?!d_NL8?12^8b+X58PYT1wXrw>b0Nh4qTqI-1lqhB zU9d~?cm?sa`6=f3 zhvbo;>6_L`-aTffxVpcgdHUPv`Q=zH(N0p?$}!U&Te`e{`J*h5mbH((l|* zJb13d+bFS6#goxHR(zoN!4KaRD+W>gh;v+8oG3@@1>eAKo?x_I@OfS01@Z&_NLIW+ ze!%Avzm4*#dE^uP81jSsgRf71DpLNzr_*!0QoXD@bxWb%z(Zq|NN?bQ_mSSfqb?K3 zKX}yTA?Xb~>iCr60sk}A5%GXW-4Q={)E)7^BR)mxts3!KZ{W4wz-zr}9{JQf@~QpU zQU0|b=uJNtdehHEy>y(YuZ|OX1F!W4Uh571wcg-g>kYiG(i?bS=nZ@sr8n?eZ{VS~ zOQbjOT5sUB-oR_Uf!BHi551vZz(a5LYQ0)-;I-ahpQH4q`R$}P@Y%#eZ{W4wz{3yv z9sCB;8|DLe=neA$`GMYaeYM`ehbX-vZ_u081N5eKrS*2{SQvL{87@AxzR7{-RsL1% zK7CE%{2!x)-Tg}vdmfJw%?_TGc+QD@wv;UC(F)NNgTPJbv8=;cNvz``ML^9a} zFJISEFy*I2)c2yQ@?WoN{le!q{$Cw2O~nJOl-XR%&j_(UFnb$);mLwm|6FnR&`1lD;5M*fjc_(xsf2N?B&e_&llVANX2qwB71 zpa0LkS|=pmlYWni4?iLK z{n?2ihi$A+aKI9sL;Qw?O^F2^}2L#s7O-r6z>@>;{hL=FrqO2x2_Q~ ze(?Jij}oQSdRH2w<$A&AoEal3s{C|VGFBiz;M1Fp6MHG2ooHPlHsb~I3I0_2IGJO zdN(M&+0c5ONpIlyP<|RIeb%A;K%d|vD4$yA&nTbJdCaB0;wIH)1?fL>E*i$C7{8YyE={B0V4;*dJH=2j4^KA3XGi^@86{dc%6b z$C3UUQ+~jIA^l&c{D6m^kx%eNl>Wg-k^a|_{=o~<|L=sgJ@gO$>kTeGQoXc)=wJIs zeZgz}gGW5jKX}9s{ewsR(7#?U^adX5h5o@OEB%8`4(!}$khoms8&0e`RFo=xQu2KhhKmoYk4qdoc%(>va8%+dQKQA> zCr2dib9#(uc0x#;=rdN%0r&)O-}SKMtC9Vn<_9I7OMcQk_e(s8{QJ(>EAbL~ZnKJe zzS&begNpB#IEUio{dP$Voiu9r4bT19wUBSVvtyzCKGCkw&*M<~9b)A_XF{98=eGDc zpfH~2_Wp%&9$M{J7(e*NYF)6`>xCbk2l&_d!E<%q5Rc9$;?#LY{N>-#FC}m6Crp)p zVDOa`AE)fWHzPlns4l>J$iF?+1^8cj?nkN%u#N{9abBUi06(Sp-6?)xtP5JzJnEwD z2U1;tb$)>1A9(}DbDL6KfDzANstYjUG^j4Xx-P&+XkD7GN_Eusi>bca&j3|-*w0aV z0Cpyw=y-aQejHVt38X6>KX|<^*z5Je59$Ix{m8%051y;@hIo+A+lLJ?mcEy<4=?ha zzZgp2%ctqP54<<+)9`%<9vI(uw}{v02{y!+Rp$xd_4gh4Uh4Y}{CDa+0el*L-{E@! zy#Bre-{kAJ^91ml)p-K=*Xle$^Z35gJihO=AAH|wKlr}8sh*4PJMefezK_7`^MwBz zeTx&{ci{E+9eAv35S=I7ARga$Md^ItEAhzBG&)ZJk9}-QI!^!(oJiky;O*$UM%!1S z?`YV=f0+8dga1+LJOO+U`fln?-<#me(|3A;iU;3!1r$Gc{e1^}{e1^sf8T+Bq|Ot- z<2w%d0k6*!G#^Lbci{1T$LKr(yeoa*Rif`Z@ayTh_`XBl!qs^K@~qDjz?Y>s@%;{7 zf8T*0s?HOj9~aL9Jl2KtE5tKionIjy=ndyr;9FBpaDD|I80QJ# zORMt)@X(vKhu(001zzh7_Rt&7H^4)0IKKj~&lA9Fy@4OA&J)0Ey@A(y1Fz2$G>`Ku z@cKLfygpCResG=u9_Lrk8+hmq^8vg*PXMp=20mDwCxD0Ev>u>0oL_;5-k__LJT9u! zxBO@N{soRx=Lx_s=o=H?zrZ+8!1ph(K2HGNpw1J3@r^l)zJG!BcPOwvPXN~E3BZfg zc>-{4b)K-4u>Sr9*5?Vp`g=KW;XL7xQ&&+=Jm7w~3vE(EO46Er?UacUc!Cje`m07E}Gp8?joTGp?wXcRn4)Zf_NVD9zA&>!jF zf3|OLWL>E%%5In~`RSYMNeq6^*V>|ZsTsnR?2RLJ#EQMsrTr#RQ#`#kS@H?vYKemb zCrf^ER(0XoWP+GW3+?ChC?dWn z|20Y$k^Zr+8(|;KQWOu?HEHk%vjN3}I3qv2GFz$mQ%=7$Pf`4^cYOWS#Cnmp;KfhO zL$qGlf1H$OmZ1EAzxyKB)cN^o??Y4PIk)lyGo11a`@9nmOyn8Qji_~BV)%!Bez7^y zPafHCcb-$|KZSlzRQnGd7gre1x&iT$4@Eqy;-&orihr8N0?DUR{JWwTNc&r~UZ?#F z3)efhLV~oPOZi!KH9^`VKmW8^B<(LyKFh={l6*(XXTSV!{7TCC>LcHH;IB;*rTt*4 zm$rXM_0sl#Qhiq_|5d5Jca{I+q=!l>o)4slITR1_FopCpMaBOw>1T(Ee>3UrceUO{ zq_+dKUfAy?eI~2?_>n$?Ren-Q=Py(~q4RB&PuQ;@{yWnDgVdvp6OX#|9C?BX(!V{` z1$-3gAGjCs`;`8{`;-4Qq<`3Np?IE?9>6Cm{lgyddy{@1691UuKSTNfkM%`^*>BooS2fu>!b6UmkMEZY0>&+#;z0yDIzbO5Ke?a>GP36an z^xT;84E_n}d6>%c6VkuV^Jvn)&NJ*^QN6VN4yqUO{FVGKqxx$9?Wn%s5l8%KJBpLt6E;A>NU?vXyhU!r`LCH;f%Liy}Z z`iGz2DCcWQ|I$C<|49Gfhfuw=eJ<5Y+i$1(qQ8*;YE)nNM_o>m9x9Xm;pdamKb|{{ z^n?Bd5B;Ej!Do`*(C_fGnDmBz2fv^6iTQv$1d={OC_jh?I>$VLAA@v`c>=!U=h|Y$ z-B{82PJ5%=wpt>(Rn1L#uoauSyDi!Cz-yX?12|wUxjGQHXhLU~Sk{J?@BR}7-n@Z@oexOC;4d<=YSVuB*uHB`OI&4FRe@SVkNH9aNn7S=40^tqVNn1J(sRgVqZkHjPvs!1q=80X9|MU^9X8*_74=K8*5=bpfAH z`3L@m>Z0QZk9vXcNcKTgN8m~1$Cl~~pMw04AYB3XQ+j|6;(<_GX1uHbV{#UI4Gj9GM^d5=%Y{Xr~QJxeS; z{0|R)&_bN9I9qHBy2lrO_k(COFIqGu8}mYQ;of?-Xht~N`v(z5_zBrBr`W*51{m-3 zr^IiV-a;(xH&c`*KB3(Y!t1A*B9ZthvCYN*qNdV4!ad$8tcCFRn<}5%zlpo3VVx-B z@p$PjzK)zI?YB;9Dvs5Qlzx8up_#a09WVK$5pH6~-Z7HDP`!zG&c{f;cA3Va{p^vF z|CHHST>Km%{kQ1TP|Tt;7ChJKbwjbDV3_0whr5czyF(>^=eeuc>oZjP`R|81qIT3T zGM=1`b;RFi2TS`W$7_h<;|EFqSHG_*D(@R8`K4~vM5n9)($B8x)x^|~{U!f!xRdZ4 z(qH-+nc*b*uk0uNS6|>L%8cqK?I-MZ6t1iLNPqMSMu?h_QIq1H(us8{TmNl ziT*zbjf1^_KW*MrdibOIDYF*o2mJdbCrq1B6Q%vQ5y#E5N^j!wQ8SSA2LDy2 z9yL=*pRf+A9iji?479i4TU`gtota-H-pRBOFs)97<~j@_vvclb)QzXWEA!n zc->#l#OwY7ulo!3y1&5d{(}7$>aUZOPw=Z%f59I8wTto(UiTO5b$@~XtojS~KdAl! zkN*0N>I+`?7kJ%Y;B8ud>o4%=uY05)@aQi)(i?c)U*J2_ZN8GU*L6rf!F;7 zKf1rb>;3{iU-cJw-Cy8!e}NyZ`U`x9>M!uQpU#R{9 zUsm-Oc->#9dz$Jm@VdWXulo!Bb$@}^{RR7A)nDLyss4h!?l17VztAtCs;AHky4QdQ zs{T4meSsR~$3=^hx9;)gZ;zR;2-^`pP~*6nabT9@D_TyN#nNX=-lOIzbLqeIe>suO z{5_{l@3xa9-c;nA`TT#85|4j>(e#cQEA8tiTr=B-kCObz1Gmk+3rBqW+0pmSr1#;{ zX7rkWO|LCOB);O6Z+6>0SmFuI-di$_mCvqQnhTxh6=ri;3)qL>ZeF+t&=_-U-j^RlFwIHq8R8WN-)U;L2_7@EGvN@z z;FlddCihg}Qx!(tF&k0$b+u_u(sNOFU>y&zjuTkN53JV(jP*XF^#UUgUX%x5v{p}Isy+;^##^-2iAH3hE7m-VCV;R2cD#K1$!{wFEet!Z_ml2~%c=dO ze~!tPtM~OJS1ZH&8t>(`yRsSfli1JX*Az^@-!Bb5%3RcbpwaCk?2Fn@`kXnzPN@Au zj~>U_Ewz6blXsf!RQrwmxqq>IwV&*=@jS!+1pAh?1J1FlYJcKh{3?r5`^kvwm)RP% zpFI8i7F(+JKiB@b$@KmwwflWmSM8U|M%-insQr@J>@h2;_E&jB|7Dfb{wjRPOV(NK zC*5-L*>trZJN<6~^P>G5_9y#B6|jM7|CZU=hL@xF5%SQju???J`$_C)N(9>SrnH|# z{H(bx_g4Eub06&=cjl3S{(ZU*ncitm+O2^ zSW=hoSNqA+Me1|CpU+%YpCkY9v+vJ_JWTB;lRG!!*VO*Mu|s2y{S4xdFdOris=k3W z+&K0>;61Oo@xPTG3eGp-wUvI(Ep5t+(0&sB9U3>|=hS}k@tbBmSbe{+y6$|1(r1HL z?%bmES#zH||Dg7hj`N%I6t$nc7w69PezM!dW?c6|gEQ{*cRZrycb4;Acivg`#n*S= z`sgFQADvY1;GH-{^%St~Bg{$E6h6W0KEhm$Q+D;e9!`o5 ze}=v8FYp&sf5E;1^%wTr;B|k&z8Ce^9m*$o-CwYOrTPoJ?l0J{R{aHD_ZRqZ)nABH z_ZN8GU*J#%b$?+$se1~&pnDBi_m}P$y@zb^OEdmj?Jb{&HRIUlU~glXO*!^I z*h6NXYr?TF0*;As;}*4_e0QfY$G!r*KBU$Kd_%1lSmyz_o5~OHYLz$OER|2-bt=!mB~<=_ zbzOjUy?}Kcfx}gOfpy)1wH|=APJp$3fVHlGwcdcW4uQ2kfwgXdwVr{s&VjZ5fpuR1 zqhFR$-GR|Zwp4du-Cw}E?|@J2xX*BJi2K2574ETcbw4{T=N`kJ5chyK)&G$g_lXN4 zb6H7s{}}n?0b9Lyy1ds*d;XX`Q}>m37yQc(sQX#FxB1LV-EX>`c)|Xs?l;GT7BGE3 zTekmu=Bn;z!@AkQ` z`!&Q9X|2I=9|ykMn3`PQM@N0G#dUtlirO6acZjEdpE?}(fUqy!v@X|qj=xk#?!CbW zZ>%e^w#WUHw#WSxo(uo_eir_5KMVVD6we>(z7p{qR`-<##Xnu$Zz6tuKa2I^eir_* zUffT?Kk~Cu-Jjl}{NVlwd}GQd?wer0h4P8}Ch!9(=eVCjy@2)o>`^mb6K7y4YP?q|o4 zKK1=9bdLKe_?bjH*Y~r>h{wGl?ztuqKb-WBd#eegf6OuPpR4^NG59$0UyAe(9{!8x)U8`Uj8rTdVuo21@_nhtqn?sr%UywBCm5eir#D@@$OsgZzwF_ou0p z&syq!7Wte=`iGwZO8+>6U-0nXUfn+;9^B7@*ZPMaM)Bi*7W`I2%y`kU1Um?BWeil6RiTMD26zLQ50elYW{H4k#bdGrfzQ^QT zwo=`D-mUO2)AymaZRzjStNYo|x33uPPjP4Z^v(yS?`NOiwc+}{)xS}3K1|)iVh-RQ z4fav?_L2v_($$f-QTMs++c+-P{*Y~r* z!)wbqsd?OE!u|@`yhq&W9uqi_ z)}{G;S}*M3GoSLH{e)3|`YHd&o11zr^0{8cgFNf|**B>V<@*%=JE{ER-Y}nd=pVR? zvIo9Jelo}pF#I=D_oS%H0D3O?#}rR%bw7)`Y^FHDqb|Rw`&rC~AJzTrOj@tzk%tUr z-+}U@{nVnm3{?L8D4+VdmnqLWo~l$Apv+z@#>I-`p@*kn@ zPf?c{>R$D-(g|#)Q=GVm1x9~GtNU3$T9@XZ(t4pQ*yK_kw4Wf#kM?gvd4sNCgM7A8 z@!0tG;coe354$WLW@Pm1!ZU1ZSi5DFH7a%aiEkndUSsgEpV8KhYx`>rf8^ku$sQQI zlfvL*)|BTyZ=RT+k4G6}=KaLyc-)Y<(&i@89z1NW)6Z%Qd-LI{Li<~@R~Xvf=gGoC z`__bY%y_O|%k#JPl1Dt%i7%>RenPx6J=a&o6G`!4EqJcx@m$T1JG;OzQx9319$n5e z9qDfk&(5;CDZGvN$ZESJZxfSc)fo1$snxhsp*=8o*l1qkxGnumuW59qv$BL?W(_un z{qD|to+@F0$N!~p_sTaOcut9ul0Q7B6?b}CT-t9t+lsr;-y($lnVX#3pS6|z&H#gN zd1q_H5I^p_wmh;!G0A&xYs(vqEhhO(4Lk7C(~3ww>{tgLlTt+TA69ne^Z)miBc6(( zU3jrqUpf3Z^yy-t2e)}3d8~KJ{C^~m z_4@k!BmEqr{DgP>Tl&eQ{Pg*7NAj&G&;4HAmOS$OAo;fBk=u(?zwyBHTy9JMEi-FK zdpy^6UJYrFb?x}0QlWpdS0(8m{JQpKWjt8#p$BDTJm5du6qoUXZ#l)bFn*8XUs;S= zug{6kOt1H;%Uh=Nv+vMrwwUq*KZn=8U^<_d8$V|{pQ*>5v9pwO`0v;DDLbd~pGEe% zURTLJPu1%c`PcQ$BLB9kzP=Ps8Knn5if0b#0lKm&QoK+L&P!81p>sQ1CVZ$aD@p%TtiECd)uo5xQHy^_|KNdRN&h9u z9`%L)$;AJu^bh`jqzA+Ueh2AcGsOdbywX2-FVataiXS}mR*KdO9(tQi>jht+^bcO^ zAH1W|KltKG|KMGf{=o~TK|(&Jo8BZ;1NIc4<7Ni zCH;fPdZ&{9!DGD^(m#0QXDI0(Jn{qmmmnT=^s2W^ba2T z*Y?G!Ua*IMt$)O?^$%X_A3XH0}q<`?ONpB0)dY>u%gV*|( z>moe|t9)J|J?nffC;gwIoWs69>0jp``VXaf1^yb@V_v}z^uK`S8~DSdf6O=NQ0pJO zztTVWB1-?@wf@0t{e#!~2e0)HUh5ycH|107ybR?NIYotR7~P24mSLK`yvvjN4{s{7k%aMGqA=hw!YCv?m&1?hkQ8` zfcq2w*5;+;e<%9}E1pU`k^H33&y#p6`5*q}fyA%qxx*dlJdl1im*VO9=x>SVP@J)g z??@Z;WA&QfaGsBQAs<(|m9%%HpPkl_^AY3+F}(H*D)j%pYWu?H)*jP|*HQ79)w^;X z=hC9xWFO&Y!LOlpVU4iY>xCbk2l&_d!E=!}{A@hMqx1Qg;?#LY{D)#o80)i{(D?@j ze^~MVD*H6z=P5tHGn9YeSM*#bsta%d#Zy3a0j@=Hj-t8%BmT7%KQPt>t!n-q)kWLa zr9Awh{Gcwt@Q=CxV_m2VFyiS!bpb}4F;o}$LI1i?U4T(9&7+R62e0c3JWbUdc#_fs z@LJLd;sNeQ`q6PhS33Ry#HXosttb0Pwce@ZN9RH77Jjszfwj)J*dJk+k{5Uc@z31h zEPeY|8}E_St{hJ&cA4#;HOb@Z$l^Tb=MBuE^bC)USHH6Of5x+zqq97omVd`eRCQrH zch2zmwRk?uzrVy%B6hMz^Hxupjm;L1PybE#DC_o^*|xW`i9=GYZOH$jjh|UR&y!a8 zPkwxk|s^9?vXw>EKFgqPNhhnMtlUj zX**K-Y|+7uojBl+m_ zPx=fSyUY?c-zsb5>UY9Y`q5|Ub3x>K%iV_OrO!(jXIVD%Pm?~~kNQ~ZY#J?n+RV%M z9kRIUH=pbJ`#$@;So*Zt_V!>w$PpPQ@ZM)O0(G~^e0%T~yKG*gy4!4ed(dI|2ILodPjcqN%pIjxJaKiTizb5c|BSB+}3-!wFAY8x-V>c%34Cj`KsRr>m3!Rmvy!^ zUBy|jl38o3I4Av7kTqPzng3;U)>9Q{%QuxxrtSTmG9Z$)&mPEz{JShLO?MSXyT(nnW~x5=Yx6GCiTWKiYB=e+c~bRzj&al+ zNc|3<>6KQRuT;MeZ9UL*Q2icNuY&of>i11k;;l1Pzu!J#HD}OVLYyhCU(8-Kmr$dK zU(TCZG?(DB7zn{v5#I^9behnMXYapJ|lOUjuCz=I3C_r&Gy; z-+WR&cVv#Xz~@%VXWY&EzAeZn>i)*2Cqs>FsqXH^BI)xY)jjJ?g!Flg>i({k7ekzj zsP6l-OESdSo$4O;X{+?Pjq1MRm--g@9wB}1bB>pB{!aSr*>#WfIfeAu@~;$z8a*R@ z_ANeA`n*m03_az>pwH8!&kdt*TcG(%q|YhQoutng>ZASx*D>VtSL&m~L#{}lLDWa_ zVcTV#v#5_|^qS8yD9#}2Bb%lnGS2bTN5|ZYGWfKiKI#%TQTlYFevcltORoJI_4_Ta z=hEjy>h~$dkIFc0so#5FT_NLaMg4vudw}#=miqm1h66)B!>He9#LkmGO`1!|^Q|&Y z%%!%EK1-j^XfD-ibY8~kLvty&f10dOKFy_dn?_5Ym`jfrSCu|ZnoId#7Jthp%|M^f zBQj2#w6_PZKC|I+erCKq=)y0{I59uNmT!&H0)t&ODm)I!;fT^J`U{wQ0`(tK!V3Ij`fy`)D@h6E!mEeRNIb z^BTR6CQv@1&(rii>Ph*8KA+P2=&Z_TB)yOFR6g(0`)In#C*GTVsqTn#1HCu*sJd^W z_vRc`_j~l-oJw_v&op{(zH9QW?zQQ?DX8wKQGa@GcF=XF_xmo=CwyL@_j?zm&yDnc zZ%X<^oWb;d??U>7PfvQkw;_E(^ONZPzKZk-pYC|SD}A1$eaJ`ENA9!_X{P$;6)63Hv&(=F*$8S7a!k;B$^_W!3&(=mGnP>|a^bV?S%(ZU6AHv&ONZ z^xu$Ad3%>fwwuc0ItN)7x{}S(DQw1p`5v&TSu=`lN|^5fewW`w=5uMj2kc#~zp{Ie z{H*?)F7r75scckekhNTs%hKmq@)9g{6`o*yx`HpI9}D<&#f)vJXw($r?B= zvJUHXk)QUUnENGKJ(Di*f-~FLvD*u*X=g8T*J^v|?k~v$Hctb0v803~5Ab)7?qipO zl00C4=@ZS-@t9Z2*5A6EGqa~qWC0sETw^4X(nR;$rv6HjdLhDD6awk}Sm{|~|W zIs35our;RcW*)KfE!(wqi3e;lj=W+Wk0yA`B;G&2fR&uG#3PC9d-W{AhkU$D|9wz8 zxA{<#UtV<0T6z6?zBbvGfBEjBHN|EF&;De`gG(>-_=jv7H!aD%jAb6+7yMD0KfjXV zQHkuMa-8}4wy&*OXIJt)tE+J@pLf=cZC7%`xe9k%n{Vwfc@+;nQk`2@#CyOd&AuAX zI2-Q){zQ5WzAkc+2kckH)#mNi|7Sh%W;y+_s5(4qtc`i7_Hw?hWi8%2?u+%@k`=s1 zW<8#=Kfwbw*`4e1l=}%D;PWQC^2civJYfI0c3nQZN)a>e`V#IIQ;)m1C~AH`n*J`1 z^0_`CnXheMpS#XY@PLi}S@3uFHQ>HKCwRcV|HfAQ?zxKQDcdF7Zi*MbKcSMjr9%>T z3H0QidmN=t*LJPB-_Ar2*gU@H%^UrlD1Y`|9bZ0md7=mGL$E3mC>{J``hT}C>>Sh9J=evFch0ED|7-Zf8d#?? zA3D4;kMN)50h{Ryo%r1^6FtB`$*ah(|31kB_Ay0wvIR3LnV5%(|7~MWFFKl-Z}|Ro zru{JHp4lOd_3UV8V%8PJtYxlEikqEic6r|1!0PZaW)jV`&y$9-u!g3bV{e8IW*=7_ zmUAp)dj!jvl4DJvd3E>Kq3n>WDQ6Vh7{RuW&yh1q+hZ0DuD_A3>r~dnY)RU-iP^3w zXSSkw;yEv!)%dQoi8<4^*A|xj(cZ+|xHBY^{s6dxiP@4^Z!-)2P|m~*Vc*jo_Plx~ zX2PxCjz$4!dO5kG4Zl33i;4bqJMw|euin8#U$1>wp8xRMC=-3!KCJ=|oHf=&Z+dmI z=ND`u%=Xl?{eP;$D;%0)q6f#ks=_l~PnCVz^j&2>cjF`z{rGv0GY@MuUG`vl@oN0! zpqa8?v^{$5=|4^R(+`QVzow)&)zTtymhSXi#OSIdG{A{WM7#&Gwr7UE*x1 zd2J7EUypX;o0BG+&}v|KWj-Zqq6vMnuT{8T$!Sv0BkfA_cMk`f&|yfL9lyV9pb72u ztXziA{$q#{I09ip*}N#4n1!yVP1~{OuSDQj7emf-MNW( z==0Lc*t*8SCf=>70by+F)G{XCm6c|VtJ)HNgaCqx15F4Xm4&M9S)Az&bEvgDRmgOb|*9XjFCDV^(>S9Re891mUNim zcAD*28fW^E4s%|fVbP=GO}v}p&Yonwi_A6gZu&{wXYSoor4C=s%4Lc+&^lU)Zw&|rTELUd!-IDSCr=C2JV--TCVKVNrz|p*Wk4$UywT7R-q=3{^g?7 z;p!h;_}bia(%yei4L)Mp1@jQiXFo3&9{1v$)M2KwhYnkGsK9&l$d)=hzSe>Jj27le znzt<`IdZRuN2CrHy(!PD%`>GAJD;`ZK1HljhuR)GJU+H0pYq*qsl$omOYn7+z4d>zLM+~>)8m@sTEyOusz z>QJAvL5GP$r?R^DrpkGkxcpaEx6%Zu!!E<4*y;^YQioAxn={9`&7}@Ab~a_cO`Cnw zVVNIU-8ny+n1{7XH)nfdnoAwlF8(9iHS2-zUp?n6Z2-dwylBoQFH!{K-Bw-zIfvw`?=(bZN8HVW$m(r92Q)hv{FB zusrV^IS=EiS=p)XR;fexpKh@U<8MhFKL6(q`>EF7Qit14UuOlSZkX7^+zo%k8l^un zPtrU*6qm=FTsQ6mJrxKRJ>rz_vG6O>`B^RD$ZZODlVYILsxBi|97?mdxQ1L9y*My@t$S% zdM|Z&;>}y;*y5ek;VP#O>_O)bQipfWzF`f@y_GtwdHWR$ul8E%P}_GP9XfW)Wqp_A zN*&Hw|A3vl_dx3K!iqdr^ID$NA@jM&7EHbI+P4|IvNcia&|zC!<`J|^>M+ly40AKX zqz*4ND#bQ@X=mblVV|o#t2e%@)M45GO0#~4!=w%~YT2{o5nZJYwLNs$sC5YYd2FhD zFOP9<$BJBDF6Uu#)gWf)oFa9&z_|nS?6Okou=k>ljJf?Lb(piR9gFf=A?KmX%Lul4 z<94aTL-$6r<+pcA9r~;s#`ZM+Q|d6HM;yx^c3RFuuNLvlzS&u+L#LcM>|EJXQio5g zrm|^Y?@Jw?&R@)*tD3ydpX5%GmCC+ zBcMa4oZakeb31|evVZy>*7_#>jR)Efe>Qfpa}`Poyq7m6?PYZrloHtYHmbj$b=qHA zxRI{3J#=`@`vMy?vxd~6Z=;K>vwKac!(JQDG1kdN+PhjVut&3MNFDm_ILGpOxJVuP zD0}G8u6j1RF|vZdUi3|K!A4mf1m@xM4M*7Z6i0!5>6s9d{Z!FGV4sW>hM)-`i^e= zPU>(+lMSreqK{ICpNmyur!70>d%1s4M|Rm~yVRjR&xa0ATq(&)EKHL+Ox|J3SoT_} z!^C5yS(I~z)M29*R?DK-L!}PSZ8&6!x;I$P!?@TZ79Y2fQirL{td?>4L!}N=XB@Fy zs5esT5caWT4;{K(E5kMp+$iVaq*~?J)n}We4ihs=v8ZF|^1bX6WzW)=ZIL=W)WU%^ zNXsg&&nV^mMAvTyGwiI{chnnK9%id&H5O^=MIV0GeG4@i2F?AMMEu9vhmpU}BZ?MEPz9e;cZpQ_Mhe9 zs5(-IY{_R!r_Qyc4hvS^inGh9jie5>J#_dW>Wd{aua?wd+#jDTI}X*9 zI?T1PVPmJ(kvfcu$g|Ac=qPn~%`w*!(X4{hVNQ$3mXF8i|HmO6+R!=nZ?@S|hrm8p zt#Tgfdqe0D{JH8oqz-}07Ri)41TOz-x6~o<*YZ=P4uON{y9wVZz(anHk~#!lU3RL} zA@I#^QF0z?d*~22qWfO?UIuPdY`@eYuxHFJ`CbMtd+vbLA#hH~!*U)1r_bCkb%^-; zZ@DaWXtVb1!4;jZNgaaE+k8Rl5cYeny_GryPH6H$&O_jQo7Yl@_}TDkrKAplTV$7( zIs`r&T2ksz+W%8szL$X`j@FPm1P*OdP3jQ%ASWgGSbu zIs}fr+Cb`1+v9r~cMzvXw3a#qj%U7d9s(y6@%d)I?(IQyRBNe28^VdDd_*?w4}oD1 z9m3~_M@^*;fm=Ay|8+v|W#I4Hxl0`aS7_5j>JWDvLvz2EI@I>iq0O$h2Qy38lR5-G zf31$xA#k_#u2P4%`zSZBveY4PQprkEhro5VI7uC{KB-n8H4oXQ6f5Q-&TaHvGjv$+ zYQA+F%|m=I+gRhQwbeX~dYNE#Q1dYVN`SSPnum8Se%9Y;9!eduU~6%jhxlF&yA)vE zr{>`~&tR(y%|m=I!+ssvLx(-=60J+rJZ#i$v9*$#hc=fMTA7-MCk`iBYtcOXO6NA` zCM8?*X&&Oe%=Rv}HdXWR#Lf-Yj%pq{9NlQu^U$UDdh05hhxlH0Icr+OX&&Nxd2RTS z|KsXAz^Xc)w=ar{6+}=pihxA1V@Cwe*&7RD!;S?-Y*=D1#Cq*ru^VHQSc$=gT~T(i z#28|*CH7$Nii*VUH}9TZ|M`ACPqK6N%+A>}_dT<_GqX#YwujYL9!=Bsa8>qSX*OjK zoo8N7+obGaHJ=M<+8$mqa?)TAF+Ut!``@%K${xn7c#-x%*+bsS#_ePeu})e2#K!L_ zdzdikQ(Aknhkw%iaLp1YzEIi2h;4cJ1+s^jA8LNs!w)SyxVDG3mmYklvWJniO7L{D zhgheyZ0*6b$sWR=xu8J_{sY-Vi9^K?9JYSr!nHkI-NA*!9-bx~7IiJev&kO5r}^Q# zlmdJ|*~2|FKRmWBKfgfs@B+;bH9ywNjR${DgFS@b=E1^`Y1$sH&b4uE5ASw8%I1uv>W3($zQuD*ufZ{xW=7;bf z_8V1#9^Ng!})79KYTKNFxT_Lstv~T z0&0FJhD_ik)%7;sQH1zaSaypWomxd^2%cFt>%Xz zehK`cnjao*xR|%5`5|!FEg*qMs`;Vj2M(uwHIwW4;p=fTIOd1&li#g2i+``?hu>bC z&M`j(4yT-%#xXwx4mCe;$cv8S4w@eVhl?A=b3H%oK6L`WujYqtz4~%JKm6$4n`3?m z9RBFtpX>QyhHDgmtk%o%8#{8nUe-A+z+qHuQ$Ag-mov^Wev#J8z#-oh!RxE_@|xVj zypmckPxmgwH>mY;Tp3sHPwQpi@IX#s-c7BSyL-BFyL({c6FGTBQ__6C3i{!y-y_|mr`3}{3dGM;%e5zV6pSt%g-=WsaeJ%~-tJQk> zLBc?ONUfLc=Vx=hUM{|EF4ybjCt*egQef%@6mthaf`R?aoYQ22n$R2)Ht(PYkJ;3#P z*_L>aW4#Rfrui{0@7Q;ak5KDn_YLQHN3~uK^gqk7UIzc$gXj1IwO;nDewII^^)l>X zapLbl{J`Oz<>{20Q(XK@>*b7O!3WcN88|%UcbxyN*2_sJIj>9WW#I61SQ^KA893DZ zz@bb3y&UW1ON7H3CHC-gv|c_&>*WqL_wy{ZUiRy|nY*a<@|go0xlOH?7bR`s9%{Wj zYseh_PWcb}-kHTOEC1o=j#eHNa2OUnf%_}}VaTE}{A=FHYa_v71ajMU?|1k4&ExuRz56`@-$F={ktKtU^Z`_>1wg0e#+cbWP{D<&k=N_NT zZz}&`gHF?Vvhp8pzCVMPQ~txKxM}>1@*hs=u#&$~{=<@Wzvm0cf7pxSDdp=e=PSs6 zh;ey>$9Ddb{D&BqXAj-UKPvy>jpE5%`wuJlrSl(^|8UHA$N5Y0A7Z^6wLFcVSN=oi zUDx${U07o{zLd}rZ>C7-;w_i@svHc@AE2~?@K@SlDrSOi}D{Xczc&Slm8Io z^3cFX{GRe3?hkyzt117X=7&A}$u+;YM*c&rQ(QOa7cIzth;_;Y*L>oD@*f^3o?qmU z{}A@DqGvwQOZg9rDSqIv`Ko_;y7C{c9h%EM$bSeN4qg0~-&6j>-4U;Ofbt){>imii zB>y3BsQFtH4j*LReaU|a zdzjkpBCnzRhuccnbX3#~1&={Zu^V%zz*HOBGLX9k-fyD%V=BQ-bdA;yYD5 zjVM_+zr{XE!5B`&4m{vTcN5p9!qv9!rLhkVTDxPxk!#(b$ z;weKzZt_SKPw8~nNfc7?l+La4ipCUA0S?0>Z6b@}Dexbjh;$LLDxTu}&P61sc*=^v z0-~vkr##qNP~@t3ir1w=VkE^=FhA7%u!jxSmJ@y|o>Hcbx0p@w6yPxb@UmhP#Z$n) zEwLO8<>zEvZ~NG?Vm`%FU=KAvaF{s1xag$fDRpkRi7<+%0EcVoT+oIpp7NoVoA9D| zN($M-v?8ve5yeyfA{=Ud*u%Oz=x=aSJO%#4J3I4>wJM&H-QU?cy&ezKr>y&bORJI9z^uBiHfeGoKSV;>(EZ z73-A55no1JFL_8DZ>QqR>!bVf_bR^JeGBC^tN8N5L2>*j#h1UKxZcaP-|`d{U)KD< zVQ}KlJc;7V7?=B1{e>5z_%iIFoAVa#r{c@?E++GgcUF9P&&}<;CB>JqPU*jvVrVM9 z?6vs>Pf_vZ6t7eKw2CkLWTo@@D!x3S=WRZn;>)myaU<_>JH?j~*DI5j#T^u1MqKat zl8-z<#g{)5uC7pgS^5vd-thz#UoKj~P1I8H<-<3Ni*OZR-n6Kg$W-y=KSq`kB`Cg( zars(JFR@j{msiy(Ddtdo8TK$P$4j(T@#PZVlo7vEd>OdX{L*hzzNUDl;>&k$*A(e0 zzPv57y4bGb%N~9;MO_tN_PA7CWUBb`EyWKU#_aQ@zl&nUmlJY)L_dlzW4#<>s~~iI zxo$llkwx)kjLWgly+sbimthYzKi13PyrfvG;>&wBd5UkzPXa&o_C{VJSjCsGH7O(> ztN8MPn=ay#iZ7pRS6IZW`0^jKj`AXu_l5X!`M#;V6y<$ky{vO|VGr5U?L32Wy0A{! zac?WnR5@Kg?M&e*$z~d<5lIVZB`On+bdgoH@(4s{AOoxC{Kb%8#mY{S5y=`B4~`Uv+=M^IW!apW=SX;WJh4Q^3+^ z+~X%J_vzOa`NdSqYl8o9P< zDrd>%q>t!L`AEQF@&aEmQ{^L-9#LM5pnN3Yuze3du~6k2tritTFy$HnhngSuF!NqR z@l@pz#qSRmxhjun?zA9bQXUcb_daYWOqCU=v&Qq|#DhGCxMdDLnCjuT(fq*Shh_VDqolZO|1=|85(9K4DN zmw2t*DKhVF)WdUp&e|z5AMcxzxx9Vni88;g%%HbC`RK$3u!j@EUU9$A6J)Mk&4vX< zrL|)kV4d$m>+fw2ocrCPm#H2 zZ4^In$n)0}Km9sc=9uNyCEww)$uh4jdr+V#W;fTr=#J)ANWp3EYe|^Q~v9lWhhh>iYi*aYDo^W_!i>IhvY`)CRf&%f_uVU=O{?9#-1B+<-mQdjWt$lkDM@k8=&!!|h}bZ~ZpQ z01gw$9(Mb%z<@pUCVRN!$u|b_ZBoe|uIR`N;LxA!;r@={25@+e>|y>#-x$DQeX@s3 zT8A6Jq2>n;eaRjMl~`n8ez=kBVcuQ|2FB$-$sS(6G2g&?c^mBEsl^6xI05!>+EN2J zOeK3*F+IUR-d7gc!{noz4di{n9zOds$w1y0?BVBr8x7dQ9I}U>E~gn7m-~}FoIWz$ z01jaf-PRv5FfN}YdpPm^MMK-e`w5o}Y@IAfECJ_Aug=0so;7*~7M>xd!Hk z+sPh&^Ha8g`629KpUs~Q#Fw{`JuEW9W+J{^hU{VdoR0?L%N@ubx_UX8h%f&@_As?} z9uwU4B5jWXG@sKa~MnZZNyj)6L}7E$R4Keb2ow8J!B7$o-bhnhp}W2^BkdA z3(XHlDSqHEmh2&)=wc$iyq@e~kt+pE%n$dIJ)E$tpo#eMB(jHtg9@0y;rC<@>wTTy z1P(Pna5$3eVZhi=2K+X#hZ*00FfcB|9u}HlGl9d#WDifpJ~R;53nY8!U+}&G9Hx;y zEMEDsfp`k$hwhU-OxVLXnjen2;BEqkdjAM;xRU0Fx7xaxu!n!r{BUdad?wZ@ZZtnk zVuejTKkN~}B@Qv)E3o#6#9-5O{@Mf%F+X$(^EH9Pi8MdVQzgVi{vqavY5T%V;IJ&s4?lfqNN0Tf z!d}q)aPy6}CU9tLYZG1icQ9cO^U?g!wQL&`I4nZ*!#zI^F@eKFG(S8&Ww;5y4d#dK zoCce~VFt|)m!*y~fkVvqD(8$h4-*bo()_T{)_4;*#QZR`;Y4!|;n1DthpqZdmblXV zu!mh~epusOg2W-_hfY5(mN?u=^TX$N7D?QC()@7vhXjd3%nyq_UL>#ZEyNETHl_Jt#iiew zz+no_4|9)>HG#uqnjfYYm>_X@h31E&@AWZ(!+kVAj9nFLBEEc_=7-K3`GzvR9QLO5a>FQQwjvy!r1f&usu2>0jcL8?JfW}& zdzen^<(C@@ny`mqv|hfju9yjXi1o7nxWXpZDcfnie0+5=6ZTN^!*BDL*30$-EhG*T zXuUjpX)6= z#9?JxFK0v#GvT*sO6%pwk^@cnu_w`bId}PNiNn>jUOqW=uEb$aS}*_PG|PlNEKKX= zQJq&w9R5n{;S})(ZmucBgS}!M0I45z4_429bnG%OsFCQm<;Bf8y;$me~x(WYb zZCWo+8Y(0Xf28&D_`Am>4&Tvwx$7J*?cq^cFHdwzllD;a!*5fE*2}4t_evbzruFj8 zi@QyX%bRJvod4xMiNoczUcOjqv&7+iS}#u-zft0F9j%w`gSJQ<&Lsa~Sgkn{hkeL@ zSa!=Si9_t8#6C6P5dOn$x5k?om&3?^nCvmeY)v?X|M1Qhhs0qu@*gJ7swHs<|KZ6R zH6;$=KTMukPvS6x{D)yPYDpZzf7r-T&qSVs<_8Y{A^+iujZ-8JJCgsf(D|v-9=;*} zVV{V}5{C`RfB4L6y2RnnmaxRm^d5howWaT)%@ z#;JED4>n`0Am=A^e9!UOkq$()<{g*OUM7Lv}s}|DhZC0|(B^&w#^8a>`*(`L|hO4!-^f=N*uy}IG`x) zQ6YPnL;l09WnP)^+h~5+!+YdET(|U|#9=q`AC|a%N8&Jv{D(1@9++6Cc#{7x^SkpB zhfm3WxFzbW#Nh$*ACC0AC~D4sI0!w)9rhlMDfGPBx` z5{JW9wdN;7R!bZro|66ZE{VffilFszroD4r5?)rDbx_$S3vUKTIFuwI@(@s!5%3o^_P->*B! zM;$E0FyGVsz~MHEr!1XZj$wZ2O7W4gf!-2_)hV9RyIonypG)x+m#O6#@?hO5o>Hhw zSqq26KbrVq4{uOB<^8wC8Rmy4DV{=^0t|kebc(0ET|wuH()@5e#Zx+$aAWWv9;bLp znPGIsGLL5ifSV-ACF(#FtN2`&Qb+Y>F?x%kD36_<-We-Tl9nI0Sz& z;)gv%eEDVU&(a?HP<+|@*;Z)}5nn!aa&SYf0Z~)r1Lh)(-#Uu^`D83xfkMp1lu$ieCier)g? z#19-!p!o8kmA(w)^0RR>_~VN{5{Lg#eEHB#KZZPqIEpVPl=NY+hZ88ioSNy)FhA7% zz~Od^FK_s%B*Xl00{KZ?XL&Nr55pkC8acqI{e6Y2zgh!5={U zu!qAa-{#WU-O?TgQNB(0(R(Eh-6-E?W|3WTosvcQHoY3|m*esS%D1W6@1O}kb`<5? z412y;+QU1PZ?kmqS&72{%C|XQ<$|0a)}?%#8|%(Udl*9bHb0ktA#unl-==Jz962tB zQ@+i$j?bh$Or?AqpZNR?>lA;=w>eRY{tg7;uqEZ&^xN&suujRQe4FswUJ{4XDc|P1 zBebWHa2QYdHU%1#Vu_%_2&;;<9t z+vKjVAjetF4;&V0>A|aWTrNrZHtvtANgO)uF2FCptjw@Z`GfLp za#jT}td}*vT&GaJ%^wfSOB_C;e4BHr-V%q%w^=;iSK=^>@@>}r>@IO=QohZ+n#CE` zDb*?8rp&J;Bo2{}cgs0l;t=%YztgPwA<@`(4;-T2qil-Aq3yuy!|j~5OB|xU-OIfe z4vC)SHeTWo^?%a33F{Ql$=w`sTn1gK=y-`k(B7RL5{IDA5I=BeLKAA?SALg(MC^XSXaMafn2QF_7L<=rx1&u^7?KK36(fRj^B=gA<`a#P9lETL&z-ipoYXD=*W^aq&);3 z(JD}m%b;sFt1fW}dgi^V(jIDlIWALPVn(3~3~@c=CBC@iD{+W?#ZjC5B@U7ISYwW- z#3AUE0v-~FpjmQBiNh?)$DXR}VK(JsUr_c?pVa^yA|E?f*+b-G_aS?T^)m9YJ1KjJ zd~9tG11TRH_6<0UqJDayz0s_bDR>n;BPky{fb1dW zhaD)t8ukt2a#ACA^R}{w>nR_*n6iiT7bnbAWe=l>{|xa1hseiHRrV11)gQ4GMb8hhKLztc#FzE?9>5{?r|9`1_NPpz`61TJ*q?HO=7;cO z2h#qOl4^d4{U(_2VV#2gDJRtY5c^Z~{4jy`r*u>EL+}?-^FuG%pOQ`UL#$Iq(f*Wj zYJNDM_NV+x^F#O#18IK>=7;bf9;oeR4p8&M1GGP-9L*2mKlGygDSCbwNc&Ut{4j_1 zr(k{v|KStbpHfTB50hzsN?Dp8!hiT+N<%Y~=7(6PETjD?8`b=t>zQS(FW zPdPyIL#$JLXn)E>H9ss)`%^GK1P)iz{*;9@Kg77ajrOM;Qu9O24;+@E{V9nwKLidR z(f*VoYJQkP`&06(`C&iWpHfH758KiH6jwDrd`bILyw&^=`}Jz5^)mMBrP6vCIMipt z0EbC~o0unQy$rui+3TiRTCJC{UvE6Emx044v|n$hS}$Y&T{T)S!ycy6e!Xq9UWWe= z`}OXq^>Q-p*DI~o%bFkKGWP4~^)mMBVZ97Lb^`6!YoXT5*snK%*2};zn(j-m*GErRC<-k zX}yfN9`@^vSL*ZkLA4&YMhec?=-W#=E&aEZPd1}4{d({`46k9bA;r$O#7FU$bX1<3idB2k^c~Jy(rqh zd{g-kXBVkuu2%lTWZJ)+uKb4yh3lC~sT!hwx)-eyo>^ z(EjCR%6~YC_Ak3A{~`7-$0+|H_AhJyA@(mvEC1nC+P_>(`46#wxuNnOV*hf6@*hUf z{$=2yM(EjBhHIAbGW7ADLv>shhP;?X-Vff{6+B; z%nt|Bc@AAwJY^%D=kQ*|Q#hUHkTKMXr%b2w95$QZbe=;b#Z%xv#CZ<0DV_oxUURpxiYlHGMdvvrsd&l?I-lV$il@MTScT4WnD4OS zDdXrohlVPi@(Z2ka6rXVRw{nrFoVu>82FtPPr-Q(85AD@4%g6m4v$nk#ZKor?4o!I zaLDL9hchakvW@tEQ}L8Kbe_X1il<2bA)V*opm+*!Sd-3kn4sb*IL`s`6xhSIbe;p^ zDZt@L#gFwe&T}}d;wd=KA&cTEz#-0a(D9UXI?v&pil-cS^4grN;wd=K!BFuOoNrT7 z#g}ou%{YoL1Bd#><n?5SOoZY{V zSxm*3lXnd^53Bg{H9FrWQ^l8YzRhnczO4B%F2~UMHuWjK3>+@pxz$`k@n!h2>(lu* z+bO<`bxKz{-=>p_FJI}m-Mpyc%M0mzn=2~599H#&*+|8guh986?NxlaY2S3ylj6&; zhwJaq-?yUpGSD->Ub z9~fo8*Ol^ZkmoQgeYCk*<=eQ?d2#b8-v;&&=f!QK zd>c6~(^+r@RK5+)g46jnnjiKM=e#kMZ<9&qyyaKfqMRwLcYw{fBK*-})#O%R>W_D1E~;Cwdc{u>S8u*|J&)A>r8fjozWboSap z%D2I|9O?DUET!^oy3@I8GbrB%IQ;ac0DDgPHt-+fTs1G1Z!?w7OgpUdZBppWv^FZ= z24|+(f3osza2{GOm2YFx*=2=PzD+Wnhc;T}+uWnG&Wfshn;LZ1*&&s0qxpfuSUSf{ z=i3ybbIeAmd>d~%#|-&4z->!9qbybB+q|YT%4{m%2K+;bA2@tR=Z_sx`8Eyc{ILQm z-=-yYJT9*h0YBtqVjEu(YaweRldz1bZ*$E z@m9XgRXP)FtID_emCgh!O!+qOA9kQK!CnSf`8FRs47R6akSH)ag4wT!vB;ZBJ%KFti2F zs1q$2c+mEoa~p=XRY+!ZlU58eH-Bg%3cqj3UQCN%Z7+T!G{4{JCSvZ{2sWW~3s%=T zTpVfEik+F&oYimKRMgDhhFzO$wOv{&NT6*6;&*>mPk_H2$$6*x7DW8}{elJf>yw;s zXip{Nga2_4xy~d!U(b5zp1ER&tOa1 zhKuopn>y!Ac4Ko>QRP-M5$$I%?>cs7hBXs|Y8vd#UOTJUIb39P31wXaOa`9r#1nFi zv8`vCh;h_*Nb$zZBcQ3s(}=#I>m9`M2W?o=R|aeItfRF53s9L@0DVI+TU;cg7_!|1u?Q@S!d zw>$OcrxV>7`m;UnP`2??taw5;`lpHCvY8)yiwnEv8^r>Lv8i?Xh(1pp#(CQ?wsUMR zk(oB%DB(ARO?HbFZh3z&3f~wcQa{HEN5*{PMaO|+j%u5Ad!Pt&j};l`RvUj@A1pHC zdx=%+=NtXYd@CGEW&q?OHtayh0#8KOvlHW1( zXD9W!*sZY)ecnKQey?~usc(P38pF`Hi`3`B-NrEVxiG!UOVzeqjj3!~&v?OIBf~DG zO<|R$(cjLVI3+Cq<0;H5@jF4A6vHCVOl6ZUkCk-u4GytY@#m}O5dMmP@;6h&c*RpY z#vwdaTkt3RG?PI-_*>SQ$siv*C)g|o`ID&acRh%Q=(5xw&3~Et(?apLqdvqdo_y4| zx@D|s{1(-bFn2a7J1z1fn{rug~05b^!_vaA;IkI0N<;14FA z@bzsNc&bp_VeV}i+Ri8b%5iNO_~WQQ4gQK`=+8Ln&*4&S>2FVzV~?m0u}N(h`p}j7 z_Gn03Hk$fYadK-WJ_L)3c7p}-I88csDRu z*$wnfjA|rKQ#@lYeIsS_H4^wnPSCdyxF%TOTgaeqB;V~2af`kYd^_zXHxl@EQt2B> zeHSF~jo`Trv)Zt-^xPWs+%reoGCUXZeWM~7w?9m-@IA7Az@<6v|us)l{afiwBHE&ds{?zC!Qf= z+c5BC|6;P(7vW-4^H3(dnu!=iKWsWqw5?2I)1PBQ4>z31+9`U|tWIL(n1-TK?NGLn zXxFZ-8R)zlri&q7)0m^z_)uq}`?VS_Ky#9L^+GhAEgLGIbw$xfNoJuR$X1j5d-SZr zihdaq$r9VNW;XE z#kVvzQQOJXH-AO%qCS74csfuY#z%~ka?rO)iatAiDyyKLwQI%)raLoH&T5&ykjtX`Y2YkbpOFvpD$8D^4HB2u#E3o*RvVzFJ4Q3m-?V2UBBu>|msyrIC;CtNjzG60nFG#@WsrY_ zo;6(2w@BvLh;|Gz@6fYqG-=1y(X-Ot4q;9cM>C%W#833E-^U2h6(d@+b`|J5T|>D+ zL?3$JhJil0^BcBvNn?@z*ktWav|y3bL&UFdOg3p7V_}L?WJ1oq*=-o)Tp&4p=e1#w zlb70N4eG+swi(In^KDxOnbk*6Wr3H+3EM52?f*WN#s2V}FhhS2{b%4bmhm)R))&c| zB7ReJ1vW+WR6JcDIYf2U_6G5p^BRih9Tk_AG*NLr&-6Q$$^)gxdJtqb^XWSX> zk;}utpKoOa7WBbi){m<0&o(dlTGr2>Vq-qPGFgA*UmMFCZ>KT06^nYk)2vmkv#hVO zYL}Us-I+C{`lP_R=If|FvOf8*y5{Q2eWe`Rs@I4A_&tuHpP=U?4v_VYE7s$=#E<&s z8TI%Y;)k4y!*+4V|4jAo+*9~bl8=7o9<>QS>JRuU)pHWg)F0FjxllngqW+`)>Og;y zME!@HPU}o@jNTXZL6J=4sP`S<+)1R7eo&uts*_ks`T>8HTD`?E(lef$>C{JzRC><4 zvA>89v-F%6A1B5U4gSi+KYMXa4moFue}02Nj{fu^`DZq5=aBQ9ve-`fk zB>8Jof3nwomh}Uu{~<&D1ms+z{{ND%f`FWCdf$q{hRC6MUwU7c$A-XjOObx+uInKA zACrDW?~by*9O?7T@4W<`TY>cXG$1B^3k8wga=RR5BM_(4{shBvfh>OQ(5(YGT~>n>iV0j$c4VtaKajJK@HtTF=P2R)E2YnVgmZ7DPvCzv{Vw~e_LBIIr{86Q==lZzsMq*M zy~aQ4HU3er@sE0qf7EOIqh8}5^&0=E*Z4=h#y{#c{!zbC;UD!$3je6r_(#3QKkAz* z{G(puAN3mlsMq*My~h83s@M2Oy~aQIHU1}3y~aQ4HU7b`@sE0qfA9nU-;$moU*mrS z)dT;P2=m|v{sV{}PW8b5Li)W>5Bx8t-wXU2|B$2ck9v)N@N4{|UgID28vm%*_(#3Q zKc1`c5BVDZ;P+AZ2fxNY>NWmRuknw1jepc%Q}~B|H2zVq@sE0qf7EOIqh8}5^&0=E z*Z4=h#y{#c{!y>-k9v)N)NA~senLVoHe^f<-k9d(UE@2jt_j;DonF^qSw0^*=IW1D z_%X^Glymrf!#zK)LF_H&*Sa_k2q=yx*%Xg^y%UyTU z-|J~F>th~&=C72T#uxlVX(hk>2tyR}wVr!uZwE1-`h#cP{-c+;M*ReRvSB|lhHwJ< z7S$iy8f1b_BmOB{Q%v;PkK{}%=fqGSLGnv}sK8J^n4bIWdsEU6s6Vr=cVtbdekJvD z`|DUq<2y>|)t^Bpxt?{*ZB!51i{2OfpjVR~o{}82%_9AHkbKndBfU+f=Ynoc`kX=i z0Ub|zK1KZm-StCXmP+F(Xs!QYw%9NAOW}x zUXowEFP^LQFqCMmAJl8Tf!6v2&rzjk)I>>far- z#shdXPEbEm;Rm$F6=;n&&>DxJH9kRW+=AA42CZ=pde3*R;_cU?#i{%B4Ze33B`S;( zCxc_yr!K|Bq-LWf?R3Odl%6?SG(Xpa)$QmjcK_ol`45iq6$3xJNuG9leMP@Dt|EeX zTDS8N8PTq?Uh|jlTbpT~q;YkaZd=X0_7{H8x~6phvtk6%1C zrse_tgTE7VCH;U$)2KhN&YksE`q4Cae*3p5b5i=zH29C_#e4_HQfl5D{8v3x-N9uCS*1Vab=&>w_NS0D=VeG<%ov9Y_R%HPnPm!d)4=Qd#o?(ufADLqYs(~ znAdHAc`XyPeinFiAJDekYbV;DKU|z3Y$uk?!{(@ObLu`Pc2Rwsng+k-fgIfy@z%OJoh1%a#{+Vs3nv=(1`qD={t)%PjnV zH0n#Dl{-7THK_Ado_YL)>ssFz}bjbd@6HgoNko^RmFlvf?mu2)`sKVThMdpeKSZt`0>82Ne-Snh29Y~+Jat4&qBTChdxmssrrMqprfb{njihaJ3g*F zTlN_|Plzr>I)r{eL%!zG{T$KBdPnpbH0sfIY<H~Co4?wJO1j68 zr)FK3L6VLPd~5!8yT7C>yv@S~<@A+w?;i@XfL0d0KGf|?{o1u9*=fbUVscrgm`_g-5srqnw-`a{liuCY7 z$?+!rq$v3xNN@h?xfMyDNvc24a~0LkdrJS;M|-m&O8=m>{y}T~gZ5MU2Mzt#C;fwN zN&U$neS(Jmza{;HhW@LN{y{_kx_%wKujXG#dT5~JX#In~nbJS#9ZLV83oHGD*811= z(7)z~{y}T~gWj$54|*9r_cQ4YH1uDW^a*+$_45|#8FWwT|8&wnXdk72&|3eXwf;dv z|9eRPptb%%`zif{hMu8+&~w*T6NMChn*Li=JXZLBP@syqM0krJ%ul>sQQT5Ee4OMb zPAGi-L1%^5Q~3WYk^Yu~!t)iQxEQSPzxu~QLgT;N`@CQ3kJNq7HUF6r&$*Vf)c-C& zspJpcagE!?V0F^&kEGhw7^;T!9~WL;Wz4qj9*5mT)6|Dd}o{ewQL^bh__rGL~zKffvY(Az!r-0w-BH&lPJl>X7SE9oEh6Ey0pDO^GS z8vi3mPDRoKcvg^njn8vR|ESmcM<049{iFUzrGL=SKkO3d%cOtUEAT`Aus^8R`UegD z<97!QeF6`lq36n~pR*PIkJqbXZ>;oxf@t6$`bWLiKk6ST{G&cY=^ynM75-6wS>Ye_ z_X_{u(fCJws?tB|GnD>8FH!ghJw)jr^a`ba&>H`c6Q%U8>!E+tYyG1hza#Vy8ow{} z4<7vPz(4A_!awSP6W|}T#y@zjD*dA#_=o<{n{TI(OQ z)<5KE{i7cC2l_|7)<5dC{y}T~gVy#3v{3p-TWxq;~(`}|ESma2d(uFTI(M) z><{n{8ukbH2i1 zu!^s2_6wke z*{vOSSl^Nr#8-Xmu;2=}nOErw!poEPyM^DP+_ehg{!)LopzBdcaz|_Y*xH=3{+Q9<$Neexg`r z9(JzWb9VENpIH2r6FYt4CHr*APi(tpW4&kQvc`Y-i44y?Y-8{{=9lg#?jLey<&S=3 zg%9|NH@jR|#j!Sf_Z{^2dCnJQw=O!_hmw65{j3B#^)!!t_69!@b)pO_yC*N%2S3r( z(~kxFI@?DOJ#R&2`kSB5c7Km(;ZFMh^KD*xC$DHxn)E+6GOvA&ceK?1sdjnnM=M5) zIMRQ3At!rWV6<=}{dXwvnKfz@En-Oj_kMWK{%jg8Zjk<;zWSG?w2KzUNdH~yqLutr2jroKC(Y5M@#*OFSOZxeW}l+|NKv#>~+gTOZ`7_ z&TDVs87(@K{*B-B+E=+#KS}>Rf}HL3h@MaS_X>BmS9FdQAKL}8BL6zu<95f2y<-}% zvvJP$HhcPrlGVakmBV@M0k8UtGPN305HF8Cf8=1XAfh>|TP~0N!@A+ZY}$%thB(=e zZ67OKKDJ?j-EH>M<|I+0LtBo#jKKtIA{e_F?S8V^@eD)SeeZ>1KzAQa4pS{_(SP@X5GV2kO&tB(gPZ2`# z^W+qFdvbD&DDbfv3vA$SUv-`Gc9KXg)|ah~bhCSZJxwGZ@5_2MbF&Y?!ec#ctxCFwxDv{MQ9yB*{5^$jv@?TY^|f@}CzjZg(rTR7B8obH6QaPd~d% zoTmO1xlZ=;{&JC@`uVJbyZz-iD?}se|EElMd;L4h#i#`h*@TuQ?ELp-V*8rfY<+qO zd#8L$MePRF*y9==_F?N2#M2)tvKk9K?6VFn5C!x2vEMFx*lP`(D}Gzy&3-TLX)kzg zrZ_XcEGt^a(>};^nmBvnD;5#rX%9-7Br>VKLUm7j%CxcKH1XHW?`eN>cbF(la-s@k=`1^ie?!`}ja?Vs6AJla2ldd+|OPp>aL)jdnw zwST7AVXGc%cF?*%;Me^rO7-Xu`cRG9>b_}y_-8z+Kic1derg{J`k;L;pdlapzmt5; z51E<=GId)#7yXBS2K~YN!Y2bB?Vmwg?QcQ7_Rl~++CPK-pe_6}=!52mZt;%r&uAX_ zWI${G40NS=bU#Ot9|k<=GyF5ChkW>Fz^`fWWGMg4e`)Y*|IB}B@ZeeaEy~aIl6}xL zWWwKqdhJUAt$i|huBIVJ`(!`|D_@Q78)Wh!*1Kz3%S63?7U&1cKY)3o_RnD6sQm+| zcmBol&w$qc8PGAxKLCFCXRzLvJjy=+I#&4yz@z;GsMr1()Wc5#{{ZT>e*pE`KO^gv ze*mhWCo2T-s51E@zoF+WE=`VapA>a~9W z_1ZrGy1VkvNFL=MK)v=4pdR|f{1ElpKZAO$f6NuN{y}T~gSILCgVy>7t@RID>tFIH z{e#x}2d(uFTI(OQ)<0;if6!Y0ptXMtwDymI*8UmL+CK(b>mRiC&w$qcG0mT)6|Dd)0C6CfS>b3qs`z!r}*7^ti=3)cxYTv|;6>VjAi>%8J zANrXcCptT;G9OrAyR46V?#0i1+$HHu-#q-;n7xuGaaTs#+Q9-@ANCn~GHS&aG*9@NMFmMH7PiGTNmHIhywIjv`|l5_ycuTgZlv3Mq)=r9cDxQXVJa-tqZ%g9Gb2;h3q2y$derl0? z**DT#Bs~{AZ%Ci}RDYo7e$-FYe^C1WNaKDHrTmRh%KWMFg&{0bNl1J$u za`5-{pnuc{D*c1DDgDc~O8=mtALt)+lF~oqX#JyJ>mPKa(m!}m-;3T0_0WF`y)S63 zf6zWk|Dd)0K|fIX2c2EHsL_w~4BD1y=^wO@(m!bEAHNsqQ%e7!q5nYAKj`jC|DbI* zEAzdoKOUs#KB}KFcS>;JXW21Vd!TD^-tkJ3r1$*d!o%7mOZt>oZrZ6yJ0$HGayD&E z^At&ki;Zb)*&azpF7BOHC48Tx%?A&UuI{j3($IhC4vY3_bSq5P^Fuui&Hv`&dc#z5 z0;m0HX!*mc=NP}K=eq4HVCw$NF70M^QvFPP<}UG%{yV7t*Pnlq&vhaG8+F%88ge@1 z`$5t^B;OIdO41MLx!0aAm$ZZW^PQ_FVJ(1ay%!ctGp6nt%4qjFFX&&P#<*L@2oyR z=8^Lq?O89oa6A`neVTXRQak0 z>$ZvXE_~3{wA_;W*u6mOT}GJu z*tEy}?AhlprPZCkSH4$vsXJ+?$2)5NTc6v@_d9(NpEWD%UM}IWWbn1_8i#}+6NfWNZW*3&2#P9gOw8l2-L8G6ox9($*scG~d z@=^a^8a%-EXtFK9yrv-sG`>e*Uemxcz8Bacd`IZde`)aJy8w@-ZDYGj9>~-*o&|h@ z2l&)9o~32td(_X;H28sG@Mt>ok6UR8ne$jqd$MnezHqH0`E4$xU753h1={|P{yvZ} z^H*-#qlNR>mWI^-rTcCx`s=BvaFP)~WP9 z9P(F@OikCMXL%`^-v3hn)w4irnFBrh+x4>s5N*~!C%-TJ7MjLy6iD^J%ztV9o8o(^ zzt6%O=mv@ge?y}2yKCC#Zh!fGL5`+@f6(B8OigQSK<1)x{iU4$(%?ruu%ziX{d<}i zA2Hr#74K&1@$S;@7*mgNpiz(C{nQSdsmI5xeEGicXa4%h01w7TPPA^T`7u6f9*mE= zE$pi1hs{TSARqj?Kj6`Q01kEEz@Ip&m#N3cRaN_%cWFGrSd&G4oiU1_`vt!qAJI46AN;1e z4{lZ77#O?JH}LEwIdWb>Jdl5u>%aUMA2kp9quZhnnjd`wt}ylillUF~m)6)uJ!tf^l^P#4 zjs8Qv9v?Lg+X$?}7D2wIAqOT6$OMMLgSMc(zV2@>RO6$YqA`{^S`Ria)A)rkOVb$3vV5XV zJw86j&GUs$oc+eoW8$#$y-htkU`dOf}h7Fb97k&#(_slG#wA;dkm=XQ!n3j?sp$ z=jFE>njiJ`XZ-ku|3D=Djaen9fv#8b%ly*di+s>pK4>jp(n`LrhkVTs`JmBH$d~mt zo6U*-``>@Mt|8sO?g>6yo7Z#Yv0Q-Q0CCmvV4$!C=}Q4 zw=|LElRpoJ;My%64HJZuNdt(<_I<~~gvdyNEvW%%UPL`2{C&+SA7pru(#mnpbwqdHY z+U2pu$m>s^JIm5$ix{g=Z4t4F2*LiKWP^*77 zn=a7~^(a4lo-FU9wB&Kc&qMJ%!b2F^p~QVBn~%Eok=J=_ro2XJ$&HcMd2KQ3zC+!2 zsQU@(euBDARM&}NcwS!HPIbLgUOU^kyhe%p&bCZ-ohjQp+p^Skmb{6`?Kce*d}?=U>&_uw$@$?wBq43giA!|;>ekHZ)xzbA(=TYg^-BUyfL z4&xvB{W%OT`8_&}b@Kak7?a%by*i9*xA6TsjQv&dJv)rj=ka|z4A-sr-W^8LF?|0H zV}!H^4&(mw>ql_Sox@~3z7u@M_&)G|zaOpdtl4t?y;wAw*$ zkmE3*SCr7ZRR+j1x1WzJ3l6Z#V>8Rk>oL8(WO;bFRj!y~)#tT&so&en_(T4_*6)q_ zGKBxKKZDO^JGIOzZ%smbn{C--tHke*>p{cuJezIsP^+~1WwTlRwAo5^St0G&UuE0N za&4)6vdqfAnDk?_JxEQE<=Y-JWqGEzWj{*}m?f`gJ0%|w(Qc>D$-|of#AAI^u zzk|)z=*~vT*Rr3dl)JlmKUtc#pJW*_^_=y*o0dIo*{`hZZ-?`BW%)}`3t4_R*h7{v zD~HJPR9(xC<}Px`>z;F`$Pzlob8X6=!Y<(o_6ns<*;Au)l)ARcK7%d0TCby37EZM6 zsqYr6w5}b7b?q=Lemo299fs8o*D>`?ANqde`#FqH z@_p&tA^H9eqr23H!{{XS<1ijceL0LKQhyG^(kJ0k>epd}OMN?x)>8itBmFae4?H_z zH_Amd@q0OptvQS6_oMfEyF=dpslWC8ILF}kruu>SogK#00>FdAsOANHIE}p z9hH)w#w*DeDesr0?{q84M~V9=ArB?mlUHb=K-sk{=^W{645hY1I#t z*Z93|O1^k?9k1?_&ZIntypQq9dQZGH-q&WsebifgsIl2BKC85zW3xd%#y7M>34ZI^ zW~Lx}T`-;~Mu9)%~67{!Vot z*SNn^-pBZh{-H$wtZSPMCHjwX*}9*p?&BKwGu8bpbw5kp$2IO}$@>_u(HcTx9ojr%U@zMH!5rtae!_ub_E<4L6?eo+Ds7~kl)GEDq;`@tI-%ZpPKBqS==(~?HTs_;!(suGFy`Pt{ zXrCMP+sioqx_~UN6g?vAt@o$*rsv{*fxwBfyzpv*EOQ^ju9!x<1Kw1I%M$&I8k zx(5C&d4aM7Zg9Q)hBfcm;%CisMjvS_=Q;Z}^`zg*W^2*SnkP7KvgQX?=`gH%hhgzK zj42z?&S9ifu*T8#|5)QD)?0WE^o)5puJJo!-K9(1$GjgU@CiO#<38s9y2Sl1d#(8@ z#y|AWx^~EM5zn`G#y0|cWtD#qv&!y!t@-BG2rqTtDq%OkzjBOqAJ2zei;sR|*$(y! za%?t>&t|jQ*=*MHY&PpTq_1R4pM`H)`rHy>=}#nC`m;)hVbxQ=Z&~_^+Ggns?}hh; zzO4BGm1K`_4LgMU&;!PK@S(&t?qfWF9YsCf!?M?2U+T4fwS5I2-b2^JzMYS|}=hxC$z(qWu?GssBq)`$9O8f!EA%Cf}xv!NHL-v32W>YpPF z*C=uS-pRe8&2oAhcd4B1>?ZH;$k;6J53ES1dF}r>bP$!ZsrkqJF}d{9!e# z9}SI-?P2J$TX39#`Yu$iCjNEQZ?v=C!)E9b@3X(h2zib2M|J&-uW?}~ueLXq7pWc+JtX@`o;)*i@131}<~(Pf*}W^;{CPUn zv!|lCo^7_M-+zWEx%p$!!@E!{zxua{{d9(>~+O=uj^RRqkV4C>lxO^7qj|KkI?R~Mh%W7|r?mc~_KCkcldPy(Q9oKD#evHL^ zCZJ!FLL3p=|I-~mKOW-`1QzY^p`Rb&z7NswyXeQ%p;<)MQBy_#*t%leyHmxK5Gm@Q z-Gk?^{5-G8=>GokD8F0aFMl?)TY30P|LQ%(Yj6AYJ^%9fPrVH0p zV}$pQLE`Im>+pWde=+=GTVHLImjcpnO}!&n-m`v^pEj{1Y<0cAwzC|Z;??bd>R}0g z5alJG|KT&&kAT1M`b1tYLYV7B2y=dfFy}`I-Z%HSLAt#`N84;qo9&;z9H`r?m%Y)> z^?%<%YkA#|KIOXm*pC6gjk??sre137yAP-=Ee?R6YNlZ(w{|@u1WS-^qT<^!P2Azfj}H?|rOaS3YMT zY$;ydjT0}fjTGZ6uJAqC`H84dsh{rC2iaEW*WkI>SMW6m)mIcdeA}1xCCej(sgDq> z-##uzgrNM}-#ZDm>pQ8U@8+u{T;KJZ`?!AIXG)ijz7c;JKFFv0D+T*o;A)(>Qs<#B z*U|o>Li29={`r%x==;C?x|=90PWo;|cN1dJX5X5aYx@4CK0>fQThW1n<l1lhoezz@2s=Fk6Kr-KSblNj_rrz zSpP-2o>#EV{9@Z5f2pY3H7izEqdoWka}M$g&ZOGM&Sc|#{24fYZoDXhaw0k+Ot~YB zEk#`8R%kCpyYqv@@e-r8O{C51ym7;?@15JAFet_A+Qw_NXl%!^XzQgg=ergihxR+q zC)WO^| zI{%f%qaH`lKI)Mgf9#V<6q%nOe(4<$d#(=_Ws8sZ-yJhVESQ~1EUP$NjKuX%t0AIJ z$LNc|d#u^0ZV&GOeWxqi0W_NmFYby{CQ`@@*k8!$$WGd}D+jrXrl z)PA14Grz{kz1M2&dcV1@uUvh<#;46o>hqsn7^t!8%~cxnb}{=SlXsbXUQF%6dW_#+ zQ(5EbaK>xL`RQbPja75?(HK)3iZ+op*PW)` zwe^X%KGE7q)=skaMr&`>HrHD`pUCTR-DT`!*1lxzOWNi-jP*p*A4iV|^C8C0VeK5& z4z+fuwZp6(X6N2OoDADQ3k1z&KH=cE6)qN4UE zR~Y|t#aG(jT+vqhpDT<%y5gAjPgk7M{_2W=_Ft@ZwLiOJmiBM(lJ<93G}iv_ifR`* zA6yaLg7d=_Z`a^_L0NK;tOqFd=lm-$JcSndWhZ1o4k1R9g`O?-P`2Dr`o)BTbut*w0UpO zpez1EGe?Q9zB`5YQF9WmM|3SRUg~nZf5dQ$Qsb*voh^>BINRcKiyJh87c4T5$?IIw zmuHYBc?b#XMm@i0lWE{UEX*`Z^Zb z58CWUEclB3h!r<0JhSB-*C_E$t2fb)D752v5ZMnR`$1$si0nrc?$g;K`$3!iAhI7s z_CsICBKtv`{fM&th!O*v{cX$H4=HxnyxBEKuBh>bT$bJyn4+6N2u*bs2KDC`w=SE6w6OLQ%=AG#dvi0lWE{cvnQ zi0lWE{UEX*MD~O2l|}Z0Hv8e&emG)sH}=EP;}Bx%dM%A$juDbEeJC^d3CSk8VJ zoNaNr#SI$S4|D!8i1T6q26_+JbAQ*#&IN5A7lT;aYt4wqi@6n3mQb^je5 z4+r0S4m(Qp9`O?VBSly?6DQ*PoP`}JVm>!~eRKB@u*1cjN3_GmgZM45Lq+l8hQAW- zZ-VUzZ=~T7)^i@Sp2+h#pLjlz*Qa0e`b2Yo*Kh9c`c40&-}F!V<8}WXzv;i@&%Wro z9``wTeSH0Uk6!VI-mik!#D8(%HF6yB9{TIzZ~mh`V0o;y8K-GSS)1{awzPJnwIi*~ z_`&*cYlm8!ysrOQn{BuUeTnY*R>&MfJ=-r?O%?eg>JC^Rt@tRp;ckgBm}2yS%>Eu^W0mIIR|D z)qUR|+ECZWme`|lL`VtU?z3OwG`=~@1u8sjxL6knd^J>0;`JziXw(;kwRUGzjf(bR|P@#8)??ZNVme{sHk9bvXU%(f4=cDS~=PUroI zJfHjT#*Vb@YuNkO(00t5{q%cw4}Qn@t`_`|=s4XicCZ+2v8lzn8bchf#*g;hW^57k zXJS71Hu6bhWW`7!I z*KGJJaTffU$j^;&{D>S+BG0406WN}~_m8dl`4YA#n)fruzx8a#_ml02wBP&MpGM@m zmssWTHQjH{U)r3%2BR#-Sd7)kd1>n7tUX2}=a(sWHxW6XjIA_s{?O*UA#%PDIZur3 zT07BVlEsZ0>Hlm;|2KF^BmLZ5hZ>yMj-S%RrX5xV>B3MB1O9&FN=7 zk@lOlD`}fZd*){`+9uLwK9=o?wEf@B(>9Uz@UCmLO{ATYKULdA+V^%J(KeBG`C(VI zO{D!%nJ3yN(r$S>i+;UC+IM&7);5v$%+JEKO{D$qu;SV#(mv3P$is{xz%GKf6L||HkLX`_kXhuUqtgd~Q7p=YuPj*5dp? z-uDUTiz}LSIIZp9m;J2m@1wre{y${k0F7=~K8>fc%||=ONh)BzCvq<}x1LvFGe6UK zsYO3szi7@gjf-DK>+>cw*6SK)W-_nuIOWUd(tdvSOj(T=OBlUWWQ5UYoyKtQ6?(CZ znNOZQX5WMU%5wTKk^W8Od?0eZ{D&A9UGD1nz}IQcbG84|rk}Gt{r*49D0c<@p5+Gd zxqkRNZG(KjbL!V)5TDb5zq8(;tNorf{hs%uf73STYCoq3@hJVvG=xRTwO+ROQ`ZsNZ>`$1s4Z7OTSx-M_d-^wRgS>thUcV2nn55qq zeEwR$Pp-(T-#2`|N57A*IHKQIR}|OpvnxK)@4G7oX+OaC8?;|wZ&mvVzQ3Ty8ToGg zJ|N%yJ^jiR6Y`kvGmOYezjMX;x9EqixDZFbM1L(W|1Y$R9)~*%&gu83#;b`MPu3`- zvHbSeG>%_t;z4Yv-s5+={eEAUN8R-3^Q%oa>yL#KzS8!vg{L+CvfQjIR-G%P$0Ofc zW-Zodgz?)qy&vfE?%#CRh+m`8xOj$HUrdfR`*j0v7=M2G@BW=xS7fpKc!>AZg1cA~WtZTlqKKFQh}t-Vp()Jr^{$m>xz8T**EFIoGNwyC37Pc;2;^muUHVC)>$ z&SC9PYlm7p%-Uhr4!1TwJFM?tR@>BJ#*Vahq-|frwy&Y>t%U>dOMZTl{^FwlW?wIp z-t)lsCG7s*$J*aq;cEYLMWXgcS5(&iiG3vPuZRoUf3csZ{n-_nw12x|hW2+??9l%2 z3ZI@2_?(BHAJ~tY#`)rkoi{jtzy~)upIp&D59b%!EjIDyk1d>kh&RCBAJnZttPU8IEj%XZV_xD!X{kY;3-FGuH0!jj;QBFYNwaH@m;r!|v}T+x|8eLfbac_P8g!1MyS?S%lM#A^nmYVtLJ8nKtGa{#1S8bI> zA3ljUpRcaG!Ss8;^#=O9Z;P5Zek)pPJ9p5pvF1##s9t}Gmw3dZwdcRca>uEw>xrzd zQThFU(W~nl+WLmN{MD-_+9sOoMcMi&ZD(?#wM{hjF}6O&+8wOj!P>Fbj-$+d&f0Od{b1XEu&qz9^$FU}`-fm zYCAjfE37B7KD!fX?MQ1&YfEkCaH6zLWcwW83Ddt=ZNKKkX`9IUa@FItO{6{d+N6Jx z{_u^SU-&GY_Agf$e{+TLKUWxkM10o%iSI*de|3fNUso7^MjY1ujhu}3cUKtyhhEn6 z!4+nHAg=5A;tDf=5dZaj!sl@G{BnhvZ}^;!o_~nPdOo_s%un1`&sXSeJ%6F|^?Zh& z(DNI5T+erWPDsyx+(+|)E3RpNfPTl07g`phcuh3zeSk%UNE!d9NVLM(Ic?Zl_UXSzlKg=k11?Mlz4dSz%n76bI;(O(ox3mrNd-1Ne z4dQ*qyk)&XSI=MCoWHz3=Phl6{2sm8Q!+?9RKK4F`F;CvZ5yN=X>B5HX>B6=6Qyl~ zv}3JJWPjqcZO|2F+>uw&?*sf-zc0{L`h9{Q>-P=oYW+UCVz+)@UGYr6&sgW`_uUm& zwIASn$J#Gkk$*D%1oK1t4d#>fBUiN3eueq3{fzGuazImy=ssm&-mkOzR$dt{GO)#J z6B~&cZ45#;|7!A*2F>+&9!}lI6KPW~ntIpPC))Z%YbRMd$=VyOy;0lLi9Dak>rpQn`P2(^veu5YcBE}z!?v%XZGNtl`FB1S z!(cCs{Cp{Ge!i5*&zBPU`BEZ3UrOZXONsn^DUqKqCGzv7M1H=M$j_G&`T0^JKVM4Z z=SzwFd?}HiFD3Hxr9^(dl*rGQ68ZU3B0pbBZjWT z|B?08>>Wje%}O*@rxRaPeHb!Tovr!4XJBig;%bEjL-N;At-ELTJgHe60?IHuQh z<(%ml{HDY#H8nWTQ=&*?b@;%Gs%?-(AeO+S5~W&qj!4FpP8?Ujosmi%dpjwKMMp&xV$# z)xnADf@O=}QNt2;1cx7fpyszp^(0O>rzWm>;)&kyP*uO09xQV6xvIQ!UvTvCS88_U zeV$K-K2_6Z1U;u}zElnB9}Mkmvj6WEK@0Odih*8f^Bma zNKZQbm*?HinbXtv?e|prGhh1NAAb)VER1ws;2<3L&K+@Hr4Z{XDN6i_`fna z(l4z&8+`WDYw7*wtoE$RQy{(3yH`DR2WCqzcJEYhTK=5rQ{P|VA+~G0+VeW*h>m55@$t6x`5t&+5HmCB!Ud~oR> zYgDJFpI1rfKUST6(k%GdU*lDQBI~P6+3Z!K^qaw#y`-AI_q!_f&)g4w)mQC|oc|;k zRrI?m2X6ET&bnP~=b2u8f(Pq;UFG3l>8S}lR#b`2H%oQvek=IHtm!JG){WrP4=1QS zP0t7OM2u2hxBnEZuWG5aDNBPZYF1TWHd_!}v#pjYzj0~sRLk+|*u0;Eg%?dyxnErf zeszD6DzM;UFn0V@_0#FA!KA- z`x$rD4};<29laVXx6K>8pBNL|+iTO#hg-*}x)&l;LgkUF^4T(Ks;|GgTJe8s z!kKQWqAyIf$X8a4TY4$Dr*d)SPd^)M|9V+9WA3Hk*iQY_k-J6J?7$#(;KDm<#&3hv z#wNwpM-$@Jmae7L2Y*ggzqG8OMkUQui|hDQi?HQt`m$(Mvcwl^a7cTVSnfMDMfFox zH>Ri`e;lN0UOu22{x(VFTzEva$T>}QNI9uyhtE=5C!SGPGbO4e!_KJ(Pv@xT<)5g) zs8#BG(Pt`Z$d~G8U<=^T>QB`B6IQ8FKVMht#Zp!1;Z?P~#bWjLo0rwO9t+jbg=bWO zHxiY+eL_`QI#b0r-lN){7_a7^Ojo_fk5z|%TC4gl?V{fJe7Y(#zm^Ic@}X+GGN1bH z@BgU*hfW30X8kdE>z^sXDL38^{;zgOu;cJ{svVB9No`a~93L!etXkn1zAK=H;<$Jx zxB3-F^?Ny$2gi}$bF0HR9%XK%?%-IGwYi#yqk3Xd+x|I@(`>5(XuEwc~ zI2JUWtmfcYnKn&*j^nj;3sn{zPsT4*_i)tP@U;ryxU^w|`US_{-;&iX9NimjQL#9_ zIPwEzqYUfX=NE{v<6>*&J_LDk=qj9Uc;=hD?}9P|4IRU(cRZMUf9 zIMQn-t00c*``75>)ag}<$Cf#>_2EtUSn=?$sHKlbZ{$!srhWKrkjGc5RB#QBM)0+J z@VV;nwW092oA9+s@VTn+wXyKIN$|Di@VWQlYrEldiSV^{@VQg)wNK!4$KY$z;B(vH zYm?z~3cl7AK6eei)*3#y0=_l^KDPkA))YQB3cmIZd~Pm$Z66~0EFD+pg32A``8UkkwJ=xYh^Ir`cH`W$?XK35vPmK#3z0er0xd@c^Y_C0*= zHhk@8_*^)AZ8ChWKe(+EIPMK_n*zrj1GhZ^$9)WL%LR_x0B)-bj{64Owj3N+1>Ck8 z9Cs1ib^;t%6x>z_99It9wgwz`9o*Il95)c$_Bl8%Ke#O?IIau0?N@NzeQ;X}IPOny zTLd_+Ah_)VaNHzt+neCHnc%h`r(aX`!EG(UaUH>JJHT<>z->*yal626bHQ;3z-d2& z+x7v^0(*hmdVu39f!lrr#~lZ^C4=J%f!qAxxLx2ja$G5J8#%5NxQ!gQ5!^j?4+sJY2!ENNY2yh!Y?f|&$E;#NLGzzuKHfR!RlW(C(s7)F|gHVesg9dpC zEiw|CV-U1Q=B-78e?fB;f!1)LIVM9}#6V+Agtkb4##ja|@jW!f3uuW-&=j|z9R@%{ zT!MCJ0S!?ITH!e~!wG1G2xx|@&<5W^BTRudCuG(lZxfx^%P?GXDbfCO1JWzJQpV53zRzV(>}C+~J75KE&Foh`C=O#x_8#orlB{ZR@h@r(C-S6F(=`B6vlUC;luQj59tb8=vxWV+DVf@A*s4J()M~4K>XSk(*0SQK zDb!|7KV6wZ?bYY-@)T;Z58qmqLao&ya&ro`SEt6?Q>d-lZ8(@htu^bwkrZmF-OFdC zP+O%poSQ=Jlrv;;3boYh#g?W}Gu8NEp~iK$7pG7oWpA3ELe1oFpPoWZG<5Fz6lx^@ zg!L)ZK;gN2rce_RseRm+9sfmYoi^7_SElx<{>I!&)Hao-E~rYa^Qz{ws?;*2D)p#J zZIgPqbX97Zv6;?Pp@xaQ5LJcRMIHDvlA2}D7ZIDNRiKr%W`;Hv^h0Q4K|h2R7W6}C zVL?p{?JKB(|JqViQ2Rpj3Tj_yTtTf1jVq{ip=kxREi|p5wuOcj)Uwd9f?5`uRZzP^ zvkGcgXjDP13XO{IhTfqj71XBCq=MQM8dOk=LURggPiRg-KZM2`hp#cT8Ahe&L288Al)PC?oKQ$jT zo}XH;NB3KT+Ad428-m(yf7A1V+OEg;p9Hntx|F3tYrAF(1hrj-jY|c!-SK%p3u?R2 zR~H1e-J1(83TnF(r>_cXyH2emh&Ls*-R1lxB(+^mQASeR zjX7CUQrk@`=a zyJdBJlG<+8vS`^HaducpdszZ;cDm{(XCuxY`*D!Gf;ijww@I=F;%v*D(_{|B**W2} zm7 z(@APOXgW!42Tdob?V#xdwH2`|HCA@({G$8xf;qFSBly zUz>HS{K~9bWkqPalP$-~pP}vEUNlL*1#P$X{v=rf+OG5Xsq&Ipx5~a|-6}(&?Jn%y zC_6&iZLXUl|Ae-C_uOuI6WXrrl>;)=tXt(+vu>4B%(_(u%(_*^n02e{1Z_8OcaFdg zXghFPV3*N$fplQcgE<0S&AK&E-mF{Yk7nH}3qad-m~mI`gtogp{FV%dPB>8gybOo7 z8`$}b{2JQs^#!T&7PQ@<;>+YXXuB6@2Fp#*c2jm$l3zjFl{tD+IUU*# znoh2Owu7dV&fu}sbn*_g9WdWG@YCYZ3j&!n?u_{ z)5%8AcF=UP6SN&PUErz7;{+N(+aZ<)t{P1jxC}%r4HPqZn!rP7JH*mJC1^Xu(tw1v zgQkh~^oCIwLO($DG+dh~^bh4~UCPwW|N`|JBvu7qHL(|E#tG6UW)5)4uw@}l`%I#vP>14IR1E}d_ z=|eHe&~)^$%2qrb9g0 zK}{#ycYntNO(#$8D(r!#lTpFU9%wpweAEwu3fvV7S;`8ZSt3cBU zC+o_J^urg>cJ#w7(00&tat*W{{jd(S9W1Z@XRCljFUpy{NuwJ0^6d>z^jnoh<; z+d+*%sOknobsmwu7dVzd_qU)5!+V zcF=Sp8QKn-PAq}8gQk;Rq3xjQWF}}kXgawY+76mdc7e8orju)+?V#!8YG^xXI{7ZN z9W0&NFPC&xqELDR`v(00&tvL&<~G@Wb0~6d9pmhHXgkJP z0d2=PI}_Rtnob^twu7dV2chkt>E!p&cF=Tk8?+rXo%|Kr4w_Cbfwn`wPR@X~gQk;1 zpzWaPO(&C}?V#!8d1yOmI>uRQI>uRQIvE3P2TdpYK-)pn$&aD! zpy^~eXgg>+83SzxO(zFJ+dv)uguHz96UB@FHx{e2R-31)fb=7cC z*Zqj&0d(Cx9E+gq7U1we*Hy;x61whh96so}S~xt=b(L|nqYiW(j|jG7 zIv#VO>v&jQC#|lN9_YH7I8H#xe1vIj$qd!{?A27E$my;zRh{Pw=(T@VUeAwHffa z&G5Bp@VOoEwI1-f%kZ^m_}pjkwUO|-Ic6Ophr`#3!{=t2b%Z=_))5l9VeNCs4QrpH zuhHk|YxFt#8hwtwh8(f>HROo3uOUaQeGNHciQKRp1D``~SQduQAvY|Gz~}P8*An1! z72#`j;B(RNwGr^Sp76Cr@VOrFwIlGk;_$UR@VVCTwZibZzVNk8@VVdNYv$j>BGr<~Zy{XpX~PgyuNxMQD!0UWDejlV;s2^O<$4ENa%R@|;<>${uFj zD&H{cR@vUHTjd{S-70@G>sI-?S+{C#D+G=sw;h{)O?ts?(crk&;5G%0YX@#?4vyPm z)~x}qSIKeMli<2F(9x`01Es-jN5OIXz-?Q=ak;^50dU+_a9c-kTw!qA6>wY;aN9v} z+*)wkAaL9baN8T;xG~_i!Qi-W!EOJ5<5q*)rh?<%0k@R}$0=~z18`ifOgc{@_nJJ3 z+-mY9GTP)xgFCMCL*)WlSw&@+5Me$&<)L#8PUzFA+ zM@+qeSlS#hH5{?@8Di=$h^6HaQ*R@deuJ1g7qPT7Vrpx|(pJ=Vh^22MrglRtJ%O0| z4`L~`T?>;Z3H)yIB!TNTrj|5$lE5>QCka$Hd6GbVlP3w}MJ#1ZonrDN^0~>A$mu3e zB3qk0i3~G&5_!SoNn~A>oy-Y+TRqfv*VdQno!buOc9g*5D$NWVeYC9seU5y#@{zYoL>+8l> zrM4qd+ueCqY7@2HpxzOisO{W}jlZY1b9dCOOl>#R$;y14bmul=zD~|h98-nb?vLa1 zw6=R<^2YKzlQ)(tP2O1gP2O0}$J&D0ZYb6k)OP=1kD7j%6>AG>yMb6+P}}vy+Jf5d z6Ra($?fyjGnA+|<))v%uN3ph`w#$LF1+`reYYS?-qgY!|+l|E9g4)iDwFR|Z4XiDw z?V4e2L2Y*fYYS?-Dkg6n_|fEzHB#H9sDpzZ3jOLQrm67+Jf3{KGqi0cD=EdCGX|HT9&-W zwJg`PT+4DzyB=%VdeC<3u$E1Nwu{7C_Dg8H(^$)LO zYguZ$*RYnQwgd0!H7$5guW7-1dQA)7(`(vsSj)Zz-kXZG>=E#u#9Fo$c&{zivOB?h z9kG^e3f@b@T9#|tAFzfc-zmGM?Si!|*R&O|mZi2kinVMCc<)WDWd(R|AJ($%zxBLQb9Fs5tOm8rHJUz(DdH@1CXBDh+vyxiJ+m*Sb0;GaXPG;B3vrhFVqu80VaS~f zMx3pR+=(A?wmotuLmTgr{je`K7jZTYxs!v4v+p8z@;c&dd*n{uM4TOh+{p&SS>)@2 zrx9n1BX=?hakdk3burL&<&xT{63}&aA6Dn;n6tZtT-`6wbv2Nys|sCr6uG)X&~*=y ztGf$bw-~v)`OtM$k*li$UH1?6U|$$rr>w41)OGWbtD~-4fm|JRT@K{xvP0KBLay#1 zbe-LY)ww$6?3kmV-NN?blrC3>XM=B0@#DC4qf*?a&@(!>;A$X z?0x9ES;*B*g0A}-xw_TJ+1*8MxCyk~5afnyLfcJ5Zuk#qI~Td(YS4DgkQ<%~ZMO@# z;d;<^F~|+igSH!q-0&G_yQ#o?g z7em{HBRA|q+s#03cmcHC1>}a$LECW;wi&ctR^*1Gq3vRj8(s))myF!-AJBFSkQ;sm zZTF=76V(vfj(e|dv3@uO`~Wx*x#31wN5I$AchGk5HMNR4V&sM|K-+QO|1D@c?)$^% zB=`Nfj^MsO*Ad)cVkP%ru@|cmd$AJS#=Tg*7lFN432sx^i_|n zb!!~0RHUaa6A>_5npa1R!H zv4VTB*ozg&*Ksdaa1R!Hv4VTB*ozh1gT-E~;2tdYVg>hLu@@`22aCN}YPxjn#p=B; z?8WN6FYLwYy)W#=>bEu^$4C0o2RPu+~!%Ad9^CkWPGrWSgS&wD^G`CcBtoh76s?b zPgh;1ocDz9I-y>EvNl-p_cQ9-L61ChcHdLE=LCacpFCE%+wSlTc=bYsH$4z6{oF|( znYQ24Z`><M^ajPAdMY%@m;UU~&EU1N1=F*1 zx$3E(KYRME`=^83w&qM<-F>yE#ZOt&7u-J?92}P;-B)&nr}>G$RmYC|gQdGT>E&)E zSN-+LbrsmXC0KLREj6%I_bT3!Gu4Toe-HMXGge((e;WI()l_P;MZuOUs;T5Ai-He2 zPgLXn{w3J;`eZdD;&Sk-xMixz9!E7l`@Onbwt(6_e4p~lQY!ZF6}9I|ZMCT79rgU< zdiY$;J+-4-0~K~SXL`#P-If1H&h*Qzx~o5jzf>!ZwNf1lzfdL4MX8I`{#1v?*Hw)Y ze^xEMRaMmMqt!3La;j_f-fG;*!m2>$l4||h^TA6UN~&$E&j&xr8>eRX3RkavHbi9^ zR6-5;ZMv%Zpq4uLC`mOAYpedAxJikd1JsiuhgI{gQ&h!~r`6#WvsJ@S&#J6xiK=n- zr>esC)hZ&_Q?(~;wc4NcnktuliTds871e9$BDLd_Q|jRAS*p#CyVN%)$Enk=$Ef2t zX0@rWrr~ILAeU-^W8l7AY5Q|o z@QoUdV_VP7Dg{U5YFkx(98q_UtHwB%-9N4t;F!Am2Q?8#lSfK5z|nSAifV)7tqEW1 z<1)skDaL3r#wHeHv=L*IA7iu=V{;K>v;bohk1={3W0M7AmB-j{jQV11I7WvtHbIOL$L0f! z(M9-9E%?yy@SQ&Jp&#HoyWm6H;X5thLv!Fe_uxY-;XASLp|onWz0>^(LJ(*lnG&D7t9P?z`$0_8NF7rN5A*U26urh^Q@@avsDddnX z#}B8FJDzq-Od)6ZKUk7NuIM;>Q3^TY@96XtazmAw>r==H{5%G^fS<=82MpZar84LK z2VW&t<(vl>;`fUdkOKwB2izyff#5vB@d4KfavnHNkn6y0f*c1<6XZ5(G2e85eD;{#3-c6EU66w=uRkrwK|7i)66B!G zO%@4q(1gE#5#*p*5tjuysM#Jzu7&^HFIzy8gZ#3TBnR!gQd^RPUVL0nl7oWX8bDLt zQ>|Ncm*k*pt-9ljS2@$aIMzy%gG!x?lH{Nt$JdqgpVr>0lKyicSWY&_{F-pGu;l#O zu=c#*{7PGWUT}WR=@l+VV18vAR6^#!{Hp$-mLvx?3u`O)V}8}SIY2%$^GiO){5sNN zwj>8-OG}jGpvdj3B{^tc+G<%2^XuL0OXNPxuRco`$tz}lNpjGJljCGG<`=j}l7qlK zk{kr?k>nt7k0b|ydn7ps+#|_B;2ud10{2LA5V%K@gTOtK90cx>nt7k0b}dcjV9D zpuTg)A~&Mrm)vRM7jmYHg7-U5l+#W8lFPtB@EsWq4r+Gxd-(($1n!abO#G4uO#G4# zI0(KYcY%YzJ%Jb#zXHFT_$61H_$AALgDzM5Q|btcmaGmA0{6(H z;2_Mcz(8;i=2oBpI0$nq@Ddz^xfNJL4m$C->;?|P+>(s*;2zoXyQE}rk9_^(E#w}V z?M6>>kBrRwQ8Ktk7HwIB+#|Q|8Bgw!6)KD;_sI1d=aYNnu=iGzd*qc1^~pVfi_=?^ zdjekI@;2sJ6BcOj|V{j0-N8SMkfqNwM54lG||B!nm^bfg5rh$XNJ%K225V$7* z{X_1N&_CoJ3H?Lvkq5y+;2wz>M(&Znf`d4}#-A)KIlsOE2XTIF2M2+BB=irtN0NiU zJ<HpQbpLfPWU@m<;~m(Fpv*!}5vOAgJZ)nB0obTN@zn-5M#u# zxr{L)KM%(ky=M4X*2LHh!WcyvewOtNKkKpK7;$VkMwXwYK^w~J z7^D3dn{JuJTB?l47LClwvgU*M1 z?;!_Wdv~jc92DB>xQ85+?c?7)kf}6=f4!D^d zl-cM*SpeKj4k~T*p$vkX$w40)eHd_zJ`6lC`Y`aR(T9QV;AW0b1EUXh?4tiLb}@zp zjeeF}5xdAiQxLlt!{#7%k%O8ec9DbNKRSlNe{>8xWc0I+T?^qqKOlCIgW4MX9Jqnl zMGjhH^s_97*hLOHX7sacgV@y&{&Uf+FXTkTc5;wiU+CCQ4#NCWoL@N*+sQ#S5ZgJw znj^N8gD}4oIf$|S5#|^4kB;#<5Zf8!E1UI&+;7$wI=1h{{Nnn89CQS+Jr(n7BVv1N z%&)U%{iU@JHBc*PpXT77!DjuXwGa8{2(%9l@{h9oqcu=2XrI@>KX(14wGTCrU4O|I z&^}EJ|0wd0U4LoqLk-jp+NU)%P+@4F0^lF6z3>en*$LWkDmW+~wBaUj&;@8i1r8bp zZMX;=#I;u_IA{R0p#TSQ?ezgT=n1r8GjI^}k7@;eeiz#CI5?;-wBhUE=lalw)xgiC zp$!j%pD{M7g5hV?&+xOt7)h>A$+CgD3=gK6!IHJIeu3u`c~ov{X!Tzg>+rnNKHU=sR= zYcSau+L`f-YYVKw^x6VzFu}FgViVuF1`}L+VGTy^;TnwG!!;PWhifpsw!j)paP5UP zm|k084JNqu!WvAkEwBdDYYVKw^xEQ?iSJy439h}c2GeT`tieR?{loN8XiR<|{|*O+ z*}sbe+b50|Cr)gsO^nCU4u1~=Rt8o%xutfob2q%7mYeN6IewU!58T>5L2PX~O570F zy~KV)hKYU!5`8b)CWxqJqr{}F*S*oesP@;r15obtH0SmDAVF+L`&xUi>GKv|`^`HK z*IPbpn3!B~mhZ!M38K#jqeP#-uX%d`KW}i|+ZN@QE1lKfliyN$1illE=gBQL-``Id zYrfx~dqHY#mM@*7pHGdy@Vm+S96Vz|pW_O14xSaL&vAv+=ipgMIA@@Lxc<&|c)3*E z#}$M1b@04`Jpa_9eQFBthu?qK_vQD#9mkyGI3@Ktj>GG)e7HWxaZc-V9EazOyl_g_ zo!x2r{kdcMJ!oZ`F6Xtcq?>y@4Pl)t7CJjo=Zbu(r)%f^<1_ttkNLwj4suP~A;>EA7oTlYLJ+-bt(V+AHtqX94d*C(c**LQL9EG3$IkHb0ow=6`o}`*Ayli5F=1 zZT19l9Orc^I6y>qF5vy3_@>$oarDDc21kFCr7eLkS&Ts0xNk>^ionwL?~*{aX>Hq# zM?LLSd+=|T)tos@gj62n`>@taZzkZzn5W*+zM;Ne&EiD@Fs{cialG|l-;Ec~ytls? z?2EYZi?_ya@xGozhlwY32Ki#94-=I$5A_XM|I%9?_~pZ=-gnCk^_6QHFCu_Z-wzWp zRfhO>kIm$Jd1bKAsqvccV#^`E_ev!Q=da%D8G*L{lLVeHsBwZ>{Z zfAW0a)N1h?ebx7k5a0efN_>%?AQl`>^lff6T6}tZweMyYJP)82f5UsNH+AJ)-ya{W z^v?Kmlt`QypBg{k6~~rLO1=H_df&90UwP*y&GF5fx6)f0*Uz2aCpBz^E8hBYY-;k9 z^?J_s`tiAULAeBxfu%8TX>&dk|L@-!bs24mY}XT53g;33@89&FTzj_EZiD&GzuRH% z6X|~qF#m~d$qTxizk_4S*n&Kf9(Kt4xo4K|kH|ybjr|AvKKkQ{#`LMf1nrqO@GJ%3 zJAcOGnJcq=zv8)Rw?7&s2L5U0-IVhfXWZlItl#wfJJs?BjW2uu;H@5q-8lR+luRF?=?zf`{)NRvDxbV-lw?l zz0Lc*o6wK010HFt9%uUZ_m8H3yH3OlzK*YOKJS~*?FTRW*>T$e@3Ag3eLH_V;H|u8 zpfBf?#~MEwJxo-E-Taq$jdw4{i=WW$7|t(*^Q-mz!Am@HZ>1jBl?#?=9y6~G&sEc} z*Ky422dC)qaGcgvM(Xh|w%xoBl@1$hcw>pa4#(=WzNRaZ^fkdzcFZ!yFk?(J#@Jlb z73P|*FxSL0G;qy~vWzy%?KRKZdot>6Fl_%2KzpO&TLQQ!9e%}?9-Nvf}7qij3Q zHdya%GB5XzJTq&0rx&@Ic5mKf@35ykyeT~%dXqwTde=?P@9SRiLE7%Ii+u%$y|qKk z{la%J?X4XZdM@yNG_uf+E0gYei~LY%$7iQEdmCKo9-JFoRl`8(;?sYgBPXk|89$K^R4VVeptB1d%9lej>h{dc|((KrEMNL z-n$a_owRS57><4%@17tU;JUeUj}V1%pC*k)h@QCbf$<4~{ixOYW5IrHo!M8gpZo6i z6Aucn^S-?yP@4z;Zs{MR%fdH|5Eo{Iju#yv@+Ae$J;FyH*1KjUVJ&y&ztUA2GvH*0 z`wj8^H2hKOx7U(=pG<$0+VZ_5U(Ub!ruJUF%vY_$I`6qRM*H%9x6+$jA9F-@PCamM ztQcP6PU@)Y<3vf%oz%Z>xnlniJiBKAp4S@hiWghPijmpz_t>%G_~8-ar)qfaVp@V| z)hogGSF_QgRjWC^SMQAxm%o_r+g*8#*jnN%-}a9(r>!gUo$v9m%xSAW{M6TT@1)d5 zl@|N*e6!ZuXV*yIz&b0vJ?r9mQ?24t7hf7HUcdTx>dTVj#JEf^QtzC_^KOPaX+tk= z^!+u>NgEmasc+)Rv8jcNFZOl+=PU1nzzE;gQ7gTl*28m&CnGNWK2~Iz|0p%N!Z=Z2 z^P|+=*YVt)z&JnWP5{rIj+5^Nqa%$%~WFXj-P8DIXx?%Zda`G zHyTIY2-D|(9nxE4;MNL_J0Bc3crHZqQr7Sy8b6Jys&U-t#u{fGHP7GPFws0mu3a|r zyW@1eWb{sjn?^frYin%BK9_Y%JM+AylIQp6`|$ZUzD|eHCpiSF8zNBqF|Ay^}=K78v4?YLS*g33? z=O^m>hguuYPt?~7({>gI&rj6#;kG{9+GVYc=O^m+k+waapQzi{u=RL;BJAxhp9f6e zG0$P$s{O|m#-CgftNjbl|J445=RIlv!}GnhKe}R!_D^VP?XS3w_Fq?|X@AD=AZq`{ znn3%zD^_X$$J#*82UonV=Z7mc==p;ArsofyPhFAo3C}Zo%=v}qk9#=Zp!xLtbHz

&t0uxpSwEXqiuTLK6-4PyV^LiUK-~SRyfK0 ze|h~}QfPktoKpOPkA3dyH2b@Xi1D(|S#4pTv)a%;XZ2V6oYnX2b5?ekWjynLm{&vDk_b%Kj4@^$06UXRT4R?q2iaYZBhyw&&Z^HwL>=dA{E3=unL zjS$aA3Lo(iuu9o)y%Od1Esm?5&(C)M8~CAaM`XM4DCaq>C$gO95_vA`c^=1seQJp^ z;tsSm<*s;u>#&S1SWaX+Q%=iqczw3Xz;IljH=kiWM`5226E#Aa^*uEI9E72|+usm=Q%6TsDPvq<4HHf?hUnkFFpV-eKC?m41 zDR=dKGhQdl*^=$ppNzkW8FdE#yViput+juBZ+}m;iv2y&^Y-^dA7@I`aq9c38Ghe8 zh1bhx{l2mF`_|U)w_3liXZ^l`_50uL^M+g7=MBf$=M8VL&l~<{TPNN3&URkxw)3K> zou6Io^MqgMcCPrw`nkCd-WTiV=J!jXkF9@Cw*Fnh`gdmQ-?RSp@6vcZu2@{j_;>%O z#=npC4CnoHTQtNLyY*BlUp!U2ner2)uWE{Y1Y02*ho^e%gHfM81BO^YusQIBv@M`Xlu3 z#2A~eKSIZ8gW>3J1mdpLXkI^U*V=sjyk3$;zWxXuXASc8)4rt9yncOu+Yi2e+I;;) zzJ4NKKhNXqC-U{PoUcDZTq$Pe&9{ZJ>iJWn;dHIrq6eFJ5qZ$Wi|0k`ypaR-bGox- zc67TH_Bq`L?7X>S=Z*Q@TI90qyg6d$O=UZ8YTJ1;*Up=(cHT6x^JcT1H}`Bj>7ajC z7xT6KLfuckZ{gMB@qS2)Q5It?#%kpIXWGSCOt9rx=iq$$uc>!85$V6iRvPKQwCTS@ zzJEl%f5vvLooF%1;zo^G;lJb=BHQzMfd((x`g9aIe z8`(i)`8B0A*01zJ$G6Hm%WXd-~Y}+(e9LY07T*yB{RQPR-wQnbh&2JYKtzNDWtv{Lce zxj#vC#_ztwPWw!pd;7G%*W}N{kcNHyZMQBFGuy24-%eQ~vbQbdANyp!I992jfBU2P zVpPxdz8zy`i(MVw_OBj2Th#dd4PS@ksbcNk^}c(Xriz|Z+SHzZZh~kU^M;Q&qVmhs zY=KGQj~idt#;2c!`nyr;tN31`!^<{l(Vz4Zh?|awFNGI@UeJf!3{6*ZD4(r zvz@cl>m`zxQ*b_UJ@CKs2(ek0M+mkXv7xW{7B-RhWIH0yTZ4NNdGG(qBZMiB(Cv91 z`$#m`UFRpV{U&=||7P>t-YdoW!>=4?@v36*KWMI7<+To>Pu{G~X9YuVjpjNMYx(XA zw2yY_(%)D7)4KZaCpl(o+)|LwO?O4Brqnbp4#!ECoAovC=i++QafTv)L;R!AK*4e2 z-yAn0$BoEwBk~#?MRU~{|!3wr|n0$zNRV1+}G`hJdgcgy(_lt;`8J2J4>VZdzD;w z@OpgCu%ofe{aB5+ck=3v^G^?h&i(BCqd>hj1=_TX#((u%wyD>$V7)e(oQf?AW_F6? zjrKaB1)Dn|Egh$Ub1x)o%g}=S>Utn=fk586p#@t;JNH9iW@#CUDijusj>?+1n3D&} zB`G>kuuW9n=s?ysRUD^@lP8;#T@;LNS;onmtDaM_cv!TPGuL}go;*%?o>=EqAWu?A z(L9mP>lGKYddCULd^=N%=s>2>;vsngS@JqrZ-rDTSiq_2qfdX|iJFm^o(renvmD9fL73qXUwOTRp%d*{^qiB>hZ{W4B@-=?D zU{5F4n7V3HZ3&-XxG%lx;DUTD2`f`htvN;cPMJE+nva($JIR%%@DTM#pt-$}Y&KZ|;X&{@E zcL^lRoNUgZ!cHgn!{ zLO-bHgcod+&B>h4$&=G59n!=p)c$?^tWrpL%cyKlp7|lUGri+Dn=;+Y)IPLSyFjT{ zq2Vz};W2Zwwtt-u$Nqn8-3NTs#@;XdX}fD1+iQ=p!8F@|8`bpQtLY|~;?R2uy$47k zp;yxaglak|)X)hK0)$=@u<0d03ge~ku2!1+Th7D#a-Mt7$;Z-n{v&Be8jVJ?(!ws& z=L{vym>l1BL3~I2w>G|G(LgdDb48JwNJt41R448qB^0c5!op- zKE3TZUbGW-82ygRdb@dWT~;@vUS#;uz?zY1Z3+_SU>3V4JskUwvKU27wjiO2#O@@v{Df8@fh7nlO?pP9FTj6^=eaa?unol_L@H*+4Q7MG6Zz*V>xp}ybJ85= zf5J>2Jb;(XjK4yH?+NEi)SX^|Es2{rdWVNah7sp&5ko5y_B5P*AI_SR*b*6UZ8jXB z@irby%Vxz_rMzucd`8d6cRMK}>r6mY#-#wdSdgc-JWm673IBcyAYT$kHNx5vniA-o zN<)L=h~rmVSl)ULXEz5AMrS_MVK;5gY9yjA>P^}$TUh%8#EDicAd-+F)R{?+J5E@#O*d(dDICD|s<|M#J$}V2wv4@Zigs!kVJ@!1s zGO`Zac}M0zt8mdCC`ka0Yh_}ylX4kZ@gBPjDo)}u7W89|lO%9_0CAGAsKS*0=5U^+ z5uz2rCoAFR&Jo*ViZbN^EAolqq=0Z-pg@(F1i=agTxGNbCwI6rROAn+L<6Ik zy*UXhkP|{G=3#YN9n{bf_CQqsJZN^>A7m*RYvU{0LW&T3X;O4;d_9305wLlfyg&N39X+Y!j+0(*+`Ao6Y$hfAxYCXulwGagV4eJpy{B1@^?TrGJHxuC_1G zyho*{=UgZJ7NP8hfh_JD}cGQtjR^5hu5th--!QR*j zqS(z-J1q!LPm7GKcbtSrp7YmKai6bC7wPR9HEPo+y&Wek_+4tGzX~UWx2yaR4LSK zAz`ci$v7tqw989bEcJiXJH#J#CQz+wELze%bxH4lCB0KQ2@gaSu#`l)M zT#kzgt|7SEluC<~q}=4d_Qm~8sk0p+zochHFGG`*8I6W0ki;!ZYg-J9#kP$cO$1t$ z`9uU0x%_aE@U|=_rtKsLBgJCKQb+h?d`w*5!YBV8nMab8$&u-jgxLM448@2Tmj3AT4i4{e+Mh%bOTGWQtD599t zQ_#+S4kuNq@Q^%j^X5S_hz1asBCNd;p+3n+5LPrawo}&m@W3(5<|Otw$yUqo;u|FP zK`63SBlgH5C?4lntd9RA?P){PuGH>Tby%#QN%(Hnc9 zp+{Gz9BL~kCkpgM*QIB2>VSkP?dwIATRvc`EyCG_WH}OfxwYw2^3lm?-BPpSmn}FF zRxEi-AhB;`xEPmPwjhC%vL&|GpblpnN)w|uqVYeK&xW1}4(hOCLpo(84@_$}jmHnz zxScx3uzb$j)Zc_S<5|0WnUfi9Lg^b4I*68!-qLm|CG#j7M8gIwDV=9Qw6m9;2HhY5 zkNoFeD3MauLsM)gdB~S`TuyAm+fELQnjFwJ5T~u3l!%(V1Xq?f#o3)W88YHd58u4TD678_>hL z(G?Q#C*h&Q`7bH<#;)n&L5n}33x`mBr#QWtkb^UUqVqs4KAi;E$P3Jv9BKDs9%!m# z@5QB%dK4S6k)jsIN3oM+(v)aIEzQ`^4fF}BYtdh7bs=@xHZp8|*DNgc_AHUH9`Z$# z{Y?%xILxdfl%XqRCkfilEY@CcCGGW~#e*DF=OpCxUEVi?RN5Bc4)6&d!db`tCmoII zxkKnGZf@76jT+kFqe5GP`tvFS@S2pv&`fFLeX!XsE8p&OX_D1S7xW5=@!=B7HvpSq&piPnb%-DGnXu_XkzBt5Bhx9FYXQN)=+C@VmmLrE;zWf$jd8MlkwzHj|& zJGwuPCg}Z5ZjuL90~M)^BIVlrOQJMZ;o^UjBHA6`{)ZIC zlG6QOl2^08F+yaCzepqw`BUtdIgB-RxautZkzOmE zX6fEhv`TA>Z==8cZLOv~iqMoatK8@GY4jJCuJczgDPk*-xh0(W`huMPYb1T9m8#*(MDu3C^ zOABgtpFFmzQk)|rE4Rnr;bppi!L^TU?nHI_t>o)T>6(5=4mWJ4*&L!{pd!Ivl5}m` zMD{oBsLk)mJ=;(nQRa%dlKf(=CA6z9OGj!ti>$xQDxaY<$#2$=XwP*M+F#SzWYc-k zw83a?enW20rXynqYnn;+?PbBQu*CgEbWq|DO{bEt-a5V_pKFWK_FHH))gNzU6;E@~ zaVt_vUG=9lIl!VHagm^J64Z>S07_e1J1MGLf0V_F`j^nc`Vq;o3R6^(U`lCTT|mc7 zBeWAv=}qq^O(LLYCdKf%ns@NwrM)|Aqppy8CxhZ<434;n^kCRCr&gAj_c0IEaj z&(IJ`7eX~DJq8V?bP-gI(qExZC|wLyrt}mvh|(oc1xn9A11bFmN}=>TG=S2j*tcJx zg*jre$@Ke6NbFCezr>zMqMg3LzO7vsyN>EF=;Lp(Uy4zB1ADg*W#3{gv6SA%0@!sc zAk>a~P;W|CTKaHT${t!jH|RxgPqG@uEdzg`@O?C3Kn- zJ4Lt6u*K@Ot!*x0@)mT5CAhAO{f*C#a(`?mLmX57MPo-1Y)nWCLh)GaVp4^&R?&n? z(!<0h(iHPZ%7d8uj5wMExNrtFr+cu5#s`^BrG-}XVXi!f3Rwkc)D@(r>+i{t`lWH8 z>(jRS2XZy^Rl(x}=rx2^_GY>y{p%Ta?Xo_FtP=F83#kq-uIls!61l;b+MVk{w}-pS zhdKK>o5hXP%>psgIPA?$lq%+4>^&pQ_6>VMn(oI1cfV+WYi^A|&V_?h5_a z-jBlhOj5L?9v?&|1r0lfUcjKmBfcW{X*T)*ISF-_<2t;&KkmzRld(sGaB&Gh*8^8% zF)t6@5?-%sR@b$-^_q%)v*FV7d+L?67t^x|9fdPGlMZDl75zwi0*2~@UV+}({!LLM zbMal`vu!2TN7_y;44`PA_>)YvGKtN%nRMcs`r`DjGzQ0AlhJyPPiV5Ky|$gNP5bJ3 z{>0V2^zqu7Ee>V8_Y4Mb;XZY?8dTQplw^vBQ=Vhw@T5#1SDK2SU5jPJ>W$9DWTL;a#1j9S?Y>E990X3_ftVks=U8Gs z(StERQZKLsn)G3qAELjp#7v?`Vt#;LVTox(kHLIzz19+66FnaD-SkFFd`a{~%xCED zEb*EC9JA?qyCo**$#!2G{gWle=_z(!bA7-PqxE#VudzO2i4l61-B(ZlYKftGuH9Et zpSHv&I@9i}qAyrtfL^q4#CIgm4Qqs1egc}_wz?;Mn~sjc_vGL=LeKjK|8{wvlu`PD zgSbvi#KnzoCbS)PawgHkalCpp>VzXzR)0jt=s<6RzE6z>WSjLXj#YPSB@-nyy^JFi zqaRajo1Y-2=%Uw95wGbVNH3uOp}rcL{)Y4ny^c;>NpF(r<0CE9g>hB&{h{M${y>Ut zq4CdPEZAe~9UXRiyuW&~2StM`((nrmq8asa|W>fe1 ztC)YWPZm?XfV}<`Sp#1QTG1Xu>)7q(z9y3#4)k_9Y(fud;uKBWeP`J};(ZA%Z+GI# z>I&+yM$@XN&_~YLM0KTe7BlJHqIdBBe$rln#CF=;oZ!k|`ZAX9xJA>lmof-Rcz37v z2}XCK{bx=s7in}z)BI1cmc|FEF7V_iVb2`_ryTR{6hq&y*b!?&ppAYPjgI$6j?icl z$pb>8onMlV$P^k{J^EfX^uZeCkVm+(#_OM*)ai;&pw);gD2N(XJG}$_EkRr1ns3A0 zihejt3Wdh>>rTqP=%7eGZGVW4-4jwsn`Ln*6Rd1>T3XDf!>oDeuQcq9R=Fo#WfhH} z&v1_XV!dsO9%VFrY!ywS*~x!c{hcfEYVTOLBi)i{-7kEQo>0o)TU~~FN z7sCBQ!QV^Mw+>EUy9%Mp@KT3dD??xF5c=|29Q;g2uxwls*dr@OqqlqOMFq|F<@45O z*L6wF&giO|o!6B#yQ<4-_M5J**>PP*vtM{k%?|PUnjLuck!Jft5!f4sKfk(KYPKo3 z70!5`q1h2uSD*Ggauo8eBw;nOvBS}O)tu4V`CbR&gT4-?Z_E(%<$@S>>i|Z*Xozg2 zyU&iffSTlagm@aM1%1TxB=uwkCr%wG`Ql(`v|Gk*4D0!~K4ma_cHnvaTioahp zwDb|(xQTUu?hmLNV0q{fj;s9$p(i6Oz z*L1LxqDm#}9Q{pKtZZGPC+(H)o3ZQ+t^5+POQJ$q>k2)mE0?gY)6=424q{hmnU`h+ zJ4efu#U}saag`Cf!h?Kfl0Wtjmb)iPCR#c4nl4im>x8bFW!N>E@DG-|wU;+7F^lUU zt2W!O`S2y?8*0-L6%JagNzy#d>z&VKdPw#GbT6$#^wns-$Qu~$c^2djcep$O{jCLo z-cNFl;tt~%6I~G8uKuS-kaNsyuXiTb;SH;Nv{RJpgx6j_cBzBceQ}oSE)S1UU!~-Y zRA($P!*NTJYqnv(P+cegR>RTJS{Gop=UbUBA9&K_H41EIEdAyMMsv+R>^o+(e|k#O z>btQV<5mB@$#ki}b5vKiPE%ie@*Y#Pym`%LHM8x~>@gPD#jRF8LF$8=c%tb+iQwc>nEF)`V4C-L$6q@V#Hpd^I88g9UXYrv@myG zilv&=ZEEgjd4)5eSg;PoxJXrV9}BzS8~7W0^2Ar3W34j_bfwd%9&aOQt~{amI8;wH zU$W^`k8?uP%<*ihNk8@9Nsq@zEy|~vxP$qgw8O0o`#FrJ#ywBj!ZkZd*+2E8JNSYaB4i)Kd|f zX6jJf5*+;0)HA@TrXG*rSX0l2rkMIuXq5S!t<>28D#{$h%nSninVtB2)&HAQvkxaq3{ois&N=!EI31^s4<%FrnjRgGI`Onhyk z*=f^P4LWCv^3Yk+R|UFYiWKO)>8k`?GDR8aqUoyuT`@%|=(6c62VFBo3FxZnD+~Q$ ziX`ZF(^ne0VTuIky6Gzk<*`_ZUx@C%@&`r~q2;DJ7EOguS#Y6W@Q3Sec`iemh z%td52T8m-UU>ygKviK};Ai820y%}xovT~3)%4|!QzzHVL1|v-RH}WQ$lAqSBN{;Ut z`?Xe;OTI&__OVuG5KmMVR zHs(Ei7pKeG&Qo21{;xlINn@Sz_aoeJVXy=vW5P0DwV$i+g>Co@2gawTG=;keAa(9V}S^py^It%Kj_Ja2W7TL*e{ zfLA*V^gFf9)B?jh8l7MaW?)^q1%@>=L5f9?W)hpmIEEcveB#jBO9Hg^kU*{7BuMMG zB#+i_NU+wgNr=|3NT}8?2@TON@O3CQPRs~xxlk&Nvfxh;hWl&}2rHy>ku6k*KO|P1 zwsKhu5^tZ5Wv&udQs+MM4?BckBUVa#QbE&S39GJieyNS2a`E-Q03lQZCW5muZKZNiJ1y}C zO}$}fmd=JnI)!d}qWd3no|D9`Vj+=Bli6Sxx z_p_`f(Jzi#x~_Sj-?Mahxc}BXLd8;^Ygysw`s7*>x#3t6dPOV~Vw8nwEBsGl1?vbL z2^P~8EyQZ7W$r%0IzY>b)d9k| zPhV&jvHC*G2^$Sfv_=E72>V)x54OIRxf9t!9p2SiD02t1EFIq3%96QV*$y3E*V-X- zTeG8@*0YXs9UJ5O1qF}O_bnc4-V;^~zlTu=>mIja+5c;<2Nx@lYBPrN-S^1eA-*-k~1b#{w?;U;#?I`L!?*C1j_C@6_{?>8FS>|QnEoYT~ zLIRcsyU626+v5WC&w}((A^OxPT$O~T=gqSujG_}~BYZ$!=lQV8&U6wu_ukhL{)iagvcO*3-_EW{D1o#&z+X?riBz#jEW$T8fjjI>vZJrCmmvIHhZt`gBMF zTG8kzN}o=}I2Ij`k&fuUwULG?1@CBrzDo@L?JN~s>6Y($Z0T*|e6!TKV;+-R@EZ8)91gEoPk z4827>&ELU@;uB~z|HzZ_bmr?|EY5E;#TaY4&3fwHN`?uIdNGq*^9^eh=11vS z+?s9Zv6vsJXLD&U`f`m$& z+$v}A3z+{%f6uM*hU7ov!iX`YqxI@rmwZ2n`iI9A{xOg?eRxfy4fX$FmvLW9FKSwj zp4YSjJ!|qx6rZG;!XRCu{4Ky;HUB=Uo6`UFCof4lbn$Ph^QY`b?;htt_rIf>{Ijp? z98S^kM{jRJB#m_ioaN*ozxQvLp!Dy&>?w<)Px9a7&SfIdSp;8)uM?%ZU(^-!#R_|f z^9YHbw=_D9;%!(+l zqPJdVvwAMhqgnYB9G}+%*WrjkkP<~^>jJleIl?Xe34n!S{H;qWB8?VT`bQi zTlw=#yk6Tn8r{I|U4_rr(|gHwk?L~T7xI!I@hO-Ynz$9i{+Owkq7Jw3zydlk|Cens zobrN1JHx!_0H@e>U(dI8L(rE2wtoUbo`}dlSu}lAFqG$WR_4u|V>x9D@*iF3$?03h zPU%3;BKs6Vayic-&etTsUX-vYHMG60XNf)kpMyO=+Oh1^LfvuWsVCV;i?}JiJ#oH3 zb0YuRKMdj{XikagG+*E|hk9`~_YL#9Y@yyc`Jbnx*e`i>IXl%CJqzq>C_m%DSP9eD zJhYS@CzfaNTDvK>dJ;<6vF|)vi3c|Vq2A@~?c8#BE%RN!_JxgG+^f-3U?E=gYhUWG ziC5#RIu`8JFA+37+79LM>Q|80^PJ^FUH;1#YreK|{@B;m+;3yLo_90L&zY}@*R~HW zMgW|4p$=Z(cZg+p#d@fd*S7`g z>=jwi$6ntisH<13fx38o8=&r9u?p(u^{s<2bg}~K;q|SBdV9rksF&Bb8tUs6OQAkq z-%6;zcM-9JZ@h!`x3JgCZJ^65f*`}Y%W8*Rx5CqwhQZ%^_($L}5ABU3@PkM42H2B_ zeL22<_Froq_FeK-w%0y(&69+5T4;^$hVK*mLeF6PBG2I(lgrqzcvvYreLzFeqC4)f zmZ%uJe700f_WH(g+=Z4w%`H-Nlcx*$Ji~sK>e6uD?xS!5owVBXfJwsnC8y5C=nm?N zv2)15P-g|FbS`o9irKxy@#=Z8*?6qTLl2_{rF!UI)Sw2Q#ibmki18%sMGd;<#usAv z{9k#N-^b^l=&`21t3i{1aUP6vYBt$}8syT+qdgev)a*--{tUqp9t?MC_Jv1(4h=;O z%0jujq6U3o=lo;TpoZAy9?xdB4mIeI$JPMV_JGIT3>!V{5%sX_A&;*ymObJTb)cU; zzJ|~-kEjJ5_4w*T$33D3^oz$=7dqh))u3NJzS__!kEjBj^!RE*r#;$+;ir?9r#f^p z&|3kqGaj$4I=9YyL^s#lm4dQ8A|ATo@s)sXdPFfO$Ky+aZhIDyOjMacs6h!usIKYd^WW7k zu^2UG7;4a6WDZ9S^4G6855EJ3dT1_|Es7d+0eiAMYS0VRpz^3e$54Y(QG+hN-;%T4tc#HA|7Q|P(qERJ z;l6>kEXgy@(F4KNWQIE%PW1E_BX9>d*IZ`gzzOh3cn*9Mj)zCVv(4pU7z7yQz!$9; zihl5RnghcI?wEk%WnB^9kQVMD@B{Z|F&3F;m`~aKyK%#Bc$bKxypfS)tC`m|2={1u zM7DR2V7z~Ra}s)*^T<7Xwe^W!LVaJE9gSq14Y%DtI)-bTb=|$&F&5uQ%p_^Sd?Zi)EUWVZVS4ql{Zm}5NRp`N~CE^c+dCiC3? zq}ucpbE)A*Ji;^7F%j_qPd~8`@h{1I_cI*r!HAoPhavts;vDg%h<`TU?LxRe!VH@a zL3lE^EcaN)9L*-ocfUk%#V0TzM^4p~3W@8<#)tJt!I-XlA6?FoKq%@f83w5^Xo|eOs(6 zVoh6jKkVgY?rn}ABVLA-tOtJBNcS-1X_izUW-Wz3N2qkft;}F#iGu@>S zxaJ<_I81eeOm}JMDumup{Y-Zm=n8ZM1CPa4Qr!!!T9s|v)!n$f=e?F#R7}(&ZHQP~ z#(6D&1=@z78dtz`9{y*&;tFrQ7EbQsdAq_W3A#Dq%?7(XQ_5101MFcwGAv;mTu*hVHyu9D1>PTi)t?u!GKX3tstwjN*{4g=e_eQ{jU zVR))28)I;x{_hc;+IHHP$iq(fL>2z{uCE5Ce-^0ibyryJ+SS6wJ#Q%wV7iD&A7Hr4 ze7kr=fGG-@)&q<_&3(I-oI%wnXzE88aH;IJEAWWW7n>a8w#~qqBTWpm+N`l|F%3(G zn_6MX@oq5%3Nv*sG{G&tf}EyyL6h9#ONaiaybF)CbL(@r_#CkiQ@>bO@p-OWOoD<< z{SvXS++qTh$JDQ&DQ+sKA-0N*INI2FZmn+wT~4s z3kyyQ-t#>y%5USC-$CvzX=~#6T^~i2(Dxjq-hE#T4x?Q(nbf<2`cDKO854t&{dvz*?t#uPd59&q?PpCCu^oXv<=rLV~9j`^{ z30;HHQ@R?Xr*#!}wh}H5x&p%uOgTm`;|s*H^s32AQNHR1h5fL;7EO}?^G9(Zme+bUvyyQP&=SUKeJZsFm z0PW@DDx6H5)ml=(Rk89~)N0V;9MCpGBy@9RY&`CB@`9>1`&;A*A zJ&DolI@w0X{E^J)AG!qY8?KkYjQ^ud{nv^_v;=KP60awR5PLq7Cy3O%p_5mW8reF@ z&76H`KqcQk5@)&-3SZ zUPKG?|LwwS$bZUL9XVRB@%7;T4UF;4@=xou_U-ILyVXhZW&4+>J|aH%e=>}OS`4}&bOLl!(0GHf>p~}CdpUw4k^e4qGGaFbO@gip zT@w03&=SyPp-V&81TBT-E(u*0%Uu-|iT?426vQqIS{6Ddbb08apyi-5LRT~nw>=_m zMHnA#|63HVZ|rFEv$!2;r0skviZw8HwK^>BrGeLUxAM z3)KYLCuA3Bols4oy+U?{vV=;7_6XSxS}RmD=qDk&V|yPeCvlBX%@NxzWDn$AEmR9= zmykW7RYJ9db_&@G%YCSv#Fav|LTrbSy^(W;P_3cuLiRz~7Yo%M+9Kp9h%FMT1GHJl z!O%jXIzpR-9D;RzsGP(FLUlrHqmV<9GgGJxXoHZ$p!q_546PS(I5bbF&d@p`M?iCh z>H=j6ITD&9R99%NkfWg4LUn`I2ss+t`%pQFvxMr7*lHoiAm>b>dO)j$91G15swcEk z$Z=TiL**n+7pfOxD})@6oYREr4Sg%*rzrauLJfiz3Hc>rp9}Q~v{1;&&}Tvoh876< z71sHoauO#AH3YFtA-_h>i9!v9<_kFmnjq9LXr7Q$p-+Vx4$T#E8Z=(05zrhVr$gg} z8VSu7at1V3s8P@?A!lNHA1Wttj8LNyn19fsgU17eT13{jTdqS)LW=&&^RGiLcN5V4viIZ z71UFx8PFIZSHIg#p`64XLd`_dXd%}iLwBKOL8F9R3w0A}HZ)SmtoH@%D%2b#jSzAj zGISAYE;L-o^(bI_p%y~}h5Qb&bfK0&1BCn@YA4h;P=6tRcwfMegj$NEenS3;3~hy4 z2K5zk8eGBy#atG8}s1;BzA$LNpgjxyp6ml2TQm9o>4MZ1b<6cr-p|%>y zH`0YXW@IPT5$ZdroshpkwT1c~`bfy*#tl@4cbDKs*-5p8`T^-}h5Qw{Y6|rulqTc} zsD@D6pf*CDgsKa*9cnG)DX5xIJD^rV{svVQYA4iE$kR|2p>{znggj&1NUrQxiR;i= zsFF~-q2@xKgDML36Vyz|^H2q$_CTpZUNEkgDDPLvKcI_HIidDKO@+J!r3keTY9i!i z<4$t2P)D&`9U*UEElENhgK7(z4J8Wo3sg(U9OL?b=|*ybP{$FgDdbJ$j2G%xsD_ZY zpyEQEfT|058!9H$NvN8Tcc7v|or0Nlv0koTZip-w}Ug}iUvNP^B_PgL?N zJ1It}vrt7LA3#NfItNt{@*z}MsPj;HAs^u+hc4i_mh&qov5-&~p%fwigbE6E2`Ve( zV^r$ALS2WFgnWirgitr2L?IOxgh603o2o)02gXKO{PNGAoM~D>^(ubDg$zc{S6sb?0)z~KUUKDz972X- zxet|-_<}1BVs;^&$oZTrFJu!k%y%#GZ?32>Dcj;QA7X!T#UPW*{LoXbIOO9p8teQ} zIf+lW5{MaG7C_F&T-hKmmj$6exw1nZE(<}AxN<;lE(=2sxe9>Za#;j=z*QjhhRYb} zK374|Yc6B4y$_X>c#o?*h`r)64ms~~6%4)PvM6+is}Se~m&LH$hssI3%~dF3&$%p) zoVU1gLM|@jQTE@tih};)vJ_(1xXK4T<+3z%m8<;F6E4eOogXSE@d{Vbh&|@AEOK7v zssQvSmnqOCt_nhrxGV=<~qWn?(RRUCAO%PP=mu8KmpxvcswJFdyUaa9aSx45i^45zp%4&CIk zI!bz!tCG+)F6$w7gsW1}RW9p8KXX+Yy253HcdNoR`7l>ykaU^LhRAS;tFq7~E*n7y zxk`a9a@iOfhb$5mbE2$$^<+saiv z=w~iFKwG$~4;|*Rp*<50~BE7jP|C&5-mHm)((J4Oh*f-CXv7R&&(?+Qnth z_XS+VRZAr8>wu7jV@P>6^G5id>mob%Hi>ISiW5RR*+y%i+*Gu0Dp=b2$Q<%T;G+9hW1aIb3yt zvbY=t&E~2rw3f@!z8lH2{3>xB8UxMbsvES1%dyZ5uDV03xf};g=c)&^ip%l7>m{c7 zRq_w$Q)ntzJ)xCcPJpIx)eBm|^;a&^WG!Lvy*D0gdHq1T=@sna~)n zMnbc>oCS^MY7{h!%h|pgNziEQiJ5+7CynB23^aqwInYS1#zND%oC}TMY8*6;%Xw%^ zpz%1aQ~kc`dB&;%}* zW1Sxg-Da+)AoeMj-y&xpuBJlcxm*GD=4u)=j?0x$FRrFTW4T-f_2g;>G=|I7P!FzV zLZi7{19j(W7Bq^>wbd)m5h<(J>Qm7x7KSFJ}S_bvyavRq9q0pn|YB^$k zxZIAMZMgat>doa2s5MtBpk7?=gj#X666(q2E~q6}tDqiS?uJ@$wHoTq0Q7s5zHspvqkR1U2LGEVlQdauO?X zwFj|OF3%xnMXvTjO}RV|Rp4qL)P&0mSnfmRB$nrDKVpr!yoj9TxHURsGP(^u6{+V2A4U=nZVTvs5+N7p?I!NLe;pu z1r_J&6jYVV+fXsCeuJuTc?T-W)oG|Qmv^B!uFgP}xV-niMUUm`ERrg6c^?^KxH<<_ z;PL@fgsbyVc`hHmZ_x{Lbpc7`xO{{Rg}Ay1rEvKtN*c-4A5b!v|00%`tLsn_m(QRG zu5LhyT&j1g!ZlfPm5rnXE_0C~oU0rto=X=L#??)zIG4{MCs((iVqCs}Lb3}>;y?{cv41nBBy@Z0f420e?^$NETu zd_yyt&&*Exizy0OOy-B4GQ}X1$!PP#YcgI2;7Io|Spc~nGbJE{$%4?IOxYkWlZBv1 zOxYn1lZBy&OgSJolSQBhOa(x1nT&z%GZhHEVKUadk$lgu64#+P=q^)1&}$}(LU)+T z1HEFh7<8MdVCW^2#m(y_ZuwR64=5hG$y5mRg2@CZhpABLIg^Rzo#d-bMPa$Wm@I>} zTwy97^pwf6&}F9bLr<7YF|YrZZX{n~DjKoJOqN5=i%b=O{$#Q|bb+aY&?6=*Kp5LL1&n34*kSbW#}}MEwH^0h5j>BRS^4)$(G2ui>a#6DJEM% zJDI8mon*2#mitgSi9498j@St%+aTw5rfNXHGMR?5Z(*uFbePGGh;3%70d$DTPS7T% z8bSw|%)mN76nfN5HA3tFlOH4J2BsQA`yiOC_*0;W1a8<`x6b$%!e zTQik`*ajwtA?JLiK8DsaIUJhDRA*=%lOv$HOm%^>m>dbsVX7;%mdR1jY^J(FYnU7j z&0?xMw3^8=*xrZ2ur*UX5L?CMSmd0+R8MFnljET2O!b0RFgYH}eJBiDGu0chZ<+iQ zIj1t!2U^bL1eE=ArapldGC3Ks&zKqvEnxC1XcALHpiCye#yUR~hOL?+e(4skulR&g6Pz=*-kSXc&_lP{4GimOulT{2sA(Onn3OXYvQ= zBc_%@{h0jmeF57twG2spncRj9X-qAL`Y^d2YQxmGP;Vx8K&_ct0rg^XC)A3ml~7M6 zcR?+gS_SoBayQh1snt+-CVzTgz~)S?K~gs+_aH+vrq)7TncNGdGL;2&VRD~8`}11p zS2MK^Nu8P8j|@$iS`U59k^;Dq|rWxBs3wFy)GIoeo#!XR- z?KayQ+eCA`50#8*8zTqrO6@k&jqj0m$1G|5All-^fjIV)*}>Qyh@rEN^TO8OCK% znC&yW8CjwUduUcP)``x>MNx?DH+vXsL}T{ItZY2N^T^c1!`=83Um@7(|1AZIH!Y|k z4t$9hEW(_rggF_pIfvmFLFo? zo=INQ@puD*(7>VEHV28rwYd0{b}x4r(=oB7S=}_Ysm$?NHL726d;-9U8SA$itC~?lw`ii9pH4F zab0#M;n!;@?V{;Atm|VZIdcH=W

r?Tld37+A)`&S z?I%o9wRwoOd4tP2pREiF}(6rPtzkvtfOs*F{!7`2W01z{@XV>6DB#SN_j&8t5;{>sge4MnA(df?pATCBJ1P-3pemayZb86Z2|}oX76SyI|Us2SfGIz*|F|2)sXy#P*TP`O!4#v(R{$_lBBBlX*9p5x)nfO*tCMNBm76 zgeDm{1%fqxqEO+6&@Be0R4I=~_(P!y1_4!3JSglxLLKn0gdiWqAG+PZ_&cKlHJI{d zls1(LNJCI=4qXHPEnjq;!MU>opts(X^tOxXR9n~i3YD}#|3{D#odAC)8cQh1XfD8C3Ji0N(Lma zQ&ILQ-OquCMO^g?p5dO2W6GjaIq|sh>;I}BBKL6c(4Q3#u^?U?mphkYJ3Cd+l=six z9DXjYCb(Bzc*+pL4Y<7`D%FEZ?Ll2|1@d`Yf8I~xu%PlY(j6KsmUc5fCCL6Qa!O{9 zeJ^t1A;IoSDI#15jQ(C!$&Us0)4y=neMNA)R)UDQp!~$(RfRnwZj1z#rx8>ej9yiE zeo0Vy4z8M@(u1&tLFGlbmIsx+aLo($bBAz>ck(H7Rej^o1J zK~=LD5$*|ISc^Qj28AZP+Z_zI;@$g#LL*%F2E%LM+8z`faBT~QU2yFPJ}*A0aMroO z)o@vt23H~Mf#6f(lf1k$C|m{CgTZhE!X63=E8yA{4BO$_6BKIT+8qqn!L=92c@c7` zmIqfpN~fQ91gjDDaPUF#MPA+?6sq9b7Yr{)%twR5Qn>yV3||S?<3Yg+*JHu34X!7H z!V75xdr;dhy6KB4e z8O(w|OYQIfDm+a3F_0ns6nNUEq;fJS5v}?i$njfoM38|VzQuDd7X~p2r&JeUX-|QW za51WrzaI2+-PyUT}*I5 zJROmqL)d8+_hDel2y!z7osLYQks;MN9#U2qggy1+5;a6ZE7HJufzl!=w2I?n2QIKV zEk~K6XXg+SInDSu0~JELN-CAdMa~aoQ9{L8+}~DkC>*ziMaTgZ!#K98rx3fOe={&s zIv+8778om?Vxo!N(9fjU;At`RXVJ~-SSLG*!o7ru7nuIDzyvdcL^RaqoGMO(x}J~3 zy%boONO=bX6H1s{6;#AvwA|Kn@yfZ#C+l|MqPhaMTN!vxI$0NB8g`y_FB(12y`Qw(pM`9!Sowmi#4BeMMO02H zQSksuKgZ0Gz-jKP$fZX(<*JBEzMxVGa+nha4LucxhHs%rs{#&=KPT|~Gjjh@rhi7} z`xy33d3HQ(GV({mx-4G#I;>!z1~aAYmwLI(2n+wnjfgNO?vCFVXq31u0ig-c=g;V4 zA{`tRGxGp{H5cs#RgAk%7t%x2(anJt$&emszFL|c`1%*A8Qt%7>G%j@qe!nI%`UA0 zSCN&M&DQ>3IYW?(d4t76$U+3dgap1`z`Y9NC|>h&fcVSJGl!LGeB;^BGxsq}O)>ujT1Xi}Bd=6{0 zq#T1aLQ;;yGE2&Lu!c%XFRV04`59KSr2GmiK~jE)B}vN3fUt$G6_sEBjc|>q+z>=F z9F~-uf@p_>k}@fPmUtmvnS#OWX!tBUWtiXpuKbz7oEkdwnSq&=UiLqRfoL|a!n4;} zGPo?#8>T}{eFD}>N%5grwb+{$I$#jFA%PQ^=Ke`C9Ed` z;VM{92f`Jwo(qJRzSDy)wJ z;Yr+NIR|1iow z^?}}gk`#YX)o=VoQig%vPDn~R2<>-CNrm+vNlA{<+ogCVah2Y(12Q{;s!-xKNp^tR zwo1xs&;p3E8P+BVG${z6+jdyDO;zU!!Yy;vA-f>lBq{6RcfF)s1M6Bzxh^1FCo%bk zz;)8Cf%TH2+!_!%B;^)_dL`vHSnZN>2dq{}*#xUuQtpY8+c8nu8YQNrA=^h8qHw<`Lm{^dV!ybbl?;XZNijq8Da15DCPOA9 zwJ0ML?t5h)EY94I=eYYDwU=trh z*vH)17y2rU9|ot8Id;Sp%Kda;3TZ=L&G+#ABr?p?*ADS4eb*a9Y}Ctr!;Pw2QM%tE zLvHF@Wn>Q`u%Bf%p%|)d$nTFx+N*szM)pPDLSruzZ|iF`sy;^fPexK+>$}3pKF9M3 zW_YtN&!{?rnw*TV>-xHkFs?VU#FzW>jlu@hEFf<}!UBcN%+%C(vr%;$GKd(T>zit1 z?;&Z-the>~jl!F#w;c0IUy+f$i`RDcMb*RNqFZF-a)bx*#|P0zZLOLOA}5u(G8;V z4x)d48jrDOk^Xe?Toc_DduBZQ?sVMvCX9d;YCiYmPfXd=x7G+2Dd`&q63;Y(nTKc` zWoMrqzJ`SFnQ~j-I`}5BUzze{6swB4AMDijzSZzeV87uSVc%Hzrk)3F_34Khtx^E*Q83I^r+>RBs)PFd&p99Jnr#p*#QGL^p zn*RJhnSKi=|6XnJVPcPaX^os12zR?&dYXzxvF>2~X!atOeh8Ry+|^ zRs&^p1+*l+@C~FrMuq&S_GwGCuJCoZv)~p{o^SrEJo;lJrvC+hRb>0NZGWn`(H^+$ z7i)pNbKAC;-ni`E2}L;n``0yL*f!+zfBsG;pWN8`kB0{RcW!&>{|Mjt^~^Wc9$Ndb z@5#siw?FcX{$~B@|Hfab{pAn$#6iCg&%M<9OYF?{rz>AycGrv34=BoOUHx@4qtBt8 zaWjvmSZ6N6^UjO%Yfn}-yk3Rp%V}vX|7HJIT_7R<@~;#Y2rE=sDGKQ&E=z|@N|0UO1G!QLG2z_Ye|!<#o=+bQG>nJ>9JQjeLh#)YA?<4 zxZ8Zx?)JKTE_WMw><*XTOUTCC?riY6I-G=jRy&cRYju;4s@&~V@AkJjO6F2OQEqu_ z8{&Ap&V?>t-DEnOKyLWdwb<7q_ZD}<8mEI={XS=#)9a=7ruAM|gZEn8)y{3lOD-=0 ze7Rm%tG~s*5$WZ&y4vP=P{5^jpOZWvkgAZ{8~k3MyLC|=olY*b`|MDs>vA~jTy1s0 zz-njRI#-*+y^f;Abv3$>tJO=p8jvBCx?7!#4$-E%N_(Tzw|=hYBdW5t*xQ^rki%cM z7+H8+_7*QKa=X`f$pJ(-^RH%^tDSLlCbocl>)V}6P!@8vwflYEB3Bzq3pA~l=yaU3 z6Dae0oWQLcRq?r;Ug~gp{q~l+)>V`MyW(By2jH#063SShOaxb2SiCcD>Jg)-g5 z_%u4joNe~{7Ux{6t#o~xz17t)8EZu#w`jG;-ho1vx;)N?dl;KUnpC=Lv3)hD!tW@D zmWGm&Qe2I6(Dju*d%dg0wV{`3GpNPuZb3tCBf7|0Dt*rOqa2URuhTg7OvZoBAoLQN zllYOezX)jexfqGLtVf$)XqubL;tDWvvYH+u-xV)gM3{G%S z`)o86NUoj4&T+JJ&?xP0S1K^$ zaQlI+N>Gl2+EBt{99G$R9d^$`uG-rUa$U&f0eh=Rx0dK;O6@e#=@Iq7cwLLDZ4Hed zpNs!ecZ0tbrSs;3+H=vo9;YMM*$H>MbG6;;_m2OTAL;fONeJ+vWVa{R?)5qmy3}3o zhBe>g^5(i=jQ4vTHT>hklNHq_PCP0TN-1IpbkU$csOw_`o@WE%4{WXuN?XlQ34HTit)-lE*x zHw5;nkT zM!%PZC^Z*huTkFRHuraOQF~nx38(h z-3A&%ccT`U!|tIuu1=?8fm)0Vn@FyWj;lLnuA>OD^TnmKMygR_>HiM&;A&sx8e zmf(6bvn=&>F8Y0Ur>oI zS;+IPr(6y98fR^EwK(T&=FPrpL30!Xth2-3;^{*SG3Vy?{PJh*wNo-+Z)!P ze^9%t-3g*|R{lfH=TRQ|&y8fJ)d{?{2=wauLS-)USos}w==IJz_za^59qv}(tIp*Z zO6wNBZ7c^{gYbZazuGB`w^GlaHKUNFLWUMZaD$3Fw=Eb^O zcy1OwH`nR2VzRK>eN74UE(Xi>^(a-9t6@zdaXZ;6r`=KMY6Ux=O4g<2l?5fw@!6fe z1nRP)d%3(#C3k5NWSft{#tQL?;~5lrN##$d*m8!9RBMEK3@sj~`)%lN5e$4531`{$ zOMpqL^w1RzpWgt;A(Y|>OP&{+39R3_xnWRw(EIlS$KgH zAlHAZnm*!$=X6}NF41A2Dny#!7Ei;QocHMY88m5~%dvpSBqTc5(o&SoXBTyeUT8;Z z%!yIOljzIlg{QzP=mcj}b6Mj28={KsiYwQ++KaWSQRMWuv{W|Ox1+Ogs+o}8O{>2q(BdtIrs-oLuqhyFCzV8_*0;CN4VZl@*P~y@2*M@IoEY~>t2aA~hVai}iUm(##{}WTcjB*Nv^^}L zW1k?brnwlu=A3|*N1A|+G>jm@f*UIcMyfz(Z*yitLm1D0!qiDLe!ew_{IfBRw!87! z=-u|t3B`V&yT$HrYtV33I7?mnSZ0nb#AB5TVyY5ap!LVW6)yts5FvgXS=#)qOAB?X z7bwr)?s$Z!$Mrn6tTf~+Z)`+;^A?jPfim(Tx;di&MrvUKZ2-#9g;rM(pGf+pgJxya zgfgMh4Ni~yaj38Jv^pKjDK3pvR}GpCQ8TfynCCqBV1*pw65DUaBEg{jjfVgTc0VU< z;KcR=YE>KwpQ!l?Y%s^D)<8gE46o&dnT(C#V-oqibxm`A<>xN(x7KIH3ty=C6{PxH zBP^f^!1X;ETUlF2wY`|56yYjNz^(1Q>eRY(Dj`{;Qq;ye(v-{xd+@j_ZUphyYbr1< zt+Q+5;xehCZjrOm_X!E_sNzSExYVRFjD#k+xsONW&c>gPAn6k_?}z zSv+)%pj((2Kbh;M`!bWah2S^K-*f*%rleVI- zQe2)|2Q7w*ii4(|eQ}GpRPLb`d%ZUo^IF|9HL<(nn21^Zdrehc3#x?!2%g6|Gqvht zD+r^Y<69joi_gO}dl-=!H-L}Waa;+_1?4yAszcP!;%aY43opea;H1XWv8xt2+gAIU zV(EO{S5s27#^uvPJE6Lm zy#D%U^kQ4A^p?G4oqfHx4#V!6y2*?mhL6vTMyt48VwZb~+gD=u`eICD-0NNuRrR#f z<(=!=(CQ{<=bQv1wMfjSViywFT*~rB@lv!_$^#>FH|0BA9Y0HKvPt!ZwCXbR^qmy* zSS*bb>9N?P0;7t{<+#?ExS?cNqGFoqQA?#65w!#jK5^6t21u;XqVr7U2WjVhL2ppS z&4!pe5RRJtML1sw8towA;6*-mG{t`=#CKtP|No^I+QhMb{!A)34ZF*O1|HYu$J7Hx z$liv<#=7wht^V;&hd+0btKMVxtj{xsV&{M{tt)P@JDjcS>q@~n0Ks)t;No)|)5vH~ z!we?W`@lf7kzdP|iw7LeMmxA8%!_SJxAJc`Vw!QTcb0p6O>SrWNLNDwRg|suyBsA# ziqAwO60Q`&d$*$JOzzqmvDlMdW%D|$9_I&YQ{@B6kXp}GOT}OpTS77F;d;?~G3A`f-qPgu z`pDM+q>vwlm^1;rdI@AvIa?!t=D-8OFA%n3{!tD=J1m17Sj zVp}#J57369rnPuzvbQvEg-mQ9!|>wyEi z&v#EUb5edG<<3hp=ITv6k%x!`ukiCjqC z?gFz%tL+<{_3m*EE#Q@14RshV{?3s3p`@<5h8DNqL5^bG@VeE{rCREI9)Gq$Y(1Y! z52uK9x5k)Ts}buarb=|L21*})LK03-9o7w4#;&fnMm0y})wMS)h~pd@TbhGq{Tu~MrD`W8F z9_J`x4GD%RYDVYz7_8wElMC8>m92utOp;wMn#Y%0($w!JsM_dbkK0=?9z3OEwR61M zM5-*(Y^D72)ot5IwbRJw4{aS>U{h;q=6LIMsp=`Id1w%4f;JH!A&8z%G*uTRX@?S5 zz_i;EHNC_QC4rbY=Y(q5gc+nWQ%2!2XdnHYxTA^urai4i1>+NSP-d#p^(V$X zLj_fC+np+$>58*MOH~a2VVq$!#cE;=oIQPZVPoye&FOg<53X0!&|w8w)qOXNI`r%= z4l-Es=GoisPrso9yAN(pVPinJ$O;>2EqLZeT0GlIRdXu`lGU?J!gw;*u6%3=7TTwH zkm6$ddOO*wv9W=rpR=<}a~lYqR%2kekZ5jb8k=5;Ws}F5&GR#a;_+=A;}7y65UFky zC$;}Og*B?USCLekyX{gOmBi#@wfHQV9KWclgjrfR@)Knj4`8R|BpA{0;C=z=ME?0J{Ov_oKgrKW$nTb)iI|{4$IZD%-AY#anE{ zx&2)a)im`mm1So|m%1Av7AESm1bi*VpkRZ`!b+psm}zH%h~b2ZJ9oyBy(t@fF7SD3 zNEYE^Cu2N5dz~E0_YVEp3}sER=X0H>4Hz znsbjIGxwf`baV4(lz2fl_m&^gFs5b7g$uHl31rD&{IAdr`+M^58p=zHJw6J9Y)(i# zg3z2VbH2PFXEISsnFSDsbYS%HoFj4p`!cFYDU*tGzO48HdZC?frcu6@jYf;lBSD~% zX}?0soR+N6xu#`lnkY{2Gc#heGsc45)Y(KjOFTi8RsKldd@V#!MKywp%aW-Wsu-J) zT?S17JC;Y597_}See$v?Lj$ExF_ujtnRaT)bVUl89>w#Ecpi`Ecknz+B7*>pV>##o9FZ^5AFmB>4r=1(3>+6(U+wNz-vtVa?u!n+3s zqkRE0n|?&17~X_zD$J%~T9W3#8z&zIqwK(o+4LxCu_kvgwGUAsERdu#B3ZE7#v%hb zZMa;CY=qfR@J%TA9f-4SFp0f`NxY>cp^KT0AWA?><}@%zQ$Abif@yoU>%` zCB#|gXF<1dw3d2HGK!x904k{LM86tsJC2+UOx<)kw|TM0?22ItxiXDbaGgIT#HMY5E56 z8{jO;z*V48GRXkv5I{Cy5}*VSZK#!iW)uMf&4FHKT89*Gg4bpMkZSrD0R2WfiVu2% z0L9KK1I+EfRljwEFyffII1efNLY%Va-gQ{?_?UtBC~qwV9iX3Wd@7` z6anS}Kw9hvp@evg9oYhb;^^|hx{X2L)gY|@!lmg6_yJ!g=Zj=Igy^7PQpa= zO={qGEE@PXP)bZ!<2*85K(tl>NCfrUP$DwZxGBWl7mb;V$wnotA{t^DSt&)aoQGm( zQl4S31o=q408j{+0GJ3I%$O35hA{}}oP^R%hW`{m>3w7>hh3dVrUt~L5X7@vdcp1r z$oAj?jdZOTCF6FC&HVx%uE)#hb0&-+gUG%a_C~-hfM}I(1>6QeYnyHd+yS@~a2H?` za8|B~;%qbO+O;#E1_3ItKiw(9bC6c~*ju`@n1kQ>YLJAu%9)^da=oLZqk$ang}qw5g*=MoNQ}e~D_xWbM0Y=$afg2e_141#B2Lf1|+ne!Td zR2T9)cj4t}s|am99r5=7=RL47a$2%ilw0zc>0zY#2ztnj4>2~0v=RwO)QXy;_Jtxn zfG5Qy=6<)(xvm~&mYyJf~M)J zgtVxhCF6WXpKeYVIdar+1Z;EMtuv8v0nQDgZ!S=g zQ@3r~Ue|V>EL)w;HE~qgoiuOTR7aJuDfgY?RDX| zJ)0`_@7=e3e=I$UnkInt}qH{xE= z<(OX9+bi5W*1!0TVS;cCG-Tk#O+iPRDHL-hZ4O^kvvsLb1!{6-=cek^GBsBm09TkTiOaXuy8x;yOtBNZj~PL5B8@Vw|>8iWzh|6f=GW451c=ss@I7ISkD* z7}_gg=&E7pZ7^c0V8m9!h+7IHzC!WNuqx@3%a!ygOO*7fiTa^IC;KOoH9?TVRMuku1uLavQ(KmssxHs6wab}m&{Vq=gm~oH>S^@p`BB(kly<^r`|SZ>CHow^fl>9&A2pWYI&*>zJpSfba%3n-kzkSuT50aJqb#>*QBKTaJKJC zNeOq8sHCqmDCwQ?O8WXZCAgQS;)Ljub4Y^O7SwSQoLNFOjj!_aM?ysY9AtA zsohPSQo9GIcWZkHnm%zxU#^AHAG!7sipaJ5C@k0Rr%Q6}zv!Y|`zQ^_wU5ySx%P27 zFV{Xn=j7Ta>8xD)6rGW4pQh9Db=-Bzbv)E@-bJTm13H_G!&rPkUhx9;$tzx@lk$p} z=s)s`m+23=_Eq{_b}Bnka1n&rZN6!7{X65R6oK{ z_ric`$~30^9)|8a82WGJ6^G~>dBtI9Szhr0eJ!u}kiL>vd_>3O6-Vex+4~}WA$wn< z&k@=5ne2UqK9zGBI|_sQ7zTd?y3g5%Ft`t7@7r`3@rE9PG3+3WjQ3%f--9vyT^O0~ zz!>qiT+4ofnrR2S-|-E-3D>`&%X=s7qBrE)6ZE=V!q}^F8Ixa==RiB53>C%fU_f4o zw(hQFA$nF`%*H7jmq3@u#&T$ZV|%PD24)2g_p&`p*>L5KN~TqMsxTa&TqE|&Hl{p^ zr;+>QWi0%tyqsN%I>+pVk<|kudk>79-SU0(9z7)2MU^hEV$hmuXOopCC^Cg!;rr-A z+JPYT{V+7!VQ9BOVe$E0c+%es?Z#(!LE-V4U5NNOZGrg(-2?MWx*O&(+6?n6+*7M# z#=D?;`42f6nwh;!`9t30V=_!Xi@-eb=edht|Fp4#clp;}8l7Zpjm^zA=hm8S)z#h0 zYr55}(YD;yQ?smk>;8SNo*J9Y*0Z-d(Ppc_0|xo#=9+!o`+KU(_Su^4%bT71su81m z`}RSrdVhBT<=dK@vA)9<2EJ#n%_Xj~f#s~R)i|BDs_GaDsgXc+jmx>Uy2sMB+&0Iy zFKKIcPd!RP{o=lTwlbTo%4XYFy?@{K?TyVn&HHS&W|U`Z&GP-WZ6xj0&=uV^x6oM? zGT!I1>4jz3I@na*UA=sHVmH!HP<2-~_aF-$<{h?xm3d@#34*J?CL9OWMj$eLIOe1N z9WRC1Fy6#I4wrKiSV}@lQP^{u+Y!FTpqj~bswTr{TA1tN$EM5(pXVl4B`4xR#j7;m zhTDT2C&t5LX1GJGjxFFgZXE~FCDh6+Wd#xc?T2ZiY0)tfEqBU$X`Vcp#WTw_xGH#< zV3l!}3he~>OPmD#oU#%|nPNw0#2XS55=5~8!4jLmEVsyK<-^!S8pe-U%p-XUrKfUS z2bT!Dz5HeFOtO}pJSPkTJ}dHGX;4yS zZmOFLPHYB1bWo0499j7D2-l>bR9poBL)cF0g^;?Q`}R7LH%h@8nXt0-?Z`>u+H zzBQ7h{3JR@V}=aXYbFhe7xlVqZStIaI+OD$H_-;<+rzz_O2ZcMR}% zM9*K38a>VtwrS9mVv|~{F%*q-glCVTE_HlLLYgByWDLz7?+90pf%J5ZR&6L6?Fb*@ zCSEzVN*No$caSa-n{jl;$g23U$<5*Sxrxh6sd)H=(@2pbG=D+@+-t(KEnNSCi{Z!U z24)$vI#PUKD@_|Z{TR5k>*XEPA?w&EX1OO)&VC?R<2lO&ZK?boTO4_WMh{CDHF@dr zlF^VBFD*iF9}cBkHpr>U7PNc@H*xw5POxxCQ$)0Rwq;@$eIFinnuSzlmJ->jT*;1+ zWeyZzEsKn1+E(l&FcsQ-=V@&9!WaoTo_))=U;8SliL;Y4hNyHm7l0v>=0`v75tjXl`9XLQ3l9@b75u{LSHE zXl|y{8j8km4sYWo){b4Itctca_KY+dvcluh@K@ZQqhsjiD8p*AB_`Ue6=h9nw$jv^ zn~b)avZku;Is3TMrlu^G23~sC=4!CzDw}1?>^)Li+JZeo*5;(DtkSfev~0^wNs>jl zdE>@G%ea%Ino?{`q@`W9Y!=(DU1eDnJv!uhvvga}-3z*+Tc&?L)@+N8leUdXyGpyO zr8HYl#eS*>hP&oqKyBJ%!zN*IqSzz4ZrZrfn9UaKQ6=g(&)GLeFYYQ6#Nu7MG?XJ` z-9qQpa}uq#rY31Yl?%1A*l()ex5v0MhR(cO-54DxRp}>L@=I*KcHi6cuUTSH_OWXD^H>U~kCccQe?_IN+i>JN#F6 zRwqPa*nei7Ju#g~^p8s+^_>sN|>^^zX3r*~M`OMj) zV~3}*hY{b-zUid1N%d@uPWYHMFrRF?mR*-bzxdhh za^F_wMYKEF)yee5dghl+SHr_}J-a4}2DBYeKzH`S3-jbxOXSxrBd%c{C?cfkNjPBp zK0Sn+*>Z&Irb2!;3q|gy0`5xob>w{vrpkM`9~=3CW-)Ch#Xh-_o%GR!?RNkh4={H?5b)~9ULRyJ`$kS*TI&SGbI8Y+>%6`^$Rv)PsGi)UGpY5MK)%@kup6N3z!qDYC3JQ zmKEdQA|+IzW6tVUj53Ml14@Rl<-|hQn4iR+WfD zW&P%|iYoj|i4`EaQcDF0QlKiyR$7r6{Za(PSxd{Rkf|9vo!FQ4Q@bs3I6|s#z!OgW z;CqXo*sVnOVlS9(OsEhOC02o*&weSvnkb6q;Yfs;85wcL$84@r*(8kHHk-v_SqP@I zj70}wt&lLhnz3ECf$uG~C4LL~S{L1-KBZ5z*|fk4uM)rms#Pjpt-;j}wOYW|hVi!{ zzYP&W-%e2(JGbjt2_+oMiV^rZC39{;ooMI zd^K6F#kKsYICAq2KA`@V4k2ebU*~*1=G%)f_%AQ^63$FqKaR&2CLa40ICKgXDU_fa z0dC}sJUmEzwrbPYDf0~+k83w%VqpWbX&?jaQ%cSii& z0jlO#D!b9rB@0&UshdEjgxlBs2W9VG%c~LnA`Je#hIlj1>QTZ^IvUQam(l^~>N+EY zQGYyOb#eJ;jas;EgTA53VCf{xvXGEQLIu1n_=tfzXNa>Qz=J~vzmsAu=!>G7&|PvF zPS0X}3;f|qf@a`<{{Gs1t14euwgkKRfBhy5ZqpGxAEizFDzOQ-WbXe&_~VD@HXc!U z(8Nc}`DKer|0kG!?Y$g62iuO(-{tVKs=uO){rz(I!aoaOEv}mPS6DRuy5QyTjwsRM US7|LP`S0+)3zx&+`*RffUkzjk9{>OV From 0caa6c9019b313a610c3b2f7da00f1041775b3eb Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 13:01:30 -0400 Subject: [PATCH 02/24] Fix build errors --- .../takeoff_landing_task.hpp | 18 +++++++++--------- .../src/takeoff_landing_task.cpp | 18 +++++++++--------- .../planners/trajectory_library/CMakeLists.txt | 1 - 3 files changed, 18 insertions(+), 19 deletions(-) diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp index fa1cfee91..3ef0ea525 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -50,15 +50,15 @@ class TakeoffLandingTaskNode : public rclcpp::Node private: // parameters - float default_takeoff_velocity_; - float default_landing_velocity_; - float takeoff_acceptance_distance_; - float takeoff_acceptance_time_; - float landing_stationary_distance_; - float landing_acceptance_time_; - float landing_tracking_point_ahead_time_; - float takeoff_path_roll_; - float takeoff_path_pitch_; + double default_takeoff_velocity_; + double default_landing_velocity_; + double takeoff_acceptance_distance_; + double takeoff_acceptance_time_; + double landing_stationary_distance_; + double landing_acceptance_time_; + double landing_tracking_point_ahead_time_; + double takeoff_path_roll_; + double takeoff_path_pitch_; bool takeoff_path_relative_to_orientation_; // shared state (protected by mutex) diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp index cf07299a9..b6f9418d7 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -28,16 +28,16 @@ TakeoffLandingTaskNode::TakeoffLandingTaskNode() : rclcpp::Node("takeoff_landing_task") { // parameters - default_takeoff_velocity_ = airstack::get_param(this, "takeoff_velocity", 1.0f); - default_landing_velocity_ = airstack::get_param(this, "landing_velocity", 0.3f); - takeoff_acceptance_distance_ = airstack::get_param(this, "takeoff_acceptance_distance", 0.3f); - takeoff_acceptance_time_ = airstack::get_param(this, "takeoff_acceptance_time", 1.0f); - landing_stationary_distance_ = airstack::get_param(this, "landing_stationary_distance", 0.02f); - landing_acceptance_time_ = airstack::get_param(this, "landing_acceptance_time", 5.0f); + default_takeoff_velocity_ = airstack::get_param(this, "takeoff_velocity", 1.0); + default_landing_velocity_ = airstack::get_param(this, "landing_velocity", 0.3); + takeoff_acceptance_distance_ = airstack::get_param(this, "takeoff_acceptance_distance", 0.3); + takeoff_acceptance_time_ = airstack::get_param(this, "takeoff_acceptance_time", 1.0); + landing_stationary_distance_ = airstack::get_param(this, "landing_stationary_distance", 0.02); + landing_acceptance_time_ = airstack::get_param(this, "landing_acceptance_time", 5.0); landing_tracking_point_ahead_time_ = - airstack::get_param(this, "landing_tracking_point_ahead_time", 5.0f); - takeoff_path_roll_ = airstack::get_param(this, "takeoff_path_roll", 0.0f) * M_PI / 180.0f; - takeoff_path_pitch_ = airstack::get_param(this, "takeoff_path_pitch", 0.0f) * M_PI / 180.0f; + airstack::get_param(this, "landing_tracking_point_ahead_time", 5.0); + takeoff_path_roll_ = airstack::get_param(this, "takeoff_path_roll", 0.0) * M_PI / 180.0; + takeoff_path_pitch_ = airstack::get_param(this, "takeoff_path_pitch", 0.0) * M_PI / 180.0; takeoff_path_relative_to_orientation_ = airstack::get_param(this, "takeoff_path_relative_to_orientation", false); diff --git a/robot/ros_ws/src/local/planners/trajectory_library/CMakeLists.txt b/robot/ros_ws/src/local/planners/trajectory_library/CMakeLists.txt index b582b711f..cc014b395 100644 --- a/robot/ros_ws/src/local/planners/trajectory_library/CMakeLists.txt +++ b/robot/ros_ws/src/local/planners/trajectory_library/CMakeLists.txt @@ -62,7 +62,6 @@ install(DIRECTORY DESTINATION share/${PROJECT_NAME}) -install(PROGRAMS scripts/fixed_trajectory_generator.py DESTINATION lib/${PROJECT_NAME}) ament_export_include_directories( include From 0a9060943fe38b3e6d73267b0be73ab3eb191a15 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 13:35:18 -0400 Subject: [PATCH 03/24] Remove old behavior tree example --- .../behavior/behavior_tree_example/.gitignore | 2 - .../behavior_tree_example/CMakeLists.txt | 69 ---- .../behavior_tree_example/config/example.tree | 22 -- .../config/example2.tree | 27 -- .../config/example3.tree | 12 - .../config/example3_nested_subtree.tree | 3 - .../config/example3_subtree.tree | 14 - .../config/ugv_tree.tree | 37 --- .../config/ugv_tree_basic.tree | 25 -- .../launch/behavior_tree_example.xml | 23 -- .../behavior_tree_example/package.xml | 27 -- .../rviz/behavior_tree.perspective | 62 ---- .../rviz/behavior_tree_example.rviz | 210 ------------ .../src/behavior_tree_example.cpp | 312 ------------------ .../behavior_tree_example/src/robot_node.cpp | 229 ------------- 15 files changed, 1074 deletions(-) delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/.gitignore delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/CMakeLists.txt delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/example.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/example2.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/example3.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/example3_nested_subtree.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/example3_subtree.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree_basic.tree delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/launch/behavior_tree_example.xml delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/package.xml delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree.perspective delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree_example.rviz delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/src/behavior_tree_example.cpp delete mode 100644 robot/ros_ws/src/behavior/behavior_tree_example/src/robot_node.cpp diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/.gitignore b/robot/ros_ws/src/behavior/behavior_tree_example/.gitignore deleted file mode 100644 index e6458330d..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -*~ -*.pyc \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/CMakeLists.txt b/robot/ros_ws/src/behavior/behavior_tree_example/CMakeLists.txt deleted file mode 100644 index 21d815efb..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/CMakeLists.txt +++ /dev/null @@ -1,69 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(behavior_tree_example) - -# Default to C99 -if(NOT CMAKE_C_STANDARD) - set(CMAKE_C_STANDARD 99) -endif() - -# Default to C++14 -if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) -endif() - -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() - -# find dependencies -find_package(ament_cmake REQUIRED) -find_package(rclcpp REQUIRED) -find_package(std_msgs REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(visualization_msgs REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(behavior_tree_msgs REQUIRED) -find_package(behavior_tree REQUIRED) -find_package(tf2 REQUIRED) - -#add_executable(behavior_tree_example src/behavior_tree_example.cpp) -#ament_target_dependencies(talker rclcpp std_msgs) - -add_executable(behavior_tree_example src/behavior_tree_example.cpp) -ament_target_dependencies(behavior_tree_example rclcpp std_msgs geometry_msgs visualization_msgs nav_msgs behavior_tree_msgs behavior_tree tf2) - -add_executable(robot_node src/robot_node.cpp) -ament_target_dependencies(robot_node rclcpp std_msgs geometry_msgs visualization_msgs nav_msgs behavior_tree_msgs tf2) - -install(DIRECTORY - launch - DESTINATION share/${PROJECT_NAME}/ - ) - -install(DIRECTORY - config - DESTINATION share/${PROJECT_NAME}/ - ) - -install(DIRECTORY - rviz - DESTINATION share/${PROJECT_NAME}/ - ) - -install(TARGETS - behavior_tree_example - robot_node - DESTINATION lib/${PROJECT_NAME}) - -if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - # the following line skips the linter which checks for copyrights - # uncomment the line when a copyright and license is not present in all source files - #set(ament_cmake_copyright_FOUND TRUE) - # the following line skips cpplint (only works in a git repo) - # uncomment the line when this package is not in a git repo - #set(ament_cmake_cpplint_FOUND TRUE) - ament_lint_auto_find_test_dependencies() -endif() - -ament_package() diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/example.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/example.tree deleted file mode 100644 index 4903ecf67..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/example.tree +++ /dev/null @@ -1,22 +0,0 @@ -? - -> - (Visited Destination) - (At Home) - ? - (On Ground) - [Land] - -> - ? - (In No Fly Zone) - (At Flight Altitude) - [Takeoff] - ? - (In Fly Zone) - (On Ground) - [Land] - ? - (Visited Destination) - [Go To Destination] - ? - (At Home) - [Go Home] diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/example2.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/example2.tree deleted file mode 100644 index 535704900..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/example2.tree +++ /dev/null @@ -1,27 +0,0 @@ -|| 2 - ? - (At Home) - [Spin] - ? - -> - (Visited Destination) - (At Home) - ? - (On Ground) - [Land] - -> - ? - (In No Fly Zone) - (At Flight Altitude) - [Takeoff] - ? - - (In No Fly Zone) - (On Ground) - [Land] - ? - (Visited Destination) - [Go To Destination] - ? - (At Home) - [Go Home] diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/example3.tree deleted file mode 100644 index 19229d0a4..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3.tree +++ /dev/null @@ -1,12 +0,0 @@ -|| 2 - ? - (At Home) - [Spin] - ? - -> - (Visited Destination) - (At Home) - ? - (On Ground) - [Land] - include $(find behavior_tree_example)/config/example3_subtree.tree diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_nested_subtree.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_nested_subtree.tree deleted file mode 100644 index 923908277..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_nested_subtree.tree +++ /dev/null @@ -1,3 +0,0 @@ -? - (Visited Destination) - [Go To Destination] \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_subtree.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_subtree.tree deleted file mode 100644 index a311d1d93..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/example3_subtree.tree +++ /dev/null @@ -1,14 +0,0 @@ --> - ? - (In No Fly Zone) - (At Flight Altitude) - [Takeoff] - ? - - (In No Fly Zone) - (On Ground) - [Land] - include $(find behavior_tree_example)/config/example3_nested_subtree.tree - ? - (At Home) - [Go Home] \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree.tree deleted file mode 100644 index 84e185046..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree.tree +++ /dev/null @@ -1,37 +0,0 @@ -? - -> - (User Pressed Estop) - ? - (Not Stopped) - [Stop] - -> - (User Pressed Return Home Button) - ? - (At Home) - [Go To Home] - -> - (User Pressed Start Button) - ? - (Not Stopped) - [Initiate] - ? - (Not Stuck) - [Recovery 1] - [Recovery 2] - [Recovery 3] - ? - (Low Battery) - -> - ? - (Good Comms) - [Explore] - ? - (In Comms) - [Drop Comms] - [Return to Comms] - ? - (At Home) - [Go To Home] - ? - (Not Stopped) - [Stop] \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree_basic.tree b/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree_basic.tree deleted file mode 100644 index 5d93cae6c..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/config/ugv_tree_basic.tree +++ /dev/null @@ -1,25 +0,0 @@ -? - -> - (User Pressed Estop) - ? - (Not Stopped) - [Stop] - -> - (User Pressed Return Home Button) - ? - (At Home) - [Go To Home] - -> - (User Pressed Resume) - ? - (Stopped) - [Initiate] - ? - (Low Battery) - [Explore] - ? - (At Home) - [Go To Home] - ? - (Not Stopped) - [Stop] \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/launch/behavior_tree_example.xml b/robot/ros_ws/src/behavior/behavior_tree_example/launch/behavior_tree_example.xml deleted file mode 100644 index fb5ba46ab..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/launch/behavior_tree_example.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/package.xml b/robot/ros_ws/src/behavior/behavior_tree_example/package.xml deleted file mode 100644 index 56aa8345d..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/package.xml +++ /dev/null @@ -1,27 +0,0 @@ - - - - behavior_tree_example - 0.0.0 - TODO: Package description - john - TODO: License declaration - - ament_cmake - - rclcpp - behavior_tree_msgs - behavior_tree - std_msgs - visualization_msgs - geometry_msgs - nav_msgs - tf2 - - ament_lint_auto - ament_lint_common - - - ament_cmake - - diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree.perspective b/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree.perspective deleted file mode 100644 index ea05a4467..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree.perspective +++ /dev/null @@ -1,62 +0,0 @@ -{ - "keys": {}, - "groups": { - "mainwindow": { - "keys": { - "geometry": { - "repr(QByteArray.hex)": "QtCore.QByteArray(b'01d9d0cb000300000000006400000064000005600000038e0000006400000089000005600000038e00000000000000000a000000006400000089000005600000038e')", - "type": "repr(QByteArray.hex)", - "pretty-print": " d d ` d ` d ` " - }, - "state": { - "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff00000000fd0000000100000003000004fd000002dafc0100000001fb00000042007200710074005f006200650068006100760069006f0072005f0074007200650065005f005f005000790043006f006e0073006f006c0065005f005f0031005f005f0100000000000004fd0000017300ffffff000004fd0000000000000004000000040000000800000008fc00000001000000030000000100000036004d0069006e0069006d0069007a006500640044006f0063006b00570069006400670065007400730054006f006f006c0062006100720000000000ffffffff0000000000000000')", - "type": "repr(QByteArray.hex)", - "pretty-print": " Brqt_behavior_tree__PyConsole__1__ 6MinimizedDockWidgetsToolbar " - } - }, - "groups": { - "toolbar_areas": { - "keys": { - "MinimizedDockWidgetsToolbar": { - "repr": "8", - "type": "repr" - } - }, - "groups": {} - } - } - }, - "pluginmanager": { - "keys": { - "running-plugins": { - "repr": "{'rqt_behavior_tree/PyConsole': [1]}", - "type": "repr" - } - }, - "groups": { - "plugin__rqt_behavior_tree__PyConsole__1": { - "keys": {}, - "groups": { - "dock_widget__": { - "keys": { - "dock_widget_title": { - "repr": "''", - "type": "repr" - }, - "dockable": { - "repr": "True", - "type": "repr" - }, - "parent": { - "repr": "None", - "type": "repr" - } - }, - "groups": {} - } - } - } - } - } - } -} \ No newline at end of file diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree_example.rviz b/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree_example.rviz deleted file mode 100644 index 1159cebd2..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/rviz/behavior_tree_example.rviz +++ /dev/null @@ -1,210 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 78 - Name: Displays - Property Tree Widget: - Expanded: - - /Global Options1 - - /Status1 - Splitter Ratio: 0.5 - Tree Height: 365 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 100 - Reference Frame: - Value: true - - Alpha: 1 - Class: rviz_default_plugins/PointStamped - Color: 0; 0; 255 - Enabled: true - History Length: 1 - Name: Destination - Radius: 0.4000000059604645 - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /destination - Value: true - - Alpha: 1 - Class: rviz_default_plugins/PointStamped - Color: 0; 255; 0 - Enabled: true - History Length: 1 - Name: Home - Radius: 0.4000000059604645 - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: /home - Value: true - - Angle Tolerance: 0 - Class: rviz_default_plugins/Odometry - 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: true - Keep: 1 - Name: Robot Odometry - Position Tolerance: 0 - Shape: - Alpha: 1 - Axes Length: 1 - Axes Radius: 0.10000000149011612 - Color: 255; 25; 0 - Head Length: 0.30000001192092896 - Head Radius: 0.10000000149011612 - Shaft Length: 1 - Shaft Radius: 0.05000000074505806 - Value: Axes - Topic: - Depth: 5 - Durability Policy: Volatile - Filter size: 10 - History Policy: Keep Last - Reliability Policy: Reliable - Value: perception/state_estimation/odometry - Value: true - - Class: rviz_default_plugins/MarkerArray - Enabled: true - Name: Markers - Namespaces: - destination_label: true - home_label: true - no_fly_zone: true - no_fly_zone_label: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /no_fly_zone_vis - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: world - 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: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 13.15915298461914 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 5.043847560882568 - Y: -0.7309801578521729 - Z: 1.8234843015670776 - Focal Shape Fixed Size: false - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.06039784476161003 - Target Frame: - Value: Orbit (rviz) - Yaw: 1.57039475440979 - Saved: ~ -Window Geometry: - Displays: - collapsed: true - Height: 846 - Hide Left Dock: true - Hide Right Dock: true - QMainWindow State: 000000ff00000000fd000000040000000000000156000002f4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000002f4000000c700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c000002610000000100000100000002f4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002f4000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004b0000002f800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: true - Width: 1200 - X: 1182 - Y: 227 diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/src/behavior_tree_example.cpp b/robot/ros_ws/src/behavior/behavior_tree_example/src/behavior_tree_example.cpp deleted file mode 100644 index 9f7ff0607..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/src/behavior_tree_example.cpp +++ /dev/null @@ -1,312 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include // Include the behavior tree library containing the Action and Condition classes. -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tf2/LinearMath/Matrix3x3.h" -#include "tf2/LinearMath/Quaternion.h" -#include "tf2/LinearMath/Vector3.h" - -class BehaviorTreeExample : public rclcpp::Node { - private: - bool got_robot_odom, got_home, got_destination, got_no_fly_zone, got_no_fly_zone_radius; - nav_msgs::msg::Odometry robot_odom; - float flight_z, ground_z; - geometry_msgs::msg::PointStamped home, destination; - float acceptance_radius; - geometry_msgs::msg::PointStamped no_fly_zone; - float no_fly_zone_radius; - - // Condition variables - bt::Condition* at_flight_altitude_condition; - bt::Condition* on_ground_condition; - bt::Condition* visited_destination_condition; - bt::Condition* at_home_condition; - bt::Condition* in_fly_zone_condition; - bt::Condition* in_no_fly_zone_condition; - - // Action variables - bt::Action* land_action; - bt::Action* takeoff_action; - bt::Action* go_to_destination_action; - bt::Action* go_home_action; - - // subscribers - rclcpp::Subscription::SharedPtr robot_odom_sub; - rclcpp::Subscription::SharedPtr home_sub; - rclcpp::Subscription::SharedPtr destination_sub; - rclcpp::Subscription::SharedPtr no_fly_zone_sub; - rclcpp::Subscription::SharedPtr no_fly_zone_radius_sub; - - // publishers - rclcpp::Publisher::SharedPtr vel_cmd_pub; - - // timers - rclcpp::TimerBase::SharedPtr timer; - - public: - BehaviorTreeExample() : Node("behavior_tree_example") { - on_ground_condition = new bt::Condition("On Ground", this); - at_flight_altitude_condition = new bt::Condition("At Flight Altitude", this); - visited_destination_condition = new bt::Condition("Visited Destination", this); - at_home_condition = new bt::Condition("At Home", this); - in_fly_zone_condition = new bt::Condition("In Fly Zone", this); - in_no_fly_zone_condition = new bt::Condition("In No Fly Zone", this); - - land_action = new bt::Action("Land", this); - // Do the same for the "Takeoff" action. - takeoff_action = - new bt::Action("Takeoff", this, &BehaviorTreeExample::takeoff_active_callback, this, - &BehaviorTreeExample::takeoff_inactive_callback, this); - go_to_destination_action = new bt::Action("Go To Destination", this); - go_home_action = new bt::Action("Go Home", this); - - // init subscribers - robot_odom_sub = this->create_subscription( - "odometry", 10, - std::bind(&BehaviorTreeExample::robot_odom_callback, this, std::placeholders::_1)); - home_sub = this->create_subscription( - "home", 10, - std::bind(&BehaviorTreeExample::home_callback, this, std::placeholders::_1)); - destination_sub = this->create_subscription( - "destination", 10, - std::bind(&BehaviorTreeExample::destination_callback, this, std::placeholders::_1)); - - no_fly_zone_sub = this->create_subscription( - "no_fly_zone", 10, - std::bind(&BehaviorTreeExample::no_fly_zone_callback, this, std::placeholders::_1)); - no_fly_zone_radius_sub = this->create_subscription( - "no_fly_zone_radius", 10, - std::bind(&BehaviorTreeExample::no_fly_zone_radius_callback, this, - std::placeholders::_1)); - - // init publishers - vel_cmd_pub = this->create_publisher("/vel_cmd", 10); - - // initialization - got_robot_odom = false; - got_home = false; - got_destination = false; - got_no_fly_zone = false; - got_no_fly_zone_radius = false; - flight_z = 0.99; - ground_z = 0.01; - acceptance_radius = 0.01; - - // init timer - timer = this->create_wall_timer(std::chrono::milliseconds(50), - std::bind(&BehaviorTreeExample::timer_callback, this)); - } - - void timer_callback() { - if (!got_robot_odom || !got_home || !got_destination) return; - - // The condition should be success if the robot is above the flying height's z level, - // and failure otherwise. - at_flight_altitude_condition->set(robot_odom.pose.pose.position.z > flight_z); - at_flight_altitude_condition->publish(); - - // Set the condition to success if the robot is below the ground's z level, - // or to failure if the robot is above the ground's z level. - on_ground_condition->set(robot_odom.pose.pose.position.z < ground_z); - on_ground_condition->publish(); - - // The at home condition should be set to success if the robot is within - // a threshold distance of the home location and failure otherwise. - at_home_condition->set(distance(robot_odom, home) < acceptance_radius); - at_home_condition->publish(); - - if (got_no_fly_zone && got_no_fly_zone_radius) { - float distance = sqrt(pow(robot_odom.pose.pose.position.x - no_fly_zone.point.x, 2) + - pow(robot_odom.pose.pose.position.y - no_fly_zone.point.y, 2)); - - // Check if the robot is with the radius of the no fly zone point. - bool in_no_fly_zone = distance <= no_fly_zone_radius; - - in_no_fly_zone_condition->set(in_no_fly_zone); // Set the condition. - in_no_fly_zone_condition->publish(); // Publish. - - in_fly_zone_condition->set(!in_no_fly_zone); // Set the condition. - in_fly_zone_condition->publish(); // Publish. - } - - // The visited destination condition should be set to success (true) when we first - // get close enough to the destination point and remain true forever. - float destination_distance = distance(robot_odom, destination); - if (!visited_destination_condition - ->get()) // Only changed the condition value if it hasn't been set to true yet. - visited_destination_condition->set(destination_distance < acceptance_radius); - visited_destination_condition->publish(); // Publish the condition. - - if (land_action - ->is_active()) { // Make sure the robot only lands if the land action is active. - geometry_msgs::msg::TwistStamped vel_cmd; - vel_cmd.header.stamp = this->get_clock()->now(); - vel_cmd.header.frame_id = "world"; - - if (on_ground_condition->get()) { - // Set the status to success if the robot has landed. - land_action->set_success(); - // Command zero velocity when the robot is done landing. - vel_cmd.twist.linear.x = vel_cmd.twist.linear.y = vel_cmd.twist.linear.z = 0; - } else { - // Set the status to running while the robot is landing. - land_action->set_running(); - // Command downward velocity to land. - vel_cmd.twist.linear.z = -0.3; - } - - vel_cmd_pub->publish(vel_cmd); - - // Publish the land action's status. - land_action->publish(); - } - - if (go_home_action->is_active()) { // Make sure the robot tries to go home when the go home - // action is active. - geometry_msgs::msg::TwistStamped vel_cmd; - vel_cmd.header.stamp = this->get_clock()->now(); - vel_cmd.header.frame_id = "world"; - - if (at_home_condition->get()) { - // Set the status to "SUCCESS" if the robot has reached the home location - go_home_action->set_success(); - // Command zero velocity when the robot is done traveling home. - vel_cmd.twist.linear.x = vel_cmd.twist.linear.y = vel_cmd.twist.linear.z = 0; - } else { - // Set the status to "RUNNING" while the robot is moving toward the home location. - go_home_action->set_running(); - // Command a velocity towards the home location. - tf2::Vector3 vel(home.point.x - robot_odom.pose.pose.position.x, - home.point.y - robot_odom.pose.pose.position.y, 0); - vel = 0.3 * vel.normalized(); - vel_cmd.twist.linear.x = vel.x(); - vel_cmd.twist.linear.y = vel.y(); - vel_cmd.twist.linear.z = vel.z(); - } - - vel_cmd_pub->publish(vel_cmd); - - // Publish the go home action's status - go_home_action->publish(); - } - - // Make sure the robot only tries to go to the destination while the go to destination - // action is active - if (go_to_destination_action->is_active()) { - geometry_msgs::msg::TwistStamped vel_cmd; - vel_cmd.header.stamp = this->get_clock()->now(); - vel_cmd.header.frame_id = "world"; - - if (destination_distance < acceptance_radius) { - // Set the status to success if the robot has reached the destination location. - go_to_destination_action->set_success(); - // Command zero velocity when the robot is done traveling to the destination. - vel_cmd.twist.linear.x = vel_cmd.twist.linear.y = vel_cmd.twist.linear.z = 0; - } else { - // Set the status to running while the robot is moving towards the destination - // location. - go_to_destination_action->set_running(); - // Command a velocity towards the destination location. - tf2::Vector3 vel(destination.point.x - robot_odom.pose.pose.position.x, - destination.point.y - robot_odom.pose.pose.position.y, 0); - vel = 0.3 * vel.normalized(); - vel_cmd.twist.linear.x = vel.x(); - vel_cmd.twist.linear.y = vel.y(); - vel_cmd.twist.linear.z = vel.z(); - } - - vel_cmd_pub->publish(vel_cmd); - - // Publish the go to destination action's status. - go_to_destination_action->publish(); - } - } - - void takeoff_active_callback() { - geometry_msgs::msg::TwistStamped vel_cmd; - vel_cmd.header.stamp = this->get_clock()->now(); - vel_cmd.header.frame_id = "world"; - // Set the status to "RUNNING" while the take off is in progress. - takeoff_action->set_running(); - // Command upward velocity to take off. - vel_cmd.twist.linear.z = 0.3; - - vel_cmd_pub->publish(vel_cmd); - } - - void takeoff_inactive_callback() { - geometry_msgs::msg::TwistStamped vel_cmd; - vel_cmd.header.stamp = this->get_clock()->now(); - vel_cmd.header.frame_id = "world"; - // Set the status to "RUNNING" while the take off is in progress. - takeoff_action->set_running(); - // Command upward velocity to take off. - vel_cmd.twist.linear.z = 0.0; - - vel_cmd_pub->publish(vel_cmd); - } - - void robot_odom_callback(const nav_msgs::msg::Odometry::SharedPtr robot_odom) { - got_robot_odom = true; - this->robot_odom = *robot_odom; - } - - void home_callback(const geometry_msgs::msg::PointStamped::SharedPtr home) { - got_home = true; - this->home = *home; - } - - void destination_callback(const geometry_msgs::msg::PointStamped::SharedPtr destination) { - got_destination = true; - this->destination = *destination; - } - - void no_fly_zone_callback(const geometry_msgs::msg::PointStamped::SharedPtr no_fly_zone) { - got_no_fly_zone = true; - this->no_fly_zone = *no_fly_zone; - } - - void no_fly_zone_radius_callback(const std_msgs::msg::Float32::SharedPtr no_fly_zone_radius) { - got_no_fly_zone_radius = true; - this->no_fly_zone_radius = no_fly_zone_radius->data; - } - - float distance(nav_msgs::msg::Odometry odom, geometry_msgs::msg::PointStamped point) { - float distance = sqrt(pow(odom.pose.pose.position.x - point.point.x, 2) + - pow(odom.pose.pose.position.y - point.point.y, 2)); - return distance; - } -}; - -int main(int argc, char* argv[]) { - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} diff --git a/robot/ros_ws/src/behavior/behavior_tree_example/src/robot_node.cpp b/robot/ros_ws/src/behavior/behavior_tree_example/src/robot_node.cpp deleted file mode 100644 index 4d711bc2a..000000000 --- a/robot/ros_ws/src/behavior/behavior_tree_example/src/robot_node.cpp +++ /dev/null @@ -1,229 +0,0 @@ -// Copyright (c) 2024 Carnegie Mellon University -// -// 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. - -#include - -#include -#include -#include -#include -#include -#include -#include "tf2/LinearMath/Quaternion.h" -#include "tf2/LinearMath/Matrix3x3.h" - -class RobotNode : public rclcpp::Node -{ -private: - nav_msgs::msg::Odometry odom; - geometry_msgs::msg::TwistStamped vel_cmd, ang_vel_cmd; - rclcpp::Time last_execute_time; - geometry_msgs::msg::PointStamped home, destination, no_fly_zone; - std_msgs::msg::Float32 no_fly_zone_radius; - visualization_msgs::msg::Marker no_fly_zone_marker, no_fly_zone_label, home_label, destination_label; - visualization_msgs::msg::MarkerArray marker_array; - - // subscribers - rclcpp::Subscription::SharedPtr vel_cmd_sub; - rclcpp::Subscription::SharedPtr ang_vel_cmd_sub; - - // publishers - rclcpp::Publisher::SharedPtr robot_odom_pub; - rclcpp::Publisher::SharedPtr home_pub; - rclcpp::Publisher::SharedPtr destination_pub; - rclcpp::Publisher::SharedPtr no_fly_zone_pub; - rclcpp::Publisher::SharedPtr no_fly_zone_radius_pub; - rclcpp::Publisher::SharedPtr no_fly_zone_vis_pub; - - rclcpp::TimerBase::SharedPtr timer; - -public: - RobotNode() - : Node("robot_node"){ - // initialization - home.header.frame_id = "world"; - home.point.x = 0; - home.point.y = 0; - home.point.z = 0; - - destination.header.frame_id = "world"; - destination.point.x = 10; - destination.point.y = 0; - destination.point.z = 0; - - no_fly_zone.header.frame_id = "world"; - no_fly_zone.point.x = 5; - no_fly_zone.point.y = 0; - no_fly_zone.point.z = 0; - - no_fly_zone_radius.data = 2.f; - - float marker_height = 10; - no_fly_zone_marker.header.frame_id = "world"; - no_fly_zone_marker.ns = "no_fly_zone"; - no_fly_zone_marker.id = 0; - no_fly_zone_marker.type = visualization_msgs::msg::Marker::CYLINDER; - no_fly_zone_marker.action = visualization_msgs::msg::Marker::ADD; - no_fly_zone_marker.pose.orientation.w = 1; - no_fly_zone_marker.pose.position.x = no_fly_zone.point.x; - no_fly_zone_marker.pose.position.y = no_fly_zone.point.y; - no_fly_zone_marker.pose.position.z = marker_height/2; - no_fly_zone_marker.scale.x = 2*no_fly_zone_radius.data; - no_fly_zone_marker.scale.y = 2*no_fly_zone_radius.data; - no_fly_zone_marker.scale.z = marker_height; - no_fly_zone_marker.color.r = 1; - no_fly_zone_marker.color.g = 0; - no_fly_zone_marker.color.b = 0; - no_fly_zone_marker.color.a = 0.3; - - no_fly_zone_label.header.frame_id = "world"; - no_fly_zone_label.ns = "no_fly_zone_label"; - no_fly_zone_label.id = 0; - no_fly_zone_label.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - no_fly_zone_label.action = visualization_msgs::msg::Marker::ADD; - no_fly_zone_label.pose.orientation.w = 1; - no_fly_zone_label.pose.position.x = no_fly_zone.point.x; - no_fly_zone_label.pose.position.y = no_fly_zone.point.y; - no_fly_zone_label.pose.position.z = marker_height/2; - no_fly_zone_label.scale.x = 1;//2*no_fly_zone_radius.data; - no_fly_zone_label.scale.y = 1;//2*no_fly_zone_radius.data; - no_fly_zone_label.scale.z = 1;//marker_height; - no_fly_zone_label.color.r = 1; - no_fly_zone_label.color.g = 1; - no_fly_zone_label.color.b = 1; - no_fly_zone_label.color.a = 1; - no_fly_zone_label.text = "No Fly Zone"; - - home_label.header.frame_id = "world"; - home_label.ns = "home_label"; - home_label.id = 0; - home_label.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - home_label.action = visualization_msgs::msg::Marker::ADD; - home_label.pose.orientation.w = 1; - home_label.pose.position.x = home.point.x; - home_label.pose.position.y = home.point.y; - home_label.pose.position.z = home.point.z; - home_label.scale.x = 0.5; - home_label.scale.y = 0.5; - home_label.scale.z = 0.5; - home_label.color.r = 1; - home_label.color.g = 1; - home_label.color.b = 1; - home_label.color.a = 1; - home_label.text = "Home"; - - destination_label.header.frame_id = "world"; - destination_label.ns = "destination_label"; - destination_label.id = 0; - destination_label.type = visualization_msgs::msg::Marker::TEXT_VIEW_FACING; - destination_label.action = visualization_msgs::msg::Marker::ADD; - destination_label.pose.orientation.w = 1; - destination_label.pose.position.x = destination.point.x; - destination_label.pose.position.y = destination.point.y; - destination_label.pose.position.z = destination.point.z; - destination_label.scale.x = 0.5; - destination_label.scale.y = 0.5; - destination_label.scale.z = 0.5; - destination_label.color.r = 1; - destination_label.color.g = 1; - destination_label.color.b = 1; - destination_label.color.a = 1; - destination_label.text = "Destination"; - - marker_array.markers.push_back(no_fly_zone_marker); - marker_array.markers.push_back(no_fly_zone_label); - marker_array.markers.push_back(home_label); - marker_array.markers.push_back(destination_label); - - odom.header.frame_id = "world"; - odom.child_frame_id = "world"; - odom.pose.pose.orientation.w = 1; - - last_execute_time = this->get_clock()->now(); - - - // init subscribers - vel_cmd_sub = this->create_subscription("vel_cmd", 10, std::bind(&RobotNode::vel_cmd_callback, this, std::placeholders::_1)); - ang_vel_cmd_sub = this->create_subscription("ang_vel_cmd", 10, std::bind(&RobotNode::ang_vel_cmd_callback, this, std::placeholders::_1)); - - // init publishers - robot_odom_pub = this->create_publisher("odometry", 10); - home_pub = this->create_publisher("home", 10); - destination_pub = this->create_publisher("destination", 10); - no_fly_zone_pub = this->create_publisher("no_fly_zone", 10); - no_fly_zone_radius_pub = this->create_publisher("no_fly_zone_radius", 10); - no_fly_zone_vis_pub = this->create_publisher("no_fly_zone_vis", 10); - - // init timer - timer = this->create_wall_timer(std::chrono::milliseconds(50), std::bind(&RobotNode::timer_callback, this)); - } - - void timer_callback(){ - // keep track of time - rclcpp::Time now = this->get_clock()->now(); - double dt = (now - last_execute_time).seconds(); - last_execute_time = now; - - // update the robot's position based on the velocity command - odom.pose.pose.position.x += vel_cmd.twist.linear.x*dt; - odom.pose.pose.position.y += vel_cmd.twist.linear.y*dt; - odom.pose.pose.position.z += vel_cmd.twist.linear.z*dt; - - - // update the robot's orientation based on the velocity command - double roll, pitch, yaw; - tf2::Quaternion q(odom.pose.pose.orientation.x, odom.pose.pose.orientation.y, odom.pose.pose.orientation.z, odom.pose.pose.orientation.w); - tf2::Matrix3x3 m(q); - m.getRPY(roll, pitch, yaw); - roll += ang_vel_cmd.twist.angular.x*dt; - pitch += ang_vel_cmd.twist.angular.y*dt; - yaw += ang_vel_cmd.twist.angular.z*dt; - q.setRPY(roll, pitch, yaw); - 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(); - - // publish - odom.header.stamp = home.header.stamp = destination.header.stamp = no_fly_zone.header.stamp = no_fly_zone_marker.header.stamp = this->get_clock()->now(); - robot_odom_pub->publish(odom); - home_pub->publish(home); - destination_pub->publish(destination); - no_fly_zone_pub->publish(no_fly_zone); - no_fly_zone_radius_pub->publish(no_fly_zone_radius); - no_fly_zone_vis_pub->publish(marker_array);//no_fly_zone_marker); - } - - void vel_cmd_callback(const geometry_msgs::msg::TwistStamped::SharedPtr twist){ - vel_cmd = *twist; - } - - void ang_vel_cmd_callback(const geometry_msgs::msg::TwistStamped::SharedPtr twist){ - ang_vel_cmd = *twist; - } -}; - -int main(int argc, char * argv[]) -{ - rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); - rclcpp::shutdown(); - return 0; -} From 4a0fca387e857bfe343150424938d0f667bcc011 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 13:35:35 -0400 Subject: [PATCH 04/24] Fix landing task so that it subscribes to mavros to listen to if landing succeeds --- .../robot_launch_gazebo/gz_local_launch.xml | 2 + .../local_bringup/launch/local.launch.xml | 2 + .../launch/local_droan_cpu.launch.xml | 2 + .../takeoff_landing_planner/CMakeLists.txt | 1 + .../takeoff_landing_task.hpp | 5 ++ .../src/takeoff_landing_task.cpp | 67 ++++++------------- 6 files changed, 31 insertions(+), 48 deletions(-) diff --git a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml index d69088e00..93217a883 100644 --- a/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml +++ b/robot/ros_ws/src/global/planners/exploration/launch/robot_launch_gazebo/gz_local_launch.xml @@ -24,6 +24,8 @@ + diff --git a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml index 9c9998792..755cd50ed 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml @@ -31,6 +31,8 @@ + diff --git a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml index b3e0a940e..b4a708f52 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml @@ -31,6 +31,8 @@ + diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt b/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt index 7066d6af1..2022599a1 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/CMakeLists.txt @@ -47,6 +47,7 @@ ament_target_dependencies( airstack_msgs airstack_common trajectory_library + mavros_msgs task_msgs ) diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp index 3ef0ea525..c71d4be9c 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include #include @@ -79,6 +80,9 @@ class TakeoffLandingTaskNode : public rclcpp::Node std::atomic has_control_{false}; std::atomic state_estimate_timed_out_{false}; + // landed state from mavros + std::atomic landed_state_{0}; // mavros_msgs::msg::ExtendedState::LANDED_STATE_UNDEFINED + // task exclusion std::atomic task_active_{false}; std::atomic cancel_requested_{false}; @@ -90,6 +94,7 @@ class TakeoffLandingTaskNode : public rclcpp::Node rclcpp::Subscription::SharedPtr has_control_sub_; rclcpp::Subscription::SharedPtr state_estimate_timed_out_sub_; rclcpp::Subscription::SharedPtr completion_percentage_sub_; + rclcpp::Subscription::SharedPtr extended_state_sub_; // publishers rclcpp::Publisher::SharedPtr traj_override_pub_; diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp index b6f9418d7..11aefa0cd 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -70,6 +70,12 @@ TakeoffLandingTaskNode::TakeoffLandingTaskNode() "state_estimate_timed_out", 1, [this](std_msgs::msg::Bool::SharedPtr msg) { state_estimate_timed_out_ = msg->data; }); + extended_state_sub_ = this->create_subscription( + "extended_state", 1, + [this](mavros_msgs::msg::ExtendedState::SharedPtr msg) { + landed_state_ = msg->landed_state; + }); + // publishers traj_override_pub_ = this->create_publisher("trajectory_override", 1); @@ -391,9 +397,6 @@ void TakeoffLandingTaskNode::land_execute(std::shared_ptr goal_h RCLCPP_INFO(this->get_logger(), "LandTask: descending at %.2f m/s", velocity); - // sliding window of odometry for stationary detection - std::deque odom_window; - rclcpp::Rate rate(10); while (rclcpp::ok()) { if (cancel_requested_) { @@ -405,58 +408,26 @@ void TakeoffLandingTaskNode::land_execute(std::shared_ptr goal_h return; } - nav_msgs::msg::Odometry current_odom; + float current_z; { std::lock_guard lock(odom_mutex_); - current_odom = robot_odom_; + current_z = robot_odom_.pose.pose.position.z; } - feedback->current_altitude_m = current_odom.pose.pose.position.z; + feedback->current_altitude_m = current_z; feedback->status = "landing"; goal_handle->publish_feedback(feedback); - odom_window.push_back(current_odom); - - // trim window to landing_acceptance_time seconds - while (!odom_window.empty()) { - double age = (rclcpp::Time(current_odom.header.stamp) - - rclcpp::Time(odom_window.front().header.stamp)).seconds(); - if (age > landing_acceptance_time_) { - odom_window.pop_front(); - } else { - break; - } - } - - // check if we have enough history and the robot has been stationary - if (odom_window.size() >= 2) { - double window_span = (rclcpp::Time(current_odom.header.stamp) - - rclcpp::Time(odom_window.front().header.stamp)).seconds(); - - if (window_span >= landing_acceptance_time_) { - bool stationary = true; - for (const auto & past_odom : odom_window) { - double dx = current_odom.pose.pose.position.x - past_odom.pose.pose.position.x; - double dy = current_odom.pose.pose.position.y - past_odom.pose.pose.position.y; - double dz = current_odom.pose.pose.position.z - past_odom.pose.pose.position.z; - double dist = std::sqrt(dx * dx + dy * dy + dz * dz); - if (dist > landing_stationary_distance_) { - stationary = false; - break; - } - } - - if (stationary) { - RCLCPP_INFO(this->get_logger(), "LandTask: landing detected at %.2fm", - current_odom.pose.pose.position.z); - set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); - result->success = true; - result->message = "landing complete"; - goal_handle->succeed(result); - task_active_ = false; - return; - } - } + // check if mavros reports on-ground + if (landed_state_ == mavros_msgs::msg::ExtendedState::LANDED_STATE_ON_GROUND) { + RCLCPP_INFO(this->get_logger(), "LandTask: landed (mavros landed_state = ON_GROUND) at %.2fm", + current_z); + set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + result->success = true; + result->message = "landing complete"; + goal_handle->succeed(result); + task_active_ = false; + return; } rate.sleep(); From 5a79e353d63ea4711ccf232089828afad60e34dd Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 15:20:33 -0400 Subject: [PATCH 05/24] Add subfolders for rviz, rqt, foxglove --- .gitmodules | 2 +- .../rqt_behavior_tree => foxglove/.gitkeep} | 0 .../gui/{ => rqt}/rqt_behavior_tree/.gitignore | 0 .../gui/{ => rqt}/rqt_behavior_tree/CHANGELOG.rst | 0 .../gui/{ => rqt}/rqt_behavior_tree/package.xml | 0 .../gui/{ => rqt}/rqt_behavior_tree/plugin.xml | 0 .../rqt_behavior_tree/resource/py_console_widget.ui | 0 .../rqt_behavior_tree/resource/rqt_behavior_tree} | 0 .../gui/{ => rqt}/rqt_behavior_tree/setup.cfg | 0 .../gui/{ => rqt}/rqt_behavior_tree/setup.py | 0 .../src/rqt_behavior_tree}/__init__.py | 0 .../rqt_behavior_tree/src/rqt_behavior_tree/main.py | 0 .../src/rqt_behavior_tree/py_console.py | 0 .../src/rqt_behavior_tree/py_console_text_edit.py | 0 .../src/rqt_behavior_tree/py_console_widget.py | 0 .../src/rqt_behavior_tree/spyder_console_widget.py | 0 .../rqt_behavior_tree/src/rqt_behavior_tree/test.py | 0 .../src/rqt_behavior_tree/xdot}/__init__.py | 0 .../src/rqt_behavior_tree/xdot/wxxdot.py | 0 .../src/rqt_behavior_tree/xdot/xdot.py | 0 .../src/rqt_behavior_tree/xdot/xdot_qt.py | 0 .../gui/{ => rqt}/rqt_py_template/CHANGELOG.rst | 0 .../gui/{ => rqt}/rqt_py_template/README.md | 0 .../rqt_py_template/generate_rqt_py_package.sh | 0 .../gui/{ => rqt}/rqt_py_template/package.xml | 0 .../gui/{ => rqt}/rqt_py_template/plugin.xml | 0 .../rqt_py_template/resource/py_console_widget.ui | 0 .../rqt_py_template/resource/rqt_py_template | 0 .../gui/{ => rqt}/rqt_py_template/setup.cfg | 0 .../gui/{ => rqt}/rqt_py_template/setup.py | 0 .../rqt_py_template/src/rqt_py_template/__init__.py | 0 .../rqt_py_template/src/rqt_py_template/main.py | 0 .../src/rqt_py_template/py_console_text_edit.py | 0 .../src/rqt_py_template/py_console_widget.py | 0 .../src/rqt_py_template/spyder_console_widget.py | 0 .../rqt_py_template/src/rqt_py_template/template.py | 0 .../rviz_behavior_tree_panel/.clang-format | 0 .../{ => rviz}/rviz_behavior_tree_panel/.gitignore | 0 .../.pre-commit-config.yaml | 0 .../rviz_behavior_tree_panel/CMakeLists.txt | 0 .../gui/{ => rviz}/rviz_behavior_tree_panel/LICENSE | 0 .../{ => rviz}/rviz_behavior_tree_panel/README.md | 0 .../icons/classes/BehaviorTreePanel.png | Bin .../icons/classes/DemoPanel.png | Bin .../behavior_tree_panel.hpp | 0 .../{ => rviz}/rviz_behavior_tree_panel/package.xml | 0 .../rviz_common_plugins.xml | 0 .../scripts/simple_test_publisher.py | 0 .../scripts/test_behavior_tree_publisher.py | 0 .../src/behavior_tree_panel.cpp | 0 .../{ => rviz}/rviz_behavior_tree_panel/xdot_cpp | 0 51 files changed, 1 insertion(+), 1 deletion(-) rename common/ros_packages/gui/{rqt_behavior_tree/resource/rqt_behavior_tree => foxglove/.gitkeep} (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/.gitignore (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/CHANGELOG.rst (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/package.xml (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/plugin.xml (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/resource/py_console_widget.ui (100%) rename common/ros_packages/gui/{rqt_behavior_tree/src/rqt_behavior_tree/__init__.py => rqt/rqt_behavior_tree/resource/rqt_behavior_tree} (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/setup.cfg (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/setup.py (100%) rename common/ros_packages/gui/{rqt_behavior_tree/src/rqt_behavior_tree/xdot => rqt/rqt_behavior_tree/src/rqt_behavior_tree}/__init__.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/main.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/py_console.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/py_console_text_edit.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/py_console_widget.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/spyder_console_widget.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/test.py (100%) rename common/ros_packages/gui/{rqt_py_template/src/rqt_py_template => rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot}/__init__.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/xdot/wxxdot.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot_qt.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/CHANGELOG.rst (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/README.md (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/generate_rqt_py_package.sh (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/package.xml (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/plugin.xml (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/resource/py_console_widget.ui (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/resource/rqt_py_template (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/setup.cfg (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/setup.py (100%) create mode 100644 common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/__init__.py rename common/ros_packages/gui/{ => rqt}/rqt_py_template/src/rqt_py_template/main.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/src/rqt_py_template/py_console_text_edit.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/src/rqt_py_template/py_console_widget.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/src/rqt_py_template/spyder_console_widget.py (100%) rename common/ros_packages/gui/{ => rqt}/rqt_py_template/src/rqt_py_template/template.py (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/.clang-format (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/.gitignore (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/.pre-commit-config.yaml (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/CMakeLists.txt (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/LICENSE (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/README.md (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/icons/classes/BehaviorTreePanel.png (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/icons/classes/DemoPanel.png (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/include/rviz_behavior_tree_panel/behavior_tree_panel.hpp (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/package.xml (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/rviz_common_plugins.xml (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/scripts/simple_test_publisher.py (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/scripts/test_behavior_tree_publisher.py (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/src/behavior_tree_panel.cpp (100%) rename common/ros_packages/gui/{ => rviz}/rviz_behavior_tree_panel/xdot_cpp (100%) diff --git a/.gitmodules b/.gitmodules index 0b29f3486..ca8abf9c8 100644 --- a/.gitmodules +++ b/.gitmodules @@ -8,7 +8,7 @@ path = robot/ros_ws/src/perception/macvo_ros2/macvo_ros2/macvo url = https://github.com/MAC-VO/MAC-VO.git [submodule "robot/ros_ws/src/rviz_behavior_tree_panel/xdot_cpp"] - path = common/ros_packages/gui/rviz_behavior_tree_panel/xdot_cpp + path = common/ros_packages/gui/rviz/rviz_behavior_tree_panel/xdot_cpp url = https://github.com/castacks/xdot_cpp.git [submodule "simulation/isaac-sim/extensions/PegasusSimulator"] path = simulation/isaac-sim/extensions/PegasusSimulator diff --git a/common/ros_packages/gui/rqt_behavior_tree/resource/rqt_behavior_tree b/common/ros_packages/gui/foxglove/.gitkeep similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/resource/rqt_behavior_tree rename to common/ros_packages/gui/foxglove/.gitkeep diff --git a/common/ros_packages/gui/rqt_behavior_tree/.gitignore b/common/ros_packages/gui/rqt/rqt_behavior_tree/.gitignore similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/.gitignore rename to common/ros_packages/gui/rqt/rqt_behavior_tree/.gitignore diff --git a/common/ros_packages/gui/rqt_behavior_tree/CHANGELOG.rst b/common/ros_packages/gui/rqt/rqt_behavior_tree/CHANGELOG.rst similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/CHANGELOG.rst rename to common/ros_packages/gui/rqt/rqt_behavior_tree/CHANGELOG.rst diff --git a/common/ros_packages/gui/rqt_behavior_tree/package.xml b/common/ros_packages/gui/rqt/rqt_behavior_tree/package.xml similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/package.xml rename to common/ros_packages/gui/rqt/rqt_behavior_tree/package.xml diff --git a/common/ros_packages/gui/rqt_behavior_tree/plugin.xml b/common/ros_packages/gui/rqt/rqt_behavior_tree/plugin.xml similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/plugin.xml rename to common/ros_packages/gui/rqt/rqt_behavior_tree/plugin.xml diff --git a/common/ros_packages/gui/rqt_behavior_tree/resource/py_console_widget.ui b/common/ros_packages/gui/rqt/rqt_behavior_tree/resource/py_console_widget.ui similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/resource/py_console_widget.ui rename to common/ros_packages/gui/rqt/rqt_behavior_tree/resource/py_console_widget.ui diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/__init__.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/resource/rqt_behavior_tree similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/__init__.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/resource/rqt_behavior_tree diff --git a/common/ros_packages/gui/rqt_behavior_tree/setup.cfg b/common/ros_packages/gui/rqt/rqt_behavior_tree/setup.cfg similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/setup.cfg rename to common/ros_packages/gui/rqt/rqt_behavior_tree/setup.cfg diff --git a/common/ros_packages/gui/rqt_behavior_tree/setup.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/setup.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/setup.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/setup.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/__init__.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/__init__.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/__init__.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/__init__.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/main.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/main.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/main.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/main.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console_text_edit.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console_text_edit.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console_text_edit.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console_text_edit.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console_widget.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console_widget.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/py_console_widget.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/py_console_widget.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/spyder_console_widget.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/spyder_console_widget.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/spyder_console_widget.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/spyder_console_widget.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/test.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/test.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/test.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/test.py diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/__init__.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/__init__.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/__init__.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/__init__.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/wxxdot.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/wxxdot.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/wxxdot.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/wxxdot.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot.py diff --git a/common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot_qt.py b/common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot_qt.py similarity index 100% rename from common/ros_packages/gui/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot_qt.py rename to common/ros_packages/gui/rqt/rqt_behavior_tree/src/rqt_behavior_tree/xdot/xdot_qt.py diff --git a/common/ros_packages/gui/rqt_py_template/CHANGELOG.rst b/common/ros_packages/gui/rqt/rqt_py_template/CHANGELOG.rst similarity index 100% rename from common/ros_packages/gui/rqt_py_template/CHANGELOG.rst rename to common/ros_packages/gui/rqt/rqt_py_template/CHANGELOG.rst diff --git a/common/ros_packages/gui/rqt_py_template/README.md b/common/ros_packages/gui/rqt/rqt_py_template/README.md similarity index 100% rename from common/ros_packages/gui/rqt_py_template/README.md rename to common/ros_packages/gui/rqt/rqt_py_template/README.md diff --git a/common/ros_packages/gui/rqt_py_template/generate_rqt_py_package.sh b/common/ros_packages/gui/rqt/rqt_py_template/generate_rqt_py_package.sh similarity index 100% rename from common/ros_packages/gui/rqt_py_template/generate_rqt_py_package.sh rename to common/ros_packages/gui/rqt/rqt_py_template/generate_rqt_py_package.sh diff --git a/common/ros_packages/gui/rqt_py_template/package.xml b/common/ros_packages/gui/rqt/rqt_py_template/package.xml similarity index 100% rename from common/ros_packages/gui/rqt_py_template/package.xml rename to common/ros_packages/gui/rqt/rqt_py_template/package.xml diff --git a/common/ros_packages/gui/rqt_py_template/plugin.xml b/common/ros_packages/gui/rqt/rqt_py_template/plugin.xml similarity index 100% rename from common/ros_packages/gui/rqt_py_template/plugin.xml rename to common/ros_packages/gui/rqt/rqt_py_template/plugin.xml diff --git a/common/ros_packages/gui/rqt_py_template/resource/py_console_widget.ui b/common/ros_packages/gui/rqt/rqt_py_template/resource/py_console_widget.ui similarity index 100% rename from common/ros_packages/gui/rqt_py_template/resource/py_console_widget.ui rename to common/ros_packages/gui/rqt/rqt_py_template/resource/py_console_widget.ui diff --git a/common/ros_packages/gui/rqt_py_template/resource/rqt_py_template b/common/ros_packages/gui/rqt/rqt_py_template/resource/rqt_py_template similarity index 100% rename from common/ros_packages/gui/rqt_py_template/resource/rqt_py_template rename to common/ros_packages/gui/rqt/rqt_py_template/resource/rqt_py_template diff --git a/common/ros_packages/gui/rqt_py_template/setup.cfg b/common/ros_packages/gui/rqt/rqt_py_template/setup.cfg similarity index 100% rename from common/ros_packages/gui/rqt_py_template/setup.cfg rename to common/ros_packages/gui/rqt/rqt_py_template/setup.cfg diff --git a/common/ros_packages/gui/rqt_py_template/setup.py b/common/ros_packages/gui/rqt/rqt_py_template/setup.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/setup.py rename to common/ros_packages/gui/rqt/rqt_py_template/setup.py diff --git a/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/__init__.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/__init__.py new file mode 100644 index 000000000..e69de29bb diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/main.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/main.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/main.py rename to common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/main.py diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/py_console_text_edit.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/py_console_text_edit.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/py_console_text_edit.py rename to common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/py_console_text_edit.py diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/py_console_widget.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/py_console_widget.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/py_console_widget.py rename to common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/py_console_widget.py diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/spyder_console_widget.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/spyder_console_widget.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/spyder_console_widget.py rename to common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/spyder_console_widget.py diff --git a/common/ros_packages/gui/rqt_py_template/src/rqt_py_template/template.py b/common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/template.py similarity index 100% rename from common/ros_packages/gui/rqt_py_template/src/rqt_py_template/template.py rename to common/ros_packages/gui/rqt/rqt_py_template/src/rqt_py_template/template.py diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/.clang-format b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.clang-format similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/.clang-format rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.clang-format diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/.gitignore b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.gitignore similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/.gitignore rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.gitignore diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/.pre-commit-config.yaml b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.pre-commit-config.yaml similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/.pre-commit-config.yaml rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/.pre-commit-config.yaml diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/CMakeLists.txt b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/CMakeLists.txt similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/CMakeLists.txt rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/CMakeLists.txt diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/LICENSE b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/LICENSE similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/LICENSE rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/LICENSE diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/README.md b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/README.md similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/README.md rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/README.md diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/icons/classes/BehaviorTreePanel.png b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/icons/classes/BehaviorTreePanel.png similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/icons/classes/BehaviorTreePanel.png rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/icons/classes/BehaviorTreePanel.png diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/icons/classes/DemoPanel.png b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/icons/classes/DemoPanel.png similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/icons/classes/DemoPanel.png rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/icons/classes/DemoPanel.png diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/include/rviz_behavior_tree_panel/behavior_tree_panel.hpp b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/include/rviz_behavior_tree_panel/behavior_tree_panel.hpp similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/include/rviz_behavior_tree_panel/behavior_tree_panel.hpp rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/include/rviz_behavior_tree_panel/behavior_tree_panel.hpp diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/package.xml b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/package.xml similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/package.xml rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/package.xml diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/rviz_common_plugins.xml b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/rviz_common_plugins.xml similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/rviz_common_plugins.xml rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/rviz_common_plugins.xml diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/scripts/simple_test_publisher.py b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/scripts/simple_test_publisher.py similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/scripts/simple_test_publisher.py rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/scripts/simple_test_publisher.py diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/scripts/test_behavior_tree_publisher.py b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/scripts/test_behavior_tree_publisher.py similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/scripts/test_behavior_tree_publisher.py rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/scripts/test_behavior_tree_publisher.py diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/src/behavior_tree_panel.cpp b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/src/behavior_tree_panel.cpp similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/src/behavior_tree_panel.cpp rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/src/behavior_tree_panel.cpp diff --git a/common/ros_packages/gui/rviz_behavior_tree_panel/xdot_cpp b/common/ros_packages/gui/rviz/rviz_behavior_tree_panel/xdot_cpp similarity index 100% rename from common/ros_packages/gui/rviz_behavior_tree_panel/xdot_cpp rename to common/ros_packages/gui/rviz/rviz_behavior_tree_panel/xdot_cpp From 9f019548e6e502b1b7b19ee491987396c3832cea Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 15:24:14 -0400 Subject: [PATCH 06/24] Add rviz plugins --- .gitmodules | 3 + .../rviz/3d_waypoint_rviz2_plugin/.gitignore | 39 ++ .../3d_waypoint_rviz2_plugin/CMakeLists.txt | 126 +++++ .../rviz/3d_waypoint_rviz2_plugin/README.md | 192 +++++++ .../waypoint_rviz2_plugin/waypoint_tool.hpp | 75 +++ .../waypoint_rviz2_plugin/waypoint_widget.hpp | 108 ++++ .../launch/rviz2.launch.py | 28 + .../3d_waypoint_rviz2_plugin/media/axis.dae | 400 ++++++++++++++ .../rviz/3d_waypoint_rviz2_plugin/package.xml | 37 ++ .../plugin_description.xml | 10 + .../src/waypoint_tool.cpp | 403 ++++++++++++++ .../src/waypoint_widget.cpp | 504 ++++++++++++++++++ .../ui/waypoint_plugin.ui | 253 +++++++++ .../gui/rviz/rviz_polygon_selection_tool | 1 + 14 files changed, 2179 insertions(+) create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/.gitignore create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_widget.hpp create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/launch/rviz2.launch.py create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/media/axis.dae create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/package.xml create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/plugin_description.xml create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/ui/waypoint_plugin.ui create mode 160000 common/ros_packages/gui/rviz/rviz_polygon_selection_tool diff --git a/.gitmodules b/.gitmodules index ca8abf9c8..4314795a4 100644 --- a/.gitmodules +++ b/.gitmodules @@ -14,3 +14,6 @@ path = simulation/isaac-sim/extensions/PegasusSimulator url = https://github.com/castacks/PegasusSimulator-AirStack-Integration.git +[submodule "common/ros_packages/gui/rviz/rviz_polygon_selection_tool"] + path = common/ros_packages/gui/rviz/rviz_polygon_selection_tool + url = https://github.com/swri-robotics/rviz_polygon_selection_tool.git diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/.gitignore b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/.gitignore new file mode 100644 index 000000000..88cd635a1 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/.gitignore @@ -0,0 +1,39 @@ +# Build artifacts +build/ +install/ +log/ + +# IDE files +.vscode/ +.idea/ +*.swp +*.swo +*~ + +# Qt generated files +*.autosave +moc_*.cpp +moc_*.h +ui_*.h + +# Bag files +*.bag +*.db3 +*.db3-shm +*.db3-wal + +# CMake +CMakeCache.txt +CMakeFiles/ +cmake_install.cmake +Makefile + +# Python +__pycache__/ +*.pyc +*.pyo +*.pyd + +# OS files +.DS_Store +Thumbs.db diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt new file mode 100644 index 000000000..83d651417 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt @@ -0,0 +1,126 @@ +cmake_minimum_required(VERSION 3.5) +project(waypoint_rviz2_plugin) + +# Default to C++14 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +# Find dependencies +find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rviz_common REQUIRED) +find_package(rviz_default_plugins REQUIRED) +find_package(rviz_rendering REQUIRED) +find_package(rviz_ogre_vendor REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(visualization_msgs REQUIRED) +find_package(interactive_markers REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(tf2 REQUIRED) +find_package(tf2_geometry_msgs REQUIRED) +find_package(rosbag2_cpp REQUIRED) +find_package(pluginlib REQUIRED) + +# Qt5 +find_package(Qt5 REQUIRED COMPONENTS Core Widgets) +set(QT_LIBRARIES Qt5::Widgets) + +# Qt signals and slots to avoid defining "emit", "slots" +add_definitions(-DQT_NO_KEYWORDS) + +# Header files that need Qt Moc pre-processing +qt5_wrap_cpp(MOC_FILES + include/waypoint_rviz2_plugin/waypoint_widget.hpp + include/waypoint_rviz2_plugin/waypoint_tool.hpp +) + +# Convert the Qt UI files +qt5_wrap_ui(UIC_FILES + ui/waypoint_plugin.ui +) + +# Include directories +include_directories( + include + ${CMAKE_CURRENT_BINARY_DIR} +) + +# Plugin source files +set(SOURCES + src/waypoint_widget.cpp + src/waypoint_tool.cpp + ${MOC_FILES} +) + +# Declare the library +add_library(${PROJECT_NAME} SHARED + ${SOURCES} + ${UIC_FILES} +) + +# Dependencies +set(DEPENDENCIES + rclcpp + rviz_common + rviz_default_plugins + rviz_rendering + rviz_ogre_vendor + geometry_msgs + visualization_msgs + interactive_markers + nav_msgs + tf2 + tf2_geometry_msgs + rosbag2_cpp + pluginlib +) + +ament_target_dependencies(${PROJECT_NAME} + ${DEPENDENCIES} +) + +target_link_libraries(${PROJECT_NAME} + ${QT_LIBRARIES} +) + +# Prevent pluginlib from using boost +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +# Export plugin description file for pluginlib +pluginlib_export_plugin_description_file(rviz_common plugin_description.xml) + +# Install +install(TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(DIRECTORY include/ + DESTINATION include/ +) + +install(FILES plugin_description.xml + DESTINATION share/${PROJECT_NAME} +) + +install(DIRECTORY media/ + DESTINATION share/${PROJECT_NAME}/media +) + +install(DIRECTORY launch/ + DESTINATION share/${PROJECT_NAME}/launch +) + +# Export +ament_export_include_directories(include) +ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies(${DEPENDENCIES}) + +ament_package() diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md new file mode 100644 index 000000000..aa2141005 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md @@ -0,0 +1,192 @@ +# 3D Waypoint RViz2 Plugin + +An interactive RViz2 plugin for ROS2 Humble (and above) that allows users to create, manipulate, and manage 3D waypoints directly in the RViz2 visualization environment. + +image + + + +## Features + +- **Interactive Waypoint Creation**: Click to add waypoints at any position in the 3D environment +- **3D Manipulation**: Drag and move waypoints using interactive markers +- **Orientation Control**: Set and adjust waypoint orientation (yaw angle) +- **Visual Feedback**: Real-time visual representation of waypoints with axis indicators +- **Waypoint Management**: + - Add waypoints with left-click + - Delete waypoints with right-click or context menu + - Manually adjust position and orientation via UI controls + - Clear all waypoints at once +- **Data Persistence**: Save and load waypoint configurations using ROS2 bag files (.db3) +- **Publishing**: Publish waypoints as `nav_msgs/msg/Path` messages +- **Configurable**: Set default height, frame ID, and topic name + +## Requirements + +- ROS2 Humble or above +- RViz2 +- Qt5 +- C++14 or higher + +## Dependencies + +- rclcpp +- rviz_common +- rviz_default_plugins +- rviz_rendering +- rviz_ogre_vendor +- geometry_msgs +- visualization_msgs +- interactive_markers +- nav_msgs +- tf2 +- tf2_geometry_msgs +- rosbag2_cpp +- pluginlib + +## Building + +1. Clone this repository into your ROS2 workspace: +```bash +cd ~/ros2_ws/src +git clone waypoint_rviz2_plugin +``` + +2. Install dependencies: +```bash +cd ~/ros2_ws +rosdep install --from-paths src --ignore-src -r -y +``` + +3. Build the package: +```bash +cd ~/ros2_ws +colcon build --packages-select waypoint_rviz2_plugin +``` + +4. Source the workspace: +```bash +source ~/ros2_ws/install/setup.bash +``` + +## Usage + +### Launching RViz2 with the Plugin + +```bash +ros2 launch waypoint_rviz2_plugin rviz2.launch.py +``` + +Or start RViz2 manually: +```bash +rviz2 +``` + +### Adding the Plugin to RViz2 + +1. Open RViz2 +2. Click on the "Panels" menu and select "Add New Panel" +3. In the toolbar, click the "+" icon to add a new tool +4. Select "waypoint_rviz2_plugin/WaypointTool" from the list +5. The waypoint tool should now appear in the toolbar + +### Using the Plugin + +1. **Select the Tool**: Click on the Waypoint Tool icon in the RViz2 toolbar (or press '1' as shortcut) + +2. **Add Waypoints**: + - Left-click anywhere in the 3D view to place a waypoint + - An axis indicator will appear showing the waypoint position + +3. **Move Waypoints**: + - In the Displays panel, make sure to click Add > By topic > /waypoint_plugin/update/InteractiveMarkers + - Click and drag the interactive markers to reposition waypoints + - Use the rotation controls on the markers to adjust orientation + +5. **Delete Waypoints**: + - Right-click on a waypoint to delete it + - Or right-click on the interactive marker and select "delete" from the menu + +6. **Manual Adjustment**: + - Use the panel controls to manually set X, Y, Z position and Yaw orientation + - Select "set manual" from the marker context menu to apply manual changes + +7. **Configuration**: + - **Topic**: Set the topic name for publishing waypoints (default: `/waypoints`) + - **Frame**: Set the reference frame for waypoints (default: `map`) + - **Default Height**: Set the Z-height for new waypoints + +8. **Save/Load**: + - Click "Save Waypoints" to save current waypoints to a .db3 bag file + - Click "Load Waypoints" to load waypoints from a .db3 bag file + +9. **Publish**: + - Click "Publish Waypoints" to publish all waypoints as a `nav_msgs/msg/Path` message + - To visualize, in the Displays panel click Add > /waypoints > Path + +10. **Clear All**: + - Click "Clear All" to remove all waypoints from the scene + +### Listening to Published Waypoints + +```bash +ros2 topic echo /waypoints +``` + +## File Structure + +``` +waypoint_rviz2_plugin/ +├── CMakeLists.txt +├── package.xml +├── plugin_description.xml +├── README.md +├── include/ +│ └── waypoint_rviz2_plugin/ +│ ├── waypoint_tool.hpp +│ └── waypoint_widget.hpp +├── src/ +│ ├── waypoint_tool.cpp +│ └── waypoint_widget.cpp +├── ui/ +│ └── waypoint_plugin.ui +├── media/ +│ └── axis.dae +└── launch/ + └── rviz2.launch.py +``` + +## Migration from ROS1 + +This plugin is a port of the ROS1 Noetic waypoint plugin. Key changes include: + +- Updated to use `rclcpp` instead of `roscpp` +- Updated to use `rviz_common` instead of `rviz` +- Updated interactive markers API for ROS2 +- Changed from `rosbag` to `rosbag2_cpp` API +- Updated TF library from `tf` to `tf2` +- Changed plugin export macros for ROS2 +- Updated build system from `catkin` to `ament_cmake` + +## Known Issues + +- Saved bag files use the `.db3` format (SQLite3) instead of the ROS1 `.bag` format +- The 6D checkbox in the UI is currently not implemented + +## Contributing + +Contributions are welcome! Please feel free to submit issues and pull requests. + +## License + +Apache 2.0 + +## Credits + +Original ROS1 version by KoKoLates (the21515@gmail.com) +ROS2 port for Humble and above + +## References + +- [RViz2 Plugin Tutorial](https://docs.ros.org/en/humble/Tutorials/Advanced/RViz-Plugins.html) +- [Interactive Markers](https://docs.ros.org/en/humble/Tutorials/Advanced/RViz/Interactive-Markers.html) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp new file mode 100644 index 000000000..622198cb0 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp @@ -0,0 +1,75 @@ +/** + * @file waypoint_tool.hpp + * @author KoKoLates (the21515@gmail.com) + * @version 1.0.0 + * @date 2023-06-19 + * + * ROS2 port of the interactive waypoint tool for RViz2 + */ + +#pragma once + +#ifndef Q_MOC_RUN +#include +#include +#include +#endif + +#include +#include +#include +#include +#include + +#include "waypoint_widget.hpp" + +namespace rviz_common { + class DisplayContext; + class ViewportMouseEvent; + namespace properties { + class VectorProperty; + } + class PanelDockWidget; +} + +namespace waypoint_rviz2_plugin { + +class WaypointTool: public rviz_common::Tool { + Q_OBJECT +public: + WaypointTool(); + ~WaypointTool() override; + + void onInitialize() override; + void activate() override; + void deactivate() override; + int processMouseEvent(rviz_common::ViewportMouseEvent& event) override; + + void makeItem(const Ogre::Vector3&, const Ogre::Quaternion&); + + void load(const rviz_common::Config& config) override; + void save(rviz_common::Config config) const override; + +private: + void getMarkerPose(); + void clearAllMarker(); + void processFeedBack(const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr&); + + Ogre::SceneNode *move_axis_node_; + std::string axis_resource_; + + WaypointWidget *widget_; + rviz_common::PanelDockWidget *widget_dock_; + + std::shared_ptr server_; + interactive_markers::MenuHandler menu_handler_; + + typedef std::map str2nodeptr; + str2nodeptr node_map_; + + int unique_idx_; + + rclcpp::Node::SharedPtr node_; +}; + +} diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_widget.hpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_widget.hpp new file mode 100644 index 000000000..89544e07d --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_widget.hpp @@ -0,0 +1,108 @@ +/** + * @file waypoint_widget.hpp + * @author KoKoLates (the21515@gmail.com) + * @version 1.0.0 + * @date 2023-12-10 + * + * ROS2 port of the interactive waypoint widget for RViz2 + */ + +#pragma once + +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#endif + +#include +#include +#include + +#include "ui_waypoint_plugin.h" + +namespace rviz_common { + class DisplayContext; +} + +namespace interactive_markers { + class InteractiveMarkerServer; +} + +namespace Ui { + class PluginWidget; +} + +namespace waypoint_rviz2_plugin { + class WaypointTool; +} + +namespace waypoint_rviz2_plugin { + constexpr char waypoint_name_prefix[] = "point#"; + + class WaypointWidget: public QWidget { + friend class WaypointTool; + Q_OBJECT + + public: + WaypointWidget(rviz_common::DisplayContext *context, + rclcpp::Node::SharedPtr node, + std::map *map_ptr, + std::shared_ptr server, + int *unique_idx, + QWidget *parent=nullptr, + WaypointTool *waypoint_tool=nullptr); + ~WaypointWidget(); + + void enable(); + void disable(); + + void setPose(const Ogre::Vector3&, const Ogre::Quaternion&); + void setConfig(QString topic, QString frame, float height); + void setWaypointLabel(Ogre::Vector3 position); + void setWaypointCount(int size); + void setSelectedMarkerName(std::string name); + + void getPose(Ogre::Vector3&, Ogre::Quaternion&); + QString getFrameId(); + QString getOutputTopic(); + double getDefaultHeight(); + + void saveBag(const std::string& filename); + void loadBag(const std::string& filename); + + protected: + Ui::PluginWidget *ui_; + rviz_common::DisplayContext *context_; + + private: + rclcpp::Node::SharedPtr node_; + rclcpp::Publisher::SharedPtr path_publisher_; + + WaypointTool *waypoint_tool_; + std::map *map_ptr_; + Ogre::SceneManager *scene_manager_; + std::shared_ptr server_; + + int* unique_idx_; + double default_height_; + + QString output_topic_; + QString frame_id_; + + std::mutex frame_updates_mutex_; + std::string selected_marker_name_; + + private Q_SLOTS: + void saveHandler(); + void loadHandler(); + void clearHandler(); + void publishHandler(); + void frameChange(); + void topicChange(); + void poseChange(double value); + void heightChange(double height); + }; +} diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/launch/rviz2.launch.py b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/launch/rviz2.launch.py new file mode 100644 index 000000000..39284886d --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/launch/rviz2.launch.py @@ -0,0 +1,28 @@ +""" +RViz2 launch file for waypoint plugin demonstration +""" + +from launch import LaunchDescription +from launch_ros.actions import Node +from ament_index_python.packages import get_package_share_directory +import os + + +def generate_launch_description(): + pkg_share = get_package_share_directory('waypoint_rviz2_plugin') + + rviz_config_file = os.path.join(pkg_share, 'config', 'waypoint_demo.rviz') + + use_rviz_config = os.path.exists(rviz_config_file) + + rviz_node = Node( + package='rviz2', + executable='rviz2', + name='rviz2', + arguments=['-d', rviz_config_file] if use_rviz_config else [], + output='screen' + ) + + return LaunchDescription([ + rviz_node + ]) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/media/axis.dae b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/media/axis.dae new file mode 100644 index 000000000..a2f7b2ddc --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/media/axis.dae @@ -0,0 +1,400 @@ + + + + + Blender User + Blender 3.5.1 commit date:2023-04-24, commit time:18:11, hash:e1ccd9d4a1d3 + + 2023-06-25T21:02:12 + 2023-06-25T21:02:12 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 2880 + 3 + 1 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 2880 + 3 + 1 + 0.1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + + 0 0 0 1 + + + 0 0 1 1 + + + 0.5 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 1 0 0 1 + + + 0.5 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0 1 0 1 + + + 0.5 + + + 1.45 + + + + + + + + + + + + + + + + + + + + + + + 0 1 -1 0 1 1 0.1950903 0.9807853 -1 0.1950903 0.9807853 1 0.3826835 0.9238795 -1 0.3826835 0.9238795 1 0.5555703 0.8314696 -1 0.5555703 0.8314696 1 0.7071068 0.7071068 -1 0.7071068 0.7071068 1 0.8314696 0.5555703 -1 0.8314696 0.5555703 1 0.9238795 0.3826835 -1 0.9238795 0.3826835 1 0.9807853 0.1950903 -1 0.9807853 0.1950903 1 1 0 -1 1 0 1 0.9807853 -0.1950903 -1 0.9807853 -0.1950903 1 0.9238795 -0.3826835 -1 0.9238795 -0.3826835 1 0.8314696 -0.5555703 -1 0.8314696 -0.5555703 1 0.7071068 -0.7071068 -1 0.7071068 -0.7071068 1 0.5555703 -0.8314696 -1 0.5555703 -0.8314696 1 0.3826835 -0.9238795 -1 0.3826835 -0.9238795 1 0.1950903 -0.9807853 -1 0.1950903 -0.9807853 1 0 -1 -1 0 -1 1 -0.1950903 -0.9807853 -1 -0.1950903 -0.9807853 1 -0.3826835 -0.9238795 -1 -0.3826835 -0.9238795 1 -0.5555703 -0.8314696 -1 -0.5555703 -0.8314696 1 -0.7071068 -0.7071068 -1 -0.7071068 -0.7071068 1 -0.8314696 -0.5555703 -1 -0.8314696 -0.5555703 1 -0.9238795 -0.3826835 -1 -0.9238795 -0.3826835 1 -0.9807853 -0.1950903 -1 -0.9807853 -0.1950903 1 -1 0 -1 -1 0 1 -0.9807853 0.1950903 -1 -0.9807853 0.1950903 1 -0.9238795 0.3826835 -1 -0.9238795 0.3826835 1 -0.8314696 0.5555703 -1 -0.8314696 0.5555703 1 -0.7071068 0.7071068 -1 -0.7071068 0.7071068 1 -0.5555703 0.8314696 -1 -0.5555703 0.8314696 1 -0.3826835 0.9238795 -1 -0.3826835 0.9238795 1 -0.1950903 0.9807853 -1 -0.1950903 0.9807853 1 + + + + + + + + + + 0.09801697 0.9951848 0 0.2902848 0.9569403 0 0.4713967 0.8819213 0 0.634393 0.7730107 0 0.7730108 0.634393 0 0.8819212 0.471397 0 0.9569405 0.2902846 0 0.9951848 0.09801727 0 0.9951848 -0.09801667 0 0.9569403 -0.2902851 0 0.8819215 -0.4713965 0 0.7730105 -0.6343934 0 0.6343933 -0.7730104 0 0.4713967 -0.8819213 0 0.2902848 -0.9569404 0 0.09801697 -0.9951848 0 -0.09801697 -0.9951848 0 -0.2902848 -0.9569403 0 -0.4713967 -0.8819213 0 -0.634393 -0.7730107 0 -0.7730108 -0.634393 0 -0.8819212 -0.471397 0 -0.9569405 -0.2902846 0 -0.9951848 -0.09801727 0 -0.9951848 0.09801667 0 -0.9569403 0.2902851 0 -0.8819215 0.4713965 0 -0.7730105 0.6343934 0 -0.6343933 0.7730104 0 -0.4713967 0.8819213 0 0 0 1 -0.2902848 0.9569404 0 -0.09801697 0.9951848 0 0 0 -1 0.2902848 0.9569404 0 0.6343933 0.7730104 0 0.7730105 0.6343934 0 0.8819215 0.4713965 0 0.9569403 0.2902851 0 0.9951848 0.09801667 0 0.9951848 -0.09801727 0 0.9569405 -0.2902846 0 0.8819212 -0.471397 0 0.7730108 -0.634393 0 0.634393 -0.7730107 0 0.2902848 -0.9569403 0 -0.2902848 -0.9569404 0 -0.6343933 -0.7730104 0 -0.7730105 -0.6343934 0 -0.8819215 -0.4713965 0 -0.9569403 -0.2902851 0 -0.9951848 -0.09801667 0 -0.9951848 0.09801727 0 -0.9569405 0.2902846 0 -0.8819212 0.471397 0 -0.7730108 0.634393 0 -0.634393 0.7730107 0 -0.2902848 0.9569403 0 3.97512e-6 0 -1 3.97512e-6 0 -1 -3.97512e-6 0 -1 -3.97512e-6 0 -1 3.88857e-7 0 -1 -3.88857e-7 0 -1 + + + + + + + + + + 1 1 0.96875 0.5 1 0.5 0.96875 1 0.9375 0.5 0.96875 0.5 0.9375 1 0.90625 0.5 0.9375 0.5 0.90625 1 0.8750001 0.5 0.90625 0.5 0.8750001 1 0.84375 0.5 0.8750001 0.5 0.84375 1 0.8125 0.5 0.84375 0.5 0.8125 1 0.78125 0.5 0.8125 0.5 0.78125 1 0.75 0.5 0.78125 0.5 0.75 1 0.71875 0.5 0.75 0.5 0.71875 1 0.6875 0.5 0.71875 0.5 0.6875 1 0.65625 0.5 0.6875 0.5 0.65625 1 0.625 0.5 0.65625 0.5 0.625 1 0.59375 0.5 0.625 0.5 0.59375 1 0.5625 0.5 0.59375 0.5 0.5625 1 0.53125 0.5 0.5625 0.5 0.53125 1 0.5 0.5 0.53125 0.5 0.5 1 0.46875 0.5 0.5 0.5 0.46875 1 0.4375 0.5 0.46875 0.5 0.4375 1 0.40625 0.5 0.4375 0.5 0.40625 1 0.375 0.5 0.40625 0.5 0.375 1 0.34375 0.5 0.375 0.5 0.34375 1 0.3125 0.5 0.34375 0.5 0.3125 1 0.28125 0.5 0.3125 0.5 0.28125 1 0.25 0.5 0.28125 0.5 0.25 1 0.21875 0.5 0.25 0.5 0.21875 1 0.1875 0.5 0.21875 0.5 0.1875 1 0.15625 0.5 0.1875 0.5 0.15625 1 0.125 0.5 0.15625 0.5 0.125 1 0.09375 0.5 0.125 0.5 0.09375 1 0.0625 0.5 0.09375 0.5 0.1581559 0.02826887 0.4717311 0.1581559 0.341844 0.4717311 0.0625 1 0.03125 0.5 0.0625 0.5 0.03125 1 0 0.5 0.03125 0.5 0.7968217 0.01461154 0.5146116 0.2031783 0.7031784 0.4853885 1 1 0.96875 1 0.96875 0.5 0.96875 1 0.9375 1 0.9375 0.5 0.9375 1 0.90625 1 0.90625 0.5 0.90625 1 0.8750001 1 0.8750001 0.5 0.8750001 1 0.84375 1 0.84375 0.5 0.84375 1 0.8125 1 0.8125 0.5 0.8125 1 0.78125 1 0.78125 0.5 0.78125 1 0.75 1 0.75 0.5 0.75 1 0.71875 1 0.71875 0.5 0.71875 1 0.6875 1 0.6875 0.5 0.6875 1 0.65625 1 0.65625 0.5 0.65625 1 0.625 1 0.625 0.5 0.625 1 0.59375 1 0.59375 0.5 0.59375 1 0.5625 1 0.5625 0.5 0.5625 1 0.53125 1 0.53125 0.5 0.53125 1 0.5 1 0.5 0.5 0.5 1 0.46875 1 0.46875 0.5 0.46875 1 0.4375 1 0.4375 0.5 0.4375 1 0.40625 1 0.40625 0.5 0.40625 1 0.375 1 0.375 0.5 0.375 1 0.34375 1 0.34375 0.5 0.34375 1 0.3125 1 0.3125 0.5 0.3125 1 0.28125 1 0.28125 0.5 0.28125 1 0.25 1 0.25 0.5 0.25 1 0.21875 1 0.21875 0.5 0.21875 1 0.1875 1 0.1875 0.5 0.1875 1 0.15625 1 0.15625 0.5 0.15625 1 0.125 1 0.125 0.5 0.125 1 0.09375 1 0.09375 0.5 0.09375 1 0.0625 1 0.0625 0.5 0.341844 0.4717311 0.2968217 0.4853885 0.25 0.49 0.25 0.49 0.2031783 0.4853885 0.341844 0.4717311 0.2031783 0.4853885 0.1581559 0.4717311 0.341844 0.4717311 0.1581559 0.4717311 0.116663 0.4495527 0.08029437 0.4197056 0.08029437 0.4197056 0.05044728 0.3833369 0.02826887 0.341844 0.02826887 0.341844 0.01461154 0.2968217 0.00999999 0.25 0.00999999 0.25 0.01461154 0.2031783 0.02826887 0.341844 0.01461154 0.2031783 0.02826887 0.1581559 0.02826887 0.341844 0.02826887 0.1581559 0.05044728 0.116663 0.08029437 0.08029437 0.08029437 0.08029437 0.116663 0.05044728 0.1581559 0.02826887 0.1581559 0.02826887 0.2031783 0.01461154 0.341844 0.02826887 0.2031783 0.01461154 0.25 0.00999999 0.341844 0.02826887 0.25 0.00999999 0.2968217 0.01461154 0.341844 0.02826887 0.341844 0.02826887 0.3833369 0.05044728 0.4197056 0.08029437 0.4197056 0.08029437 0.4495527 0.116663 0.4717311 0.1581559 0.4717311 0.1581559 0.4853885 0.2031783 0.4717311 0.341844 0.4853885 0.2031783 0.49 0.25 0.4717311 0.341844 0.49 0.25 0.4853885 0.2968217 0.4717311 0.341844 0.4717311 0.341844 0.4495527 0.3833369 0.4197056 0.4197056 0.4197056 0.4197056 0.3833369 0.4495527 0.341844 0.4717311 0.1581559 0.4717311 0.08029437 0.4197056 0.341844 0.4717311 0.08029437 0.4197056 0.02826887 0.341844 0.341844 0.4717311 0.02826887 0.1581559 0.08029437 0.08029437 0.02826887 0.341844 0.08029437 0.08029437 0.1581559 0.02826887 0.02826887 0.341844 0.341844 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.4717311 0.1581559 0.1581559 0.02826887 0.4717311 0.341844 0.4197056 0.4197056 0.4717311 0.1581559 0.4197056 0.4197056 0.341844 0.4717311 0.4717311 0.1581559 0.341844 0.4717311 0.02826887 0.341844 0.1581559 0.02826887 0.0625 1 0.03125 1 0.03125 0.5 0.03125 1 0 1 0 0.5 0.7031784 0.4853885 0.75 0.49 0.7968217 0.4853885 0.7968217 0.4853885 0.841844 0.4717311 0.8833369 0.4495527 0.8833369 0.4495527 0.9197056 0.4197056 0.9495527 0.3833369 0.9495527 0.3833369 0.9717311 0.341844 0.9853885 0.2968217 0.9853885 0.2968217 0.99 0.25 0.9853885 0.2031783 0.9853885 0.2031783 0.9717311 0.1581559 0.9495527 0.116663 0.9495527 0.116663 0.9197056 0.08029437 0.8833369 0.05044728 0.8833369 0.05044728 0.841844 0.02826887 0.7968217 0.01461154 0.7968217 0.01461154 0.75 0.00999999 0.7031784 0.01461154 0.7031784 0.01461154 0.658156 0.02826887 0.6166632 0.05044728 0.6166632 0.05044728 0.5802944 0.08029437 0.5504473 0.116663 0.5504473 0.116663 0.5282689 0.1581559 0.5146116 0.2031783 0.5146116 0.2031783 0.51 0.25 0.5146116 0.2968217 0.5146116 0.2968217 0.5282689 0.341844 0.5504473 0.3833369 0.5504473 0.3833369 0.5802944 0.4197056 0.6166632 0.4495527 0.6166632 0.4495527 0.658156 0.4717311 0.7031784 0.4853885 0.7031784 0.4853885 0.7968217 0.4853885 0.9853885 0.2968217 0.7968217 0.4853885 0.8833369 0.4495527 0.9853885 0.2968217 0.8833369 0.4495527 0.9495527 0.3833369 0.9853885 0.2968217 0.9853885 0.2968217 0.9853885 0.2031783 0.7968217 0.01461154 0.9853885 0.2031783 0.9495527 0.116663 0.7968217 0.01461154 0.9495527 0.116663 0.8833369 0.05044728 0.7968217 0.01461154 0.7968217 0.01461154 0.7031784 0.01461154 0.5146116 0.2031783 0.7031784 0.01461154 0.6166632 0.05044728 0.5146116 0.2031783 0.6166632 0.05044728 0.5504473 0.116663 0.5146116 0.2031783 0.5146116 0.2031783 0.5146116 0.2968217 0.7031784 0.4853885 0.5146116 0.2968217 0.5504473 0.3833369 0.7031784 0.4853885 0.5504473 0.3833369 0.6166632 0.4495527 0.7031784 0.4853885 0.7031784 0.4853885 0.9853885 0.2968217 0.7968217 0.01461154 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 37 30 90 21 30 91 5 30 92 61 31 93 62 31 94 60 31 95 63 32 96 0 32 97 62 32 98 30 33 99 46 33 100 62 33 101 1 0 102 3 0 103 2 0 104 3 34 105 5 34 106 4 34 107 5 2 108 7 2 109 6 2 110 7 35 111 9 35 112 8 35 113 9 36 114 11 36 115 10 36 116 11 37 117 13 37 118 12 37 119 13 38 120 15 38 121 14 38 122 15 39 123 17 39 124 16 39 125 17 40 126 19 40 127 18 40 128 19 41 129 21 41 130 20 41 131 21 42 132 23 42 133 22 42 134 23 43 135 25 43 136 24 43 137 25 44 138 27 44 139 26 44 140 27 13 141 29 13 142 28 13 143 29 45 144 31 45 145 30 45 146 31 15 147 33 15 148 32 15 149 33 16 150 35 16 151 34 16 152 35 46 153 37 46 154 36 46 155 37 18 156 39 18 157 38 18 158 39 47 159 41 47 160 40 47 161 41 48 162 43 48 163 42 48 164 43 49 165 45 49 166 44 49 167 45 50 168 47 50 169 46 50 170 47 51 171 49 51 172 48 51 173 49 52 174 51 52 175 50 52 176 51 53 177 53 53 178 52 53 179 53 54 180 55 54 181 54 54 182 55 55 183 57 55 184 56 55 185 57 56 186 59 56 187 58 56 188 59 29 189 61 29 190 60 29 191 5 30 192 3 30 193 1 30 194 1 30 195 63 30 196 5 30 197 63 30 198 61 30 199 5 30 200 61 30 201 59 30 202 57 30 203 57 30 204 55 30 205 53 30 206 53 30 207 51 30 208 49 30 209 49 30 210 47 30 211 53 30 212 47 30 213 45 30 214 53 30 215 45 30 216 43 30 217 41 30 218 41 30 219 39 30 220 37 30 221 37 30 222 35 30 223 29 30 224 35 30 225 33 30 226 29 30 227 33 30 228 31 30 229 29 30 230 29 30 231 27 30 232 25 30 233 25 30 234 23 30 235 21 30 236 21 30 237 19 30 238 13 30 239 19 30 240 17 30 241 13 30 242 17 30 243 15 30 244 13 30 245 13 30 246 11 30 247 9 30 248 9 30 249 7 30 250 5 30 251 61 30 252 57 30 253 5 30 254 57 30 255 53 30 256 5 30 257 45 30 258 41 30 259 53 30 260 41 30 261 37 30 262 53 30 263 29 30 264 25 30 265 37 30 266 25 30 267 21 30 268 37 30 269 13 30 270 9 30 271 21 30 272 9 30 273 5 30 274 21 30 275 5 30 276 53 30 277 37 30 278 61 57 279 63 57 280 62 57 281 63 32 282 1 32 283 0 32 284 62 33 285 0 33 286 2 33 287 2 33 288 4 33 289 6 33 290 6 33 291 8 33 292 10 33 293 10 58 294 12 58 295 14 58 296 14 33 297 16 33 298 18 33 299 18 59 300 20 59 301 22 59 302 22 33 303 24 33 304 26 33 305 26 33 306 28 33 307 30 33 308 30 33 309 32 33 310 34 33 311 34 33 312 36 33 313 38 33 314 38 33 315 40 33 316 42 33 317 42 60 318 44 60 319 46 60 320 46 33 321 48 33 322 50 33 323 50 61 324 52 61 325 54 61 326 54 33 327 56 33 328 58 33 329 58 33 330 60 33 331 62 33 332 62 33 333 2 33 334 14 33 335 2 33 336 6 33 337 14 33 338 6 33 339 10 33 340 14 33 341 14 62 342 18 62 343 30 62 344 18 33 345 22 33 346 30 33 347 22 33 348 26 33 349 30 33 350 30 33 351 34 33 352 46 33 353 34 33 354 38 33 355 46 33 356 38 33 357 42 33 358 46 33 359 46 63 360 50 63 361 62 63 362 50 33 363 54 33 364 62 33 365 54 33 366 58 33 367 62 33 368 62 33 369 14 33 370 30 33 371

+ + + + + + + 0 1 -1 0 1 1 0.1950903 0.9807853 -1 0.1950903 0.9807853 1 0.3826835 0.9238795 -1 0.3826835 0.9238795 1 0.5555703 0.8314696 -1 0.5555703 0.8314696 1 0.7071068 0.7071068 -1 0.7071068 0.7071068 1 0.8314696 0.5555703 -1 0.8314696 0.5555703 1 0.9238795 0.3826835 -1 0.9238795 0.3826835 1 0.9807853 0.1950903 -1 0.9807853 0.1950903 1 1 0 -1 1 0 1 0.9807853 -0.1950903 -1 0.9807853 -0.1950903 1 0.9238795 -0.3826835 -1 0.9238795 -0.3826835 1 0.8314696 -0.5555703 -1 0.8314696 -0.5555703 1 0.7071068 -0.7071068 -1 0.7071068 -0.7071068 1 0.5555703 -0.8314696 -1 0.5555703 -0.8314696 1 0.3826835 -0.9238795 -1 0.3826835 -0.9238795 1 0.1950903 -0.9807853 -1 0.1950903 -0.9807853 1 0 -1 -1 0 -1 1 -0.1950903 -0.9807853 -1 -0.1950903 -0.9807853 1 -0.3826835 -0.9238795 -1 -0.3826835 -0.9238795 1 -0.5555703 -0.8314696 -1 -0.5555703 -0.8314696 1 -0.7071068 -0.7071068 -1 -0.7071068 -0.7071068 1 -0.8314696 -0.5555703 -1 -0.8314696 -0.5555703 1 -0.9238795 -0.3826835 -1 -0.9238795 -0.3826835 1 -0.9807853 -0.1950903 -1 -0.9807853 -0.1950903 1 -1 0 -1 -1 0 1 -0.9807853 0.1950903 -1 -0.9807853 0.1950903 1 -0.9238795 0.3826835 -1 -0.9238795 0.3826835 1 -0.8314696 0.5555703 -1 -0.8314696 0.5555703 1 -0.7071068 0.7071068 -1 -0.7071068 0.7071068 1 -0.5555703 0.8314696 -1 -0.5555703 0.8314696 1 -0.3826835 0.9238795 -1 -0.3826835 0.9238795 1 -0.1950903 0.9807853 -1 -0.1950903 0.9807853 1 + + + + + + + + + + 0.09801697 0.9951848 0 0.2902848 0.9569403 0 0.4713967 0.8819213 0 0.634393 0.7730107 0 0.7730108 0.634393 0 0.8819212 0.471397 0 0.9569405 0.2902846 0 0.9951848 0.09801727 0 0.9951848 -0.09801667 0 0.9569403 -0.2902851 0 0.8819215 -0.4713965 0 0.7730105 -0.6343934 0 0.6343933 -0.7730104 0 0.4713967 -0.8819213 0 0.2902848 -0.9569404 0 0.09801697 -0.9951848 0 -0.09801697 -0.9951848 0 -0.2902848 -0.9569403 0 -0.4713967 -0.8819213 0 -0.634393 -0.7730107 0 -0.7730108 -0.634393 0 -0.8819212 -0.471397 0 -0.9569405 -0.2902846 0 -0.9951848 -0.09801727 0 -0.9951848 0.09801667 0 -0.9569403 0.2902851 0 -0.8819215 0.4713965 0 -0.7730105 0.6343934 0 -0.6343933 0.7730104 0 -0.4713967 0.8819213 0 0 0 1 -0.2902848 0.9569404 0 -0.09801697 0.9951848 0 0 0 -1 0.2902848 0.9569404 0 0.6343933 0.7730104 0 0.7730105 0.6343934 0 0.8819215 0.4713965 0 0.9569403 0.2902851 0 0.9951848 0.09801667 0 0.9951848 -0.09801727 0 0.9569405 -0.2902846 0 0.8819212 -0.471397 0 0.7730108 -0.634393 0 0.634393 -0.7730107 0 0.2902848 -0.9569403 0 -0.2902848 -0.9569404 0 -0.6343933 -0.7730104 0 -0.7730105 -0.6343934 0 -0.8819215 -0.4713965 0 -0.9569403 -0.2902851 0 -0.9951848 -0.09801667 0 -0.9951848 0.09801727 0 -0.9569405 0.2902846 0 -0.8819212 0.471397 0 -0.7730108 0.634393 0 -0.634393 0.7730107 0 -0.2902848 0.9569403 0 3.97512e-6 0 -1 3.97512e-6 0 -1 -3.97512e-6 0 -1 -3.97512e-6 0 -1 3.88857e-7 0 -1 -3.88857e-7 0 -1 + + + + + + + + + + 1 1 0.96875 0.5 1 0.5 0.96875 1 0.9375 0.5 0.96875 0.5 0.9375 1 0.90625 0.5 0.9375 0.5 0.90625 1 0.8750001 0.5 0.90625 0.5 0.8750001 1 0.84375 0.5 0.8750001 0.5 0.84375 1 0.8125 0.5 0.84375 0.5 0.8125 1 0.78125 0.5 0.8125 0.5 0.78125 1 0.75 0.5 0.78125 0.5 0.75 1 0.71875 0.5 0.75 0.5 0.71875 1 0.6875 0.5 0.71875 0.5 0.6875 1 0.65625 0.5 0.6875 0.5 0.65625 1 0.625 0.5 0.65625 0.5 0.625 1 0.59375 0.5 0.625 0.5 0.59375 1 0.5625 0.5 0.59375 0.5 0.5625 1 0.53125 0.5 0.5625 0.5 0.53125 1 0.5 0.5 0.53125 0.5 0.5 1 0.46875 0.5 0.5 0.5 0.46875 1 0.4375 0.5 0.46875 0.5 0.4375 1 0.40625 0.5 0.4375 0.5 0.40625 1 0.375 0.5 0.40625 0.5 0.375 1 0.34375 0.5 0.375 0.5 0.34375 1 0.3125 0.5 0.34375 0.5 0.3125 1 0.28125 0.5 0.3125 0.5 0.28125 1 0.25 0.5 0.28125 0.5 0.25 1 0.21875 0.5 0.25 0.5 0.21875 1 0.1875 0.5 0.21875 0.5 0.1875 1 0.15625 0.5 0.1875 0.5 0.15625 1 0.125 0.5 0.15625 0.5 0.125 1 0.09375 0.5 0.125 0.5 0.09375 1 0.0625 0.5 0.09375 0.5 0.1581559 0.02826887 0.4717311 0.1581559 0.341844 0.4717311 0.0625 1 0.03125 0.5 0.0625 0.5 0.03125 1 0 0.5 0.03125 0.5 0.7968217 0.01461154 0.5146116 0.2031783 0.7031784 0.4853885 1 1 0.96875 1 0.96875 0.5 0.96875 1 0.9375 1 0.9375 0.5 0.9375 1 0.90625 1 0.90625 0.5 0.90625 1 0.8750001 1 0.8750001 0.5 0.8750001 1 0.84375 1 0.84375 0.5 0.84375 1 0.8125 1 0.8125 0.5 0.8125 1 0.78125 1 0.78125 0.5 0.78125 1 0.75 1 0.75 0.5 0.75 1 0.71875 1 0.71875 0.5 0.71875 1 0.6875 1 0.6875 0.5 0.6875 1 0.65625 1 0.65625 0.5 0.65625 1 0.625 1 0.625 0.5 0.625 1 0.59375 1 0.59375 0.5 0.59375 1 0.5625 1 0.5625 0.5 0.5625 1 0.53125 1 0.53125 0.5 0.53125 1 0.5 1 0.5 0.5 0.5 1 0.46875 1 0.46875 0.5 0.46875 1 0.4375 1 0.4375 0.5 0.4375 1 0.40625 1 0.40625 0.5 0.40625 1 0.375 1 0.375 0.5 0.375 1 0.34375 1 0.34375 0.5 0.34375 1 0.3125 1 0.3125 0.5 0.3125 1 0.28125 1 0.28125 0.5 0.28125 1 0.25 1 0.25 0.5 0.25 1 0.21875 1 0.21875 0.5 0.21875 1 0.1875 1 0.1875 0.5 0.1875 1 0.15625 1 0.15625 0.5 0.15625 1 0.125 1 0.125 0.5 0.125 1 0.09375 1 0.09375 0.5 0.09375 1 0.0625 1 0.0625 0.5 0.341844 0.4717311 0.2968217 0.4853885 0.25 0.49 0.25 0.49 0.2031783 0.4853885 0.341844 0.4717311 0.2031783 0.4853885 0.1581559 0.4717311 0.341844 0.4717311 0.1581559 0.4717311 0.116663 0.4495527 0.08029437 0.4197056 0.08029437 0.4197056 0.05044728 0.3833369 0.02826887 0.341844 0.02826887 0.341844 0.01461154 0.2968217 0.00999999 0.25 0.00999999 0.25 0.01461154 0.2031783 0.02826887 0.341844 0.01461154 0.2031783 0.02826887 0.1581559 0.02826887 0.341844 0.02826887 0.1581559 0.05044728 0.116663 0.08029437 0.08029437 0.08029437 0.08029437 0.116663 0.05044728 0.1581559 0.02826887 0.1581559 0.02826887 0.2031783 0.01461154 0.341844 0.02826887 0.2031783 0.01461154 0.25 0.00999999 0.341844 0.02826887 0.25 0.00999999 0.2968217 0.01461154 0.341844 0.02826887 0.341844 0.02826887 0.3833369 0.05044728 0.4197056 0.08029437 0.4197056 0.08029437 0.4495527 0.116663 0.4717311 0.1581559 0.4717311 0.1581559 0.4853885 0.2031783 0.4717311 0.341844 0.4853885 0.2031783 0.49 0.25 0.4717311 0.341844 0.49 0.25 0.4853885 0.2968217 0.4717311 0.341844 0.4717311 0.341844 0.4495527 0.3833369 0.4197056 0.4197056 0.4197056 0.4197056 0.3833369 0.4495527 0.341844 0.4717311 0.1581559 0.4717311 0.08029437 0.4197056 0.341844 0.4717311 0.08029437 0.4197056 0.02826887 0.341844 0.341844 0.4717311 0.02826887 0.1581559 0.08029437 0.08029437 0.02826887 0.341844 0.08029437 0.08029437 0.1581559 0.02826887 0.02826887 0.341844 0.341844 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.4717311 0.1581559 0.1581559 0.02826887 0.4717311 0.341844 0.4197056 0.4197056 0.4717311 0.1581559 0.4197056 0.4197056 0.341844 0.4717311 0.4717311 0.1581559 0.341844 0.4717311 0.02826887 0.341844 0.1581559 0.02826887 0.0625 1 0.03125 1 0.03125 0.5 0.03125 1 0 1 0 0.5 0.7031784 0.4853885 0.75 0.49 0.7968217 0.4853885 0.7968217 0.4853885 0.841844 0.4717311 0.8833369 0.4495527 0.8833369 0.4495527 0.9197056 0.4197056 0.9495527 0.3833369 0.9495527 0.3833369 0.9717311 0.341844 0.9853885 0.2968217 0.9853885 0.2968217 0.99 0.25 0.9853885 0.2031783 0.9853885 0.2031783 0.9717311 0.1581559 0.9495527 0.116663 0.9495527 0.116663 0.9197056 0.08029437 0.8833369 0.05044728 0.8833369 0.05044728 0.841844 0.02826887 0.7968217 0.01461154 0.7968217 0.01461154 0.75 0.00999999 0.7031784 0.01461154 0.7031784 0.01461154 0.658156 0.02826887 0.6166632 0.05044728 0.6166632 0.05044728 0.5802944 0.08029437 0.5504473 0.116663 0.5504473 0.116663 0.5282689 0.1581559 0.5146116 0.2031783 0.5146116 0.2031783 0.51 0.25 0.5146116 0.2968217 0.5146116 0.2968217 0.5282689 0.341844 0.5504473 0.3833369 0.5504473 0.3833369 0.5802944 0.4197056 0.6166632 0.4495527 0.6166632 0.4495527 0.658156 0.4717311 0.7031784 0.4853885 0.7031784 0.4853885 0.7968217 0.4853885 0.9853885 0.2968217 0.7968217 0.4853885 0.8833369 0.4495527 0.9853885 0.2968217 0.8833369 0.4495527 0.9495527 0.3833369 0.9853885 0.2968217 0.9853885 0.2968217 0.9853885 0.2031783 0.7968217 0.01461154 0.9853885 0.2031783 0.9495527 0.116663 0.7968217 0.01461154 0.9495527 0.116663 0.8833369 0.05044728 0.7968217 0.01461154 0.7968217 0.01461154 0.7031784 0.01461154 0.5146116 0.2031783 0.7031784 0.01461154 0.6166632 0.05044728 0.5146116 0.2031783 0.6166632 0.05044728 0.5504473 0.116663 0.5146116 0.2031783 0.5146116 0.2031783 0.5146116 0.2968217 0.7031784 0.4853885 0.5146116 0.2968217 0.5504473 0.3833369 0.7031784 0.4853885 0.5504473 0.3833369 0.6166632 0.4495527 0.7031784 0.4853885 0.7031784 0.4853885 0.9853885 0.2968217 0.7968217 0.01461154 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 37 30 90 21 30 91 5 30 92 61 31 93 62 31 94 60 31 95 63 32 96 0 32 97 62 32 98 30 33 99 46 33 100 62 33 101 1 0 102 3 0 103 2 0 104 3 34 105 5 34 106 4 34 107 5 2 108 7 2 109 6 2 110 7 35 111 9 35 112 8 35 113 9 36 114 11 36 115 10 36 116 11 37 117 13 37 118 12 37 119 13 38 120 15 38 121 14 38 122 15 39 123 17 39 124 16 39 125 17 40 126 19 40 127 18 40 128 19 41 129 21 41 130 20 41 131 21 42 132 23 42 133 22 42 134 23 43 135 25 43 136 24 43 137 25 44 138 27 44 139 26 44 140 27 13 141 29 13 142 28 13 143 29 45 144 31 45 145 30 45 146 31 15 147 33 15 148 32 15 149 33 16 150 35 16 151 34 16 152 35 46 153 37 46 154 36 46 155 37 18 156 39 18 157 38 18 158 39 47 159 41 47 160 40 47 161 41 48 162 43 48 163 42 48 164 43 49 165 45 49 166 44 49 167 45 50 168 47 50 169 46 50 170 47 51 171 49 51 172 48 51 173 49 52 174 51 52 175 50 52 176 51 53 177 53 53 178 52 53 179 53 54 180 55 54 181 54 54 182 55 55 183 57 55 184 56 55 185 57 56 186 59 56 187 58 56 188 59 29 189 61 29 190 60 29 191 5 30 192 3 30 193 1 30 194 1 30 195 63 30 196 5 30 197 63 30 198 61 30 199 5 30 200 61 30 201 59 30 202 57 30 203 57 30 204 55 30 205 53 30 206 53 30 207 51 30 208 49 30 209 49 30 210 47 30 211 53 30 212 47 30 213 45 30 214 53 30 215 45 30 216 43 30 217 41 30 218 41 30 219 39 30 220 37 30 221 37 30 222 35 30 223 29 30 224 35 30 225 33 30 226 29 30 227 33 30 228 31 30 229 29 30 230 29 30 231 27 30 232 25 30 233 25 30 234 23 30 235 21 30 236 21 30 237 19 30 238 13 30 239 19 30 240 17 30 241 13 30 242 17 30 243 15 30 244 13 30 245 13 30 246 11 30 247 9 30 248 9 30 249 7 30 250 5 30 251 61 30 252 57 30 253 5 30 254 57 30 255 53 30 256 5 30 257 45 30 258 41 30 259 53 30 260 41 30 261 37 30 262 53 30 263 29 30 264 25 30 265 37 30 266 25 30 267 21 30 268 37 30 269 13 30 270 9 30 271 21 30 272 9 30 273 5 30 274 21 30 275 5 30 276 53 30 277 37 30 278 61 57 279 63 57 280 62 57 281 63 32 282 1 32 283 0 32 284 62 33 285 0 33 286 2 33 287 2 33 288 4 33 289 6 33 290 6 33 291 8 33 292 10 33 293 10 58 294 12 58 295 14 58 296 14 33 297 16 33 298 18 33 299 18 59 300 20 59 301 22 59 302 22 33 303 24 33 304 26 33 305 26 33 306 28 33 307 30 33 308 30 33 309 32 33 310 34 33 311 34 33 312 36 33 313 38 33 314 38 33 315 40 33 316 42 33 317 42 60 318 44 60 319 46 60 320 46 33 321 48 33 322 50 33 323 50 61 324 52 61 325 54 61 326 54 33 327 56 33 328 58 33 329 58 33 330 60 33 331 62 33 332 62 33 333 2 33 334 14 33 335 2 33 336 6 33 337 14 33 338 6 33 339 10 33 340 14 33 341 14 62 342 18 62 343 30 62 344 18 33 345 22 33 346 30 33 347 22 33 348 26 33 349 30 33 350 30 33 351 34 33 352 46 33 353 34 33 354 38 33 355 46 33 356 38 33 357 42 33 358 46 33 359 46 63 360 50 63 361 62 63 362 50 33 363 54 33 364 62 33 365 54 33 366 58 33 367 62 33 368 62 33 369 14 33 370 30 33 371

+
+
+
+ + + + 0 1 -1 0 1 1 0.1950903 0.9807853 -1 0.1950903 0.9807853 1 0.3826835 0.9238795 -1 0.3826835 0.9238795 1 0.5555703 0.8314696 -1 0.5555703 0.8314696 1 0.7071068 0.7071068 -1 0.7071068 0.7071068 1 0.8314696 0.5555703 -1 0.8314696 0.5555703 1 0.9238795 0.3826835 -1 0.9238795 0.3826835 1 0.9807853 0.1950903 -1 0.9807853 0.1950903 1 1 0 -1 1 0 1 0.9807853 -0.1950903 -1 0.9807853 -0.1950903 1 0.9238795 -0.3826835 -1 0.9238795 -0.3826835 1 0.8314696 -0.5555703 -1 0.8314696 -0.5555703 1 0.7071068 -0.7071068 -1 0.7071068 -0.7071068 1 0.5555703 -0.8314696 -1 0.5555703 -0.8314696 1 0.3826835 -0.9238795 -1 0.3826835 -0.9238795 1 0.1950903 -0.9807853 -1 0.1950903 -0.9807853 1 0 -1 -1 0 -1 1 -0.1950903 -0.9807853 -1 -0.1950903 -0.9807853 1 -0.3826835 -0.9238795 -1 -0.3826835 -0.9238795 1 -0.5555703 -0.8314696 -1 -0.5555703 -0.8314696 1 -0.7071068 -0.7071068 -1 -0.7071068 -0.7071068 1 -0.8314696 -0.5555703 -1 -0.8314696 -0.5555703 1 -0.9238795 -0.3826835 -1 -0.9238795 -0.3826835 1 -0.9807853 -0.1950903 -1 -0.9807853 -0.1950903 1 -1 0 -1 -1 0 1 -0.9807853 0.1950903 -1 -0.9807853 0.1950903 1 -0.9238795 0.3826835 -1 -0.9238795 0.3826835 1 -0.8314696 0.5555703 -1 -0.8314696 0.5555703 1 -0.7071068 0.7071068 -1 -0.7071068 0.7071068 1 -0.5555703 0.8314696 -1 -0.5555703 0.8314696 1 -0.3826835 0.9238795 -1 -0.3826835 0.9238795 1 -0.1950903 0.9807853 -1 -0.1950903 0.9807853 1 + + + + + + + + + + 0.09801697 0.9951848 0 0.2902848 0.9569403 0 0.4713967 0.8819213 0 0.634393 0.7730107 0 0.7730108 0.634393 0 0.8819212 0.471397 0 0.9569405 0.2902846 0 0.9951848 0.09801727 0 0.9951848 -0.09801667 0 0.9569403 -0.2902851 0 0.8819215 -0.4713965 0 0.7730105 -0.6343934 0 0.6343933 -0.7730104 0 0.4713967 -0.8819213 0 0.2902848 -0.9569404 0 0.09801697 -0.9951848 0 -0.09801697 -0.9951848 0 -0.2902848 -0.9569403 0 -0.4713967 -0.8819213 0 -0.634393 -0.7730107 0 -0.7730108 -0.634393 0 -0.8819212 -0.471397 0 -0.9569405 -0.2902846 0 -0.9951848 -0.09801727 0 -0.9951848 0.09801667 0 -0.9569403 0.2902851 0 -0.8819215 0.4713965 0 -0.7730105 0.6343934 0 -0.6343933 0.7730104 0 -0.4713967 0.8819213 0 0 0 1 -0.2902848 0.9569404 0 -0.09801697 0.9951848 0 0 0 -1 0.2902848 0.9569404 0 0.6343933 0.7730104 0 0.7730105 0.6343934 0 0.8819215 0.4713965 0 0.9569403 0.2902851 0 0.9951848 0.09801667 0 0.9951848 -0.09801727 0 0.9569405 -0.2902846 0 0.8819212 -0.471397 0 0.7730108 -0.634393 0 0.634393 -0.7730107 0 0.2902848 -0.9569403 0 -0.2902848 -0.9569404 0 -0.6343933 -0.7730104 0 -0.7730105 -0.6343934 0 -0.8819215 -0.4713965 0 -0.9569403 -0.2902851 0 -0.9951848 -0.09801667 0 -0.9951848 0.09801727 0 -0.9569405 0.2902846 0 -0.8819212 0.471397 0 -0.7730108 0.634393 0 -0.634393 0.7730107 0 -0.2902848 0.9569403 0 3.97512e-6 0 -1 3.97512e-6 0 -1 -3.97512e-6 0 -1 -3.97512e-6 0 -1 3.88857e-7 0 -1 -3.88857e-7 0 -1 + + + + + + + + + + 1 1 0.96875 0.5 1 0.5 0.96875 1 0.9375 0.5 0.96875 0.5 0.9375 1 0.90625 0.5 0.9375 0.5 0.90625 1 0.8750001 0.5 0.90625 0.5 0.8750001 1 0.84375 0.5 0.8750001 0.5 0.84375 1 0.8125 0.5 0.84375 0.5 0.8125 1 0.78125 0.5 0.8125 0.5 0.78125 1 0.75 0.5 0.78125 0.5 0.75 1 0.71875 0.5 0.75 0.5 0.71875 1 0.6875 0.5 0.71875 0.5 0.6875 1 0.65625 0.5 0.6875 0.5 0.65625 1 0.625 0.5 0.65625 0.5 0.625 1 0.59375 0.5 0.625 0.5 0.59375 1 0.5625 0.5 0.59375 0.5 0.5625 1 0.53125 0.5 0.5625 0.5 0.53125 1 0.5 0.5 0.53125 0.5 0.5 1 0.46875 0.5 0.5 0.5 0.46875 1 0.4375 0.5 0.46875 0.5 0.4375 1 0.40625 0.5 0.4375 0.5 0.40625 1 0.375 0.5 0.40625 0.5 0.375 1 0.34375 0.5 0.375 0.5 0.34375 1 0.3125 0.5 0.34375 0.5 0.3125 1 0.28125 0.5 0.3125 0.5 0.28125 1 0.25 0.5 0.28125 0.5 0.25 1 0.21875 0.5 0.25 0.5 0.21875 1 0.1875 0.5 0.21875 0.5 0.1875 1 0.15625 0.5 0.1875 0.5 0.15625 1 0.125 0.5 0.15625 0.5 0.125 1 0.09375 0.5 0.125 0.5 0.09375 1 0.0625 0.5 0.09375 0.5 0.1581559 0.02826887 0.4717311 0.1581559 0.341844 0.4717311 0.0625 1 0.03125 0.5 0.0625 0.5 0.03125 1 0 0.5 0.03125 0.5 0.7968217 0.01461154 0.5146116 0.2031783 0.7031784 0.4853885 1 1 0.96875 1 0.96875 0.5 0.96875 1 0.9375 1 0.9375 0.5 0.9375 1 0.90625 1 0.90625 0.5 0.90625 1 0.8750001 1 0.8750001 0.5 0.8750001 1 0.84375 1 0.84375 0.5 0.84375 1 0.8125 1 0.8125 0.5 0.8125 1 0.78125 1 0.78125 0.5 0.78125 1 0.75 1 0.75 0.5 0.75 1 0.71875 1 0.71875 0.5 0.71875 1 0.6875 1 0.6875 0.5 0.6875 1 0.65625 1 0.65625 0.5 0.65625 1 0.625 1 0.625 0.5 0.625 1 0.59375 1 0.59375 0.5 0.59375 1 0.5625 1 0.5625 0.5 0.5625 1 0.53125 1 0.53125 0.5 0.53125 1 0.5 1 0.5 0.5 0.5 1 0.46875 1 0.46875 0.5 0.46875 1 0.4375 1 0.4375 0.5 0.4375 1 0.40625 1 0.40625 0.5 0.40625 1 0.375 1 0.375 0.5 0.375 1 0.34375 1 0.34375 0.5 0.34375 1 0.3125 1 0.3125 0.5 0.3125 1 0.28125 1 0.28125 0.5 0.28125 1 0.25 1 0.25 0.5 0.25 1 0.21875 1 0.21875 0.5 0.21875 1 0.1875 1 0.1875 0.5 0.1875 1 0.15625 1 0.15625 0.5 0.15625 1 0.125 1 0.125 0.5 0.125 1 0.09375 1 0.09375 0.5 0.09375 1 0.0625 1 0.0625 0.5 0.341844 0.4717311 0.2968217 0.4853885 0.25 0.49 0.25 0.49 0.2031783 0.4853885 0.341844 0.4717311 0.2031783 0.4853885 0.1581559 0.4717311 0.341844 0.4717311 0.1581559 0.4717311 0.116663 0.4495527 0.08029437 0.4197056 0.08029437 0.4197056 0.05044728 0.3833369 0.02826887 0.341844 0.02826887 0.341844 0.01461154 0.2968217 0.00999999 0.25 0.00999999 0.25 0.01461154 0.2031783 0.02826887 0.341844 0.01461154 0.2031783 0.02826887 0.1581559 0.02826887 0.341844 0.02826887 0.1581559 0.05044728 0.116663 0.08029437 0.08029437 0.08029437 0.08029437 0.116663 0.05044728 0.1581559 0.02826887 0.1581559 0.02826887 0.2031783 0.01461154 0.341844 0.02826887 0.2031783 0.01461154 0.25 0.00999999 0.341844 0.02826887 0.25 0.00999999 0.2968217 0.01461154 0.341844 0.02826887 0.341844 0.02826887 0.3833369 0.05044728 0.4197056 0.08029437 0.4197056 0.08029437 0.4495527 0.116663 0.4717311 0.1581559 0.4717311 0.1581559 0.4853885 0.2031783 0.4717311 0.341844 0.4853885 0.2031783 0.49 0.25 0.4717311 0.341844 0.49 0.25 0.4853885 0.2968217 0.4717311 0.341844 0.4717311 0.341844 0.4495527 0.3833369 0.4197056 0.4197056 0.4197056 0.4197056 0.3833369 0.4495527 0.341844 0.4717311 0.1581559 0.4717311 0.08029437 0.4197056 0.341844 0.4717311 0.08029437 0.4197056 0.02826887 0.341844 0.341844 0.4717311 0.02826887 0.1581559 0.08029437 0.08029437 0.02826887 0.341844 0.08029437 0.08029437 0.1581559 0.02826887 0.02826887 0.341844 0.341844 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.4717311 0.1581559 0.1581559 0.02826887 0.4717311 0.341844 0.4197056 0.4197056 0.4717311 0.1581559 0.4197056 0.4197056 0.341844 0.4717311 0.4717311 0.1581559 0.341844 0.4717311 0.02826887 0.341844 0.1581559 0.02826887 0.0625 1 0.03125 1 0.03125 0.5 0.03125 1 0 1 0 0.5 0.7031784 0.4853885 0.75 0.49 0.7968217 0.4853885 0.7968217 0.4853885 0.841844 0.4717311 0.8833369 0.4495527 0.8833369 0.4495527 0.9197056 0.4197056 0.9495527 0.3833369 0.9495527 0.3833369 0.9717311 0.341844 0.9853885 0.2968217 0.9853885 0.2968217 0.99 0.25 0.9853885 0.2031783 0.9853885 0.2031783 0.9717311 0.1581559 0.9495527 0.116663 0.9495527 0.116663 0.9197056 0.08029437 0.8833369 0.05044728 0.8833369 0.05044728 0.841844 0.02826887 0.7968217 0.01461154 0.7968217 0.01461154 0.75 0.00999999 0.7031784 0.01461154 0.7031784 0.01461154 0.658156 0.02826887 0.6166632 0.05044728 0.6166632 0.05044728 0.5802944 0.08029437 0.5504473 0.116663 0.5504473 0.116663 0.5282689 0.1581559 0.5146116 0.2031783 0.5146116 0.2031783 0.51 0.25 0.5146116 0.2968217 0.5146116 0.2968217 0.5282689 0.341844 0.5504473 0.3833369 0.5504473 0.3833369 0.5802944 0.4197056 0.6166632 0.4495527 0.6166632 0.4495527 0.658156 0.4717311 0.7031784 0.4853885 0.7031784 0.4853885 0.7968217 0.4853885 0.9853885 0.2968217 0.7968217 0.4853885 0.8833369 0.4495527 0.9853885 0.2968217 0.8833369 0.4495527 0.9495527 0.3833369 0.9853885 0.2968217 0.9853885 0.2968217 0.9853885 0.2031783 0.7968217 0.01461154 0.9853885 0.2031783 0.9495527 0.116663 0.7968217 0.01461154 0.9495527 0.116663 0.8833369 0.05044728 0.7968217 0.01461154 0.7968217 0.01461154 0.7031784 0.01461154 0.5146116 0.2031783 0.7031784 0.01461154 0.6166632 0.05044728 0.5146116 0.2031783 0.6166632 0.05044728 0.5504473 0.116663 0.5146116 0.2031783 0.5146116 0.2031783 0.5146116 0.2968217 0.7031784 0.4853885 0.5146116 0.2968217 0.5504473 0.3833369 0.7031784 0.4853885 0.5504473 0.3833369 0.6166632 0.4495527 0.7031784 0.4853885 0.7031784 0.4853885 0.9853885 0.2968217 0.7968217 0.01461154 + + + + + + + + + + + + + + +

1 0 0 2 0 1 0 0 2 3 1 3 4 1 4 2 1 5 5 2 6 6 2 7 4 2 8 7 3 9 8 3 10 6 3 11 9 4 12 10 4 13 8 4 14 11 5 15 12 5 16 10 5 17 13 6 18 14 6 19 12 6 20 15 7 21 16 7 22 14 7 23 17 8 24 18 8 25 16 8 26 19 9 27 20 9 28 18 9 29 21 10 30 22 10 31 20 10 32 23 11 33 24 11 34 22 11 35 25 12 36 26 12 37 24 12 38 27 13 39 28 13 40 26 13 41 29 14 42 30 14 43 28 14 44 31 15 45 32 15 46 30 15 47 33 16 48 34 16 49 32 16 50 35 17 51 36 17 52 34 17 53 37 18 54 38 18 55 36 18 56 39 19 57 40 19 58 38 19 59 41 20 60 42 20 61 40 20 62 43 21 63 44 21 64 42 21 65 45 22 66 46 22 67 44 22 68 47 23 69 48 23 70 46 23 71 49 24 72 50 24 73 48 24 74 51 25 75 52 25 76 50 25 77 53 26 78 54 26 79 52 26 80 55 27 81 56 27 82 54 27 83 57 28 84 58 28 85 56 28 86 59 29 87 60 29 88 58 29 89 37 30 90 21 30 91 5 30 92 61 31 93 62 31 94 60 31 95 63 32 96 0 32 97 62 32 98 30 33 99 46 33 100 62 33 101 1 0 102 3 0 103 2 0 104 3 34 105 5 34 106 4 34 107 5 2 108 7 2 109 6 2 110 7 35 111 9 35 112 8 35 113 9 36 114 11 36 115 10 36 116 11 37 117 13 37 118 12 37 119 13 38 120 15 38 121 14 38 122 15 39 123 17 39 124 16 39 125 17 40 126 19 40 127 18 40 128 19 41 129 21 41 130 20 41 131 21 42 132 23 42 133 22 42 134 23 43 135 25 43 136 24 43 137 25 44 138 27 44 139 26 44 140 27 13 141 29 13 142 28 13 143 29 45 144 31 45 145 30 45 146 31 15 147 33 15 148 32 15 149 33 16 150 35 16 151 34 16 152 35 46 153 37 46 154 36 46 155 37 18 156 39 18 157 38 18 158 39 47 159 41 47 160 40 47 161 41 48 162 43 48 163 42 48 164 43 49 165 45 49 166 44 49 167 45 50 168 47 50 169 46 50 170 47 51 171 49 51 172 48 51 173 49 52 174 51 52 175 50 52 176 51 53 177 53 53 178 52 53 179 53 54 180 55 54 181 54 54 182 55 55 183 57 55 184 56 55 185 57 56 186 59 56 187 58 56 188 59 29 189 61 29 190 60 29 191 5 30 192 3 30 193 1 30 194 1 30 195 63 30 196 5 30 197 63 30 198 61 30 199 5 30 200 61 30 201 59 30 202 57 30 203 57 30 204 55 30 205 53 30 206 53 30 207 51 30 208 49 30 209 49 30 210 47 30 211 53 30 212 47 30 213 45 30 214 53 30 215 45 30 216 43 30 217 41 30 218 41 30 219 39 30 220 37 30 221 37 30 222 35 30 223 29 30 224 35 30 225 33 30 226 29 30 227 33 30 228 31 30 229 29 30 230 29 30 231 27 30 232 25 30 233 25 30 234 23 30 235 21 30 236 21 30 237 19 30 238 13 30 239 19 30 240 17 30 241 13 30 242 17 30 243 15 30 244 13 30 245 13 30 246 11 30 247 9 30 248 9 30 249 7 30 250 5 30 251 61 30 252 57 30 253 5 30 254 57 30 255 53 30 256 5 30 257 45 30 258 41 30 259 53 30 260 41 30 261 37 30 262 53 30 263 29 30 264 25 30 265 37 30 266 25 30 267 21 30 268 37 30 269 13 30 270 9 30 271 21 30 272 9 30 273 5 30 274 21 30 275 5 30 276 53 30 277 37 30 278 61 57 279 63 57 280 62 57 281 63 32 282 1 32 283 0 32 284 62 33 285 0 33 286 2 33 287 2 33 288 4 33 289 6 33 290 6 33 291 8 33 292 10 33 293 10 58 294 12 58 295 14 58 296 14 33 297 16 33 298 18 33 299 18 59 300 20 59 301 22 59 302 22 33 303 24 33 304 26 33 305 26 33 306 28 33 307 30 33 308 30 33 309 32 33 310 34 33 311 34 33 312 36 33 313 38 33 314 38 33 315 40 33 316 42 33 317 42 60 318 44 60 319 46 60 320 46 33 321 48 33 322 50 33 323 50 61 324 52 61 325 54 61 326 54 33 327 56 33 328 58 33 329 58 33 330 60 33 331 62 33 332 62 33 333 2 33 334 14 33 335 2 33 336 6 33 337 14 33 338 6 33 339 10 33 340 14 33 341 14 62 342 18 62 343 30 62 344 18 33 345 22 33 346 30 33 347 22 33 348 26 33 349 30 33 350 30 33 351 34 33 352 46 33 353 34 33 354 38 33 355 46 33 356 38 33 357 42 33 358 46 33 359 46 63 360 50 63 361 62 63 362 50 33 363 54 33 364 62 33 365 54 33 366 58 33 367 62 33 368 62 33 369 14 33 370 30 33 371

+
+
+
+ + + + + -0.2908648 -0.7711008 0.5663932 4.076245 0.9551711 -0.1998834 0.2183913 1.005454 -0.05518911 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054209 -0.6141704 -6.925791 -4.01133e-9 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + 0.025 0 0 0 0 0.025 0 0 0 0 0.25 0.255 0 0 0 1 + + + + + + + + + + + + 1.88745e-9 0 0.25 0.25 0 0.025 0 0 -0.025 0 1.88745e-8 0 0 0 0 1 + + + + + + + + + + + + 0.025 0 0 0 0 1.88745e-9 -0.25 0.25 0 0.025 1.88745e-8 0 0 0 0 1 + + + + + + + + + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + + \ No newline at end of file diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/package.xml b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/package.xml new file mode 100644 index 000000000..f3e2934ba --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/package.xml @@ -0,0 +1,37 @@ + + + + waypoint_rviz2_plugin + 1.0.0 + RViz2 plugin for creating and manipulating interactive 3D waypoints + + koko + Apache-2.0 + + ament_cmake + + rclcpp + rviz_common + rviz_default_plugins + rviz_rendering + rviz_ogre_vendor + geometry_msgs + visualization_msgs + interactive_markers + nav_msgs + tf2 + tf2_geometry_msgs + rosbag2_cpp + pluginlib + qtbase5-dev + + qt5-qmake + + ament_lint_auto + ament_lint_common + + + ament_cmake + + + diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/plugin_description.xml b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/plugin_description.xml new file mode 100644 index 000000000..3aa60feef --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/plugin_description.xml @@ -0,0 +1,10 @@ + + + + Interactive waypoint creation and manipulation tool for RViz2. + Click to add waypoints, drag to move them, right-click to delete. + + + diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp new file mode 100644 index 000000000..0d4f145d4 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp @@ -0,0 +1,403 @@ +/** + * @file waypoint_tool.cpp + * @author KoKoLates (the21515@gmail.com) + * @version 1.0.0 + * @date 2023-06-20 + * + * ROS2 port of the interactive waypoint tool implementation + */ + +#include "waypoint_rviz2_plugin/waypoint_tool.hpp" + +#include + +#ifndef Q_MOC_RUN +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#endif + +// Define slots macro for render_window.hpp compatibility +#ifndef slots +#define slots Q_SLOTS +#define signals Q_SIGNALS +#endif + +#include + +namespace waypoint_rviz2_plugin { + +WaypointTool::WaypointTool() + : move_axis_node_(nullptr), + widget_dock_(nullptr), + widget_(nullptr), + unique_idx_(0) +{ + shortcut_key_ = '1'; +} + +WaypointTool::~WaypointTool() { + str2nodeptr::iterator node_itr; + for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { + scene_manager_->destroySceneNode(node_itr->second); + } + delete widget_; + delete widget_dock_; +} + +void WaypointTool::onInitialize() { + node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); + + axis_resource_ = "package://waypoint_rviz2_plugin/media/axis.dae"; + + if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { + RCLCPP_ERROR(node_->get_logger(), "Waypoint Tool: failed to load model resource '%s'.", axis_resource_.c_str()); + return; + } + + move_axis_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); + Ogre::Entity* entity = scene_manager_->createEntity(axis_resource_); + move_axis_node_->attachObject(entity); + move_axis_node_->setVisible(false); + + server_ = std::make_shared( + "waypoint_plugin", node_ + ); + + rviz_common::WindowManagerInterface* window_context_ = context_->getWindowManager(); + widget_ = new WaypointWidget(context_, node_, &node_map_, server_, &unique_idx_, nullptr, this); + + if (window_context_) { + widget_dock_ = window_context_->addPane("Waypoint Plugin", widget_); + } + widget_->enable(); + + menu_handler_.insert("delete", + std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); + menu_handler_.insert("set manual", + std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); +} + +void WaypointTool::activate() { + if (move_axis_node_) { + move_axis_node_->setVisible(true); + } +} + +void WaypointTool::deactivate() { + if (move_axis_node_) { + move_axis_node_->setVisible(false); + } +} + +int WaypointTool::processMouseEvent(rviz_common::ViewportMouseEvent& event) { + if (!move_axis_node_) { + return Render; + } + + double height = widget_->getDefaultHeight(); + Ogre::Vector3 intersection; + Ogre::Quaternion quaternion; + Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, height); + + // Get viewport and camera from the render window + auto render_window = event.panel->getRenderWindow(); + Ogre::Camera * camera = rviz_rendering::RenderWindowOgreAdapter::getOgreCamera(render_window); + Ogre::Viewport * viewport = rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(render_window); + + // Convert mouse coordinates to normalized device coordinates + int width = viewport->getActualWidth(); + int height_px = viewport->getActualHeight(); + float screen_x = static_cast(event.x) / static_cast(width); + float screen_y = static_cast(event.y) / static_cast(height_px); + + // Create ray from camera through mouse position + Ogre::Ray mouse_ray = camera->getCameraToViewportRay(screen_x, screen_y); + + // Intersect ray with ground plane + std::pair result = mouse_ray.intersects(ground_plane); + + if (result.first) { + intersection = mouse_ray.getPoint(result.second); + move_axis_node_->setVisible(true); + move_axis_node_->setPosition(intersection); + + widget_->setWaypointLabel(intersection); + + str2nodeptr::iterator node_itr; + for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { + Ogre::Vector3 stored_pose = node_itr->second->getPosition(); + double distance = std::sqrt( + pow(stored_pose.x - intersection.x, 2) + pow(stored_pose.y - intersection.y, 2) + ); + + if (distance < 0.4) { + move_axis_node_->setVisible(false); + + if (event.rightDown()) { + node_itr->second->detachAllObjects(); + std::stringstream waypoint_name; + waypoint_name << waypoint_name_prefix << node_itr->first; + server_->erase(waypoint_name.str()); + server_->applyChanges(); + node_map_.erase(node_itr); + + move_axis_node_->setVisible(true); + return Render | Finished; + } + } + } + + if (event.leftDown()) { + makeItem(intersection, quaternion); + return Render | Finished; + } + } + else { + move_axis_node_->setVisible(false); + } + return Render; +} + +void WaypointTool::makeItem(const Ogre::Vector3& position, const Ogre::Quaternion& quaternion) { + unique_idx_++; + std::stringstream waypoint_name; + waypoint_name << waypoint_name_prefix << unique_idx_; + std::string str_name(waypoint_name.str()); + + if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { + RCLCPP_ERROR(node_->get_logger(), "WaypointTool: failed to load model resource '%s'.", axis_resource_.c_str()); + return; + } + + Ogre::SceneNode *node_ptr = scene_manager_->getRootSceneNode()->createChildSceneNode(); + Ogre::Entity *entity = scene_manager_->createEntity(axis_resource_); + node_ptr->attachObject(entity); + node_ptr->setVisible(true); + node_ptr->setPosition(position); + node_ptr->setOrientation(quaternion); + + str2nodeptr::iterator node_entry = node_map_.find(unique_idx_); + if (node_entry == node_map_.end()) { + node_map_.insert(std::make_pair(unique_idx_, node_ptr)); + } else { + RCLCPP_WARN(node_->get_logger(), "%s already in map", str_name.c_str()); + return; + } + widget_->setWaypointCount(node_map_.size()); + + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = position.x; + pose.pose.position.y = position.y; + pose.pose.position.z = position.z; + pose.pose.orientation.x = quaternion.x; + pose.pose.orientation.y = quaternion.y; + pose.pose.orientation.z = quaternion.z; + pose.pose.orientation.w = quaternion.w; + + visualization_msgs::msg::InteractiveMarker int_marker; + int_marker.header.stamp = node_->now(); + int_marker.header.frame_id = widget_->getFrameId().toStdString(); + int_marker.pose = pose.pose; + int_marker.scale = 1.0; + int_marker.name = str_name; + + visualization_msgs::msg::Marker marker; + marker.type = visualization_msgs::msg::Marker::CYLINDER; + marker.scale.x = 0.5; + marker.scale.y = 0.5; + marker.scale.z = 0.1; + marker.color.r = 0.0; + marker.color.g = 0.0; + marker.color.b = 0.0; + marker.color.a = 0.0; + + visualization_msgs::msg::InteractiveMarkerControl c_control; + c_control.always_visible = true; + c_control.markers.push_back(marker); + int_marker.controls.push_back(c_control); + + visualization_msgs::msg::InteractiveMarkerControl control; + control.orientation.w = 0.707106781; + control.orientation.x = 0; + control.orientation.y = 0.707106781; + control.orientation.z = 0; + control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MOVE_ROTATE; + int_marker.controls.push_back(control); + + control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MOVE_AXIS; + int_marker.controls.push_back(control); + + control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MENU; + control.name = "menu_delete"; + control.description = str_name; + int_marker.controls.push_back(control); + + server_->insert(int_marker); + server_->setCallback(int_marker.name, + std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); + menu_handler_.apply(*server_, int_marker.name); + + Ogre::Vector3 p = position; + Ogre::Quaternion q = quaternion; + widget_->setSelectedMarkerName(str_name); + widget_->setWaypointLabel(p); + widget_->setPose(p, q); + server_->applyChanges(); +} + +void WaypointTool::processFeedBack( + const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback) +{ + switch (feedback->event_type) { + case visualization_msgs::msg::InteractiveMarkerFeedback::MENU_SELECT: + { + str2nodeptr::iterator node_entry = node_map_.find(std::stoi( + feedback->marker_name.substr(strlen(waypoint_name_prefix)))); + if (node_entry == node_map_.end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", feedback->marker_name.c_str()); + } + else { + if (feedback->menu_entry_id == 1) { + std::stringstream waypoint_name; + waypoint_name << waypoint_name_prefix << node_entry->first; + server_->erase(waypoint_name.str()); + + menu_handler_.reApply(*server_); + server_->applyChanges(); + node_entry->second->detachAllObjects(); + node_map_.erase(node_entry); + + int waypoint_num = node_map_.size(); + widget_->setWaypointCount(waypoint_num); + } + else { + Ogre::Vector3 position; + Ogre::Quaternion quaternion; + + widget_->getPose(position, quaternion); + + geometry_msgs::msg::Pose pose; + pose.position.x = position.x; + pose.position.y = position.y; + pose.position.z = position.z; + + pose.orientation.x = quaternion.x; + pose.orientation.y = quaternion.y; + pose.orientation.z = quaternion.z; + pose.orientation.w = quaternion.w; + + node_entry->second->setPosition(position); + node_entry->second->setOrientation(quaternion); + + widget_->setWaypointLabel(position); + server_->setPose(feedback->marker_name, pose); + server_->applyChanges(); + } + } + } + break; + case visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE: + { + str2nodeptr::iterator node_entry = node_map_.find(std::stoi( + feedback->marker_name.substr(strlen(waypoint_name_prefix)) + )); + if (node_entry == node_map_.end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", feedback->marker_name.c_str()); + } + else { + geometry_msgs::msg::PoseStamped pose; + pose.pose = feedback->pose; + + Ogre::Vector3 position; + position.x = pose.pose.position.x; + position.y = pose.pose.position.y; + position.z = pose.pose.position.z; + node_entry->second->setPosition(position); + + Ogre::Quaternion quaternion; + quaternion.x = pose.pose.orientation.x; + quaternion.y = pose.pose.orientation.y; + quaternion.z = pose.pose.orientation.z; + quaternion.w = pose.pose.orientation.w; + node_entry->second->setOrientation(quaternion); + + widget_->setWaypointLabel(position); + widget_->setPose(position, quaternion); + widget_->setSelectedMarkerName(feedback->marker_name); + } + } + break; + } +} + +void WaypointTool::getMarkerPose() { + str2nodeptr::iterator node_itr; + for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { + visualization_msgs::msg::InteractiveMarker int_marker; + + std::stringstream waypoint_name; + waypoint_name << waypoint_name_prefix << node_itr->first; + server_->get(waypoint_name.str(), int_marker); + + RCLCPP_INFO( + node_->get_logger(), + "pose: %g %g %g", + int_marker.pose.position.x, + int_marker.pose.position.y, + int_marker.pose.position.z + ); + } +} + +void WaypointTool::clearAllMarker() { + str2nodeptr::iterator node_itr; + for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { + scene_manager_->destroySceneNode(node_itr->second); + } + node_map_.clear(); + unique_idx_ = 0; +} + +void WaypointTool::save(rviz_common::Config config) const { + config.mapSetValue("Class", getClassId()); + rviz_common::Config waypoint_config = config.mapMakeChild("WaypointTool"); + + waypoint_config.mapSetValue("topic", widget_->getOutputTopic()); + waypoint_config.mapSetValue("frame_id", widget_->getFrameId()); + waypoint_config.mapSetValue("default_height", widget_->getDefaultHeight()); +} + +void WaypointTool::load(const rviz_common::Config &config) { + rviz_common::Config waypoint_config = config.mapGetChild("WaypointTool"); + QString topic, frame; + float height; + if (!waypoint_config.mapGetString("topic", &topic)) { + topic = "/waypoints"; + } + if (!waypoint_config.mapGetString("frame_id", &frame)) { + frame = "map"; + } + waypoint_config.mapGetFloat("default_height", &height); + + widget_->setConfig(topic, frame, height); +} + +} + +#include +PLUGINLIB_EXPORT_CLASS(waypoint_rviz2_plugin::WaypointTool, rviz_common::Tool) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp new file mode 100644 index 000000000..18988eb21 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp @@ -0,0 +1,504 @@ +/** + * @file waypoint_widget.cpp + * @author KoKoLates (the21515@gmail.com) + * @version 1.0.0 + * @date 2023-06-18 + * + * ROS2 port of the interactive waypoint widget implementation + */ + +#include "waypoint_rviz2_plugin/waypoint_widget.hpp" +#include "waypoint_rviz2_plugin/waypoint_tool.hpp" + +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include + +namespace waypoint_rviz2_plugin { + +WaypointWidget::WaypointWidget(rviz_common::DisplayContext *context, + rclcpp::Node::SharedPtr node, + std::map *map_ptr, + std::shared_ptr server, + int *unique_idx, + QWidget *parent, + WaypointTool *waypoint_tool): QWidget(parent) +{ + context_ = context; + node_ = node; + ui_ = new Ui::PluginWidget(); + map_ptr_ = map_ptr; + unique_idx_ = unique_idx; + server_ = server; + frame_id_ = "map"; + waypoint_tool_ = waypoint_tool; + default_height_ = 0.0; + selected_marker_name_ = std::string(waypoint_name_prefix) + "1"; + + scene_manager_ = context_->getSceneManager(); + ui_->setupUi(this); + + path_publisher_ = node_->create_publisher("waypoints", 1); + + connect(ui_->button_save, SIGNAL(clicked()), this, SLOT(saveHandler())); + connect(ui_->button_load, SIGNAL(clicked()), this, SLOT(loadHandler())); + connect(ui_->button_clear, SIGNAL(clicked()), this, SLOT(clearHandler())); + connect(ui_->button_publish, SIGNAL(clicked()), this, SLOT(publishHandler())); + + connect(ui_->x_spinbox, SIGNAL(valueChanged(double)), this, SLOT(poseChange(double))); + connect(ui_->y_spinbox, SIGNAL(valueChanged(double)), this, SLOT(poseChange(double))); + connect(ui_->z_spinbox, SIGNAL(valueChanged(double)), this, SLOT(poseChange(double))); + connect(ui_->yaw_spinbox, SIGNAL(valueChanged(double)), this, SLOT(poseChange(double))); + connect(ui_->height_spinbox, SIGNAL(valueChanged(double)), this, SLOT(heightChange(double))); + + connect(ui_->topic_input, SIGNAL(editingFinished()), this, SLOT(topicChange())); + connect(ui_->frame_input, SIGNAL(editingFinished()), this, SLOT(frameChange())); +} + +WaypointWidget::~WaypointWidget() { + delete ui_; + map_ptr_ = nullptr; +} + +void WaypointWidget::enable() { + show(); +} + +void WaypointWidget::disable() { + path_publisher_.reset(); + hide(); +} + +void WaypointWidget::saveHandler() { + QString filename = QFileDialog::getSaveFileName( + 0, tr("Waypoints Save"), "waypoints", + tr("Save Files (*.db3)") + ); + if (filename.isEmpty()) { + RCLCPP_ERROR(node_->get_logger(), "No saving file selected"); + return; + } + const std::string str_filename = filename.toStdString(); + RCLCPP_INFO_STREAM(node_->get_logger(), "Saving the waypoints into " << str_filename); + + if (filename.endsWith(".db3")) { + saveBag(str_filename); + } + else { + RCLCPP_INFO_STREAM(node_->get_logger(), "Invalid saving file format: " << str_filename); + } +} + +void WaypointWidget::loadHandler() { + const QString filename = QFileDialog::getOpenFileName( + 0, tr("Waypoint load"), "~/", + tr("Load Files (*.db3)") + ); + if (filename.isEmpty()) { + RCLCPP_ERROR(node_->get_logger(), "No loading file selected"); + return; + } + const std::string str_filename = filename.toStdString(); + RCLCPP_INFO(node_->get_logger(), "loading waypoints from %s", str_filename.c_str()); + if (filename.endsWith(".db3")) { + loadBag(str_filename); + } + else { + RCLCPP_INFO_STREAM(node_->get_logger(), "Invalid loading file format: " << str_filename); + } +} + +void WaypointWidget::clearHandler() { + std::map::iterator node_itr; + for (node_itr = map_ptr_->begin(); node_itr != map_ptr_->end(); node_itr++) { + scene_manager_->destroySceneNode(node_itr->second); + } + map_ptr_->clear(); + *unique_idx_ = 0; + + server_->clear(); + server_->applyChanges(); +} + +void WaypointWidget::publishHandler() { + nav_msgs::msg::Path path; + std::map::iterator node_itr; + + for (node_itr = map_ptr_->begin(); node_itr != map_ptr_->end(); node_itr++) { + Ogre::Vector3 position; + position = node_itr->second->getPosition(); + + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = position.x; + pose.pose.position.y = position.y; + pose.pose.position.z = position.z; + + Ogre::Quaternion quat; + quat = node_itr->second->getOrientation(); + pose.pose.orientation.x = quat.x; + pose.pose.orientation.y = quat.y; + pose.pose.orientation.z = quat.z; + pose.pose.orientation.w = quat.w; + + path.poses.push_back(pose); + } + path.header.frame_id = frame_id_.toStdString(); + path.header.stamp = node_->now(); + path_publisher_->publish(path); +} + +void WaypointWidget::poseChange(double value) { + auto node_entry = map_ptr_->end(); + try { + const int selected_marker_idx = std::stoi(selected_marker_name_.substr(strlen(waypoint_name_prefix))); + node_entry = map_ptr_->find(selected_marker_idx); + } + catch (const std::logic_error& e) { + RCLCPP_ERROR_STREAM(node_->get_logger(), e.what()); + return; + } + + if (node_entry == map_ptr_->end()) + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", selected_marker_name_.c_str()); + else + { + Ogre::Vector3 position; + Ogre::Quaternion quaternion; + getPose(position, quaternion); + + node_entry->second->setPosition(position); + node_entry->second->setOrientation(quaternion); + + std::stringstream waypoint_name; + waypoint_name << waypoint_name_prefix << node_entry->first; + std::string waypoint_name_str(waypoint_name.str()); + + visualization_msgs::msg::InteractiveMarker int_marker; + if(server_->get(waypoint_name_str, int_marker)) { + int_marker.pose.position.x = position.x; + int_marker.pose.position.y = position.y; + int_marker.pose.position.z = position.z; + + int_marker.pose.orientation.x = quaternion.x; + int_marker.pose.orientation.y = quaternion.y; + int_marker.pose.orientation.z = quaternion.z; + int_marker.pose.orientation.w = quaternion.w; + + server_->setPose(waypoint_name_str, int_marker.pose, int_marker.header); + } + server_->applyChanges(); + } +} + +void WaypointWidget::frameChange() { + std::lock_guard lock(frame_updates_mutex_); + QString new_frame = ui_->frame_input->text(); + + if ((new_frame != frame_id_) && (new_frame != "")) { + frame_id_ = new_frame; + RCLCPP_INFO(node_->get_logger(), "new frame: %s", frame_id_.toStdString().c_str()); + + std::map::iterator node_itr; + for (node_itr = map_ptr_->begin(); node_itr != map_ptr_->end(); node_itr++) { + std::stringstream waypoint_name; + waypoint_name << "waypoint" << node_itr->first; + std::string waypoint_name_str(waypoint_name.str()); + + visualization_msgs::msg::InteractiveMarker int_marker; + if(server_->get(waypoint_name_str, int_marker)) { + int_marker.header.frame_id = new_frame.toStdString(); + server_->setPose(waypoint_name_str, int_marker.pose, int_marker.header); + } + } + server_->applyChanges(); + } +} + +void WaypointWidget::topicChange() { + QString new_topic = ui_->topic_input->text(); + + if(new_topic != output_topic_) { + path_publisher_.reset(); + output_topic_ = new_topic; + if((output_topic_ != "") && (output_topic_ != "/")) { + path_publisher_ = node_->create_publisher( + output_topic_.toStdString(), 1); + } + } +} + +void WaypointWidget::heightChange(double value) { + auto sn_entry = map_ptr_->end(); + try { + const int selected_marker_idx = std::stoi( + selected_marker_name_.substr((strlen((waypoint_name_prefix)))) + ); + sn_entry = map_ptr_->find(selected_marker_idx); + } catch(const std::logic_error &error) { + RCLCPP_ERROR_STREAM(node_->get_logger(), error.what()); + return; + } + + if (sn_entry == map_ptr_->end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", selected_marker_name_.c_str()); + } else { + Ogre::Vector3 position; + Ogre::Quaternion quaternion; + getPose(position, quaternion); + + sn_entry->second->setPosition(position); + sn_entry->second->setOrientation(quaternion); + + std::stringstream wp_name; + wp_name << waypoint_name_prefix << sn_entry->first; + std::string wp_name_str(wp_name.str()); + + visualization_msgs::msg::InteractiveMarker int_marker; + if (server_->get(wp_name_str, int_marker)) { + int_marker.pose.position.x = position.x; + int_marker.pose.position.y = position.y; + int_marker.pose.position.z = position.z; + + int_marker.pose.orientation.x = quaternion.x; + int_marker.pose.orientation.y = quaternion.y; + int_marker.pose.orientation.z = quaternion.z; + int_marker.pose.orientation.w = quaternion.w; + + server_->setPose(wp_name_str, int_marker.pose, int_marker.header); + } + server_->applyChanges(); + } +} + +void WaypointWidget::saveBag(const std::string& filename) { + nav_msgs::msg::Path path; + std::map::iterator node_itr; + for (node_itr = map_ptr_->begin(); node_itr != map_ptr_->end(); ++node_itr) { + Ogre::Vector3 position; + position = node_itr->second->getPosition(); + + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = position.x; + pose.pose.position.y = position.y; + pose.pose.position.z = position.z; + + Ogre::Quaternion quat; + quat = node_itr->second->getOrientation(); + pose.pose.orientation.x = quat.x; + pose.pose.orientation.y = quat.y; + pose.pose.orientation.z = quat.z; + pose.pose.orientation.w = quat.w; + + path.poses.push_back(pose); + } + path.header.frame_id = frame_id_.toStdString(); + path.header.stamp = node_->now(); + + try { + rosbag2_cpp::Writer writer; + + rosbag2_storage::StorageOptions storage_options; + storage_options.uri = filename; + storage_options.storage_id = "sqlite3"; + + rosbag2_cpp::ConverterOptions converter_options; + converter_options.input_serialization_format = "cdr"; + converter_options.output_serialization_format = "cdr"; + + writer.open(storage_options, converter_options); + + writer.create_topic({ + "waypoints", + "nav_msgs/msg/Path", + rmw_get_serialization_format(), + "" + }); + + auto serialized_msg = std::make_shared(); + rclcpp::Serialization serialization; + serialization.serialize_message(&path, serialized_msg.get()); + + auto bag_message = std::make_shared(); + bag_message->topic_name = "waypoints"; + bag_message->time_stamp = node_->now().nanoseconds(); + bag_message->serialized_data = std::shared_ptr( + new rcutils_uint8_array_t, + [](rcutils_uint8_array_t* data) { + auto fini_return = rcutils_uint8_array_fini(data); + delete data; + if (fini_return != RCUTILS_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + "waypoint_rviz2_plugin", + "Failed to destroy serialized message %s", rcutils_get_error_string().str); + } + }); + *bag_message->serialized_data = serialized_msg->release_rcl_serialized_message(); + + writer.write(bag_message); + + RCLCPP_INFO(node_->get_logger(), "Waypoints saved successfully"); + } + catch (const std::exception& e) { + RCLCPP_ERROR(node_->get_logger(), "Failed to save bag: %s", e.what()); + } +} + +void WaypointWidget::loadBag(const std::string& filename) { + try { + rosbag2_cpp::Reader reader; + + rosbag2_storage::StorageOptions storage_options; + storage_options.uri = filename; + storage_options.storage_id = "sqlite3"; + + rosbag2_cpp::ConverterOptions converter_options; + converter_options.input_serialization_format = "cdr"; + converter_options.output_serialization_format = "cdr"; + + reader.open(storage_options, converter_options); + + while (reader.has_next()) { + auto bag_message = reader.read_next(); + + if (bag_message->topic_name == "waypoints") { + rclcpp::SerializedMessage serialized_msg(*bag_message->serialized_data); + nav_msgs::msg::Path path; + + rclcpp::Serialization serialization; + serialization.deserialize_message(&serialized_msg, &path); + + RCLCPP_INFO(node_->get_logger(), "n waypoints %zu", path.poses.size()); + + for (size_t i = 0; i < path.poses.size(); i++) { + geometry_msgs::msg::PoseStamped pos = path.poses[i]; + Ogre::Vector3 position; + position.x = pos.pose.position.x; + position.y = pos.pose.position.y; + position.z = pos.pose.position.z; + + Ogre::Quaternion quaternion; + quaternion.x = pos.pose.orientation.x; + quaternion.y = pos.pose.orientation.y; + quaternion.z = pos.pose.orientation.z; + quaternion.w = pos.pose.orientation.w; + + waypoint_tool_->makeItem(position, quaternion); + } + } + } + } + catch (const std::exception& e) { + RCLCPP_ERROR(node_->get_logger(), "Failed to load bag: %s", e.what()); + } +} + +void WaypointWidget::setPose(const Ogre::Vector3& position, const Ogre::Quaternion& quaternion) { + ui_->x_spinbox->blockSignals(true); + ui_->y_spinbox->blockSignals(true); + ui_->z_spinbox->blockSignals(true); + ui_->yaw_spinbox->blockSignals(true); + + ui_->x_spinbox->setValue(position.x); + ui_->y_spinbox->setValue(position.y); + ui_->z_spinbox->setValue(position.z); + + tf2::Quaternion qt(quaternion.x, quaternion.y, quaternion.z, quaternion.w); + tf2::Matrix3x3 m(qt); + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + ui_->yaw_spinbox->setValue(yaw); + + ui_->x_spinbox->blockSignals(false); + ui_->y_spinbox->blockSignals(false); + ui_->z_spinbox->blockSignals(false); + ui_->yaw_spinbox->blockSignals(false); +} + +void WaypointWidget::setConfig(QString topic, QString frame, float height) { + { + std::lock_guard lock(frame_updates_mutex_); + ui_->topic_input->blockSignals(true); + ui_->frame_input->blockSignals(true); + ui_->height_spinbox->blockSignals(true); + + ui_->topic_input->setText(topic); + ui_->frame_input->setText(frame); + ui_->height_spinbox->setValue(height); + + ui_->topic_input->blockSignals(false); + ui_->frame_input->blockSignals(false); + ui_->height_spinbox->blockSignals(false); + } + + topicChange(); + frameChange(); + heightChange(height); +} + +void WaypointWidget::setWaypointLabel(Ogre::Vector3 position) { + std::ostringstream string_stream; + string_stream.precision(2); + string_stream << selected_marker_name_; + std::string label = string_stream.str(); + ui_->text_selected->setText(QString::fromStdString(label)); +} + +void WaypointWidget::setWaypointCount(int size) { + std::ostringstream string_stream; + string_stream << "Total waypoints: " << size; + std::lock_guard lock(frame_updates_mutex_); + ui_->text_total->setText( + QString::fromStdString(string_stream.str()) + ); +} + +void WaypointWidget::setSelectedMarkerName(std::string name) { + selected_marker_name_ = name; +} + +void WaypointWidget::getPose(Ogre::Vector3& position, Ogre::Quaternion& quaternion) { + std::lock_guard lock(frame_updates_mutex_); + position.x = ui_->x_spinbox->value(); + position.y = ui_->y_spinbox->value(); + position.z = ui_->z_spinbox->value(); + double yaw = ui_->yaw_spinbox->value(); + + tf2::Quaternion qt; + qt.setRPY(0.0, 0.0, yaw); + quaternion.x = qt.x(); + quaternion.y = qt.y(); + quaternion.z = qt.z(); + quaternion.w = qt.w(); +} + +double WaypointWidget::getDefaultHeight() { + std::lock_guard lock(frame_updates_mutex_); + return default_height_; +} + +QString WaypointWidget::getFrameId() { + std::lock_guard lock(frame_updates_mutex_); + return frame_id_; +} + +QString WaypointWidget::getOutputTopic() { + std::lock_guard lock(frame_updates_mutex_); + return output_topic_; +} + +} diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/ui/waypoint_plugin.ui b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/ui/waypoint_plugin.ui new file mode 100644 index 000000000..bce84c609 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/ui/waypoint_plugin.ui @@ -0,0 +1,253 @@ + + + PluginWidget + + + + 0 + 0 + 469 + 175 + + + + Quadrotor Steering + + + + + + + + Topic + + + + + + + /waypoints + + + + + + + Frame + + + + + + + map + + + + + + + 6D + + + + + + + + + + + Default Height + + + + + + + -5.000000000000000 + + + 0.100000000000000 + + + + + + + Total Waypoints: + + + + + + + Selected wp: + + + + + + + + + + + + + + + + Load Waypoints + + + + + + + + + X: + + + + + + + -1000.000000000000000 + + + 1000.000000000000000 + + + 0.500000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Y: + + + + + + + -1000.000000000000000 + + + 1000.000000000000000 + + + 0.500000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Z: + + + + + + + -1000.000000000000000 + + + 1000.000000000000000 + + + 0.500000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Yaw: + + + + + + + -3.150000000000000 + + + 3.150000000000000 + + + 0.100000000000000 + + + + + + + + + Clear All + + + + + + + Save Waypoints + + + + + + + Publish Waypoints + + + + + + + + diff --git a/common/ros_packages/gui/rviz/rviz_polygon_selection_tool b/common/ros_packages/gui/rviz/rviz_polygon_selection_tool new file mode 160000 index 000000000..d64ddcfde --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_polygon_selection_tool @@ -0,0 +1 @@ +Subproject commit d64ddcfde28b97701e4748f5c4895ce591021053 From a47af4e3b398768b64bc270920ec3870b4cef635 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 16:07:30 -0400 Subject: [PATCH 07/24] Fix jazzy compatibility --- .../src/waypoint_widget.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp index 18988eb21..2fc25c6d8 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_widget.cpp @@ -322,12 +322,11 @@ void WaypointWidget::saveBag(const std::string& filename) { writer.open(storage_options, converter_options); - writer.create_topic({ - "waypoints", - "nav_msgs/msg/Path", - rmw_get_serialization_format(), - "" - }); + rosbag2_storage::TopicMetadata topic_metadata; + topic_metadata.name = "waypoints"; + topic_metadata.type = "nav_msgs/msg/Path"; + topic_metadata.serialization_format = rmw_get_serialization_format(); + writer.create_topic(topic_metadata); auto serialized_msg = std::make_shared(); rclcpp::Serialization serialization; @@ -335,7 +334,7 @@ void WaypointWidget::saveBag(const std::string& filename) { auto bag_message = std::make_shared(); bag_message->topic_name = "waypoints"; - bag_message->time_stamp = node_->now().nanoseconds(); + bag_message->recv_timestamp = node_->now().nanoseconds(); bag_message->serialized_data = std::shared_ptr( new rcutils_uint8_array_t, [](rcutils_uint8_array_t* data) { From f513da84b07805935a81a4150e0968771dbb55cb Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Thu, 9 Apr 2026 16:07:40 -0400 Subject: [PATCH 08/24] Add task panel plugin for rviz --- .../gui/rviz/rviz_tasks_panel/CMakeLists.txt | 79 ++ .../include/rviz_tasks_panel/tasks_panel.hpp | 155 +++ .../gui/rviz/rviz_tasks_panel/package.xml | 28 + .../rviz_tasks_panel/plugin_description.xml | 5 + .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 940 ++++++++++++++++++ 5 files changed, 1207 insertions(+) create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/plugin_description.xml create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt new file mode 100644 index 000000000..d5391ba7f --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt @@ -0,0 +1,79 @@ +cmake_minimum_required(VERSION 3.8) +project(rviz_tasks_panel) + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_AUTOMOC ON) + +find_package(ament_cmake REQUIRED) +find_package(pluginlib REQUIRED) +find_package(rviz_common REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_action REQUIRED) +find_package(Qt5 REQUIRED COMPONENTS Core Widgets Gui) +find_package(task_msgs REQUIRED) +find_package(airstack_msgs REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(nav_msgs REQUIRED) +find_package(diagnostic_msgs REQUIRED) +find_package(action_msgs REQUIRED) +find_package(rviz_polygon_selection_tool REQUIRED) + +qt5_wrap_cpp(MOC_FILES + include/rviz_tasks_panel/tasks_panel.hpp +) + +add_library(tasks_panel SHARED + src/tasks_panel.cpp + ${MOC_FILES} +) + +target_include_directories(tasks_panel PUBLIC + $ + $ +) + +ament_target_dependencies(tasks_panel + pluginlib + rviz_common + rclcpp + rclcpp_action + task_msgs + airstack_msgs + geometry_msgs + nav_msgs + diagnostic_msgs + action_msgs + rviz_polygon_selection_tool +) + +target_link_libraries(tasks_panel + Qt5::Core + Qt5::Widgets + Qt5::Gui +) + +install(TARGETS tasks_panel + EXPORT export_rviz_tasks_panel + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install(DIRECTORY include/ + DESTINATION include +) + +install(FILES plugin_description.xml + DESTINATION share/${PROJECT_NAME} +) + +ament_export_include_directories(include) +ament_export_targets(export_rviz_tasks_panel) +pluginlib_export_plugin_description_file(rviz_common plugin_description.xml) + +ament_package() diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp new file mode 100644 index 000000000..0d27b8de5 --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp @@ -0,0 +1,155 @@ +// Copyright (c) 2024 Carnegie Mellon University +// MIT License + +#pragma once + +#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 +#include +#include +#include +#include + +namespace rviz_tasks_panel +{ + +// Goal field definition for auto-generating widgets +struct GoalFieldDef +{ + std::string name; + std::string ros_type; // "float32", "int32", "string", "bool", + // "geometry_msgs/Polygon", "nav_msgs/Path", + // "airstack_msgs/FixedTrajectory" + double default_value{0.0}; + double min_value{0.0}; + double max_value{10000.0}; +}; + +// Task type definition +struct TaskTypeDef +{ + std::string display_name; + std::string action_topic_suffix; // e.g. "tasks/takeoff" + std::vector goal_fields; +}; + +// Per-tab runtime state +struct TaskTabState +{ + QComboBox * executor_combo{nullptr}; + std::map field_widgets; + std::map field_data; // complex types (Polygon, Path) + QPushButton * cancel_btn{nullptr}; + QPushButton * execute_btn{nullptr}; + QTextEdit * feedback_display{nullptr}; + QTextEdit * result_display{nullptr}; + QLabel * status_label{nullptr}; + std::any action_client; + std::any goal_handle; + bool goal_active{false}; +}; + +class TasksPanel : public rviz_common::Panel +{ + Q_OBJECT + +public: + explicit TasksPanel(QWidget * parent = nullptr); + ~TasksPanel() override = default; + void onInitialize() override; + void save(rviz_common::Config config) const override; + void load(const rviz_common::Config & config) override; + +private Q_SLOTS: + void onRefreshExecutors(); + void onExecuteClicked(); + void onCancelClicked(); + void onGetPolygon(int tab_index, const std::string & field_name); + void onTrajectoryTypeChanged(int tab_index, const QString & type); + +private: + rclcpp::Node::SharedPtr raw_node_; + + // Top bar + QComboBox * robot_combo_{nullptr}; + + // Tabs + QTabWidget * tab_widget_{nullptr}; + std::vector task_defs_; + std::vector tab_states_; + + // Polygon selection service + rclcpp::Client::SharedPtr polygon_client_; + + // Waypoints subscription + rclcpp::Subscription::SharedPtr waypoints_sub_; + nav_msgs::msg::Path::SharedPtr latest_waypoints_; + + // Discovery timer + QTimer * refresh_timer_{nullptr}; + + static std::vector getTaskDefs(); + void buildTabs(); + QWidget * buildGoalFieldWidget(const GoalFieldDef & def, int tab_index); + void updateAvailableExecutors(); + + // Widget value extraction helpers + double getFloat(int tab_index, const std::string & field_name); + int32_t getInt(int tab_index, const std::string & field_name); + std::string getString(int tab_index, const std::string & field_name); + bool getBool(int tab_index, const std::string & field_name); + geometry_msgs::msg::Polygon getPolygon(int tab_index, const std::string & field_name); + nav_msgs::msg::Path getPath(int tab_index, const std::string & field_name); + airstack_msgs::msg::FixedTrajectory getFixedTrajectory(int tab_index, const std::string & field_name); + + // Template for sending goals with type-specific callbacks + template + void doSendGoal( + int tab_index, + const typename ActionT::Goal & goal, + std::function fmt_feedback, + std::function fmt_result); + + template + void doCancelGoal(int tab_index); + + void setGoalActive(int tab_index, bool active); + QString currentRobot() const; +}; + +} // namespace rviz_tasks_panel diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml new file mode 100644 index 000000000..bb166df76 --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml @@ -0,0 +1,28 @@ + + + + rviz_tasks_panel + 0.0.0 + RViz2 Panel for dispatching and monitoring task action goals + andrew + MIT + + ament_cmake + + pluginlib + rviz_common + rclcpp + rclcpp_action + task_msgs + airstack_msgs + geometry_msgs + nav_msgs + diagnostic_msgs + action_msgs + rviz_polygon_selection_tool + qtbase5-dev + + + ament_cmake + + diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/plugin_description.xml b/common/ros_packages/gui/rviz/rviz_tasks_panel/plugin_description.xml new file mode 100644 index 000000000..8298c7dc1 --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/plugin_description.xml @@ -0,0 +1,5 @@ + + + Panel for dispatching and monitoring ROS 2 task action goals + + diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp new file mode 100644 index 000000000..051fdf1f2 --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -0,0 +1,940 @@ +// Copyright (c) 2024 Carnegie Mellon University +// MIT License + +#include "rviz_tasks_panel/tasks_panel.hpp" + +#include +#include +#include +#include +#include +#include + +namespace rviz_tasks_panel +{ + +// ─────────────────────────── static task registry ───────────────────────────── + +std::vector TasksPanel::getTaskDefs() +{ + return { + {"Takeoff", "tasks/takeoff", { + {"target_altitude_m", "float32", 5.0, 0.0, 500.0}, + {"velocity_m_s", "float32", 1.0, 0.0, 50.0}, + }}, + {"Land", "tasks/land", { + {"velocity_m_s", "float32", 0.3, 0.0, 10.0}, + }}, + {"Navigate", "tasks/navigate", { + {"global_plan", "nav_msgs/Path", 0, 0, 0}, + {"goal_tolerance_m", "float32", 1.0, 0.0, 100.0}, + }}, + {"Exploration", "tasks/exploration", { + {"search_bounds", "geometry_msgs/Polygon", 0, 0, 0}, + {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, + {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, + {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, + {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, + {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, + }}, + {"Coverage", "tasks/coverage", { + {"coverage_area", "geometry_msgs/Polygon", 0, 0, 0}, + {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, + {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, + {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, + {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, + {"line_spacing_m", "float32", 5.0, 0.1, 1000.0}, + {"heading_deg", "float32", 0.0, 0.0, 360.0}, + }}, + {"Object Search", "tasks/object_search", { + {"object_class", "string", 0, 0, 0}, + {"search_area", "geometry_msgs/Polygon", 0, 0, 0}, + {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, + {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, + {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, + {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, + {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, + {"target_count", "int32", 1, 0, 10000}, + }}, + {"Object Counting", "tasks/object_counting", { + {"object_class", "string", 0, 0, 0}, + {"count_area", "geometry_msgs/Polygon", 0, 0, 0}, + {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, + {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, + {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, + {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, + }}, + {"Semantic Search", "tasks/semantic_search", { + {"query", "string", 0, 0, 0}, + {"search_area", "geometry_msgs/Polygon", 0, 0, 0}, + {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, + {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, + {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, + {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, + {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, + {"confidence_threshold", "float32", 0.5, 0.0, 1.0}, + }}, + {"Fixed Trajectory", "tasks/fixed_trajectory", { + {"trajectory_spec", "airstack_msgs/FixedTrajectory", 0, 0, 0}, + {"loop", "bool", 0, 0, 0}, + }}, + }; +} + +// ─────────────────────────── constructor / init ─────────────────────────────── + +TasksPanel::TasksPanel(QWidget * parent) +: rviz_common::Panel(parent) +{ + task_defs_ = getTaskDefs(); +} + +void TasksPanel::onInitialize() +{ + auto node_abs = getDisplayContext()->getRosNodeAbstraction().lock(); + raw_node_ = node_abs->get_raw_node(); + + // Polygon selection service client + polygon_client_ = + raw_node_->create_client("get_selection"); + + // Waypoints subscription + waypoints_sub_ = raw_node_->create_subscription( + "waypoints", 1, + [this](nav_msgs::msg::Path::SharedPtr msg) { + latest_waypoints_ = msg; + }); + + // Build UI + auto * main_layout = new QVBoxLayout(); + + // Robot selector bar + auto * top_bar = new QHBoxLayout(); + top_bar->addWidget(new QLabel("Robot:")); + robot_combo_ = new QComboBox(); + robot_combo_->setEditable(true); + robot_combo_->setMinimumWidth(120); + top_bar->addWidget(robot_combo_); + auto * refresh_btn = new QPushButton("Refresh"); + connect(refresh_btn, &QPushButton::clicked, this, &TasksPanel::onRefreshExecutors); + top_bar->addWidget(refresh_btn); + top_bar->addStretch(); + main_layout->addLayout(top_bar); + + // Tab widget + tab_widget_ = new QTabWidget(); + main_layout->addWidget(tab_widget_); + + setLayout(main_layout); + + buildTabs(); + + // Discovery timer + refresh_timer_ = new QTimer(this); + connect(refresh_timer_, &QTimer::timeout, this, &TasksPanel::onRefreshExecutors); + refresh_timer_->start(5000); + + // Initial discovery + QTimer::singleShot(500, this, &TasksPanel::onRefreshExecutors); +} + +// ─────────────────────────── build tabs ─────────────────────────────────────── + +void TasksPanel::buildTabs() +{ + tab_states_.resize(task_defs_.size()); + + for (size_t i = 0; i < task_defs_.size(); ++i) { + const auto & def = task_defs_[i]; + auto & state = tab_states_[i]; + + auto * tab = new QWidget(); + auto * splitter = new QSplitter(Qt::Horizontal); + + // ── LEFT: Goal Parameters ── + auto * left_widget = new QWidget(); + auto * left_layout = new QVBoxLayout(left_widget); + + // Executor selector + auto * exec_layout = new QHBoxLayout(); + exec_layout->addWidget(new QLabel("Executor:")); + state.executor_combo = new QComboBox(); + state.executor_combo->setEditable(true); + state.executor_combo->setMinimumWidth(200); + exec_layout->addWidget(state.executor_combo); + left_layout->addLayout(exec_layout); + + // Goal fields + auto * form = new QFormLayout(); + for (const auto & field : def.goal_fields) { + auto * widget = buildGoalFieldWidget(field, static_cast(i)); + state.field_widgets[field.name] = widget; + form->addRow(QString::fromStdString(field.name) + ":", widget); + } + left_layout->addLayout(form); + + left_layout->addStretch(); + + // Cancel / Execute buttons + auto * btn_layout = new QHBoxLayout(); + state.cancel_btn = new QPushButton("Cancel"); + state.cancel_btn->setEnabled(false); + state.execute_btn = new QPushButton("Execute"); + btn_layout->addWidget(state.cancel_btn); + btn_layout->addStretch(); + btn_layout->addWidget(state.execute_btn); + left_layout->addLayout(btn_layout); + + int tab_idx = static_cast(i); + connect(state.execute_btn, &QPushButton::clicked, [this, tab_idx]() { + // store which tab triggered it, then call handler + tab_widget_->setCurrentIndex(tab_idx); + onExecuteClicked(); + }); + connect(state.cancel_btn, &QPushButton::clicked, [this, tab_idx]() { + tab_widget_->setCurrentIndex(tab_idx); + onCancelClicked(); + }); + + // ── RIGHT: Feedback & Result ── + auto * right_widget = new QWidget(); + auto * right_layout = new QVBoxLayout(right_widget); + + right_layout->addWidget(new QLabel("Feedback:")); + state.feedback_display = new QTextEdit(); + state.feedback_display->setReadOnly(true); + state.feedback_display->setMaximumHeight(200); + right_layout->addWidget(state.feedback_display); + + right_layout->addWidget(new QLabel("Result:")); + state.result_display = new QTextEdit(); + state.result_display->setReadOnly(true); + state.result_display->setMaximumHeight(100); + right_layout->addWidget(state.result_display); + + state.status_label = new QLabel("Idle"); + right_layout->addWidget(state.status_label); + right_layout->addStretch(); + + splitter->addWidget(left_widget); + splitter->addWidget(right_widget); + splitter->setStretchFactor(0, 1); + splitter->setStretchFactor(1, 1); + + auto * tab_layout = new QVBoxLayout(tab); + tab_layout->addWidget(splitter); + + tab_widget_->addTab(tab, QString::fromStdString(def.display_name)); + } +} + +QWidget * TasksPanel::buildGoalFieldWidget(const GoalFieldDef & def, int tab_index) +{ + if (def.ros_type == "float32" || def.ros_type == "float64") { + auto * spin = new QDoubleSpinBox(); + spin->setRange(def.min_value, def.max_value); + spin->setValue(def.default_value); + spin->setDecimals(2); + spin->setSingleStep(0.1); + return spin; + } + if (def.ros_type == "int32") { + auto * spin = new QSpinBox(); + spin->setRange(static_cast(def.min_value), static_cast(def.max_value)); + spin->setValue(static_cast(def.default_value)); + return spin; + } + if (def.ros_type == "string") { + return new QLineEdit(); + } + if (def.ros_type == "bool") { + auto * cb = new QCheckBox(); + cb->setChecked(def.default_value != 0.0); + return cb; + } + if (def.ros_type == "geometry_msgs/Polygon") { + auto * container = new QWidget(); + auto * layout = new QVBoxLayout(container); + layout->setContentsMargins(0, 0, 0, 0); + auto * btn = new QPushButton("Get Polygon from RViz"); + auto * label = new QLabel("No polygon selected"); + layout->addWidget(btn); + layout->addWidget(label); + std::string field_name = def.name; + connect(btn, &QPushButton::clicked, [this, tab_index, field_name]() { + onGetPolygon(tab_index, field_name); + }); + return container; + } + if (def.ros_type == "nav_msgs/Path") { + auto * container = new QWidget(); + auto * layout = new QVBoxLayout(container); + layout->setContentsMargins(0, 0, 0, 0); + auto * label = new QLabel("Use Waypoint Tool (key: 1) in RViz"); + auto * status = new QLabel("No waypoints received"); + layout->addWidget(label); + layout->addWidget(status); + // Store status label for updates + tab_states_[tab_index].field_data[def.name + "_status_label"] = status; + return container; + } + if (def.ros_type == "airstack_msgs/FixedTrajectory") { + auto * container = new QWidget(); + auto * layout = new QVBoxLayout(container); + layout->setContentsMargins(0, 0, 0, 0); + + auto * type_combo = new QComboBox(); + type_combo->addItems({"Circle", "Figure8", "Racetrack", "Line", "Point", "Lawnmower"}); + layout->addWidget(type_combo); + + auto * table = new QTableWidget(0, 2); + table->setHorizontalHeaderLabels({"Key", "Value"}); + table->horizontalHeader()->setStretchLastSection(true); + table->setMaximumHeight(150); + layout->addWidget(table); + + auto * add_btn = new QPushButton("+ Add Attribute"); + layout->addWidget(add_btn); + + connect(add_btn, &QPushButton::clicked, [table]() { + int row = table->rowCount(); + table->insertRow(row); + table->setItem(row, 0, new QTableWidgetItem("")); + table->setItem(row, 1, new QTableWidgetItem("")); + }); + + // Store combo and table for later retrieval + tab_states_[tab_index].field_data[def.name + "_type_combo"] = type_combo; + tab_states_[tab_index].field_data[def.name + "_table"] = table; + + connect(type_combo, &QComboBox::currentTextChanged, + [this, tab_index, field_name = def.name](const QString & type) { + onTrajectoryTypeChanged(tab_index, type); + }); + + // Trigger initial population + QTimer::singleShot(0, [type_combo]() { + Q_EMIT type_combo->currentTextChanged(type_combo->currentText()); + }); + + return container; + } + + return new QLabel("(unsupported type: " + QString::fromStdString(def.ros_type) + ")"); +} + +// ─────────────────────────── executor discovery ────────────────────────────── + +void TasksPanel::onRefreshExecutors() +{ + if (!raw_node_) {return;} + + auto topic_map = raw_node_->get_topic_names_and_types(); + + // Collect robot namespaces and per-task executors + std::set robots; + + for (size_t i = 0; i < task_defs_.size(); ++i) { + const std::string suffix = task_defs_[i].action_topic_suffix + "/_action/status"; + QStringList executors; + + for (const auto & [topic, types] : topic_map) { + if (topic.size() > suffix.size() && + topic.substr(topic.size() - suffix.size()) == suffix) + { + // Extract action name (remove /_action/status) + std::string action_name = topic.substr(0, topic.size() - std::string("/_action/status").size()); + executors.append(QString::fromStdString(action_name)); + + // Extract robot namespace (everything before /tasks/...) + std::string task_suffix = task_defs_[i].action_topic_suffix; + size_t pos = action_name.rfind(task_suffix); + if (pos != std::string::npos && pos > 1) { + robots.insert(action_name.substr(0, pos - 1)); // -1 to remove trailing / + } + } + } + + // Update executor combo preserving current selection + auto & combo = tab_states_[i].executor_combo; + QString current = combo->currentText(); + combo->clear(); + combo->addItems(executors); + if (!current.isEmpty()) { + int idx = combo->findText(current); + if (idx >= 0) { + combo->setCurrentIndex(idx); + } else { + combo->setCurrentText(current); + } + } + } + + // Update robot combo + QString current_robot = robot_combo_->currentText(); + robot_combo_->clear(); + for (const auto & r : robots) { + robot_combo_->addItem(QString::fromStdString(r)); + } + if (!current_robot.isEmpty()) { + int idx = robot_combo_->findText(current_robot); + if (idx >= 0) { + robot_combo_->setCurrentIndex(idx); + } else { + robot_combo_->setCurrentText(current_robot); + } + } +} + +// ─────────────────────────── special widgets ────────────────────────────────── + +void TasksPanel::onGetPolygon(int tab_index, const std::string & field_name) +{ + if (!polygon_client_->wait_for_service(std::chrono::seconds(0))) { + tab_states_[tab_index].status_label->setText("Polygon tool not active - press 'p' first"); + return; + } + + auto request = std::make_shared(); + polygon_client_->async_send_request(request, + [this, tab_index, field_name]( + rclcpp::Client::SharedFuture future) + { + auto response = future.get(); + if (response->selection.empty()) { + QMetaObject::invokeMethod(this, [this, tab_index]() { + tab_states_[tab_index].status_label->setText("No polygons drawn"); + }, Qt::QueuedConnection); + return; + } + + // Take first polygon + geometry_msgs::msg::Polygon poly; + for (const auto & pt : response->selection[0].polygon.points) { + geometry_msgs::msg::Point32 p; + p.x = pt.x; + p.y = pt.y; + p.z = pt.z; + poly.points.push_back(p); + } + + QMetaObject::invokeMethod(this, [this, tab_index, field_name, poly]() { + tab_states_[tab_index].field_data[field_name] = poly; + // Update label in the polygon widget + auto * container = tab_states_[tab_index].field_widgets[field_name]; + auto * label = container->findChild(); + if (label) { + label->setText(QString("Polygon: %1 points").arg(poly.points.size())); + } + }, Qt::QueuedConnection); + }); +} + +void TasksPanel::onTrajectoryTypeChanged(int tab_index, const QString & type) +{ + std::string key = "trajectory_spec_table"; + auto it = tab_states_[tab_index].field_data.find(key); + if (it == tab_states_[tab_index].field_data.end()) {return;} + + auto * table = std::any_cast(it->second); + table->setRowCount(0); + + // Default attributes per trajectory type + std::vector> attrs; + if (type == "Circle") { + attrs = {{"frame_id", "base_link"}, {"radius", "5.0"}, {"velocity", "2.0"}}; + } else if (type == "Figure8") { + attrs = {{"frame_id", "base_link"}, {"length", "10.0"}, {"width", "5.0"}, + {"height", "0.0"}, {"velocity", "2.0"}, {"max_acceleration", "1.0"}}; + } else if (type == "Racetrack") { + attrs = {{"frame_id", "base_link"}, {"length", "20.0"}, {"width", "10.0"}, + {"height", "0.0"}, {"velocity", "2.0"}, {"turn_velocity", "1.0"}, + {"max_acceleration", "1.0"}}; + } else if (type == "Line") { + attrs = {{"frame_id", "base_link"}, {"length", "10.0"}, {"height", "0.0"}, + {"velocity", "2.0"}, {"max_acceleration", "1.0"}}; + } else if (type == "Point") { + attrs = {{"frame_id", "base_link"}, {"x", "5.0"}, {"y", "0.0"}, + {"height", "0.0"}, {"velocity", "2.0"}, {"max_acceleration", "1.0"}}; + } else if (type == "Lawnmower") { + attrs = {{"frame_id", "base_link"}, {"length", "20.0"}, {"width", "5.0"}, + {"height", "10.0"}, {"velocity", "2.0"}, {"vertical", "0"}}; + } + + for (const auto & [k, v] : attrs) { + int row = table->rowCount(); + table->insertRow(row); + table->setItem(row, 0, new QTableWidgetItem(QString::fromStdString(k))); + table->setItem(row, 1, new QTableWidgetItem(QString::fromStdString(v))); + } +} + +// ─────────────────────────── value extraction ───────────────────────────────── + +double TasksPanel::getFloat(int tab_index, const std::string & field_name) +{ + auto * w = tab_states_[tab_index].field_widgets[field_name]; + if (auto * spin = qobject_cast(w)) {return spin->value();} + return 0.0; +} + +int32_t TasksPanel::getInt(int tab_index, const std::string & field_name) +{ + auto * w = tab_states_[tab_index].field_widgets[field_name]; + if (auto * spin = qobject_cast(w)) {return spin->value();} + return 0; +} + +std::string TasksPanel::getString(int tab_index, const std::string & field_name) +{ + auto * w = tab_states_[tab_index].field_widgets[field_name]; + if (auto * edit = qobject_cast(w)) {return edit->text().toStdString();} + return ""; +} + +bool TasksPanel::getBool(int tab_index, const std::string & field_name) +{ + auto * w = tab_states_[tab_index].field_widgets[field_name]; + if (auto * cb = qobject_cast(w)) {return cb->isChecked();} + return false; +} + +geometry_msgs::msg::Polygon TasksPanel::getPolygon(int tab_index, const std::string & field_name) +{ + auto it = tab_states_[tab_index].field_data.find(field_name); + if (it != tab_states_[tab_index].field_data.end()) { + return std::any_cast(it->second); + } + return geometry_msgs::msg::Polygon(); +} + +nav_msgs::msg::Path TasksPanel::getPath(int, const std::string &) +{ + if (latest_waypoints_) {return *latest_waypoints_;} + return nav_msgs::msg::Path(); +} + +airstack_msgs::msg::FixedTrajectory TasksPanel::getFixedTrajectory( + int tab_index, const std::string & field_name) +{ + airstack_msgs::msg::FixedTrajectory ft; + + auto combo_it = tab_states_[tab_index].field_data.find(field_name + "_type_combo"); + if (combo_it != tab_states_[tab_index].field_data.end()) { + auto * combo = std::any_cast(combo_it->second); + ft.type = combo->currentText().toStdString(); + } + + auto table_it = tab_states_[tab_index].field_data.find(field_name + "_table"); + if (table_it != tab_states_[tab_index].field_data.end()) { + auto * table = std::any_cast(table_it->second); + for (int row = 0; row < table->rowCount(); ++row) { + diagnostic_msgs::msg::KeyValue kv; + kv.key = table->item(row, 0)->text().toStdString(); + kv.value = table->item(row, 1)->text().toStdString(); + ft.attributes.push_back(kv); + } + } + + return ft; +} + +// ─────────────────────────── UI state helpers ───────────────────────────────── + +void TasksPanel::setGoalActive(int tab_index, bool active) +{ + auto & state = tab_states_[tab_index]; + state.goal_active = active; + state.execute_btn->setEnabled(!active); + state.cancel_btn->setEnabled(active); + if (active) { + state.feedback_display->clear(); + state.result_display->clear(); + state.status_label->setText("Running..."); + state.status_label->setStyleSheet("color: blue;"); + } +} + +QString TasksPanel::currentRobot() const +{ + return robot_combo_->currentText(); +} + +// ─────────────────────────── template: send/cancel ──────────────────────────── + +template +void TasksPanel::doSendGoal( + int tab_index, + const typename ActionT::Goal & goal, + std::function fmt_feedback, + std::function fmt_result) +{ + auto & state = tab_states_[tab_index]; + std::string action_name = state.executor_combo->currentText().toStdString(); + if (action_name.empty()) { + state.status_label->setText("No executor selected"); + state.status_label->setStyleSheet("color: red;"); + return; + } + + auto client = rclcpp_action::create_client(raw_node_, action_name); + state.action_client = client; + + if (!client->wait_for_action_server(std::chrono::seconds(2))) { + state.status_label->setText("Action server not available"); + state.status_label->setStyleSheet("color: red;"); + return; + } + + setGoalActive(tab_index, true); + + auto send_goal_options = typename rclcpp_action::Client::SendGoalOptions(); + + // Feedback callback + send_goal_options.feedback_callback = + [this, tab_index, fmt_feedback]( + typename rclcpp_action::ClientGoalHandle::SharedPtr, + const std::shared_ptr feedback) + { + QString text = fmt_feedback(*feedback); + QMetaObject::invokeMethod(this, [this, tab_index, text]() { + auto & state = tab_states_[tab_index]; + state.feedback_display->append( + "[" + QTime::currentTime().toString("HH:mm:ss") + "] " + text); + // Auto-scroll to bottom + auto cursor = state.feedback_display->textCursor(); + cursor.movePosition(QTextCursor::End); + state.feedback_display->setTextCursor(cursor); + }, Qt::QueuedConnection); + }; + + // Result callback + send_goal_options.result_callback = + [this, tab_index, fmt_result]( + const typename rclcpp_action::ClientGoalHandle::WrappedResult & wrapped_result) + { + QString result_text; + QString status_text; + QString color; + + switch (wrapped_result.code) { + case rclcpp_action::ResultCode::SUCCEEDED: + result_text = fmt_result(wrapped_result.result); + status_text = "Succeeded"; + color = "color: green;"; + break; + case rclcpp_action::ResultCode::ABORTED: + result_text = fmt_result(wrapped_result.result); + status_text = "Aborted"; + color = "color: red;"; + break; + case rclcpp_action::ResultCode::CANCELED: + result_text = "Goal canceled"; + status_text = "Canceled"; + color = "color: orange;"; + break; + default: + result_text = "Unknown result"; + status_text = "Unknown"; + color = "color: gray;"; + break; + } + + QMetaObject::invokeMethod(this, [this, tab_index, result_text, status_text, color]() { + auto & state = tab_states_[tab_index]; + state.result_display->setText(result_text); + state.status_label->setText(status_text); + state.status_label->setStyleSheet(color); + setGoalActive(tab_index, false); + }, Qt::QueuedConnection); + }; + + auto goal_future = client->async_send_goal(goal, send_goal_options); +} + +template +void TasksPanel::doCancelGoal(int tab_index) +{ + auto & state = tab_states_[tab_index]; + try { + auto client = std::any_cast::SharedPtr>( + state.action_client); + client->async_cancel_all_goals(); + state.status_label->setText("Cancelling..."); + state.status_label->setStyleSheet("color: orange;"); + } catch (const std::bad_any_cast &) { + state.status_label->setText("No active goal to cancel"); + } +} + +// ─────────────────────────── execute dispatch ───────────────────────────────── + +void TasksPanel::onExecuteClicked() +{ + int idx = tab_widget_->currentIndex(); + if (idx < 0 || idx >= static_cast(tab_states_.size())) {return;} + if (tab_states_[idx].goal_active) {return;} + + switch (idx) { + case 0: { // Takeoff + task_msgs::action::TakeoffTask::Goal goal; + goal.target_altitude_m = getFloat(0, "target_altitude_m"); + goal.velocity_m_s = getFloat(0, "velocity_m_s"); + doSendGoal(0, goal, + [](const auto & fb) { + return QString("status: %1 | alt: %2 / %3 m") + .arg(QString::fromStdString(fb.status)) + .arg(fb.current_altitude_m, 0, 'f', 1) + .arg(fb.target_altitude_m, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)); + }); + break; + } + case 1: { // Land + task_msgs::action::LandTask::Goal goal; + goal.velocity_m_s = getFloat(1, "velocity_m_s"); + doSendGoal(1, goal, + [](const auto & fb) { + return QString("status: %1 | alt: %2 m") + .arg(QString::fromStdString(fb.status)) + .arg(fb.current_altitude_m, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)); + }); + break; + } + case 2: { // Navigate + task_msgs::action::NavigateTask::Goal goal; + goal.global_plan = getPath(2, "global_plan"); + goal.goal_tolerance_m = getFloat(2, "goal_tolerance_m"); + doSendGoal(2, goal, + [](const auto & fb) { + return QString("status: %1 | dist: %2 m | pos: (%3, %4, %5)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.distance_to_goal, 0, 'f', 1) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)); + }); + break; + } + case 3: { // Exploration + task_msgs::action::ExplorationTask::Goal goal; + goal.search_bounds = getPolygon(3, "search_bounds"); + goal.min_altitude_agl = getFloat(3, "min_altitude_agl"); + goal.max_altitude_agl = getFloat(3, "max_altitude_agl"); + goal.min_flight_speed = getFloat(3, "min_flight_speed"); + goal.max_flight_speed = getFloat(3, "max_flight_speed"); + goal.time_limit_sec = getFloat(3, "time_limit_sec"); + doSendGoal(3, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | pos: (%3, %4, %5)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)); + }); + break; + } + case 4: { // Coverage + task_msgs::action::CoverageTask::Goal goal; + goal.coverage_area = getPolygon(4, "coverage_area"); + goal.min_altitude_agl = getFloat(4, "min_altitude_agl"); + goal.max_altitude_agl = getFloat(4, "max_altitude_agl"); + goal.min_flight_speed = getFloat(4, "min_flight_speed"); + goal.max_flight_speed = getFloat(4, "max_flight_speed"); + goal.line_spacing_m = getFloat(4, "line_spacing_m"); + goal.heading_deg = getFloat(4, "heading_deg"); + doSendGoal(4, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | coverage: %3% | pos: (%4, %5, %6)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.coverage_percentage, 0, 'f', 1) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2\ncoverage: %3%") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)) + .arg(r->coverage_percentage, 0, 'f', 1); + }); + break; + } + case 5: { // Object Search + task_msgs::action::ObjectSearchTask::Goal goal; + goal.object_class = getString(5, "object_class"); + goal.search_area = getPolygon(5, "search_area"); + goal.min_altitude_agl = getFloat(5, "min_altitude_agl"); + goal.max_altitude_agl = getFloat(5, "max_altitude_agl"); + goal.min_flight_speed = getFloat(5, "min_flight_speed"); + goal.max_flight_speed = getFloat(5, "max_flight_speed"); + goal.time_limit_sec = getFloat(5, "time_limit_sec"); + goal.target_count = getInt(5, "target_count"); + doSendGoal(5, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | found: %3 | pos: (%4, %5, %6)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.objects_found_so_far) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2\nobjects_found: %3") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)) + .arg(r->objects_found); + }); + break; + } + case 6: { // Object Counting + task_msgs::action::ObjectCountingTask::Goal goal; + goal.object_class = getString(6, "object_class"); + goal.count_area = getPolygon(6, "count_area"); + goal.min_altitude_agl = getFloat(6, "min_altitude_agl"); + goal.max_altitude_agl = getFloat(6, "max_altitude_agl"); + goal.min_flight_speed = getFloat(6, "min_flight_speed"); + goal.max_flight_speed = getFloat(6, "max_flight_speed"); + doSendGoal(6, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | count: %3 | pos: (%4, %5, %6)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.current_count) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2\ncount: %3") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)) + .arg(r->count); + }); + break; + } + case 7: { // Semantic Search + task_msgs::action::SemanticSearchTask::Goal goal; + goal.query = getString(7, "query"); + goal.search_area = getPolygon(7, "search_area"); + goal.min_altitude_agl = getFloat(7, "min_altitude_agl"); + goal.max_altitude_agl = getFloat(7, "max_altitude_agl"); + goal.min_flight_speed = getFloat(7, "min_flight_speed"); + goal.max_flight_speed = getFloat(7, "max_flight_speed"); + goal.time_limit_sec = getFloat(7, "time_limit_sec"); + goal.confidence_threshold = getFloat(7, "confidence_threshold"); + doSendGoal(7, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | best_conf: %3 | pos: (%4, %5, %6)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.best_confidence_so_far, 0, 'f', 3) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2\nconfidence: %3") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)) + .arg(r->confidence, 0, 'f', 3); + }); + break; + } + case 8: { // Fixed Trajectory + task_msgs::action::FixedTrajectoryTask::Goal goal; + goal.trajectory_spec = getFixedTrajectory(8, "trajectory_spec"); + goal.loop = getBool(8, "loop"); + doSendGoal(8, goal, + [](const auto & fb) { + return QString("status: %1 | progress: %2 | pos: (%3, %4, %5)") + .arg(QString::fromStdString(fb.status)) + .arg(fb.progress, 0, 'f', 2) + .arg(fb.current_position.x, 0, 'f', 1) + .arg(fb.current_position.y, 0, 'f', 1) + .arg(fb.current_position.z, 0, 'f', 1); + }, + [](const auto & r) { + return QString("success: %1\nmessage: %2") + .arg(r->success ? "true" : "false") + .arg(QString::fromStdString(r->message)); + }); + break; + } + } +} + +// ─────────────────────────── cancel dispatch ────────────────────────────────── + +void TasksPanel::onCancelClicked() +{ + int idx = tab_widget_->currentIndex(); + if (idx < 0 || idx >= static_cast(tab_states_.size())) {return;} + if (!tab_states_[idx].goal_active) {return;} + + switch (idx) { + case 0: doCancelGoal(0); break; + case 1: doCancelGoal(1); break; + case 2: doCancelGoal(2); break; + case 3: doCancelGoal(3); break; + case 4: doCancelGoal(4); break; + case 5: doCancelGoal(5); break; + case 6: doCancelGoal(6); break; + case 7: doCancelGoal(7); break; + case 8: doCancelGoal(8); break; + } +} + +// ─────────────────────────── config persistence ────────────────────────────── + +void TasksPanel::save(rviz_common::Config config) const +{ + rviz_common::Panel::save(config); + config.mapSetValue("robot", robot_combo_->currentText()); + for (size_t i = 0; i < tab_states_.size(); ++i) { + config.mapSetValue( + QString("executor_%1").arg(i), + tab_states_[i].executor_combo->currentText()); + } +} + +void TasksPanel::load(const rviz_common::Config & config) +{ + rviz_common::Panel::load(config); + QString robot; + if (config.mapGetString("robot", &robot)) { + robot_combo_->setCurrentText(robot); + } + for (size_t i = 0; i < tab_states_.size(); ++i) { + QString executor; + if (config.mapGetString(QString("executor_%1").arg(i), &executor)) { + tab_states_[i].executor_combo->setCurrentText(executor); + } + } +} + +} // namespace rviz_tasks_panel + +PLUGINLIB_EXPORT_CLASS(rviz_tasks_panel::TasksPanel, rviz_common::Panel) From ea81bea1485b24779dd42cf35540b94ca3e727dd Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Fri, 10 Apr 2026 14:20:16 -0400 Subject: [PATCH 09/24] Add docs to tasks panel, ensure only one task execute at a time --- .../desktop_bringup/rviz/robot.rviz | 72 +++------- .../gui/rviz/rviz_tasks_panel/README.md | 133 ++++++++++++++++++ .../include/rviz_tasks_panel/tasks_panel.hpp | 5 + .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 47 ++++++- .../local_bringup/launch/local.launch.xml | 2 + .../launch/local_droan_cpu.launch.xml | 2 + .../takeoff_landing_task.hpp | 5 +- .../src/takeoff_landing_task.cpp | 51 +++++-- 8 files changed, 251 insertions(+), 66 deletions(-) create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/README.md diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 183df82e9..9561dd1cc 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -15,7 +15,7 @@ Panels: - /Global1 - /Global1/Global Plan1 Splitter Ratio: 0.3440559506416321 - Tree Height: 480 + Tree Height: 330 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -33,11 +33,23 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: StereoImageProc Disparity + SyncSource: "" - Class: rviz_behavior_tree_panel::BehaviorTreePanel Name: BehaviorTreePanel - topic: behavior/behavior_tree_graphviz + topic: /robot_1/behavior/behavior_tree_graphviz zoom_factor: 0.1919851303100586 + - Class: rviz_tasks_panel::TasksPanel + Name: TasksPanel + executor_0: /robot_1/tasks/takeoff + executor_1: /robot_1/tasks/land + executor_2: /robot_1/tasks/navigate + executor_3: /robot_1/tasks/exploration + executor_4: "" + executor_5: "" + executor_6: "" + executor_7: "" + executor_8: /robot_1/tasks/fixed_trajectory + robot: /robot_1 Visualization Manager: Class: "" Displays: @@ -76,8 +88,6 @@ Visualization Manager: Value: false base_link_frd: Value: true - base_link_stabilized: - Value: false camera_left: Value: true camera_right: @@ -86,12 +96,6 @@ Visualization Manager: Value: false lidar: Value: false - look_ahead_point: - Value: false - look_ahead_point_stabilized: - Value: false - macvo_ned: - Value: false map: Value: true map_ned: @@ -108,10 +112,6 @@ Visualization Manager: Value: true rotor3: Value: true - tracking_point: - Value: false - tracking_point_stabilized: - Value: false world: Value: false Marker Scale: 0.30000001192092896 @@ -122,41 +122,8 @@ Visualization Manager: Tree: world: map: - base_link: - base_link_body_body_link: - OS1_REV6_128_10hz___512_resolution: - lidar: - {} - base_link_ZED_X: - camera_left: - macvo_ned: - {} - camera_right: - {} - imu: - {} - rotor0: - {} - rotor1: - {} - rotor2: - {} - rotor3: - {} - base_link_frd: - {} - base_link_stabilized: - {} - look_ahead_point: - {} - look_ahead_point_stabilized: - {} map_ned: {} - tracking_point: - {} - tracking_point_stabilized: - {} Update Interval: 0 Value: true - Alpha: 0.5 @@ -687,8 +654,7 @@ Visualization Manager: Enabled: true Name: Traj Vis Namespaces: - traj_controller: true - traj_controller_extra_text: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -718,7 +684,7 @@ Visualization Manager: Enabled: true Name: VDB Mapping Marker Namespaces: - "": true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -853,9 +819,11 @@ Window Geometry: collapsed: false MACVO Disparity: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Selection: collapsed: false + TasksPanel: + collapsed: false Time: collapsed: false Tool Properties: diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md new file mode 100644 index 000000000..2cb7aa790 --- /dev/null +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md @@ -0,0 +1,133 @@ +# RViz Tasks Panel + +RViz2 panel plugin for dispatching and monitoring ROS 2 task action goals. Provides a tabbed GUI where operators can parameterize, execute, and cancel tasks on any discovered robot, with live feedback and result display. + +## Overview + +The Tasks Panel replaces the need for CLI-based action goal dispatch by providing a graphical interface for all 9 AirStack task types. Each task type gets its own tab with auto-generated parameter widgets, an executor selector, and a feedback/result view. + +``` +┌──────────────────────────────────────────────────────────────────────┐ +│ Tasks Panel Robot: [robot_1] │ +├──────────────────────────────────────────────────────────────────────┤ +│ [Takeoff] [Land] [Navigate] [Exploration] [Coverage] [ObjectSearch] │ +├──────────────────────────────────────────────────────────────────────┤ +│ ┌─ Goal Parameters ────────┐ ┌─ Feedback & Result ─────────────┐ │ +│ │ Executor: [/robot_1/...] │ │ Feedback: │ │ +│ │ target_altitude_m: [5.0] │ │ [live feedback stream] │ │ +│ │ velocity_m_s: [1.0] │ │ │ │ +│ │ │ │ Result: │ │ +│ │ [Cancel] [Execute] │ │ [goal outcome] │ │ +│ └──────────────────────────┘ └─────────────────────────────────┘ │ +└──────────────────────────────────────────────────────────────────────┘ +``` + +## Features + +- **9 task tabs** with auto-generated goal parameter widgets +- **Executor discovery** -- scans ROS 2 topics every 5 seconds to find running action servers +- **Robot namespace selector** -- auto-populated from discovered action server namespaces +- **Polygon input** -- integrates with `rviz_polygon_selection_tool` to capture 3D polygon selections from the RViz viewport +- **Waypoint input** -- subscribes to the `waypoints` topic to receive paths from the 3D Waypoint tool +- **Fixed Trajectory editor** -- type dropdown with auto-populated default attributes in an editable key-value table +- **Live feedback** -- timestamped feedback messages stream in real time +- **Result display** -- color-coded status (green for succeeded, red for aborted/canceled) +- **Config persistence** -- robot and executor selections are saved/restored with the RViz config +- **Active Tab Status** -- tab text color reflect active/running task status, GUI only allows one action to execute at a time per robot to prevent conflicts + +## Supported Task Types + +| Tab | Action Type | Key Parameters | +|-----|-------------|----------------| +| Takeoff | `task_msgs/action/TakeoffTask` | `target_altitude_m`, `velocity_m_s` | +| Land | `task_msgs/action/LandTask` | `velocity_m_s` | +| Navigate | `task_msgs/action/NavigateTask` | `global_plan` (Path), `goal_tolerance_m` | +| Exploration | `task_msgs/action/ExplorationTask` | `search_bounds` (Polygon), altitude/speed limits, `time_limit_sec` | +| Coverage | `task_msgs/action/CoverageTask` | `coverage_area` (Polygon), altitude/speed limits, `line_spacing_m`, `heading_deg` | +| Object Search | `task_msgs/action/ObjectSearchTask` | `object_class`, `search_area` (Polygon), `target_count`, `time_limit_sec` | +| Object Counting | `task_msgs/action/ObjectCountingTask` | `object_class`, `count_area` (Polygon), altitude/speed limits | +| Semantic Search | `task_msgs/action/SemanticSearchTask` | `query`, `search_area` (Polygon), `confidence_threshold`, `time_limit_sec` | +| Fixed Trajectory | `task_msgs/action/FixedTrajectoryTask` | `trajectory_spec` (FixedTrajectory), `loop` | + +## Widget Type Mapping + +Goal fields are mapped to Qt widgets based on their ROS type: + +| ROS Type | Widget | Notes | +|----------|--------|-------| +| `float32` / `float64` | `QDoubleSpinBox` | Range and default from task registry | +| `int32` | `QSpinBox` | Range and default from task registry | +| `string` | `QLineEdit` | Free-text input | +| `bool` | `QCheckBox` | Toggle | +| `geometry_msgs/Polygon` | `QPushButton` | Calls `get_selection` service on `rviz_polygon_selection_tool` | +| `nav_msgs/Path` | Status label | Displays latest path from `waypoints` subscription | +| `airstack_msgs/FixedTrajectory` | `QComboBox` + `QTableWidget` | Type selector with editable attribute table | + +## Dependencies + +- `rviz_common` -- RViz2 panel base class +- `pluginlib` -- plugin loading +- `rclcpp` / `rclcpp_action` -- ROS 2 node and action client +- `task_msgs` -- action definitions for all 9 task types +- `airstack_msgs` -- `FixedTrajectory` message +- `geometry_msgs` / `nav_msgs` -- standard ROS 2 message types +- `diagnostic_msgs` / `action_msgs` -- status and action introspection +- `rviz_polygon_selection_tool` -- polygon selection service +- Qt5 (Core, Widgets, Gui) + +## Build + +```bash +docker exec airstack-robot-desktop-1 bash -c "bws --packages-select rviz_tasks_panel" +``` + +## Usage + +1. Launch RViz2 +2. Go to **Panels > Add New Panel** +3. Select **rviz_tasks_panel / TasksPanel** +4. The panel auto-discovers running task action servers and populates the Robot dropdown +5. Select a tab, configure goal parameters, and click **Execute** +6. Monitor feedback in the right pane; click **Cancel** to abort a running goal + +### Polygon Selection + +For tasks requiring a polygon boundary (Exploration, Coverage, Object Search, etc.): + +1. Activate the **Polygon Selection Tool** in the RViz toolbar +2. Draw a polygon in the 3D viewport +3. In the Tasks Panel, click the **Get Polygon from RViz** button for the polygon field +4. The panel calls the `get_selection` service and displays the captured point count + +### Waypoint Navigation + +For the Navigate task: + +1. Use the **3D Waypoint Tool** in RViz to place waypoints +2. The Tasks Panel subscribes to the `waypoints` topic and caches the latest path +3. Click **Get Waypoints from RViz** to capture the current path + +### Fixed Trajectory + +1. Select a trajectory type from the dropdown (e.g., `circle`, `lemniscate`, `fixed_trajectory`) +2. Default attributes are pre-populated in the key-value table +3. Edit attribute values as needed, then click **Execute** + +## Executor Discovery + +The panel scans `node->get_topic_names_and_types()` for topics matching the pattern `*//_action/status`. For each match, it extracts the robot namespace prefix (e.g., `/robot_1`) and populates: + +- The top-level **Robot** dropdown with discovered namespaces +- Each tab's **Executor** dropdown with the full action server topic + +Discovery runs automatically every 5 seconds and can be triggered manually with the **Refresh** button. + +## Architecture + +- **Compile-time task registry**: `getTaskDefs()` returns a static vector of `TaskTypeDef` structs defining all 9 task types, their action topic suffixes, and goal field definitions. +- **Type-erased action clients**: Since `rclcpp_action::Client` is templated, the panel uses `std::any` to store type-erased clients and goal handles per tab, with a 9-way switch in `onExecuteClicked()` / `onCancelClicked()` for dispatch. +- **Thread safety**: ROS 2 action callbacks arrive on the ROS executor thread. All Qt widget updates from callbacks use `QMetaObject::invokeMethod(this, lambda, Qt::QueuedConnection)` to marshal back to the Qt main thread. + +## License + +MIT -- Carnegie Mellon University diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp index 0d27b8de5..9dd95078b 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp @@ -120,6 +120,9 @@ private Q_SLOTS: rclcpp::Subscription::SharedPtr waypoints_sub_; nav_msgs::msg::Path::SharedPtr latest_waypoints_; + // Global task lock: only one task may run at a time + int active_task_tab_{-1}; // -1 = no task running, else = tab index of active task + // Discovery timer QTimer * refresh_timer_{nullptr}; @@ -149,6 +152,8 @@ private Q_SLOTS: void doCancelGoal(int tab_index); void setGoalActive(int tab_index, bool active); + void setTabStatusColor(int tab_index, const QColor & color); + void clearTabStatusColor(int tab_index); QString currentRobot() const; }; diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp index 051fdf1f2..ff9f99791 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -5,6 +5,8 @@ #include #include +#include +#include #include #include #include @@ -17,6 +19,7 @@ namespace rviz_tasks_panel std::vector TasksPanel::getTaskDefs() { + // default, min, max return { {"Takeoff", "tasks/takeoff", { {"target_altitude_m", "float32", 5.0, 0.0, 500.0}, @@ -545,16 +548,41 @@ void TasksPanel::setGoalActive(int tab_index, bool active) { auto & state = tab_states_[tab_index]; state.goal_active = active; - state.execute_btn->setEnabled(!active); state.cancel_btn->setEnabled(active); + if (active) { + active_task_tab_ = tab_index; state.feedback_display->clear(); state.result_display->clear(); state.status_label->setText("Running..."); state.status_label->setStyleSheet("color: blue;"); + setTabStatusColor(tab_index, Qt::blue); + } else { + active_task_tab_ = -1; + } + + // Disable all Execute buttons while any task is running + for (size_t i = 0; i < tab_states_.size(); ++i) { + tab_states_[i].execute_btn->setEnabled(active_task_tab_ == -1); } } +void TasksPanel::setTabStatusColor(int tab_index, const QColor & color) +{ + tab_widget_->tabBar()->setTabTextColor(tab_index, color); + // Create a small colored icon as a visual border/indicator + // TODO: replace this with icons later to denote state more clearly (e.g. clock for running, green check for success, red X for failure) + QPixmap px(12, 4); + px.fill(color); + tab_widget_->setTabIcon(tab_index, QIcon(px)); +} + +void TasksPanel::clearTabStatusColor(int tab_index) +{ + tab_widget_->tabBar()->setTabTextColor(tab_index, QColor()); + tab_widget_->setTabIcon(tab_index, QIcon()); +} + QString TasksPanel::currentRobot() const { return robot_combo_->currentText(); @@ -586,6 +614,10 @@ void TasksPanel::doSendGoal( return; } + // Reset all tab colors from previous task results + for (size_t i = 0; i < tab_states_.size(); ++i) { + clearTabStatusColor(static_cast(i)); + } setGoalActive(tab_index, true); auto send_goal_options = typename rclcpp_action::Client::SendGoalOptions(); @@ -616,35 +648,42 @@ void TasksPanel::doSendGoal( QString result_text; QString status_text; QString color; + QColor tab_color; switch (wrapped_result.code) { case rclcpp_action::ResultCode::SUCCEEDED: result_text = fmt_result(wrapped_result.result); status_text = "Succeeded"; - color = "color: green;"; + color = "color: darkGreen;"; + tab_color = Qt::darkGreen; break; case rclcpp_action::ResultCode::ABORTED: result_text = fmt_result(wrapped_result.result); status_text = "Aborted"; color = "color: red;"; + tab_color = Qt::red; break; case rclcpp_action::ResultCode::CANCELED: result_text = "Goal canceled"; status_text = "Canceled"; color = "color: orange;"; + tab_color = QColor("orange"); break; default: result_text = "Unknown result"; status_text = "Unknown"; color = "color: gray;"; + tab_color = Qt::gray; break; } - QMetaObject::invokeMethod(this, [this, tab_index, result_text, status_text, color]() { + QMetaObject::invokeMethod(this, [this, tab_index, result_text, status_text, color, + tab_color]() { auto & state = tab_states_[tab_index]; state.result_display->setText(result_text); state.status_label->setText(status_text); state.status_label->setStyleSheet(color); + setTabStatusColor(tab_index, tab_color); setGoalActive(tab_index, false); }, Qt::QueuedConnection); }; @@ -673,7 +712,7 @@ void TasksPanel::onExecuteClicked() { int idx = tab_widget_->currentIndex(); if (idx < 0 || idx >= static_cast(tab_states_.size())) {return;} - if (tab_states_[idx].goal_active) {return;} + if (active_task_tab_ >= 0) {return;} // only one task at a time switch (idx) { case 0: { // Takeoff diff --git a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml index 755cd50ed..fd46b9282 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local.launch.xml @@ -33,6 +33,8 @@ to="/$(env ROBOT_NAME)/behavior/drone_safety_monitor/state_estimate_timed_out" /> +
diff --git a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml index b4a708f52..453674779 100644 --- a/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml +++ b/robot/ros_ws/src/local/local_bringup/launch/local_droan_cpu.launch.xml @@ -33,6 +33,8 @@ to="/$(env ROBOT_NAME)/behavior/drone_safety_monitor/state_estimate_timed_out" /> +
diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp index c71d4be9c..36e282dba 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -28,6 +28,7 @@ #include #include #include +#include #include #include #include @@ -99,8 +100,9 @@ class TakeoffLandingTaskNode : public rclcpp::Node // publishers rclcpp::Publisher::SharedPtr traj_override_pub_; - // service client + // service clients rclcpp::Client::SharedPtr traj_mode_client_; + rclcpp::Client::SharedPtr robot_command_client_; // action servers rclcpp_action::Server::SharedPtr takeoff_server_; @@ -113,6 +115,7 @@ class TakeoffLandingTaskNode : public rclcpp::Node // helpers bool set_trajectory_mode(int32_t mode); + bool send_robot_command(uint8_t command); // TakeoffTask action server callbacks rclcpp_action::GoalResponse takeoff_handle_goal( diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp index 11aefa0cd..7de50ace8 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -80,9 +80,11 @@ TakeoffLandingTaskNode::TakeoffLandingTaskNode() traj_override_pub_ = this->create_publisher("trajectory_override", 1); - // service client + // service clients traj_mode_client_ = this->create_client("set_trajectory_mode"); + robot_command_client_ = + this->create_client("robot_command"); // action servers takeoff_server_ = rclcpp_action::create_server( @@ -142,6 +144,19 @@ bool TakeoffLandingTaskNode::set_trajectory_mode(int32_t mode) return future.get()->success; } +bool TakeoffLandingTaskNode::send_robot_command(uint8_t command) +{ + if (!robot_command_client_->wait_for_service(std::chrono::seconds(2))) { + RCLCPP_ERROR(this->get_logger(), "robot_command service not available"); + return false; + } + auto request = std::make_shared(); + request->command = command; + auto future = robot_command_client_->async_send_request(request); + future.wait(); + return future.get()->success; +} + // ─────────────────────────── TakeoffTask ────────────────────────────────────── rclcpp_action::GoalResponse TakeoffLandingTaskNode::takeoff_handle_goal( @@ -156,14 +171,6 @@ rclcpp_action::GoalResponse TakeoffLandingTaskNode::takeoff_handle_goal( RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: state estimate timed out"); return rclcpp_action::GoalResponse::REJECT; } - if (!is_armed_) { - RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: not armed"); - return rclcpp_action::GoalResponse::REJECT; - } - if (!has_control_) { - RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: no offboard control"); - return rclcpp_action::GoalResponse::REJECT; - } if (goal->target_altitude_m <= 0.0f) { RCLCPP_WARN(this->get_logger(), "TakeoffTask rejected: target_altitude_m must be positive"); return rclcpp_action::GoalResponse::REJECT; @@ -212,6 +219,32 @@ void TakeoffLandingTaskNode::takeoff_execute(std::shared_ptr wait_rate.sleep(); } + // arm the robot + if (!is_armed_) { + RCLCPP_INFO(this->get_logger(), "TakeoffTask: arming robot"); + if (!send_robot_command(airstack_msgs::srv::RobotCommand::Request::ARM)) { + RCLCPP_ERROR(this->get_logger(), "TakeoffTask aborted: failed to arm"); + result->success = false; + result->message = "failed to arm"; + goal_handle->abort(result); + task_active_ = false; + return; + } + } + + // request offboard control + if (!has_control_) { + RCLCPP_INFO(this->get_logger(), "TakeoffTask: requesting offboard control"); + if (!send_robot_command(airstack_msgs::srv::RobotCommand::Request::REQUEST_CONTROL)) { + RCLCPP_ERROR(this->get_logger(), "TakeoffTask aborted: failed to request offboard control"); + result->success = false; + result->message = "failed to request offboard control"; + goal_handle->abort(result); + task_active_ = false; + return; + } + } + // set trajectory mode to TRACK if (!set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::TRACK)) { result->success = false; From 4d7661355558243aa0db66297e2b163e1be934a6 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Fri, 10 Apr 2026 14:58:15 -0400 Subject: [PATCH 10/24] Try add icons but they're rendering as blocks, idk why --- .../include/rviz_tasks_panel/tasks_panel.hpp | 4 +- .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 41 ++++++++++--------- 2 files changed, 24 insertions(+), 21 deletions(-) diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp index 9dd95078b..d873e4604 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp @@ -152,8 +152,8 @@ private Q_SLOTS: void doCancelGoal(int tab_index); void setGoalActive(int tab_index, bool active); - void setTabStatusColor(int tab_index, const QColor & color); - void clearTabStatusColor(int tab_index); + void setTabStatus(int tab_index, const QString & icon, const QColor & text_color); + void clearTabStatus(int tab_index); QString currentRobot() const; }; diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp index ff9f99791..2f2b32e66 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -5,7 +5,6 @@ #include #include -#include #include #include #include @@ -126,6 +125,7 @@ void TasksPanel::onInitialize() // Tab widget tab_widget_ = new QTabWidget(); + tab_widget_->setFont(QFont("Noto Sans", 10)); main_layout->addWidget(tab_widget_); setLayout(main_layout); @@ -556,7 +556,7 @@ void TasksPanel::setGoalActive(int tab_index, bool active) state.result_display->clear(); state.status_label->setText("Running..."); state.status_label->setStyleSheet("color: blue;"); - setTabStatusColor(tab_index, Qt::blue); + setTabStatus(tab_index, QString::fromUtf8(u8"⏳"), Qt::blue); } else { active_task_tab_ = -1; } @@ -567,20 +567,18 @@ void TasksPanel::setGoalActive(int tab_index, bool active) } } -void TasksPanel::setTabStatusColor(int tab_index, const QColor & color) +void TasksPanel::setTabStatus(int tab_index, const QString & icon, const QColor & text_color) { - tab_widget_->tabBar()->setTabTextColor(tab_index, color); - // Create a small colored icon as a visual border/indicator - // TODO: replace this with icons later to denote state more clearly (e.g. clock for running, green check for success, red X for failure) - QPixmap px(12, 4); - px.fill(color); - tab_widget_->setTabIcon(tab_index, QIcon(px)); + tab_widget_->tabBar()->setTabTextColor(tab_index, text_color); + const auto & def = task_defs_[tab_index]; + tab_widget_->setTabText(tab_index, icon + " " + QString::fromStdString(def.display_name)); } -void TasksPanel::clearTabStatusColor(int tab_index) +void TasksPanel::clearTabStatus(int tab_index) { tab_widget_->tabBar()->setTabTextColor(tab_index, QColor()); - tab_widget_->setTabIcon(tab_index, QIcon()); + const auto & def = task_defs_[tab_index]; + tab_widget_->setTabText(tab_index, QString::fromStdString(def.display_name)); } QString TasksPanel::currentRobot() const @@ -616,7 +614,7 @@ void TasksPanel::doSendGoal( // Reset all tab colors from previous task results for (size_t i = 0; i < tab_states_.size(); ++i) { - clearTabStatusColor(static_cast(i)); + clearTabStatus(static_cast(i)); } setGoalActive(tab_index, true); @@ -648,42 +646,47 @@ void TasksPanel::doSendGoal( QString result_text; QString status_text; QString color; - QColor tab_color; + QString tab_icon; + QColor tab_text_color; switch (wrapped_result.code) { case rclcpp_action::ResultCode::SUCCEEDED: result_text = fmt_result(wrapped_result.result); status_text = "Succeeded"; color = "color: darkGreen;"; - tab_color = Qt::darkGreen; + tab_icon = QString::fromUtf8(u8"✅"); + tab_text_color = Qt::darkGreen; break; case rclcpp_action::ResultCode::ABORTED: result_text = fmt_result(wrapped_result.result); status_text = "Aborted"; color = "color: red;"; - tab_color = Qt::red; + tab_icon = QString::fromUtf8(u8"❌"); + tab_text_color = Qt::red; break; case rclcpp_action::ResultCode::CANCELED: result_text = "Goal canceled"; status_text = "Canceled"; color = "color: orange;"; - tab_color = QColor("orange"); + tab_icon = QString::fromUtf8(u8"🚫"); + tab_text_color = QColor("orange"); break; default: result_text = "Unknown result"; status_text = "Unknown"; color = "color: gray;"; - tab_color = Qt::gray; + tab_icon = "?"; + tab_text_color = Qt::gray; break; } QMetaObject::invokeMethod(this, [this, tab_index, result_text, status_text, color, - tab_color]() { + tab_icon, tab_text_color]() { auto & state = tab_states_[tab_index]; state.result_display->setText(result_text); state.status_label->setText(status_text); state.status_label->setStyleSheet(color); - setTabStatusColor(tab_index, tab_color); + setTabStatus(tab_index, tab_icon, tab_text_color); setGoalActive(tab_index, false); }, Qt::QueuedConnection); }; From 9e058543cad85ddd4c3666dad24b974f1e376e81 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Fri, 10 Apr 2026 15:32:50 -0400 Subject: [PATCH 11/24] Ff --- common/ros_packages/gui/rviz/rviz_polygon_selection_tool | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/ros_packages/gui/rviz/rviz_polygon_selection_tool b/common/ros_packages/gui/rviz/rviz_polygon_selection_tool index d64ddcfde..018c74644 160000 --- a/common/ros_packages/gui/rviz/rviz_polygon_selection_tool +++ b/common/ros_packages/gui/rviz/rviz_polygon_selection_tool @@ -1 +1 @@ -Subproject commit d64ddcfde28b97701e4748f5c4895ce591021053 +Subproject commit 018c74644f1c1b96dde48b4bf118c3bcf0d70877 From c2590fa8a49ca8ebc949b0d392a3c1d25731f320 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Fri, 10 Apr 2026 16:06:32 -0400 Subject: [PATCH 12/24] Update rviz --- .../desktop_bringup/rviz/robot.rviz | 118 ++++++++++++++---- 1 file changed, 96 insertions(+), 22 deletions(-) diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 9561dd1cc..081dd9c46 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -1,27 +1,23 @@ Panels: - Class: rviz_common/Displays - Help Height: 70 + Help Height: 0 Name: Displays Property Tree Widget: Expanded: - /Global Options1 - /TF1/Frames1 - - /Sensors1 - /Perception1/StereoImageProc Disparity1 - /Local1/DROAN1 - /Local1/DROAN1/Trimmed Global Plan for DROAN1/Topic1 - /Local1/DROAN1/Droan GPU1 - /Local1/DROAN1/Droan GPU1/Traj Debug1/Namespaces1 - - /Global1 - /Global1/Global Plan1 Splitter Ratio: 0.3440559506416321 - Tree Height: 330 + Tree Height: 215 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 + Expanded: ~ Name: Tool Properties Splitter Ratio: 0.5886790156364441 - Class: rviz_common/Views @@ -33,7 +29,7 @@ Panels: Experimental: false Name: Time SyncMode: 0 - SyncSource: "" + SyncSource: Foreground Background Cloud - Class: rviz_behavior_tree_panel::BehaviorTreePanel Name: BehaviorTreePanel topic: /robot_1/behavior/behavior_tree_graphviz @@ -88,6 +84,8 @@ Visualization Manager: Value: false base_link_frd: Value: true + base_link_stabilized: + Value: true camera_left: Value: true camera_right: @@ -96,6 +94,10 @@ Visualization Manager: Value: false lidar: Value: false + look_ahead_point: + Value: true + look_ahead_point_stabilized: + Value: true map: Value: true map_ned: @@ -112,6 +114,10 @@ Visualization Manager: Value: true rotor3: Value: true + tracking_point: + Value: true + tracking_point_stabilized: + Value: true world: Value: false Marker Scale: 0.30000001192092896 @@ -122,8 +128,40 @@ Visualization Manager: Tree: world: map: + base_link: + base_link_body_body_link: + OS1_REV6_128_10hz___512_resolution: + lidar: + {} + base_link_ZED_X: + camera_left: + {} + camera_right: + {} + imu: + {} + rotor0: + {} + rotor1: + {} + rotor2: + {} + rotor3: + {} + base_link_frd: + {} + base_link_stabilized: + {} + look_ahead_point: + {} + look_ahead_point_stabilized: + {} map_ned: {} + tracking_point: + {} + tracking_point_stabilized: + {} Update Interval: 0 Value: true - Alpha: 0.5 @@ -443,7 +481,8 @@ Visualization Manager: Enabled: true Name: Trimmed Global Plan for DROAN Namespaces: - {} + global_plan: true + global_plan_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -588,7 +627,12 @@ Visualization Manager: Enabled: true Name: Traj Debug Namespaces: - {} + collision_points: true + collision_trajectories: true + free_points: true + free_trajectories: true + unseen_points: true + unseen_trajectories: true Topic: Depth: 5 Durability Policy: Volatile @@ -600,7 +644,7 @@ Visualization Manager: Enabled: true Name: Graph Vis Namespaces: - {} + default: true Topic: Depth: 5 Durability Policy: Volatile @@ -626,7 +670,8 @@ Visualization Manager: Enabled: true Name: Global Plan Vis Namespaces: - {} + global_plan: true + global_plan_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -638,7 +683,7 @@ Visualization Manager: Enabled: true Name: Rewind Info Namespaces: - {} + rewind_info: true Topic: Depth: 5 Durability Policy: Volatile @@ -654,7 +699,8 @@ Visualization Manager: Enabled: true Name: Traj Vis Namespaces: - {} + traj_controller: true + traj_controller_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -684,7 +730,7 @@ Visualization Manager: Enabled: true Name: VDB Mapping Marker Namespaces: - {} + "": true Topic: Depth: 5 Durability Policy: Volatile @@ -737,6 +783,15 @@ Visualization Manager: Reliability Policy: Reliable Value: sensors/front_stereo/left/image_rect Value: true + - Class: rviz_default_plugins/InteractiveMarkers + Enable Transparency: true + Enabled: true + Interactive Markers Namespace: /robot_1/waypoint_plugin + Name: InteractiveMarkers + Show Axes: true + Show Descriptions: true + Show Visual Aids: false + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -776,6 +831,23 @@ Visualization Manager: History Policy: Keep Last Reliability Policy: Reliable Value: /clicked_point + - Class: rviz_polygon_selection_tool/PolygonSelectionTool + Close loop: true + Lasso mode: true + Line Color: 255; 0; 0 + Patch size: 15 + Point Color: 255; 0; 0 + Point Generation Gap: 0.0020000000949949026 + Point Size: 50 + Render as Overlay: false + Service name: get_selection + Show Text: true + Text Size: 0.014999999664723873 + - Class: waypoint_rviz2_plugin/WaypointTool + WaypointTool: + default_height: 0 + frame_id: map + topic: global_plan Transformation: Current: Class: rviz_default_plugins/TF @@ -783,25 +855,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 26.301408767700195 + Distance: 7.636964797973633 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 6.924289703369141 - Y: -7.847400188446045 - Z: -4.3323540687561035 + X: -14.859757423400879 + Y: -8.647265434265137 + Z: 3.183002233505249 Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5103968977928162 + Pitch: 0.6203982830047607 Target Frame: base_link Value: Orbit (rviz) - Yaw: 2.279876232147217 + Yaw: 1.6853976249694824 Saved: ~ Window Geometry: BehaviorTreePanel: @@ -819,7 +891,7 @@ Window Geometry: collapsed: false MACVO Disparity: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Selection: collapsed: false TasksPanel: @@ -830,6 +902,8 @@ Window Geometry: collapsed: false Views: collapsed: false + Waypoint Plugin: + collapsed: false Width: 2490 X: 1990 Y: 27 From b038fb1c5dee021f95b47ecf88be6d680f5480e5 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Fri, 10 Apr 2026 16:15:42 -0400 Subject: [PATCH 13/24] Update rviz --- .../ros_packages/desktop_bringup/rviz/robot.rviz | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 081dd9c46..4c65e3bb5 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -481,8 +481,7 @@ Visualization Manager: Enabled: true Name: Trimmed Global Plan for DROAN Namespaces: - global_plan: true - global_plan_extra_text: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -605,9 +604,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 49 + Max Intensity: 41 Min Color: 0; 0; 0 - Min Intensity: 0 + Min Intensity: 31 Name: Foreground Background Cloud Position Transformer: XYZ Selectable: true @@ -670,8 +669,7 @@ Visualization Manager: Enabled: true Name: Global Plan Vis Namespaces: - global_plan: true - global_plan_extra_text: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -700,7 +698,6 @@ Visualization Manager: Name: Traj Vis Namespaces: traj_controller: true - traj_controller_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -730,7 +727,7 @@ Visualization Manager: Enabled: true Name: VDB Mapping Marker Namespaces: - "": true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -891,7 +888,7 @@ Window Geometry: collapsed: false MACVO Disparity: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Selection: collapsed: false TasksPanel: From 9999eca08597103e3e09d98341075638789d1321 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 17:39:50 -0400 Subject: [PATCH 14/24] Update tasks panel to use navigate tool --- .../desktop_bringup/rviz/robot.rviz | 42 +- .../3d_waypoint_rviz2_plugin/CMakeLists.txt | 25 +- .../waypoint_manager.hpp | 124 ++++ .../waypoint_rviz2_plugin/waypoint_tool.hpp | 73 +-- .../src/waypoint_manager.cpp | 553 ++++++++++++++++++ .../src/waypoint_tool.cpp | 477 ++++----------- .../gui/rviz/rviz_tasks_panel/CMakeLists.txt | 2 + .../include/rviz_tasks_panel/tasks_panel.hpp | 26 +- .../gui/rviz/rviz_tasks_panel/package.xml | 1 + .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 172 +++++- 10 files changed, 1046 insertions(+), 449 deletions(-) create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 4c65e3bb5..3e0d87148 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -13,7 +13,7 @@ Panels: - /Local1/DROAN1/Droan GPU1/Traj Debug1/Namespaces1 - /Global1/Global Plan1 Splitter Ratio: 0.3440559506416321 - Tree Height: 215 + Tree Height: 332 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -481,7 +481,8 @@ Visualization Manager: Enabled: true Name: Trimmed Global Plan for DROAN Namespaces: - {} + global_plan: true + global_plan_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -604,9 +605,9 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 41 + Max Intensity: 49 Min Color: 0; 0; 0 - Min Intensity: 31 + Min Intensity: 0 Name: Foreground Background Cloud Position Transformer: XYZ Selectable: true @@ -626,12 +627,7 @@ Visualization Manager: Enabled: true Name: Traj Debug Namespaces: - collision_points: true - collision_trajectories: true - free_points: true - free_trajectories: true - unseen_points: true - unseen_trajectories: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -643,7 +639,7 @@ Visualization Manager: Enabled: true Name: Graph Vis Namespaces: - default: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -651,7 +647,7 @@ Visualization Manager: Reliability Policy: Reliable Value: droan/graph_vis Value: true - Enabled: true + Enabled: false Name: Droan GPU - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -669,7 +665,8 @@ Visualization Manager: Enabled: true Name: Global Plan Vis Namespaces: - {} + global_plan: true + global_plan_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -698,6 +695,7 @@ Visualization Manager: Name: Traj Vis Namespaces: traj_controller: true + traj_controller_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -727,7 +725,7 @@ Visualization Manager: Enabled: true Name: VDB Mapping Marker Namespaces: - {} + "": true Topic: Depth: 5 Durability Policy: Volatile @@ -844,7 +842,7 @@ Visualization Manager: WaypointTool: default_height: 0 frame_id: map - topic: global_plan + topic: waypoints Transformation: Current: Class: rviz_default_plugins/TF @@ -852,25 +850,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 7.636964797973633 + Distance: 24.656192779541016 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -14.859757423400879 - Y: -8.647265434265137 - Z: 3.183002233505249 + X: -15.954153060913086 + Y: 5.539872169494629 + Z: -11.331672668457031 Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.6203982830047607 + Pitch: 0.5953978896141052 Target Frame: base_link Value: Orbit (rviz) - Yaw: 1.6853976249694824 + Yaw: 6.003584861755371 Saved: ~ Window Geometry: BehaviorTreePanel: @@ -888,7 +886,7 @@ Window Geometry: collapsed: false MACVO Disparity: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Selection: collapsed: false TasksPanel: diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt index 83d651417..c19c09c71 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/CMakeLists.txt @@ -1,9 +1,8 @@ cmake_minimum_required(VERSION 3.5) project(waypoint_rviz2_plugin) -# Default to C++14 if(NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) + set(CMAKE_CXX_STANDARD 17) endif() if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") @@ -35,24 +34,13 @@ add_definitions(-DQT_NO_KEYWORDS) # Header files that need Qt Moc pre-processing qt5_wrap_cpp(MOC_FILES - include/waypoint_rviz2_plugin/waypoint_widget.hpp + include/waypoint_rviz2_plugin/waypoint_manager.hpp include/waypoint_rviz2_plugin/waypoint_tool.hpp ) -# Convert the Qt UI files -qt5_wrap_ui(UIC_FILES - ui/waypoint_plugin.ui -) - -# Include directories -include_directories( - include - ${CMAKE_CURRENT_BINARY_DIR} -) - # Plugin source files set(SOURCES - src/waypoint_widget.cpp + src/waypoint_manager.cpp src/waypoint_tool.cpp ${MOC_FILES} ) @@ -60,7 +48,12 @@ set(SOURCES # Declare the library add_library(${PROJECT_NAME} SHARED ${SOURCES} - ${UIC_FILES} +) + +target_include_directories(${PROJECT_NAME} PUBLIC + $ + $ + $ ) # Dependencies diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp new file mode 100644 index 000000000..a96a7b4d7 --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp @@ -0,0 +1,124 @@ +/** + * @file waypoint_manager.hpp + * + * Singleton that owns all waypoint state (interactive markers, Ogre scene + * nodes, persistence). Both WaypointTool (3-D mouse interaction) and the + * Tasks Panel Navigate tab (UI controls) hold a shared_ptr to the same + * instance so they share a single source of truth. + */ + +#pragma once + +#ifndef Q_MOC_RUN +#include +#include +#include +#include + +#include +#include +#include +#include +#endif + +#include +#include +#include +#include +#include +#include + +namespace rviz_common { +class DisplayContext; +} + +namespace waypoint_rviz2_plugin { + +constexpr char kWaypointPrefix[] = "point#"; + +class WaypointManager : public QObject +{ + Q_OBJECT + +public: + // ── singleton ────────────────────────────────────────────────────────────── + static std::shared_ptr instance(); + + ~WaypointManager() override; + + /** Called once by WaypointTool::onInitialize() which has the DisplayContext. */ + void initialize(rviz_common::DisplayContext * context, + rclcpp::Node::SharedPtr node); + bool isInitialized() const { return initialized_; } + + // ── waypoint operations ──────────────────────────────────────────────────── + void addWaypoint(const Ogre::Vector3 & position, const Ogre::Quaternion & quaternion); + void removeWaypoint(int idx); + void clearAll(); + + /** Build a nav_msgs/Path from current waypoint state. */ + nav_msgs::msg::Path getPath() const; + + /** Publish current waypoints on the configured topic. */ + void publishPath(); + + void saveBag(const std::string & filename); + void loadBag(const std::string & filename); + + /** Update pose of the currently-selected marker from spinbox values. */ + void updateSelectedPose(double x, double y, double z, double yaw); + + // ── accessors / mutators ─────────────────────────────────────────────────── + std::string frameId() const; + void setFrameId(const std::string & frame); + + std::string outputTopic() const; + void setOutputTopic(const std::string & topic); + + double defaultHeight() const; + void setDefaultHeight(double h); + + int waypointCount() const; + + /** Read-only access to the node map (used by WaypointTool for proximity). */ + const std::map & nodeMap() const { return node_map_; } + + /** Expose the interactive marker server (needed by WaypointTool for menu). */ + std::shared_ptr server() const { return server_; } + + interactive_markers::MenuHandler & menuHandler() { return menu_handler_; } + +Q_SIGNALS: + void waypointCountChanged(int count); + void selectedMarkerChanged(const QString & name, double x, double y, double z, double yaw); + void waypointsCleared(); + +private: + WaypointManager(); // private – use instance() + + void processFeedback( + const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr & feedback); + + bool initialized_{false}; + rclcpp::Node::SharedPtr node_; + rviz_common::DisplayContext * context_{nullptr}; + Ogre::SceneManager * scene_manager_{nullptr}; + + std::shared_ptr server_; + interactive_markers::MenuHandler menu_handler_; + + std::map node_map_; + int unique_idx_{0}; + + std::string frame_id_{"map"}; + std::string output_topic_{"/waypoints"}; + double default_height_{0.0}; + std::string selected_marker_name_; + + std::string axis_resource_; + rclcpp::Publisher::SharedPtr path_publisher_; + + mutable std::mutex mtx_; +}; + +} // namespace waypoint_rviz2_plugin diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp index 622198cb0..b599df90f 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_tool.hpp @@ -1,75 +1,52 @@ /** * @file waypoint_tool.hpp * @author KoKoLates (the21515@gmail.com) - * @version 1.0.0 - * @date 2023-06-19 - * - * ROS2 port of the interactive waypoint tool for RViz2 + * @version 2.0.0 + * + * RViz2 Tool for placing/removing waypoints via mouse clicks in the 3-D + * viewport. All state is owned by WaypointManager; this class only converts + * mouse events into manager calls. */ #pragma once #ifndef Q_MOC_RUN -#include -#include #include +#include #endif +#include #include #include -#include -#include -#include -#include "waypoint_widget.hpp" +#include "waypoint_manager.hpp" namespace rviz_common { - class DisplayContext; - class ViewportMouseEvent; - namespace properties { - class VectorProperty; - } - class PanelDockWidget; +class DisplayContext; +class ViewportMouseEvent; } namespace waypoint_rviz2_plugin { -class WaypointTool: public rviz_common::Tool { - Q_OBJECT +class WaypointTool : public rviz_common::Tool +{ + Q_OBJECT public: - WaypointTool(); - ~WaypointTool() override; - - void onInitialize() override; - void activate() override; - void deactivate() override; - int processMouseEvent(rviz_common::ViewportMouseEvent& event) override; + WaypointTool(); + ~WaypointTool() override; - void makeItem(const Ogre::Vector3&, const Ogre::Quaternion&); + void onInitialize() override; + void activate() override; + void deactivate() override; + int processMouseEvent(rviz_common::ViewportMouseEvent & event) override; - void load(const rviz_common::Config& config) override; - void save(rviz_common::Config config) const override; + void load(const rviz_common::Config & config) override; + void save(rviz_common::Config config) const override; private: - void getMarkerPose(); - void clearAllMarker(); - void processFeedBack(const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr&); - - Ogre::SceneNode *move_axis_node_; - std::string axis_resource_; - - WaypointWidget *widget_; - rviz_common::PanelDockWidget *widget_dock_; - - std::shared_ptr server_; - interactive_markers::MenuHandler menu_handler_; - - typedef std::map str2nodeptr; - str2nodeptr node_map_; - - int unique_idx_; - - rclcpp::Node::SharedPtr node_; + Ogre::SceneNode * move_axis_node_{nullptr}; + std::shared_ptr manager_; + rclcpp::Node::SharedPtr node_; }; -} +} // namespace waypoint_rviz2_plugin diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp new file mode 100644 index 000000000..f315a00fa --- /dev/null +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp @@ -0,0 +1,553 @@ +/** + * @file waypoint_manager.cpp + * + * Implementation of the shared WaypointManager singleton. + */ + +#include "waypoint_rviz2_plugin/waypoint_manager.hpp" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +namespace waypoint_rviz2_plugin { + +// ─────────────────────────── singleton ───────────────────────────────────────── + +std::shared_ptr WaypointManager::instance() +{ + static std::weak_ptr weak_instance; + static std::mutex singleton_mtx; + std::lock_guard lock(singleton_mtx); + + auto sp = weak_instance.lock(); + if (!sp) { + sp = std::shared_ptr(new WaypointManager()); + weak_instance = sp; + } + return sp; +} + +WaypointManager::WaypointManager() +{ + selected_marker_name_ = std::string(kWaypointPrefix) + "1"; +} + +WaypointManager::~WaypointManager() +{ + if (scene_manager_) { + for (auto & [idx, node_ptr] : node_map_) { + scene_manager_->destroySceneNode(node_ptr); + } + } +} + +// ─────────────────────────── initialization ─────────────────────────────────── + +void WaypointManager::initialize(rviz_common::DisplayContext * context, + rclcpp::Node::SharedPtr node) +{ + if (initialized_) { return; } + + context_ = context; + node_ = node; + scene_manager_ = context_->getSceneManager(); + + axis_resource_ = "package://waypoint_rviz2_plugin/media/axis.dae"; + if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { + RCLCPP_ERROR(node_->get_logger(), + "WaypointManager: failed to load model resource '%s'.", + axis_resource_.c_str()); + return; + } + + server_ = std::make_shared( + "waypoint_plugin", node_); + + path_publisher_ = + node_->create_publisher(output_topic_, 1); + + menu_handler_.insert( + "delete", + std::bind(&WaypointManager::processFeedback, this, std::placeholders::_1)); + menu_handler_.insert( + "set manual", + std::bind(&WaypointManager::processFeedback, this, std::placeholders::_1)); + + initialized_ = true; +} + +// ─────────────────────────── waypoint operations ────────────────────────────── + +void WaypointManager::addWaypoint(const Ogre::Vector3 & position, + const Ogre::Quaternion & quaternion) +{ + if (!initialized_) { return; } + + unique_idx_++; + std::stringstream wp_name; + wp_name << kWaypointPrefix << unique_idx_; + std::string str_name(wp_name.str()); + + if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { + RCLCPP_ERROR(node_->get_logger(), + "WaypointManager: failed to load model resource '%s'.", + axis_resource_.c_str()); + return; + } + + Ogre::SceneNode * node_ptr = + scene_manager_->getRootSceneNode()->createChildSceneNode(); + Ogre::Entity * entity = scene_manager_->createEntity(axis_resource_); + node_ptr->attachObject(entity); + node_ptr->setVisible(true); + node_ptr->setPosition(position); + node_ptr->setOrientation(quaternion); + + auto node_entry = node_map_.find(unique_idx_); + if (node_entry == node_map_.end()) { + node_map_.insert(std::make_pair(unique_idx_, node_ptr)); + } else { + RCLCPP_WARN(node_->get_logger(), "%s already in map", str_name.c_str()); + return; + } + + // Build interactive marker + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = position.x; + pose.pose.position.y = position.y; + pose.pose.position.z = position.z; + pose.pose.orientation.x = quaternion.x; + pose.pose.orientation.y = quaternion.y; + pose.pose.orientation.z = quaternion.z; + pose.pose.orientation.w = quaternion.w; + + visualization_msgs::msg::InteractiveMarker int_marker; + int_marker.header.stamp = node_->now(); + { + std::lock_guard lock(mtx_); + int_marker.header.frame_id = frame_id_; + } + int_marker.pose = pose.pose; + int_marker.scale = 1.0; + int_marker.name = str_name; + + // Invisible cylinder for picking + visualization_msgs::msg::Marker marker; + marker.type = visualization_msgs::msg::Marker::CYLINDER; + marker.scale.x = 0.5; + marker.scale.y = 0.5; + marker.scale.z = 0.1; + marker.color.r = 0.0; + marker.color.g = 0.0; + marker.color.b = 0.0; + marker.color.a = 0.0; + + visualization_msgs::msg::InteractiveMarkerControl c_control; + c_control.always_visible = true; + c_control.markers.push_back(marker); + int_marker.controls.push_back(c_control); + + visualization_msgs::msg::InteractiveMarkerControl control; + control.orientation.w = 0.707106781; + control.orientation.x = 0; + control.orientation.y = 0.707106781; + control.orientation.z = 0; + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MOVE_ROTATE; + int_marker.controls.push_back(control); + + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MOVE_AXIS; + int_marker.controls.push_back(control); + + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MENU; + control.name = "menu_delete"; + control.description = str_name; + int_marker.controls.push_back(control); + + server_->insert(int_marker); + server_->setCallback( + int_marker.name, + std::bind(&WaypointManager::processFeedback, this, std::placeholders::_1)); + menu_handler_.apply(*server_, int_marker.name); + server_->applyChanges(); + + selected_marker_name_ = str_name; + + // Convert quaternion to yaw for signal + tf2::Quaternion qt(quaternion.x, quaternion.y, quaternion.z, quaternion.w); + tf2::Matrix3x3 m(qt); + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + + Q_EMIT waypointCountChanged(static_cast(node_map_.size())); + Q_EMIT selectedMarkerChanged( + QString::fromStdString(str_name), position.x, position.y, position.z, yaw); +} + +void WaypointManager::removeWaypoint(int idx) +{ + if (!initialized_) { return; } + + auto it = node_map_.find(idx); + if (it == node_map_.end()) { return; } + + it->second->detachAllObjects(); + scene_manager_->destroySceneNode(it->second); + + std::stringstream wp_name; + wp_name << kWaypointPrefix << idx; + server_->erase(wp_name.str()); + server_->applyChanges(); + + node_map_.erase(it); + + Q_EMIT waypointCountChanged(static_cast(node_map_.size())); +} + +void WaypointManager::clearAll() +{ + if (!initialized_) { return; } + + for (auto & [idx, node_ptr] : node_map_) { + scene_manager_->destroySceneNode(node_ptr); + } + node_map_.clear(); + unique_idx_ = 0; + + server_->clear(); + server_->applyChanges(); + + Q_EMIT waypointCountChanged(0); + Q_EMIT waypointsCleared(); +} + +nav_msgs::msg::Path WaypointManager::getPath() const +{ + nav_msgs::msg::Path path; + for (const auto & [idx, node_ptr] : node_map_) { + Ogre::Vector3 pos = node_ptr->getPosition(); + Ogre::Quaternion quat = node_ptr->getOrientation(); + + geometry_msgs::msg::PoseStamped pose; + pose.pose.position.x = pos.x; + pose.pose.position.y = pos.y; + pose.pose.position.z = pos.z; + pose.pose.orientation.x = quat.x; + pose.pose.orientation.y = quat.y; + pose.pose.orientation.z = quat.z; + pose.pose.orientation.w = quat.w; + path.poses.push_back(pose); + } + { + std::lock_guard lock(mtx_); + path.header.frame_id = frame_id_; + } + if (node_) { + path.header.stamp = node_->now(); + } + return path; +} + +void WaypointManager::publishPath() +{ + if (!path_publisher_) { return; } + path_publisher_->publish(getPath()); +} + +void WaypointManager::updateSelectedPose(double x, double y, double z, + double yaw) +{ + if (!initialized_) { return; } + + int selected_idx = 0; + try { + selected_idx = std::stoi( + selected_marker_name_.substr(strlen(kWaypointPrefix))); + } catch (const std::logic_error & e) { + RCLCPP_ERROR_STREAM(node_->get_logger(), e.what()); + return; + } + + auto it = node_map_.find(selected_idx); + if (it == node_map_.end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", + selected_marker_name_.c_str()); + return; + } + + Ogre::Vector3 position(x, y, z); + tf2::Quaternion qt; + qt.setRPY(0.0, 0.0, yaw); + Ogre::Quaternion quaternion(qt.w(), qt.x(), qt.y(), qt.z()); + + it->second->setPosition(position); + it->second->setOrientation(quaternion); + + std::stringstream wp_name; + wp_name << kWaypointPrefix << it->first; + std::string wp_name_str(wp_name.str()); + + visualization_msgs::msg::InteractiveMarker int_marker; + if (server_->get(wp_name_str, int_marker)) { + int_marker.pose.position.x = x; + int_marker.pose.position.y = y; + int_marker.pose.position.z = z; + int_marker.pose.orientation.x = qt.x(); + int_marker.pose.orientation.y = qt.y(); + int_marker.pose.orientation.z = qt.z(); + int_marker.pose.orientation.w = qt.w(); + server_->setPose(wp_name_str, int_marker.pose, int_marker.header); + } + server_->applyChanges(); +} + +// ─────────────────────────── persistence ────────────────────────────────────── + +void WaypointManager::saveBag(const std::string & filename) +{ + nav_msgs::msg::Path path = getPath(); + + try { + rosbag2_cpp::Writer writer; + + rosbag2_storage::StorageOptions storage_options; + storage_options.uri = filename; + storage_options.storage_id = "sqlite3"; + + rosbag2_cpp::ConverterOptions converter_options; + converter_options.input_serialization_format = "cdr"; + converter_options.output_serialization_format = "cdr"; + + writer.open(storage_options, converter_options); + + rosbag2_storage::TopicMetadata topic_metadata; + topic_metadata.name = "waypoints"; + topic_metadata.type = "nav_msgs/msg/Path"; + topic_metadata.serialization_format = rmw_get_serialization_format(); + writer.create_topic(topic_metadata); + + auto serialized_msg = std::make_shared(); + rclcpp::Serialization serialization; + serialization.serialize_message(&path, serialized_msg.get()); + + auto bag_message = + std::make_shared(); + bag_message->topic_name = "waypoints"; + bag_message->recv_timestamp = node_->now().nanoseconds(); + bag_message->serialized_data = std::shared_ptr( + new rcutils_uint8_array_t, + [](rcutils_uint8_array_t * data) { + auto fini_return = rcutils_uint8_array_fini(data); + delete data; + if (fini_return != RCUTILS_RET_OK) { + RCUTILS_LOG_ERROR_NAMED( + "waypoint_rviz2_plugin", + "Failed to destroy serialized message %s", + rcutils_get_error_string().str); + } + }); + *bag_message->serialized_data = + serialized_msg->release_rcl_serialized_message(); + + writer.write(bag_message); + + RCLCPP_INFO(node_->get_logger(), "Waypoints saved successfully"); + } catch (const std::exception & e) { + RCLCPP_ERROR(node_->get_logger(), "Failed to save bag: %s", e.what()); + } +} + +void WaypointManager::loadBag(const std::string & filename) +{ + try { + rosbag2_cpp::Reader reader; + + rosbag2_storage::StorageOptions storage_options; + storage_options.uri = filename; + storage_options.storage_id = "sqlite3"; + + rosbag2_cpp::ConverterOptions converter_options; + converter_options.input_serialization_format = "cdr"; + converter_options.output_serialization_format = "cdr"; + + reader.open(storage_options, converter_options); + + while (reader.has_next()) { + auto bag_message = reader.read_next(); + + if (bag_message->topic_name == "waypoints") { + rclcpp::SerializedMessage serialized_msg( + *bag_message->serialized_data); + nav_msgs::msg::Path path; + + rclcpp::Serialization serialization; + serialization.deserialize_message(&serialized_msg, &path); + + RCLCPP_INFO(node_->get_logger(), "Loading %zu waypoints", + path.poses.size()); + + for (size_t i = 0; i < path.poses.size(); i++) { + const auto & pos = path.poses[i]; + Ogre::Vector3 position( + pos.pose.position.x, pos.pose.position.y, pos.pose.position.z); + Ogre::Quaternion quaternion( + pos.pose.orientation.w, pos.pose.orientation.x, + pos.pose.orientation.y, pos.pose.orientation.z); + addWaypoint(position, quaternion); + } + } + } + } catch (const std::exception & e) { + RCLCPP_ERROR(node_->get_logger(), "Failed to load bag: %s", e.what()); + } +} + +// ─────────────────────────── accessors ──────────────────────────────────────── + +std::string WaypointManager::frameId() const +{ + std::lock_guard lock(mtx_); + return frame_id_; +} + +void WaypointManager::setFrameId(const std::string & frame) +{ + std::lock_guard lock(mtx_); + frame_id_ = frame; +} + +std::string WaypointManager::outputTopic() const +{ + std::lock_guard lock(mtx_); + return output_topic_; +} + +void WaypointManager::setOutputTopic(const std::string & topic) +{ + std::lock_guard lock(mtx_); + if (topic == output_topic_) { return; } + output_topic_ = topic; + if (node_ && !topic.empty() && topic != "/") { + path_publisher_.reset(); + path_publisher_ = + node_->create_publisher(output_topic_, 1); + } +} + +double WaypointManager::defaultHeight() const +{ + std::lock_guard lock(mtx_); + return default_height_; +} + +void WaypointManager::setDefaultHeight(double h) +{ + std::lock_guard lock(mtx_); + default_height_ = h; +} + +int WaypointManager::waypointCount() const +{ + return static_cast(node_map_.size()); +} + +// ─────────────────────────── feedback ───────────────────────────────────────── + +void WaypointManager::processFeedback( + const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr & + feedback) +{ + switch (feedback->event_type) { + case visualization_msgs::msg::InteractiveMarkerFeedback::MENU_SELECT: { + int idx = 0; + try { + idx = std::stoi( + feedback->marker_name.substr(strlen(kWaypointPrefix))); + } catch (const std::logic_error & e) { + RCLCPP_ERROR_STREAM(node_->get_logger(), e.what()); + return; + } + + auto node_entry = node_map_.find(idx); + if (node_entry == node_map_.end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", + feedback->marker_name.c_str()); + return; + } + + if (feedback->menu_entry_id == 1) { + // delete + std::stringstream wp_name; + wp_name << kWaypointPrefix << node_entry->first; + server_->erase(wp_name.str()); + menu_handler_.reApply(*server_); + server_->applyChanges(); + node_entry->second->detachAllObjects(); + scene_manager_->destroySceneNode(node_entry->second); + node_map_.erase(node_entry); + + Q_EMIT waypointCountChanged(static_cast(node_map_.size())); + } else { + // "set manual" – noop for now, marker stays at current spinbox pose + } + break; + } + case visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE: { + int idx = 0; + try { + idx = std::stoi( + feedback->marker_name.substr(strlen(kWaypointPrefix))); + } catch (const std::logic_error & e) { + RCLCPP_ERROR_STREAM(node_->get_logger(), e.what()); + return; + } + + auto node_entry = node_map_.find(idx); + if (node_entry == node_map_.end()) { + RCLCPP_ERROR(node_->get_logger(), "%s not found in map", + feedback->marker_name.c_str()); + return; + } + + const auto & p = feedback->pose; + Ogre::Vector3 position(p.position.x, p.position.y, p.position.z); + Ogre::Quaternion quaternion( + p.orientation.w, p.orientation.x, p.orientation.y, p.orientation.z); + + node_entry->second->setPosition(position); + node_entry->second->setOrientation(quaternion); + + selected_marker_name_ = feedback->marker_name; + + tf2::Quaternion qt(quaternion.x, quaternion.y, quaternion.z, + quaternion.w); + tf2::Matrix3x3 m(qt); + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + + Q_EMIT selectedMarkerChanged( + QString::fromStdString(feedback->marker_name), + position.x, position.y, position.z, yaw); + break; + } + } +} + +} // namespace waypoint_rviz2_plugin diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp index 0d4f145d4..f41882d53 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_tool.cpp @@ -1,33 +1,27 @@ /** * @file waypoint_tool.cpp * @author KoKoLates (the21515@gmail.com) - * @version 1.0.0 - * @date 2023-06-20 - * - * ROS2 port of the interactive waypoint tool implementation + * @version 2.0.0 + * + * RViz2 Tool for placing/removing waypoints via mouse clicks. + * All waypoint state is delegated to WaypointManager. */ #include "waypoint_rviz2_plugin/waypoint_tool.hpp" -#include - #ifndef Q_MOC_RUN #include #include -#include -#include -#include -#include #include +#include #include -#include -#include -#include -#include #include +#include #include #include +#include +#include #include #endif @@ -41,363 +35,150 @@ namespace waypoint_rviz2_plugin { -WaypointTool::WaypointTool() - : move_axis_node_(nullptr), - widget_dock_(nullptr), - widget_(nullptr), - unique_idx_(0) +WaypointTool::WaypointTool() { - shortcut_key_ = '1'; -} - -WaypointTool::~WaypointTool() { - str2nodeptr::iterator node_itr; - for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { - scene_manager_->destroySceneNode(node_itr->second); - } - delete widget_; - delete widget_dock_; -} - -void WaypointTool::onInitialize() { - node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); - - axis_resource_ = "package://waypoint_rviz2_plugin/media/axis.dae"; - - if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { - RCLCPP_ERROR(node_->get_logger(), "Waypoint Tool: failed to load model resource '%s'.", axis_resource_.c_str()); - return; - } - - move_axis_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); - Ogre::Entity* entity = scene_manager_->createEntity(axis_resource_); - move_axis_node_->attachObject(entity); - move_axis_node_->setVisible(false); - - server_ = std::make_shared( - "waypoint_plugin", node_ - ); - - rviz_common::WindowManagerInterface* window_context_ = context_->getWindowManager(); - widget_ = new WaypointWidget(context_, node_, &node_map_, server_, &unique_idx_, nullptr, this); - - if (window_context_) { - widget_dock_ = window_context_->addPane("Waypoint Plugin", widget_); - } - widget_->enable(); - - menu_handler_.insert("delete", - std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); - menu_handler_.insert("set manual", - std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); + shortcut_key_ = '1'; } -void WaypointTool::activate() { - if (move_axis_node_) { - move_axis_node_->setVisible(true); - } +WaypointTool::~WaypointTool() +{ + // move_axis_node_ is owned by the Ogre SceneManager; it is cleaned up when + // RViz destroys the scene. } -void WaypointTool::deactivate() { - if (move_axis_node_) { - move_axis_node_->setVisible(false); - } +void WaypointTool::onInitialize() +{ + node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); + + std::string axis_resource = "package://waypoint_rviz2_plugin/media/axis.dae"; + if (rviz_rendering::loadMeshFromResource(axis_resource).isNull()) { + RCLCPP_ERROR(node_->get_logger(), + "WaypointTool: failed to load model resource '%s'.", + axis_resource.c_str()); + return; + } + + move_axis_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); + Ogre::Entity * entity = scene_manager_->createEntity(axis_resource); + move_axis_node_->attachObject(entity); + move_axis_node_->setVisible(false); + + // Create / retrieve the shared WaypointManager singleton + manager_ = WaypointManager::instance(); + if (!manager_->isInitialized()) { + manager_->initialize(context_, node_); + } } -int WaypointTool::processMouseEvent(rviz_common::ViewportMouseEvent& event) { - if (!move_axis_node_) { - return Render; - } - - double height = widget_->getDefaultHeight(); - Ogre::Vector3 intersection; - Ogre::Quaternion quaternion; - Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, height); - - // Get viewport and camera from the render window - auto render_window = event.panel->getRenderWindow(); - Ogre::Camera * camera = rviz_rendering::RenderWindowOgreAdapter::getOgreCamera(render_window); - Ogre::Viewport * viewport = rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(render_window); - - // Convert mouse coordinates to normalized device coordinates - int width = viewport->getActualWidth(); - int height_px = viewport->getActualHeight(); - float screen_x = static_cast(event.x) / static_cast(width); - float screen_y = static_cast(event.y) / static_cast(height_px); - - // Create ray from camera through mouse position - Ogre::Ray mouse_ray = camera->getCameraToViewportRay(screen_x, screen_y); - - // Intersect ray with ground plane - std::pair result = mouse_ray.intersects(ground_plane); - - if (result.first) { - intersection = mouse_ray.getPoint(result.second); - move_axis_node_->setVisible(true); - move_axis_node_->setPosition(intersection); - - widget_->setWaypointLabel(intersection); - - str2nodeptr::iterator node_itr; - for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { - Ogre::Vector3 stored_pose = node_itr->second->getPosition(); - double distance = std::sqrt( - pow(stored_pose.x - intersection.x, 2) + pow(stored_pose.y - intersection.y, 2) - ); - - if (distance < 0.4) { - move_axis_node_->setVisible(false); - - if (event.rightDown()) { - node_itr->second->detachAllObjects(); - std::stringstream waypoint_name; - waypoint_name << waypoint_name_prefix << node_itr->first; - server_->erase(waypoint_name.str()); - server_->applyChanges(); - node_map_.erase(node_itr); - - move_axis_node_->setVisible(true); - return Render | Finished; - } - } - } - - if (event.leftDown()) { - makeItem(intersection, quaternion); - return Render | Finished; - } - } - else { - move_axis_node_->setVisible(false); - } - return Render; +void WaypointTool::activate() +{ + if (move_axis_node_) { + move_axis_node_->setVisible(true); + } } -void WaypointTool::makeItem(const Ogre::Vector3& position, const Ogre::Quaternion& quaternion) { - unique_idx_++; - std::stringstream waypoint_name; - waypoint_name << waypoint_name_prefix << unique_idx_; - std::string str_name(waypoint_name.str()); - - if (rviz_rendering::loadMeshFromResource(axis_resource_).isNull()) { - RCLCPP_ERROR(node_->get_logger(), "WaypointTool: failed to load model resource '%s'.", axis_resource_.c_str()); - return; - } - - Ogre::SceneNode *node_ptr = scene_manager_->getRootSceneNode()->createChildSceneNode(); - Ogre::Entity *entity = scene_manager_->createEntity(axis_resource_); - node_ptr->attachObject(entity); - node_ptr->setVisible(true); - node_ptr->setPosition(position); - node_ptr->setOrientation(quaternion); - - str2nodeptr::iterator node_entry = node_map_.find(unique_idx_); - if (node_entry == node_map_.end()) { - node_map_.insert(std::make_pair(unique_idx_, node_ptr)); - } else { - RCLCPP_WARN(node_->get_logger(), "%s already in map", str_name.c_str()); - return; - } - widget_->setWaypointCount(node_map_.size()); - - geometry_msgs::msg::PoseStamped pose; - pose.pose.position.x = position.x; - pose.pose.position.y = position.y; - pose.pose.position.z = position.z; - pose.pose.orientation.x = quaternion.x; - pose.pose.orientation.y = quaternion.y; - pose.pose.orientation.z = quaternion.z; - pose.pose.orientation.w = quaternion.w; - - visualization_msgs::msg::InteractiveMarker int_marker; - int_marker.header.stamp = node_->now(); - int_marker.header.frame_id = widget_->getFrameId().toStdString(); - int_marker.pose = pose.pose; - int_marker.scale = 1.0; - int_marker.name = str_name; - - visualization_msgs::msg::Marker marker; - marker.type = visualization_msgs::msg::Marker::CYLINDER; - marker.scale.x = 0.5; - marker.scale.y = 0.5; - marker.scale.z = 0.1; - marker.color.r = 0.0; - marker.color.g = 0.0; - marker.color.b = 0.0; - marker.color.a = 0.0; - - visualization_msgs::msg::InteractiveMarkerControl c_control; - c_control.always_visible = true; - c_control.markers.push_back(marker); - int_marker.controls.push_back(c_control); - - visualization_msgs::msg::InteractiveMarkerControl control; - control.orientation.w = 0.707106781; - control.orientation.x = 0; - control.orientation.y = 0.707106781; - control.orientation.z = 0; - control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MOVE_ROTATE; - int_marker.controls.push_back(control); - - control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MOVE_AXIS; - int_marker.controls.push_back(control); - - control.interaction_mode = visualization_msgs::msg::InteractiveMarkerControl::MENU; - control.name = "menu_delete"; - control.description = str_name; - int_marker.controls.push_back(control); - - server_->insert(int_marker); - server_->setCallback(int_marker.name, - std::bind(&WaypointTool::processFeedBack, this, std::placeholders::_1)); - menu_handler_.apply(*server_, int_marker.name); - - Ogre::Vector3 p = position; - Ogre::Quaternion q = quaternion; - widget_->setSelectedMarkerName(str_name); - widget_->setWaypointLabel(p); - widget_->setPose(p, q); - server_->applyChanges(); +void WaypointTool::deactivate() +{ + if (move_axis_node_) { + move_axis_node_->setVisible(false); + } } -void WaypointTool::processFeedBack( - const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr& feedback) +int WaypointTool::processMouseEvent(rviz_common::ViewportMouseEvent & event) { - switch (feedback->event_type) { - case visualization_msgs::msg::InteractiveMarkerFeedback::MENU_SELECT: - { - str2nodeptr::iterator node_entry = node_map_.find(std::stoi( - feedback->marker_name.substr(strlen(waypoint_name_prefix)))); - if (node_entry == node_map_.end()) { - RCLCPP_ERROR(node_->get_logger(), "%s not found in map", feedback->marker_name.c_str()); - } - else { - if (feedback->menu_entry_id == 1) { - std::stringstream waypoint_name; - waypoint_name << waypoint_name_prefix << node_entry->first; - server_->erase(waypoint_name.str()); - - menu_handler_.reApply(*server_); - server_->applyChanges(); - node_entry->second->detachAllObjects(); - node_map_.erase(node_entry); - - int waypoint_num = node_map_.size(); - widget_->setWaypointCount(waypoint_num); - } - else { - Ogre::Vector3 position; - Ogre::Quaternion quaternion; - - widget_->getPose(position, quaternion); - - geometry_msgs::msg::Pose pose; - pose.position.x = position.x; - pose.position.y = position.y; - pose.position.z = position.z; - - pose.orientation.x = quaternion.x; - pose.orientation.y = quaternion.y; - pose.orientation.z = quaternion.z; - pose.orientation.w = quaternion.w; - - node_entry->second->setPosition(position); - node_entry->second->setOrientation(quaternion); - - widget_->setWaypointLabel(position); - server_->setPose(feedback->marker_name, pose); - server_->applyChanges(); - } - } - } - break; - case visualization_msgs::msg::InteractiveMarkerFeedback::POSE_UPDATE: - { - str2nodeptr::iterator node_entry = node_map_.find(std::stoi( - feedback->marker_name.substr(strlen(waypoint_name_prefix)) - )); - if (node_entry == node_map_.end()) { - RCLCPP_ERROR(node_->get_logger(), "%s not found in map", feedback->marker_name.c_str()); - } - else { - geometry_msgs::msg::PoseStamped pose; - pose.pose = feedback->pose; - - Ogre::Vector3 position; - position.x = pose.pose.position.x; - position.y = pose.pose.position.y; - position.z = pose.pose.position.z; - node_entry->second->setPosition(position); - - Ogre::Quaternion quaternion; - quaternion.x = pose.pose.orientation.x; - quaternion.y = pose.pose.orientation.y; - quaternion.z = pose.pose.orientation.z; - quaternion.w = pose.pose.orientation.w; - node_entry->second->setOrientation(quaternion); + if (!move_axis_node_ || !manager_ || !manager_->isInitialized()) { + return Render; + } + + double height = manager_->defaultHeight(); + Ogre::Vector3 intersection; + Ogre::Quaternion quaternion; + Ogre::Plane ground_plane(Ogre::Vector3::UNIT_Z, height); + + auto render_window = event.panel->getRenderWindow(); + Ogre::Camera * camera = + rviz_rendering::RenderWindowOgreAdapter::getOgreCamera(render_window); + Ogre::Viewport * viewport = + rviz_rendering::RenderWindowOgreAdapter::getOgreViewport(render_window); + + int width = viewport->getActualWidth(); + int height_px = viewport->getActualHeight(); + float screen_x = static_cast(event.x) / static_cast(width); + float screen_y = static_cast(event.y) / static_cast(height_px); + + Ogre::Ray mouse_ray = camera->getCameraToViewportRay(screen_x, screen_y); + std::pair result = mouse_ray.intersects(ground_plane); + + if (result.first) { + intersection = mouse_ray.getPoint(result.second); + move_axis_node_->setVisible(true); + move_axis_node_->setPosition(intersection); + + // Check proximity to existing waypoints + const auto & node_map = manager_->nodeMap(); + for (auto it = node_map.begin(); it != node_map.end(); ++it) { + Ogre::Vector3 stored_pose = it->second->getPosition(); + double distance = std::sqrt( + std::pow(stored_pose.x - intersection.x, 2) + + std::pow(stored_pose.y - intersection.y, 2)); + + if (distance < 0.4) { + move_axis_node_->setVisible(false); - widget_->setWaypointLabel(position); - widget_->setPose(position, quaternion); - widget_->setSelectedMarkerName(feedback->marker_name); - } + if (event.rightDown()) { + manager_->removeWaypoint(it->first); + move_axis_node_->setVisible(true); + return Render | Finished; } - break; + } } -} - -void WaypointTool::getMarkerPose() { - str2nodeptr::iterator node_itr; - for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { - visualization_msgs::msg::InteractiveMarker int_marker; - std::stringstream waypoint_name; - waypoint_name << waypoint_name_prefix << node_itr->first; - server_->get(waypoint_name.str(), int_marker); - - RCLCPP_INFO( - node_->get_logger(), - "pose: %g %g %g", - int_marker.pose.position.x, - int_marker.pose.position.y, - int_marker.pose.position.z - ); + if (event.leftDown()) { + manager_->addWaypoint(intersection, quaternion); + return Render | Finished; } + } else { + move_axis_node_->setVisible(false); + } + return Render; } -void WaypointTool::clearAllMarker() { - str2nodeptr::iterator node_itr; - for (node_itr = node_map_.begin(); node_itr != node_map_.end(); node_itr++) { - scene_manager_->destroySceneNode(node_itr->second); - } - node_map_.clear(); - unique_idx_ = 0; -} - -void WaypointTool::save(rviz_common::Config config) const { - config.mapSetValue("Class", getClassId()); - rviz_common::Config waypoint_config = config.mapMakeChild("WaypointTool"); - - waypoint_config.mapSetValue("topic", widget_->getOutputTopic()); - waypoint_config.mapSetValue("frame_id", widget_->getFrameId()); - waypoint_config.mapSetValue("default_height", widget_->getDefaultHeight()); +void WaypointTool::save(rviz_common::Config config) const +{ + config.mapSetValue("Class", getClassId()); + rviz_common::Config wp_config = config.mapMakeChild("WaypointTool"); + + if (manager_) { + wp_config.mapSetValue("topic", + QString::fromStdString(manager_->outputTopic())); + wp_config.mapSetValue("frame_id", + QString::fromStdString(manager_->frameId())); + wp_config.mapSetValue("default_height", manager_->defaultHeight()); + } } -void WaypointTool::load(const rviz_common::Config &config) { - rviz_common::Config waypoint_config = config.mapGetChild("WaypointTool"); - QString topic, frame; - float height; - if (!waypoint_config.mapGetString("topic", &topic)) { - topic = "/waypoints"; - } - if (!waypoint_config.mapGetString("frame_id", &frame)) { - frame = "map"; - } - waypoint_config.mapGetFloat("default_height", &height); - - widget_->setConfig(topic, frame, height); +void WaypointTool::load(const rviz_common::Config & config) +{ + rviz_common::Config wp_config = config.mapGetChild("WaypointTool"); + QString topic, frame; + float height = 0.0f; + + if (!wp_config.mapGetString("topic", &topic)) { + topic = "/waypoints"; + } + if (!wp_config.mapGetString("frame_id", &frame)) { + frame = "map"; + } + wp_config.mapGetFloat("default_height", &height); + + if (manager_) { + manager_->setOutputTopic(topic.toStdString()); + manager_->setFrameId(frame.toStdString()); + manager_->setDefaultHeight(height); + } } -} +} // namespace waypoint_rviz2_plugin #include PLUGINLIB_EXPORT_CLASS(waypoint_rviz2_plugin::WaypointTool, rviz_common::Tool) diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt index d5391ba7f..8de5d6393 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt @@ -22,6 +22,7 @@ find_package(nav_msgs REQUIRED) find_package(diagnostic_msgs REQUIRED) find_package(action_msgs REQUIRED) find_package(rviz_polygon_selection_tool REQUIRED) +find_package(waypoint_rviz2_plugin REQUIRED) qt5_wrap_cpp(MOC_FILES include/rviz_tasks_panel/tasks_panel.hpp @@ -49,6 +50,7 @@ ament_target_dependencies(tasks_panel diagnostic_msgs action_msgs rviz_polygon_selection_tool + waypoint_rviz2_plugin ) target_link_libraries(tasks_panel diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp index d873e4604..a0f914f5f 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp @@ -45,6 +45,8 @@ #include #include +#include + namespace rviz_tasks_panel { @@ -102,6 +104,15 @@ private Q_SLOTS: void onGetPolygon(int tab_index, const std::string & field_name); void onTrajectoryTypeChanged(int tab_index, const QString & type); + // Waypoint UI slots + void onWaypointCountChanged(int count); + void onSelectedMarkerChanged( + const QString & name, double x, double y, double z, double yaw); + void onClearWaypoints(); + void onSaveWaypoints(); + void onLoadWaypoints(); + void onWaypointPoseChanged(double value); + private: rclcpp::Node::SharedPtr raw_node_; @@ -116,9 +127,18 @@ private Q_SLOTS: // Polygon selection service rclcpp::Client::SharedPtr polygon_client_; - // Waypoints subscription - rclcpp::Subscription::SharedPtr waypoints_sub_; - nav_msgs::msg::Path::SharedPtr latest_waypoints_; + // Shared waypoint manager (singleton, also held by WaypointTool) + std::shared_ptr waypoint_manager_; + + // Waypoint UI widgets (Navigate tab) + QLabel * wp_count_label_{nullptr}; + QLabel * wp_selected_label_{nullptr}; + QDoubleSpinBox * wp_height_spin_{nullptr}; + QDoubleSpinBox * wp_x_spin_{nullptr}; + QDoubleSpinBox * wp_y_spin_{nullptr}; + QDoubleSpinBox * wp_z_spin_{nullptr}; + QDoubleSpinBox * wp_yaw_spin_{nullptr}; + bool wp_updating_spinboxes_{false}; // guard against signal loops // Global task lock: only one task may run at a time int active_task_tab_{-1}; // -1 = no task running, else = tab index of active task diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml index bb166df76..76406b6b6 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml @@ -20,6 +20,7 @@ diagnostic_msgs action_msgs rviz_polygon_selection_tool + waypoint_rviz2_plugin qtbase5-dev diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp index 2f2b32e66..03d41e4d1 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -3,6 +3,7 @@ #include "rviz_tasks_panel/tasks_panel.hpp" +#include #include #include #include @@ -100,12 +101,30 @@ void TasksPanel::onInitialize() polygon_client_ = raw_node_->create_client("get_selection"); - // Waypoints subscription - waypoints_sub_ = raw_node_->create_subscription( - "waypoints", 1, - [this](nav_msgs::msg::Path::SharedPtr msg) { - latest_waypoints_ = msg; + // Shared waypoint manager (singleton created by WaypointTool) + waypoint_manager_ = waypoint_rviz2_plugin::WaypointManager::instance(); + if (!waypoint_manager_->isInitialized()) { + // WaypointTool hasn't initialized yet; try again shortly + QTimer::singleShot(1000, [this]() { + if (waypoint_manager_ && !waypoint_manager_->isInitialized()) { + waypoint_manager_->initialize(getDisplayContext(), + getDisplayContext()->getRosNodeAbstraction().lock()->get_raw_node()); + } }); + } + + // Connect waypoint manager signals + connect(waypoint_manager_.get(), + &waypoint_rviz2_plugin::WaypointManager::waypointCountChanged, + this, &TasksPanel::onWaypointCountChanged, Qt::QueuedConnection); + connect(waypoint_manager_.get(), + &waypoint_rviz2_plugin::WaypointManager::selectedMarkerChanged, + this, &TasksPanel::onSelectedMarkerChanged, Qt::QueuedConnection); + connect(waypoint_manager_.get(), + &waypoint_rviz2_plugin::WaypointManager::waypointsCleared, + this, [this]() { + onWaypointCountChanged(0); + }, Qt::QueuedConnection); // Build UI auto * main_layout = new QVBoxLayout(); @@ -273,12 +292,85 @@ QWidget * TasksPanel::buildGoalFieldWidget(const GoalFieldDef & def, int tab_ind auto * container = new QWidget(); auto * layout = new QVBoxLayout(container); layout->setContentsMargins(0, 0, 0, 0); - auto * label = new QLabel("Use Waypoint Tool (key: 1) in RViz"); - auto * status = new QLabel("No waypoints received"); - layout->addWidget(label); - layout->addWidget(status); - // Store status label for updates - tab_states_[tab_index].field_data[def.name + "_status_label"] = status; + + // Instruction label + layout->addWidget(new QLabel("Activate Waypoint Tool (key: 1) to place waypoints")); + + // Height / count / selected row + auto * info_row = new QHBoxLayout(); + info_row->addWidget(new QLabel("Height:")); + wp_height_spin_ = new QDoubleSpinBox(); + wp_height_spin_->setRange(-100.0, 500.0); + wp_height_spin_->setSingleStep(0.1); + wp_height_spin_->setValue(waypoint_manager_ ? waypoint_manager_->defaultHeight() : 0.0); + wp_height_spin_->setMaximumWidth(80); + info_row->addWidget(wp_height_spin_); + + wp_count_label_ = new QLabel("Waypoints: 0"); + info_row->addWidget(wp_count_label_); + + wp_selected_label_ = new QLabel("Selected: none"); + info_row->addWidget(wp_selected_label_); + info_row->addStretch(); + layout->addLayout(info_row); + + // X / Y / Z / Yaw spinboxes for editing selected waypoint + auto * pose_row = new QHBoxLayout(); + + pose_row->addWidget(new QLabel("X:")); + wp_x_spin_ = new QDoubleSpinBox(); + wp_x_spin_->setRange(-1000.0, 1000.0); + wp_x_spin_->setSingleStep(0.5); + pose_row->addWidget(wp_x_spin_); + + pose_row->addWidget(new QLabel("Y:")); + wp_y_spin_ = new QDoubleSpinBox(); + wp_y_spin_->setRange(-1000.0, 1000.0); + wp_y_spin_->setSingleStep(0.5); + pose_row->addWidget(wp_y_spin_); + + pose_row->addWidget(new QLabel("Z:")); + wp_z_spin_ = new QDoubleSpinBox(); + wp_z_spin_->setRange(-1000.0, 1000.0); + wp_z_spin_->setSingleStep(0.5); + pose_row->addWidget(wp_z_spin_); + + pose_row->addWidget(new QLabel("Yaw:")); + wp_yaw_spin_ = new QDoubleSpinBox(); + wp_yaw_spin_->setRange(-3.15, 3.15); + wp_yaw_spin_->setSingleStep(0.1); + pose_row->addWidget(wp_yaw_spin_); + layout->addLayout(pose_row); + + // Action buttons + auto * btn_row = new QHBoxLayout(); + auto * clear_btn = new QPushButton("Clear All"); + auto * save_btn = new QPushButton("Save"); + auto * load_btn = new QPushButton("Load"); + btn_row->addWidget(clear_btn); + btn_row->addWidget(save_btn); + btn_row->addWidget(load_btn); + btn_row->addStretch(); + layout->addLayout(btn_row); + + // Connect height spinbox to manager + connect(wp_height_spin_, QOverload::of(&QDoubleSpinBox::valueChanged), + [this](double val) { + if (waypoint_manager_) { waypoint_manager_->setDefaultHeight(val); } + }); + + // Connect pose spinboxes to update selected waypoint + auto pose_changed = [this](double) { onWaypointPoseChanged(0.0); }; + connect(wp_x_spin_, QOverload::of(&QDoubleSpinBox::valueChanged), pose_changed); + connect(wp_y_spin_, QOverload::of(&QDoubleSpinBox::valueChanged), pose_changed); + connect(wp_z_spin_, QOverload::of(&QDoubleSpinBox::valueChanged), pose_changed); + connect(wp_yaw_spin_, QOverload::of(&QDoubleSpinBox::valueChanged), pose_changed); + + // Connect buttons + connect(clear_btn, &QPushButton::clicked, this, &TasksPanel::onClearWaypoints); + connect(save_btn, &QPushButton::clicked, this, &TasksPanel::onSaveWaypoints); + connect(load_btn, &QPushButton::clicked, this, &TasksPanel::onLoadWaypoints); + return container; } if (def.ros_type == "airstack_msgs/FixedTrajectory") { @@ -513,7 +605,9 @@ geometry_msgs::msg::Polygon TasksPanel::getPolygon(int tab_index, const std::str nav_msgs::msg::Path TasksPanel::getPath(int, const std::string &) { - if (latest_waypoints_) {return *latest_waypoints_;} + if (waypoint_manager_ && waypoint_manager_->isInitialized()) { + return waypoint_manager_->getPath(); + } return nav_msgs::msg::Path(); } @@ -977,6 +1071,60 @@ void TasksPanel::load(const rviz_common::Config & config) } } +// ─────────────────────────── waypoint slots ────────────────────────────────── + +void TasksPanel::onWaypointCountChanged(int count) +{ + if (wp_count_label_) { + wp_count_label_->setText(QString("Waypoints: %1").arg(count)); + } +} + +void TasksPanel::onSelectedMarkerChanged( + const QString & name, double x, double y, double z, double yaw) +{ + if (wp_selected_label_) { + wp_selected_label_->setText(QString("Selected: %1").arg(name)); + } + + // Update spinboxes without triggering poseChanged + wp_updating_spinboxes_ = true; + if (wp_x_spin_) { wp_x_spin_->setValue(x); } + if (wp_y_spin_) { wp_y_spin_->setValue(y); } + if (wp_z_spin_) { wp_z_spin_->setValue(z); } + if (wp_yaw_spin_) { wp_yaw_spin_->setValue(yaw); } + wp_updating_spinboxes_ = false; +} + +void TasksPanel::onClearWaypoints() +{ + if (waypoint_manager_) { waypoint_manager_->clearAll(); } +} + +void TasksPanel::onSaveWaypoints() +{ + QString filename = QFileDialog::getSaveFileName( + this, tr("Save Waypoints"), "waypoints", tr("Bag Files (*.db3)")); + if (filename.isEmpty()) { return; } + if (waypoint_manager_) { waypoint_manager_->saveBag(filename.toStdString()); } +} + +void TasksPanel::onLoadWaypoints() +{ + QString filename = QFileDialog::getOpenFileName( + this, tr("Load Waypoints"), "~/", tr("Bag Files (*.db3)")); + if (filename.isEmpty()) { return; } + if (waypoint_manager_) { waypoint_manager_->loadBag(filename.toStdString()); } +} + +void TasksPanel::onWaypointPoseChanged(double) +{ + if (wp_updating_spinboxes_ || !waypoint_manager_) { return; } + waypoint_manager_->updateSelectedPose( + wp_x_spin_->value(), wp_y_spin_->value(), + wp_z_spin_->value(), wp_yaw_spin_->value()); +} + } // namespace rviz_tasks_panel PLUGINLIB_EXPORT_CLASS(rviz_tasks_panel::TasksPanel, rviz_common::Panel) From ec298abdea8f74d0e42af4b72d6595473ba90575 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 17:52:27 -0400 Subject: [PATCH 15/24] Fix waypoints panel to be more intuitive --- .../desktop_bringup/rviz/robot.rviz | 70 ++++------ .../waypoint_manager.hpp | 4 + .../src/waypoint_manager.cpp | 123 +++++++++++++++++- 3 files changed, 148 insertions(+), 49 deletions(-) diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 3e0d87148..77cd9e8b3 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -6,14 +6,12 @@ Panels: Expanded: - /Global Options1 - /TF1/Frames1 - - /Perception1/StereoImageProc Disparity1 - - /Local1/DROAN1 - /Local1/DROAN1/Trimmed Global Plan for DROAN1/Topic1 - /Local1/DROAN1/Droan GPU1 - /Local1/DROAN1/Droan GPU1/Traj Debug1/Namespaces1 - /Global1/Global Plan1 - Splitter Ratio: 0.3440559506416321 - Tree Height: 332 + Splitter Ratio: 0.8474178314208984 + Tree Height: 693 - Class: rviz_common/Selection Name: Selection - Class: rviz_common/Tool Properties @@ -627,7 +625,12 @@ Visualization Manager: Enabled: true Name: Traj Debug Namespaces: - {} + collision_points: true + collision_trajectories: true + free_points: true + free_trajectories: true + unseen_points: true + unseen_trajectories: true Topic: Depth: 5 Durability Policy: Volatile @@ -639,7 +642,7 @@ Visualization Manager: Enabled: true Name: Graph Vis Namespaces: - {} + default: true Topic: Depth: 5 Durability Policy: Volatile @@ -647,7 +650,7 @@ Visualization Manager: Reliability Policy: Reliable Value: droan/graph_vis Value: true - Enabled: false + Enabled: true Name: Droan GPU - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -695,7 +698,6 @@ Visualization Manager: Name: Traj Vis Namespaces: traj_controller: true - traj_controller_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -717,6 +719,15 @@ Visualization Manager: Value: false Enabled: true Name: Trajectory Controller + - Class: rviz_default_plugins/InteractiveMarkers + Enable Transparency: true + Enabled: true + Interactive Markers Namespace: /robot_1/waypoint_plugin + Name: Waypoints InteractiveMarkers + Show Axes: true + Show Descriptions: true + Show Visual Aids: false + Value: true Enabled: true Name: Local - Class: rviz_common/Group @@ -764,29 +775,6 @@ Visualization Manager: Value: true Enabled: true Name: Global - - Class: rviz_default_plugins/Image - Enabled: true - Max Value: 1 - Median window: 5 - Min Value: 0 - Name: Image - Normalize Range: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: sensors/front_stereo/left/image_rect - Value: true - - Class: rviz_default_plugins/InteractiveMarkers - Enable Transparency: true - Enabled: true - Interactive Markers Namespace: /robot_1/waypoint_plugin - Name: InteractiveMarkers - Show Axes: true - Show Descriptions: true - Show Visual Aids: false - Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -840,7 +828,7 @@ Visualization Manager: Text Size: 0.014999999664723873 - Class: waypoint_rviz2_plugin/WaypointTool WaypointTool: - default_height: 0 + default_height: 10 frame_id: map topic: waypoints Transformation: @@ -850,25 +838,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 24.656192779541016 + Distance: 44.563514709472656 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -15.954153060913086 - Y: 5.539872169494629 - Z: -11.331672668457031 + X: -0.3901923596858978 + Y: 19.888120651245117 + Z: -16.52528953552246 Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5953978896141052 + Pitch: 0.6703976988792419 Target Frame: base_link Value: Orbit (rviz) - Yaw: 6.003584861755371 + Yaw: 5.133573532104492 Saved: ~ Window Geometry: BehaviorTreePanel: @@ -882,11 +870,9 @@ Window Geometry: Height: 1376 Hide Left Dock: false Hide Right Dock: false - Image: - collapsed: false MACVO Disparity: collapsed: false - QMainWindow State: 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 + QMainWindow State: 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 Selection: collapsed: false TasksPanel: @@ -897,8 +883,6 @@ Window Geometry: collapsed: false Views: collapsed: false - Waypoint Plugin: - collapsed: false Width: 2490 X: 1990 Y: 27 diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp index a96a7b4d7..9001d1592 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/include/waypoint_rviz2_plugin/waypoint_manager.hpp @@ -99,6 +99,10 @@ class WaypointManager : public QObject void processFeedback( const visualization_msgs::msg::InteractiveMarkerFeedback::ConstSharedPtr & feedback); + /** Rebuild node_map_ with sequential 1-based keys and rename interactive + * markers so there are no gaps after a deletion. */ + void reorderWaypoints(); + bool initialized_{false}; rclcpp::Node::SharedPtr node_; rviz_common::DisplayContext * context_{nullptr}; diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp index f315a00fa..4f9374e83 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/src/waypoint_manager.cpp @@ -208,19 +208,112 @@ void WaypointManager::removeWaypoint(int idx) auto it = node_map_.find(idx); if (it == node_map_.end()) { return; } + // Destroy the scene node for the deleted waypoint it->second->detachAllObjects(); scene_manager_->destroySceneNode(it->second); std::stringstream wp_name; wp_name << kWaypointPrefix << idx; server_->erase(wp_name.str()); + node_map_.erase(it); + + // Reorder: rebuild node_map_ with sequential 1-based keys and rename + // interactive markers so there are no gaps. + reorderWaypoints(); + server_->applyChanges(); - node_map_.erase(it); + // Set unique_idx_ so the next added waypoint gets the right number + unique_idx_ = node_map_.empty() ? 0 : node_map_.rbegin()->first; Q_EMIT waypointCountChanged(static_cast(node_map_.size())); } +void WaypointManager::reorderWaypoints() +{ + // Collect entries in current order (std::map iterates by key, ascending) + std::vector> entries( + node_map_.begin(), node_map_.end()); + + // Erase all interactive markers from the server (but keep scene nodes alive) + for (const auto & [old_idx, node_ptr] : entries) { + std::stringstream old_name; + old_name << kWaypointPrefix << old_idx; + server_->erase(old_name.str()); + } + + // Rebuild node_map_ with sequential 1-based keys + node_map_.clear(); + for (size_t i = 0; i < entries.size(); ++i) { + int new_idx = static_cast(i) + 1; + Ogre::SceneNode * node_ptr = entries[i].second; + node_map_[new_idx] = node_ptr; + + // Re-create the interactive marker with the new name + std::stringstream new_name; + new_name << kWaypointPrefix << new_idx; + std::string str_name = new_name.str(); + + Ogre::Vector3 pos = node_ptr->getPosition(); + Ogre::Quaternion quat = node_ptr->getOrientation(); + + visualization_msgs::msg::InteractiveMarker int_marker; + int_marker.header.stamp = node_->now(); + { + std::lock_guard lock(mtx_); + int_marker.header.frame_id = frame_id_; + } + int_marker.pose.position.x = pos.x; + int_marker.pose.position.y = pos.y; + int_marker.pose.position.z = pos.z; + int_marker.pose.orientation.x = quat.x; + int_marker.pose.orientation.y = quat.y; + int_marker.pose.orientation.z = quat.z; + int_marker.pose.orientation.w = quat.w; + int_marker.scale = 1.0; + int_marker.name = str_name; + + // Invisible cylinder for picking + visualization_msgs::msg::Marker marker; + marker.type = visualization_msgs::msg::Marker::CYLINDER; + marker.scale.x = 0.5; + marker.scale.y = 0.5; + marker.scale.z = 0.1; + marker.color.a = 0.0; + + visualization_msgs::msg::InteractiveMarkerControl c_control; + c_control.always_visible = true; + c_control.markers.push_back(marker); + int_marker.controls.push_back(c_control); + + visualization_msgs::msg::InteractiveMarkerControl control; + control.orientation.w = 0.707106781; + control.orientation.x = 0; + control.orientation.y = 0.707106781; + control.orientation.z = 0; + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MOVE_ROTATE; + int_marker.controls.push_back(control); + + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MOVE_AXIS; + int_marker.controls.push_back(control); + + control.interaction_mode = + visualization_msgs::msg::InteractiveMarkerControl::MENU; + control.name = "menu_delete"; + control.description = str_name; + int_marker.controls.push_back(control); + + server_->insert(int_marker); + server_->setCallback( + int_marker.name, + std::bind(&WaypointManager::processFeedback, this, + std::placeholders::_1)); + menu_handler_.apply(*server_, int_marker.name); + } +} + void WaypointManager::clearAll() { if (!initialized_) { return; } @@ -494,18 +587,36 @@ void WaypointManager::processFeedback( if (feedback->menu_entry_id == 1) { // delete + node_entry->second->detachAllObjects(); + scene_manager_->destroySceneNode(node_entry->second); + std::stringstream wp_name; wp_name << kWaypointPrefix << node_entry->first; server_->erase(wp_name.str()); - menu_handler_.reApply(*server_); - server_->applyChanges(); - node_entry->second->detachAllObjects(); - scene_manager_->destroySceneNode(node_entry->second); node_map_.erase(node_entry); + reorderWaypoints(); + server_->applyChanges(); + + unique_idx_ = node_map_.empty() ? 0 : node_map_.rbegin()->first; + Q_EMIT waypointCountChanged(static_cast(node_map_.size())); } else { - // "set manual" – noop for now, marker stays at current spinbox pose + // "set manual" – select this marker for editing in the Navigate panel + selected_marker_name_ = feedback->marker_name; + + Ogre::Vector3 position = node_entry->second->getPosition(); + Ogre::Quaternion quaternion = node_entry->second->getOrientation(); + + tf2::Quaternion qt(quaternion.x, quaternion.y, quaternion.z, + quaternion.w); + tf2::Matrix3x3 m(qt); + double roll, pitch, yaw; + m.getRPY(roll, pitch, yaw); + + Q_EMIT selectedMarkerChanged( + QString::fromStdString(feedback->marker_name), + position.x, position.y, position.z, yaw); } break; } From 20f3636ee7904079d47d75bc6b87a24800b4a540 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 18:48:48 -0400 Subject: [PATCH 16/24] Switch isaac default to standalone script mode --- .env | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.env b/.env index 6c47f55cf..63a62094c 100644 --- a/.env +++ b/.env @@ -30,7 +30,7 @@ RECORD_BAGS="false" # "true" or "false" # ============== ISAAC SIM ===================== ISAAC_SIM_GUI="/isaac-sim/AirStack/simulation/isaac-sim/assets/scenes/simple_pegasus.scene.usd" # Set to "true" to launch Isaac Sim using a standalone Python script instead of USD file -ISAAC_SIM_USE_STANDALONE="false" # "true" or "false" +ISAAC_SIM_USE_STANDALONE="true" # "true" or "false" # Script name (must be in /AirStack/simulation/isaac-sim/launch_scripts/) ISAAC_SIM_SCRIPT_NAME="example_one_px4_pegasus_launch_script.py" PLAY_SIM_ON_START="false" From bbc59268d101e5ada4a95436cba6ffe57a8155c2 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 18:49:43 -0400 Subject: [PATCH 17/24] Change default takeoff height to 10.0 --- .../desktop_bringup/rviz/robot.rviz | 31 +++++++++---------- .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 2 +- 2 files changed, 16 insertions(+), 17 deletions(-) diff --git a/common/ros_packages/desktop_bringup/rviz/robot.rviz b/common/ros_packages/desktop_bringup/rviz/robot.rviz index 77cd9e8b3..6ded1ee37 100644 --- a/common/ros_packages/desktop_bringup/rviz/robot.rviz +++ b/common/ros_packages/desktop_bringup/rviz/robot.rviz @@ -6,11 +6,14 @@ Panels: Expanded: - /Global Options1 - /TF1/Frames1 + - /Local1 + - /Local1/DROAN1 - /Local1/DROAN1/Trimmed Global Plan for DROAN1/Topic1 - /Local1/DROAN1/Droan GPU1 - /Local1/DROAN1/Droan GPU1/Traj Debug1/Namespaces1 + - /Local1/DROAN1/Global Plan Vis1 - /Global1/Global Plan1 - Splitter Ratio: 0.8474178314208984 + Splitter Ratio: 0.5792563557624817 Tree Height: 693 - Class: rviz_common/Selection Name: Selection @@ -625,12 +628,7 @@ Visualization Manager: Enabled: true Name: Traj Debug Namespaces: - collision_points: true - collision_trajectories: true - free_points: true - free_trajectories: true - unseen_points: true - unseen_trajectories: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -642,7 +640,7 @@ Visualization Manager: Enabled: true Name: Graph Vis Namespaces: - default: true + {} Topic: Depth: 5 Durability Policy: Volatile @@ -650,7 +648,7 @@ Visualization Manager: Reliability Policy: Reliable Value: droan/graph_vis Value: true - Enabled: true + Enabled: false Name: Droan GPU - Class: rviz_default_plugins/MarkerArray Enabled: true @@ -698,6 +696,7 @@ Visualization Manager: Name: Traj Vis Namespaces: traj_controller: true + traj_controller_extra_text: true Topic: Depth: 5 Durability Policy: Volatile @@ -838,25 +837,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 44.563514709472656 + Distance: 37.564666748046875 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.3901923596858978 - Y: 19.888120651245117 - Z: -16.52528953552246 + X: 25.773038864135742 + Y: -5.22532320022583 + Z: -18.542400360107422 Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.6703976988792419 + Pitch: 0.6403977274894714 Target Frame: base_link Value: Orbit (rviz) - Yaw: 5.133573532104492 + Yaw: 2.878566026687622 Saved: ~ Window Geometry: BehaviorTreePanel: @@ -872,7 +871,7 @@ Window Geometry: Hide Right Dock: false MACVO Disparity: collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001ac000002f0fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000078000002f0000000c700fffffffb0000001e0057006100790070006f0069006e007400200050006c007500670069006e0100000205000001630000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000002cb0000009d0000000000000000fb00000028004d004100430056004f00200049006d00610067006500200046006500610074007500720065007300000002ba000000ca00000000000000000000000100000109000002f0fc0200000007fb00000016004c006500660074002000430061006d006500720061010000003b000001880000000000000000fb00000014004c006500660074002000440065007000740068010000003b0000016a0000000000000000fb0000001e0054006f006f006c002000500072006f007000650072007400690065007301000000780000008b0000005c00fffffffb0000000a0056006900650077007301000001090000025f000000a000fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073010000028b000000dd0000000000000000fb0000001e004d004100430056004f0020004400690073007000610072006900740079000000028d000001410000001600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b2000000000000000000000002000009ba00000037fc0100000002fb0000000800540069006d00650100000000000009ba0000025300fffffffb0000000a00560069006500770073030000004e00000080000002e10000019700000003000009ba000001d7fc0100000008fb00000014005400610073006b007300500061006e0065006c010000000000000489000002c500fffffffb0000001e00460072006f006e00740020005200690067006800740020005200470042010000048f000002a10000009400fffffffb0000002200460072006f006e00740020005200690067006800740020004400650070007400680100000736000002840000009e00fffffffb0000002200460072006f006e007400200052006900670068007400200044006500700074006801000006f6000002c40000000000000000fb0000002200460072006f006e00740020005200690067006800740020004400650070007400680100000714000002a60000000000000000fb0000002200460072006f006e007400200052006900670068007400200044006500700074006801000006e2000002d80000000000000000fb00000022004200650068006100760069006f0072005400720065006500500061006e0065006c00000006dc000002de0000023300fffffffb0000000800540069006d00650100000000000004500000000000000000000006f9000002f000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 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 Selection: collapsed: false TasksPanel: diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp index 03d41e4d1..66fdd8aa5 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -22,7 +22,7 @@ std::vector TasksPanel::getTaskDefs() // default, min, max return { {"Takeoff", "tasks/takeoff", { - {"target_altitude_m", "float32", 5.0, 0.0, 500.0}, + {"target_altitude_m", "float32", 10.0, 0.0, 500.0}, {"velocity_m_s", "float32", 1.0, 0.0, 50.0}, }}, {"Land", "tasks/land", { From be6c668f65c6cb562bd9cb57c7ae12affd81b6dd Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 18:56:17 -0400 Subject: [PATCH 18/24] Update readmes --- .../rviz/3d_waypoint_rviz2_plugin/README.md | 165 ++++++----------- .../gui/rviz/rviz_tasks_panel/README.md | 175 +++++++++++------- 2 files changed, 163 insertions(+), 177 deletions(-) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md index aa2141005..3a2b1ed79 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md @@ -1,32 +1,54 @@ # 3D Waypoint RViz2 Plugin -An interactive RViz2 plugin for ROS2 Humble (and above) that allows users to create, manipulate, and manage 3D waypoints directly in the RViz2 visualization environment. +An interactive RViz2 tool plugin for creating, manipulating, and managing 3D waypoints directly in the RViz2 viewport. Waypoint state is managed by a shared `WaypointManager` singleton so that both this tool (3D interaction) and the Tasks Panel's Navigate tab (UI controls) operate on the same data. image +## Architecture +``` + WaypointTool (rviz_common::Tool) Tasks Panel Navigate tab + mouse click in 3D viewport UI: height, X/Y/Z/Yaw, + | Clear, Save, Load, Execute + v | + +------------------------------------------+ + | WaypointManager (singleton) | + | | + | - InteractiveMarkerServer | + | - Ogre SceneNode map (waypoint visuals) | + | - add / remove / clear / reorder | + | - save / load (.db3 bag files) | + | - getPath() -> nav_msgs/Path | + | - Qt signals for UI updates | + +------------------------------------------+ +``` + +- **WaypointTool** (`rviz_common::Tool`) -- handles mouse events in the 3D viewport. Left-click to add, right-click near an existing waypoint to delete. Delegates all state to `WaypointManager`. +- **WaypointManager** (`QObject` singleton) -- owns all waypoint state: the interactive marker server, the Ogre scene nodes, persistence, and publishing. Emits Qt signals (`waypointCountChanged`, `selectedMarkerChanged`, `waypointsCleared`) so external UI can stay in sync. +- The **Tasks Panel** (separate `rviz_tasks_panel` package) holds a `shared_ptr` to the same `WaypointManager` instance and provides the full control UI in its Navigate tab. ## Features - **Interactive Waypoint Creation**: Click to add waypoints at any position in the 3D environment -- **3D Manipulation**: Drag and move waypoints using interactive markers -- **Orientation Control**: Set and adjust waypoint orientation (yaw angle) -- **Visual Feedback**: Real-time visual representation of waypoints with axis indicators +- **3D Manipulation**: Drag and move waypoints using interactive markers (MOVE_ROTATE, MOVE_AXIS) +- **Orientation Control**: Set and adjust waypoint yaw via interactive markers or Navigate tab spinboxes +- **Visual Feedback**: Real-time axis indicator meshes at each waypoint - **Waypoint Management**: - Add waypoints with left-click - Delete waypoints with right-click or context menu - - Manually adjust position and orientation via UI controls + - "Set manual" context menu selects the waypoint for editing in the Navigate tab + - Automatic reordering after deletion (no gaps in numbering) - Clear all waypoints at once -- **Data Persistence**: Save and load waypoint configurations using ROS2 bag files (.db3) +- **Data Persistence**: Save and load waypoint configurations using ROS 2 bag files (.db3) - **Publishing**: Publish waypoints as `nav_msgs/msg/Path` messages -- **Configurable**: Set default height, frame ID, and topic name +- **Configurable**: Default height, frame ID, and topic name (persisted in RViz config) ## Requirements -- ROS2 Humble or above +- ROS 2 Jazzy (or Humble and above) - RViz2 - Qt5 -- C++14 or higher +- C++17 ## Dependencies @@ -46,86 +68,36 @@ An interactive RViz2 plugin for ROS2 Humble (and above) that allows users to cre ## Building -1. Clone this repository into your ROS2 workspace: -```bash -cd ~/ros2_ws/src -git clone waypoint_rviz2_plugin -``` - -2. Install dependencies: -```bash -cd ~/ros2_ws -rosdep install --from-paths src --ignore-src -r -y -``` - -3. Build the package: ```bash -cd ~/ros2_ws colcon build --packages-select waypoint_rviz2_plugin ``` -4. Source the workspace: -```bash -source ~/ros2_ws/install/setup.bash -``` - ## Usage -### Launching RViz2 with the Plugin - -```bash -ros2 launch waypoint_rviz2_plugin rviz2.launch.py -``` - -Or start RViz2 manually: -```bash -rviz2 -``` - -### Adding the Plugin to RViz2 +### Adding the Tool to RViz2 1. Open RViz2 -2. Click on the "Panels" menu and select "Add New Panel" -3. In the toolbar, click the "+" icon to add a new tool -4. Select "waypoint_rviz2_plugin/WaypointTool" from the list -5. The waypoint tool should now appear in the toolbar - -### Using the Plugin - -1. **Select the Tool**: Click on the Waypoint Tool icon in the RViz2 toolbar (or press '1' as shortcut) - -2. **Add Waypoints**: - - Left-click anywhere in the 3D view to place a waypoint - - An axis indicator will appear showing the waypoint position - -3. **Move Waypoints**: - - In the Displays panel, make sure to click Add > By topic > /waypoint_plugin/update/InteractiveMarkers - - Click and drag the interactive markers to reposition waypoints - - Use the rotation controls on the markers to adjust orientation - -5. **Delete Waypoints**: - - Right-click on a waypoint to delete it - - Or right-click on the interactive marker and select "delete" from the menu +2. In the toolbar, click the "+" icon to add a new tool +3. Select **waypoint_rviz2_plugin / WaypointTool** from the list +4. The tool appears in the toolbar with keyboard shortcut **1** -6. **Manual Adjustment**: - - Use the panel controls to manually set X, Y, Z position and Yaw orientation - - Select "set manual" from the marker context menu to apply manual changes +### Placing Waypoints -7. **Configuration**: - - **Topic**: Set the topic name for publishing waypoints (default: `/waypoints`) - - **Frame**: Set the reference frame for waypoints (default: `map`) - - **Default Height**: Set the Z-height for new waypoints +1. **Select the Tool**: Click the Waypoint Tool icon or press **1** +2. **Add Waypoints**: Left-click anywhere in the 3D view +3. **Move Waypoints**: Add the interactive marker display (Add > By topic > `/waypoint_plugin/update/InteractiveMarkers`), then drag markers to reposition +4. **Delete Waypoints**: Right-click near a waypoint, or use the context menu "delete" +5. **Select for Editing**: Right-click a marker and choose "set manual" to select it in the Navigate tab -8. **Save/Load**: - - Click "Save Waypoints" to save current waypoints to a .db3 bag file - - Click "Load Waypoints" to load waypoints from a .db3 bag file +### Navigate Tab Controls (in Tasks Panel) -9. **Publish**: - - Click "Publish Waypoints" to publish all waypoints as a `nav_msgs/msg/Path` message - - To visualize, in the Displays panel click Add > /waypoints > Path +All waypoint management UI lives in the Tasks Panel's **Navigate** tab: -10. **Clear All**: - - Click "Clear All" to remove all waypoints from the scene +- **Default Height** -- Z-height for newly placed waypoints +- **X / Y / Z / Yaw spinboxes** -- edit the currently selected waypoint's pose +- **Clear All** -- remove all waypoints +- **Save / Load** -- persist waypoints to/from `.db3` bag files +- **Waypoint count** and **selected waypoint** labels update in real time ### Listening to Published Waypoints @@ -143,50 +115,27 @@ waypoint_rviz2_plugin/ ├── README.md ├── include/ │ └── waypoint_rviz2_plugin/ -│ ├── waypoint_tool.hpp -│ └── waypoint_widget.hpp +│ ├── waypoint_manager.hpp # Shared singleton (state + operations) +│ └── waypoint_tool.hpp # RViz Tool (mouse events only) ├── src/ -│ ├── waypoint_tool.cpp -│ └── waypoint_widget.cpp -├── ui/ -│ └── waypoint_plugin.ui +│ ├── waypoint_manager.cpp +│ └── waypoint_tool.cpp ├── media/ -│ └── axis.dae +│ └── axis.dae # 3D axis indicator mesh └── launch/ └── rviz2.launch.py ``` -## Migration from ROS1 - -This plugin is a port of the ROS1 Noetic waypoint plugin. Key changes include: - -- Updated to use `rclcpp` instead of `roscpp` -- Updated to use `rviz_common` instead of `rviz` -- Updated interactive markers API for ROS2 -- Changed from `rosbag` to `rosbag2_cpp` API -- Updated TF library from `tf` to `tf2` -- Changed plugin export macros for ROS2 -- Updated build system from `catkin` to `ament_cmake` - -## Known Issues - -- Saved bag files use the `.db3` format (SQLite3) instead of the ROS1 `.bag` format -- The 6D checkbox in the UI is currently not implemented - -## Contributing - -Contributions are welcome! Please feel free to submit issues and pull requests. - ## License Apache 2.0 ## Credits -Original ROS1 version by KoKoLates (the21515@gmail.com) -ROS2 port for Humble and above +Original ROS 1 version by KoKoLates (the21515@gmail.com). +ROS 2 port and WaypointManager refactor for AirStack. ## References -- [RViz2 Plugin Tutorial](https://docs.ros.org/en/humble/Tutorials/Advanced/RViz-Plugins.html) -- [Interactive Markers](https://docs.ros.org/en/humble/Tutorials/Advanced/RViz/Interactive-Markers.html) +- [RViz2 Plugin Tutorial](https://docs.ros.org/en/jazzy/Tutorials/Advanced/RViz-Plugins.html) +- [Interactive Markers](https://docs.ros.org/en/jazzy/Tutorials/Advanced/RViz/Interactive-Markers.html) diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md index 2cb7aa790..9ce5dd2df 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md @@ -1,67 +1,90 @@ # RViz Tasks Panel -RViz2 panel plugin for dispatching and monitoring ROS 2 task action goals. Provides a tabbed GUI where operators can parameterize, execute, and cancel tasks on any discovered robot, with live feedback and result display. +RViz2 panel plugin for dispatching and monitoring ROS 2 task +action goals. Provides a tabbed GUI where operators can +parameterize, execute, and cancel tasks on any discovered robot, +with live feedback and result display. ## Overview -The Tasks Panel replaces the need for CLI-based action goal dispatch by providing a graphical interface for all 9 AirStack task types. Each task type gets its own tab with auto-generated parameter widgets, an executor selector, and a feedback/result view. - -``` -┌──────────────────────────────────────────────────────────────────────┐ -│ Tasks Panel Robot: [robot_1] │ -├──────────────────────────────────────────────────────────────────────┤ -│ [Takeoff] [Land] [Navigate] [Exploration] [Coverage] [ObjectSearch] │ -├──────────────────────────────────────────────────────────────────────┤ -│ ┌─ Goal Parameters ────────┐ ┌─ Feedback & Result ─────────────┐ │ -│ │ Executor: [/robot_1/...] │ │ Feedback: │ │ -│ │ target_altitude_m: [5.0] │ │ [live feedback stream] │ │ -│ │ velocity_m_s: [1.0] │ │ │ │ -│ │ │ │ Result: │ │ -│ │ [Cancel] [Execute] │ │ [goal outcome] │ │ -│ └──────────────────────────┘ └─────────────────────────────────┘ │ -└──────────────────────────────────────────────────────────────────────┘ +The Tasks Panel replaces CLI-based action goal dispatch with a +graphical interface for all 9 AirStack task types. Each task type +gets its own tab with auto-generated parameter widgets, an +executor selector, and a feedback/result view. + +The **Navigate** tab integrates directly with the +`waypoint_rviz2_plugin` package's shared `WaypointManager` +singleton, providing inline controls for placing, editing, +saving/loading, and executing waypoint-based navigation -- no +separate waypoint panel needed. + +```text ++-----------------------------------------------------+ +| Tasks Panel Robot: [robot_1] | ++-----------------------------------------------------+ +| [Takeoff] [Land] [Navigate] [Exploration] [Coverage] | ++-----------------------------------------------------+ +| +- Goal Parameters -----+ +- Feedback & Result -+ | +| | Executor: [/robot1/..] | | Feedback: | | +| | Height: [2.0] Wp: 3 | | [live stream] | | +| | X:[1] Y:[2] Z:[2] Y:[0]| | | | +| | [Clear] [Save] [Load] | | Result: | | +| | goal_tolerance_m: [1.0] | | [goal outcome] | | +| | [Cancel] [Execute] | | | | +| +-------------------------+ +---------------------+ | ++-----------------------------------------------------+ ``` ## Features - **9 task tabs** with auto-generated goal parameter widgets -- **Executor discovery** -- scans ROS 2 topics every 5 seconds to find running action servers -- **Robot namespace selector** -- auto-populated from discovered action server namespaces -- **Polygon input** -- integrates with `rviz_polygon_selection_tool` to capture 3D polygon selections from the RViz viewport -- **Waypoint input** -- subscribes to the `waypoints` topic to receive paths from the 3D Waypoint tool -- **Fixed Trajectory editor** -- type dropdown with auto-populated default attributes in an editable key-value table -- **Live feedback** -- timestamped feedback messages stream in real time -- **Result display** -- color-coded status (green for succeeded, red for aborted/canceled) -- **Config persistence** -- robot and executor selections are saved/restored with the RViz config -- **Active Tab Status** -- tab text color reflect active/running task status, GUI only allows one action to execute at a time per robot to prevent conflicts +- **Executor discovery** -- scans ROS 2 topics every 5 seconds + to find running action servers +- **Robot namespace selector** -- auto-populated from discovered + action server namespaces +- **Polygon input** -- integrates with + `rviz_polygon_selection_tool` to capture 3D polygon selections +- **Integrated waypoint controls** -- the Navigate tab embeds + waypoint management (height, X/Y/Z/Yaw editing, Clear, Save, + Load) via the shared `WaypointManager` singleton from + `waypoint_rviz2_plugin` +- **Fixed Trajectory editor** -- type dropdown with + auto-populated default attributes in an editable key-value + table +- **Live feedback** -- timestamped feedback messages stream in + real time +- **Result display** -- color-coded status (green = succeeded, + red = aborted, orange = canceled) +- **Config persistence** -- robot and executor selections are + saved/restored with the RViz config +- **Single-task lock** -- only one action may execute at a time + to prevent conflicts ## Supported Task Types | Tab | Action Type | Key Parameters | |-----|-------------|----------------| -| Takeoff | `task_msgs/action/TakeoffTask` | `target_altitude_m`, `velocity_m_s` | -| Land | `task_msgs/action/LandTask` | `velocity_m_s` | -| Navigate | `task_msgs/action/NavigateTask` | `global_plan` (Path), `goal_tolerance_m` | -| Exploration | `task_msgs/action/ExplorationTask` | `search_bounds` (Polygon), altitude/speed limits, `time_limit_sec` | -| Coverage | `task_msgs/action/CoverageTask` | `coverage_area` (Polygon), altitude/speed limits, `line_spacing_m`, `heading_deg` | -| Object Search | `task_msgs/action/ObjectSearchTask` | `object_class`, `search_area` (Polygon), `target_count`, `time_limit_sec` | -| Object Counting | `task_msgs/action/ObjectCountingTask` | `object_class`, `count_area` (Polygon), altitude/speed limits | -| Semantic Search | `task_msgs/action/SemanticSearchTask` | `query`, `search_area` (Polygon), `confidence_threshold`, `time_limit_sec` | -| Fixed Trajectory | `task_msgs/action/FixedTrajectoryTask` | `trajectory_spec` (FixedTrajectory), `loop` | +| Takeoff | `TakeoffTask` | `target_altitude_m`, `velocity_m_s` | +| Land | `LandTask` | `velocity_m_s` | +| Navigate | `NavigateTask` | `global_plan` (Path), `goal_tolerance_m` | +| Exploration | `ExplorationTask` | `search_bounds` (Polygon), altitude/speed, `time_limit_sec` | +| Coverage | `CoverageTask` | `coverage_area` (Polygon), `line_spacing_m`, `heading_deg` | +| Object Search | `ObjectSearchTask` | `object_class`, `search_area`, `target_count` | +| Object Counting | `ObjectCountingTask` | `object_class`, `count_area` | +| Semantic Search | `SemanticSearchTask` | `query`, `search_area`, `confidence_threshold` | +| Fixed Trajectory | `FixedTrajectoryTask` | `trajectory_spec`, `loop` | ## Widget Type Mapping -Goal fields are mapped to Qt widgets based on their ROS type: - | ROS Type | Widget | Notes | |----------|--------|-------| -| `float32` / `float64` | `QDoubleSpinBox` | Range and default from task registry | -| `int32` | `QSpinBox` | Range and default from task registry | +| `float32`/`float64` | `QDoubleSpinBox` | Range from registry | +| `int32` | `QSpinBox` | Range from registry | | `string` | `QLineEdit` | Free-text input | | `bool` | `QCheckBox` | Toggle | -| `geometry_msgs/Polygon` | `QPushButton` | Calls `get_selection` service on `rviz_polygon_selection_tool` | -| `nav_msgs/Path` | Status label | Displays latest path from `waypoints` subscription | -| `airstack_msgs/FixedTrajectory` | `QComboBox` + `QTableWidget` | Type selector with editable attribute table | +| `geometry_msgs/Polygon` | `QPushButton` | Calls `get_selection` service | +| `nav_msgs/Path` | Waypoint controls | Inline height/pose/buttons via WaypointManager | +| `airstack_msgs/FixedTrajectory` | `QComboBox` + `QTableWidget` | Type + attributes | ## Dependencies @@ -70,15 +93,16 @@ Goal fields are mapped to Qt widgets based on their ROS type: - `rclcpp` / `rclcpp_action` -- ROS 2 node and action client - `task_msgs` -- action definitions for all 9 task types - `airstack_msgs` -- `FixedTrajectory` message -- `geometry_msgs` / `nav_msgs` -- standard ROS 2 message types -- `diagnostic_msgs` / `action_msgs` -- status and action introspection +- `geometry_msgs` / `nav_msgs` -- standard message types +- `diagnostic_msgs` / `action_msgs` -- status introspection - `rviz_polygon_selection_tool` -- polygon selection service +- `waypoint_rviz2_plugin` -- shared `WaypointManager` singleton - Qt5 (Core, Widgets, Gui) ## Build ```bash -docker exec airstack-robot-desktop-1 bash -c "bws --packages-select rviz_tasks_panel" +colcon build --packages-select waypoint_rviz2_plugin rviz_tasks_panel ``` ## Usage @@ -86,47 +110,60 @@ docker exec airstack-robot-desktop-1 bash -c "bws --packages-select rviz_tasks_p 1. Launch RViz2 2. Go to **Panels > Add New Panel** 3. Select **rviz_tasks_panel / TasksPanel** -4. The panel auto-discovers running task action servers and populates the Robot dropdown +4. The panel auto-discovers running task action servers and + populates the Robot dropdown 5. Select a tab, configure goal parameters, and click **Execute** -6. Monitor feedback in the right pane; click **Cancel** to abort a running goal - -### Polygon Selection +6. Monitor feedback in the right pane; click **Cancel** to abort -For tasks requiring a polygon boundary (Exploration, Coverage, Object Search, etc.): +### Waypoint Navigation (Navigate tab) -1. Activate the **Polygon Selection Tool** in the RViz toolbar -2. Draw a polygon in the 3D viewport -3. In the Tasks Panel, click the **Get Polygon from RViz** button for the polygon field -4. The panel calls the `get_selection` service and displays the captured point count +1. Activate the **Waypoint Tool** (key **1**) in the RViz toolbar +2. Left-click in the 3D viewport to place waypoints +3. In the Navigate tab, adjust **Default Height**, or edit the + selected waypoint's **X/Y/Z/Yaw** spinboxes +4. Use **Save** / **Load** to persist waypoints as `.db3` files +5. Use **Clear All** to remove all waypoints +6. Set **goal_tolerance_m** and click **Execute** to navigate -### Waypoint Navigation +### Polygon Selection -For the Navigate task: +For tasks requiring a polygon boundary: -1. Use the **3D Waypoint Tool** in RViz to place waypoints -2. The Tasks Panel subscribes to the `waypoints` topic and caches the latest path -3. Click **Get Waypoints from RViz** to capture the current path +1. Activate the **Polygon Selection Tool** in the toolbar +2. Draw a polygon in the 3D viewport +3. Click **Get Polygon from RViz** in the relevant task tab ### Fixed Trajectory -1. Select a trajectory type from the dropdown (e.g., `circle`, `lemniscate`, `fixed_trajectory`) -2. Default attributes are pre-populated in the key-value table -3. Edit attribute values as needed, then click **Execute** +1. Select a trajectory type from the dropdown +2. Edit default attributes in the key-value table +3. Click **Execute** ## Executor Discovery -The panel scans `node->get_topic_names_and_types()` for topics matching the pattern `*//_action/status`. For each match, it extracts the robot namespace prefix (e.g., `/robot_1`) and populates: +The panel scans `get_topic_names_and_types()` for topics matching +`*//_action/status`. For each match, it +extracts the robot namespace and populates: -- The top-level **Robot** dropdown with discovered namespaces -- Each tab's **Executor** dropdown with the full action server topic +- The top-level **Robot** dropdown +- Each tab's **Executor** dropdown -Discovery runs automatically every 5 seconds and can be triggered manually with the **Refresh** button. +Discovery runs every 5 seconds and can be triggered manually with +the **Refresh** button. ## Architecture -- **Compile-time task registry**: `getTaskDefs()` returns a static vector of `TaskTypeDef` structs defining all 9 task types, their action topic suffixes, and goal field definitions. -- **Type-erased action clients**: Since `rclcpp_action::Client` is templated, the panel uses `std::any` to store type-erased clients and goal handles per tab, with a 9-way switch in `onExecuteClicked()` / `onCancelClicked()` for dispatch. -- **Thread safety**: ROS 2 action callbacks arrive on the ROS executor thread. All Qt widget updates from callbacks use `QMetaObject::invokeMethod(this, lambda, Qt::QueuedConnection)` to marshal back to the Qt main thread. +- **Compile-time task registry**: `getTaskDefs()` returns a + static vector of `TaskTypeDef` structs defining all task types +- **Shared waypoint state**: The Navigate tab holds a + `shared_ptr` (singleton from + `waypoint_rviz2_plugin`), the same instance used by + `WaypointTool` for 3D mouse interaction +- **Type-erased action clients**: `std::any` stores templated + `rclcpp_action::Client` instances per tab +- **Thread safety**: ROS 2 callbacks use + `QMetaObject::invokeMethod` with `Qt::QueuedConnection` to + marshal UI updates to the Qt main thread ## License From df9f464eedff28792be51c5b2f97ae5b45b83630 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Mon, 13 Apr 2026 19:01:16 -0400 Subject: [PATCH 19/24] Update picture --- .../rviz/3d_waypoint_rviz2_plugin/README.md | 2 +- .../rviz_task_panel_waypoints.png | Bin 0 -> 699251 bytes 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/rviz_task_panel_waypoints.png diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md index 3a2b1ed79..1af109794 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md @@ -2,7 +2,7 @@ An interactive RViz2 tool plugin for creating, manipulating, and managing 3D waypoints directly in the RViz2 viewport. Waypoint state is managed by a shared `WaypointManager` singleton so that both this tool (3D interaction) and the Tasks Panel's Navigate tab (UI controls) operate on the same data. -image +![Waypoint Tool Demo](rviz_task_panel_waypoints.png) ## Architecture diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/rviz_task_panel_waypoints.png b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/rviz_task_panel_waypoints.png new file mode 100644 index 0000000000000000000000000000000000000000..f58a48502cdebaa6df496a4bd370b15aff23df31 GIT binary patch literal 699251 zcmZ^LbwE_z);EfPNC_w%N_R-Nf;0mX(%s$73@AuF?0>xJqbD#IU z_j~TU|2XIDnc2P8Uca^W?@aI~c}a{HL@y8!5HO^rJ}My~pf({OAc3AEKYlWyg1Gv4 zd*&o6t@8Xa0iPQOAt1a#kpB2V#XW6*(artUXZ+riqkY>KZ@)ehJ)(ZoB6ZXfuvFY$ zl>defulT#~ix*Fy`pzO@e=Hx1UP3}Dc(T)yNEMZ_n0^)cOL~qIXXVNx1ElUs%K;q` z;)oqiYneH|xZrZy==&Po zHU+bxBgjp3+1BBbl7=tZs*zZ{3|!sYv)by5rerpH{f`jS(#ybH_J7vy5N$wk zeS2$IMcsBjFfoB!G$mthZeEBsOxDHAM34IEAN6m1*f=;y&+06-T3A>(zPwZ=p$`J@ z?(Fb!$|f+;FD3mo^ydf(f+|P1bVB@GJr7+pm;OJ8e?g_+0qHbbgfWO!X`$UhBv?(d zkoa@6erf-N1B;nP;rqOY&0i)Q_cJk7GRruV#mhkf@gUxst5?wlfW)u?FSYI2`i|ot z_EYndWqRQx_*ae;xJPK4`NlH4MX)ad-NbddAG_Yl`wMXJCvnDZL5IB3%?yZY8N@ce z;(im^hKc?j3l*t{yL%Lu)wD`kuW6M*9mIi`B!rUC!QA+-#q>Zh{;^d4c^`egf55=y zL=IY_A$Uip()j8IXYtbu!vW3ouOcNT6Q`^mf^RmLqhxf``t=#bplW(q3XxlJ!-oUC z!<@VLb%7p-RVQKYd-S`T(u=(d&U;OAN44BJ4y7MnoDHjf?G0!JGmbj{l#!S1EL)^F zxpydoKh2DUMa__xNsPRz-JB+f9f5I*Ol!xd7*Ucsz5&&{3pNVLwT;rUJN9vK_N9*b zU@AxG=8?GQgh0H?bgh(kGWxObb3S+pGMsP5vXh@JR`V2ikb|y-hDVdH-hneOvrXTf zWGmd1TYXr(`y*u1lDfLO7PY05uYyf3d6^Qvi6m2lP=@yI%rj!E6%HGzfG|{M_8|zY{tMOb1LGI z;8ecWG%;l~ueHbC=}-{;kRBWh;%dE~SreKhe2+1ocq*lvwzI=>8Oo?M;da#wnST`< zrtQ?NGh8P(Et0&ZF8g&O&F-BF&7NJNab;3`_6}3{tw8qy==~WpHEd87#5U-*Z@dV* zu$P_cK^s3=*Hdryq|~ZCGKNO@%vGCWiztvuWcG;nKh?h;H(ii$MMA1rzj`8Q++y>Z z8g@E(`Nr3^R9{_ZbQ0Q>^Kwz|K-%I;{T>Fw)1pwGX#dFb@hh#5zSgIgA9zG+L8C?< z%<7J+xqDXYNfqYIsdY9+XN}!M1RP&_knHvyWFsukNrdCY_v*?ImcyCgH_E!^N-y0K zYwe;+z*MzMt?;5qn`I#xGPD)NZwY=h9A?9&wYD0A&1Fm9ZBFWU2Y(vMHDVyo4P33X z9Boy(4szGpYIfMg>Snt*DBv%*1(&=e?J3dkEqzn_FdwOuKvip}YrI*Ulg3`9*z^#} zc`{sWCh>bwqrFm6Q?&|n_nOm(O=ZV!wS%+Wj+Rb@4<$(OLj4tlZ@$&qK$cE)A+nGeZEN$3j+0x40%apS(&iOV7O+`=GxrHDlvzTt0 zH_8;<%UgJnPXcA9?@#mP+pw8YGu&d}?CkDo=ietFM*UTmY?(Gv(w~#?Z=OD-+pq&W z^V{><7!NBZonpLDZq;?N^uB&R3I~SOpiSe)DqrpLgBN@zZld^E>3!Ur6;>_(^`QpvX>m%wW%x0UtJed zl}6CF?)*PhZn8+_sDcQU*-~sHy@x+get7`g`6e=Y;CSskhbfrk88_ew@^B+uE$I+c zF&B_FW zWW~rlw@d|~`c)LuhncVVgWT)=u1MTMN>_i5=sc(@k_D&gZGaJ!yPS2<8*H7-g-u4C}p-y*ptKxUxzP3j%sG zum0LdP$`KoG-qg=x;qL?LT7DRMT*$m zd;Jo0q?*>-s@psAJ>5EGDe;sC>vQ5X{Hgv)UN_81y~%@7YkCB_#{>Dazx91Q`$*|^ zT|5v&Prs9uakkn6Xh)Eik;=Kd_h z8Gv1%G8B+hBxJ!Pm)Wd3UT|A4^<4V!R9at}HBYym17M3t!KB2fX_91@GSZj`wat?r zp3ju=i%kY=ZLH_&L&V#FquaED>zD*{0`EMmUVec11W@rZ0@r^`(sc-%}GJ%N!4z0g~T^oEfrY+yK^M27BBuNPWD?;SaRSOqkZ zlhVM!rQg$wfn}Fd6r^a~naSOk-*v3hZ=WG8*x8hMO(@>A?2SYhm4@HP6(5+@S{+=t zET+RhAFd`i+uYNM^@u2Z27d=;vNyxrof>NjKJ1#ps;jKDQ3_QGhrr?FCg-;=(-QV4 zw-6hZBH!I&?TL!pTOV+uP5;XFYEWA)IvsEmn0*y3RIzP8b<;n9n z+v2oailG&TB}$>Eby!^+pHr|vkJ_t9U+BA#Z3N~KDd#EL1-8CXo{oV^=w#Kt(hb?PpT0Xs7Q?If7+#K0N+S}=mMkwUT ziHL&vQ!Eg(+F~N$gC8=x_uchgw;g@37`e+IT)5F{YFwsJ)F`Y@(yLx+j$cu0$hkis zL-gdPZ?}FZhmCP=-$2{hQyE@kcVqcUvhek358(lo*4X^HJ5;OHy;g1^Tm|fJQp%oP z@4Utqh(*5Dw=>9#6N>7WHthL}BJsnW;#WtL=_$dBCV=nE_@XRMNbSdY zatDR4PAXRF9n(sz>YNTQS!EWn&CoG3?=~DF*T$2pzG*n&d^&OvCV-=FS|e!W^R8Is zqJzRbsh#wLo8?pzfY(Wh!7UywczV0&w{ah8Kn^6C;FZKSL$#0m7lRk^rf==AeTEpL z3B1J%&boT#yi4#jCaR8Iz|Ubb#oU>w4-Zghk7Tb-^H z)zdg;N!!q`3f&CP)G-7HK5xC{DUUCGui=IW?G7()`^DXFvydElQofbvxSkTn7?WE3 z4I9UHMXQ=-aVfo>v1XmYMB7rK@{HNz&^(kH>p&9NvBEM%w|%fOU_y+923?sJi8s!< zWz^%i*>qJIFoE99**AwwZ&hHmuEACB3Ho=6x=!ySYMY{Br|(oOv_l=m9aph&J9DIX zPU9>@k5-kFuZ>Y>0{0a5XQk)@?TSKOs8QH}1tP{TV)YK&!AQ($BK46I>~nM~xyXP* zd3l31jqgCtd$kYGK-@^6vgG-ezh$9#%XRk+{E=KjT%JF>rDA9*7Pm8?J36M zDLl6@No(VgHD%s%rFs*q0lgL;eMU%1LU+juZ(rxliC&`4&chy)M}ay$x$1=cuiTPv zepaB(0d^M@MsGfNd6K-~soGD?8^ddl1t4BEE^sV3PhuMvY9>;q(7-&m6Gac6W|)GHQh zTL5uEZLhf7HP01=flc&$tSr!M)FQi7Z{C9Iv@|%BJc1X)+N4nFt;_4wKjs_<3oHf0 z9$Zfy;iz%ow4B^dkd)}IuwNDJ2_poze?=tZG=FK-6DD2#YdD@)WuN9xp(}R8wg8*_ zb(Q_2fy30nfvC2V%as_-KP z`BK88^%<4I3q6<~H#d{_qm{<&tQD5-w7XLU3X3ThH_MZLJb>s8`F32R>x~MWS(f6h zZ0NGt9P?*a3kWOEykkh_E$8&VsQwE>?dWIEbyC(q=2TV(;ln=Eo~6%aXg?P%`G z1QrEqety`)RGpGtMzq;q|3`^tOSxQ^LQ-d)CH@B4>;5*V% z(x%hi+}xOQmd+$)EF)vvTp!zKE=^uKJIqiyS})A@l<)zme(;Ur41Rrj;GPTmU_GKd zoz1>XDMOVj=2tbcVI$(CW3>($-Dz&i%I=$66Tjse0DqmUdOo0-X{Ki>mNEO0wU4D7 z=a&&!QFY0FPX^drd7x~Y;u@qLdf97^5*Ut~j9D7=EF(Tj{4T@>mOj^(`K zkw?+!Q!ae^dH|0yFAr&L>W#$t`k%bEerLe+OXJoiW=n7wm~21^O{bV2mZ zmK!nBT)rq&UELfc(gV*HRfP9d5YUiqbq`78&q1sUOh`N2*GPq4>06Ok0qhUXKorTf z6Fzy8E%oByRoySX{r4c5Kh~7$Y=V~b51?-FA>^}IXr$2%@bmMz?_Y91!cXbynXeF1 z`RYi9JQC${*Lu$Bn#K3d=gC7)ihA>)Vnxzaj)@XZY>kQ+zv_8Ay6*5@&D*31Atudw z@}^Zl%ScJz-YIQeeXTxn)#19N`PGJ&+%1Sw(#TP%bczFby9fO# zXLlRu!kAdGk;s#u-i-hbE!L>#7yb5?!8z!?fU}g$9P6s0O#= z^D4}4ss=0^OWD)Q2ESQ#6n*GM$m?fw9mfpv{ZDsh+zNsr4))ANkv;Dd_|Y|vX+^vz zBe%LMqx$M?5qKj@4Tj&M1gMD@#xcu=7q%v;mA*8f?*M;(p;%yvpvsX3D0*0xQG(bP z08Z@F40=a6cq>-+$kje3XI)Z7+x6opXjym5C@z?;G}i~4JajFtM7ET;cU*p=9`GO_ zAdC0#7-@TkbYOf_e(O$*JPq{kGjpi0k=}&cD8{k4VosDRd8 zRnhflQZYr%94OXLOz1alSJ3C$eO)@Fw<-tMtlR|Q2b!3=@XRwN0oU}NVE=u-yR{cz zW78vNeyh{-PZ2b`9erb6^J{{2zT&CbY&O&u>TS5}{TU}t*L$ry?h^hS`P6hOaQ4QE0` z@#&n5mkc_k2f*AU#`A`zGVKqI91{mr3YVhf{Y;&Ht%~{Uin$m1z7Au$-W-WQaUDUi zS(WBlDV71yjy7i?U;4yJ)%|&hn$`vJI#srb%27qcOR$f5k_~B z`{%;=VFhkCMr3&kQBhR+bNHZp9WeR6rqa>kgf>hkw%voF;Cg@cTQ7nHUZtrt44d|k z&X76Fn}xJ-C%&1GyVs*XjOU%Nwg4BEwGLdLtp5hEzkOCxerKuABn+;&e*z@11Zp>B zO|`48@*|UzOxSuR#U7EGFu0*Q%)^BpQC9FO;V`T}eSmacvGYX&$w5*%ebD#s>31ic zVzX?=`SZc;S@bvCc;LAbryF43#53-LA=u!^YV}s`scr_2@HxJ7w^1u<7a1=XnD553PH?IF<|Z7CiTIv>`LKa~Zned;#6^SXsB9Z| zkPtQ=c;|7CQzX&a)z>YFL%__$x4%z9EVZc$Rwv(mCM#U1!q~-Zu_-vxtg(m6!FpPEs$l@Oh-^l)RZgszAD2bs!@0vxs??9| z1R`9Td}sN8Fl%6x3vqtYOK1kTq@tZ@2%b2j3~d*ISpVQS3;GV$MT8>N5}EVpmraZQ zte4c35nXc0?>0-j$8rJ0$QVRjkJ^yTVTOr@&tiPOJ%&!g%Qog)_jB!2Me1LX-aMua zoB5DJGX3SMBP3gnAfi z0`OVfaYPYT)m*9fbqFoZ=x()LJb94?^mGSIA`Com2t$je34n-IqcPz=Y!jk#w;*t7 z@qCwCDpr5OK@;cH;lT4AqpaAtChC0}*#?95b8@sK^$ZuL1j@ z3t4F8?y@&kv- zzJz( zqsx!{Q0?b#zBzB=88&4oW^gU*2z?H7ualmZM{yJYuIN;Wud(y5gSx*(U)oUr3`INad}C@jhGs-C(5{h$oXf^B8} zIVK!8XK9GCwKUC_5*$Eg%!r|z6{(D*5t_@A~)kd!`|`3$G6w=v3Na zw?`$m9)ri9SP^qz4#K;meB)Bi$Jxl_}rru%7zPAnNwUlwq9bTzrp9YJ~Oh{8Wg%9RkR@oitUh0DO z1w04?QB5b2BFOkA`qccB08g}c16LCFiUDWpWhR-HL zfgz6?+QB#@W@xwQL@t1k!xY_VYpCJ=_IEJlF@r(G*={JkQlui?WgvU5^9Sigd&N_W z3~Q?OkP1NXSvSpbt~}Dr@Q*K86^@VByUjT)*)f)bdlqRKZ9i6c-Ch+pKOHImnb=Vo z3eW;uD2t$!h-iq`pp6*^Ck;BK_m(eun8_` zbi%SqAW8;~FCp62jWu#S0b#&^HC5b+)%LHii>BJyNYiwiQWjm?gG5H~B@b48vvE8u zTL;dQnfW~D0&(VS!wgmhxf74@MLK5No2!W`q9p7BUK*Ux3?>+Gf~e1L9ZhFdX1Mfv1q!ilNA!K24dk&fAH5Zv4zQJM0#yB}4nyFi%73Fy>{zW*Hs+Ozcprtj$8L z%qW}9E~T-MQyPcbLO;1a5=R(rFD`jMQhTcx>R{x>W5|&)0=%d0wIXPydME4b*XZu( z--cI4-SteX;bU#|P^*+o79^x4CJP95h!c}MNQ$ouq5vRe0IHfy$V$VeNU zaUzFSu^?I8-V08nH%rAy$}gBLmEYlvfu@WYOSz-+P9T*R8hUOVSw-=I&ThGh2tq7WHe1jfR{ioM_uUxrZO@q2f0rU`X9q88L)sw z`r-q}@Yw9Co>S!+a*sx1MbGBR@XQCEaHE-9YC}qqk$Ks`CnhJSPdV0Db4M2dopnqx zb7W9y*Mr8ODp8gJA#Kd72I3%j`Ak~Bk_BZT$A!Zk*bg9v-`w3*9}l z#96lh7h9P&71aQuo)5Vo)6144eD529lur+vcc7d{4^w2Yx_g-S)fylg$D^FDtlVG@ znI-MH>}eVyE#vFLxSoJmzXw}rC!qJs+4d38V%8+#Z!SR7Hfm2Tqx2Dd(KgX~L|r0M z@7xU#*6ZL{ea#BH|2pYN1FyE*))`gh z0Q%z>Z576XEQ7nF)eROGL%=)Er}I{2-2%fqzDQ{5)#i%LM-4cE5`V+am>hdFO*MPJ z*#jnBSBjl6fgwg~k_*mJ1@*p5<>-134OEfVuuhahX@onHy9VZTN$a*bs|JL5UQ2cHM< z*TF9y(I!V1rYjrb)&dTMmA7jEwm?5p;}+(KSwE4}jzmasSE$Trvpn=^!ubwd6EV#z9ilFqns1KhpXd%7WIyFP>xNZ9Gdmb=c^2)IkYYeoF(TuFb4{4CrMRe5~P}KpXrK*MKhk2li zrkJoOy*d(TC1u!3DEmokg8oC&+v1z=JaCcJ(Y9W&{n@a8rWO?x^T=?$2lNdgsiT-^ zI@No9tNcdlc?8p3{~_7%9Oy$@#7Vo9sorAr)y+t6rWzi;^`xx-$fie);cSq6VjmS=dP@}Bs{4mJ~msK7e1BF5b?C6q>2hPH0(}wSU(#2 z!zOuz4tL*HCT`?xCUFYs=KZ9(n$07+T5`XfwAANY-0~t~Np+gLVM&KIB6yly@9%f{31NqlNnRP4%f< zkcgLt#$b^=6n5xUmBD4NAZ+Mkt)$=C1}pk5M_A@Pzv#zW!#I{Lv5n~PA)0W6`p+FA`)VSit*B8HOaFRlyKaB{A+ zyL*h!g}sKl`ao-rBWoA79=n#(Z)N)zjRsuvT>OuBc!-K8BPbBNjGWNjYQbv*yK{CS z;_Hs9IGh66m-VD4!3qFZ%38MTOF@y-az9&UP;)QQjVEh4S>e(~$ig=-^jqwGqtx45 z=oEnW9Cp(qovUT!IqUUrw21`i$6S{~;ULzYeTq$UnxV0yGYb22^pC+7xgk798Z#JagjVJ%#%Icju@UudlCHc6O2rT|SD7J8Xs&iLEn6 zSaF6I`~}HbF_K_z$GM1?VpWC45Uk_$#h0V0%wr7^cj4+N#1{Yot;q&hTNu zdUBrVAEr#S^J_f3fGNxF;bCTR5prDI*xjd9C|sDYn}UB2pbyl0`$<+azS=;-R(~wy zEZJ})WQbs5(Y5T*uZgT~6|jUuO;5NyRAc%Ir83vMwZ^N4b4~Tt6iadolL+#HX3YWxKVsad^UFG?KM-c~a^m)3bji zSXe9lfWZ5k+nawN9`7V%wzV#b$w~B5{`Qp|GdTdUzkYpcZfS`X%F-}4HV(dLwIb4kTmc=e*GsSdAz;7dC2ZR6P~&;NsQc{ zdtG4<%#YKLLz19A->sJF2^=?u03G8sJGUd+n7s?>2YHd|+^ssvG4RBfpoyZb_lFR(>|x zUN+-%yM3OTCxk45wNjHQpB=;YKUMtw5Dk+J$z`u;^jKNl3C_!-%^*9R4TI#dw}cb+ zL=>=&)ykm0z@wAto-Si^vQuFYi!`dxtZ49xuIrf)R2}SCS`4&*v~Oe=1mTP*pX&AB z%1rH!z+@Hl(mf|PI;%@x9SX)tv%2PbWT&W<;`KGjj_R_;RAp-RNGeQb%SAtZ#h??| zE206uac9^biUP=OFMfH~9rCGK9U(rYb$C3giOt7+@`*S3fG?*@~5L2kVe0`%THSMIww(m&|Tj*Z1`SLXtPiY&ycsjTstp2?Tdp&Iow8EfrN%I(ZlLM!7~KBuj5>6$5&VBKs7cdCbx zOm5Fc$aqxh*SITID*H5UEDiK5^3+0A*Bvsvd5Mvc=k~a>9Q$lt^_&ftg;NQ8Q_tr2 z0DVUW9aW!Xb&r$-YR;w?Rpm_eot!AQhIC!YcqQYa{hMDiD0OkT0G`JF(t~}v+`VU3 z%z8$>*9_LHP+N}B91WYJ5nA%h*uA$^uR{K{S<~C!;7pdf&PY~$J$CA|NVkTpeujIk zVwHtAWMXD5I2iJe#Whx{-FOHhu36UYgOXN0(XYQ*u>%-8Kt1F$!?)V{h4Q%$=JU-k zDZmRm?$q(h-kO6acM2jW&Wdi$m9W(VZx^^Jfq)N5Pq|&f*|NVnlPZeZNcT9)Y0o9o z(%f+aUc_odDpx`hfqj}#e{$68=B09Eu~KFd+yJjRw$g=n@df^!Eg~k94cK8mm3ScV znex@x4B@@1SBTfoTt#Hz63GgnJK{oFt6>H#S=c5~+h(3#J}|?$-^oS8-KH&dOxtym zk}0D=wcY4D+6B}(7pG?0}|}oCreukEc3bUami8{0?Z=&U@Bhkiu16E8^+h4|Jws!T zS=2vzOJT9c5_V*=Le86zse7`1C0s+NTmIa{(#34HS?puZ1fI?3jMbKDFOMn%kY?>( z*OwdbNxFlzH?FpuguFI5!X@eq>XqbV}cFYLF|l zmk5^7hBA6e8q)Dymec!#9QQnG4Cr6rz4&ekn@OsGzBrj~)Ce7`sOg`bHlf#DRrDT( z;pw$0`l$?8GyJ2&j){b=t*u+D;6M(3Olho&R03_7iC~)sSRh`R&8XzRNK|z33px>z zHg`QNOicM$eI?>vE;oUU>KK)#l_i_MVzU2UO3IR|XqLI^m8MAo@Ay1?p5<>l@;~?J z$#Krye{_r@W=G>4|8KMY|E1`kvj~qiEPc%3-<$c@GgTk*r%L1gun4h#np&z4+z5FS z$^S>Wn6W4Stv>Ppj#=g&Y4CDmSVs#DzcHDpsOUInK1z6587rUT#&_$vNP+GofBT1M{vUI>_fM|=#|>M>|BjMS@tSNF>amNaJbRtg zo;`c^^5x5@+ifaE6ikwp--Hg*0IA&5LDn`l&vSFr(Tw!5ACD8ipqz$3io<6?pmtkB zxxab%QJyH^EXjMO8J|>uR4#ku$Z6l%ULugfG5u8Of4evCi_y+GEU=WXRmU>3)O6#a z#P7P_w>6ylWP3aZt?mBSDg_Dl#@>V+kwnlvN;;P2$*(paADKA1=nMmC{sN_(7vdqW zR!i!Z*486MkXMFzmgP=w7|WVFLs?trlE;Z}K%vt+#E9_o3L+69ICFfCVEU0@q)p9Wx$((po-SCm$pTrDu9V-EKS>vn z=G|6H-uB!BN3J}{`&FPfA!&l(N?hXqu62y6HEPQvt$!Vq@ygB3%@H~Rf;aqZvGTX& z!EY*9IaoTMGs_$+9>FZv&0V!SSl6wlx>!Knk`KXSPQiX_W|?b&gNKLQ9?z)82EYZg zz2jwwhV{~~laM!p`c1uF`UserI`hW#)9W3QnyOGm<1T|eYJMFgTp1b#rM*ii&KWT3 zPo_o8iruJh_`cnSYeuhJ!`Xr?r(zIoOt-n|w>rnpIOipJ$gk8G#j4jb&+A8t^S8`J z!#?{?B-zeaqoxkKJ}x^!z*hqTUXqAONxHiFhF^~yJ;NH!vWJJ24nIQD462DFcBA%V z1Ta?d>oqcI;j(Ab2uq%OC1IE%%5xP)D49O@e2*O7Y{$)kS9G7gu(n?N>NL5UIGa;k zHOorSmDPu5X(vPsMe26HfYlL_#uyt8Bzld;-*7x{u}@&cL}8~Mh`E^1a0k8f%fAzE zShKh1qX-*x^6uMaqekVye?`g*dcu<$AMymLPmzuFafp+X(J^o160ss$dd054>){G- z&un;({qJTb7MV+ zV14P2rH!SO#MG>_9gbBH{tc3UpK%#>_#zR$ZlnrDr80W<4vH##@BXe0eyPGiuL+FpMyYl!hjk|}3Vu2Dhzw>sxT^sz-Q_Xoi6C)(e?GvIM3es;rknCxMzvpDH z7w1I$F z%`M+7N+`>!X_dbI7gUXfMS9J~B#H5uCV3C~{}siZ4rB-AheZ}{Ztf*$zd?;A>htF- zKLW`Nmzq7C_h+%ch}>VVCqQTB9=80pz22P^S>0$9CyZoFz`> zCO)17&qg$V11=dRD|4;0mfj=BE9h#;3o8)ZK^ZC7S@^lAFP0X|YNoWMbqH5M@B{qz zf{;xg!4Cz?bZaPCy<}Qz2EQrd!)wTC&4mV@_5C-`42J{$DG z;ToOM>Wl$ki9>$Go72IiIGN*5j*jl4vW*$=sBo~=TEbn4lf^pL9p0R89uZXbYC*a$ zf>eOlapU=Kaa^c(&~9`NZf}3THJTaO)+X}EI5nOw)|fqT9Y|#Lfxa-DVb3>2@eUi1 zt}PPi$nK}LzRp4vcB`ZR5)o}h6GlGRAttGOUPT>(zuNt^tP4&Xn+7}NqM^xb1Q-=V zR7ArG-XL>uhb(ut{;XG96)63@l`|Da#1^)bis{h3BM}j@=2~6K6YzXC zb-e?3w8YwXzZ6sN+@ClHaE>JOxlnTMEXahdBRJ98X1gz!#$A1xe9#3I&0-vlZxyx=%QR8V)3-`{o4iU5?0?=l!)F`oS^hgX?vO#{)N2ra)I3q%V>q!g1_|ZSH6n@D2qt@U<243>NV2 zq?hxK`DJk{Rnf|@QWVdU`}(a9DXeYH-z{>?=makVqwneE%gYBZoMq<&by|F$yLPo7 zn>*sr;@S z3~!l90odFD-lh9$(GV6v=6QOBHgAqF|yF5<{Pv9fbS zOd!#@F&s4GbU`t@ev20gj99Y4JU!SQy4N%SM9CvImGm)$f4V_0?%=Dff{bQ^fCDv?9WU@_vej>Df}qlOV4Q zbY?c#>+{HaF{xp~-9X7qt@o&9?V4$3rd>Lc;5wkxo@?2=npM%;*MI{%l%;Btd&U~4 zoW(k=g%sdWPiAB6ly{7V0$1*Xq|2;uD{96Gi_Ke~tI;GPExJ`KzfK+b9N0r+v^YZYB7V+_Zgm~eBfhY}5(AM>aGP|d^ z6x~d#o0gHs)7v}*zaBKmju!mtw#dLAUJ=vC>+5Xe(TKo!Bd>`13kPXFk{T|dwCw!i zj;bwz{93;teCD63udBbM?6M=Yfrxww3djo>S)ZKC3EN%_A0dTI)S75z-08E^mJZhw zHDoRaUQ(5t5YN|GNhT(mIUKK)0r{;&dZ8_Yv5_MEgArka z|MD8j?eXfj7kkrdtCoNr0T-U=mpr$Uz2k!Ku1P&P3&b}ar`(OlX=+D-!Iv0CinY$n z8StH#4x1o(mSSSD(Oj+qjVk`nd(LZ%;_S7Kg5_>~P^!!RIDC3@?Qn5w9y!wa@TghdY-elhB|j zUTo|uGT!$Nv0fW}>G3JaDHhyvjKc%bB2|?`0o*$Arna(9c20@73y8EqS?w**D-_B} zFKjvgQ#erY5Iood1&&?;XZY-ez1v7;ADHbx7qpUQSU){tO$GT(SR=p&Mgxsohujj$7{yludMB!Cv|NN_LqR=JxD5P$}QACr+7QQB97uD7ALsqIRJ-*$D##{ zXPI(|f-P}1tKOEeG&$})A(ta}P#;yj3@?(+k@s_NwW6J`@$fTI!>wwLOadgsW=he+ zK*7EE9BU_ylldBcD}^rG@4T7u(Ghx0Ui#Q0!@)($C8`89qN3*fp17z#XE68U9ITOH zP(;_}%hz&3PT-iIC|^cN>?F&y(@AXYP7CDs65@}YxW0A=uH1gM7jX(fb7e``A`!Q^ z+@iYON*j@M8eRM$)Sy`Xf%Iu4`I@;Qg(S31qG%m^2E%}4(-36h-MP>)8)%ZoOsNa(?&ssu*j!n8{`{!-@y2Djz>KfX-%JfisWsUT_~zv(d?hwrgYV}g(l*MI0Z%@+RQgW* zWsW1L$1h-l%fnI`cE$bWf^GTAMy92F{+nuBL38O2xZ)hHuB$O^m!&h+(0{WQ$)lr$qC01maR$GEJtXiFX#O1kE#ETj5w$<+jQn zLOOQDyzFj=szfi)bKNdOO+I?C9=uv^F0OPU~|ZK zypB!A3F}!y`9;^$3MSI&h_Su(33|!)AcH|k1#I0ShRuQLtp<%~w^mvQhWBt}lOSP| z4(ilwtJZMkDwJRA6GBwEVXNtZZ26LE{52Nu(_M`;$Zhm%IA{d(y|UuIWSz0AIk;9* zwJ_n?E=XxnYJ-t@?Y5WGRcSEu0th{$}jS*;cv~2xR-cqg` zUp4A9+~L-0KG7>Ala-hNe}=tO41+eB}Q$duw`>!2ev&7tGK9#G-&linv-|$*Pk4TL;LbOiP;ft_!Df*Nn@tjMH z=xl2Mt(fGDWsucwrNtFsKJG{$n^j^l|AGLs*N-l@mR^1jKVZDd%50wNMfTh;YUyQ@ zFJR{h#z7|gviTg@P5x(+C1&gN#Iq4q230(fEx)3yh`Ak*r0%RpQ`4-J1dfB?Ckwp2 zLoA!ymtgZVcWfA0JC;ZuiX1B|myW zY3Z?e4i#7T5rf&93Q?a{jf6?o&}ehVN?ls^hT+UVWQ+0AC6USB*Tezs&} z?qf_&5Vl|S_;(Sxw#rqe02b}~b_Ef5*JG%m{~IbUug|@p&3v`N_3^5O6341y9quD* z%V5mkG%k}1YvwW&w;F!7ak?}pIob@q5e}W3=KAtYMC7N~-V@+w3o;>yhdfPV(&p(6lOQc-B;rgt20{?xRKJOdD;E)G+PH2h?aj5m5XOk9z!w-)g}qqf|&V& zkw$M;UT7~0hiv)fy}XAE#(BSwzf(wL2drvuqW(X^-a0OhC3_!+5a0$45?m4p?(P;W zIDz1x@x@3^3vmy28SnM4X?!l2u?KjpgNK zi`imAI4-N{pTN5dxbE(5{HZL>)Hp8176v8i4OleCV4H2)f;d7lkK(J3h-lS+8aEwsrxpk9kYm*pseY zf#uz#hAP2|5x*OwLa$b6&Fj#Ru%32!F>1j>dC!upas3I&w`i9EX+yl%b@&!Gb;4jO z2I|QML*2Z{A?R^`9r-9M1jIVwwjH=tzSOTJ3LVS0uT6rc1p7f9_FZaU8MJ>xTB-M(Ae7 z&NC0^x##W_RtfOUd1M&m*V1$@Nu2=DLgZJvCk(q20P+5oczM(QGh_0+GtW8%V?bACb^g?CWHB**>PAY#rV^uh2Of=V^FcebxOKnbYrJcrI4M;(1?6kLeb*1VUY%w{ne+k+N&&j38W;WtL%No_&kOHbG$CPPc zFzYvm#VtgH7vVf8Wo-06f6ntA=gIi`QrZW$n<9;9Df>e0>dhg^f0G4lv1Dvi&b)5r z#!!4o6<3g&oPXfA4i@ZN##Yr7Xrcyd%(7K?pkar{`o0V!Yer)kxFW4Z4I@ZXPgDnH zcyZlLHm^+q7pgGS@V{ee*RX$xT$(D?f6q7Bf`KdJ+z5NyP{*fsL46Wc&L0wh#K(bj zY^mXMg6D5MBZCY;;$4~MlLM&jQl?h^b6PKMN=;iG8qx4loPByaXDjYC{V8Y2l!t<2 zNg(dc8Yg!vzJr{l`|7Pqc?jNta0B3kT^hY}5Yx0LkKuBlA@r(Z#-rkkEk)lbU@6iK zSEnt?dFKAh1eZuINyHwLH<$77i|@Kc6M(MMa#vALx+cHxOFs#w6sNRaD%(?&^m#3r ziFW?3%$9PRe0+X@n>J)dXQ@AfKo<-#Wb_(Kl36J5oeFC)+SzZgCP13ELE=Uz?IG4I zK?>zYNJ9_X9cp!+eOmgrmrl8pe@-r(eZqp7yaM%<0>sD1=U}x(Kwn=5v`};NJe+`0RVqb^t5t>$Xxw-4dKF?slEY;qY7s;Gl<|dNwH<}Lg-*JtT zAy;T^Z7=jy?z(UQnoXt5KJ`P+*&w8&S(v*9mcueFaeI$*C!)lrqP9OB-`dgz+5f-xagas$yX_bG%Iq!`=2?%w;b+vD6 zXGBE?L$8k!kF_rUAoXPoxx;LSTUxj(7XA{xw}{s}!0JH1k}>+OufhV#e0is9Gx(~2T)C3>JTWybFzp=pGshZ}Glyy4aR++8qvswdIIU zmu@`3yiBet!tzy-!Sd(lzFq8NL?lm(TL}(bu)%=eQEPFz4%t9Q6Vkv=%vWk8q@V`4 znNL3<;XX1ps?pl6U4;e%TZzxl@9#eg?z$`nu;4u&3CU{lQ1Y#QIC|(`8JwPXx1*A) z&3J#9!ORKbv8*FbQot4Tg)fR36C>0tAXLdHn0uInd~!aVw)(u)nA`q2pOgTpSHUcO zy?%{~=rwNyT$9K%>-FTK&-)}Mjk5?CnvgxRXhY)-o#x1?kH226Gb8zI#?43>ySK7u zIvPR|d`>#ZiXACv5!H^=3>|3(RoxKI?{-Nx?WBTI$^6gXSB)=6UHYPSp7kv7;7NZ`JWtDX&4dwK6_<%Oil;nm{9S}E-HJAo&lX=oweR{aq#zpe3k7&akwhvhFBmtB4dk#` zc@pRg@OO}-%M`?|?WRmSZP_pPc&@}K=M51L>mI#Ac=T$%j#$7zj%62}YtjV=c=~7> z2}Fa?RmhmJ^v>+?H)(fWNv!U!<&qz~{`JsAJ$(Jwy^8A|2QD;PLivX8EWExW?e&%< z3jDsE7fElJIbJzr8}>ti!qrF*s|VIEshP^CWz$2Uets$67O&_wtPBb4a9OmzaY!o} zab1`%2z@!o@=Uqja2C9JqXeo8$DndZg8D560o%a8rFk z%@H|Uve6v8G(UU<(0a(ZQWqn{6`?ZIDQqm3 zMF8#C#HxHZrcn4;dq(q|3lX&{ftq;>imYzOK;J)u>g4=es#$nUveQ|TNz}KqWn)T3 zWf$q_j{?B;a#bU0M^v9)xE6hGu+pVN7H#n;{x!J<< z<msmd{Zx)?`a$(vgDY0N5RIy@fuk)UdOe^qN0-i&$rIdB%^3%`Y)% z-OVAXmuPiiJ{>`yw?r!T?c-y>Y&xgF9vAF12?2omdG-bi4|M- z9_4wdzT1H$TWmH+JvV}#6m6EbNQFNzX5%6E_tU1$LU^n=HZA{RnATz9wRm#)^ele z3WNNFiKCOJB%j4_94h)m>iZ&FlDe6!f(7|sc2o1yC-hYUNrt-p zJd?&*G|puCZy2?HO>T{qyLUM?t*M>f+T07Q;c;TjQ?RDk%&Qc2gk5Foiju@{^$)_0 z*5|Y!rK-OAXy0Zhz(X*UNEn^}=BSrmw*F6shT9wz`~WEf3duwVx2xOxobI=UbO`2Heeq&s;{ zs0p5Oywh@MymA*qzOuTYmDoA!Dj5TCe@gPql5p%W0G6^qi?sw?Uj@s}*LqPj@Ons`;m+VG?wKDDY1(7gV zmQwoj@_pXc`Entnl3+^ktih91$dU`TfUiP`z(AlGCEJJG7^08VAD2nKW&YxDomPZM z-E*a99OAD}iMiU}H$1O+0Oj3f&SdsggCJCVmo!}Io?SRhPaw)^D-Sn=)E+=5)pcLWc)tmV zZDp@_+jupHhI4vq*DYl*Q0WVcHvNH$YBHM6hejrtOeL527Apo93x|+!pweu}V{J(@gCne*5?*gRfyJWJ&FchK=6Yn|(ehkxivpdxNisB_y95v7K%4TS& zj2$sy>*}h(LQzZdnKj1`JD8s4~O6&u35bt)X2s23{M&Y`tJ(jGQaKeLr7wUJ1SHwo=>}`z#jUY;>?!_ zr@PV>kx5aYo}bla7Kx6$b33*K;-7m&ll}mB68a)*I1x^nuR@cJli@g?=W3=E?kgczot7s8UbmZNBQ;n%@Q{1JODS#^122 zLdo%^jdv8=yiKRo+?byOPreM8o5Qwvg)+hB#&5&F)gh8v&6VMzcPgW`>V1=?$FG5ry;#TxEbkBa@z!2GnGP3w zxS@>tqDk(LUy@Aj1Y;w(HZPoNNtjt{>7Oq5)%g|HFV)mXlDj5euOBM5zOcnwxt@OU z%$t)sb`r!(=+6{7()cS?DDkm~7x+C6Hp}%}GIwsWPiL5HBt<)#h+W_dAY^rY9gUIP zJ$`O~{%Od*oZoMTPb5-5U37t>?$qX&OP}vo0`~aRhp-=WRLH{cfw2G`$2{XU%zY8_ z*FtH&Aqzck>SC4HjDX0GM|D)UeLR*6lL4J2(ooAX_IVwPUEd~$jaM*oeGUw~6wi=! zxjtc4bJ2ruFy8D5ji53fm7Z4}qj~v3oztlj^qkq+J2Y1J;kHErTj80LoF|k9l}2Rv zqF5>a4Bzv3=`mtim%8D+UfFfuy;)$B3XGN#F|#0%CHFzQ`Hm_fY{f};OgrN7jzgI2 zoSBLKW+!MMVxftX>Apnlx}I&mELg zQRy!T}hbLix1rxp#dnyDOb7#hF#se9EmWC{* z*L$Hr^^z9bPk3t41m|yXm#Ptro@ZM#k*t^Dz%rLvm?MoHY66oEUU*L@EKYE+RL9a6MVc)UiVcf7W50dd9zn=KtD1)fGhD+Gzp0ybT8Fk< z5C{m=Q|cv%`2xJ5J>9H=tbB~oS){>}CI>^D)?5kSq%Y!ll>Bl+jCF9^+8)p{kE6P5 z6hBUIBxB(aZ#W(qk&BW$>W&54t??3H#&{2I%xgrn8u)hZd_X8vJ>Vb3W7rimYUbVX zkwxaEMtlLI>uJt z&EcL9bv4G~;WKDA>d_{hCJTW#99YXJ1Cc7eYj@i~1{XHJ;=x(pmOJpuNUkmCacyQN z+qY((&cN&?&w9b(x@BJt+t5kU5F!5TNkhDJJR69rNZ2AAQ|)3kb}{6jaMw(N5gq2-|HT0OrmdquGi>*~&F>9GO<49ZxQdM|W<)xuSR@m$PSu_zMlL z??T_mh*{#%&=3h;ZR+JE#^s44vDJZeQpcD+fdvE4>C<- z1py~|kyRH7>n2%^YZsXMhM(Nwy(gP?0i5xp^3OI7N-jt8+Q`=#X4jCVKj(#({0FH%BuQqEBD~u| zXVFW!(ypEKVDr-n_3!sI=ux9);)Nb}lz72&d08Cw-*ZL4X-}{w zeucd-BL&WVq@a&_w59$SDW2%93}&vYjd@c&nDNXwfzd}1PPa5$CX|5S%uZ9p@!?<4 z!xu|xdwct>`3jRdpN;fpGW}1VIu#(QjCzgn>+6QtI5>3r&Ad%+Cs|($RSK8PyF+nk zXboBgb!u(yg7eQId)wRHu!)G}a{W1JonF1ehl+}d%flJeKS89gV7lTF$W1b}SR^FF z(&Rqfu*A=|oRn1<@+t20p_-$yr@LElodjUueRFCCo7&+r>n7tdX_p&zyow?hQG_8p zY4sXi)B#E#brx+F#HXN2tPGA6kr&eghsU3}^RF))l5b{SCyw6Ze(R0C`E{iSyO%nj z+dZ}tX1aV#tRKk&`M@;h{i@neo!y>`hxNv0y)*B`7R^J*3qkx_X_C`=0fad>_R_g9!~J=!V+u*lHDB#?D;|cWQCgqz@`^`_p%p8S~lT{P>}W z*MWl0utDONt~T}Gl)zKs;0`PNcNwd zV43I`Nx9j>5ypY!0G{xwB*l zxQ`wl!|>&gM>eZx#Bej>L}rdK75absv)kR?4~K#Hn;=u!?KQ}9Vs;dD&aSRzJz?)) z9e}r}>d)+FSJaO@~A4sy_+8z4d5<>^xU$;8Vmp!ZL_5K4s7U&?cpzxEX}S zXX_m{Iu$bSV6Omd>{v;@e*vaFZ+X-I4^^L|q8I%a7U0iv#m3Wq@qdFu?Qp&+2?q;W z5D0oW;O+fWXAO3Gd&7A25ba-F1ygqze*@+b6OfZxIVFsb;I4-M*T}pu zgpq#X+;46;|MdfRfKxAX9@ub=A`_Ao6@^n&OnrZvS-xOH!sqnb-X2ms`af6@wWb%> z*W6LCOEd%^Yi*hP`xaT**$~@OGWI{qv9y#1W2Tw9s{dOP{oih7E{Ky#XCRgeq9**` zXC+9SUa_K47D4~EC4Uv2V)F-1dv7Fh6+ijEKKgqHBL&u_1n!_ z2#oX_5*oTO{!1K}NjpC59fL7<8iZc;Kg#uwgNrrnckcp6%$p9Xy6bt}BFL4dW2p=Y z3d^L4xUvSzjd&ZH))J*)-QtI0dD@7%$;o0(x_~Q!w^o?h0SXZCOBjkFmMM7b(N%p^aDH4?_@hL0VTbuI&p6sRG z*UAfPncef6tZ0mOcDnO5;X-lLUuq57roZvT4Y;WCV+5?Yoh}c+pmwl@AI#go!QVbS ztX=vj!$k7M#HLI2(xQd$LkbFL-A)!Ib7d1q%)P!AQ5T2T-9&P5Aw}ekOiBJxZCd{N zzx&-s9S$@~u6f&sdPk4rrQqmr)VYi8j#^g+0wiX$p-tyY+C9)q#z{rR>$bbRmFi=p zCfI8RR#(5ODyXfW9d+D69@p2Wr>8$b?=YkSOyJZX*3O$dJ7zbA;-GuPG;k@2{eaOL>?<|ZFj_hQ|KSW4+AaNz^cYgP{OA&&-Z&@BlKhW}+Z|K6Ia%a-d{!KE2}OCx698Qd_gShwQd(rRGm#>d~x z&MMbyaC#6P__I-adf=5|t^yi>-fXEzqil7AZ^0-}^a+C##i8%`P)YOi`#GT1_yQmDD^;!{5=*a*pv#9gY=l>A>`zv zU805j+)`HC4?786-+n7|^KjeYe4*1JG1#wmc_r8(m0-zT>Y76fFNxBLIyA&d?1Y^Rej;CqYGDD}sc7GDb&NjM=wW@+(7}_le zB-1VkMh@wP9k8XyicQN$J}RSe;uwMFDvKV?mn% z>^h_pt>xtcLF3mE1RDN8Md3{4eq{Uk6 zlP&SyNLo@jK8w>vCn5~^spR6qNk&HI;o)Ieqs`}aNef#e$LRj@pu49hhDM1D#@h)R z$Vr+0>jD0~C3EAkTVCHDh=XwmO!-TP&8sSmdr;s6g@pWE%-!S`jOI%9U{^15Q|Y3_ z4M@N&FbrbaXTuGk7ys{0aIxmPJ50E_xd}sP0rRfCw_~Kw&d%Q3uQnHE<`N$#QczO| z!Ftr&ckg;;iZtM1+$m(3jsooQzh+@68_o>;dnEt0_Zf-L%#@Oag#`v$c4&kC_bn-m zlV(Z(d$pk$n=#nxLADZ7QvVM>VRHC?$y=Pz{V#coN+HC*{j$GG7V^0^-|#=&%zuu- zf$KlLiI;cCm}DPe)s;(PHgi?q79PkD;DHUWEX@jIt&D`=#QOzM=KaEo>dP%e^`+nI z5b)x22>AEvEu;-BEiHvaL<}DSAB#u@J>J69-eM>uEBP6mG9{&?j0u9szL~>cRRss% zYwZ?-1O=x>Dx>Zfy2PL4|88E1j}Ne#-iX5d4|HPg;X|8#g!Qehu8W8mgXSyV>GPu5;V&c!Z?-n$ZG5>}X|8fG=7qtGnbU`J}$p7$+USu9_AT%&` zn(BjxmzN5R^7{}^c}MfVoTwKW*c9+JGBUs_vqYzEHGjEZQc^wG<>pZjns4l zaU`qHgnfB$FN~5@EZe1MUwIaPvb&|1)`fHDL_-Rx)ez<%xz0NHkz}dW4U-#puwPJQ z0~q=YA`ANG7ZEo+7ENxPtnu15xppxWlW1ZC@+r`CefC6!thaHA_G;H>Z#hQuaI;R( z+9IvwdLF^`p1b+R4{XK4nIk%9pp}4A@;Wk(5r(xkL(wMdo9axe@~doS&fnOd?eI~3 zTavIrQx(%=m1!Z-WIb(9a}v2<#W%^M<_5)Ebwr9tMduchZu4v2y*#{^z2~pTxC`Vs zkfrrm+m}eO;n1-1vgMD_qh#2yVK(cDR z+Qqbog0bwHWCuMdLDgaUQ>|k@&>YIPA$Efax3$bu-FBis5-qhr+kUbt_p%sM z@A|5w=p9X4oj@s>C+$KxxdEgh^)lBn1)cmV%dzLvwv%f|m8hh4TkDUlP&dr@peO58 zM@t-Xw=zEvv%BC$eBQ!1BFPH`ulZlr0475+J1E6QRGN@!YFc)<%_`KNO{5E+2<_A& zh;vHfXlgjy&k0Bm=U3?N9kX;iPzC!qzoCoHErUFNQ;d$>`Fv8RRsTRM?as1Zl8Wrv zq@Y0!k@LbOX!GP$YOM(V4Po9YGm&0sI`m!z788)w;eD4TZWZ)Ooyu2ozP}~$!W$Id zJLrq`750g@7eM?{qK9mCYZfPSC=ZT5y2Rj6KiQaHh&u*P;pbcGc{-l%q><4Ytg%P^ zBEC?j10ZRqpKw;`-z68B1>6ecjP-_=c}*P1p+4c0Z*7L|G#|4?MvaZG%U^r$KL7Cg z_Cz_tM(k70(qQnhB}x(E4?!RuC;REWI0i#rqx^aZDSRw*{$PiZrY15J^=Li&5i*Ky zBNrviK5B1%R3nN)KJPIFNQ;W6$kAqgw&Zard?0I5q`E4KV=(vyjOvx=|KX&k{kg63 zo#jFcSzwjSuWB}qcGsOM3*l@ zEivXDYDcb@d&DB$Ktwz+mcasTD=n+IOwHJo}_}xcKKb>B@x16 zY#V!olJrFooc)l{z?C6P$V!gX#^^ZK$A%8ku+U{TOrWd}Hw$`uXCva3o-yTZD1Y=R zT8Xj(XA(Sk$~96y{3v$fxo4wePFgQIy?aAjacSA8bkBlJ^zRdQ)0*O_3D$CL^z`sR zsOc7Vy--1yIgUH&2Xl4-BS)tX(td9ntLf#ATSfSc5F==P$)4c*behNZ5QyJypM({; zvk_rD`=4(FC$rjpNJ0w;_r7tcHMREQWRzvr&~Vyikj#i$DKt2nWlV8&bL|=#LFduH zXQVE#ucv-G-VLi_I$_V_(Ok|aP*{ERpVQI!P;Lm90Mi{_NkJGUx}@DfKvB-o=E*w_ zlT#2npSF)URZp9QM?7aCl%2a#cV@nm$#yhDom##Bp77;B$g8==u$dMMTegAX?(FCNoIa1SR7B)dsuXEg$T`oH~~JnM3kh-Rf>AW@Gjrs z14wonm|o{Al<_F~h!pp!f<1*@|-nWRD=*T+>RD;bI`uhq<2t+GnH_*~uf825^aGsAX zMBJ}^iZb0Td=xqXD8~EPzzJ#3!}Tbb@kF&SDf_NN#&}VO**NA5QAAgE_fTK85KXgRB{s5 ze#hyjDzYi3&pylx&P zxOc?gzf4j#6kN>g3;_7C^&8%k)vfk>20}NJ0hanDyoiq|s#^nd9$BWZb=)Oru5{$S zqzX>O)m{y4>^bR_p8uXrY1K@DJY}6Q|nT67!Vi7(y_9n%6AWk zJi64-nx8gyEJ7`K_8b!w7cOVD4kjPU~=b*T7uL zcLg-mQpHSn{cJfXHD|F_M$nj|iIS6YmZK*Qxv*C7q#r!)8%D*Rpt5soCj;3V-_uR6 zRftN4aUcSnPCiZMNqs6c>!R#-=Xvu}m%*~5aZTD7_lmDMvvO#oT9_)WlAY5Y`cIE< zEW0?;e3ppA&();d{xn?-s+p9RR>Y!|}28hlChrm$48~Q-ee1h=cVi0 zI^W1QW5QBXXRN;itG7zlMjxMmqejP)ldXYEtphpFC57bJ@=1k#Au?5h1y}15LgLS&ut*N@by!lijE5Q>r_=p8RpBUM!k>Pr2~JaBJItqq;~h z>ivs9F0)=RjmUg^&%@;(SLBMp<_Tmj~96-^O)i3a0o&4 zDbiL86g!$*w+H9G4LF_qyxrsH+@OV8<3inlJqjhx#tInpT=KZoN1Gez_XU?RNXu3^n#Hy>&BW4Ut=8xg4T zTQ0-g*^@~OnztPaa>w}*dTd-9{ zhJ2TQV{4x?rg4+?Nxf>~Ii;Yz{BroZsee;xm zS6Sclt3DRW+%!>l+8=iUbNGxBt6~}=+Vr*M+DAjqNm!#>`Y0C8j9hCmJfjM+Wa>EF z*F@NuWCHWELS6q}!lCd@h; zn;K=zyJ+cc`e`G|0aajmA3`j}a^A4HgAlRaW=*Pgo#%+i$G+B56}>_z~! zODkV`#RqTwF|AH7Pd-;=K6*qEl4}03Zh(_K zMgAk%{75Fx=}N=Dd43_Ek&>GWp!dkt(F7eo?I}Z7d4v4cc8&ItTWG<8piiB>GrFhe zT;aZYU4zj9T0(}bRipEtMXo7i9`E15Jg>+d;##&MjdoixgWg;NE!>$%ayQ9JA1Br{ z16!s1LgwcBeHIGt=D?RnBVaurJZpXZK2>8Yxk4YL*7civN5j{5(vH#Lu*X_l(cXAc0K(;IlKC5WMnNhvt+b4xj=^g!ADXj*@#*hh<G|Bt{Fpt=4YGLc{BU|sQn3|7yJCsm#Lr4FKotEKVTClB6H_%v2>@^}H7VcMn zr0lviVY$eG;6qz&6}B<~yei}#vLk7MwiBC24l_AaKU?s}_y5^O()#^6*;~0Cs$z|dtJl3u_L+( z=RXus8V#LTdba}jRRtB2oNT!gaGLs5j-skaRuA>BsxAvM&E%*JtiI!#yaX{x(2$vJ z&60dA11Di~(L1}TUI5ZYRXSN38Th z*=kknB&$`?uWd-4cD%XOe8F=%?|Qn9BMkOM@8|g1{dWN6=Sug|Qr#8zOXLlc#R4Nf z$KTVaPL1y`5vEVU>_=%ZikMtC8Mx0F`rcQ_7aY=%(ZGA{h&0mX`DR0)@tG!5P$&X{ z^tmrw&7K?+61BzFkzU7tawy5sx=UH#DEz74gW*YpNc2vC^u8AOjN1FX_>eqQfN-i@ z;)07d$x?&bPsxWv+zXe^ZS@~g2#u=dbNAC}=EDt^k6)2rrNhg?YYVQ# zAEAPb-2LCs005g~$AFt(w54gw0~)Qb;O*S&Gn*>FnV=ELJ+TbhQ@hSwL!6+?;zaX> zF956PrLJ=polP$d#M9(~I;KpUh0)oo@Y~CtsP7td9uK&aQfS1|LIW>$XokxiJ;$rb z`Q8f77W+jDrgEt<{6%E_H3{ZaU~QAT!q&sPCuC4?CzaF9th_PcDDgd~N8UCasqy^{ z5t)P_4GwBvZkB#A9iCtt;(9&l&r(~b;@_Gu;iDtEDqF~W^0-Z3h`BUHHkjCheTGc@ zWNG(^9ApB6*Y*~;Mm()`R4;XbSb8%1?a^9^yy^I-C8Gp7?@R98cJwpt&)D?<9m0+o zzm0t@Ebb<6hP~UjI@{hAtN_E3NEsJ~!Cje|ErUhmwiNuiZ*vD_-JCwGq~mudc-$pw zGHVL*RD`Sa%m3`StR)ZwbMxG*9n*pf;X$Pcl$kKoB4AF!;d z{g?`z>u+l_`Y0`DmQj1m`X14La&GJ#B%{$^^4q4|P4g1o+ZjuuDAI*q#7Ui?9AK14~iTv;z%gB+No+`d|e%Ind z8X%nXROK}eEn2!;?~|#fEmOVboYgxNQrPGbhxmvM7XUn~XOEIwh$f&hb`ssc&s|Eo z2dKWk{q)C&zyI~V?PC243m{v-n+di8bypt4Q#>9 zq0ToMX^^_$Y02Q^#b+$+7rPD^057Z{3a@e_Km zsm>t(4Oy|JHSONBU@h}g>@joIfeJ-rUXimv%;AY{wee;GLxho58?$_E#MT4LJ(j2B zLA|x>M!Kj^7N!Kw_=z4_@lF&-c{A5^KaDEezp6OJw7b;gSO34F-!$37Ot&H7rX1S!m=zvDf!mzy!V=i{pq{*#7dhg5CZj_J0hA z@3$;XU!}SR3vS^~-L}$A_uuIl|y|UR0k*nVDsiUE2Uvd~ZZi zL~CL;_TUfN!c}YBj7@x2Z)a}WN00rxFRx2{5<4JI^77`wcZ4(xoX+n}Km{H9jyGGm z<#DYCKKeS%p(Y+>z0O*EzhUt6-aj|QIXec&tNA>qaL=Va5$%2?j!Yc*;{gS9>HZO$(6b<-ezsg5%@#o*rxEw{qTch-8QP_ttkl}$ztgGY>sKTHX%?I& zUMk1R)fG`t5mReRSM)-!#W|@s$pe9&|01!G9I(mYie95=nrsL{IXYJWwm>--0()lS z9wWTI%D&rQ8h?lp6wcs`&XBni#oBcap07S&UGSLtf#j}{_j?y@q9`$Dm(R+YXTo)h}p9aaY!9*jHe+yq(p79 zLe3=2xse+M%A|RLT9I%spzM;GfWXgox(ui8I~nc3sL6PTo9JOP+X-Y$1cn_OGE^H5 zjOCA?{tO=Ff5>YML*w6OT&K?0cr52Q26~Akh%srP9kM+}!>OS`ZT5j!5@k&Xj zv|rwj$R0Pkdu$D5n}RrP8-|Zrnvr zxCTXq8jR&NfxetS)S8s*WZxNIn6~no2M)F7i=7&@Rcw`gWUq?lYdlp$YIO#$Ze{+= z$_o6?QTulDUM+rtmcKOwuqyitlHM?!B7j#XnVr(W1A&}mC7qxCCSbe7#OyK4svKfD?@#6u^fkqHUIJne3V`sP2KTkM2X*Ad5 z7`Jh{M5^WtX;}dH!F!TLaHS#m)~!SKI!FI*s!SOVtIqrtCQp%Hv=Z-0uMPEfgBp;( zo?n);{^1tq?OTV9KAZrR!0;rI)zY3BDfVmN=)=&>4|IdW|uF$z(F}oqCkBpkC&Y5}N%jGTWY#m3911wPXt|NJc%(mR92ut18IL1`TUO?%z3)%5~W0Ss6A%Q7F>$LzFa zMN(^u#iV|tDx?VvwptaeZDL%E0dQu1(=qD~B$sIqmisb3R`Yn0U*;HHSxpy!@Sn_W zHf)T}A4Y42qlY3b;g$}{Zf(3jws=b?I4d?NUyYO?`k0mo>H3BcP(X% zKO`A@Ju{fQwwy%D5wsvtB;QO-(T>CkiFyLoD_t?E%ccL1uD5`y za@*dAK?D^A0}yGEZlxO)0qF)oy1P4-5G19$r6r_O8l+pK8>CAb;Xn5|=icAFcYNO& z5gu4 zq5M&zRkg>=gH@lrSP~&urviPMkH=|R`1NH;Ln*#d3Z4u4XiN1i?gcxU8{U6T-#FjE z5L4{SZ}Lvs>e*C_*_|XYv~LV_J8@&Ndw!XFSa1Wk@O3YPnU&xZ=3xoYgbcJ=NqW&-6W^5sfb{ z;fF7(=}dYOGBtN=$vA<3==q1H!(iO@Sma@{lrUtiVC|ME=Zkx$zI0B~-B+d*(zEKf zJ!h@B>#9;#Y#R($_}aTpl|uhJNcEu>LB$KM%jhBC^PYOKvuCD@5+DC3?l7H6Ttr$| z*@BjO4dqvoIcq*gn_o7}mTfFqYZD*%p<<+M+jRBu|B^kdWFwm8DpC7Gf|Pc6Awk9k~IS2w?gy zmxBE)wgyDejH8P7j{klv)>z}fu)`QH(tG1`FXl zQLr%diR$d^M0-rRqNnH}{;wOU%2Zfkv-taIRet*XnY^y94m!PevzcH0Ii8J3Or(GR z_d}LVi(_FShbuafw!S`b4aHlAHV{|P+S(eq(TpACQ$&QMj*b`0?;q(xbZ}ir-+Ow< z+1N7CT^Rp$UsD&f=lG7*+Lf!xt|8FTR&y8`pVg?b%y_ua_$^|&)Z*K8(m+P>bL+@- z;v4*fUbQSI+!Ydfj_8+Zsm=#0*bg6;IPT2kZTB%WjgCh7``-kfxoob&(#pyM5)x@0 zodx|_L2PtX=&b1D=eM}9@KQsA7%s83qa(&7TY(l@Zl}5&u2)r6X|X48*{@?8_9fB` zGeYZLV7_LIZFKhbE<>xvL_XIF1)eA|q1Uf(rlqC*vg5X~wdHc&*Nd}s&K)%Yo}MsJ zst1f%`y5vLQ<#Ps>FI+&NyCbd!NtXu$Z730GBT3y&TWa_)YRnT>-$x=BP4IT3uk!E zPN7I6>D@adc&9;WoR81-g~dhjV8L=#Nf;e^6CM3!fl@?LQZEQ_UW<#@ZayPiEQgN2 zRW&slHg((+T7NQFwTGSD9^)a)Hu@ znet2(CI$utIe9CWhIBHos2K2|5@WeoypOh|MF%8r?iDTEENz;_nMk!u?bUj!#q1oO zVoA!t5WKYX*(Sd->Q1?@pUB+GijT=!ai(}uj6K!7IaIhWOt*P6$9}%!-63%%7!mL>Fpvyhg}=^{PU+*Abz3wWt9Nxw zc0W=9EAkG}Dv03`rL7+SdMK?@^n9Gv^G`CzYbCxt+t`U4nzaINi% zWDE3)f6kAyQ&Zou81~5&sIrZiup#sT4Hx^jkyHz!UwEVKwPHzsiir`ClY0Og4XJLo z`L@~YxB8NlBLa)vxhCicxCghSe!z77QWTh@K_mjnuG`gqiHU@A^76MZG12DW%MA7w z+MwICnwr`pHWTc-{3nl9R8&4^Wx?oz594MlaHo3x$$T-qQr*!E&Ii35NsDYxpWeHB z_wJ1A4xiGOH}hs=-`rg_oR@Jn9eA>(Qz&5>l$DhYdSaVkt0!*N*sV3g$mpcS(PxFT zE*lI#3e|68-`FJfIMGh_I5YmDL0KK8R%8%2iDZezNZ13J!U6&HVM zZGB}JyA`FZp$$I!`JU6(Y=eON*>CHRF_Y1}G`ZZrq~?cXnskTd)!4UcZjoB(<1%rq z&n+x?X%vZM5A%4Nef)R}2}eoy_T5mVRG~nn*j@v8C|q3Q)KOhF-ZsX@#!E|jaNbo- zY7-O9{{k_4L)md9G{?! zhG!8NF8_pp#V3xk8pM99{UVOP?l~&t3(HDj{@lv>?IL%VcxfP!YlPrg^QrdpG#Lf` zO5b}6C19jLyrFxr(%UzQj*bqEzNK-F)_)A;%2Tb6njl5o5i%?0(%72_bA69*zL31GZ8F z(NJq>co-Bf+8|fsJ)W{9lU#BhkBhD+}1>S~a09JCWyB8G^7dFKe#sy-emXi&>^FX7ii8q>(Ws9H)eU0w!9QIG@LBzVz-|KrTs-&ns~O=;u$xa5 zd;B?j`{WneK%qL%_P2A3XnK`qn3+sNOZx2;`m(Iug+($Ky#B@+?+6Iqz88n;wYan4cB0BE70};vEv?bSP=SQ5-or% zr*HCTXSRQ%s6ooagcjK05{aCHD&zdz-1ySc(#g&+9TRje1eSF#l$0KVqeZMc??DgC zD-jXfixcaMi;G9hdN)BYIUme1)2Q0g(kx!l>y@aAH|-Rb+X zkgO=}2EL;&*VA%Uchb2m2FzOZ6Z!m6Zcjqes_;t9aE1_^j2gr~=XTtFS?TAp*N{!c ze7;dnj?3+`B+}jCI?OF&zttZCA=Ms}K_$3_^K5Am80Imf%CM69m|jKYO-TuLkbh&h z*7L8@KI0}bZ$>|x}4*x0SGr9nQ14YDQbsLZR4jNvtem`UT-Py#l3uq{{n@85RO zjOqb$xu4~;rJh@tvqy=wfo~CXap6Xyp`oGIsC(qy^c-Xe$WFk+2eF{rpTjW-XRdvU zjBNEI@$ers`V7YhiT7mA8zR1MXX|uu43RipkLba6wDk9fW=SSo8z^|oQBqoZx)8_& zAAv+pPX5&O$PC=0(LgG)4B?5mq@+GHSL$;B>%KDWI7H?#cdH-@(q78Vk6 zTBYXI+O$EGcmk*QO|=b$kdP1(NE5!go!Y?7?H(SYrh?so?tLFXUBIK655We)(L(4X za=1Q9$J_3HJnfgCPX~iX>_0RyGc&)bFvCOl^@!wDhXEul0yiq zV6@Q9M!~y$KGPP4@DY0Y`p9jw57o+y?t`;~z!2>nEJ18@^Gl@yRo^xpbzME|B3 ziG+kiwaf?^yC17`yhmBnec25h#7B^H_@$;k#^+$X6xx8`RocbHC3g>>grwhfr(Ogi ztQ^gT%foMkF%&O2NLzbbCns;fky#%LeL|Z@Dl3a&JeZEdpj!5XlhbEz?j8~dqhCu% zJZ58yTI>krqANh|GcmzcR_KPnmWqm?bX)?0qO>&a-@o=ANyf7-9!+NW2YpdAnFZP3 zT#TlNL3ecT#mOQXoOxHn*g|kxuY}mhd3n9oM@>O+BIxAgQ`!$_5HyC4N*=b<)kzs% ziGOD&3tenMCOsm70y@9uv|AIoWmi0sUi1z$k-dRqxU`C+ZlhV`xbrGoYWa_y?vON> z!n$Jl1LruYB%a~JFe<#g3Ff0L#X9s3fh_9yP&5p!`LKo*Cdnp^3}9lS!G;Ou+%VSuWP#SO|LOI;b|1p!}_M!jEvYr zxf>VQloqCA^DZf5h%inwe~G|ly*=3HI;u7!_4C8smYnrb!3>#H%ORhh%GvhMGP|qs zY(F)fGXq>1Ajip;q2ArwdjbA-)C8!2f|+vQ`>U=l&pW%ibVl8KF6 zUqA$sX(0fO*`1x8L7b5)Lv1u&!v^otr)?$Tw0h^|bq&1B`-OE4i2A8WNz)W+-OrD} zo#leDKysXMrh;_B8f}x%F2EZ zMvNL8eWJo#9M%USw#*5L!&2aDSF0?BvoPR87s1=WZ)fTW5_(q%{ScqQ&!4=sv?RCX zalXZYjqYnp2o5?D=GYoqjcCL5=Zvls@M{pgsI21DL8k0eu|2sUL&E_z zjE#+)Z})p{i@=Xuq6!Kvx1%Oaz`jCyi1Zkt(lty?Ox%JlWez zR5~6M6NCHy{fnPl?7v-5Iy*(-QQao3+mB&nP&w@F?M-sn;{FsK?lqoBC!YK_OeBlk zF_ejsfgcg2c)=rp8&jgWZa-DIn{f(9W)O01@$KU_MbqMO`tmuMSk^3*_vJB5Y}N@Ru5!>wLM?qwI}O+g*faN2RN4j%GU}?5xT|Q?y{si8E;$sVy9-HVHZtk!22;?tojYhA;i1>k%~@|8ou8zZK@r8+t1L4NWM zB0TG*@Av5+-bO`5P2_j4k+`{Pa15!;P>H^HmPA}LRf^k7h_&FbWD5FWA{4Zslt-_` zxP6-pHjTuuc9Zh(*jWFB1OhlGySrA9P$rEQiB<4`Uj)|y`y5n5oKCxs$H&JrCvb3Z z!XhJ=?$F8mJqZ367vO`R-vQ)SQO<>d0Rf0+R|dQSN@XWb(Zim0ho);w~VO_%E>@a%$NliHL!6wQbdA^?YGR#!tyksH`B}J z#@%SlbRODrA>kk3FI%eZ!{}X`(c@h~6vmrluF`sL24F+|s2*l_EP*sjUz;K`eIS@5SEKO?|QZ2N+ds$H2D zD#(Ydt%4yR}ycer zaql7G3BH@(Zz#bs-6qmlG^&-w|CT^g5x*8!a$$>$Am_k9`Pzg->PlDdMf70uIWLZk zmA|IL^Nqbj8KQF^)VJ<!SUk?ws0;@%9s}s4n6LBx5D76%;sPu6Qb#BKK-_M*UMa*`-A1$~oN#f#qB4dDv$V9- z+TLCW0-fPCT0%dFE&7pAIHbI4bJp}b2;5nyCw1ehdd-Bgq!zw7Mu zba8pv*U#^Mfs(jbmow7Bf|Mrv-0CmWz=s8J$N^F6OXed}oc-qjD>)s;*9oku3*T|Y z&oB3{<7MIYCU)fD_)(xK4lgMa+2w!Y^P9dsqov=MQ3sN-mj`!?^@gx#E}r;1y81;_ z@A1u?4f>|-&}Sz}qw%arYMt?D)Lj`U7p~A%IEeG|94886ISI_5H@bY_^F-b2`;C0v zbnEAW(ldt@jVB%b`Zid~eV0$YW3qdiEJ5sQjrzrKoZxNJ@eKaUcg(&F!^!&VB~~k# zIg&G$w$AqY{L&JtJ!LXHR1FDz8}cz&N0;)iVL|rE zdT`ukFn+fy6MHk6J1$B68K$kb!GT=$iv1AQuRsa-Gw4QYO^0zzc0)0mznIG_%TV6REMsU-L+0Hrt{D! zF!r33V>g$cpDFydL~`MqbjDsM_ZH(TzCyH~R9kXdh$|cKg(;SYd8iBk`Z=uZ3B9N7 z7XAHxb-dUb8b)Mfoo-j|B>@4u8?z*8YSaNAn+g@UnUZO-_Xp)}?(JBE5ZthhJfT+@ z;zOCbB?D0iefwxf9BPvwk%DdmD$p7z*8x=S^%~MfM$~XF&uK1$rZ# zLevbP54dOOef#FaU6MXPKA6r=x?CG%sIm1gb)ETk=*0Bbb`BNGn0#N#QeIb(y%PH- zqS1S4VE`f;2>RJAXVl- zfq|vmDniHwJv|cO!k*y=`+RuFG(MFhiv?+O();Sb7=rpYoidNG{YK2#6H3nvoVBaV z%F5)L96{9%2LlC1*`3Z=Q$axxX}h-Qwu9@Qp^Wd#_iZ{fhlzv&m&&ReyX4&mGrn# zVE4@10?F6!XG!<-jp+i&e~K<_>M)x2Y{RLoCK*B%nG+i`ZSXbaG7Ub!Q6@Gz>cy zXiqX-*`Hja`gmtCU040mvF-!CzJ30)7mZ0=YU6M+LAq?HgL=N=i*4Q|Jemv(lcDLX1-N4}{Lo|j4>UF57> z5}zSH<&Pt_ugYJ2d^RhOLX4vq=WQA??EH-XV30K)-{zPl}&fx zQe9hX3up6-QhsTYQa*#cVmCB3f)-MvCiY6za`~hB6Y%F@F)^!V*~4ox@N=F?bxq9- zv-q${xhjC_LeNSeH#b*tIw>EV_cLK2i&pw0#1`d5HXSN{OG0}c}k8Zx;GnJ@jt zG9TdL#xRTfa&xxl*VelFF0z3qMWlg6aNSdT@sW`VCUqv|6U?jkGX`Iai3OCZTOYa> zu;^{fZEyEMT`Fl&6+9YUrTSE1-JXl}VKo7phB(@EG-G`g_qTfs4NG#}!Q6duXx_*X zox^y~c|0zP&{51NEFFECC(1XTLrxF>ea_B~nc%>_(QMnMM1rkqB5CzLJ=q4=myj45BAcV_(Y5 z@|bmeH2VXidd zxsk+_Qzcm6i!&qQl^WMZvGB@X%ui{)NdCaSa$7rIuA_z*n6SBAAdJ&_e4B{l;c{AT zvY*Oy^fx94!_NI`-s3%IyLkrZ)T_tDIUA&-)35NN?1O8Yed3k!>-F?GMA$ec4;Acc z8(kczc%+?W9X|<(>4-TF6w!o+nszN7xrHAyEFaPwoRFGuPb1e-#2u(O?8+gr_fci0 zvf&TLxCA-KdB%5alG!`iuZWL4%ln%BW!bmMm4+XM+RD_1BN&&_a6^+)YV#m_8Y`{M z^ah<;uJf!6;?- z2nYy(l4+jRB;==qkZnQ=B<7p1rmlVq9sLPA`@@9Z_Q4F1TX*kvKm#&C+NwiIk~-wsZX3r^_M*E&1f z(Bp)GiD>{0ULYWYvP|_>#U!-ba$wBA(T1qweS%gsU`-&-Zl7&%>a5;x-+;nV;udr- zdx{^N+3W=AFtkgJ#xDXd?&x?d_nxi82`ZOg4y?gvLy1j}R?iToj==(jY;^5!Rkkg9 z9;~cCu)|sqNKb$MR!eKo(CfnOwzYLOum>EHuexr3;EE=OYqDnKgX7i(?bI0YqQ%9< z1+$04;^PBCLqkh--U`is2^7?}u-Nwb@B#8Gauybp`kA>qzQ{OAp0+;CPsmKQ*%Ro# zq$|xF=zLuQxc7yJ$0de3?dbhhx@v{I#b@eUa=C!6_MzJYrckn!`?m*G?&@J!Iu-Iu zyxJZf5^kvpgGC#v6TR)QHSRnu9!IMt@rW&#Jo{&3KId)uPvH{Lu8%1*ZzK~tIHX9o zgb1KFCfg@t2i~|(+;v+VTf=6@NL?b9cbXCFy8ME+4b|~aXL<)Kd87)3aCrsX3ckA) zcf!MOrz%-5ucse~ey(-ZQHbAVUCXiGv71?6S3lwu!ktB;W*l+MpJPsM9=mJpnM5u3h zpk2qIdSkxlddfx@n^lftW&LbnElVgja-7=dUb;!t#pBeWjcW7Oo0tZM5xcz{sbjj8 zf{;;R3t@1uLV8GUK@7w-J<*IVz=;FpZrS3%fQ-&(LsjaZx_& zEUvPW!=${XSxg1#ZKVYQ#u+JiJBEjJ4LVn$;s<{~oWIIR1OW_C9tvjW5(VEn02cvu zMN9)nB49V0i!)4418f8UqKWZBct6y{z|*23`VJzBVx**`nO=M__?!t)BtiiX!gp|F z25KEG5r^FKvaVDePR+A~-qu!ZPiGUTu^@^l08d1Og+a+1YWqMV;DjO0iULK7O;9j< z_^=&jP2|yGNZ(>Pt)F=QIaIDr5p>v@k%W376nW@yZf-#HCvdP(15$Ph zf+jdNJN3tMMH+n2wsC#Rv(%s$64Hy))fC8rJuXiTRV&Oyq29}7z2H--4)g)wtn_7u zdO|s{J%mWy$%zvh>hvv6*^jBiAHXR`Ms!}s<9Fi(Rsd9UI47rV`}u(VvOlKT*5nJr zk`6}XrSCs_^d>J}2ZHj>?(RhdsNAvlD9|`bg$R+D5~Zy|5JORbYNwW~+LSQ_(@EXA(Q1^3a%o&pOo5+227U1b=oUO~ z+NeoqUmqn4ON$ELmRO7!gLBV*a!j~*Ce&r110tBgM|VEZY0!>NPWnN?1q|O!3=CVP z2jy=7KMt^o5wqXS&};0!|GI9(mi+H5w4n9AUBa^!Vx%LH6#ca`!B;*jy9d#dc3V^R z3UgcWbalq-!xhzWTy*RM9%{HR={-vpy6aD-xT2nx-`Aa_=GOon4ugnIwj&yk!1)KP z^4e!z%E+QohelD?E6oJID{CH{e*5s-a;bSdxcg1YMC^ME4BUyOua1W?gdr~BHCx#_nw#y`d!EvauShEHMu3ndK+4q4}F^3$IQ0sXkkmp5H;95>{8N` zAKQE`vUok(?MKj_G;6!&+t&sc_d}L_2gzB3r_T#U%oMOJ>*<)@PZaVc7tbl5=DU(zbOkxk8Q=Ie7coBk zy7NZCv!G}c5u2ivYYQ*tXS^yd1)hDKwd=!ix_`KPaK~gjAYB1l@kJw_``THDTKk>1 z-j$ufsc7Xnxl)XS!s3503%(XF)}KxzYNeJn2?rF3DjyEBmR{1d|3bfCBcK1^f#L1Yx7O7VMREL5Z31<|Z5wJKnw zo2j7(2r?>A-avxj*Z@GGy8SLXsFH<7&4dyl3Oa~>x=_)C`2!DAPntIn)E_A+2eck= z>!<&eB}v?Nk&y)c{Kf){fB;>gXyFG$1gr-SUS3`Pp`oUp16UVz?tG`ga3J*sFBDY( z!3_mw8_X5!YkZG_s5U|Q7YWg44jBb)pwdzk-g6hWF3c;Y1j-5}l>Fd`p}?@W*+F;} zG0MEj`^MKd^ivL#=649#gMhhZs9y?o*};5erVn@UngI}}rl(&znzS^8d6y6?lmhi4 zl~eEdJ6R}9Gky&gOGH-ozT=ej4X9CT0X)`cHQZY$n<4x;Gc&4obF+6Fh&^f6i|u!a zxJS5Fx=LYoMUBH&7kqH+Q|)UIt+Sf`2)g`pUaH-KX83MU>uIsYG&iCgywaO+qY;+u z5xdzVK9}EG$J^5g7#i~T%j1SC**9;#k7;^hV2Ap_EeyluLLsUnj>Qm;nm)Abgi><} zd{C+rAtsP9_}$NTJ4ie~#m9?*O+qXMA72vibFZ~6)@U|(ARZ^m4a`po3F1&2LU117 z8QUt+t5sSM!SpZ#SneQVzIcGjp-R^c1eK4$!OO?9o{mRFhW*Kig#%KGoPxqDZ#0ZY zTsGvcN1OBTK%(~JUk^z7zfB-}gSzaOFNT&1oCKiawe|LH1zgjXaWU>aJIp}(-rw)Y zsJ{O5xJ{eOFPtH0dUcy4NW$`&W%K{s)Y!y( zkH1@O$l9Nh($f5_K302h!O@kfJ$UP7YI<|C(by}zvwQsl5lx%Ug3hevHwCS9iCvt@ z&4U7NcPFC_W@RSf=(^gnqFy8%FQ3lX4v7Hi45b@dKoSR{_};pU#z(U~ zsAV;CoiXA`E{eTQ8INetzxe)Vs?zEKk!1KYz>%$O1A>Dyp)>@6gjq%RkC%*qmFiSZ zs(jT!MKm8pP(3-)6Ur=SFF$N515O3hO_gFTWT=opw?1ZQTZpKzK4j96fEp1TyBB3*O{$4?*wO*FZU#sU*pJKKk_cuyh=!^#TKq!)jw7%VIEBMo?Ru z6hizjnhnV~bV{5pf=FNx5Z?k7uusX!A+@zUP&-DDd?4KBoP-NAoqb9T`aq~ zYOaYLM=8*#fU?^HoF-Wl=drg+4-`fWahvC`C_c($a#ZcY}$*z`N+EP60m2!NozpJXi*~MSEDE&6)biaYkC& z00iF`?%J>x%J&FTArPb!w}8Cf4kQ~Ol#%oC5y92T$;mmLZ&h+Zb|%BC0U={A7?8b# z1KW@>So|4}b8}20S`9J5T!o=D!5e6pg#MwSck%G>s;*M%Suo7<#D4BZl=Ti#st>WN z(}*(!KF9GB8uy`P^sfrO9r6UdD<|h2b#u?VfNKj>wA)od-03&ha~7Yb8|hmKJ(5v+ zVPs5`XLu#pC z#c@hh3o4~lTK$r@MFa`nC7ZAK!cB^}G9vNCK!a`d0fr zH7a~N41(s*NgRjQZ8AQxq&c`cEecFJU-lutJDw#z5A-yc^2L=`R_=(IHJkf=AwU?h zmt>{tSnRegZ?x_DLDadK7Ax_BaI3$nCH$}M(1@V`u#qK1MQDl!Evr&vwr9T6zS2?QU0qp zViFR+of({#!(r*5AveHYWfc`*blgn@6lrlFx7~lljRoi)6sWomY^&8clcW-*vZXg2 zfh~dQ*OJZupw9Fj0f9L1#2904*G@AkrwO?vLisrq*lks6jAra_6I}CvJGy4~>(FJy z#J-X3mP2B%fvG%SKKyp$5cp1~RqgHVy5SF54 zs|0xfyib7^hk=0s68@BOo7!n$J`^A2x6C)L*;P~Smk zNn~WCk5sm0MCuBYlIY1;2(mfT600Qe)? zf|r-?pL&aGLsibaoj@Y~pn(H0f&wMKL8Dfky&o~+_F0$56a!9Ca>{0AiM*>{zL=f9 zx%%4C?&8TzpPA!J=R+eu(zC*vD0PE2iu+d$Z3l4(E3U**#1B?dQrT#9(mMO7BRMH4 zWiGs;nu#Y%9Ekk}+wR3HLd$XUjlTM-^hN851gD~1sw_Npk z)0-PAtZTO_$T61tkNZDA7OcCE*y(di2*NC^F@5xR6QEnm`B$gja`+b)AUHVc>H*SA z2duvj#R&r$;?$myiHde%Gu%v0Mf?5)&k5_>%TD2W@|@EYfj3_GP84OYAB;58^@64S z?NXok^I^ziid)*@tt)oiOV`V_j)n1EA9wa^#^0tq*Vofqu;YIH`gIUBUcctc+mS(3 z(6F0&Ohr_{8b3L?4gfLySHg zfs-&K)xIR`^CC?LrUFFoP; zJ^s#4n){={VjUkMk|~o&+~`E)<>ZVlETZW|Ci63WG&Q-_tvFwcil%*DdUr8l^}Sz! zh*J&){kySV+UGnOT}%hh$VHGSM4F1w(b2)pYiBRg6cOY&l+|;OAGH&jU2t)!FWc3< zHWB%gFGr@LS+Bv=ZQ)YSpMDrcs~>et(EN5*M)%?0$K&3`<-L-G=Z`t>-yD~Gd@u3$ z$k-Sb35jRAAL+dd%KM0y5WA_#(r=^4QfH+{9qG;^tFv3g!OyK0ZYhf167flEZ6)U_ zC?H!iei(>auR)^3pl@GJvH6>InXtKl5QD-8wZ?)oDkC@;qqW^d{`(y?!B;jBa(T=N z!&clxISMA#XsiQ&Zn3XC_tK^&rI*<9JtgNg^B61U-U9rvFCkaXgF6H!$jc+~vmtFFjy$u$?&cP>efGbSD@<n zt56}hm1}ZpY7&(e(^9{mUiX?M1bQpZ|J~#D%wH9D#w3?}ceid4hdsA)1?P`=5*;ZqV_1-OxVgO~ zFlG!tM0NYY`I9gF#~U%3jn`W_CEE(w!{sWvYnMnR1C+g_;n&%&_QXG$hwtKc;@_yT zATKYGlS{Yh`S+QbtL*+7IqlQ(gp>FtZrZ_Dhb>jahVqIa*~1Wi%*p=Ob3;7LxytwV zrmr{HKPezU)oY?2s*$Bpr{m{G4i@%qlM{jsonY#dN2nOU-}Q{9=)MtVQh|+vb3JVL z>iBZ9s0`vzC=m(k>Ix>hU6TOcPYL@1$K+6*S59?ABmG6BRzZe z%x>dHFwmtydILTdq&l*inj}9qFwjsS7$GAiMULqf($}YeQ3F-e7N?++6LfH32Nos3 z^6~NUh!`X@Gjrdsv1<{6c3^yErKPYcVn^N>)Q-n2tR7lKIcssPTdjBs5k!l#!K}T&~%@-ww0E6f^EyvlA}s z>pJ~V+SkS9lfaH^mQ=1<5SohHIaczIGn`uj+wavEVs)RJ1db)enUjXqw6Z|4Uhpvo z=?;s@ zVGd^jE|@k;Dk-325iu7B{un0Tw4vPPZG>4_Xim#@AjV0CVs+XW&&LqPrnR0-k-KbU z!WU7{ApiS83W)HqC?!%Mw(05;0}6++xw$@M@NSSmB0=&9$#C-Af*`nkc+@9w!#ZPucr|yP>43Lx3%ev$REv9lwk>C>)3-Y2G{ z#BN}V|L1JEGM7+sCgZuS%nZ|&s>+q?l7Qdy4K)>&`#-8O&rzS6C?I3{p;S&1$;D4r zY>7ByiaATtyheLVmig0wJ-hRx*FBZ399D~EZn}OFiTK-PeM5C#w~QbkOzFsc)pXEL z0w$}?q~IX;9;RVZX-P?E_Xb{AG1b2kK_rluKwLZ_@bq4xIz1tCtmQWKd<#Lij4yY^ z^4sm+2IR5sNoO-7iH^cCS*fLRRIiBGMcP^h75SD;y8WM3+0hiH^mc3;Tr$h4`6~V4 zY-~Z>Da~`qqKU^b%^B2nY^6sl+dTryw%_8X19R?))HpC1{Hi`zDfZ-AHGWbXQ2Xna zFvcm#apbqYwvJqerB`b5{{(=KIq?vhLYPSr^!lM(t^$mG`~bs^2wTE#L87#pXp4!! zR8RMp5xOie;|OL_gfxFA%%VexYTP~}d0N!%3HKPVASP0QiG>UcAuK}xx5n8??SP=- zaobTt8F?9!j1`22Ys(>H(8%dmnja_Z{!<_wBBV74+z6x~tH5|#9XCvATihFH@bpB0 zO^CA#dp)`y z+k?V{is5`97=?<8I284wt_>|W~e$A#GC7b(~*#Qk1f?py)Xgpc?L7_spgK1R)P z+Pb0x{YFgTGQ$kcPnd|vAcPPCf>ylGc zq!HJef6b_rj{_%7Lqi(KrEt=^ndLaWf?tIaS1&CelGD*mu1;+Al75mXcic(-#2ik3 z^HkiHJs}u$4ko6iC;%fpNy>-oi?UgqZ$4sDrPLAu1>?Ke8PWh!gK0*LOGgcd9Dw6 zFW5~eg2Hqg8yD3aZ05B(xlChtCeF@$YqJ6k)8$7o6Q8ZcAG~q(`Ye~&-MJQ^lpnDZ zGpdTK)SGX|=!wjbSUyvGOf_Y}f#zMQ@#D($8=tjQ9PQ5{O@164zudgM-_=F`gjLtx z3&1!(9T@gZggX<0%ZOW;lk=%C;Q3?!AUMXzW>fOws^KA~!o;V@%_{W~T=~agt7I*m z{UnUqml>QEjR=I@;LD35VqNI6EVgFuCJTGe{M^> z1xj=&HyR}dba|cFd4q(z~Ar3^>2LuRQSiOP|$^-8{ z7_|ee8VV(lB5veGy3h@Tvl^PNI)uvb^yih=MJa%;OX69vnIM9jRVsO#cC}x z#%8V&8NgDqqCwC-Ic*eFA}Y@CHwai6_McLb#+EJk06cKnE75N)n)H}alMe6<6A?rb zm2YlbAbh`(>UnhuDjh3`FuLU43JRj!<@^t!$R|XXWJhLybs%M!eQ>2L_+cF4b%lwwSTsh?-`s|1AgZ9T5jD z*Ytz0MX1CPl6Zu1f!-$75Hna+tJR%v*Y1yr2AjJp}RzZ4-|0`ozEI7!3AwCZ)6 zF}0>9zH-Lpc1-tMOI0UwQNK_lxTwq`voGiy!?FFh=|PEjmgWp>@%0~6q@%Sl`NgiezXtk4bga8Zld46 z!o>CUQ5|aeK3ip}8H#3cAM~U_Egw!MWU(NVa>#@aR!}nf@Sy6mshHPisq75R1~(*? zlZb8koN}cu)Aw@Uy$UKLQy;FW(zS6dtBQMygylVtI_?yZmEp4RZt@>bq@k9{Yzcr2N7wc&?whU^U1rLq0LGr;GMW!2T)BYimTDl&yGM^+xhrIh-P zzQvRq)LIFknpp_@+Udr8AWc839IzU|J2Tq;)X9UC&ax+cr8{%V{+Ri)v=q(0U1h3j zN$8=*L{w~aQSA8fLldfyjH6l8@o7#k{RHC2>tO_Of7UrR3vAN6@tT%IVoJ5lqLsaD zH&+U(hgEiea71#KeLidm>6m@{s>kd3SRdt`mRFBYByH8$a$P&(-;}gBvyqk3TX@XL`U0}v+7{u|86I7VW-pbW zFiZ8uvn09Ls-IW;qe01U`#-Oa6<>Jqmf_6qO>A}s)y_R7De#O<`|!O#k2$%0IU@AZ z2=yOh=!MnEcRVHd;sr9u2vR{=1KK`tF-)GRHxOkJ434QrsDlQLnjmVV2-gVq1Ndgp zK_U~(7DP&jfvCE=WFRlH8F~e5Ncw@pt;ra0ix4+}A9@1$TU{M5wu~eFhdco6;wX2&(!lk1yuk# zIv}dp5a|OUMhNTy;)sKNLe+u`q<>oxlq;WI0>j!C>mCq+sBi!Zz5L+q**jemI4li7 z@eCG|!syQ?WCYfngg`wTUOfctC2;w>Ujlp#1tTM7#^A4mGl)YV@6`)?200F-DC{=l zXNMbc;L2f4FR~VBh`}%uV*2%41OF6(Pq$)IfH{RSQdmF$I-;M13N}7WU4)|#!0ZX3 z=kDAKsEItM$Fa;&7 zDxkSR8=64+XJ;%B0)dT&Ro!=X1Bw9DZ3i+$?jnH+f;3ntp?nrNL>85A3)`U$2`3m8 zvxu`}sGmV0U}=%D=GWcUj-9zcCLNFa({+e`R#2TEF3&&qBZX47-p)+D`Oyw=cRzx< z8&XI_Ju4By8U(a#PCjD!?exRnr82TS2~Uv|^k!q7{uVoiu+TzY@t7*|qojiK45H3w)3BRL=O}L z_=d_ueOXtp+&nJVZ17`;*FFi+Ua|5U7hVn#`ba hpi=k>$*r?Ei{(nNK0B0#$YA z=(_0c55J0-=UHx3pn&`I>G5n)$d^i+DTmtWYb} zFuKh9G;u>=R@7odYj_lf}5WKk@eVZ7)qCNZ8(_k~W^ilD-WT8Zf zEa(5D>aD|~-nu_fR1^^v0RurmNokQrN~9ZxP7!HokPbmakdUsSgrU1bLO{A3q*FjZ zy5X)l=RLoB?;k$rIULUn^PRodUh7lag?FI*%r7EN;I-1Hxb0lcLR0o#Y%6oXeLwx# zKR?;rfj?NT8xYd62!C#^2`!(Y?s(=IS}HaKi?AaTRtyg_Ma%9f@0eTPQg2hYL9K+c z>nX)>xHmK$O+PyB)-4W@fwwO7xB$>so~;lk;(^tG|_zaBkZ z%U(IULKJ*^t``eKojPSf-_qhD%CN{x^DSeGYiIU%-v zW!=xTF2J@m<(ImndX)omQWRo%@@-}UaE{i@$_qC3?f9$szxd8?ERpi+;4}dP#n``8{v+8u)I~ z9e>@Fyp14nxs6+M#6Vz^@=3#PpCwn{cn)&@s=tDp1S&d673Kq}8!aRKwk3tJcM(E?p;?ZvrEg2%a&q@<)(^(2%R=tiQfAOQ!GiJsEar&vzc zYS|AdgHcm~-^0y~5BfwH4HMTKc}anFL5@v~Zth?aj? zsscd{1$vDT+=5$d)Uz+KxCWJ4Sy_2^b2`y1za|ozqk;bZhAR6tM@V#lPJCP93U3U$ zeFc>aNS4GRufMngB%ckB#xnqj#O37D;U8Vj&@&Jb5xsr#{0>yuO9t&w@o$syOA85k zA#YZKDhmGNctGK|Z(cx(V*nua18UcpD36(m3EF6iM0Nu094%e>XS&Xt+qT3L!Jh}* zDA=%p#iWby2UxEFL`EE&5c0%mBZ-nkkpnOY5(tiijuksaRaG%jQPI|ur@vi=6**0d z$H+r7QuV=wAjg$KMHiXh2*=W+M-qz_cv&^oT^{x!)-sT~SF+z$^3;rfE z$HuJF9FLf!jOo&K{32`@7VRcNik0W_PZ=FlvHDGI6RHNCP}tg*7rnD9Iha_xZFS*s(ScZ^<~Xw_e9&|8 zV1BCN=Gj3otG@jM(zDrD&8SS{r&FEhgnfjJ|C=Pa&e652xmlFs-RNW0&yf)kg@8iH zzF03w%7>^mXjG0~@p{6BO@Q9$Q_d97aOj~5u6S+zM(jw>2}BsEXmHUsv(t)>#WxT@ zQglaAM@QDggtoGB3il77VW1mYg#4_9-Y1(_xlqBrpKf;q5V79?JDe2UymxZ2tb1`B z#ZdKub88Lk>q{^=y~-Zy9~^8#gGvJKu9W3}Kc)bpl>(%JdLSa&B%A zEHtr?Xo0-uv>wVJgq8515hy>Jgqhlt4SkUDp{HZhAv$y%8RVV-IuBV-*3eL)wJ=Ao zhN1W(At}xV21;Nat_gw&g>%B{ibZ)`G~u-FwuGeQ96(tRanm}Qu^+YkTBLwKLsiagcewn`A}MbG0|dDtv~A<9Tf-nk!dM-*I${Lnbpq&3Jb|j zKuoX^$;eCe7#8={3A{CoyrfZP5f~bV83C+3Kmw4q)6~?|3%?4rLErpV2{+*X*LY>K zyzblad$q}6WBakOI~{yi%=pksnPr7Z$E7G09TMU+m|7_>B$MO>1K5`_gx%6K*;YWB(W>Bh@i~9bj z1yJxQUUE4&7k-y>P&4rQSqZ&@g#K2(aaYHhk4m<=L)R;m=hf`>o77z^c054(f;%BY zX|-T@!lUNLiT&J`<6AtPTotVEs^>djmn=Bak0#D{fyBZLZ=qYevJn*Lm3W+)58|EJ^StF`$AlYj-(!uf|J%$&ToG zKjukx*b_;I?3(iU>rq@C8*yQNk}UpsqI76*RZ%?fWRaxB&GP{hN%v_WV^Y6un^d*a zEV+-)Qs&Zp`N+W9ey*0SBm-TQ^_cg7Q{ITCtDO~H`6c1tnf*E~@ift^HI}b8nrJGl z_O8V;5&7mFh-i(RMA^oOSskoXsP7+GX6`S95!oQ`Z*tu_mrRJgYkOm(Ye;PpLt#OO zJEG9UR8T5kqWszRhl_dL6Qka0&EGD4MNaIS!`kfw2e&EMi3r)^>$J~!J)BR7&n-lw+F)yDuB)iI+`MYp)@o#VS;)C8Gj7wMIUjP zDm*8v9R|SPfUX=6gXjpjkQLV>s2(g3AAwfj!L}YPGbg?PMg$FNqh-k;_66}&KkRfm zdU_LR4_WVL548hB1ZV3mjJD9z-1q)b-;a{|r6iAT(F9IsaUqN8@eD8conn9!0-~yM ze(Meaf%nfhdN6VBLMD`P)nr?9W_kkPmW$c>wSZZ3uZnNdf7s97b<8*$pE7H7V?c)2 z4JtjL4)X^3>~|lAT=nvK_{23@5l2F{edomM5(fcHO9J$h1_8_R(tW5B%j+_KPE66(Cgzi;NLHb#f@SUL^B75U541_w;JLh_c?%{Ss60p5UTg zj7goMieu5zU{NA|;bXudv3VjTprTW=KX+tb@CKKJWREF8tSmDIg-tjcNar%x=^ zU4wjnq1*XhGowIIMK%rDlqT7oES2MP;|uYdmjmHS>BD&er^TU&N!@Z9sGu~ ze7MEiac_wD6f)w6xVAs(@7z&*kD#FnTbPhiPQj9HCnK#cRML=#pCnzA4-1WSrlgXM z^B+@_5s4tK@~M5Wk#)ng-#IKdgw&6^+U(k%uJUX|;7}6{VK8OK&!#&A6T+-__-06T z+^qOtoiFlXT0XLt?ABpP%9SCKr-)jwW?j<&jM>wL&-Cc=PHf)WC! zGC)<@A_1)ioCKf^HKmwG2StIn_!^0&QBq}P%+k`5r-XcH>yqvwEXu-=@o^2wbE`DHzI7iX5;d051JRbJ}T??^ROIvPRZ^@s3QnM=17y zJfP3C)V%*Dn7hF44=fvSnINw)W{c&ZwE+mIsOY&C(*qzV;nbIw4(K`YEU#jVtg151 zs~``wthH{>v^(F7f(Z*yBlwG;1_8Z`l2Z8T9%idVGzbl#+kw7`k}N&^B)kP%_U7z$ zbLSd}oJ}o2wA9nP*|FK*3>w5c#!;eCjP<4{lC6LVVnCR@OJb+BV@;yY{fH|*=<8+W zq)JSw-WzuLr^}F#`U(K=_thj}ZIr4=I(l;NKy9b9@81)4HxtRMCeO^o&ca$e3&L71 zqqb!WZB&%U6WJi6 zv2LEnwVqyeXQ=(o`DvKQzxE>Zm3A`=dGR_eZ`rkXg=4#`3F2%PS#^#v%GDa&ID!rw zoLcLK4HII7C(V4w_@$*@TmkvS7aymr&qqL!b?3vMYb0S4;S4~;{ywLDlws4$#~8F> zVxBE1dLXCQMuf9`+w8)XaPoI+0eZ}zJ%v|pen_V!wWfC1)?ce&Y?;bDrK2fYp*2jEE z*-m}9R){#vSf(;J zWfaQI{$wEro+(Gl58pi7#mEhh2q&4uOWV65i-Q*3xvWt1u8|0Ai2Bsb>kj2|T7A4G1~D zdw=a=i2`Bt_XieP0jML?nZRFy0#W+hR(V<3oJ}P-+HW`qD3Kk4XRjCx^q=#si{@=A z(I^3sk>&|-YdYu(03s&a-9xjQK*9>8n4IL}`8Gb;^akII6+pNgZEUd7Y@CCdK(Frz z@8uRm3_eBK^f2JN0CV^~R!jr5B0wNVt^Du{gS5z}Q+hg4(S(htn|t{YaIC*P?Nfmi z1QAEsSh*s*VaA#3^AIFbI+&DC4VYSJzgd1P+9-eo=>7ZmahSz`0=&`Jhiudv$Hy?) z^rEC5NK=Q&t)@V=g8l(Y7f{ep;jlzg%J~axYjya$joH9_ceLqof#XOY4z4M%2^W1X zurnb^5!2jqe6ChAeliNlI{>8sXnidH9^}Cwt!nS+xHMXBNd`hAG)97%0b>Ik{EMd3 z-@cK95^0f0d65rZYCY}k4R?}rn=d-~Q6miDb_>Db!;y&|&cuE+;k;BscO*0QLnLkc zOJ~Jb2|ud-$_QWb)TQcr7$~Zq>L(l6wA3aBfEB#Kwrtt+U*OyNQC&U2*8AtZfcz9`xzk+{@)5;Jc>N@WawSi! z(rf~w=uKSa=sx=kGd^>gbjjJ%>~6#EIV`7xP@^M#Ln<=ZVBkO~&9}6I3V{EVyQpR+xNs;H%Et-%2y5eySJe-0!<@>LZs~jHX_HnzUv2 zVBzoR#M$XpaqTcGPXAl9ufqR5nbfyv!KXSa+ zKmRMn#H!OihYEXWH~n}}GivMaFFGb|YnAGTShE9-slwfbh9{GL!E#i5eJ8&r{-dXV zY%PHh2tt@a&g1qm18jp=BfLQ~1hy|g#)KjhYY*peAS$L4LW{Z2b_cv`IUt`GT2gS5 zxGILj$u*Qr7Vfx)`UB`+FHLDSPzze`#|+TnaWJSO6cl~{Ug!Fjvs9xC-Ut}ISvX^Z z565Y6V6aDz!;r^~2Xt@8VrU{Ubj5I%N1R0yE z=pj?!O@hErkd>9SFhWB`b(H!J3P2w;(Y5EtX6llVEcd42BQ{9-Ix^n@Oo;x3Xx-W1 z@NoMwh%SiX1m*X_cRUb>;T@PLOkZ_MMfAypPg{*S_Utbgsr4C4Zevie#YfCMDj)y zrMw8a94(3)bP=o3D%lZKL@3OAzqQWszj}0K3RB+8?LQ@#h=Y*Ouk;$fq~dVOHtz76 z%R2RVp}IbBYAYV=xRo?jzBVJvNMoN^VBsQHfGJ^N!ER52)JzVEL+v3F%A0m~`Oo{f z@0JvJ%QNEU%ZFQ0_G-wJQsvwknJeaUNJN5WG~M6aBVqBBzENDPsvuP=@UkDI@cl|ba?!6-uv>d>R2QZ zL5W-QMYZlbeSMp6p#uNyR^ud^TF-)l%n|GQ&A0?pqbi!~p%va3Uso8itt+wOZ&YPu+Y06I%Dqceb zVxpVL0oBWiouuhk!}kPCi!9Z;{ri7axEK?0j@vB+ARE^5Wl_FFTAp-AZ}M7QV+#55 z4C+_|6%JMA;7|gpnzQ|4JlI4WPBYUKLtBI+UJW7i319@Bf=ZfJD`#rHHy-*!+F<^AE`v_ zxD;aq3@LRzJ;kK+S}stL=oq)YL&p0!0NbOJ_0f_|bU=KcF>RJ<7sJ4hrcE&bmOFxfuUv{XJ6wvh9IbX> zhRk-DK(6>U{wSYzzQEf@hpL+mGeG{cBhZ*Iv%p8(_`V|xgf04npNW`0-!HG*0-@PX zJAHnVO7_t_*+naqoTC|UT=WZ)2K$=-Dzk>Z2u!$5XkA##{1aBzF!)e+Vb}-3vFno4 zYGyhbzl09vvdSNeu_7Pn?9s1_#tuLY1$heS%7UJY+)jAJywJ(AQ1j~AZXo`qvD^oa z1v(ikNJA*HniYaZA3TEdaQy;Wv8ANsC~ycj4dtj6dO>J&1jtv3J<*`agzHY1mdko6 zh@r0nRRL0a^eqdp-{ts^Fg?*xN}vQ~v7Qq~=cfY!!nGKVr~pDPBP;6-Na`?Lcl*T9 z`mzbT0h!&ka=(=Uhf7y7@;yGouMYUk3k(q0G%BlV|AcU+7*Mw5=H{Yl8ua7?JyQX& zD)sbZ+Hh8&R~O(pXqsJC;LHxKPD2-RC*6F_@*sdjtw*#SSS+V_p>95evWu1zLZyv2 ztV<9VqDqH*Hu?t_a`SJM=PA(Il&B8SYKzgzO0>|TDy^>GmWTxwD{_%mBG$XUNS$k2 zNi3DyK-nmxT@>5Hk6KB@?D3^u-2|{Wkjut}ZG?n#jP&*jBEnd|L36VjO({o9uS6k1 z@`A|3Hl!8NU*oMy(@i^4%jeX7ae8hxoxqiTH^bfBAU&LS7|&Xk*25=`D;+6S&{Qd} zd-9{H5-tC1nNQ2il!zQn-SMg3m)w$bddD?~q?8dQ?>?fLlDIeVqjukWsI)99`u{Yc z*D<{ag6UXT`icQ&>V|Q3KbXH=e2)0ehnam%6q=!2D*P~wa8%{QdqI2W=~E`AG-zvS zoC(4F5d;qZ=WkoT>f3DerFd*kk6gX{QVcfggu}Gk-Me??forn2XNQ3h&a)7}vC+0( z^!EhEyLyGy6STY+G|OlzQq!XHs%KUf9W(4DzXGfqw9#k<1f+0m z!$LJ9-=J#yi8B zmTmbxU0nuCoiU&z^#!37sNbwBwa_d3`)|dbANmj`Q1q1vpt7~gcaFv47 zd?2T5{{gxub42ueN#iRJjj6;Pu9WLQ8p#sGYBG>A&bL0?t^ zNJ6pQielnmad*AQ18vGWW~fOp4FKO68g>ZSV>8IP0STRl(zaaG!4$Rz_y7fZR)c(# zD8ymv;7`bsM;F455%i8?HS9zufx@$g&ky#9SxA10K(Ts4Ut$Z|?y%TcIxu zUIu90YJHrJ6SQ`$P*%VgZES3e7TJTWADq~fG(TY?W2!r~$*bAd0BDCJ?$*C|d4XKt z4~cQ$B8JZfE(zbwr)q|4%spvLQjnHSIOjOe?;j-Lz8Z%rX2ranDqDG zWAKiYXlVED;g*;6T^z6b*|wKPDYozworiKg=sxz9BnklF#PMwXeYF-NGqz?(D%G*B zZfLrY@-E%-x4X+ifdZpiV9>PV(e|Z(5#i?{*tE9!513iR^#YEDa3lv*Q~W9HbG zqWdaQ-39NJF6hcG9}bp^7M-`R{rX40_P$!C^*?WpJ1n;{4|y!~6#=rJ8_5sPo@jmS zZUOJNT+SbAd2$fkJtqABSai750hxvnaZ)f8waovR{i|XfBTWs*2q4Tt*+b|r2KEuy zh~Tm%z{J7*Dl8&0yX9zXVv<}~*e50r*{rZqkFNAYM&1VvCVYix`Of&bf0rRxVc^CY zzu@5X!a|7769tBwDXN2JRuV2zf^2A@oCex4;L8IOF~p$j@)H(!e2WmavtxtwuE6HF z%tyxG!S0)ynkuiYEh8n>QTTmbjHFZ}@W*S|xRBosTOaNAfwKS*d05i<`3E8N_4L!| z--nb3@-m2t-8S?9D*RVA0C+^}Jc$2KlZ_Av0>Yh>yQ=%E=sR}VO=bL z1l%+a6fb{)yNH;WWMv7$vn*cV7#1Hzy^U-p;0yn}MQwUj&L}54JM1SXaMgXr;Rj|w zHKJc{-%LXz_B0_$IDZ7Z8J|HkRazPW{3qCydsyfqfRtq3#9A?f41EA3`HwR`dSf9* zzjH@8Ob>zZXl7^XF$v8&Gwf;z>*|Hea^^tJCW2A~dQj5M%`NWWF1#On`23NMgCxiu z8mKuq)o92h2Dmy}x-C44Y+K?o4wi>?yMVR0Q@mAErqw|6=}+3sG(@NX51s7QFvHX% zO#E~Vb>tUeB5X?8tCDfhWp9&tB&{9xwCEy3n<{my&jsbJpN}5X|IFO)Kfdf|yS0T4 z6@wu%tH4y_tc6T`!e1B(M6KQz-E-S5U5_Lg<+Vcm<@%G-{2^1c-SL8-Fq3PAx!XsQ z#LV*SO5ilvqHAjGlrDuVtk|g|r)7k$<wa=^?jv(++0ai7V^<6eu)y?B$;8wx#_RtU_bH-<{9bzM z)~gdgx7pO7v)HDWE60U}*8DC>d``mxr3}a{eGlu~e>2SjDeajC_ZmZJ^!4XGDeQAY zHZGZ5NL;o`b$L87$o;SG!E5@;e@4ioe~or`KU+QnSMbaKGuqNT5VCv0Q$iC&B&V#5BS!;4)$ZSIW$@61Ka?%v>sQ#^BBS3VlGd;!V-x=S+Y2g?&SaArHBX1OPaspOugZe_usqeW#=3 z_lWUuTR$b_PGYdf+-RR9632d8X#LXSTH{M-v?K~hCa)wfNG!UBE5?P}MSlJIJ8X0` zq)K*EjTm(Mhg2xe3ah7GR7%>WPs44G*zIf9QDvp&Sm6?N*Sw#+JCgIeAbrZni1(ip z(VY_(L+=*jd`vg2A}A8A*3pge(%5?c3#l1jl5>`&XI;Mp(3 zOB3o!r!cWS-w9Fd2K|AFvGLb~m#K4FNiKwbTv4H+3e3+a)|KOP_}|^`{8?kg-(pbHhUodmd26_W zftHEsvb*-`qsP-Hf^D{96!x;*G!hA4f)7+;q%v)1Z-mdLmR$|K9kGq1yycKur2H@X znpA8}Zomm$I*6)T^}XiCe>OZx-x@K$qP9Cf(z$VO(QQJz-FA6zX@75QVrS?!>BC2p zg*!Mrw;Du#yZ+-lwY$;8N%&!A^f4S3|4^-7VcsaIHA22Bwa*srAL$8cuNDXnMTcmK zsdqsS{CEVX4AvQTGA#qfBaKw;^8;J7}Y@cmX$-RK{ksIt} z7vbqvo5^hH0P_J*3F07QQ`69F(Z)%vA5dcQ2Xw|q^T)8-V-ay()HH#mQT=JId?n1? zSL1>y|B&3WzTF`Vj(RmlEGYPSzX5AE_5^J(1i zIPVMBaO?!n9v7k16G3jQCw2cCz7KP)$PLOtq8|skQ#)x#+x0iIUj_b3>fgpDP}!P1 zb^UhfpcWOtzj^hxa(2aO*gB2RpCy}0I1Rw@e%M70$Fc9%NeEd;7j*T;yB>7w|56RO zwoVg7%J)}AyO!8i*K+k#$7r|Ye&3*O6Fk92kc6Npt-Ez2x9emxxP2r|acDqArAHU~ zmfG+1bihDDG=Bu^Zd$!61A3)p8s6lfK|LD^sktN0^Tm$&X;?dXh}}5B@@YPSDVdDAqhpAjo^=Vat{m!Gh7c0}#Y^p9I?*_Xb%I6T6yKc%jsQ~CQY|0#lY^P=tKpeHTZ;_-6Gz@g!pbk&A>XRmGT@~Ni& zQ`b$g+wsSoWvBX&Kmi}O@@0D7;~rBemR6THGjDejVvpo|<7Mnwayx#wi?73PME*Zr z`@dkSyYDHfFsFo4YilbyQYIKH>(VVsv8VL68u7?yKIgnH{{>wrv=&WoGA}2kE(ng& z>Vu6$AMA~wqUne+x*b84Y()S!#hfVccWbVX^=|NnL-r!*02!qA)}n%kG{g{yupWCa zKSRmW!lO!CDA~-`ZtBGMW5|R9?u}dy%KDg zKgMR;$ez1^vFCE@oEDc$a@F`8E7l7CWj%@K=YDVdA2r-t{zr7kAT8nY5~bJ{QFBL& zC;U2_@9UE%z2_<$kQg8b)0CRa%c@ToZtvc`!~8l;EVO>rguj1nXWJQ^S76~ZKH#UO zNk7bqp#0|Lzzis4N%e!&7VmW*`ORDHH3bfva2+oNh?I)C(KfH6n&cX{3|AdVtMGkr zSs&oh{)!8>xt%QB{rXMrLFHT6_9f-%XUlhtnGfqY4>zwG@FdwVgL&*G{gG^?tf8$& zebsn52aS@)yv7;dBbo7HuRJv%G6KG{y!x#V#l zzGuo`6Ak)v!OHx-B$$4$9`HzQBlw3aX&)r1ot?gjTKF;@i%v#SwtyLWsPkdV}`Pq`c#ipTFGLc;elMTvDS<_~pQHu+85) zqUBw22=4Wg9PgTVYCR4E2I!+%BGhCG+Pc<3>hS^`+(1&@R@cvn3cX85)%8ajPG^5> zS;7}NsR1kNKRU-U34AbMzNC;`#$Qn+XS^jJI^Ibg7?a6$%jlXk5P{FT)n$+aX#qa{ z-c!7@bfSB`Qc-ZL#nsQ^xS|q9Dp@Y9&!5BGQI6!IdHVD>cCR?DVQCV-ShgW8OBlrT zfQd{~lUPAJd;gKhV(vXYV}j{U%6AWy$+Bfi4NG4ujbshef6QCEYoZ^L+MU@Wn3{Iv zI&|pD56SZ=7w?!7RtmoB6j|dX4XX# zJBziJo9qaGslD}i`hV7z^C+C~TO% z6{O9YaU5Vyjqcw}=Q%Gj|K}S=e?s&JHF;7ZoDw&l1mT2fnwk%o45XuLCM?SJh!9VA zqQoQGyVf%(DOYk+e0lVwqa_0ZSVUQ|5s?)jobXwplld^RrmTqC-ma2I%p;`vXB8_; z{KTCl%ndsg*M`shJMM{riN_!%{Ma5QlAFZu@%eSx!I`5td?TVAC5lW@m_x?I3_3qE zQ-UR9$~Rb-7!kPpnl0?vY(^k$M8v%`#b!@YTK(I;VN*3HPn)@~C-$eY|Nf0CRquNR z(GPGh1H{xX6Otv?&-{1==t#q&O`+KcQ-|~CU^#h67GNGqq}e+G74_A`e2qSD_2O{n z;faYL^!JUe>0Xxz`m?V~+#xd=L*Blr;ZV0n||`JisUH|Fg6f5<91de&5e($M@>e1u6g# z0pQ@MrEn*GW^X#x%7ZC{F3Lj9%Fl0BqGapcsPi4ndb?UqJJx4|$MO#t_J z`!9gVCN(8*`lG2B*?cC=d=_g2m4fr``7vUQJ_U zmAzy+T~@{Wc>EWr4McGH6MF`^KV`kRg?ah#?EJCJ$85ne(*%OwF^VL&vA{72kSYQ~ z3!caH2RL<$6O6BF8Xv~@)m>mLx)?5f{rACh4?->ko@(@sKP%}hc`ef2E+{e_OH1GQ zYsGPlwYSVC;vfE9jq2_BW_7Mm=NwZ$obj-{hSpKF@NVO(ZG~|RYy|T(ceF~PL{`d!kcGg2e-%?ip7}c!(cEl?5Li2 zzHWLyS53~R_{uBh>fn|j4*ed}+s z(i0@M=5e=Y$!|L^tT* zrDObeYtuQ9F}cNen+f$opT{*&%I8x_vn(!F+po!VnKnGllrevbpLUxiDuJ4uz57xm zdooAPb(v@ugy}MV2KyzYOGGOT0n{)KhP(L0V7}bq|Loiw5FqV* zu#u8l3U5EVB)|F6jE6PF&wkAv9Sj6%9vT`vOi@yms%jFo1ViPGpW=ld&rDku<+9{r z)2FdgAi&v#Nff%=sr2#F^B$)fol|!YHJJ<#u}pfzs~C(@7Yr}_Q%~3+aU$_E>66|$ zyb=Gb{%tuFcYp=PC~rXRLEUM2Q)9?O4*7dG@n3x0X;Eg?>#n(}%^Rry{96Xyxu2Xz z0n5xs20Hrv(20DUhqAmL7^~;1tsSWNhkf~1ay8TYsrxDg9=H9Ry}Eul z>m5ACZOukoo2d5P@hX21%fvM817v5Q?fK8SbKGZzs?Yx%d2jL`lN@|bwu`)m*Cz1w zzWI9`zhX|?`!dTl1T?k>y$;-{zvLSk3C-0bBz|VoxDzbjnI~WUaC92vD-k4`^}^3x!{8DKK0!PM_j8EQ)g)pwlHcf+aB8E zk}+&Z{rZhR72`&?ETi4&*&x++DMPcz%ttoTO|i4ToeJsDDRNVt6=_Cx6iZU6>0~un z*r~x4*^|%r=vUfL=|?A&W4NyMWcuR@mD?Q6L2*qD8=JNwG%=59xSI<9s{e>=|618m zu^b)Lw64=;o*q2wbtG13Xz}vwmesWLjgj|8dnX6|KWcrbmPs2A<6QoB#h-=9H2t^s z{ZcEVpCya3RCOhK5ccr9ygnDWT}+(`%+k#JYAD>G8ch=13yb#HS;cH|wW+y_0l{+Do#ncI3q`*H7U7@nl891ARlc`a;ipN)4lBaMq;yV6 zY3hay1}IXD(w2K!C6rZE(C5F|AOWk%G(C&&v;F8HpJz><$A6)3YcVs6802QHdiK2A z@8PTX#OSuQJ+PCcLpH_So(kL8$xeAi0`YS69(p{N-kDQG%;`lW5)7T|55zF6o@=>drd?`vME4Mu#rICx~VkAEQ7Gz&R$Q+Bby^HvunigU}h`zYt%># zTuG);{+_;h&1&So)8Vf1{ghwsZ)}gBQHpK8u)Z04Kz%UvEIw0gqP)>l`o6=AF(zpS4+B`Szja zbhCE$rn~Wr4Zb$%qnWzSKldAJ*;T^?OkX%$oMX~dV_g2DW{2;4Pxj3`YoWBc1Ic=n zM+ak#<|X$sUOQgxM3QdKY{LQdc?z6&x=o*vnK^c)%_dj{1BU$_uIxvwLF;v~*&H>^ zj^*cs=UuqZN)DE_Di@tZ#d6;?>lrDOTJZ%Z%wS}x@ouE_M3Wa9+fP>@DAcmq}%jJgZNSQZT2pDj&Ix z@-A+lWPNM>ts?7Lrhg2 zR;41S)DWe8;uohLi-P}Gp%>&u%dxd?4(h@#Ml`V?3g~3OY zt}P#k8Zt#>c!-nbH9rsElF~FV;RwX>x`hpMjoqe>;JbG@Z@%{DQ7!ee+CJ)ZMzDMl zU+mB3yn03_&k`nnOOeJ#ou&KbtI+UgPgYGD{h4<0moc%b=9ErZIm=TNt#7<8=RCDn zV5QYxRbtW;WJ$S|F_J27N^l-oL4bkV1zg z94VE;UWqV_mgw!18Y|(^DV{>{!^%am-_7ijGA)i8|9z~g5^st)9bDor6zd)N1b;W6 zW-fuoJuzA$fdJmpPAsYerTM{3^npz73r2c+3R+t1{1K^t>C?2E<%X-WrQ^?BdI}WT z={EL2n*+xTKwNEN+wiO%6q5|1ZK z8R3L^QERuwXSeJV#0j~;PdVN0LFFrIW!oY_l7TGy8B_E!GLFNVD|DypBKGI_=;$#Xe}Agx4k z)fus_k(|Zwvr1I7$;wYkKL3`zxgKR{IWb3$Wtl(X@ti**u_xX5Rs5hKDiVP-($O)3 zTV09n?F+oF9ysGL|6Z2O*?maY%v|opmB=Le$#Y2D2qO;Abq)ymg?H&d#*c89%_iV z=BttUcSTxQsryc*G%Jr$8xt&P^jjzGqlb%<{=X6$>fiUHC_*sqWT1-PFt?pmeVr}& zu&J8hy#4C?u4+w2=pxQ}SNjjnXOCBj?@t`@qWZ5jN7(hMku_XT z$!%aWn;MY%ix|0=HS*k6dyhebAn2j@V3mE{HD#nm<_N)NqIf)kggLxA=!NOmVk8I= z#A2O<{w2jQT0l>@b(94NX9l5IXLri*wL5lcUh?eerX*QrI9;(RO{9a@X!X1lMvy|r ztRV?3w2E$!H9C86;`ikXnDW*6<@WetVYc-!U+?z~!R~8S%jBSr8S<^D?O0UAC%q&> zHrp97+i7dKn=G^C?Q9OfQyfRUi2&pZtU$%|>`@KuGUSXHzTeGjq(pP$hp4c9!#v;( zj6?CCB;Vm+URF|8zPj>ib1FIaNg!pR%vmkaF3{bHR7O6dP*G9&n8Q0H^={yoZ++|M zryC@zBWf`s|M!)M-{$bm8SAQBF-bdL6Kg(Qww0CkZ+Jg^HgO>90Y5TVVdnAS&gYkS zeZ2Q5jxTcZ16Mx}+0R2_GQ*FIejz)Fv%WY?=@)p|sWb*wb{9`5bKk87{aKK$^2sFA z>h|=)YLk@uHvg4>H)!n9*btBOY-N;NC(`YC<%5maiL5ab{OK&q=V5VG3VsW{KbG`5 zZ*gu9`_O#7(4v0mXU<)gM24-Kp+hj_S4eTClQ_D|Nb^dGz#?@*wI0Uo7oY!15x`<3 zrG+m~1dky7j{Z5T!{3#3vEtV+iQ7B6Vm>GRxSJ$%g;k$CD<@~>V0wf$|4ZulT_V!< zWhl;!jPYgWwnS7b(d<1wQXDw;K@Brt+pyx%XGB?H?<$TrpsakdQdu=Evl3*?gW5aR zgdijig?fP@J)*YS_3gasA;C8|o^o-mZxw?GR)?h?YW|PqY|a=F4QskiL#TBqw^II( zV_omga&;8r#A$b&v!z#FnM*5-l*VRy+%1lXikg349dQ?~7FVLmWbBVcgz%)R8kh_} zreaf3SJxX0_`Q|-^!PgF=}A|_kG)ov-Q;+YFA9p9pyB%`1vqU`T_dx8h!qJ#$tP(L z%+!{x4*EY)_)Y^W$e$mk5ei8&Rwz*inS5fU{KL5?f#4wd^Zw-gB(tN)N%ju~STr;D zayfg){vNreg`MsiD&(iQF|ySP@Sv0UjlS{+!81{DDbR|!)`u(FjejU zaFXfCzK><)`sY`}C-fnNifU@&b?#@kTT6X!KC}_cqyHCx-d5EwyQ~zSw%tT99TtYL zv~xK>B27bd?Mmy;{ji6gSzbu9;#iV>mF*epJ-a*aR`G_?$bINTeWw~mA(ulMO0h7u zd9q=jW{)w4Z)5UcoQ8xk>$q=%lkAJQDXsBvj%-?YFz+Lg?@KJ!EyDW^n?Gj6UnQdX z8#DB|Q51r0)i5z z1Ex*we8SbZ*AsU$+pfri_QLJs%m@;suVWnDOY^q-FxPkL^O>)ug)q5q~776@XQx8_lZ>4AciKeW04#d zy!o&5w=F^I&-Y~hDFYG||JUA{uIO=#A96CiwyLv?-fLk+9^;CC=6)+Vpg=x$ zk`ljdn#|;VnE36R{r~YoigHh11p^!-pLPGLD6aEz&ve(XLCEO-S#WXCX)rhK2(e3Y8Gp=xQ`jHJ14 zFZ-Vsz<^EjA7Iv-&!t_)OxW^%Zb+*?p28WAUT=XZ{v|KzTL5Pfqe^1>K0hp0uNVVc z7W5ryrm6gudH5LBlXi81RJ}ZBGg1}K<^ZLN}6mzupvyiHv0yaIK#u%6H zP4A5Nlk6tg@vf)D+I|TfIeziD%YqRX{nb-4UjF~DfQ3Y%rv&$Z$N4_y`Tz;$PyTot z=-Hj@4x~Ub=%}cPAWVkgksAf?ZsW133dM=5no0`AJ)<03e-ErIBTb19#uzAm zW5erFlfDXSK>txdr5zpWXoyGY44F_aXUW#tav>$Pi+YxE`g6xzBoO`MWfqelWuVrvgz6Ew z`v0)?mSIt@QQI&WC?KF9T}nzzcZnd~9Rm_WcSwgQNVhO_!_W=V-Q6MGE#2^4?!BMq zdyn^c=a>8#oMTw`b**)-GdvL1z;dCsmLO*gUqO>lkLIad((7l}0iF?!g0uD$tdWSd zNW!cVuF&(hk*eQqhb-3N1P%6;wYdKd;r>X^#`ZYuH>81cWqkJwYq$G8{_5hK-R-WC z{3Kt&h5DZ-MYlfXf_L!=u9fK+(uqf=(Y*GU z*it3R6Eb1pP|kplqh#StdK8h5ec9?H{<%iEqvZvipAq0gfNqm8%UU$DAXCN!3nPhI z4${@^lmCwKppSiu2%U{%Nce=Z0$FK1EqwTAe7qR2%>~raKpM$9i2X!D-safgh7j{Ip8PZ({{N}wEL*~Gxjebt5w zJ4v10KlcJtB0i;7Q_)<^tVhCfhfVNvzZrUxkVv|2CJ%G`Cu@#M+e$bOvXT2(k+CRs zgtB~K;PUxC?>kdVRrAWTes38Gb0xw{GI%()ak|VIsuA1RAXdP#^c}bS?#JIbg=T_@ z%hKkvV+5E_2aHm&nxud?FD0GaKM?%YGu!tARv=Wfb@k|@m9vu41#9)$ewT49?$P8G ziJ7jTKZkvp^F>$P7L&V%&wM@qFYluc`>XY&9z(O0d9w;Zr5jyFQ%=8Qf2TjUw&pG- zvup>hC&o^dy{U`8s*k#f4Yt?3n~PL_^RL_CxR<pkm!1E3-D3A}fO5n_~n>DTUE z%EQ^~Kh7$Q;ThL-FJ)^0#K_U4XV$M=cAIGKjzxKDWMg}>Fl`G`?e zo*m48lJH>5$0~%0_GjEDUkc!v8{M2+7HC~0q+>Nls#a_g{JVJu9J9YfgR1KsK~<%i z;EfS|!}OE?V+QU6_HQ^xeELlPt(-e20QSuWPCP<+&@TDS?Q=L*t!#F9@PI~Qz77}R z31!gtu|U_t|5nv*Bc6hZs;Y(8%AAD*!RM8mDDR#B$Ws=|ybwPF)lR z9iz~%9Onjz(uU>!uMZ8-f$VEwUdq9#$*dW87#kZ)CwS;YJ=)+VEH7!om9(W&Y_>U~ zdYQM0^>-FpZ$vq(<-EE7Z-@J_7tA5RfCLhSX6>`DTL!g9=RcmW#m+*Q#>D3_dp;7S zdMvYV$P$t#j5ytO9=5nPHouQQ))@IEJEf&wr`*MOOd0*6Xz4n_*lse(#hsZmMJCAD z-fM|gfDR^JXTsEB?v>SP>gyqBb1{A5Vm-`S0I}nv@oF3>P{8_CFs4RN9BWlSBsN|O z`GWS0ctfx&`oec?@|LhturYZGC5ax`Vr9ihaUI45;gvzTrUZ`JdF_ByCD#B}X+xi) z>&B%}L1sM8?_N^FWSJr5YW(|Ye593I=^(;oni{a*sA-{~SeL9dZoDCW3PE2d; zT#xno+Zf%1SZQQKvHq^A$-%U13T5Co)}+aXlP(l zp^M1AA`Yanl(#-LV=VMOJ7q8#Mq!I5_Oo(E(r^+`#4 zib`Q$)%f^vs&hpR4GBQQP^`nF9iWeNX&s1-h>&=*)U_S_w@P1S1%98E%6-C^aoQzL zXLwdII$puSsyUJ%$27qd$@boHG@heSrhz1GEHI)+3ggT@{im7^27!c!T`onve2=GQ zMp6yZM^)CmSOj2&L$!lHf~`4VkzCe#5kqL zY0J(QJT#U!GdDBR=)9l#Ie*p<{wnlkQaZWj&J6YNHId^RxyhSWitRuyC*AC!`(mqd zli%ZM%usy+AIivcHsbrm>A2QlZAG@7mUgN$8`gy@yV-ur(SGoybYIJ!{VJo%9%NP7 zl%c+94i%-gRbQsyXmr3q7S2Bex8vXo4Rt@>#?NgdpME#@eqkctLA+x>%@e&N#C@-x zwC6Ofq0FE?ltInqP5U!+U~Pku?($%Ap`vx@r++B*LlpdVlQU9je8!ozr*~R|;AStw z5G#*l-OrS>lV^7AfiwlW9IwLAn)?W`>@#{7Lt~K3=JH_z3JOdLGwP2G#mJEeZyv!2j;@F^pp*yOP z^2boLwfbTDN6){FLIXUIc;19M-3PxFGeQOB(l%c2JWZ3eZyBMHf|7p< zhtUkZuU#~F{7gou#RD&Xw&h3?97$@@KZ_8CCH0Rqp%7ewmTo$s zN=xH{>+%LjBI?hsKyJvzvMW$lMfqq6+6CjJq2Z%t{Xeo3Guc>FmFNQI95Q z;XxESj49DY_GRzK%`;cu)6wX7rBd98aS-GvL%9gQz|X6ic>bBi9;CnrOf1{bg1BTh zEGX+4q&3UhbQ4RA_3V%gApRy@c{6|MNdNKEe7wDymdk9*bZgv#CcE<>pWKpN|9;qr ze@4d20$kfFF}GJ@`SPyJlIEx?J*E}7&p8s{W3wO4awpuRavSjQ2N2d59-$dCV$SvB zF@_8}{aFIJTKjB`GVaI|%vYT8Nu&LA_<6(SF=av%6&X?U zvnEYa4;l_cvYHUD^kN3!m^vwyf5B$0)%mc8x@b4|ieby-mM~6m>s@0?IV?wx*(H{> zud%qMYLk1MZ}O!UO~h>yaBRtePkCJEY|$pyhJ@KE9>U#!e|ekmQ||3N(m3|XLSZcP z&B(=7R=-&9a$B6!VOu|bv{~BYyEobinv+fLXi5)<8md;)BGO{kvI!>$7rJ&&3Jb3u z|1aA{q#*A56ElNY6|5i0zbKiCrQ~@M)W<9eGn_9AI0nDR%k@t;c|8^JtH)>-!9W92 z)JBC!+X8~kC!jwCCtrAq?(jQX)PBPBX6+9NBfAh&2iy zv_wU}uYVL|1-0b5^0_fiA!!uMmDVznr%FwbIPCcNQRt)zG!wS7v*Q~%iWCx6-7ekw zT%UbHu7IXrUUNWwMC#p1qN~h%j*$R1N&qjFvqVi=kOv2Vsq2-gn0Yd)F%e5`tXb4- zznPdN2WreX4&#hmLvl@*y3Dx}Vfyhg4=^z#QYcHgz8fc~KON+ZrZJnZ)%86kgI1Zz zDj$lPbb@gwaWb2O1vU{J4|r;q?h|VpPMNtTvE7KW2E$5n|{}u zVbM-x%ea{px^$f&yCFD*kL6{;&}EF;P(b}BPfd|5Cj6*4rnL|rcWYPF<%Mh`84 z0XfVKSNC-c78g&)sJ$8g|8qNn5HcB40B(3c^Zts2h@B?C>*yuZ7yPg%vCFF^U3m#!9<^QU51ntkm5dlVHO=#q-`PShtfY%ss?Hr_NaF^c? zy>)C_Y-27xDgD&7VihG7=0kpUL0yiw$ht7AU-eNI_JB#4Eo1O;PGiq1W-wxv)Uaow z;YT+5qMwmA=ar)8j6x7Y6`DsU!&<~hz{{lWM70!(_jj(L10;P1LPVxXVfwcr7_1+@ zq#@KL6NlVrOvDm(mD;q~ArTh7nussY4%6Qb=EGzP+SuZ4)Sr33yQvYD^c&cIp859S z%l~w;B#K@r)6nv&RQa&qGpon=$;vtHA*G%Qil;b2~PzGA-{~ zo*#kNLE46&Bj?>0=X;Pva9`T@-2Hak4j}qj9~ODIXmq5rIP%a@hmTJSnhV3~rpp%; z{%rq|Xhxx6i>3+$oOQ=EjIkK zZ*xi*3;m&s?3L+LwY6!u%R0RxH1lNg@PbwRV%7G25!y}TouDh4MpuXzFrcd8c(jtg7@ z=j_g98;-n9)`Y?Ag`nim-O`}InaIhb0Dl*_6aZ10Q|mVZXn!teZQ;K#y5lBru%H4~ z*}#io&#A7AMniG#Y4!((H&e36*oveWO*KGb? zaek}8pHVF_9sftY6X?y!0Y>7GFI3n+MO15BhxNZ}g9>f-f@)lo_Xa{+wDM=ct@R_y z^I#hJOJA>5puQ2!!)K0Ka7}Yq{malXY!b%``i7hduYJV|V@KN_0FJ-`Lu!S;&Fdl7 zA8BIssm>b2wh)3HGh&fwf=eTSArBoPNPGloFpA{nl=DL-RPT$Pq8Yt@eL;{igj;Gg z?gkJNzov|Slg@tW*{f7xPS*>9=dvahJW-Qz*tCdp=1YNwR1FP31gCzup{3q-Ae3Ja zoI&0=5J29|=N__0P-Vi45AA;C78E>rJ{p2gp0psXw=ivXYAgo3{zt;nv*-(Q!HB|l ziy#fPMlR|U3^?RWU)K($0Feh(#%V5WU?DJ9wa{du_Azy$8_PcFO#oV@jiE9=>2Es$ z`{e6HM_zX>dnCK%CeqcPQDr-0VUO0`@1~pLjt-};oaO{p%G~U?4XjzJo33{dd#7#_ zN>?G7yLZ-hhdubtO)hakO!YBeIA*$euF0q>T>?4+g07Yq?`9e&<*;NOwjszZZ33^e+kZt$_Ujx^zSLW z>TR?^$EgyF4>;9z#)i+oc4R$ISjcjIl0DGHC zUfwH=uF3%WN0lQW!h~n}2yY0;P$i_L19L|e3JPVjStMmJcTJ7QrRD(14V}l=#-wu9 zVN#9f=g$LBF)_31mb0ogJL+I&4$vawrooJw0nj0EO9S>4KA+oUTQ~EqqW6r??bA4> zewgpRG82nPer<}Kt3GAnQ4rJ4KoqUIwT09_!E0tbs`@psoq@G>M729mQXc#|p>Sc< zt!yCgPS50U992RpsFZbD+f8!M`S`+nBO?{zy^ z5fb(mWhQ)TRD`K?VD$*$%nNZQ@JP{`%EY}h^}%I4pHwv^WCr&CZ{5>Gf;j4sZzr^_ z98BMKJT=%}MtJ_xZTcgL*4ZQe(Z>Z|%b2n}54xw z+(peVJ4lruiEjrIa_zT<;nmlKYx!sDofNKh9#xm^My^{lrt`Wr)x3Z@X^&%6qJx0pzDo`N>&O0?q)T>LP() zhfb(cB@~KAy5a_<6%rYEw^Io8>SRR-*ca}eC1@!jW zIGJLLnR|T8JSjbKRRY# zInpd%|Er>!kC@{2yAsW(u5We?p3bszC_T-aKpUsNQD+wpxO*-lb#qQ^GRN_Wc_)rv z?WodbgIl-;ze97S+?4&Z_>c*XDe*ftju#pu=wR;-5cqV$h-4E=Y{dqs{Zx10!`vQz z{y=1FDwo}w2_-0ObR$vD9ai+18Y4CkE7!4X^AZ==m>VurjH8U_2WbA`P8Ft>X%3Gk z&4ts_FqQGNh|zQGhF*!4i#q@uX-w+JSc1YG!RK#*?G{w$WYP{`H4OawLtZRG!F%$A z&w>kqK0k@~3$526^9^JhHZX2X?`gaZy9jo`g3m~ssNcH05p41X)My?1e00! ze$W3cdWpWwrwQ|B&gP0N=Mo4UdjX%`pJbhEV?JH_+&s2h-D9jX-{`&qvT)1CF5 zbkb{K7DF*P0v$gcAK_YL||~4hzK5l60vT>*ZXljjZtTUy{vrQDyOl zwK;h86Fy1wUPlJC+ULZ^U+g|-@Ml;z27cFpEEO`~vN9;0Y3k;}T*C|bAJ6E~UL}-Y zSKmhQWl`npVS|E9b^gFBMR7=Y^_vHR;OF)IL1Al z$PKbRx=f`wkGGNWFDDr{(iN!fMbD@BSjZGS+5VfxHQ$Jtnu5k3;Z;s~q0SBQuV2J8 z@3v-gdHSXAa@2va*!F+804MpylkbqJA_SCQi~W>MI{xFV7=2xAlg&>aB@9p`J9}OZ z_#?KL&xe7Q3Rm}*0|w(gSBtem?9a)7Nz7oH`>{}cuyKuxv7eNh-T7}(j1%!35kE#n|^)RATk*_;Q+S?Nm-loby~$Lh!q8JtF1@D2z~;4oat1M zGVd^#Wxm_RS22}TXa&|FAN6|!+1sP8O3?5Nd5G##%qpbV0&%RO(ip%@g)d0*XI~+S zHn>#c%^OV2mTErB<9M=784oLbtg>j2&L0? z021qqDHhGK(8*{JZ3(-*eFTUCj`_rG1G%zhtWke*?zlh8O9R{Wm(Rl!<`kGwVeIby zQf937ha=fm@JfSo*0lMs+$hk4s#cJXzAZHQwAUqVm#Cnx1=Ne8qJ-eOldm8zGU({f z0hm=K79ru>)`CIjYqSVhUAwO8%MI0(Vjgi`sB~Z&psdgueJ@p!<6U8WCE=Q=$qU|Z zv=09t+M?Z$5x{Uomvu2C?4zP;S+JXAdJr7M^P=L;Usyesg*3XY5EQwXa0~8F2l3~H z^3R#!ucCQ-J)@jU)v?kdh;?{$ufO1O=@Qx5*cwefA4t=#TN|QdI^Sb5QQ`?zm6R6+ z%=kd#2i!;4b2A5h`rdgcY*m)%G`!WNZ5aElgT^_PylE}bn8Y#;mS~liGv$RZmYl zOl$Floz>4(YuA1M?YmXYK#-**+O@e<=9|BHCCzuv1Fe6+x)CFiaVSqr`R^;s{8g&Y zh=m~tL{ss~4>XGGU>S+eZO1lObteI+>+9EYM~IK`A8diDid++2H(fRfM3*h@KYz^Qv!MB*a-spv&0X)t*P&54awoe z0xz-4BC?l+MfOt_u-|rB9<7S@fsgw<`k7}~xoN>M(!V93rK1x9p13?G zwi{0{zmMfRu}QLwsrGy@l(5t%C9_49uXr3M`-9CORmq_9MV9PUxgu(wj@+IxfKXpe zea$O2sB%@26BJ01gCm6m1pzR%zrwRMt5Wz_{~0B7J;&d^_RMN$x&Sp?UYVh zSjzBQdnLGSze`+@%vQ;yOEM(?e@d9_%54nPFxqtbyaRzPV_TH}pMyL*Mz~J5=oGFk zWLd3VBV0V+W6|CqW%(9SPmYp&zB7TadMO7h#9iaOO8atrUs>l1VuqDlfYH=hm*rzO zNgj#0YWXsZS~0|N`LfE_UO%BsD=EmPnLL3r^_A$$;rR0_THuab_055>_-W61nUtE}PT_Y2eF_z!%9az!%_+^0&X-KInjBO3Kh zYh*lK75erm?o|w)fz^yOOBLsc9E@)9U+()2^dSxR<`C|nX#DN^vzxmYf%kRVbAAnK z*0Y12->HG;KcQdd>dg^;@?CByBc}rwo7MGy>;MM5ecwUg^8iR$M_2B`7^DO7sqy9a zAO#yxtX>030D0cSH$Q(rGI;xLVVMOZmby$jOZ?crY;aAd?fvci+S)jEE&rt+;q`@_ zb#zHqb#?@|0>w6a)}z-uq^*F%iLQl6U?%JMH4ug(Z{qx;AjuxUn=#kZ0Lu|g9Hb(# zz#!qP&^Wa(F&C<|hZQ1D3~E3i3%MUA^CZMmWoJjnFydHU;tIpj*p2PCKbZ%=R7nM@ z^6CBaALfQ_6Uqbw$RWEz6EUG;<^%(j!31fv#3GcH$otQ+q$nIyci6vg%M_z47vS&A zx^@=XbVkXWYJmm=gjb0QrWF~m#U{V)TMsmMz+f@AQPJ(%@kHowfJH>iWJ(U(fF(zY zOeM2~jtG58JXdZ}6gHLGn=KN5N3;2P5bf%VigPFOLa^Ui-hcH=H&napqxC;JVRgmySgJd9p0DLtwYQxu_ zxG0sk|Cj6&ajOG&wt8)uLfCU?tt%ABW+Z;UTw$^((%ckQ>v5x}`;_pfU>k43oQ-yl zb8cR0Z;VVVdH`5~4u;{BpT>F+J=Ht08Et>1EohD&_QEBY<`cyV-F0NjUBlK~)qU;x z=_`8Yo6n4d96v`!ijO<@$R)V+*>XA)dvwCIrBh7jr|Vn=E*Of*Y|>gb61(g+Xx!pl z=g2w*S-&$b$i;n8d#hovkmE+j>v%P9D{%kToECtqzey(f?&)>+2lOSU;The$j<1PH zH2Y5o<@D|R-&Hl7ykoLHwJ%ucv)oQ}S+yYH^+Yj-&JQKwrU*@CHblEuCw4sC|MZkP z(4U6+)@+0(xU5(BbCcWi_F2`2SzpVpM_BL*qXoP*{yP72fj?kv$skCEj9>LOAtmpd ziACsSW>%dof=eua%c__5pyQ`3R!=$aZ;7749+${PT=Xb^l#aVn+DTmq{I`EgU~E)w z+cOM3)J40?>|7^COSBAZG*h}C zqLe8y4Y@M(E-pzDQc_bB@-;)*Ji_$al7vK;Jm78KB?K%Pq|bHi&Df|@3*beL^t7|j zZG`BAMPRQd?Afz0m2U+ce`yDLA^_fwj0Z;{Ri#g3kF>en_iI}H=27D|6G0y#U^trh zgVu*x3gM_x~^x78!W@#FQtxN4g(AAqRjY{VKI$Bcs2y4tVk@mpMf- zmFc8(+qP-JMQ-QOoOvkrd-#>TVcWETdE#>z<2 zKy%aiBfQR`hA`ev#}4H2dQWt?L2?e6UfV*i#O|rK>kFcu@8!m}R>c%;#vmtjg3oho zfbY1|__o%A^aw`GRlg|CSPR8jMg9G3Ps390hD>Zt`{QS{>AjKmET@e)d+U{!Ik_Bz zend@WGVULL^&Du{y5VA{PdO|U&?9FrKCkI8*|d!?SD;&~{(hP9(WQDjwkSOGvKs zqluDxbJO{*EG)U-C1dVLS~>b2t>?SpA{5gLH z`)#+nAH3tqICuWb)a??XQ@SBE!(h*uN}$u;OWJ6|+hMTSF4BI_Fxh2C-){d&!u*H9 z*YDMJ$V_Rbx4BMOX`y+IYu&5;Zm8TRkfhjWy;pmzq?iJZ8>+PXh%`A{U|A%078mnemEGHFYb^8&H(Z6`znz zhAX(nDPX7IN2O0`WtnuFkwx&#faZ_aFewAZBTq+T37$xEalF7n6LIr?;2c$e_aY(h zZFvgDzGr&@nW>bC_;}L&L`>=jkpTtdJY!|x(B((KqJ?b6F(R#VLH{oxl%ENM-MMe! zr;b;~eh|@Xz+sELmbR?TfH36dZnNc+X4H<^T#%h50=fi8F2T5&W~PGc@4sFtz`Eq{ z!k~KY@BBPCnde6)VGbB;fUr%|x`{D5ME}do9#|=8nT^)^jh#VqZjiweO{6IJ192 zNBzm)n>yI@#Oc1%*jk_`ipgtW`fD1I{Gx_~*TL<90d(!a=td3om(A%@?a3^`L+$8^ znj?8K)8+q5EzA&%0>Ph(c#Om@GDWWE9U?Ox7Rzc(WNvQkVfc z(ui^xmygnf<4p$BvWRTI8!exVcK}KN#P|Yo$1(*a z2MWkkv|EHaD-d`{ct0YTc$JVewx{8rF!mQ#QA??qh+Z_EEyuC{#`0`?0Nx;*J5!PC z7!CHthA+!Bsq-7Noe$6Y)uE%a?eS);#!3##^21739{VRMt0z}qUwnWbimDE2TE>0# zyI`ZCk$^u5$y8Le7Bm~f+}iCnkv(%mQs?l?d-x5aMos5y7ltWEXUUkq2MJ;YP_PK8 zeM%Exn$?`izLmwgkpT1PeI2|OXT0FEw3fa3M!}iGnhn<<*M`64<~J-3Rnpb+m=xn- ziC1zX)^MTy2O$%nQ!U_nGo{nu>Zp#Ff9^^T4Hvr|K9 z1BvttcSnq1o0QdTwUDgce7W-L_IS{c#g{~7s`TK%=hSsaUEp#D{hB)jXI5&2aLT?X zk^0KQoS~2x!}$6RgLQSw(BkrHwNgX6@rbf>iZbRil8HbXUbf>?@!BaocC(eGKuv!@cw6Ck;YaB>ykU# zJS?qjdwE?^TE5@*E12ixvFy#IebF|KV+n{DBO2}2eUI7WBm7sk5%BR?t}AaDJ2BFIThQeg1Xe z^YWmY`PWg_713*6RZC|_px{#JMQO#~swjSHfTe7|BVO+XNID3;{1SKE{PH}Q<$)K< zaoEJ@{)+R20imt6cmDI0(f1DL{qk-JevFo^w zyuE&Qfamr z+}8x{4kts{7!nLNPH}wFz!41xHu1>d_=WqUR$JA~REUY@Z?NoJM3^8Gki10o)u4c) zm*12|7ENetVv2Quev-;mfOhe-{7)jrOiC&Y6NY=c^7pgr+@tq0RAWL)~oeq>ESXNlj-{l6&Ye z8QA@Mr14C~v!}8%!{Q~>SfeH<$0aq+JX2c=@CXU>^RsMH@ad3v8Z;&}?YM}58K(t@ zTl>bFeT$tTt#=IH$0A~8PS3GOQ&Ka-@+u9_l20G@lD@br8=d>7;J;x-MwXy@` zZhNKA0HNXwPQlS9s0>jbxd-&*svx8LI1RPV@w`vv^?H)Ws` zyE);V2jo3u4tx^R0M^PA5%+8nm#73TwNxM=jIxrqd#6T$E@L#Y)u=Zj1mpr0=+yc7 z`5~!g2v&M?Qdb6E)Z&}xl2ofHDXro$j^)eHWwUs_EsSt$eL95p+F?RP<^}0JIzl-# zWJUL(w+t;dpmGmlU8pIN_Ht%s9!Ml?*u^HFqp&0)BbwiOt^CB85xS!}mk}%EwwJ6>m>&Bid@i{pU1@6qh0g$~A@Ilza*mlgC#SiJ zHnIE82R#Q}=KJ>sM9hXKH3T%~4h@C1l`a!fD=u{Odomz`9XK}zH1wD<`BWZdy1q}c zi_UPiN~*;-^Rad{5EmxRR=S9sKh!xBm#=Ox#NH`a%vW2ADvJe~AkUF}Ya0xW>T~9g z@?D$B_V8qOo|feLt&cN@xc1NuOLN`1GD9Zwv=U%9x|*5Da`^pkrKD)p5;bE` zaY{jngnaS$RByRN9=Kzru93uho=5y#^W8A|&251flw-XTgXJmZynB2%sMVfw zq1|F$z1Z$s?9o43`v{%?hU%bh|B0)I4Hb9JAbI{59EkvPl~4PrT9?;_Cq0WHVlYXZ zv{loEdY9UR0B~LXAFsM^!Oc0Rr!P3Hi_+5dqYQpz6j*?2@}*%sn1iy#^AzC}kfER8 zFhQcZww!jlDOM&YCNR-4Qq_t-4EQQielvXiDfoeq!{Xa=oJxL4;H6X>Q`2p$ljVmM z9yDT}L~J@q_EpV76=a-g?l)?ke3wfD$iw>`xJ+xi#nq20Ly2+#1(&L*n!urC#g9Ti z&?~R&$E*qk=3C5wm*^M9OU;q((_+I1pUWX%iTzt-ecpHLyZwhb?_H)7-)LWtMM1&noicbPaAk|XNc8A|X^`u< z+rY%aA{EdgQ-+LPtTBseE_A4y({n3pYvcR-rNJf8Jviv}L@{W#qNrL`Py?H55r9Pb?|E@j!?G5!CR^FnjUUS-W9cESSq^MV~Gu@jASjysqoPj@~QT{H!**G4s zBZmrVY*Q)_>RnxdaGg^{kgmNa}A^7=|?^TH_a2>jajuk zJ)_{OLz}Z6oqz0XN%)Ut*8@mNpvpp=>Cxk|Q4UT~k&(0Ol%{4h@bid&egZ$o7=Fukq@51Lhx6@npo2o zBiZYochq!CSV9*E+{(%pb{@mD*KmM5n^Y{=3ewEafD@d|%GFiu(R=XwAll`#6`ikm zi08Lr2q6jzq+}5TPkehmk|lg`70k+XkUX4An}r@~9|+%;(=f zJbBc@aku8cmi6-_dfwA+^*pCYWl!$Nd9V5?WaFhj#IiRrSitzn7|l&j$Vs%StUg<2 zg6AW1M#~+|n1jGxPrDU9BTDLWW|-LBlfmTABXat`D-rSvTZ{jxn9XUNpbi93z1bj` zqkN<+J*Bsg6Axn0u;?M1I2)bfPn^-wutm+l$;!~(Z_-|{5T|c*5S-%<1vwd*1`RE) zg50)YV{V?&2nAcz)Mut4>W(~lsz5p?DQTuQJ_t@&4$FA^Vapq)de?(j+P@C87hG3S z&Lt54jKHP58IwHio$9E-_F(Eusy*%H=e zm-nvA(oa@yw#4t&eY7~gSpxz{LpFD<@5A_G7YAC%b&cBl4&Sf-u!`n)WBjCZxO&jR zWN%lE!BxD)~*8{iOnNqV=yZS}H?F-mU zk_IVXZva0h^M%|e`-MQM%j-6p%Ljh{vU+Bs--1!H>?yYMpRqL9J)RbmKA?Uf0(}MP zIh$AAk$B+O5M_GZ?x{*Q`%|A^dt#kdk)m7Pkp|LPnVCG_)^LNPm2bpbt^RrTnsO>q za{vzj4AeS4gnE2DqX%0nU)NOL&VyAOn;#o4sl zuwE;<4D7cCN_vZP#c*+Ry~Z>+f8_HT23ilPitGBYC( z74-mzYxCv_wfCDkgpee2D>h7rzMs$GaMR4}Y)!lA@^~eX^WzPbgYgSmybI2_iSp# z6jL$ZE|6ZiYwA`FaQhx~HGQ=F?cXHDvdtejW4z`(*mP|sOPc5-XFR_lgX(aOr;_iP#d!TDUB&>(jAK4O|V?ZL+2@0}noKPrt`AJXmD z@VZaj`2C2*?ZtAltTl7aP~Ytmp3`Ifb&&rS`+mRFOF@-1^H2E6uZtrs?(F6+Ik}WR z?k|l)Wr2m4k!~dqrqw5xI@BYa$W_HDUHx>{YdvAWaj%|^`_A9~njy@tZ^Q-DDQXrT zS&{%eLHxsSzeYrwk^a+*N=o*c&phpGN6f@h<8b^9*8hKfis0~(U~_Ex$GbK#{M1Mo zOyYf7%UBBhB$g`AMhI5Dzm`VGx4SXF)ikWaUE*=qGjFFidAVRE9h^NueOw zPRQ=Bd$_^Zdsd1!)8P1a^dO@y#Z^sYp&cJq_kS*98^G@JEKO z=vC@AyW!8+sVJd0e-g&@Gct~*RKba9D@>Yul9w~Cmx6!`{&Srlvc-@Qr6Xs0!~mWK zFU={U{ua@Ee#-x*9G*xgD$x0_f2RlZd4-QZh19r_@}}a0Yh9qDZuX6HEjGPRtcIB4>qb z3;HR=!YWeaD@^ntt7Vq*>v0y}zVs0jGEz?RzzJ^d?|pldIX_vfK7Y3MR`pnSC}w$F zvUeVX>lTBFbd0Gvo+rmZ#~5TKW*C^*Oj411k!1dKqfD`Q7JG>1MW#v$j%KL51&J)JkK7Q)nNM4MI(I$OY20PI^E zzT@`A~;Vqba3@J0UL4Ndg;;LmUKnLM?BzxQ$5&((k1bO%zaOQ*TeDV{TEC8{<;ZCo4mXAz3QYP^FXK&Vi7mZb>v$NgDVAd*$`l0Lvxd zSk*FM|FdLgiic-?Z(us;U?puAgL(*~B#GU=c=I+tdF8}$csCri=A!t^AAbmRC@FgU zA^E@IFN?C!He(p4J)lG1(Ac=#ut$HY=&{-JZW?u@b1_d8Q{uJ!w{LPv{Bq?`o$Xh$ zjj++#BJHFN_(@no0eMk@#!1kw2!BIk?cMno8u|jg!LLx7GG6nfwJ| zUr7YEo8BJC)6S{+JcESTRU@B|x*ht=x1NAi%J zI84Qu&(TBAy1jshdbuVpX+8-^+o_2B_wTbyAH!h3ssav$n7rB7D^ZYq1CCZPJwfC6 zw^ans8a$K{xz3T#(PnyINFe2y)l0B^9mD+c)y&Us}xmETrC2A*>m1C_?U2Vyui1PxZg|x#ZtJzV-4ZQ*0S~aa=OKPA;8Ckhxp~;^KUt z%h9(ND@Ns9E8d^BA5L$6bK(djy0UHlgtT&!LL^h>O`U6^qo4iztdBnwMf-bsZ<~k@ z3v5-QLhyYYfLmrj8x3bFlF4Ih*=817?+s{wo?RkDR+f>F^FDBBlQr0!if(G&tbv9` z2l&$!38B4W0u)1adNFXYwkcGpUiUJ-$(Yh=MY9H1Drj|EvDI#SyCYD6-ylH`V};3@ zLoU(V9px4Is*;i~bS4T{FXn7b%U$R9g@UZ!zA=J0Iyzdq_AzE|k2gqr9-n;|jK44^bxFc9ka263JvD@(OQU0SqOEa@Fv^binvd8b>Z)v=p`DE#F%qxw5 zecu{CFiV}+5<7Ec{{Pr|>!>K#uwR%EkPs9^It&~E$&qe@ZlqyAkPxK1K@>zvxDjH4%8#0=tj=JlsSSyi}#u#8h0)<03TdP%bm4n?#?xX%L0Q^<8u)a_CF%Jw55X z;*am|-e?4iSn;mUT&eFQ4kU1U+FIBKm98yvY@PLfa6d}9F-&cW5495UH&4-({PgZ= zOKVu76Eb4PQ&#x$l6{#lsoy{B;l5q%5Z}eCWNlvGus)H4siPRXgFt-E>DUh1<*b80 z=`l9?wHb>Uj#d;NEw9u)TDj6gSM%+n_jj4`8S75;{oHxuRu5R8AaVBgA$+#YQ0l$y zbsd`Mo!ceKif)zmL7V&g9n-OEpl|38Etk(5xJrIoW3a z);b|SwEs{>=u=dPRFL1jqZK>^{bByR_*eU|!i`VZQ?e3cIj0Z-)_FBnGgA)Y$wYF! zKiFEYFueBdmbR~vX-k9|6vh8!jqrUimIqQy?5_kfrgS9`M9))YlyRB(jzCX z>fRjj!fJhjVV6QS1D||E(rypO{^w8pQ(n z`=p{svpKLe7n#pdzB#Ad3CCpnB2caHPq)+){QuV4EQuo(dwh(v@!lje*?q!}Up5b{ zt{QxH`@Mc{rSuSs`q^@tQZz;oTl%`+vW_sXmE$EE~Ib z=Y*QfV2?$@y4QaoJ7frTV+drUG3M&N2bJnAl6P8$Z_*s%`|HDR zabCxlDjnN%LjE%|w74a`A<)FJT5u2x)_|P|J*7tv=MbLwyvZW>rHIn%m1v z8N9ipr`Gb2M?ZyfU%A!=FNQI@$u20BJ>O8h0lQaP8XK}X@`cQcs983DP2(l@0)>87 zFEc}?dH!`7=M$Bh=md`N&C8nlW!zxXf8ahD3Km!&w>issYQjMUgDXn31i;8HKY6XuzOdm8*l|{x_S=URr z;nINEOYlq%-q3D6%3jJfyxRl~aIi|6iyof1zBf)J?3)FN*$2f^j)x6K1B@Dpmmc6b z{fOORm+@KCrI6Fsc+D(lRV3mj_1V_g-bl-bDv#=;^;bjTTFI^bZm@QV8|v<1OognS zLC$3A{Cn`WF~Q#0$M|Q%wK1{epAB|0l6B@UQeK`P+~+4ToGti0c>u?KnRFxJdhy|c zsLHzetMtyz*<)8B!SJg!y{?`blZYcK@8jbP16uNPI^o6wvcl)juA`Ul&0AhqdY(GU#Bu_;RCSKbB2K>J%DzUojTb#S z&y`VhOjP{48PKVNu9?3`$=ebQl4$*9eIZSiy`w8r?l4CCRDz8S`WL5y$f4mY0{b4* zFYPLOFstzUTW+@@JtPcb89xzx7x~k zpo8r^r01BpSI}&vX8v9VL1E?ONA>|nU+w*fzvM@|)`o{$e9NC!jSe+gPB`h&OL8s{ z_Xg5%Vkfb@E5{^w%C{oZzvSmqpV=MH0x1u34f%Aub!E1=M!C zq;Io(5udzV&`)w{_D9gtBd*KB$NTS)+u7Oz%;LS88gcNL%s6P7K-1(n*#C7F#6@@a z_j9|47DWpBBNddZlDCA`FpT?aeM()#hg-K=ET=s^Lrpw)erqltKg+4gkeev{)K6hA za?N12EbN}-`|*gP2X~lmiEW)QEx%>`K{m9chCVi<`Ac z676fzC7Dfe`D}&-qCp{<(z91l`{#1w*1L(j69WtBBuDSxN+>pwY9;H7XwJTA@-Y*} zXhBPQJ^ArUyyy%=EWFaf$hV5>TPlN>J(L0@qLR*dzPHx99e7X zJ@THf_5D9Lk+j)(WKwAgYP>jIuc-v02y)mM&d#tvO2_M0T2^$eo z`qDywvFk;jnTfEVJ7iQc=I>3Cfqn;6t2hj_s$G1BdSXYZ|Y;06EmnB$P>aTP~yWPy# zMRavbJ*5qWTI&axv%gt+O#QmInUmeA4bj~V*GZ2C;VVGEwX(9pX|0dj;7VGF?v;3` z4zQ*6b`J|*qn`M8UJlz+qi|-J=48(uQ|4p#u!-CAaV6U<-)skp_kM<$SgT38j<-h$*+>nT2sXsz|Ud`8&)x`=gO65q*m^n z+)leTLMq`d9v4H&T8^=wYm_O@lADCkf+5nXtBVbt7z-&!MZc+5%bq0_Z?QoxVx7GJ zJpu~#y=4e-z-LRW8;#lD6=ow;=u98g4!&TeFr3S*ELDhysq@aHSXVbar#Cm5S1Ve5 zs4pug_mnaikT>+Sp$x|*fCte=`&ruoCgHseW%LnDSIS5;cJSILG=i{ApvT?=FPhc4 zbr_=t+q@}?rZfiB>)Z6fJ9i!hk3mGm>X2dlZ1iCVtSpe zl0}azdu0dISLpNxp@Fm#k#hLfT2y>|M~;%Aq_lKeZZ0EwcYL9Fl{m}BQS3m;ho@+K z`~R#Uvy;If3TX9CEh-Vy>JIPm#!+uvq`duXcCX;o+x~jj`Sj|6;ZSXY zboi~aE{9`1jlDR_C)iDX`+4>y;rzv$0plKm6-bo{>uiVoGD=-OBcU)9yNkvZi%55m z@OPF_|ECn$%v}W{o0i~wKJz)A%k*cy{nK6x(O01c+g9+i_x1&Ba2%nb3+U4B&0>}q z@f3i^3XMHAOXIf*vTo+CCJy(!a({%T`V%dw%4pUy_I|+R|LX|3FbZqi=u6(6? z$hdZFyOQ2qnE=k>k&##6eE!fEuV-Ie6-8@@8U1N=W?FSoXFHL|uiguL6OLtU`0zt^X( zHam>uaQOXABQ22yRpcdyEsNc>;gYo`ALkHZz3GZpbaL{}3&;cQ=0HH{;`-yDO<;R{ zjU1n1)ycwQ`*Ab3#JyJ3SplHph0t-KvHf$x>d&{84w^Vii9&r5>9l1iADAlVX0D`^ za;N!EMrS0~mn&LKi)vZi8{R^tBrxcm1{7-`ZdPvmRYN?ynLK;P2!j>>+v~#PQqxyv z6xT}QFX+h{>PP-&JZR3b|0XRbXNPryi_>B4ESj$rT$0{da2TU#V>3TLhO(M`tk94G zRy0`rG`;oMy%mjYeaXy)>yk7GS&X}6Xh0+4yG*Ns8T5p$&U+F}u+W+{=kbnHgDstC zR9S8m(u*^rn8t}4inlmc-6}G$VpY}E%Z+3ZyKe^#!CPizXA9&hF|!GMAN*6JT*M$M z_um@Ndzzn@*TeO9?Z7EZW&K$#DNRS@@bPMk$u(li)P$9-*8j1dM=PnvWi$69n9%nF zfu?36=rIocTt$!xlBz>*?Yb@c5VPjbqDjrwpX3}V!qqdk2Q&!$in@zqp%_;0mp~}*8ByKZ5+u3N^I~t?z zhc_rg&XalL9-rLAZ4?uIT-$T|Sql`eH)o0W8ag-t_`7o8`2$(|LuAGS_r%>doVm>`frbVmSIGFd;J*jS0wD%yg0YKilnEf&-Q~@EgW-j z={=?1*~NVy4YHj9O^1i?Rz@+DdWG{|+8t*DZp%^W6c_a9mXJ5vP<258p)Bm`-VAl8H*YY(7X)mf z?(aaY5SW&Sai_~*uz4IBA~myfMpR^zvTs3&xd=!`Zu_7Ba>vZ;AaJIuI&s4f#Z&OA z3mOvl4h^(7IQCxh%_6@-VZ1XUi_O&ntww2T=rF*Lqc5CXkl3{F>loj`i+|@ zgq26uih~+1-y>^11c%p=jbx$dv@mTIW(@C)1U*D?5cRaQObkh2JMbQYyZ1TF2_qB_ z)M~(>LXyr{2v|}+TfS{5dPp96`Dng6x-&-Xq!0PgZOdVa4rTeSbje+gYBnWfA9kw* zW}Vy1m$|vOSC{2c;3RhM;aC}p9!Fq?4X(3auruw-#YFQ&thVu=X2gNo1-%}<4HW}D zxw;{K(fB>t_z%v&;U2>Ms#h?&k5zv-5kW5Cf_K%F@_U84LE%;Tey+Lm3r{S)$P~F< zRweG2FnN`~JOk-9K|Jf0>wTeP`)1i}HP_#ltJkbL_pY&oIK;&&%QuF-{!Xqv31Q1y zZeUjUDBj0ae}Z7xB27XD11)l7U8}pxuzql8(MpO8cG<#m++kKEPN?9Ys@RylpFwdT$oXKN zV5fXZCkv;P_nScEP7H>=JtrmT#EB!hsN~EJ-5D=raj!MH+h4GylD54#epM(u9JoBz z(A)JG$_BkcSbv*hvV7>_dh> zzOBoaE8#fO&da~e`h`_?Nrd^GHeRcofzck<%zVDC13+KLa`TC50iRcPX*z<( zX}gE38oP&3IKv7cbR`s*EamksD_T1>ckNG{M=T~(E@P}IK<5z&f@_{$_b?Y*uY^hL zZ0X#RwXfi=M`l22@90RWtX!9L>kt_D^=8^=doW$13Q>Ct+-|cJV*Uo?`fV32YUKEV zZo0Q zS+W3-C9KlZ*Z3${yc@`hMA_wAz<;r6ZoD3kI*J?RA65Qx-#|g7E}HLZrvfiJZj@za zuim=wLBoeJbF~yU2(ot2c^Ji()YI=+8h$iu3kyg7aT^sHT>B^DmS6Hjk<# zQIQ*rtR10mD=|&$Ay@pEeJ`6(^c@A&QRCN~g#V)jQ1ucjySFv=YMsDU7O~K-U}eyx z|MO6hUreNpr*G|#XEEo8Gk@7`^HRg<>mz$?xq`J8RRzvVha+;8hFHT~FH6C9#qu9l zZ@kMBK0e@221~Z8PN43ei|oHo@MvA0r+dO|i9Juk?#|Y&vx7dDA)AxkF%08nXmf?K z6UfiNV1oXzc)lq3Sf_r5S5ge&BL}LMbhp$Hn$S)P&W|_T>1s*T8vGP+ybenv*kQai z>Q;QIrsmk%Ey-4S8Z_u?T=ZEwE?Dp$wlC1sy_ZIyu7lrVoeUOJztKF!!`S7{8G(Sz=sBm*aZS%MlE}N8K9kD+|qfji*^2z6ZD-ALb2DN=} z$M33Y)s~f1f9K9(<@gBU2geSBDVr`kyQ}ttTprKSfH$B@ndjy$I=VF$G8DZ7gqFm~ z`+Ru-w5o+_JETE-WG+?szNl_=m>S7GtDtSkD;UPRpM@Qpx>~gv&(-v-F+Fm}sORQE zn`M&Lj**sI0&Etn`!QVJFE5{lNwzZH5@pVU(bgg5ZVE@6BegiL$Z9l-sHX0UnLm+x zy%}5gnyqJwCy$_1PG*&UuvwWH)-n5@@&h+9gqVDs_RB}Z)Mw`7j6?-K_W$xl+bj~P z+OLJbZ1AnD8CTMhZlYc*$83L|roGwzMh*|-U(ytqBWBj?^fQ*+z0<~B=J+OPN5b!K z`8yGi%=G^!ed~}SRNkG5QnX~P5%9xVl0p1()5kO)<9P$a#~UfJyr-(^v0-VB7f&>A zNmwoA;QpVE<3AXuDx8?x22Y)lp+gU--s>>fB1_B5%Si?TsMP6f=wH}QN2Qj5V-kd< zr{YI_YUjxx#s__>cp+tQb4B_QYJ9L*PvgW}nT9Ip1Kp9N3Y0<&0w@Ff;{h)9P#F?MhS&iWcS%)-7H^;MPidj~Vs?kKJfV=kf@ahT$ct|#nNLS19#%KZ&i$kps zA`))y6ZCK6H@(TjFq7dIW>6ZtV=4>%`M~kgvXT?yeZHm5cKd`g2dxS(=hOxdOS6KN z;6^{~Z-AtZnGxg8M8H%M3zQBLvK9)B=!m&M;%a!*2%wuze5!wAh zZPo2-g1sQ^iT%U;Y8?5FwtsQ&8xD$QyGXu{vu!bguYG{dEn+Z=44_flAod9 zcSlGSW>lCteS7u~@C7M+Hn5qXn>;)}LpdE^JTw5cPtk=OBC1c?eV}oDJw>kv9p@$5 z!i?R?ue=@?WWWqSK}rcY;*a9J*`#H>9Pjo0z?81KpB^0;`M?={?dtggejWQ4Y;w7nZhn}5`7x%VWgnP95Y|Ei}iuHO(tUh^|D26o{%#=H6rS|v%GoghU z1z%-=r@2s1*_dO~MvIYJBBE`56crFZq8~w3EgRHfKWx>5`h2JHYR)>2(w(FzNWQaV z%I1>_qR1^S%DuwYw^B5gqSv&YQNcxFbT23ari}~br)bY}APSn8AZdIQ8i;P>Ol zLgP%#D5_QCD#yC?(xCS`GcmViPrs7uxURWSiDTD?JH+DYN}z57BheNERN}hi__#-c zRWw1Luso=%RSIq-A5r#2#}5yue*iR%>iE0r#2u~VZzCh`5ew0AeuOmg9v&VEnAYq~ zJ81tAdYJ6yV=tmvXAz_;PnRUpm4K-2lbM7?3+#VTl06xuF#i?;Y6 z@78xHd>QA(V8w}Z9*j|gEXAzf6Q%A9Ur5f88oD8e~%DX#CICP z69_rMb65F$=Q)PjxvCqS#yBrAwP<$SxLj3}5-4Ai>}~U2+&yiTvebeHdXn@DTQ=J} zSZbw)M$05CH3gj1HV{eUyjqQYU9ujYtwS^=tgTgs!I!JMKQqQ;o1dSbUQ|>`D*LgW zL7@RiKZ+P~q*xrbF<435s2B3qBhkvWW0gD zzoohAdKM2QNkLsqO}Ct8UDyp<3+qY>k2ML)%B$O-fcRC{a4FC{!y*z>h0r;OXqp~t6@uG zVJTq*{yh*(r`wFPMI#vsNjXB8$$#^v1~`f<7goy;Y&e1yY@WZ%kV_M>Dc=G4%H z3wr(Qv^3#bA(Im~Rid+y7d@smz8Mis?gkApFxjN4RkfLwvLYcxBFJ}fB&}T-#ChUy55Tv z!~YlsV6S)W&n0%OwNRQu)g1Xkw4o6R)4rK9WCD&T<(?lhao?>n9ib3*DC4rzZt@#T zOQOop0Rs~ge{dHJM<9;oCqoo$V2n0Ub7_>Xk)bK1a@HZg4*GZj5wb!@;Sb(z^r%Uj zATS>;8kKfu_U)xE7SnKEgU}41Wft2Q`Yj8!IPI88p6>T9B}gF#Elp~p7?+t_I13x? zFweGr5V}am4if5Q!XNSa76wrx5`%sWBanBEXQBX)RRHIp#Td~Cs66}{M z*PWkXtp6mca9}yeTNj;&_jWNVnBU2dDKhdlp6A2zI5Zm#ht21T(G@4{*JDsd!THZ% z-qDRDH|65=_y4vf4KnE%V-;KoEpVde*Et}{F=IZBHX6x%1$>K|XnNF9!AcfZj8Ca~ zV$@OMu`XibFTv6td5eCTxxaWZ&CWmSV#lI?l^vR2L$Y;=9WU~>%&#x|X}033AUxNL z*tJ;0y&}(m^-Ejke_6p+qqg`ne4Iq%VD76edH{(;dUGC~DwUTeymp1V;YQ-B2lgeH zgPD3oNqYs=?UUc!>g^es87XGgO0?V5VQ%?`5qzNG}3)4FW|BXxZB307(YyQSBuV?PXqV+Y9P&OZe;#?P|&8#N2{XNCHEOZ#N91y`ZJiWG?U z(XXZ&$mR0tPhcS*RLAh977}Qx1nbh}`!c>FmiBl>4UnLR<+B0wGy*8v(M<+Y`FTv~ zs(a<;TSCI-K{M6F3=mAN&6a6PiAW~HAC1~|j=|I}x6tpX&;QyMwk6Xu?`{@))U!D} zQ*36uHa%zyYolDq4j0!vZwy-Cn14S0?O#hV=3M&AY02gmUMh8*cB=)?`898IG_`*A zrdhR>M%IQYncwd(7+`%ewvn;3WuM_F)6GVH>qr68(u|C)E`lxKJvRm<4s|G%YG)Z< zq}YY8(B|plUvF;FI3;)JJu2>2Zbj@V?{C&h7n}Lt#_(SOUPJFcsg%Sxj0JMinscJn zVaHXuDa7NEjdcR{j&g_7l5$p5#CKibEfS@dyzPrDb=ih*jawSgS zwtpJnFzbnw_9OE0KRXDlUJmgTz}nd(Homj{TfBMf6nX5|(@d+8IaWjv6>td%BUvBu z{M2tMe-R{BT~@m_9bbCKiSnoMxP=x;r_0kod*O^+cEo(1@9F`p(`@L zJnm7>TGmO04#G1uEcS^oIi|d2r&r!Glh-;>t31;|H0#b!){wb+tGs-KNe^UJ(4X=v z*!`BzkWlDW5GJKstC7VT;W`g z0$un+RByYYyeo!(grB#EA|wfoXEUJK2{x88{f8u^Aw;$-L#tM(+qQ{CG# zJfF~_j#KgZ{;=JTvS~N9ne_t6ZRJXvdd1``x{s#|qRFc`dXL=2_o^48t|e-P^hW?GbFtO)ZsE;K&U(Dt9qCKAv*g@NA?k zA_WXu`1*1R!Jt4h&p2?mA03}T*Ey&WGa zaWu009?gmd!w!?Hv!!Fz4(IyO5Y6O&_sm{>0=C}+%>J^GBo>MXOAgx?HCaBd8DS^p(Nrr&0tkD&OT{#1FpvZg`HQ<{{aM5un*aesLDgk&Gkzt`v`Z!X#+ZagQflj)5IjS*>!Y1P1Tj zWMk2lmzGus(qc_ekc=PU1zZ-q4mS3mQA4T9oL!Lwi<1yaTPE#Cp1eN%;jGKtIQc@> zVK);HzdbTZdZ5Pz?*UoBgXn7l9gM1Kl!dE8J`5hT$;LJ>`tp&?VRF>bp&9AT`*o8M zFJok~_v@{Ze7IlNFW@W$I}SuyrI(epa*X6`37K9MY={MGSu5!3S}>Q$6+n(%Ax&2! zCr`Mzf`LU-QBN;)e%ER>=rfkapcXO*20z>+vyStoOlpPpc;26nz$j906;fMZa+qTY z8L}8JXWERFm8V5HtF{&l7$BNLI~GlmRX`IeC2T`Qq3A^-oZpUOsa`baP`0 zktdjZ{8fR^1avUjMaG*#R{Nuy{QM@5*cZG5bZ#bOpFcdE7P+outI1mV9G^0Uj&@!q zVb>nyLr^CBEY2Jy!j^WTq_A%;yDZ{J(IF(_*{^!VKhY3j`x4P_839qi*3#!;^Qp=f z@$$P#u!CaSUK}iaWBVDCY;yJ6Vb^BPyF91f4%e=~|IPG@?CRE|>8>VYoz|#w;j{wb zxH*4VS3~G*uhLnPR^lun7y!b&RKGVMQDC+S245=t9pSD4DZ^3yli7PStpYDx z*UkEyRvj93Rr@L{*bQ$E?}zFMg$F4IpLlTu58+8me zeW=op!;{oGGKoJquma(8vtsq!F|?!{{I)G~-O*>K!e@1U=f^10WA-Aksq-1ru1=4( z$&>F*kY*TR$@+d`i@t4T`Hm{oRUWb!jPmRpNa zKag_QWfx#Dw3ZqGakhdt_g>5&Ez!^}KtRWl@^Ci@RxIJiyg)y!rm4z{Nl6Mz?>Uu6 zjrQP6@*V+wXbHIPm#hb0iahmiKHd_6zlqay&zDz{-|?p%!K~O2sWSAh*tgq!xLN@# zJOu>yM`L49wiz-u#zmfa+<3@@0ObmYgPEVPd&!s=OkjltR^K&vG_H*ds0&cKv6$0& z19}nUxdO8Y&(-=j^Te_nG`XDKPd9uNSU80!_1fd=Z#|Kvk(O%m;y;+itysj$?h+i zY}VT%`dE}le|jnO%pP&ql5+kHj=c(V$N4(j!idR`%fkF>qFPBn6{|=*6tcdT;zFi! zw=Mss1!bb^(0mg5ikE4Jm#I6CFS&9{v*K@7pAS<}}#dqWOE zbI=GsI%AHFiSnA&W;z$=$c~HUs7T7T`RkO6n*Af#%)xJ+j@9!V-76L&U9GOlwUnEd zHwtT<$MKaV)0ORX2T~vJ@B||)JUk+ZJ}z<0y6i7wjli^Go%!af6HOp=ow8X6JE#bX z`xW*o|8#t}pFZ~#y&*QG+q|vu_k04?F28(%1)OLESY_npNrQVee&>_?re3{s7)mLB z^YoYE_g`=Phk?SYtEK-)UAh{nX%kqE5sChayK-gqU0*AOIIo5#Mct>hXk}&2*uz76 zq$@jMgPEI=!7_2yj|c1&?Ut0E6Ye$eIs+vnPypNf`IWAXZsfXG$omd74JyZ}bEhq) zucU$Hj+8V(=Z*c7CZ~Bh3@y~D^QOijSVh<$?3l-I zjv>^v&1-#JuU@_4-4rom6_*D+rMRWh(uD-|+rSfnLd`S2OzlWDBCTA#B>!0EgnNW~W`cuY_Pl3;82;@Sxn33(Xs_WRo>1eEW?t%HQ1utt{YIy*FVz=IgrixySs&a|a@ffcZ@D(*^fi=ZVIO$%>_k33V>N z36G`A6126n2Het^IMHY&Ml#P9DKkmu#ih(Os?^OS_w&bslzKZsc0!_Dw|Kst}oM z-GI_j7ud`!{ zTHblVXovr~LVH$QuFfT9(~iRvGTPBl0+9hbs}9*I?Y(HN#uTAoX5;ImU2g6O_%7qj zaobfQT-`PSRSGVx8P79&W2ByxMG281tH)1>75SSGy6+OF$KCm{u1M;}`Rb%1tT)xC z-8_7M;ZSGWRjnn+R~P8OH%zN!q)hspeh^05L57-_35L(3wp_kksPLsd?j2ld)>SWM z+IZ|uX4=ql{Z%rZ!^`%qK|?ev*gk)gxaVq!lSxTtY4kK?rboCz`g1W=es0?HShLNzXnSs1;Jv`wbvCh+^g4_#6bDB;M zV$keqyEA#H<&e+lwrse^Q;yIinyxA2IzygTca|pBbXu9O27R2$^#3~m)l(*A`&Flu zmTTy;pjZ62ODJ@&%jm>zF%R38sKMKfHl;h@s-jCx zwm)6)4>AO>I+$yeIb;1Mn)NM6!<<~Nx_QXEsA{G#aII00RknJbm8bMtWRh>Pt+DV4 zvF}HE*ohEPvNcKZQGK9GXp-ped}jIooJ@`i8!fWG6z_V2Ezx{c4FW^*@YN^3xd8i} z5J;rB1mXpNLFoQ$W>u{8yy6F}&F2~na=r@Oag1W|My7*uyb6jVZ*q~%j!ZEM5diXD zU*RZfOiV}6K154X7kV*P4pr-t1XAgpSvzvxl4myFPi?I+4>c%U7(Zf1+)eGp_ZMVY z=<5+;cg4mUSnlY4+t#%7LvLg9z`XHdM`x`MCFa>EkfS8DHq0c8J|#qNYs%;BIPbf3 zzX@a)0GnfgIEqHhqvxo8M~uS{fu94ugKX`bUY3D$S}|Ur{|4R_+>)_RHyfk*q;x@U zinvEWoHj-4Zyc!yuyYjc``5C@_miRz2@k-DQ-Zl^gU7A)t*2t9R9H~*srC>rA!D2hrU{-e~%gNbTGnU$zfAY`?K00JthruL{s z9~hc%lNbc1aDqGRnGWnQqFn}kH8PqsE9k@pO#Aadls|Ug1!mSJ1no z1KYhZ`rv7ub-GeR>h^gS*CX}AR97Okkj|*53LvKfm;wJk%DS0VBF@Dbm#v#tr+Sa~ z*vu)(y-E;W=|v(o8|AeSq&=-WfA&hyYG$YzpP4&lo4NB%CK03Hk;?H7wc++wAn)## zkh5|31$6{GL_LeTn@{_~j!AU+wWZJ}CK-j~-wJg1(hp9&7Bg%hwjT5E1YgyzB9pYq zdb8Imz4qHnEZ?r__M*qkwV(c`)BhOGX-79pL@t(MZfw)uN1up9>IHkC@^_}nx0gz898Q{aU0@ucm8wWe$=!0@#dUWU4b`2 z=ECE*dG@N}UPpUSQ+o1-73*?3Cg&%eD=vgVH?{M8pw6k1xk=RoQ+sXlC=&zxO=Z|K zh@os1x7F%uG3-}Xqu)2?rjH$NPNfcRBqEllVM>^Us~}-_N)8jv%lHvRFmp};PB@wu zdPMS--!f&i^~qvqd85*ij|Kx3^W&xxlP_pTMx;Z`nc=}v9FpjIX2Mu;OD(%^kuaB6 z?&@M5)cnOa-U7vqzUq&PvRLPEy$nh3E&Aq$8WPl@w=AXCY?h|i;F+Eu$t1_xK8ZlG ze4JOfew))*xBTAo8f|>$kRT;;Y+xprWZH~LvMD3E+7~tAGN12qT$xaFbpEua?v?y$ z7kNmr=Yx1!CRGgSAp3gC^ zMNlQ{J*WFA##q5dKi7D{V`@TI?8pGOTaO4pgkHA5#m7aPX&t>e*&DGz;OWXbnW9$h z3>^B6LUFB)5s4qe8TRHGu~f4l0BqIVeht$;^!A$+vcZS~Cc8msjx3tcrf|iuue9iI z+?g~S2S91vVje*0T60d5=JzME*u33;p6Jg55c+Er5g(t08#OtLKPzhFYREoahchZl zG-21PGH)pG)cf0rs2svv69iVd3yXkv)A0$`x*zfAeU=kZMUjuIP_`SKm;jt>hJY^z zDqvjf2%45)Eg@5^GCtGLTfS*Wi2aM}4F6hyIenu@q+;jKEHtF1B`x?{9X(6YbNMmXnTGMuyL=yATHxm;NMD#qKdN>qH9`aUb~G zna}?AVG-1>6jLXqd<`{_Z*=86X`I|&kF%I>>`zF5{O#hx8Ek-BHDLUe)%RhVWeU9$0EyW zv~@S`#~WI|>lB*gt{LX7Ev5K9^_v2-?OLD4>>Y>llouPoP{+Hll^VT}#kqtI<@;!^ zq03n^bVkS~uh+A={(EzFyUNaIJUX_b+)3W7?|$>$*H73}JuXvYWPGfx5l%92kA8r! z**AMuLD!Jx=5p_8^68W*7Nan{^{ux5Z`T46TD00guR6gUYt<)q; zK2Oc)`lW68a)F+~zryaGeyC{@uEGlBAK|t37-rI2e zd9KSPnaGP$Mr=Uh${aF`dVF!JncB(DTDxFvDP+Q!IqgB9LX~ZC5j2hTjJ2rp>RM8{ z2-}?RX=1%+M}a2nzIk#He)n0+vBmUvOyShr%IN1|@oY(t*M*v=!AE5to%3d^VVpb4 zr@+1yT_9F;*N?J;1wwZY zlGh@iNY($3G|q*~^8E`Tq1k8|Khjucpfv_QGa(y@%I}Y^d=oyB^?uz$!%*JCfx&>^ zln(B7r3Gl7jzwa+x-7Q}X!&0}To>vm;6nJ`nq_snV4jgXf<_I|wM>!7lxb zt{U;2i^Kht6K&4ruWF<@^d5HxkJtw@gPc#cSzAbO*qGPQ75-=Uq5;aT^Mcp?5 zPMWuLUydI9+&qdTo_Dca5HBSYPd~!V>9y$FbbCUN4Y5vtG-0Y%uC-}S?@i0`11U$R z<pEckDToh0wa$?Z2>6{JA3Akx%4bZumR@6pTC0y#R@QZ`ZZ zyRt-oI55O2W_l89pEEWkRGgPo9GY~3!$>k)HG-z3mqju=W*%6;h(n^5>LxcO^;!J6 z>lPBmxN?e$iCT z{tTxbIg}ESw}r{p;k8+lhg(vRn~R%*j3Jk^!2T9jGo*=ys3;NxlUz$RUY3&m5U#jz zYs1}w+#V{UHjz&o7kHKz$yPZ=h}9R2K(tN+MR8G4N@v*fd~L@u^a5KuST3qH?=Ww zD<{?AVBzYgL$MkTCdyL36fRwT+OQ|#JB^UstOzdD9#kZArM1O9p|iy;N!n~@vssl= z;q~ZfytLNFLm{Znb}>84#y^*8K<_!A%TE#GU~P@*G=|*cI;eKu45LpFZ^KmvSRQoE$K9Ch&MvRKL_v4VpMO}dn4Fw6H0GK7 zOrP-GIL7-Y8W-LddQ&c@#!**MEcnp*lN{1Jfsj1qwz0|qtz6}!!cNLP#Zt49!q@Cr zQfU}eea4uYj^*9SPR88bg1dC6tCeJvl;0kwv*iNTdMOGbQ6JZm&3D#$kg{uM{SLZz zi*@vgaPNlH0=0CSvX=-Rm< z7Cy6DuD+zJe6ra4!F7{7zVfrEFa_q1(B(kAQ$}MO%Z$GLW*!@qQ2E69RG{_RCkqYk zOZw}xqMO#e#sr&lTl&e7uWc$#oj!c24CtwXz8jO+_97-+o6F66kfz|eri)iSRMNlprO|fOIzs(gMQ_h;%C=A>Ae2-673Tf`oKQ zBN()lGy_OC$alE!=Y8Jq`}oaY@MC7K>+Eaqwbxqv93^j`CA6jze1SaAk8dWQzG$e# z2_cG!)z{b$c;-WEz8-5(PSk7=8z7TiU++>|TWf5;=eKvhc(JuE+dw1Uv|q^0JS)A> zda2`o$GVB0NM-+L90l9MhYz)|Rs9D^#o`VF`)Rjlj$`qKV9cxgJfxnZnpyH~P?eL+ ze$qr@XH;piiMja;j%r>!wq-hL8={tVGHfBFwv315#AH>8V(1V5hw|B_f^g8PE}CQy41|SKY3RxquI|SW$rUH@=7v=H z{Pch5{xP@8E&>0LG(sNiHoCd;%#JUaVC7yt&h>Q+W7Y_L!T>#a#Oo}Qz+67syYZzA zgy~P?*0)(t+?`!q$PEnMeEabuys=UAG?Ps{ME13Xi3TNc8;-1F$wg*sEW*x?4$|R} z8GdS|`B9a;;82VBg*Mlyk(kBqS3g6tH^gTwdP*qooF7>4-H5<@#VRs!bnxkZoA6Zi z+Z&URX-P(q!tqIbRs9m!T`BbUOe3SC^BNl)m#%eJK8azy=*^~U$0;vr(_qVOYopzC zdRdzOl9Ur4z?b%=H_H0~C1w3y2H1lf5mnmQsGHv<5Nuvg zxU)>H{`ID) zZ`s7(h{Ui@|32YGE$wbiYT?9iH&^0_H2AN~P>=2RYV(gG_-zLJv zAXtTS5Wm$|C{M}x+cicD#w=p3u1mfXD}|69D1@Oky5!FWh8Fx8%~UwYlE%DM*%6M|Xg=FHI~8Au z7Ic7cU-0WM>|3_fUenp za^Jw~#Bt~I3b(hhFlS$rs}F`al~lk(=?hrq$%P5EUNw1!kptnM>+d%a6&w=6F%};; zB^SOl#JugUANor@wA)NlwVk-?QBnTyPjWIG^=vw&h+%+%k5)`v=TXkCJsq8fO6ann zQQRcM75)}mXh^3ye87C$!RdpP;qfuYd+<=odd8}<#ErTdzuJi98|&l1Wx+p$yvMKr z&PyIiNqOvqs7Qil9?HX93?Z=TH9e7uCl4QAr9j%_oKyo(S`$UCyf?9FYZ!8uJR}hLQShfpM1zAOsrn##B)6} zV8eR;2Thz6ojy$-``rEa9gy7`f(6)U@cd3V4=4n>W%5gw7f=5V`|;uR$M{Qd(kSED z!qEo(UX^U0w%^daeEG5#N}ewfOoJ0A`3-B(FX6Hy-W~jwS4_jMh{mft3{cqNe`Ii8-EJpBBDuu`T>DvDa#n@oAhi=9p|wiKsa zc>9OsWOCugaP)#@6WWt2^G-e=$)xq+2sFuUel49zs!ZpJ>6f22yhrjjO=X=^Jx{g` z_jawabdLhdM!vwo8LUJ)h z2MhXx#^ZytNJ?QVQ_I4Ff{o6<3t``{c_TLtPsF7|pQQTuWt|ERNn7c;TZ5LiuC@@T z3F|ebhoJ*j_Mx!r;_}V0sn-%S;n{V&H))Qv6T5A5KfWR)wC*>Vog13e+4r*VzGw1h zdmJ-s{xvV~x!jM>Kkx5K`_tJrW26X5hS^Fr%xEuX<&t=vpm#C_Fo4S0ImG@+$eVMMF?#XDzMQpU-@~WLD zrPP)G>F+;|H?%t0)0nEXU#k8rglt=I_lnsTYGvO%YiT^@o4txl`8_0T6#mEjUI?8p zgh)-2DCMnf_o|LzaK^$7+SSjXoNn>#h0vuA?){8|w5b-BkhSdxwA877hYFAJ{luEq zsVdB3{ywxlmt~ya_t(i4zne&V&LDNrUDR!DOC9Z1Uhv3S>tSGEZ2b9SX!B58dsJl3b-{b8#v&rFj=N>=3FFpF-L!aI z#hx~&X!O#SEf<$cyb5xH!$llkXXlF2&-A$**s}YtNi=D@PGr_ZFXtvN&miCCTFJY+ z)$=vjaNUXBGwEaU`Z_Pq7{jtJAJ9B1(&-)mk{a%+Dv zupL(onJ|qZv_J|Wf;5c0GB$4i7*f(_Okr-GdxzeQd2{>V%OCAe2IafGv!}*Dj zpKwEIQpEo}=nJB_Yi$3K%+B){B_zP=QJf+uqyQg4lrGRc2@h!VjgckZ#`a0d)^~5t zY>3=KL#k5nJiP8zPv7xSizrIuCE6Ca>4KK;v>RztWYm@cf@831QEbn8*a9^gw zj~@u&H|pO7^DPDIz4S2>q#d4+uAgBKGG!dH7k`HZ2XiVH-e+Oy<;XQoayK6pMdJP7 z7981aS@9krUBo;Tk(4Bav>mcxP;a>%WhnGHXmF*(4Vc&F@>MC+kNOCHtw}1MUnkhe zVx3xV28alBijC{fvgjW5yF~_2w|-*Na;931+wuG+G1wx#;c&1mo<4y4IPQG#H>u8m!mp;?Vm4 zTM5qx;^d@1^&TyB8@1Z~a@kN%@8U%v^?8$!&D)k+%KI<-p>R$Ug-)fX zpwC{so$*47k#h~@(HVWc@1nB)X%&%K(|)7dsxyV@-c!&0B8<}|wWyBaZ0^O2H&Wqt zf2~PZi=y1dady8fv@WZbhl+}Lovv=2&u8qd0A1o3qH)1B-*RDRKQVH-pIw)fI5B*4 zjX!@AH@e(rwB57#<&L>_c63EmGg^c1w))3McRJF#@{L;V?Ou)ve>^N@xF2P((Y!JD zdD&>*f1dS*oWjQa!LIa~-Ptmx{Z;AZ-oTb^@4C;`gWfEHnTebb>Fd3$vpoy_xO6l$l44mnJ+@um9!;unX zts+Pa#JRg-A?%f%(Po!818pAZnkJ^{fd?d);M;i^4$BnQgDRZe<%oi)0k^~~1-#T@ zeA&_f@0Q#AZsFE9iqWhn$;VfYr8VG2igtO$)vGaL22kiT1qDVlTA8aSb>)2@y>H*& zX1EdYnPn~RbdS{+7Sqt~Ee=^U*ll|Dimn7LJJ)@zRigrb?+ncXGS?$SyZ9kfK{v+a z54aR#B-8V+rUQhJL#^y^d{?TREtCbSN3x~Qm@&%_M z+8nYVyiCT}WZ>=gVKiGw5h{-P&H=5{n&w14g;RO2#LSp52S=GzGdYQi9-r7>9$Try zB)5zDzPQl2RuK~1Ku|4;eM6n;k%DTz&C6bTvwr`(DW{yj2GYgAnc)WW1_NkfKT@sSzABYUu@PiWcgld7u(6`g?Xd%W6Z9XPMnwRwWi2cis zoAAsKS6FGH-W=o7BjtHBl2tU^5R?<_;7rgj;ZrOCS6*HOU}H8+7Lt9o^vr$5MDmyn8Sx|4jkAI5Z><|JkvM=8)SCsTqe z9xrJY1tb~dPWX!fyVGX~=Ot)rV!sMCtt$??V_y05 zO&9Q?n7Z5A)D(+ZmrpW7wNH-k}QyDYfg0pb# zWnUS970kDJnRZu^VkOQynv)#gJeDyho=H4mezMS&7R`HO0{^M|Z^P*$2_&Yd58Z^H-sn@N&}jt->*d`29p$$HP&s^e=gK z_cIAWa{ymkKRF@n9UP40+_pqS92okk7Q)y_@m>;>ao?L#!<_vsd318}`|qVMbo-Gq zXVNf!e2_b&>r@u&06!2#-RGc{%Z5A-kU;u*UtK$E4YWx8i_bg0efxkMVcLBJ&5A^O zmdHQA^}vlAg6(dM=lLAj$3l>}n2;+cA;(@4uEoMWLd24vIgp)w+;92N+X}Y2R7`%+gd zOBM`7RuCiZ5zV@xWz!RB8si}XsCWIpu8fT(dS(ltas6|bI*CT|_ol|{u!EkU4S=0A zSS&{4Aakn8Ll$5&B*hL+c&}IgNP+bez1S%tcL;pA;Lnz3JyaNvlV9_CplSdbzr6qX z@+sH!=vY%Z8nI>9{;H44!LogK6F^lFaBMTbHnxbWOXOWxdc#U zhdnx=e|^~JQ1H$Bx8UdHN}{DMA(f`b%(~PZ220Glt-6XqYxuuvuMTL+x(Mmx#3(; zbu}-@7I*gkCGhvYo_ph2Ieg#G8N z)dha)-}EQWzj*cCG!~N+k~U2tjg&V|pu|ZmP?aSxOPns&GvLvZk+|4^zUsF7&1Q~N zc!i$tU5Loxuv(YTl?0Dl2wsy#RnN!wBvm0L-nrPWe&=Qh%7u`QpicjwFlRmrGz*gJ zu0QHjF<`EU{MscE>>etnu89uF9Vazx`?mZFRgbd|EkP`|LmRsH+i^AQl&}Dj5VObpcxqS11ieyD}p9?akdSv>7 zgU>HU2L|p4Q|eo>pfw_Ac{-x0iVi(iK0Lv0LUu$q4Fu0y!??FCUm<3u|Hlika6eLB) z7TN$WId+1J_zG8ZS~!}RbTzjzWr4h=C|-ZJEdxaBU-)2dbl1}#ikDhG<5=26q&e`q zX7R54DpH4F=1zvnbfOSt$Gy<(FgP@*x0m|jl8!Y)#l<1sH!6f#7R@yFeZvp9wolS$ z$eez*2kQ0NL_-@E1dM?Eye03*XP>!nS^Sp0cYOTz9m&HysD`}1e3Hl1$F%;{ceYs+ z<8Sx~W;L;B*dcK4&p*G#%9p|!vQ*NjVE019sMyS^?1WMv?-PD>O%zo27G@9e;6gbE zc(#vA@i@=JLRO8W@YhiqJEmv|5g>CdgmGx?p@VJjizxsDVCo_Ww@JkDSQW6l-z?7r$J?8zy zTDm2e?%x5g;jdpCAxPVUvIgW2?xYt*>4;hs{F%4+q4c|rKZYt|DSVI@q{cYLorbWY z{{6#Z@sy^;4B^*59jHN?80zfAP=4bfiH0Fm1bf+}KTKD`5APBq{*;|DcQQssdxM_9le{834V zwef+*SPBc8@z!ZH4IZ1nupg(kwzR9@>~;21-=(?=4vov?w}_5m)9CFcNZd3BoX>2Z zrds6kF=#QQik@i;z19KWHke#4RbZg z4-Tbp=9as6vBbHiZ5Xk!PcZz1w%O3z28xn2C*u#4EWmE$zJ7zsFO6fNXXMyZtA{kU zgiID5*%T0PfeFL~TQ>Q!fxZhUD@onpxwmG4Hz z{0FZre~PEnya_+6ExqOD>$t!IjyG{`YkL9+4|r6yP~X7w0d*e+!pfbQI(!NPr?~$v z^rkXX5*-Rm9^O>b z@w(fhf6DR}7$%ToP!h{9*?i4FT)7}GgmU6?nK!0b?Cb5VedFMs!%+2Tdb*$-xz;H$ zhX?bk3?9SZ0ne1`^XIW&i);u>6<=nQdd%idkG0}H#@K;$^5}?Vp+SV_qQ$ZzD@xO; z)*FgYSZ{X?&%UxSYmnEbki$qt$8h($&b$hVT_2tVYF~PT04&@y?6k;sqOY zYYj?gW_F@KpQgu@o|@iQi^ZS8myUf;#kM?YV{P3vJRIr5T&gIhH|6agJLkblxs9*mM$i>-7@f(rl7g#mLV6kFcB_$nG!T-tsZf=`TCD*d$*O;AtktW zeb1e`4HOEA0+IxeUyAo1;%sZw7oGV}*jAi}vmNZeRc;P={(ATlq_p_(|E=UUMEHWx zIXvjH)m)r0Q;%j`NPH$_!0JT@U_?I17t9RPOk93#GrYHj-m9qGh2XF>UHO^j&$VNK z@BwR*tHJhJ%8BIA+*tT~tMPbAqS3blDR~GquJs$*b$~?q%Q`9?qPuw-Y_Y>E#Dmyctw3AlE6T4QI!5 ziNtSk^VoMhMS1J6RB*gkS-$rd3??*|iBGdhTb3Q~FJz)S% z{z(8H3&!(5@>*IX|1hH-4-{f(nMGa0(Z&643^7})G8DnBdb#}M-f)NwUy7@mZjOn) z0YjY32MrmPgh!rsRylF0U29rS+$Hy$0-*0oW%M<3_#h-$0OUJ*cu+w=1ao+mv^;kv z5pMPTUkVfyfBLMix#{}Sba~@nN!N*_9Qe~zwKK(?7bY$Iq%})a$rvIJ1{SLTpWFb| z!GZoPeSZ84zt3TIG;`ZKswR4z2$oR6gthTT>AZli-LZJYhA*e4u0YmPHVd}4&Yv}c znJsQ%sfAO1@F!?lM3E(djXWZ>$F$(iTN9~3*iXO3-8fYl3y}71*)<4{sHpG!{3k16 zaIC0lsh!Uur9ejBo0p)nKQ6jO_FG`WdPfP*UX7&ki~q9UVVkpZwbYlygm> zqwjzPa{B%<-OYm({daffL9~Hc{^zEGI11Pbd*?T_ozWPd+?qD%lS-dj{laV6Xc_;! zcEr>|@bG6?afto(i6*t-_kfr-sTgO&X{$Wp`}ixYCU8jV%3F1KBcb!q zGH63<@M1yZ;kSs%sZFDZ*m{6f)?e_&og}P8E9OD2yyg~eNuZbv4*|HPYDx)5b=XD z7Dc&G?47f(#Uty_!=YAEt1n&D$a1_MmsOh3i!` z{maIip7E5-Xri_g&JUL_bS3pHOd70W%w_pd5yKryp*Dbz*hv)m>t5;yH=%#OECOhw z5A8P&H7^yUbDEO!Nr@?U0}<}^4OLEW6cEv2Ikz;_?-|YS)5N8GNr3*$-eviqF&14T zh=Bdr{^`>YFAix086sk!-&vjJjEvnIyS`8Q6%ysF6)lXa#w+^~ST5$?;qaRD z?9mdW!gu^WQVq=)WbE>V*(K^}P?(R}pz;V{D!4fRV7)_duaz-{$ro-^<5{7c_#jXC zp%*?+lIZ(JvBjmrq9hrh3zlpbhVeq<= zaMD&RdRIauIxhS8^UbVM3o@_w2$R-xa@J*1Tlc z&7yaSFEJVhVRPBkS-rl#?;gISif=ouuBk}}RX1BV5BU)56$G~`#-{#zYlkvo^Htuv zL_CINNl3@Em7R;Pg*s@1LS@Yj=`?dknw%wjtre~%+`L2o1cl9f2ju%HI{$d&Gg&bo zDL>R#Ha+f)ucpT+uE?mUJD0?|I@rpjXwH7;_@ZKD{60$`e^X%s)!Rsj6-Jkff z8xzYDPq5g<7dGK5!JWioyUwNX!HR*xOwA;!AM~+hRQ%ATrz@uX7UPU%Kl95yjxI2} zMho-!t)W>FtY(_{jx0Hdwa$MY*+L>8pUujr1DRT}MEQYJsNg?tAg`?0bw4 zCgfJ;a=1R8#7M0Y^*$~$isB!YAfdaQ>O-H*^z@?R`fP=1wvX+#=lyWM=-JILnj4I5 zmv3Re6E6trvyu4IXgo58vZ=Ync;(Xk346*OfjV3H!|LE}!{gf`fyZYViZKaD~ zlb(9(R1=!fenp(^`;uecXLA#Br8Rd3l9?`I5aiTCdSfu}bEn5NuAGYqw;h)n`#D-C z1oJq^;sk3GR!P0;y>du1Rk!uXgpOg!pL?!Aq+JlPvK}}dU1P+9@$ES?Nkz}9H{`cW zC}$=!>Qh4lQD7hrL`FO;Lg_>#te`dx>9X>Hb*@&V9@_$GVzmw}fUyH^W)+>7K}v37 zcT<<{4s4*yyoneXnl8T6)74bz-dp@y)h1vg{X(+xwIb_aNPpzXQ8{acn|Y}|MBjeq z=(2S(L{+|$K#mRdsiK1B=g*(1Sy_)nQ&1gn*~>Vfex>sbQvJwng2yf2caBS|`BMdm zO)9DyTjbqbqXZ7eOgVo()QUuvdU7Qbo>6%Doo|S^k&zJ~{4Q>M&o@UD$nYGoWKj22 zsbtyrqux<&7wZ+TgQ__hchPF;Okcs1Bg3pwh<+hoQ5tVKe5uH^*6FHk)dJ^GLUUvf z;arVF>7#<2<)XDn;g(R@(PkEvES#}iKImRlNaNYeEUYvXw9PZQ_oee??3Hz1kQJZq zt3fPe?42wBM4}(;=?Io7wMwC#jj$(dtjpB1^f;Jac8(Ns{vQ1&i6K+~PC+{BPF0-1 z5mP%2?bnZOKmW!C{+wC+Zo;#ZhW4mFI$vr#ujPkeAQf-cdD7q&XbT=LoIUe8`II9s zmD5)&ef?TMSQw{L^mxx~>LMyXRi%E3&JNWXG(@xAxU1uKeT|g~AufB9e4y8*D_0fOqO_ zLKMjoU)o`-NuL%rsA+6snhss;8-f=ymJN{{KdNcNRb)y~?zMfIB-d-6=K?<#3EBy< zsmR}0KBr+FuN7e#pFv3b4u^!HG{3L##9bRx$h{DxT+KZArZtv1s80{Wn$KGk0NAUb zpC^ch6}t(oBT1)C9_f>Kzrd6NUD$TJ`^%TJ0MYSAdsfHHyj+F9T?XFQc<O7_9V_`Sa@&fpQm;&}=O&!2-A=Qtv6=*`x&Dw}|`0gk^)P-u*s8 zh2`#;&$Z*CBMB1VwY)i+&Y93#l=ZbxhhS`fVih(fs)dj|aBfVDg$be*5$o(Fe6Hr^ z4}b=1{>_Y3gS3v$XB{>TeR(fOHmN`?sS)y)nO)^>e(>g1hcF9BW=+Y7%nk>2jiip& zdC6l$uzZQ#PXZ%OVy&+n@y@zqt~`AN0k{18_z>-Vj!J2#H1`UTUqL!)EXK_hY$Xqs zh4!yQ;rai@)Hsz^(X9@D)7aKD$6=ja!!!)dby*=LT$;V={bM@AG-+-oD-Wlj2-dcHne>010+O+`tgyBTi!bhzY5vcstd2hz8PC z%-0h*Mdp$P(j}3ZmQ!1h>+pUZ9UMS1i@7G+1}^n6g+y}{YZ{TU15&{~HWcXrKRNeY zUC#&U5D3QvMAAD?zGzCx(Xw)is$w6MY1c7ANb#^H`wU#??m(uh^B*?MH$88vQ4$hW z!(`#tT&7O6Wz%ZhY+!N5DixlKT{2}pq&i85x$mSauimzKdb z#g#4`>5=66{|$gTM)WWM%?bDT5yP|?EH05xi-!^-97O_I+W-8{gWB`C=70^u>FFPw z3@z=`SLhxqt=L~trto+V*(|`)*39Tn5B9N@3_FEWBObG3X{-vD&3jl)3tp3A{SAXV zV7nJ%B2~2$(BGBXd0D@NdvnPgUR_&4vqnCD8f3~i`;*0s9KF6ZWd1jFm<6EypZ}b5sK6o&yY6b2+)XF4zCEb^NKCw?Z1d$i3@Ey^s<1VXOT3Y^f|g z&Imj6fzSP_>q}XQ`eBUb>kpMj1V&Rk<~4dhMMryL4Cg{u!q~kI_&ps)@BIVPivo-r zYL<fENAQTswb}R97Yhb?$j9N|`u0C6-Uz z)4-WGM=4yRR4m9aTQ&n?;2m_k-BmMjNETt#QVXg)T`?LQhGnRcRHi5TJkEYYxD0+A zE#ri!#5;SS{T9ivR@l(MZLeL1c#8KP!^O*+mPGKV&vM-E8B#X|A6^wMFjxlFDAMae zk>y;N*YN2yti_%4XgY4DoM4v}zuO;`ZxEW?3M_p138|npx{y)3dVEi?jC6EC9oWqJ ztq@pO2N)@CbdcF~J3jeJV41MCR;D^Rth}=kXeV1&02;p)_5hPbJ-9*nLOMk9tPj|o z%Ac!7HupU{c0@wY`sg0Av|r3xYbOkjKrP~_Z!RnbN~>QC2RW&+Yy!NkI{*;IKeXU@ zc7buj&aZ|9Kid{skBvuO8&B!bA-7!7=c|JuW*z&z6-M<%wFR+&Vs*$sFoDM}b+jVO zYEQSjj`QXX8dGlxg{Y}J>U~AucUrKwtYE!;A?)(tR6;C*vTq{wCEyVPjD;a*7B{$m zSL$!jAq#Nf_FIJW6?Ba#SZSRA5DknH$&b4j zpRcAEuoY#z{nFphqr{Lh`DQ8xo~%s99w^&qRE-GUJ z+t1xy2ihdh#~gDa^A_Y-JdDL~UuJq^gDpKHW9}tPhAS1bUUiR^|(pmsQupE#D|HC)JK4vJ1 zMhCv&Eb_3Up1%?JyVKd0`<; zm}(_xT;wj1bkvg%ADP}zyK{>PCd*1u$_WVxtzAH}C6n?Et28O9(^7iUClO`Z%Zr_z z$ggiwQ+i5hcDD6{^tlwIs%i}7PniDkO2_J~04(d;8a`Y$9CR0n;)VRd5=FTql$ImY zb#~ieuZNNkp+7_ro$Q9i*&bB$r)~E~#CJWrN^KcDe*pdR$p;xc5G&cjs~W6ns-zbL z39jmAO%mARa_7YE1aT_@(~`WpvQ)|MO2n#=Hlhk9EyQ0!OT;LPr-@qyrNZk zhVlu^=97qhF-gfC@hY*f%sQAn)ruhA2}y-3_A4n8kiyXXzPm>qK=B@@l`yV;plgdJ z)u?hW*h4k20*{zNG_}JzS#IE_n+S8s+CAb05|Tx_OU|i@iRh-Lrf~N{Wv}~LI*_*5 zyY_r(zx146GwjDyd5l#slVK$WOhBMo$5SooNM^zV6wXx`d;``E=iF~?_I!NaGUyQ% zFsRBjfQ3k?IWkN7@>IF%DjW0+5I~C3XQADy%a#8n4POJI=C%Zxga^#!{i7WFf)4+N z!9!}{_k<8+yyD@pM_7PK$<{M8rp?Vu1H8IKX8dTTDVRgGiKShp+n7j%q<~($H#nxWt;gv-(vBr)E&0KTum9 zP>IQ1Gwz{ z{P=bCog#}?0slj73V<_}-CL$Eg^cW0D_kor315$8!x<&HN@niG{vrvNtIUP|0JMPG zngC%uFI~ryP8@pDM+_D5F*PyxK2%8*_p+o_%@xS44B$pY4nsLHRK8 zhZ>>u!Ob5)2BWOdvzQv`O9(p9_wacVnEHHm^3jttSxc)WO_Y$Fn#p52@Kc{ zzk@LTk&yuB@wEB{4@?>={>cPDG++khP5!c~CUzt)RpZ>~=M$80ssJfx8T~ShEt?MI zNeg4*qHmedbhexhQiLcg@ymL~kGg(-&CBw0*(qW9Y66aUQO7t=#31*fp=5da*wn+) z%F+@j^ob_YhRAPvq~=zpmVwbJ&poL1Qut(}abT*$<+zCq7>SylPCka`;R@Ox6cIUP zOM+~ODt#^t$ZIIYE?GwaxD~WH);jSAhG*#te?OsNWisNy!Y1O=-w({p%*3g(0Bd(R zFhD%{usHurP&3&bQNfHw9^g{`tbvM$^2V&Qkmr-l*UCyk+bAw@-c30RnLFJ*|3Rdt z8Xg4n=&x*TE6-Fp@aHeH7)z~vZ_T_qcHSzTVHPixZu|% zk5!=^8LsM;ZB2A~4S%U2_Nz&D4qN*r_f1o$untR{o=;EmksYn8iJ1>Lklx`{%~SHN z@uOir+c>^W#S_B3++yo5v+w}y*FJ-?k|Z_ClDVrC29t{DZUMW8CX~$KXhXARw6U0?uE{ipfE+H1Vb+LIWlNj@DkG$zaOd)k(53o z)75DR|3MTw0Q?DJg{5#l=};n#GA6Loy4jnWv8VMEr2P2(vU0NPWOiS{j-ghGI)6nr z3TQnh$JM0F4IkjrMf5=Y%1?ALz3^4y%3Pug)k8__B$@I+f z4R}pH)6GYz#bewaqpf{y^G_9r-0H(^zySI``fz_+=L_95&BvX#^Y}icaBJCsd$~ly zq42kZPt3Q69$OQKwCAcDER>)(%kQWF?s0prIfL_Fuw)V4N&&j+eqN=Wx#0^_eNJ-5 zvH>!zRygv78pK?dJ*3Hz13#8G=xfD4jC^BVex6|-X`&P}UxNufC3DH3k;LX7!-(I% zi!s)<>#!9B{8g~wd`V9IqZK6-arnGq9eTtiiJ)?-7TpeZJ&}?l!xjsZ(Q255bxc%9 z_eImpeg1p#?9>Ms!Ij?hLUN0(B*7z+Gw!&hvt9ygpscTaj#X+@Xa>Gm1#`>+5-%YQ zQZnV)*zn`tH+6CI_|iU%t}W>@&5WVqzEVFelPzR_25xV0A1`qsmE+cWPgU&5pwwWP`pBymE1_ z0Qz!8f)W|qPo)-ojQpoJfoN~Ctj6H%Dix^v68DW@4hDFn~f zMDE59FopNzWiS;dc=b<=D{UW*gol~e(5DW2jv$n_Fkcz-t&ybOI6#hP2aDRmCKA#E z##$W3!PEtCunHZ29Yj(7#{lsEFYtF*;G8*q&HTI+sG%7W_i#$Cx+2kgdE>}afOif5 zJm`r(XD2Q$&R_UxkK6(IWsM!+qE8vHWvJF-$o>`d3XL8@6pah~+pSVsyW?0nr>_YeqzYY)8szo;1Wn zqf;(`T4l@J5#JAUJ_)O>%b0mSLMb+~YQXGMnVu5TbNK3nIc4ZKuyFkm)v=hPuae=B zDZop_LbDb#&FKV@sHvk9^8I^v1Wal04`aL+?zf`&^NI{$AM!HP$kH>|7;5GwptAml z;TA|QT2EnO)l;)Zr2-!l(r*Oqm9KQk%SVH|_zA+-#60*3)n?jUDRbe#rJ`x-xoDtc z(L2@lu@P(WukrLPBPr?luNlDN9xwx-H;X=}y!O3;Qj72LM90uPJAZL!zX>yW{oqye z)w9~RGaAIc2`Ka8HFiAO+LrLQQ&C7;I0Y^KLHs}7X&zqQ=gH_8q5c$5;xt9PtZ=T+ zi#=07JAREyhKi8YahJmJO5x!Gcd++zc<~_dV!YAr1MA`%P%_|mR7|QukBiK~Fa6^8qh`5X()ZX7w zi5>z18)$x<=(;){rI|5(szkb#bdGI@Uy%6^O!a8r6Hy!IfGiYD_o&8TKu236c$;Mn z^GB8ik>fKtH;J)Zo3LB>*e7pJ6CN<6`za=Q_1*kp%6R*J zIgwXbSV0@(F$QX2JK|P_^;r8Cr`?*kkawF2ueXhOFOE<1KS)OP{t;r*E+E#cCm5+F zVN)ZsKk8t!WJ&p5dupR#?VRHv4e)v0qrZffU^f#ovNsHamY+l}w?7eze5ygdO?y9A z*@QxMAmwC;EQzr!x)#Nxxq*E5`Q~qqvirT`Ukf*KxfC*lU%sOS2XJ+;Bq%YK>X~%J z-VJ@4^`Nh%TyHWEDDL?RG4X{xXz%vIRCm|{TS_<{Jy`q_k=Le4k%^a{W>bG}dD%?F z%k6!wivYpJPbEgJ3PZyCmj^AyRv5v-cOUPeZ;bN~v`okuPI`TfV)wH-{bTePvK`O@ zS*kN74GU>W0dG+Vi{tDJWiJQ4eO|m9n+IBuzinV(h1)8JIEG!H-}t-6NHCSQ&8!US ze}5a~kOEDO)n1dC7S^dHo8*>|Kw?X!nn-akOj{I$&`A&6L*HnDMLQenN@X;m=X0pfwc#Xq@c8-p zORB1HWN?_n{5&+nUi%ybmas`}eH?WMd}*RGGw_|p`(l(p{ABNV%8nP1`n~ieb^)Y(WZQo`w^HQCUwfnNk;OO1P^TjP!YxuW(>t}= zxBG(IFM_b2vuu8{aPXhB`Py|;~zaKwG*-Wz1)K2h2saKp15jcc$e)KY& zkE8L77q3^|iJE_k0!|DTwb}U6wgmrv)v+kP_VTU-r~`g(*;{j;GpcG;mZx`P&(8}> zXbQz_4R4bR;AsZdb-q*$UZo>#x3_-12l3^7dBM?UKN&;`zkc>r75H<2kyG6vUMVVJ znu5|Es_GLK0)hSzV>iauZ09Ter)S&=%vk^-0V*TYM`(LxsF58~Z)_NRCm^vREPT+e z@nD0?y%>{#`-QNsr=Vsz@cs@I#A~u{@a}&kKwKod8X#AmCQl8-8?!Bh$o*J`ucc6B z< z@!7@Gl08^V$zEH>idC0Bsw_)i92x~z0r3l8VJEqSaAJD3^o6lQ8~Lpb$lOVY&*81~ z+zhbehgdU+vUt)GRarRJUH8{I+1hbv^UOoC|%Fcx4>9pdHl7L}2Ncne6m|B!-6?B*;HsgMQz z=KEzMFQc4Hu`&mi!5B1!_k$tf7ScZ7LmKM#8xn}$3utthnS3NI+cLmVh9zLQ0IB9~ z(!gf_cDr=0e?>c=D~qHpCTaYWW>LZ%B%Pb-48O8W$F zNWqNDfRx@~LGih)mY;OVmkBK6f@py>)e9CkR6+lM_9h?JSDp-`?Qrkg(UAbG6y8IyHO#G-0#&m0@EBCf zsldjiOnl$ZbdWZ|EgyyMb(kGkYVGX&W2MWoDE;+20Of2zV2s~S0^TcY19F!#Niezo ztHG`h7=03HH}*%{&`bA?K3q4xS&XE1yt!i9J~04sp?x}PHf`Z{;2QGHt<&hkd63<) z(a{(6?>Da8ogYeTZWj7RJ7-+~K92U?2@-KTdcVFqVRrn>CrV2^g+r1KFi9w7Y!}Bt z*1fFuKRvVC4-5~#qjBnGe+2R+!cVo!78pVjNbMQ$7D31UNIe1r>Q92K6_IJLIQBFy%>=^K)1&)0Koy$Qg&H@oz0NA3i|Zra zFB9u70`7ZobkTxD=;6pEtqX95RWwv4%upcO83sbYzSLg9frgGv^pwpV&qce-v11Ut zU9k5J=%HEAFdrpS7Q^KJe zcw1Cd)zsJ#cEJ_+B{!)N3t+SZOt;^Q=uy=A+`{hdvxO|^-`|2w_5&XrpHO!VS)$K3 zQjI%MO$_H2BktT@pCjCoNfc~^MZfJQwqbFb%P_r%xmPYpg(37$2Liu<_)>ruMk@OZ2s)?DqyY! zXi2s+$(-NFSu`~iUF@8Gly!Ys49NW=qN@=e1_16()c+XE_L&nNP$cmwqQ!u?+MMF$jG+k|WsFdVUl5s*&D;&L?+v?4H@@Gy>tXt-+8bF`?;G#2B zvmC>{)E6u3@^UqcIUDo;hpD%Ws;X<-hBvKJQj!AFEz%uIcXue=-HlCmr*tFT-HmjE z)TX=hn|QtVGrlqSC)=@EYtFNdIOAmmj9Lk?j8A?Ii|*vDa}kR{l^2Kk9HYk80w6PV zo`xAG@jr0y#?YOk)>NWu+J#si+IgG0yG(^!nj|SOZT1@vzRBrv@XL+Z zPAmb|2or|wnhHzb_$4F@M@Lrgtn5e4pqR>!B$8lcbMwBMZ*A@1b+`8KNf z@nDpqw43Y#{zfEaAIxfx95zj%SWM9x7wGBiqY(2W*CADg&>BuqfgPY!IKxx`*7G6E zW5Glo34cO?;{N_VoL?XbmO^q+VFVS@lYXf%oAm#9?2+FWAv7?yVa<&GsBvj;N>G*?gw^w*|Ze7~56~MmL zSWdD#mCW)8-9S3N_4R^5Bi0SwwEi&TCMMTk6B9Ezra-f|$<<22v{#{0vrP`?HY9#Y zUX`)>a>SKX3F;|A=-y5&5d;}IoE5GIy6x^M*ZN-x3J6QT&a4~FTk(^(@mdC9o z8KPVqq&vucF>e@nqey4g-@wVheE`~I(3X}vmeCxEz3V}7nFoM3FqFvKOBgx^jg^0o z)CPM=RQxN%70|#MvEY{%Fg(1w4}FawVY1o-?{$uOPBcJe8*l&$>fom3vXR73ecFvA z7~5`WaAdPY=xD^udct(8)E1$#Sv@ePFF_YCA}w8*v@WSRpj!CcVcW?>I5F4ebF!R4 z7|GYDfepL$UJTH_GX!wInkB@7kn%nPuvWB8qjh0{2v{^o#eRMkFCUR9wQ`b^%h<(@ zNY{oNyO{t+{7?;}FjWgl*>+_>NbZHkr#%;Hyiuc+L}QLi7fYeYO-k>EGp<{>tE$yt z_-;@pagq26p;^U`C8{ShZB2tg4mN6g;)jPn%R_UHPreJ5| z<_6mM?_JfOC~3`SP{Wayh~1S@M!YB0xa3EM9{n9*H;#onry3yxJREJ@cU*FOH#nrP zJ}``b*YM`uOjNqM_uX&L@eKX(7VTN94O%R8_=EePk6XRagM8Qpa*kl+GJtF!rOC5 zeHJ6WMBWtUT1IG$I!~+0#1eRH#TIi@N>T#r_rJ3cY){@GRFa;~MahP+Dso$}u**TK zaH~1@W)xw3Wj=++$=&BY_lvpazTF#Y4$#Kl{y|6Tf?ca>*=H}bp$81n8f_C)YSL#x z008)eO(69K(GM6~A4xeOHY4$f3@G)*4NyagVZJo}D~J(Zq&B_=+7`2>u&beAgWMh% z2U2`ruYCW#-|%%7xumdd6?<`?pN&#|@1^MN8!p?1=SECY7<%^-RW85Phzh0^^snGv z3-hE z#xF+|_4HX#yTgdmM6TaKm=1{sN(e99$Rr(v?X=_b{?cyd0{$9UIS=@%8j;DpmLrFa zSnNFz>le5!J^zicyJu$NZ!ZfO@Wj!E*lNOXk8~w7=es?0s5TBUH5((l6 zP(>G7^kM&#IpgFMwA!?IXusyrX~ZatAWKeA(QhC2q`nNCY6I z_s>r^5s%ysJfc^3P4pLVtRpqNPD^U@^~yr(k!E!}|8e;y!sbNQdF_c7qe>g~d;S}) zo<#N23>=h#;2Lt;GoUcQ3{qhSyqCwSCR@wJ~5qi`nRtVbY^=^9BOEw20A2 zQXgvw5NNux5@TOg34&MjW%Ed!J-gv6nhrL z!XnnOj>w=44-p9+!d!t{6-$Pc4*L`S6}2eZvmbpjAB_0y+FLbSrepVr;BL0f^=P{7 zi7rpS1!!Izh>oJ`L5`hRlqDUOL_`Gq=?BApid?jhps(o9_oqd{RK#R?Iqw4%Ez4a` zsVoePhyE@&DY6$vhq)7;Kq#IE%9adT=YrHGa|b}4m=nC1gz3AQ=D|vOJ?`1YH~%D+ zcl;-fnl#9xW6$v{-EH4d_E#4B;b%x4H5aRYr#R7c^&$TD&k&c-V=?vNZ!hkgDL#^M zLs_nUZ^55F5N$&XHbgIl-SKAcUFb3x- z<$5p``SvWS#uq(Kb5mc?AKu@(xo0CMz+VFn187z`t)(Zzezu3E4L`&~a%SRA2stl4 zxm}q*l_4HDNsUHrcnRxVlLR9)$N4s&e2h#JR>9Va|M(AmST%lTBV_5(X(UlGN#Fni zcMk&Tu&85(a>1OjwRoT!kfnUXXr_ymuf4~L2xlup@kWWdHzCnD{Q`4chSCZ3ehioKP7M8G1Y~q#4Hi`|`p_ z(8r7`LU00ps-%5r`WY~nVv-@rV9qTq$U1oeTj*JHJ#-TF!g#LqZ4>s8kOsBx3u z7gb4V@N z;#K%g^F4$|L$)WlAULU+r0Et^q&L^^*hey+$NJ>MD5fJDYeh{<1AB~%y;)hr`*#U4 z^IE~{wR!g#k}kiJq1raIA9ttH*8cuj{$A?qoy|L=nd$nilwWCfI(UmQOA-aaKhSn4wMA1p(%HAahTlrc8T+b4_O|n#OfCUxWe}KMGze0?Y5mV; z;Xl=EJFsx*3(oThm7+eCUdc!_6&$$>qfz}U(N8e>n~l5Q{nfW7l^sdhT$q!zH0f+I z@JwFsP)pSVK~rnWavlEfm|QhA9&o#HvVn;L1OhZnT95NP32#5mSl?dkOQjQzr|#BA z=o5;YxL^;js~n*^4&jYhx1K2*7qx7_lyx!w?^Pp0I$CZ??v7aB!vFu6OcZ-Ald9@b zFq}Nj^5p^c(E%_*)>PfE`8}ffjHM?ktoF?~k`O*_O4A^2^<81eVvOg<4)J}O^;z{vP=9d&(@r)*c z3&6oANhJ$TTG1`^^S+E)#7SyqWQ~dvM*dj4n-K3m1?$KE$h29K4jHL&T9G=y>JPAz z07FvkoGJ$TJ8{wCy^+thcB4@wMt&jnY*-pZMW`72v)Xh@*?uL}Q-F#1KwC%}F%Dve|*s&}qDJ^GnYcc&6hUQ6dO@dpecsrApClkd(> z#}}KXiW4!;$!|0idlZ~=^4s3&J#kmaX|)TE(w>DI(INa9spx%&RhKTE5WU&NT
z2xR{*rdqf+hM3>7RY+NsS#<~c>;ab|n3CN+?3WY*t^TJM@d@TG?`pEMCtY)BF?Auw zMj6@B)m@S4D&r50W3r9NUu-nqV;E->Ms0>`)QbL{ zwf!!WmYbQ*dH78e(vE8?JLF^v1^drz6o)I#{TS$+$CQON|HlOw*cBJSrggaEX-v~$ z`T@M_ROqT`SW$m=_}+zm&&T2GmeZ(tJiBh86MJP@hac#BlKaf$T^e$+XRophh7E+5ht>!qK zMV9Vs-gF-Cy_+&*jUE`%hpwB>!K>i1k1w4n%vdg|d?q-2Vg~~S_0O)=_;|eO65*OB z>9fQClDfrjLI~ga);-?+i9Tsc>ihaC;%y$J0YfyCf#*c7v4$2X@kw0%se&!yL{304 z;?Yh2!X+s3$?N1!b)P^Pr|j*k#(V-lAA{s!1h*FCg~2F&gXFwins2&()1W?&`5iN4 zQf6;R0%YA$lNKz1{#2fCpOR7->~DzjFfJ>4+OJ}{7e)=g@Q9m#^{-jqb7 zC{$a0bt@dA|Kd}X5{Ca4J`iaGXES9SKP%eYUKl$VApz&0lY42Z=gd}N1^nYEa?hj| zVGELipMC9cSxU%}xqbd++-dCl-3nVl-NF98qiN#3LNJS@9O4w#x4yf`8W}%Z;XZ9W zK^9A8YFn7obdDtRs9WI#s-6)xA!OMyM`vKNl9Q98^E-wvMCO&(sWdelooVlc5A#TC z-?a2UUWo871v}f!lO}weXIq@pcQSA$m;c63s{Pn|)s9fPClfkNepVpO2-*Jib^!%i zM)GO)Z_i6!4%A#5gi!WUajOn#y8~5UU3QXx$QZGU=hfdIi$Qi7{TmKkyG0c!|Bx|8 z_8CSR-Jon3h|{)~pPNDQw6Y3pLVhO~_!9`^50{1w6fdj2SRVv6EG<1k8C*ZfuqDyYZ*v0g^1EcQz!`qlmuKd(FP zBOxkM^(YD_H|7GP+)5x^+>M0P*Kwo}nP!+oA-PdeQNhw1swxMl{OZc%H>ip%U|j{> z2u|g6!3s$faLZ6%I;#cp2;f>3iG0{-WFn7P$@)C3tSL1$wR?2*O=P01k9A7mXga@C zwi3ke{jZM{{7latGzy+Ov`RAnQlX2?AuGtSzJ}rS*%qNv#&9=7cvd0>-+3v4RQc&e z;;s%8l&Vg}u_Ph)cmHyi%tB&39FrYVB|yH;=u`yia!d!MP#}G!u2ChI3|+R2$zm&|p;u}0jFzB)3{u;o z0{0ZH`CBf%-?U~-pD!fVb*y2%4DELBECs5z%pHWd?9_|dxDQQHKYnUY>4#br>?jb! zIuYfPoh!RqFR_wVPYcufu{g@6eC|o#pPj`A_H*Y&vHvWMUVQ)<`9E&-&mT_~M_ZM6 zzmrgYb~d+;OP)QCHH4=iuCfg4ep|^#Z$0ZuyB(0kjGO~Q4hMbc0gTD zXA}|5sH}f*@-aMMol94te*~-0mJn}7{)GkHDy_Dk7iIz-1TT80`&JWBpFw+j!R$Od3Z`v z8cPyXi}2hSzhzylRj;$HW28hOq_PoF$3*aw-?DoXzCykztwYWotC`ku5F?KrQAZzy z$QeMF=2NWdS>i6g)XBJ0hu9gGNn(e^K0T3++HwKV1xRhhkO=#COHOVW#!XXo}tX_t|GS=z?>46phGGV_VV{}{1YT>bR*BK87A`|h(dY@h?1Gj~u~ zNm?d8?$e%tT1BvNlh!h^@3||eMV=U#cY^XAVkc<&)&w&_B14Crl%;xl+o}69xtM1f zyXQ}XI2G0gpstBNiN(t?Cy$Pp1G~t?#Kf`=rl+R91F*2Vn&Wchzj9z55F>z}9n13u zUHdM}s;DZOsH{fZS>P)f*{33^g^UwS3JZ1>Neo6=NX7j8Kc<5!LpqYAsP2_%ORAB= zOUj=wV+oM9V2pCcs{UUgl&>OErlDge%rY4DQv@piN{j_YCFqi*RPyW+U+IFRU^Co*++Or%PrFomT%o-*`M4uG6faQCm_#nu`dREv%cseln4 zbzeff_3M|+bh4o=F|re!s)@;*-Vv+IELPPOv)zFtlnUO^mADdICv71jszR}1D-aTw zXZ3=kMX27=Y+TMxV-s!HR9k5!s{8a=)i*ama{#grgwLvyGsw4PS-r&h$!o<$sn7qV z^O&FCfBg6}G4XZaZHvzKgWy#gIzZnxVQv4tdaaXxzl8t9U}(DF*$=8J{}?A@p#zfa zLCa(ASgJ_p?Uba*X`n9Gg#Y5*9mEcc@ya8bMvx^8A2D(ZhzJ^IQvc7uBK1ybt}#_4 z3pVoSdk!k)wZ?E2jeF9==RcRoUqG16!qkejLIAl{kp{arYE5J}+!%%>aN0Bc$y*dq z51)K-_Kny|Roc4pGz|h6kKGpVxTvCjs}5DlQwhogmz*aXkSCTzT7&4Y^5FRK+DO;^ zrSB`qQHiTA)^qasqA)NBN0uQQOR=8x7^V5ikTT3*(H}bsx03v4tZ zb7uq9a)3Z!sVaX&d2d0BDefJclf-i?~neWbRp*VtUDhk->DYhyJlLEgvLkM%A=1EK690(Yj>@qFr@KC#(U%wk@ZTuGLKewiBMK2+KfIl_b@j6;&^4pL+6M zGC%|t*q{NEmG1O<=H-F_2dYp1uQ@yj!Jd%DPm_zU6Il!LiXVfgU5qLd5U zMa65l@$xjoz)7jzNb04+R1J!ZNrBIJL-qg9k7O>u0lWFjW|E+5(gIdXl_;IE>a-fp zEe1{@oc^8&H+`X2#J`*@ayFp?!4fa2$3Dxh5Anre$3busV-WBzcm4D&OWln>vgCFpEMN>cT$ zkFmw&m`9C8e#NF|q#1pMQU4L9ZTtj893>tw0o5-!8e@a5!&xgD8CB(=DgebcQ^1`qF2q1>#F!%(l5 zi1$Ft=6QKgtrCTwzZ(l9wjE-vuEnmZ%81Y_64LKP!lGQWC{TxA>`ujNiQlFL+1SA0 zyFXKo?dG_>*{L_Kv+PTjc9sQ;+2E!$^85BI6YO0p#;G||);hoa9UjhvC{5Sq&4)%s zCkRYVGDe-SHO$sm5&di>FoR}Md#ttXg#cq75o_z$f`1$Dm?RbgI}sq2}wNVP^JBH%4BO{v;{gN=o^Fz z=15Ifo(AWjkqVpIUT)`ESZh47{Q%FkF9|Gpr=~9W{RK& zxu>^48+9Rj+#Fa$)6mloaN#uk!6FxDD14b7Q?@^)tE>CL``&?y3KL&K>EZ^_awQ1^ ze#^^!3lU>`v{B z8}RhIm)NEbi``ds*lb6&tYnf1^r8yh&=8)yY9NqL9oBn3BilJBPmS4VH?6zAHzS-d z(sQ;&lQq5${{=-x_MPK#SMn|TV>rx`m%#FBn@whBW+U`)xz|6+{qA}M_k+RbA$5Ts z--S~g3(H;5)5)jurKBjeKk+YWP)ha}>Y@gi8V0}h^SSdhRK@?+=78ik`*4FZ6HA~? znT5-nry7+vu!m|ji>B0{NI%pQwk`Rz7v*4B3Xj`OEWc}-GS*DhPBxim%TG?Sm+V_N*Jv8_+8uP-fgu}&(k zpFH>=x5oa>NJzx z3%=wYw@waRM0rj@K{kHet69qht3{WatYD*<{m@@uA%sp(ERpv^tb7b693f114#n$)BTge86%Ira6%rwcz9 z0?80g)6@q$DYfzEZ5F{Bfn44D&|2z<4Q8d%YkvCl#;0YOJ#X0TQNvz}m9?6ohOw+$ z)T+R3OJ>Sc`@9*+5nVmeIoc7~OzAMquJ+?FLEJTWm(8LU^DHx8A`*G|bXai!T~ zEu@t0Cui#Urm61VwQcGs;Trbu22G!}T#;qFyHoTJNbWB@-)6f8u+zbx%(JlIaIXz| z&C7gwn2O)?xXnl3y8IU*0?zZrMZR4YJC^SO*PypB!?W`1Ih0X5d^#=n4EyqaWyH%s z(8{ZWr`g$usktk^^ZVG{#xJP*TE|*+iD2CRv{)Y^mORP+N`YrRm!j5C*rPo@bi?Qx z0UUTp{-+wNmARlEc|}zMDuQ9od)`#OCZY|FJrf+_FL4ImttoF$hK7oA%Q}xD`VUSRQ8g=VdKFmGfem7KC>UXBkuSsordi;cW}HJE z;RvwiYVBFUih$VFo7`BebmiU6-13~rNX*dJyH1qN!nOj&5TkM!T4Pxd5>?cge$~{7 z-w^zmbv8o`FCV9_Su^~$8$P(DVTT5XFD&6N1Zi0wY5TH|yh%*`fLg?zN$Y&M=*r5& z)BW0Yp{+Y4ZftpZL}K8Xyx=X{<^7tP8oOMDZkY>UHS3 zY&eq24?y>lmIsf6hQnrV_F|n`3F8gS$UdV@9VW*R-T(=;)XYi?htt!*u{vo@EH2j> z%u#0iBUN2?c8n8`EK5Q(K?KSLQFSZP z&&qH#Z4=9Kp6a5!^>12huv2i}uCI8Rv~9Yr3v{cEcq#jXrPY>$_43%!wn`j%IeSyu z4c}{dgUbqr&dLf3q>GZnQdvcl0{K0$*WT|Z$jPFZ%`mXp&{NvbFmR8(USN@iTz zIQgOc8wC0^elo$uNVVLWYjV44QxwChtEYk55d8R{IQDt!;xgf8&%~edub>W^mJ5A6 z6T4B$zvrTIzfHYwvuU}REPe9v*-S)j?d^Sr&VTkYB_$X8k z4xFUcsjOBT^NTwhTw8ae&y=M+am#wTA|>?#zVVmMhkOrZCN5`vnXelUQki&^!<98V ze0}pm9T}opiT5_QH{Q_yo|mB;ij^0X@bZf65%gueuJb{6IbD|&w`sSjS-P>GKZ;M1 zV*pF3op^@8e(i~*?eP1Y8eJNxUTbkidqXJ`BLjZxkR@+*Xv>;D7n@C6T>P1L{JiOnRHBRagE8hwH`W7hRU= zy1{Fe4-Bi4(A3nZv-5K)*DzMcrG7+P0{%bf2M{Gt4Saq7X7Q&HH586N{-6$O0#zTG z92!i7b%mh3DZXZdgCu$v=*KE2rk;iq?k*HG#A-qm?n09eM^I7epZ!3_BO!@u9!~Ll zJ4;#)f;_O#MsS>FQO1fFj2lRlKTlNRv2u1Hj`27h?)Tbhixfi>vH73`LUf{Hc{$O~ z2d$~Pya7pye8Nz3shO&xqU4AOjP1~LHK?-f!`Z4)aj3AdRf7z4|Z>TSc#Z= zyy87|PY=`PdS}*_|I#n}e(fMhHK_XnE(>*Z_CZ$a`UINW$*>8)hgDYl2sTELz{ zB7gFQQ&wfF+1m$1UyqMnU2&CZB;>yvY$fYYTyUD;v0vqSs(p&`{r!Ci2$P5=P2ouq zV1>1v6C$>PrsCD0^3ooL^D&ro#RXbYG}!IXQ%PMY9NfK%`t<1N@Ae2R?`ERwx;8;JmkvcmMWbyi=p`4|K8d&$= zU0d5q!;a2srshAdgub0m4D4A;C^P0o3%D*SE{-DLr?Id$)A+L(Efw#YG`G*C z8cBi<8OfTpH@yP6@pav-CJn9cguLBavBHjaENpmZm7#KYyB&2LFb@gHD zj~0wOZPp%^Qg@9-%{0FH6H8-bQe+XNcqqfXx!SsdJ7we%@8>;LkSWHspsSC@XQIgs z=N=_U_kMNGXcf@n?(UpHVrQ+ID`JcQ?6H~Jz<>ae&Ex|ouX8Whoaqc4ac<)gV?Wzf z)^7?QI$jhMS_1#??3R`^4Tf0FT^E6dJSf)SrKq$8o}^{UfE%e0cUlItzbfyp#C#G% z;Y^3S+ToF2f4QJ@Myi(g<+HKT-|wZqmM?jI=KdkXTH?^(49=Q~jT|zCA zs4UMvcn~Ok-O#PGrTSnO+4N}7>q^p;EWhB*TX@pozP_8bdAeMSj;QKFQ=?zS>zE-oSoUZ>oizDW4K*ouF|!Nnz^sE9Gn zYF=OO`TW~^A}%{Wkd6xV?=1$_hGN2E)j5xgPaU^C4Bl${un&qXbM+`Iq{8+23pd{< ztu6SPB{!Q3#;A5RK9n0bnyP-3gUdlgx@x&3g5vh%1TZkJrP*iBsR7LtRPC2R;IVe)o}Bt?J|w@+JGv^VQDBSELhcYRBK-pLgbL^E!D1V@Y;9 zo@iEh(2_J21fC)jRnJD{vMOw|UCFiFj%1B_-TU*ypE|gW;8?z@VFr!atP&f+kd6k# zQz$7l+U|$4`Q+q8WuRdX4=ZlNpomwZD){HxWzdLQmA3!=ZHfEg{jZmQ%qB3l$hA#` zioYPu16Mm|>{F8(CjQYLtJ2_B`Udv=>H6@!YgRZIi@L`I`^m^z+$u!GC;L10;6D}f z^e`a_-^gQF;O44o4s#nD+i_mHT^{IK&Dcehuzrg&6Vn`x*OLX6fqK)90S`|o#9_J~ zGl%uGQ$Ry|7vyS@OvP=|bi7hfTk?Cloc60z$xZ)GMJ3#^g7Z64x|j3gB=-~DCL;GN z4k8Qza~$2M#VRIJs#((X6Fx2Vn&8dNDQ-*MZduGiQUwlNZs*dk^B>s=oKeFuOZ;Fd z;Gj$nED+kJpR#^!Z7?rhyvX83OYm>ldv8?U_Rd-M*p07Zn2=CiGGw+=yFqa<=fyy9|hvcGT(}|rb6I{+N~{UVK8%#;=>8#h=_>5 z9{8{R{xHA*J&QXmA12ajG)Oa!Z6nS2LX^9D%iVIfDD!BlczQ^CS8lovt5v#GUFt}G z5jWQ{5!Fjsj7HlzdK@;}$ltb1Lvyp@7<@Uf$Rr@(xt9P*W+r*)^64JL-(*d4a#tsq z5sqVQ$KB8ntJGt%E1}Bf@)s53jDl`M%8!X?=5$OCT*EKtS6Wq-5Ee$RAt|eZ@Py`> zV%@t?NF!Ks&%CQ5`0iZ<4E5qc5VgGT5Rcso1Ox>`6O-;`D9hc&4RR#Wr?6gB+~G z*@b*NP`i4QeK&G?i`P;R*mV28sIDBg<&eVtK~au)Z^dZeqJV6YO?1ztJu0_CI$wnj zt~5JJa-Lee?tfeW35uhb*vRD>i91VuLpP7aK;S~w{wW8YglhlNlq}G@xlSUFat3t| z#HMo7=cvkNNT3#3N;(`!vXHwNLnAxdgs2*Tc<%F0GJ> zVf7F7Exy3La#T;46Ta`*;16BhanR9^dvs;Vkko|oB(+eH(`h{VW0I-VwZ)fN?6 zSa{-ITH7(o(_F^7T1|msK`>jpyZmeE)mBZ3@$un$g?ag4l%PNpUH1}c)=*$EIz}&m zV9_a5S>TNo73SogEN$+vefn~t5UB(J&{I;xvrC;>(^D5UWZn8=#zM{o1O((99i=z7 zjT4|Q{PDvwx*zw1Tvj{n%|o#*^4pj)&ux%M=bJp^*j_3Ws{0FtJMS_9r|mSpUon9#~xxS&?-22^1s%5exzzrSvi#)8X5{~w5qk=PV91ZB5=dsqw`5a4(A-RVmlY~E{FaLI}crushc03;Kv z*K=^P8R5t^v6$v*DQr`J$I%P7dzQ|BL?+Mg&QiFbnpBsyp62e>!;D+}Kps|EYIG_d zyNVP&^o)n8zQ+eW694bWb(<-Nn~ChAsSQcFao^zg)b0|enJW#E z{x*4XUtiR)+TU@p3N73Ee6cnAnOx4&ZaHn@v-EDyL>z>G+ryT$B->_uzlMYQpd_36 z06Q)jX=&u1Q0LTd&L^b&2EN5trYarhX&hR_^SsI?8eh=wfJRM+0qa4`bP0 z*WDg^5xgCSg1(`b{H((xX#uBgJpO$*c}>3qNbY3cxEtPkT}dOk<<+DuJ54L_nz3~= zlQjPNUX!*3t?4oS$yB;(sE#|t;j&4I6#Kbbs``LrMexxneq<;(g06Hkgr3Ts?esPI zPzA5&j37d`rTWnq&REO@{0(~j`3`>X`@89&bDi+zkq+{3tm5^cLz|D@2iTX7N18T^ zoUEq7xVc^`&E=`{oH&^Av>&f#e0*H8eppk-9r+}^zF6OuQRWICDCxN8yIz$nY02|9 z6K;m?Z1#=gGf-w_yE@i`+YBy|@xm*k54aH$e~C22HRF__T%X3@O7GO~?8dS35t$ko zv^#a?Y9`o+j29x8f1xMj&{?O0-%@ibQa0XIC5!lIWfgpIz_iVdFRZJDySOJ}(eE^- z*wdq?#$?ZEGCg#qVShXw67)mLmGcd+LQ-mS{ZfLxv=hBjX4Adj{0?FJ__ z@_>|jl{mzr1{sF#_TW4HN6%Y-ndl;xK-q2&Tt|y47gmLktqMY$04WXm*Jb9|x3oT- zNky>EVq-focAt)~y~Z+-zKImOtQm!PWW(bvK(ao%G^waErqnDM*IVLGrpgSDPS;@4 zWS1UNSX;}-f7a{rD9X!o>UyWxE0a|eGlIgRyZ&|JC0MtVTCrpdGp<#&`?^Mzlbc^d zyxK64MU4XwMbchQ<)W*EHC~S)-;P)b7NwlnM&W~!7L%Kr&e+7*7u1v~rdD-Db>I?0 zz-Z#e#ni?9=LKI*$$$)7KEXlwb9jq3A%iA3$BbtwMb5b;<{nJiLYoU{CsV;o$px0v z+J`1n_2GmoNp>-X1zP=`BA-7pi}3mMA9E|s;wm<1whjarCSN^TdDoEha}@*X-m!;k z2e&M}fttHb9O@J;RHf9VV%Tq|Ow`-Js_mTMO^ z6WVc50qFMQjmL(02YWAHA&vuYTLgZ71*LWwx^K2t!3if0V)~~9Q;QzE(sFhMT*?E# z=c}gmEV;YSo@{WzMCC8F;Pvw-zBTmp&**4tAP)W2=nsKT^_Ck|fzyPMBY$)+zon(6 zJ-FehFv|0HQ=7rZSAXF@=yvRd=GIaqcI5w+q#6%bCdd##BK>g_2;r7t;o$2tyUBjH zL-%>t6zYUc0$Cok&$;vn2@UD`iKM;DD$C*% zc}7az85oc5F@DyS`x7ZQUgCos!{CWdYn=24V}S?nfVl3T@=;_%eWrRw6RMRz zfRd%ErPWU!#<%AotG4^O>swD}S6^3wWGNHtQG6{IRIIp61Ap5o@u{E=rElf46V;8w zf6m-5r~7fC5OfCqvv``E9+?Qv+|CeeC0KJ73-xL6KT3JupU6z451unwaPBh0&v6ch zOnDj_Mp=@s^v8s-an`U12vG4e%}TB3Y0XYerSdnh%5OFNA#9o(;+prjFP$pdh5%P( zs*f^KP5t#_+icLZme7X>0pKQ^ow`;GcDlo`lr0&5i0q%6E^P^KZl1NImitAsF$1jC zSryA8Bt#O)LuThvcr2ffj)we{jc-zzo~fn7DxqUsk)i*K;n}CAzPnv^(WkjP%_x zsPF~Tu^NX62nb+kM2pTp2LrobZ&kOS_$mOq+=pSyV zTfjMf$qDQH za%n)Fhl=a48=3Y`x#oai*tAXZI`Z;8xAmhFDm3;c0gtPH35~>ZSYM8-#(&dM?5h3C z$oSpTWz=EVXd_RbJh7X9wyg)QsDK1DTG?71zFKNaq{eT*$W`V#ffjInw~gOW?!{uE zI1CHk!8M4BaWz{L!hgw9rX3SH&W;9OeroaIkkFpY_YZ2< z(4LG#d3bs20J)+LYzJ{4&|U&E>B2f-QGB&$DwuS=`0LjjDJiM)#?N7ndb6!@)9vJ! z{3A$@eC;iQqeC%=g}=&a(!5AyP$;*O{WT6yQko=9{LB;u5E3fH5{H+b=k$`>8hj@2 zFhAN*R9ne(W4XmMh>vEv+BCerj?ua5r3t$Ya#z+4PsZx^y;N3=4oZ`hyP%FI6={?C z-0{Wy=$a;M6LV;UeC11LFNL>x-VtaDx7`h86z!KB1R9t`5Fb(`v5GG`{1Wg_*8w26 z`&MVz*JgPnjKmz;6ISV2Vgs<(PvstOnlm!SBIv(jWZ|G7vXXpWfMkfA#l_SQes(FF zu}TiN3aIZNpnvx5eIh3tF0vV%5wEtffg7a;-|Of69z8HZh!xd1kB6&K6l&t1OE;?18zLDuSOl<_rcPVQIhag0ymsX$&)*H~GQg)c*0gWvpBpNX zxd?7U7G@hqoivrE?PZw_Vh`U0e< zvoWxRvtYmq-0#voch&BG4vrGCm(LUcQt#>-7d_(RQDu5d^wD{!VV@!w{^N&V3RD~m zXn5H~`p7Kh$gSY+`ptK8>-iy+`w3Nnq`r_d$!-fT(U+)x?C1A0E(W6}UzIl=X}PkM zW)!IpV7#i+B{*+)DWo(fN)XZZ1r{=K>u80P@S*O``yYwkS$3()4a~}j5#@W_X%xwL zbQY=YtECK83b8N?^bGjHR#~W*^Z{^pDY2$v={#L%V?-mu4hb8w_Y`B(ETa!1%RR^~ zMmS1M{DjVDR?zmg`=XLCZERKnnza$9pZZr$DSx7I`S|u8ELyg|-iR}Oy{zv3JZbvQ zue3(LQxjHVqR~PEAc5 zrF5(v07utOuV(=6+468+3d7~Hho`RZ%|0Ud*m%*(O768?=y`3^5*A{s(Ni-#LOHqI zHQzGTmX>>3cVTVqWphoFc0DKXu#2t26m(pW@tk;;w?F-DC$9}(n0D-t-7@;aAoWFV zZy&PV(hgam=MT5_bvABki>qy<9Sv6J!1<8wyvysn>tl~w#M_a({kan1D5P_&)h zU6>iLK`BnxMRRjG)%{2 zcDfo=HA{V1AuMjuLq{EoYEt<$P47ab2av<;l3AZj3ka!PE=A*2$oQZKU^{G2NvI#> z+UMR5iJfo;Od-mIp7%-efJ50)UlBBJuJ3j`(3$CmC&#$Ym-k*bhJbmp^DU5ckd^OLZ;rO zxAshqYmS9@4b48>pd-o0NP0i(k*SVr6jolzS{*fKEMi3vVymv@i~#E|^L71C<|5zC z7O%gfUrJ?__u_@6X8z){m;QTc(8WY;40`&E9ivVwI%8M8At581OEFE}!5^rDegYnt zYrO@!x*$4&{lv+iKf}^0CRv!DcZ26NjIrY$bI-4{eUZaA-B7mKb_0hlHkwk;sn)}( z+z?N%d0gIah-Inw{Y!K`({{u;0lY!Q5vS7 zag=3+?R%BM+3$|9S?q~#Nu1nfxMN>fXvuQ8xXRij1CjPV;6QFq453jSrtjSaAFg<} z+9s1`RP0XQbi6LPh3%o{%pJ?c(*Sqx9d*?xwzYD(sJ+!bo{Gw$ol22WbXKa z=V23relyYUl|2(&CpfSW%<+K;Y}dwP|%@aTKgh6KHv4R$cVX)MeR zf~Kad*Myy)G^o?9BYEdmQsL2-dulcI)z&(9I+M?wNLUu`>udBwOFp z_FK?jADy!&C&8^_6NbSsm>2)ue@nEwl-Y5&+J|A`Xt2OFa?~!bDjQue?whD|Z<$^l z+px3=4Vw3KyXz9TxINV>>?6iKUg%HN>o>S?2;7YRnms&ja6QZb z6{=-)QA!flDs;cz-2a^$MTQZ1#83K?0I~RtQhj={>Z#~_6vHEgTre^ zZJ~UpUi+E*TXNM6WjE%oUhMxz*IPzK9j$$!GzbU+N;e1sBHfLYbazP%JqSZcry@vq zhjb&|A&qo*hm>^J-JWyaFL&Mh!G((j!@z&%$A93E8nt?m(2y{U_YNrfw>>wm!{YZoj9DTDj#}!M>W23 zP5p^Mf3rFF4XM~7$EAg^#lVIZm2i6t1M3U9hV7c^+_;kqYl888p~001&6(!qYsJfw zTlbarcF`Vq7UD2|{uPo7l+6GS5O7a7ceeo3uj}$~VXoQ=PdKAybr}q(ACH4X1|3{D z4-d8_K*MSR7Gwf9IG~w#ZhpL&Ic^y73NI>>{o8uibp7yeL)A}@D=2VwyapR+yIFj0 zJjPR+37XK#Gt=^;+?j>qM!vfu5|p`*n5QQNng~wt8*D5PoN3sgb6BL5a*{9J8)+ z`Mav}vDsNOD`+Wi1bkVeC4&b`C(e+iXA^soTbtJ*^;h#l`9WbW;aj*brf9av(iuyySMO-_Wj@1#rDtf(Fxfhwo)q2pNQO5T3ujE1I;K+dH((-|X9b>QS zekwjD%I?uo2A+VWdIC|Q0Yb-PC$=usY|q)=)lT0lNS|T7UnRA$$4GO(Zdm%nilRD?yx3HxD{D zA0DQcMF2d77SyQ@oH!q$V#al#j4-@voN*YFB&c-QpmT)5ZhClHJ3LnI3?DD;pImBR zWJK(jx22bry-W8z{UCh#GvWj+6AE5=db~nHfd9X9`1;`TplSpH#ZA)q@Zs4`hKR`W zWK4cS6F!0q2V(daaVo%>)xUErafTV~lIJ&9SfVz6A{NSzZ?w3$_zld(9A2xA9=;j+ z^6gcq1Ud)7eyYR|>wbn8anEb@LeX^04HVbd@-uT(3;^@)B|*ZAhzx$Fnbw7|erq&t zk{t6Iqsr-4{G3fRCeP2p3W zi0-HGr2_Sq6La_%?vy3$?sjaZ+=uNk&=EUY)kFsw0vn_09Wr|31fp+)X!9{tV;-+5 ze;AsIy9k&6{)!N1QvwFJPW*@S^K}R;R%yK@J&aAS*hnx@cFsRs?vS-}qm}La+L4kk zZgd$<*UJ|*u01)FZRm-ON~tu3l=jH#!Xw0Out;p?P0uH|4cFZnns8aWWUZ@Dt*n%^ z)}}<|fDsWhb7|5|YGUHC{)(VmMGC!AI=&+vCV9o&>1^@^z*tex&ysK}oX#_FQ$wlT_69|PL(ia1lgzwjU z*q@K|p+I7Bjamf+BCMAek?$yDBhzk&8hhbm6SR)cCzN!`e%q2+zmeD%Z#1}ioy5}< zMr{`K^=pp5vN&Xqha*Ai#2U)m`>fQ+hsw*V1#X;lEVfdwP3Ln7m~^U?NO2clmC2*> z2@Jc>^{7p2f=QN&N^E#Ijjtf3#Em=9Z8QnNCWI72jSLMt053B+GbFUe{t6`m2Mw(X z*5GJP175W3SM=WPkiRd*(>2J3d#l(!1v@kp4AX+bbMK4?u5$lFT{obE3_T}6sA^9k z+YzcG+nnU7IP|xZ+Q8^rEUQBLgJ?#rJ23=9{3C6{kKDKDE7YyP2=9jow&8quS~PuS z`xCFcL0L3Yb1>7;z@^8PxGoQw{7WZtQXg0T!v{JHrB3KYdp0O9M=HFDppMX?@_C)U zFd1_Jcxs3#T=NDIzNVaFq8{2S36s7wJ|eJ=>ZBa1Ye#bM1kuJE-+;^?t;*o1b>7-uA&%vMC&*)c+EcT!%Iq+rpUp~9q-T{vqZtPn(qFtwCurlV-AA|RwPyFpu_~+iaY<$~;*5?*& zh{27k^c?-_t#&G*0=TwUPF$M3N-aa@q_S()!A+0H2EN^r_iMNK*;M6SkR8B!&$4~BEyX`1b*>*nnmm9_8rZwPFrI4Fl|9 zAy}mbA*w&bYAWV-5f6*Nvdl+k$Gd`p1LMr2c9yN`2Y0b(W*i6zlVGgNkBa8XVL~)G zWl!&TW^3?N*)Hll@-=7!+}@dW-J!eRPz@ zz%fl$&@`qHSPj*yNQ|5Vk1NW0^}yuWpDSB7YO}CC1REiksdrq>)bzCZ!8L(^teQ@W z;oGA5+|ffq9k$j}x=?UCi7rSk-o8YKug5K>GhBeC<|U;!aJ9)2YD)C`>%UNL4o|zV zueGSO-NX4mEjZ4T$T zr7sp7BqxYhN-aAqIb~t6;z>)f3mfgy71@!+g9yzBmk#o(4S`aP7S#XNK;!n`n2b2| z9u(bcl|_yD(;%RR2@!}@h5V4NF{`z3>E&VCx*qtITPVMv4P8hwyMfCJmsfaS`dnFOBE!5H854ENbqKx#tdB*QjcT;WYuZ!8yTd`!Ft4p>;dC>eAj7P5Z+N3@!ui2u+8cq+Pa32 zwxx#JYYl*7#!Vmq(VT?jT435Kdird;16{X+?nxz1=zShJoOdZgOQht3KT)$~JE$i?56R{~q#YzYO37gJzGz z@IM~~`0$}CE6;d_iqqVHZ=UX>X1AzUri}ltTIr!p&G{nn{udxcA+PiuGnH0#>gmeltK5Bk&f{q zdUK@*2H<{FHXH$UQFhf?fla$Mpd7A|S70EbH@qr-#OHt0ht82ep;9)#4iwaISpM{oSExM=%Hy3}-#ED#BFC!e zGz7htOV4ce2IQLn4Dxb@Oi|HW^2lcoZ`R;d^eA6Yf)4C^g2r$8hrI^|vpfsyx;H%S z$Drs1u)@wEe9{rT3$=L7HtZ)2L`(qkBDL3cAcRQ$Na=)p73C%JwyF4`xS4hD>$!`% z+FBf}AP$fA!$h45f*LD2=qIWUQLaT(f*(-^ZNxd4NC=pinDzKvHpuc-Rj7;MG3t%o zMcMJ@&0kN2FiQed+!g&~Sw|FR*s@R3#QmVtAanX4%qB^32`%=RZ>;( zLQ)>>cCOX&@ze6D$%b|qWb{nd0S9ooplFR=#T%Ue!>`EL9D%&(GSh> zpBPL{HAn?NKU0=xtxs8Bmwtv~lv98GZR;dWhRN``@kshonJ2}kM(p$Hqy3r>cRVv#zyySXyH3QuYWa!|e@3aw8n%-MNAf1D z?!84oZ+~_=Ap}H2r?I&IwzxN$f3gEhl=WTa%-^X4+QA%i-9O2WHW0+kK)nM_h75?> zL-oom2j-Jg^mhO7Qa|+6MQXelVC1F4$eV~sL_A5Z%r-M`ht5sw0=A0F-^GuG@0i$= z5sB{FOZhYfP(d}?P>Fpo_*26YLbbTjMQXN??E-z-&p)%fq>uGQ94G{UJ(FDncU5`H z^VzC@!GNoGukV$4DrFz+1v^GF1C4y?0ipw*8x^&A++BMiQ?hDhyLOA0vZ|^$SSN9) z{}B>C(xa`wQIiyfm&rte_SzcOX{E|g%J*q6G~UjWUUdfa2j8T=gLl6^u!COuN2R54 z6?6&fiH4u4&`W5e3aH83aKGVV3M)CBV6D9Tx9tE5VvPxRx9}$c z2>zf5uLY#E5R_LNdU1~TPW)+pUFJstw#I2m{1>TP_#D=n1}TwoUaNH1bgdH-+1;Qy z1KEANL$oQ}*kyxzDcy8Uyl@${av39)KfG`z<@6&}T{{~GtmM(wY-@3?mMP^kCHo7s zXn94mMM5%YNa>W|H!q>O<=J#{f&Jl_<@xe;r*fWQ_*mov12L_8xER(jZbUv zHR&7{n(S_=n$9~%Xb+lHwhF+^0Kz~;F7kQ`M}dKfHGvG3na4dRmc2+>C*>`VB+-%8 z92^Ksu^Q8tB2Q-`PR<7H79vfF%iNu$2KE&J zb_ciF*w4@#A%VWrLfBn)bfI*E{Vb@(Zn3s9P0PNr5x-5~jez z!yET7L&d6|ulo{+XmKU>B4dR9c~0!sZ5}ep-XWsEhKDZU|MdZRAL{@TxNjHYL%p&hi>+R9HK+GRO_0Dw3= zf+t|`sy~OJX~H>GlXSQs&WqI8K#=OI47sZXts;Owo91bl(RvGMk{wCs;Hn#I!6PSn zF%Z^bjI3UXE*8APhBvb-0r=2BT_zuxTv?j}-P`$v;bTttF2qfp?y?2+3QZc9XB&p;z#IbPY&fz{5?)AteEF`nBlSkZehE3YN+*F&PQwrY%ZZQ1?4$xJ)ci4j-I{-G>J`$bHfbqr#o65jabHRVOeA)dD#|Ahf0c-8vuPbDRW@Xb zvPEa6$u@fJO@5hXslUfW1TgfJ+sGmBycEzP}(Ys^Wh3 z77bAU~G%QXJ6%Wvj7uxv}~ z)Tj1>H9qwT>0@$(Pd=+#c4Kp-UB*I@(DC3Kqnmm1)(O<8akQaa@1C!Cqho9wn_ks~tF+QG46-kEGbgqJSQPYjN z7HL4i^TA$^E?nS-tY`5WPZA|iE;yNO)4}m&8>Ev zr`_SD4YyUd<$zNZY>zyj9Ao?M6cAnl0Ve=O59bY8IYy*#a^`O7s-)fjMIAIz>Zr)= zZ+Wo>eZ3_yq!pAEiKjhZ$r1!;`cbl~jk_(Yd10pSbr#ZG(@iGwu%s(U5=BsGBH8sk zV;9bvK^>Hof~0B9!9>rRKs1ULx!w+;Ep>}WMhZDu`i85%OgXWDQE9eCc+eHqc!>Gh zFdNA8OifL}M!oh1j%0VwdC3~+2Ww*Zx+~i{rVQuEpS+jG&P4eH*?O>9O;kK)8&$N z*=h7@XnVBC-}CCT?)XvDgRz6^RE%>=>c_eORBU#3_FwJo?IsE9yO_XRgN8V4e00?K z8n!(DldiN?*MA94uYEyU_!P(RZhq#p-w5-xoT8a@#R|m^Ydt<4yF)=Szu~a#@Sy(A zo~u_OZEyR~i2ql{*}!$3UP`?u_s_`SC?rHTs-gf<_v9rdiY+E3tke5dOuncW1TBt4 zbx=k~FhyR3%cm(JgVb;FXOFc+-c1`X(>QKQ+RR=XEow_dv2?E)NZ%ZEJ{*vzLg;uB zPRCib?D>MQxwb_eQ;me3Vvi2VxBEUP%Qyte@k~0LNlJFzTZIcY29>svz4nAM^K4nnBlFEkom$YX3*&E_g&8WHxx!vw3;2gv&#_;8%Y1M5! zWD8#2*f21mTR(<_^be`gu1LYjq{WE+iQ8bIIWP|z0e0>iW1;1V&=NR5&5!Ls={A$L zVJ!Tjpm~-Wku=5ub8cGye`O!2;B*TfCT7HZs(dwFsnNP}kzWR@F4fh@v6>b2U7aD5J7aZ0O7;Bt&npfb9}ar6*BT z$t|RP0OkZn_Wzj^d^h!Nz~N)R3Xoq_upa`rFe@kL=Db@csBK=7!#ISs$(U)^CqxYg zEAg&aE{14C&$j!-rL9BeR}a2TVFq=A^6JN!$u7@zY$b6qgEdDJ1wI0%t)1P(BDNy@ z+}!oJd2B4Fva)jL?CeVe1Nilm?|!3Jvvwk^@S*Tt?a$)hy6p;lpWbnDwi`%^gQoE; zE@MM^eG9WOJA)ieB7|FF~h< zA_h4RVuMw`okcScIb!iHFD%fI^-cNjx5K>jWLot9b3xY6ZnXaaTmLS|1Ta7O4pise zA+M63{+5z?s9sI6Yt{UdXvzVJ<~b*D0TN9n6*=H{oVWVLvm*kFP1!JYGZ#ZK8H*Mn zHMV-;5{~V#6M=p5YXFVeS>;{9bCp9>nTebHhsA5rREdwVB=4AM9ad?vZGEClcOieh z6p&6l#|D)tL~L0sY~*lEM^e{M4yCWx_B59%$To`?8t0<$){^Cl3ltQ_98402*IwpW zTwi#x9J6@j^|6Fi<}wF)v0zpn&fM`PTdxHr1hUtJ-*53=spFsRaltdbkGWs(!1^l^ z|C@=WVC|Po$nr8yI!P+6d1Eo~B50lx5$vG%t`5*Dd9$;mRf4iQI$~*9<4%ATWKhn9%P>fc+Ms=gKG*T{^6~-ntTL#3fk44kSXM@b z&y?bN5Akca^%D4>uoS*>Jx|HXiUCYhljhBai>FNcP{OUIrswxao!Fy!QK;rbSJyg& zEbZ*Fvp#;Q?&EZ}16Ch-ASFZyo>m;5gvA~b9t;+%t{;(*q_F#VFDyXFeE9`_lTDR* zW?0(lOM+XvexjE2{i5{JDS*zN#+4l%K2#m7!bRTHin>zEdbp5FKJ z^0A0iC@88R8#?a?g-Z`uabtT@m1-Grx`-$S!5JzSXDRd*vH? zdt@$?dIe;fvyB)0;P?8E`@qn^wMqIRd4P@ucA42M=Uwq|joa`F=TxMhe#GJ&W zq_p_o*;rXcX>p^_l|vjRdo%BON^eWx%m&Ee$9HtyFhM1#@6f%%$`;k<8(VpWI4gic zW5KuOQ90*UL486bx=+~U&FNn~D5I0li=u<2^-l%n$#b_e_n@q)N%!heSw!39lCWCz zO=8>j7QGeHdKw?tx zwujl?Zgc1rkYlqAqBZEd+@K3r^9QM$CVQ>$bv%*@-Mg6vYNeA8BpCgYURmzj@5EDg z66#F|fBpF48nwu7TS3?LI z)-3`Kyz?Rm3=O2$c26FDzV_Vk`t2qu94UL8COwgJqDK0BT%BOO==W$=&ZpKo|1o{To1{2SiFLT!z@aK)RPVD`e{U`5HI2s6$Ufvve2XJ*vc;K7md zs~fwA+IpDm43quC@{NqjnUr)bKxb0lA50=!xuZJ=R$~s`?3DlRlIUN?mL+U2!Ap-~ zN?sm%MHE?>WJ(AOaPYpI0op|A4nza}~OtIFa_a0==pNcg^piRqSC+Tjoq>fbaIW)ad%eGi4c zYiQ626qk&Ri(}`S>IMZ{X-bxEdm@R)dN4it$U*S(GI?PJ&~@3nd;A(qh9MHFMX>10 z*IWjcJQyPrstpXJf5IRPxPg_1GEX}OsLntjo|GKv#I=<)%-VVXp`v_QIT9hOV#a2y zMMs@?0IWn_<#toxCj*yMuaiAr()?A8aNw=y%xHxP*8LhcDcYc0!LPFS$?nVye){>J zf^idxNJ-5;f4<}pqs9H`>8U^8N$=9m!*o)pdz`+oss}C|(0zh+${*!|$N~(s zKiDf3eAJ1=U}A_6YyRrk5@PxZH>;>7zNFn5Lc81vNZ+8V2W}23Dk>kGofWn}GVrYO zbM$7W>y;iQLBSV=XZ`#c3?#VggPr?OPmzoB(-;Dg-F_LV{Z2iB%iM!B^VuQA(A~j7 zOf@yNNX3n-n?4TTr96vq+I-c)obl@iVTGBxgiX_azTel6Ma1qNQf`-h4CJ3HQ$)_O zkGBrl%G_aCLNrz~N>vZ77IS6yQxeg5cxJ{tJ|Dk*eX;sGi*+^N+?F{|uED`H_EK8O zVZz8~fVv)Ux%{Yu5*bXKWE}XPXSgzd$eU?L|`O`NYtA`g^A#vv3^d3@Fr? z(ep!c`f#r(lT(c7;$F-oVG1+st943t7_**9^d=!ebaoBiYI65F42RwRT0;PAhwY_L zJZc#_Nyy!kHGU1t&p!7tzmaNAKSij(X{P}O4PG3MhE` zFO40`%os900gDDA3xyeorfj55cL*x{=f4e++ar+uv}MUXPyuUEy*Wt+*gGJbY+T*# zOwyYw@ggq|O0WRxomx_#N}c{DoPyRnp*N$}M`jIu47q;|SP64}{D=mEWhfUZtmy|qD_4*r&e4Xg9@m(rADIj zz-9ef)5+9pVHpk-f}d}}D-$yjQCC-&btSDqK%GZM?Dknow#oet(U=;S_e>70hb3a; z2E$MjgAj)<6?aEp3#2Px{81I(R5Y!r*`6;{OU8eD)`b^gam$j4spFf8Gir`BI6sG{ zxinis9x#gs2NVsVO(mg0ui~7G)`XZS8j#taI@)cc-sMW z5#>qzvXqx^k+wufXK{>JIKet6&#%B3M;E8a!6kHOlo-aQpqLk$wv^Z7X6q9I8xB_f zNjnfH7osi1HE7yKM3s~XNqzC^i!kBHTJ#L}X?SviaNuyxeTlMR@zt)cbF2Qefy=uE zmZTq5EMj-98=j7L;6nb$aBX{?;YdN6l)l=hOg!L)iB0=QE})H7G|8krHMLgQ+6OW-XuCbJ1gOF2ftgMe?M+y z)FybQ3l+5kt~r(by;f6@o@WY^^zTUPZ(i$l!O}}bR{^~!H#ZkB_^a^IUg8eFhfdK` zb58N#k8Czf71?!u{jMKIs@xdgP{RTQ1UbCfMDX7`jK7VIDbBdRP8|y!R#NO>)A1TF zW+snN1FRf5mZdIWF2p(do`DI=aqpJW;|NLcW$??!TKcZ;)5b<&IPdFDUk2XavO>Rd z6;Y1!>R7+a1 zr21RJD<92idQ+o%c+Y~YZlI_)`Ke9!SEd%D{7;My?>v?u7`A~H6hVI(Or-x+KCP_# zpA!zb0%>C5bW2I4c|D`&L65S=jYZmLYL){w3b85=Zkka=f{m;UbadmJJ3EMcNC7l2 zUpC7a8YUbzPW2jBLoQ52N*lB5YgkruNiu+v-x64~0WQkpm5x9q4AZ4ul*f;a3oW;X z#SCt9&-8_ly`=j|vaB>s-7p16Zquz5`)~76_G81HE5qNXwsp7u&kto6YOCutaLG6H zRy1!JPf9sC#`FcQjSIIdE3duL>>S?Q;_Sh%&4FcLXf$-LUrUk_NxZCvz`N%KKfSaS zn#sAe;IF;oDvQ8v0!XW#h1@FGtG-?LPL?E zr9gq%Qa-*oHIj&jqZkWTxynz&kTnMYc7vr#Ois{1a>7bnUjM!rDsUYTqPjKP;SzLH z9SDdQEHv-qW!NkwvjNQ?=Rclsz#QSk?kv#c11aqc4VD&!y4AZ+>+QmXNFec;VpkmuxFVS4=vU0*UAEV~u!t;7hkUJz7coCuHQQ}Y4uInmCHKMB(Zd8U>*;)hX0l+bxfiwMa4_e1W`|KfwXCr2>#8(!vm;^*!cO^(O=T+ar<8$ z@c($0^rhs05ua&efXM>x&t9YNbCT%~K?vR2)}Q<2?Tm#@G#6js+i2EK!l+2l0~6q+ zlZ-PPTY)3i4H1t?pXAaUT!3x3BjoZ6Nkxz{5ZF%ev}#5HNNAbE>=2{4B2iUyI(?P^ zDjF*r#JQ!<8z!eQ@ElDRLmcb^1JLW*)m<*1*fWMZGdg^A4DtZ)RUOsBrJRW{d4(zX zeLq3*EUf#-cX|1!ygRAcB|2*2_V(X8gL28l^B_MVb#LbNk2J6V- zas&H5{%uumD^nvX)nWRSvNZFF`eI%#e*!?_pe>TJ*io6eHA7LYBz|4u{k%?pyvrwU zw8S@5(yNjbzr$Ow0LL?bkpPNdy3SjzpFh~+1MvV~b%KP1T=lMsb-(>B;`Ix5gvQX} za?Qo9$;@c-ScsNxX7nt9=(bR2e{1CP*209I4_};*~$dFW|(I z%Clmp8kGMUaI~mhesFt?6k17tY>ZRPe+@79!TaLsx#z_zrPDj?x1Hs;GwQuF4fj(c zCsFTLHi~@vsnnz!cIN9o{V`p*nbESM=LWv0`8*Zt`C4ZQcPnhYoBio|b2q`x_YdcF zZkJ~yeP6reDIT94dHilW7VUkxt=~=OlQ3E}_o}G# zl{3k;Ir;g2fnp9!2HkFV^KEAm6vixL$Hs7m<_GH+(-=noA=d8hijed~*KFY`l|seK zo_`~l zpZ%$b8yv{w@g7bY(#uhGIcdr;vH_Lx_1m8@>H`$C@hs6uyd-NUDBn)%+_%YWX(oNd zpe~1fc>6j1mXdnmZ!@1v?SZjaY<&Dbo#^>_s#CYyB-Se6&Bh>4S$%l!7<`4C-6t#1 z{?-_se1NV6CTD;2WN|dunawyN>^Xvz_%=p9x?db2@CBjhmv1ug4v4SD@LhjuSR3qX zmcF{uU1(%+F4eWODSnvL6mhsxE7Y~dNsu*&3_%YhQOw0DBJ0}6`GBCK$!&g0xuZ@*$155A$HomgCy2jhCegJKQf_8R7^#5hZ% zV@F$zaiTkAr(Rr4kAu1Gcs|zKZS!8rY zp&Pskh7UV4dY4`_1pnsRm z$HlrH)2gZYPZ%?EQI=}t-@E(z`>6y3Qk37&Zk^?m_>M5@Th-$4S{Cxdwy8F^zT`}P zWfRf3n~w2%Ft&teaZY)lYfoMA1Pa_?rGeOjSiXwMegX{p?RkNW&CC$1rFz(^XAA?8;={qa|!Ii~mTCmP)@f^eYZS5m6J#b>2W^=%%)EQ%ve zNE*nOLf=!)82iOKg<@)8@_8Hk`G?IZA`!BO^PVfk? z&e=*lA31+DSxm}wC0|ee0zUH13$`OI0p#2@Eyhh1Ndd0G9pc=4O|H$vMIJ#Z5z!Kz=xeW+vOibE&v+ z%XVLqL6_62%pAkVuRPFBh1Awky|bqM zGEK-(k$Hdg!_8U7Rs3ITvq8J{F6+I$)=FgN`6yq4)bLJpUVQW~`rQ>jBz7E~$K2rc>b+`DiJYwi=KZ$w)nmB#o19-$NKX6p7bH?>>ey5n z=6G?pc5=AYLp%R)lAs~YR^|@jZjQ|p=M)#Czo8{2Q_x#*q6|>}LsnVYijdqlSVASz zHg&>#@XK_aw9Ij++o7n%i)n6-&&kDw7ePd=`-Lgo4v%GwU*YZiCp?;@^9@!3!&$$D zlCDT0lqe%`%R@p!06Q}hL6m6AX=UE;Xk3HjmJorxE;=KP(4?);*J5aKLBbABcBd#O zhm&D&YuaE~7L%u_hW0GE=;J2Nbf4iuwR?JJ6cK)ddAT@h?9UQ9nnKMHu zAK&Hd#Dlb*Ge?r38nD9rUGj{ zYYmN*mD>ST`;{5saQW1Z!#4$|P@DEh^bHIELo}Ud=YZUqudW=#Ci3dgHgvpK8D5CU zv|gq19vuTCSSq{3uw}r-TQkm@lzm%iEBX69oni?caTsoxR4#wk?iP|um4Hu?{>O86 zL`3tMAavHz&#=Oh62ay0Ur=vNb8~Q2Ea`p&BU6m)56)il8N!`7iDos=3w_^c1eo*? zLKkunJkM1q{#1_$$K*tGz7z??(v)PcpHTjhB2k1;(U>F-7u|9!7if5 zM;0`7BiE~+)E&8Gt$E2i*ggp?Dj^X3Vok5CK?Tvpm({91iUwN;U7r}?<9kim8k?Hp zM7K;16g$4CpAn#cxqa}eBrGj;b8-$t_*Gr2IX=aOczo!)wD%`qX*x1vr7frF+Vc@bYfq#p2Udn# zBO@1|5lRR(Lm8Q#vCpfjQgiqEGua-cR!tYzrymCt_s(*Zq>NzTsgaWr|8+t$sr3%G+5o z(Kq?NnZjSmabtzBPK2ro3K9VghoKPLD=eVJK|4)^hpmK>jO{TdhuG!2&7Er5;uR+U zkzvQu+5+#NyRgOMjuz6!?DrOTOgn5_(<*{zbxdy_ehXge@W#sxXrA6COA#-~@$P*^ zt>3Q5GJ_K$Sy|Q6x{rR+sf@oIj3RZqEM0`{ioLuOTeyXfSbl)d9u|m5dL3-Vs%Bj1 zg|lb`*>y35Q%1+B9p0P;!Hcy+b`c8j`nsxWHJ$sT; z`OkI8p9@W*Hd*Q2Y(^E=AB6AR)VC)5YS}qCyR)}=Bwuh_yMJgn-X-QoFn_rdv2p+8 zm5w)aA9`l*8INtF_vcyo_9({D`lH-s{^-o_1lQs9Z(K8{H}((?q)}b+jcXyp%^a5W z?afie*~75x731Xt8#hxq{H<<2O!SPdPWz?y#}9o?d3kipZuBPsCmfJLN>VKB>l-Ly z6H&F-5XJT1th%VP;_iE^q1%ZvH&1V?oFp zLg#icw@Y`lDy$-k-LBFZADdTk|K7HZSdnqY+NXJvT`heU%r32+ai-d6)`gnxN#R}H z;468>V_24y7uVf4{%V$g#|ss44*my#iYSs-{|hT$i;C%=`}Po%kN|b$#=D<4E)$Pz zOE+PJDxj76F0xzOv}NJ^*hTQ@wAs{DUf##1;tgtaAXLk}0Ml76D~wU~L;KRfj0NuO ze%jOD0|O=lv4zz&HS@zGMX8~kWebS|4Y=dI6?@YV9txcenfQ!PLF&&WOLQ;H2OMaN z*VNDGz02H(_V;->%m>uD?dA)RJgu#*L+ff)kcB&jN!p5N-wE#PB@duv44TxdP)iFd zO!SSgP!fkRI^;}7&}aa4nz3|I%9D!;uZF@9v44kto_vz5mR9WFztF;PKWY?S3TbvN z&W95vBMQcF`rBH|TLAh0l~Yn8EQ_Bc2#c%vVz_hwxx z6mqKMv%4UnsUB+9^$i`Mp8BQbI+&(<%5$GGeO)CmUtt#~hP|hFk3yQr_?2W=4|?_B zlc@YAV}8Cyc0OXBENE#u8AQrTdR3gg=ayXC$Mi5x1$s=^YG4VohfY!$~wE^)}Amn+y>*l5gN^HC5rc+ ziX1(kJoGuqiy0ZEK=z1hJa*eF7sK0e@H}x4e7JJK5@JWwWh!UUAN;n#Vt!9)318cG zg{_<6^F{0OclKGQ9xvn(q35l4s#=Kf&f|o4*9z9>NS-Iwm|wSTr)M`iFt;faa=t7i ze$C@w_8IHGZaeH%v~J`*nz0Ka27@BC@;iGp-|y;{2Nx5vcV3?Kb{|z-ESma}3mcvz zC$zREHVvR=jSVr`?sVo8z}COZ=?Jubf88b+eq$lh9ysG8F3~kg={f#>@oL)yN_2W4W8HS9nCM_pm=x;!v__d820nn)8Uta@^gGH(Ps-vOT0Hca-FH zD3M~=80gj(;&}1o-BY|_`u1rl$@8dsVa~LFgzuK;sH(;8Wd!LdH%ppENCe?Nx6<}6 zX_lQ#hZ`raTfJeyzqZiXtM`BTEm=)I{}9?6)~pbi&N~Xa?oI8@=4tM@{vv$_U7TZf z`#udA^qdMCxe12E$4%Mc{EUwt^s>?<6W-QO^gK_iJ0&7F9}GpZNHg-X#`?#NQoFX8 z+D0;-E-=;DZLU`+MmA7INPge73CF%wcyD7ki2FpH?&E6juS-&%_QdQxRq4Ca#v61p zR#*SG>*(x3K3 zFtA1nXc)+(*O84gl9omVyPaegLbNsi_!!0qY!uBS37;nd~!g zy%5X&PN3D}LpQ9@-?N5KI`RH}(drzqWCAC>^63$^C(XBH+d@OpuTH%b5|;5ZaKjLE z9p;(ZdU|@Eq_-)^Jwkt8hO&KMlj@(>2*KZHOwB;5RyGh~*mbWj#1SHl3g?QD=;_uQ z((NBn#AL&wZ}%tD;>%}S41KTpd(w>Ud~Yvg_i;pt;yMrhC)v~ArIQse_TS~8w*`gK z$B$X(_(qz&SqVCNed@i0I>u>n4(eJ;KY-~y4h`e27ey5O&Trr4l3%7p?Nm|ags7~P zQqCk$b+t8(2ycNz>5*FsfHoCr00kF1}$6`_7Fz(X&08xbUUEjTGNtZ0aKVidwV}x zyo%4gki9nkAeQyyEw*XGi&YUaQi*wCRuM<3P*9`PBgPKGv2VO5gqnf~^i%49)D*Wn zat^AE{S3XA!of?*SF4h|9{$WBXTD97QjBKwwTW-@WmT|=83ZB={&L?6BF3(~EJ})r zaTGluFPKM<61Ql-=D!>u{Cz?ny19U{l5_aYw9n?2Y2+KWZ%RvLmb+M43i z5oxG7$PVz8ntlGRUwzmfl7|5{0bDZ~XsS*!1T=I%^4M{(F!Kh81bPqrFgj2w^Sy73 zKb}=<@jNQTNFpXj3N>Gj%RgNmV>uSPq9R3m!JAk$Tu3K9G5SO9^KBgIwumb}o}*W! zKnxSX;IEiq2@{&LI>~;FFVr(`EJ!c$yO6O10-fo|A z1Wb99;MW6V{p2NO={ZQa6U9|k99Y70ew7CWt=?5kePihLv&*e<#;jV;CaGcvmxg3h zbeJ|)Dn1H<6TGX`MZEv{bd#Y(PfMDUSVNUYlajFNK3Yr?ax)jaCb7O=VQGqSN;-DV zM#-mcA=#h#LrKIyQAdXl%+!)#ndHQ>o5tqNI?rbjdb^Iy{Y)S?!Kq-PCPBS%D@Jxp zx+rrLYi{ubVCwTbt?ot^qelmk%>2^QA(f^PGe^V_qBu(|P~uE1FDtSVs*lfOxcr?l zGgd9)s@>arfw|2nz#S5V4uTH*M{#G;A92q|=?q;n{<0t+;J=51g7}9?#Gbgf_d(S9 z8ma~F5BZc518dVu9G8a}kL4+l1b3U95W_cQJRFMJ_weIXB8>hLO%&zsLq0E#0#%UJ zag6X+-evwTmL0k_svB&E+>@q@Z6>xo_wB;QR-sgQzU=<=LqkI+#Qnp=@q4S*PO$-# zcQepC5TVSefsa44;I z)(L$^M}t@YrAWdzVjO0%ZfE|a_QWOUI>bo6e^UVjTv9MD0NYl+`z%NA4kQ0vYy*+v z!Bw~Fp?Ktd53d9!$LN3piAFKoV)*;X;5;iQCnuS5oCn@^;Ww74of^fh@@UV{`)Bpi z2RHLi>tkj&TEE=axV=MdIpsW35{z1qzQ!4ze*9tb>(~8!f|5hl|HIf@MpfOsVWTui zDk-oLly2!RMUd`Jr8_p=p&;GeBHi5r(y%G%Mv(4qIOFqw-?h#%eUDN~WL7bOx zP`|pcxIgwv?b8*u33MPkMA_tRaQJ=cJJ&U-j|u2s-x-^j^spAEY|yQ*eVG+-F)_og zsi{e*5BT!4%?@eYIMBaHyLvuh4njyss0;+*;Nect^Ru+Fs#z>%n~QifcK$s%SqQcre!PB)ukOlA6%LWOYWp^`7}G?f2I7!rZ9KKRznDo zcw5xgmLZqMEe-6?eQ@s2lZca%y`PuayGHL=<|e&Zwz9HX->YcYd;Asbw-Oo__;)MH z@a{6=OV@km(HwM5S=K+5^sBT=wAI?u8X65DltP* zOYwQy9ZdjGx(7h>t4w4_K@q}vOX9-IRmf&Fd$8$}J1dLxSb^m&Kx;cE$G_ z&=j54RRyF7Q#T zvY=8{a+?3@ghXELFP}Bjs_ZGM4A_BIP;B|NN}?vG}nEQJ_iD*W}`Wl zPNq+=P-Od8^cC#NB6809gezOY2pxWw)h1H2n5^#)1r>!~0um)sJ-9eUI$TmobV3OH zH!)PS(+7SQ{QMPWmUQ9iRl>S_nE{ub-+7t0c-w_K=W`I&>iU_0@6o2U&JZ{0FgdI< z5Ouu9+jGSWu8P^lI^x2$b7J;cb5CD9ueZu@hCmWH4cT4xHR+?ZJq&pw%8qnLcX;aT zZzp^=3vmselIH-%67gw1Yh|stE&NBSgq_!+3(P>C?SsEu>B3l``h0Ne2cFX0CVTu( z2B$(f?*Jy5>Ap#?%rjPeGnB>A^%w7K$I;<8DK)k%4)p8WS(W~Us4gMSS z2dG#U^QvW0T@{qV@BgnBzy{>9R}IdSgx&*89srai_Fag7`O?0;%i(R@qLM6u@_OH5 z=DiJGxOe%AyHRLCa&v>s$vMe5G+s=ZszS^8nj@G$1wA;-+-_y?%QHMse?c6bTY7`X zBbl*@R+PgAk5TjmF)bCP9!_oClsn}t6)$BtC*ML_EWd`?+O7--MIbzbf49xxFb4sKQ>|<^Ov8rvsYfJBcp5kH|@h2 zo3a_tgq&P}>lhsqlQEdete2YAq=)_(?_r-({Im=A>VfdtiIlfL^i6UejH*czULh8E zi1-G0X7XivZeivA*${9uzQFWhFY$Z*f%c^BJ6_XCJ>UJ|>H9)7r-{bfEU!jq!Qca( z0J}X@L60lcaQ-7f)5IV3?t3^mWWVw>4u|%$GJ2gmTN>>z%@MH3kGHZ6`m+$s&L-(8 zk1dvHu#HGkr-ypYjy9qS&pj!*AB>IdHc(%rRce^VUsx{s-- zgVXe=J*02hW;M1d&pXo6wA}Pj3F56wa3xsl*UU=G{#5?SVXGk{(!9;u?XWNX0j6oI zb541Q`6DP5<-i+%<&_glRO=<)Pp*b9%gqJu#!8Iy^duz6Fg|B&o`?H_dy7G`^lDdl z>!pqYndxYrJHuYg!=qjaJJf@5L5AMMxPyt=pN}6N&v#8f)B5M%(9J;=5TYJ4Ob(#Q zF>MJZQIB7vJO=sR#gWrA`BF+SFDV+7<4@Z*aEOY&d7K`wm z!!M1W-PCvw;<@A3M_$D5(Trd9-{a+`Lk}Jx=N(P^Je+|ea*Xa<9OM(&DWWdzH;4!v zyocY)n69UCVRuW!;`~XDeM@$VKIdWkF*&bXI7Y0r4I2m;)$RYrNaBX|d;`(ki?I5I}uroykxl{a`Qna}m|zSZQ-MUz4A@ z8kcq`sWyY?8p8jH%egy$fpCMF=ZF}}Qpn97t^vQjvh{WV(+WMQF!{r|v^m~eIM1|g@2d(cAM z&FAa^o~GH)8m+jj2#RZp#d)qdI5+^eGUz9Lk{Q!K8-J9A`Qz(fqI8p%{uC*=a#V7` zu*5_{>cdo9e;&rw+0zYj5Cuc;|MeV~nKQyF7VWS7?qW2|dpHEP`4&K!{(N7~vy%zj zM(KI;NxX2`;Qm2u*hFB|W+vmESy^;N|5A|pz6yn*lXjNR!1O>Ru1U!Mf{$|~NmjJe zElxy0pntXV{aiD_{QQ?8oh(LC&UxheER7ZV2drh|1Jj5bf4)VO0i7KGRQ1$1L7H(X z95^|-xm~sD##13W+ru!iF_2sCtS^Q9tl2?=BP{3FYq`I4+77PHA3#JuKvrbDHRW-l zW^HmU30~nn*&%;~Qd0JF0rb(~SQmxDoUn`e*j$~_!;Dq!j**xt5e?Vrcm5o+uGt3! z-2K3>y)V#^3M*EaE;Q58%WFrb_rVu+_G{DsA`!6<`R!MM;K(*{~CD6(`+aF0v312yin+hqukw!ilC?uHbNPbLK z(YPY;eY#tTueT+5B4q2c=twh=Px{UtqivMURROsv`4 zu?)sQC9``R)~)41=Z0637b#fhNRrh@4WpX_TO&s8z)ky+i!-Ql^aQo?w)%ni%mOd4 zFQelCC!tfJ>+Tcr{M5o zT1)TU+_l2>+4b9!>tjEIvxDl45d#NamT4HNLMtq&SGPR1j#dMHwO|cKd)+=nn}R6m zZ=w5eNA7T<@N@X_3SZ@UX8&XgrB)qcGsb9JTEV=}0GF9hSP75I3$zHsij*zKp--qi z3(4q`Y(bFjo*B8d#fhu+3hIr&NwS|;in^|y`ZN(xSymGRN7n*~@01j^e`QL-3|Bhq z9u|@h-6}dB%^d%XLHTUY?RJ=jzxFM+L<9y=85q%4BUBZ+x`b6deqA~H)hto3*F?Ud zartDk8H01O5l36|#G1L5s8ep*Db}E}a7f!=jdLk-K;&hW2p>HOcbW`6%WB*{9pdx3 zA2lac{q@(~^|&ufm80KZCsU7jYbYrzt3v4JZyYRzLsDxDc#ac6)_!bI5DL(?u6LxZ z9GP_mVO>8w`h?ibRex=}T25<%ZZQm5Bo&zvi)3(S9j=tEjt~dBI&)_VK1deU*C!4R zO2aLCoylPfoh#~8xSoPC=bz8CYt3IwFOJ=XsK)==+prj`}LAjLlKOD(Fq_8^d)_nv-lfo(y%yZ?zqOroL_AcSw>Xs zk<-(JUcy;Uw4C08Ek;r(%hah|I}>I<%G8k{+b$WyR8|Kn2R#4^AtBjKKu9R+jYTJ^ z;SXl-OcLjlPhn3eFQ;2tTKerz>&--Km1WJEI#pwR-6^})`wgzFW1c_D!;%Msu+;cu zO`4FYUxDO(I;BaeH@kUhcD5hbjq*l*Ajp5@CM<|F_bAf8%TUzw5lL2eDf@Qg=twy! z&nQQnrKdc=OGvzD9j{5G#S@9Q@e&OQIR62IEIqgNw#3TLEMr)oG53Qm0{~V5{^-@w z^kH-BZ9^TxK*k2Y02K7&LXeROIC-K>&ogKl-W1K0(>TWBx#5Km5q zs_>99!s+vG$#nbqA3VSC9G5HeyRX{5`mC-_2;whJw8x`9RpvG9-L1omI8qxEN&OClj)40414w*}? z3*vumlvaqu&sHrh(aPrn^bvr4?SU!8k^U4YRV#c?l z0%vIXWegbxOG+*%@D8VAmo82W3Ni-*3MUcYQvqC>Oasdg&8?G z46q<)8rP4iPCcp^umYGXJ`wu>b)wilu10{6v5X*suNaBpLKdFJSK%~iZo%F~a7K%cW zzt0`QMa%X*V)zop`9i~nitQj;#9??EoH+*zGDQ_4--3cD{cRFdZoztbu-G$9TS8EH?snwPeHvDU2oUw`j25X95u>Z?Y5_^S!DC(X{z z((nQW^UjrN5@!ain`2pDuMc8LlSyW8&YU`Jp_{N1KWYU;kU_0gYp$d`JG>wOVm&oL zE6h$o)<{*~t35QgmbFku-nDO(jVCw5PEI(S6&xh*iRWm-pe>OFCm`Cfn5x zr%8b8gbXbpi@E(y^97z{p{jjuxX> zh8mtSBvI8?_Xt<2R};25uF2}M6tg)>-f5E5W=!mYXyuoU*{@7+oIhFx?nU3ff1WNY zi92M;PFkws^$#g+oEnJ!slUHzu2$_AuX?PfrFFv+oM{Xf@CLi^#_P3XI=Ehf%M@fy z(YdSV8I}2r1JhD;c9p5|B=8(VEzEfdXMf$_jN(Sv#-cwXfif{NMg>Azev=JjFK*IA zlBS5&F_4L-hxcInCG|JS=EHj5Oc2YFOKxi7iUo*j?;+zx^)OSR?Jk`FwqHq$FBBXo z0D=V~O08R0ng)ufDfdN!Y>IvB5LygedmMg@fRRM9rA%^t9(Cn!R=ZHoeS~X=?UBA}UswUb zDy77dcW`ANW$?)(>df2orIyC)-v(#9X2aJ*m+RpRzN5o^k;ccDc}%l=5N)5gNr_K7 z-CGB!r+dCjLqA-P{>Czruh#kUX zv^PZ;y(VwVS{V#~zic+066pR^#!s@>@-5w61jnFCq|Nt6IBwKCG^q1EaVpQZj&#qP zWB*T!Kdg+3>mK4zS(?8s7~F;@ikZmXJ<16>?FsfGZF?TQPh#7;f6a8$K00^pOcX=@ z7}-}L?B|tr6Yq9u4fwh2T$2=5sd zEOw0MkcJDWo}QPjhU--2!v^woi6qfeh+ySu-(w3=b?)}9Vo&(|}D zm7mSu-)w;EDq#K8xw3DRZuD-cncLc$Ut zu3R0TU{$515YZ5fVB!2F^=x@Q4Wps&m?;H2FfcLqH8K`r>)J+-?OtF1z9W&>A7meWXPSwbjj#+(ylUcLf2Fn9=OVE zgf)?k=W2uu2PWWd9(?qDA1;1WrZu?k5Ajw6 z?*HsO8x_GZ#Bkf&*~uv=KppEp?&`C;llMTV;99RoF}Z%JmWqeEUixwGI)KRFfyciX zO5A*ilg@qgB537`W-pRl>TZFD?db1>yZtZHdpD}Fnoy0Th))A+3*U?_yDeX>eRIcA zahYM9Om9V<(@{SeO|`yvs{Wg5)bw|ypvJyuNOoAe%V0zxHLikWlon@%24gIBc{O7( zk4alu&U9i=*KPHx$@&-V{hxS|)3H4}Fn92{^0!Gc#)(4{8uqnr(gd zaXFXrx~fMzdho*a5w+5Wd3O3954L!|m_0|LmDB35i}X&)I^4PG{x9XWU`gX2|8G#Z z-yfPA_xSEJzaddf+yun+YplO3HFci#@;w)L?B?_M0{Cj-r#l54RMhf*{dvRA!BJG6 z`IoNGsXuZ^lixDGs3_*6ap^jw%(5%!0uwyumUrYe5Fq*M4G*C!1J-)3e+o&*OxsPR z&GeKa@ab$uZyqv*6R>Q*U4@AEHV0+I!fOpB`9jEp2g3rnxU34xGsSszIaleIRQa?s zBu`ucO(|2sxATJ*PC3BVln(^~9t=C`E|erLo?dG$fo76z}M?s1NXImp*}<2DvSmbfo%b75IM_7mtIN@}9UuMWrSPysm!`>n7~I zxwZBF6P30YA-lKABo>TfOn_ zyPZ7)g5$}#IpT^GW}W#TE%qT9wN{EXz}BIsv61cmRdEHD2fdGtDM20q8f$M<$h zYB^IHmlD4w*kiRNq}3ti88K(rgfRidhxprM0l4ynosM#HjM)<6w;~cGTT1s0-|#}h z>khQ{O__jB8gaMRV)&cahjc5+UaU)NaAiL7&hPssz4&RsK-lN6ZsNXNb4D$?pl zZnNs2RxkUMmDplI*lMNoo;r}9(UqBo8~IN{P4iXH3ZLw%9@jp-(1IqKGkIu!G#&m{ z^^Lb0PUpeFYv(t0#|SvW5$lUKnWh3E(YJ!RD?_(4gQ+#*M$b^7DQ|N~{J<2UEIjkA z3XOW+%!QmC<;;C@bPl}T>s-0y6`@rf@^o^OSm%1Em3N}0K6>4n;^|9e8#}&nph+2^ zWY=E8INGQ9Nh?RRgkegGiqXe*t!+jIre~H5b6EQ=EqeBy$goVIG##Q3O?$M#XAU+x zgEQxsz287}+ToS&RvW5<{IMisllweXxj}}4Prk&}w0!lIaDu?&mTmq|H@Z6(;b1P- zOo>_4u>p(%b%)Vf9JjMYewKxGs(D|Pt|M$5xVF;UDR|k3z9z4mwH^FD_?B`FKC4M; ze4!`$207A2qRTU#WVV9HG!3DCSgOvP-MoNq<0Z0>;x?j(mP3~+whol6E^1^`&WLm( z)8t;2x8>lBLFA=7L6?En$gs+7V^`T|`nxIT+?%~%9>um>^~;4P%JM?bP&_D{4PLvD zm%_538Re4z>(J>v@Xltj{1>6mrM$E6axpbS<^0Qj;!ufou8e)y5yC<94qOQVk1Y+! z_>$f@$?FiO!e@5ddOjj=n^P|yyAzaTt&o_I(5Gjq+R{SR68$>YR+YCur6(B-U%)>J zWC7Yd@>exvNmWiTVoaxE==|D*Erdt9mX=G7@_%sS4xMC4_3pPV!soK6R1CJo$x{)s zh3c@muSEJCLRX7jp!jJdK|_C_hsXeyOl;(4KK{P-er?F>rkg>%Trl%&)Nbvhk9-U4 z$F#U1AR^UcaA?T=eEccr=TG6+UIoQdh58|opW$ODtGmC-(SuoQgox3QK;5S4R52?& zm$OkH!LZbjYK~J~08l}QgO>|PHJ3=2^+so0*$wW*k;@cQ2V=hPJL`VBs{@U+K#rO4 zF5sQZbg$fbPMM#$`#Z$gGcdX1{XA}@OA3@KT=>f~^DhFyhrUmxpPgPD~*ol z-Q!G>o~(mn>zIO)Me=qFmJ{Ya%+l@1W49%U&1hCWslN0D0X~;a{wLIqogwrX9=9z` zRGjJA`ZC&$QXp&jhncr1XJlkJd_#-Y?&k%2o5)5&$$B z$Z7!lS8XvNk+-+B{BtU%MTg;fB-zOMf@;V1qXaS8xGFDN=!}-Lc+Ge5i!uvs!OY?| zn#@+8(}99(&_uzz9?k*RxS48|%xyygu$A-%yA_jw^mOWQVkqW}E|eMA*g;?o-hSOo zX6w`A9evaWI4RS|++`AhtPddfKxPAyLw8W04VIF&btT1J)gVTwsYR%x&(Ju2fFjnX zNF~OlE1B{*19W~Jhq^G}=BrT#!SPg4O}c%Yk{%B@Zr4~uC?!-uLeF<3-1tA53FsYo z&Tk+xsu|F8c@Z!p+>t%umNiT?!xPy$3W;KF@8MOg2e+LFUhp_~{do(p#iU*J+#~`X zzTEW2p`8_#1cB7$os#dLslcfNqB4Ovc+HnG*ESud^@bX;@3#_<`r^rc{evvNWS&53 zzmiuzh$#a{Y2v14ZqoSczDTPC0y9o;2oH<3OK-00-ME0mAOdm(l&0%o7&G)als;0a zdMW07olS>y{gwS59o-`{h=T{PWqqT-I5>A)XB+SK<3H;AB+8PWVEyog2KohY>z`a$OFnblk?R>0+D*kNnH++fA1W zVuK1xo1Y;h9Hy8h>Sb%WQNp`dWStW{I^H^c+Qqt& zrI7hC^MraKiNt3W{9STAwZVA4SPaV#R^IrWoGO^xC8Ce8gW=wozNl42Zn;!owXj*k zMcv*26AMk>4C>K*Y^ZzWKDv(W*(8YI4 zyIYITPl~z}<<&tujYG9)^4>-6Y^#aCtorptK zEL@^+#5PiWOIf#8NvPpgJ)Z#xDV-6EwyNvudX!2K1d5AxtWqqIab>xaiZ;h>(#BPB z`4D6Qv|C>M#uDZ&#P$XPEO!O4#L`_XJGiAlcTS7@Xb4Yw{eq@1dr!c`aYKct`)~;ab$oU zOJ_TsymHYt+chD=Wum87!wyO5d|gd8j-*L@wplZ$%gw`shlT`*``BIW!lW0tH3$OK z+DEF+h>qHkG;w|}82>|L+vj7RJ>y5oT&vW9JBDX_6T?0@L`&1^pK!>`wny-PwE%>v zx4gDG1-nLQA<(pwEqN0cL=gyfUxiwUr2rEmzO1ug(z6+AQjC4;fqzs|ejR0vZ3kJ0 zNzW(wbf_xd$xa{T2;bV)8%cW{^ibcuE5AoqTWak>1VBi-9Tb{FkDPFlhfS*0mk{uk zpM|D~dEwEjUzLz)`ISY_BH9}M5Qi4I-f19Xkj$XqzE`l-&HRo0v#t&p!Z#1yDp@iA z32RlirBJRnQ3z#;uJbMaZAlN7lBP>ww#%m7Moc@;8dgJeQGd-+P-j%necMLkDfmlI zae~uJm>i53^@n6sam4p%m!H@kbb(pu)!QUft92@Qh9ab!pCO^*Z(8_~6`pcVFC#s* zf|k+)Y~h52gwD^;*UqrMf0E%LO>5aclv?(5Q4ER-s%J?DO*n6FyC+h-t|D|V&XH_| zd;~i)O{aa1xk)8q8y${u?IM3rz4kO395xK{9j~r>BXi34ZtN0UzDYJM=^hVRHH-7S&Ejmr<10*_cUvzLpYcmfOn+J$T?3!Y@g#pNzajiB%UMFESWNv-93$mKZDk6j@m zm%Zyy-ymGB=13~m8}C@$7?x`p6=zfR6EKC&{pVKBEi5!o68&t-hhU5|n8U5!vR>e= zFjikzr=)RZ@|zcs)ehM@YC7-XwTOt4-hu^}lA;9;-WSoR;X4^Z;s?BQGU^K!`4dWG znD|J12P$gs?0TD2^#ppaYS>@Vt|rSivZS0l0Ov}i@GbBBymp=#sj0)Fs8@&~?b`~n z1{Uj(-ZzgKXlu~*aMN%^s_=Dn3C&7SKCLfM9VHNQS$nNl4JjMRBcm8T(Clvi0D+$m zg+?*;tCLIOQ1S^~!98rM;9&fcM>TJdx0aZLUoq|s@VHj0&yBxseTBKH4CXrx4I%)) zgDFeeyAa0QZ|2OR2JhlQ9oTq&7*K5}_F%?MOp)clBJ$wm-Y!&vzUGLI8E|nH>0_gc z5cnptpADB-(#lF^kh|(X7l1%N;r^y-m1fokgEmSDk4;`tTN*x@@WAoib@Q+^sS5N) zGNTI*qowgY^hnWJ9Z@LdtEwDd5Tow{*;#u9e^OuO{I4DjhnppZK+ z>dGmu>(d%8%j}iJbp71`^GaBtuN%f4+47aP!JqMT&Qk?1v-6_T1Cl|QOy+82(`&De zpJuv)lShw!e{PnHN4%4#qSOyDcZbXl^%PW~;~yY=YmVBe38!T$hg$Naxc1lr6ZEBmhGWT~ABR+bQZ9*z$cRlC;zG`#GyKlCfE@%0y@^b_f;*e8dD9mZ z?`yA)F;)KR4!0Qe}(kFFmyte_b7h7+f|Z>9irxY~4>|yfc2UP>Hu$i|~UQVKLUfUVd#hhWMJ>;WHNiEP?UV!pbUP4UMTwYlM!& zP4N^-3!kld?sRXTK+qDe}r8{4KR*?xi6rT0?dcB_~=quJocNhrpT}2HhL4K zL)NxG=@4HSp>JFBD3@`~kyZqi{mg8T~(qh8Ec z4|M(efyHyvY3R;~S);+DL`DNGS!Ypq^2&*6Iu|}Zj2ze{e}Yn19Im7FG9qXdo-+Rb zx%7Xufl@Oyb#-~*i~}RYH4#%Z4&R(bpb@gAOnffPMPPvQ(>pGo_N>dxvS(sU#LyiV zLG@Juhm#Le5$tWa5q-m{3nA<3y@IY=w+;w6AsBxd#IRlzfGvHhMB}0*2Gx;_*d)9U z{cS$U?R0vYnjnbj8-PLv_xeWMV*PCfSj1C%ZnkrOJ}sMNN!bRo zQABEL5L;z3MJ{+p4>~hsT&O53ryhTAEG0}WT5F8)VZp$_027YsQZqj|71%#64Y;NA zMuhMdQxMhgt|c37ZX+G;Nlv@P9t>AkI|g(bYHtlQMKZbaP2Gw9rMKm_oBJ&Rg+kl8 zvV=UjBQhccW6#hQeOTXOXm-8wTok7mn>cy^JsKE9EPt=pqmHi5ic|{NeILCJ+pcB+ zCAm=`(iV!0L0D-y#V{gpB>3~H?dYT%PXW-Z9iYQy2p$#EflQ>^F_^%3w_!15W34e6 z)mU_hWLrbpSB48u-6Hew4bqv>rOSWmpA4?#N+2m?Vri)d;KQhs8NTVf*|YF{i``X} zHM|npNQ;3<)qQbjkcpY7aNZDOXTcCSrIriI7U~~LfG;d8g?s=%!GE4%iw_uweMUX> zGO(sycNxOI2m$SCUcYMSSR%7`nOb0{p#>gq4pCqen3Cl$W8G9!u0AP_vZC8=us&SUUFNV0*kCG0wTRAY=GdzD#{r!K5 z21L$|Tes48HX)~rOB7-a&>h0xZv*uVSC_y1d?+FL{hUZH+#z-<8qbYR3DUs6nZnZl z3>GCcaO$-CmKzN5)b?RY-?>P#VN#0S4xUwbFsqO4n>z?Lcy;km^m^*p6HNvT(1~c{ z?{-I_s3IaSCe{M924Xrw+f*e7MqrgkJqw|rjVWl%sVou0n#<0X9+RqVC1?8{(AygX zpB)$K<`U^3pUp<=kS+~bKku{m&aB>4hT!c-N=I5(iwgds6#t4K0bc0#=PS{_D>mRNLeuPihBU1Bq@j{~ zJ@*43%<-1U(^nwCI|g_0rU3olO7GVsp#Nh>21T*#g$UaKgFkNQ`P#nc^eJLzC`0Yy0om{3H=K!~*JXW#|wBN_4f%hC7m*bT+J zA<+i!5eWD9_Z9WuyY#N3cqy^j4LE|+1^L|H=$1Q-eZ3L>rj&oU2w@*~%7*wm`-w}u zA!|Ln4;u(b9qer9eg~}_H6Xv?i?D(y0Pw-;sN}wdt$v>l;M!UfyE3 zHF1Y@QCs!3MaLnzL%gehb84D2#=c9R(AC+b8FIaWMsm^s84(25UHk@FYaj*{l-~W& z_xM*sp>SGTV#p()xKNIi{v}L>lZ0znWm8TtLHE`L}xSb!k9(?F*G^lorjN$`=;o6vSd^vH4CYdQxC&eFVbp60k9ob;FOh$oKa7J(Wk?RM%x2FJM zSQUU}OtLBZZ)86slT5Tw6$?I6EntM4I%&TzHbnH!{2tVeW!mDdoe*~dgx%>|nVyji z%N}74>%HT^jRYJ{S>Bg+w#_@H+}4^3&dyvScXOlLfGEn#`}&az2r-#m7aeE~d~T4h zmOWYP_N@300w)^F_TTqLk;}b*kB3Jy$>FrE2ui^7NIymLbX23v+@_< zpvK!{Ik0rTI3Tyu*3q%Bv7u&U3_Drxt8v_r2H%ztDTKoA}io0y%-heeso)fSHB!C@e@%Y$E(?PcSZ@h|yaUiPa1HU)32JPiE6 zNn7jBLLV~avvnB3qKD<$YZKup4*ZP#!}qUP(Lw`klK)ye1)Ki&&`A`3;vv8`&&IZA z-=v2tAYc@BjxWf#c7dbiIZMHw1<=B0U}S+CH&>;n+BO9pB1jX@f{EArUBvKW+lX*C zh|xC~T^$haYy$@7J!ytG^gKH;>l2o2HTxr4(g=dtV$7OF#cI|AtZ6x4(2`|m=Uadi z%jBOX-j*qB7H~@Pd>eS!g7);l=n5wJpBsV)FtcVq9(X?BGH-M_lBUrr3sz|gFS6#c zgi*ivMl*yZ_i;-9?Ir-8fzU1()c}uH+$rd%wOV= zaBBQPTELJQv}^4&Ee?>R3>RcTW2SiJjlVP?y)FEef%g|NuvajmGOl>^s&^eig^IG| zXS8EpP>hNKYIP+3L%auu;RIUB&(t?L^hO*_9bmg3d$;)JR&}cRV-LDbX-Y&>7x<-T z^Z^fuADn^YR`NX(2FF6+Y&_F5QiR*1q$J6pyQ1vhz@8)apYdvA&4f zg5gs`NySfz0W1@H?48-KJ->G-3Zin+ackFsIR2qy(WJQA5g$zV4)FzKT3VFEwwgO| z>Ef9x`LZSx`4N$)wUh;`F=`roCqH)rv~m3d)X!>jo%{j-R1CbDjNZEj{S1Xh$oPv> z&Qxo%>6&t!BoT-W4C!MXOON%4;dv!`rodN$#baE(;=|ep9`bC8LO$-~DKENs1s$Cd zM^V@a2{k{rR?4Uog5Cd1VlWZ8=(Ais|BgcsnuNyd@OzgdMYSHDi=XP5rafReT#E1# zwK79ixfz|~vHR&?!sO7Gfb}~zEo}(26!mb;=yriuEp2B958Nu?>HHvgJ_cQMT`|zC z-**@hd4dP!R~#OmpBCyd30Yd>&7DZM(xEs}!XA92Jmp(IdV(D$j&ZKXqb^@V^!p2y zDiDv?$;taZ1tWaH7Y@IAhF! zb_1XX^m;MIbW@AeLmb4M#_1D4cersV$9}q~CXIsS?^QWmq}(*9H2?+tIihW5(O?b8 z8hYeN$Tl=Hqy1waV?@hYvYMAHFm;!mZ;CZhFuKh{GgtPiX9Wk$9e|UT&fo(!Ga$VO z4#Fyr3x>S2hEH7{Z(^zvMMXYhhUYa$>j1tQcx08gMr6IMYT^B+fYeDZV+E%_MoUJ0 zizO!3|9!9EzkoUPuknXp|Ho|SH+ul(pFB^UD)`3$Tqnb3d%aP|3Borv#>#vSOZlDn z9p2+XsXY&2Ym<|upXO^HfMT!n=!%h#mJ0+D*r^WKZ`Yz@gt8S!&#stmg{pGdHAHs* zOcVAFa_Z=SX;uEur-SO%uzkQxK{)hof|J{BB(Kfe0Peezx%J{ZI@OPMN6!)bJFVv@ zTi0EMDI|>6)um!;+~h>vqW=^@gp zv&71kP@|v2x#ddbJ9`eqvT{}fHe?}-7k3N8!-K|U2D=^nKmwxfb)n2Z|b zkmEC8(c=KO!yp_DPed3PD4&G1>#eo!Wt!DMwK@o&`A$a(R!pAG_p%5ERL+xS`Ho8Q zBjk|RrNCllqTs&+n$g#wTU4VV zZX4fP=Eug6h$*;ODPJ`Zd-0i%v1j`?tc)lmTe)5dBO#DCg)%Q|K*&oc<5Uc-Z%(5o z5HJ9o`OoNm+*t!|B}(cty-iSU1rWrV$oiBF)}KWna>Sh&%_`LzRY1|=;C_%RFC@RD zM5ah5Oz#_O3L_y^FmexnQ7N@UO`e#)(Iyk80t*Ag= zZumA%tLAbujFtQJ;pi#!U?Gfe?VC{3pP;j*jYLnkn~j1so^`O1%ZTuFjx^iZ+R{L< z83WU^pTH5<&F|lPew4{vt(-yV0bT568QYw(78Gm6Dhp5v6A|!abnLGi`}C z+f>%Wu=40>YAW`HXf;MIwWUTf`b#9|yG}HDG{d(L?1|sMai0XVIP^xqp>yQdlkkiddjdxbrZ)X zNE+$*m(wZ143B6zaP29;eyBw0g<-ilg86ac2(?D&u$ycc(oDP&fLw2m~B(H-d%2{$cK4xB}U4gTf*JP1AurPtEczCU^l%socoMBHYzeT5-udHH4*3^^+hz1hsr*Z8y85G|IktUK>judxe zbpu=j;&sdfV7oj&n~++|sU-0?MtRLVVo!X`tSe2AA#erZ;mXY|4KL6zt1^Q12Monh z$^)`d++>^9*U<|+1U-fETNsN%(kzw zZzkUtb=z?iFDYVk^>f<&lEjpVZpKiPb~Q;8%qO}MM!=tI6m!BF_dBO+lN5`0TeekV(JyP!1;|?Z@pu<*3GV7@rdMSSeX_Y zYCTV95}2 znCcFzDCpfj?Ps`pkzU;Nt;Duc4J9@h2?#j2$fEgw`4aP%*oKZwb2~ojq{DuKf$C-906_ zcP*+IZz!1nN!1(!J@atL0-F*uC-+#nx%3`=Vp{U)VuZeevSDR$@$ch#3;*R>gh1)z z7~-=}fBThqAv=FJH-m(;&XG{^ej_@DPA78X_7?VyKB$ILK5{wAHZ{5D9C?wl~pL=TI`imao%v!mD36>@#l5q5q^}FlD0KEt?yn-4i7*{ zpkU+35fkd8`ic@38hYZ^EEkAkAi5Sp5qDH6s}PsNc4mqN$790?3Tdk2a)CDqjOY(><=R0YPCwYhS> z;7a$Sr69BbbtX8Bv9Pd^5d5DX)BLg?N@B%U|Hsr|j37JP}{AJ$kAyDa)1)k7U2jgXTiKN-55FEBOEg8Ilvm)%|L>Q7y_ z{!+)$=T4#%6JjjN<d2Ix=eGh-2ceDBJJbWBa;Ag+;57$TwMi2VIg zw^1;!Dbe&jgzLgh@O6WHSkHIH4hjbKXjaH7((WREL{NHn`}d)2H|rM}T=T?U>#n7v z=pIRzI<3RVnuV(*mx0z|kutb4u zuEWDapyNM2TA~xWXY01M13JslTmy0U|J4EK*ii;96@E+bj_U`}rxCa=<-##Ac?X}WrR5|Qnc~);}^?Sm4_Q?mXx&v+}z>Xl?sSV64 z0-^+Xfxr-MBK6V)fLlE}QYFTRJr%qODHmKf`|$=}1FaR~WJZn0$-G&OL!JAC%n-`<5<`pq_K7x8QW@seTIU7VdI;3#iOiji^%_-J~KEVQ%;YfMOtco}KeiX!K~D}lj%X*`mZH1_ga z=@TGaY&gG<6ztFoH8do=CzLen!SlxwABL*U1Rv4wQ>fWFb)NbP-2@~)KINe6PthB&+ z&nBOG)2PWLe{;#5q=d)X?aWTxE=Fp4^mJ)%@xX|ei7l<#tb6MWbR$SWxLYdTKq{dTRdq}!JD z_b)A^+39R2#wr$~K6g zwjD2=f*@N6AQp>DSp;pm38rAHPKJrbD}n=n2KdCL~L z1i|6=+#V;X1R+*n$nqx_vk!)rA|(=AkE+1Zg2CXNaay5IG`~=PAHws=Y~!Q-4kDU< zd8GL-WC?fxi2rRC5188inEjj@o2iZZQ(MigOjE05$jI-qTukDAEIplASw#i7iGaPW z!>pk*)~8%-pEUiqz_%)cAUyD7CfxjBXuOMS+~FLS<>LHynQtQI>)F5J5rKWlv-ac9 z)P-nH-Y5Q)x{u1g5cGDsWYN4E zK!iN>FhD&0DDFDN0Z~aA<0fExzsoQhk!IhGw&#E%(fhl{CRss+r ztR8n(;`MC?UH-{A^>(4RdlsC7IS4JQ3O_bk>FMvFLvpB@no1Jp^v_HEmb!QOO~-Up zbXt3{Z0+Cap*6EH7XBpVigRlIJ9Xjkawj13yy$4$DjLnt`w3Yf+MI-vXTtLw8ZtRR z7ni;c?0MF=60@RQpzM!O?T~JgTzZ#nBK$7m<_**#4q{kTdMC5P$V|#aOPAYni)|iB z#kZh)!9c|2+6uZ{n?N~7oMrchx+Zg*Gv}M);>D7I9bc~Ax<256O8NJd`)avvFgT3JQt7*ApAEsMLnjO-V5 zzvn%W+ZcY>U#M;{A-&JwM*Ns;XnspzSq8y2uh`qiGt*NMUZ?eJ?_nPBgZi`quBfeL zo|?vB_i~4>Y`sEpU3KOG3LljOOJ0Mj{zb8#)Mr2C4RMnZNc%XqVY$ABMr9h1K^~j{UDd#i3W3w6p~4+dh#ks9wg?JIg=%JL{XtoFe+z!KADj{iP#+ z=99!yJ$A1w7@XhIvOL3;k1H5DOCTpq)7f~=y5%|o95*;Iq`IjY53tPsSHX=$WdXHc ztp%MAPrsQ+^Rvz`d2{LdptmaYd1V}d!;R(_AUUVVPa`VyfD7U^aeCdU&a zG2!*9IBFkuqmFByxtB+s(0Hh7QD5J85gnY#MX;E~51w@`n-qu7K1Cv7N%U`nz~~>n z!ghu>%61>*{p~`f*9X&U3Z3gwSUuP%vPKU~g%(^8HE3s5^nty-F%!qn- zkOAd!h{nbnkpkK)Oe@9~^-aizr?;O#mL7rg^ADsBs^0w$g<<*S8d-3Slq3zNFL{Qn?0R%DanUO@z@jTaf(v^*qZ^*UbEwi!(tmch_z zy${uUCA*(fAg!!R@S}$#*+8r}Fsnn@0PCQmz|h$hgjg?;R%*hV17L>1ONgNxe{cu5 znL=ltR7(H&fk{YCU&+ZYP_^3si)uXWXy`c#(#{V-cuhq*JJzO zD{1k6tenSc{(<^bN%w1YmnoenQ@KLx2oLG!^r}$(`ZhPw!s!>X4RGK}?_Dkzm(ZsW zQuDIpjRI0oNXF`uzA4TCdHsm0wn#`W`%Ocsr7GD06CJXHV@6(~K=m?7UjCxF^(i3e zV3rI=icR^Q!=q8x?B2J{PP1AO<6F;L0MrD*0gdj>e~ME|O&CzG!k$JM-}gBj`J78!J8aWM)3?k#N+mihEUBTr%w(^?2L&0{)i z302X-7G*P9=vjvE*_fF{#%}j6^3m#EcT+9_8_Q0G_HWXkDFCtpg1}@9FiG?Daq}Eo!NP)A)qU8@-iI-v8Zwkgy5!Fc@ zL+_a_zTXC+^elwezJ^Tu->+*Z)jm`@5j(S_iL_@7diKFy7hFz9D74p2-`#c?JpbOmP@ZSBX*}nx7rKQx4rFk19iSlAeZ{?Bal!D> zZ3@z=jGG+L>s0jd5z!d^*ZG+K9!fKr?0x6C-00z9XThK+%^2@}*Optu(5Sjki7WEi`q{r; zmHM&4v-fU&++^HqK-uNlH2!5B(ew77J$}#>a)hnJKFfNpnDlm0R;A&rtx4PuWaale zj1-SM#}l_lnw9r9j)xw$b5aWp`elqXMgH1+^1Ac4SdKBzV71vndBJDAm&26flmvp4 z>HgZiOp7s971z#=U6GdtcG0U9c;Y1I17e{WZne|_;}?@Rk*3oi>d1Cmkfm*!Z-mX- zYZnApX#U@~dz-ynthZjy!8bk!iE~e@L&u@4ZhxA)i?^uYIENX}NN3@$^>vRl=S;`% zocI~Y&Z?>l;K0S5&NQtFv|jE4Z_!SZAeOt^wVxj<0aa9(;@|K1D#;a1Tth#QRm;`~ zXWw0>Q?@o9DE=N4TLAfG9t(T*7kj(#J9B6Isdy!eM-9sC{2_6UIe(keV1>vbLMO)x zn-4};_%SE@!&m%k&t?AaH4AS0FIH1VV21xe3nHvZ&me9TQW3-ZM?rDW595VuCl$`u zueM-nmTODz8wJ`NG3GXsUZ8+H$dilMvQKbq8hI`cNKSew03Cq1cK7xqte8rS1wIg1 z5TaIPCzobcW$T@?&F=93=gj5{>;`9-?-ps%?b7=!A^Ma5atm zg{?DOy;gQ2oVZ<~60ovKBT0mO{HBaoa90WG-RN7pr$(K@Dw#Ix4@m^2TL4K7b79 zRpryvaUF+7}w6k-B7 zO?7$60dJ$RT+`V`wlZi+b3Z7V<7>#uZScuwF~iLzpD!uRFH?kWm zZbEU2y)Et&rlLqj=JI6X9#+r2rBqbn7#nnKI$mAWmM^?sY}Gm8K0Wf!vL6wvX9`|- zr;-RKw%F2|wbqkjx;nbwt%>`(VJg4+POaGSVl*Zg-AltzVS3ZLjh|GTx=JKslH`Lf zFz>B^0bL@ZrH$3YG~zLNoLOcbS2j+y}WK`A47Ubz>!O+L-9 z#DkNdzHAS)J~g0mZW%7HN}a#dCb7H8V|KALR5g9>`~z_>LWeFsQe{9~tM#>+0JYrS z+!$1AR()q$u$n}!C-wR8Y2n$AG|pd_@i{NTrHt68A3IZ+A3ldKW0t|OwQHM%7i|j-=LcmV$FjAUCMzwOJwTS{0g1lC!%)^=?9VjdHm){KQ2K&= zNGWB3sefYqb2Ty`oyV22;wC<@RQn6ER|L)|G`Lc|c;XoQ$JZ9ce4P*svL6ub0ZnXV zGrulaknA?WBC{Gxad|0V;exjarEJUC4R;cY+t*T6mA9~<$H935DDJJ>+8f(`9G^698D18+9tGs$x=gX6M9P{TTWQR~H901}9nEsi`6; z1X?2U@+big#D6|5s&7hKN{an{J*yvI1A0H*lQMz~(4g=9v2V>u+pf9h;b=}ArU1cDzF;s%J}i*rcY$!LE^rsUefDS zw78xd0z;1NS0Snlb)AW%&N%l8A9)UUnqUBRUc10Nc&a|?|<+@1|>KFZ_ z2FPZ;banh*&^S-%*cj01Llfxl-QT~Bj#wcz<^GP{bAP?%xw9vTukV_UuVJCN8Gm_s z8?(7$>qA6yH@98y2NL>%^-OF0ZfHi;OGRB>Nwa*=74}_ZVZ}YW6)}?{wx!*oTg_@w(G0V>YE(9)0CLx<2P%8 zR?a}tE)W#(*tT1WT-;we>!d1jYuQhVR@d(oEv zvBWSH(YDWxMxrn$-sY+Ln(hnUigvp}*0yKG^J&BP%N3M6l(@zNo~S_ULi03-Pk7@G zOuK2qTj#d3cC&wcE}sZ7@<#Ty!l-|UqqjV2KEKp>P8u6O-204^ohM7Bp3`daWDaKu zzfiCw>i5_dWc+Jgd0wnG63UtxH$CpRkpvTucQG9=EU5N3gGr?`27V6^T9VAJ&U{UR zS_q>ZN(^6DmmXv#ioc&&S)e4)Uw`#=bvy4#6lC_ggMItU8#m_a^Dl2YEB`2>qxvZZ zUix*JDaBE3PPcP)N>-^VdUHq#iqhEa#&aZSJ9D#Ze0?KJe{~3~W_xiS0CT6(KKhtj zMjo&lTc9`87Nvudk=A%$i)W5|BHwYSMk>Nn$dgDFFoFt#(>8aJYG=N1j;3EgJAiF4 zhhBvO6f%IbiX2Ik2{)Fa)8@_Bw}D2QoYtUDlHwiq zfq-Q_&2frhZpV?p?*Dh~B*evugGb+lJMdK;+Wq`oMOCK#Rh?#@j!H8M(myooF!S>- zJqroPFXzLAlL`elHwWa*(Fagz{2Kp0Cf&eL{MD45E7Hqd2X$&1o=Lglv#4?ZQYf6| zp{@pppI8z@*x~f>Q>`oK=Zcx%il^|+nm^cT{D5vmP~!lE+MhPutH=!~OI9E~Xl34~ zTnZ0|gRSqTei;I;u`w}X+S)|uApyXZmVi`~`OidvJ2NI{tU}Iw629J(Tsw-#M z)m<76fkMp8y%rMKgJ)@E&QYRnSfOBwz{khOsOPCbhCg4Fc3KT(TRo$uqb(T#-U7q3 zB|fyVq!Z~0I;(-^&0}Igm^aNizYXGIY|OGrcf#NriboX#nMciXP(pIL`uh>YJE;#a z5>-_@&sOzfwx*ZE@1>5tR}p&S_ps3!*Dz>Gju|8|T!o zONs_;twZ{8#>@et40bmZS8iCbu6m}PM2#W;mP%Lqv+s|1hE&{S7GmBa1i~3Y2KB*D z&>x9!+=ZH(cw~&|M#Y4nQ1hFQa2R5Do@EEiM`-OPPzS^gm)MV_@U~hfP;v)FTK>$c zp}T!~IhCS_ka=M^D-8lE4s0LJ%@Tm=aC`zJi8$BeMylRKW%(!}orsyFf65 zS%o@zgy${aIIQ^dml=s77s?h22`RKpnq6un%QczrV*+OkRwRQk+z`BZ37@YN)cf2s z-;agYSiGg86>YGu%oY({27e58XI6|%GrX3E=R>U>eLb>{-6h*fojHl6o=@CthHcdv zsF+4)2!1=BxTCqa*qmD0_h>(nb&GFMB~kWH9dP(ert=PrT@Q;G-%dp>e2*I_#?T+z z(|+p>sZ=x(H;T?Xq+w?fF&UCdIB9C)W!yLwmbNa13JTeRKju}!gDTtE*)`mqcx@Mc z7W=$RORabUe|>^Q&C!qWynIx2jQ!MUb7b6gC_msYs$q)v>XIZFwewxa{qiU2XNsM3dn%lo&WHSPjEeO4D!9yt_v z0^Eb6oIjIMto#HyqvAn@_f6fX4Dc0{We*Gbt1@95J_-loQzK zC@N{CxY>hNfRG4b&LCt-l!TIU=-|$A5<3c%xu~34161%x{szfu;i}b**?mjFGgbyl za4g-U--VcYWj1>uIeNd)Q4@iZ0u7&$DI*(lsi=s@Y0j9t7vwaybn3DX0+;EwG6_@kh0d9%mVX}oZg2g2oB%o4ui5@^m$k4V4WObWB8d4y zXJ%@Zh8h1uIDiJE~wNA1M1L@M(PfZoI`Pt#pIK-O{2%IpI<)h=&nXlhY; zIThb`a=sMdiL}+s{)^3W078!F`G$$bS%j;EonRxE^XbNC$XY&O$EBsmAN;|~i;pwnXISNh9+$HDqJv?j03Z29jRo^(+7@EJw@bQ zzd9WMvhTgfC3_6;3u`{pij)=ghh(U*2=SoKn-(_mA_9tDoflf4r?szN3Y~bME8My1JMPoXTqXcKQHqeM}yHqyY8AL*>IM8tuv+QU{Zf(tD! zX$dMDRH3ae-{{P2;{>smjTh{=QL??p%JE&bXI(!s@HpBUk^IaWZx|m^;fBW|{C>IJ zr}I1x`!myyMNa>LJ2$^qV_eTg4WTMe(Qqlb(iNmKfz;AR-?1LGPS$BC^CxF?*v|w* z&u2#;pL&szvr(wXXw~2IuESdAj_M9ddZeJ=gk5B~oHHrLx#-3jHrt z^`AMP`jrU|`{T4l`$~0)T$Zh|4fD(ihQm=p{tj{uc=O)r`dd?)q_aqmZ;3Z&hX+jj9d*E>>m~%5w^+%g+AL(1OEC z+Kw{spe{3MQHo&3u41Si2?*IMw=xh-wA@6PXcKjUw&HjG8ml|Gd zb>qmDjM$pfwgmz~;9G@Iq7U>i?z)qWloTPMYznH$ezqX`}_}YP*<*UF2%yIkAaVqwqD8FtZ07K z5B{lMDFU8QDHU;ZuPnu2I+DcOv%MSuci4=FH~}F902M)zvsC(ucFI~>!W#8c9>SoN zkZNQ-Gi~~uv52_*R)$HNnPX+JBq}dgxp*ddC2vr2hZX=hFJ)zVt^h!5VIJq6B{y;oONeR7ku@NOiDQd1Hd(6!)J0HgZ%Xm;YZC%)jxwPY+ zy5-#gT1B07a1tw{R>Q`~a#o(S(lcagP>PkSuN$%Dtvjmn^v71kJfu$8#f;K%a#n}? ziRrEJ_55X%g&>_nDC6!`VBz7-RNmVVL<6=CYmb@v5^SuUV*{(Gb5Btpk z`_wVRzoo-0bXn+mvF>$J0wvdPuJiY6*Cwhj_MYyoZb1hGW7k$>aJq-t#3eFhX*KJz zBZ2vBp(#40^WS!)k^GdF%h`g&)ycV|{8|hpS=`XJ?TL8RPqzEs6k2;@_n}xH;f|(b zc;VJZFYdReuhdLwJ=mrsS+)xbM&v1zNvq?EQE~~q*#ouwKqonA-y7Hir=Z@v*R z`?@3c#de}^S_#gI!VaGbv4w}Ovnqdx?_=;S6Y#+=2Zl8|-K|<_wFTd5(zR|arze)L ze6G8^J#IW1WI3$gaqPW-eYwSZAJCWibMqq5bjFM4cQsq)3gT51iP*;8>zM}^blP+o zocj@V^`9-dr1H0ZWNx|{GO4qhC~uE2*H%H?1&6#180P1J`bRSUkrnS?kTq1jg&|ZG zvU#|$HKePHR>RX0jB#izLUvyHg^Mh9veaZy8O91}7l*28qISCrP}ZI-L|kW09mc{L zCDl2Va6AYwWobXbIysp`Cylb~Zj(48YcvF65(ZAeVsi}ZBB3|PF)^fl9Ks2=KXl+F zwvUjrZc&{~_*n%7p4=$yg5sp(yKdC^4iQ|ft*yn+w3L!+G0CPQRT?RpOLhQoSksq> zDJ6MU8`6WxD;1_dQIKRxyFaBcC4J|qv5$ZbD_{gIT?XRu9E9y%3s5`&Y9h@O-n zSM?2oql8S3Sap6LfsNVZlE%>{dm*>F;ML<5V4ljZsR`)r{!A^OEN^6lrK?LaGsg`i z5JmP(in_Vw+pzW7OD{*-1=J?r_5GG!o%YDu26H5C7a@r@McF}lWRQ{Yt+ zj};MR+i)yiC&u{WO{s6V^P)?J=F==t?$M9I((#%lGH7xB6R&hB0V+>yY-~by zkvt$h$3#h0l~~IN(5T6X(YMVd$1-R&YDzY!2E8feePdF~ug)7E$hBiq^AkG_M>z7v zHBHOl47q;<_);F8Ok(J z_>XAmuGjjeOlgX1aQExH@o{-uzMH;jj| z)pwI^qW8~_SI3P*UU=g+kxYO3>Y}CAUJ>0I-XoLVpLsjpOxeHp^eef%P%)-vW3I~Z zWfGk=M?1SR8ZS?oF2w%*MIh3VYDA3kGr|}@jD;_StWr}l&7kYHT#k?7OW0(sk$2zn zaQe&1+5W?MO~)>Y95p;eA?y7gAozIVP<`qKD>>| z#D1&#+X1s~e0MxiQnmLE?8@s!Y3u!?mheHf3hO0yMf;J9w{s6n=&Vydm_L+k)gDEF z)Faiwm3x}yg>QV#6@`EnD#GIUEP33Og<&^ny>cVsewo)p#$<=MEVpsv@AhL~>ixlA zT*t8n#ZTgwK`A{9boU4^#oeQO5LNji0n4W+yDI{z!W zG1}}73WjgG8e&KhaAo#+Tp28;iQfc$wWYQKkY7#zGQEy~DAJCJsukew$myyK4MhQX z3AF#5@O*$Qn5#`B@t!h%f=3Jx0~p+$ECyRW7o^#!!&Qnd_o-ZdRXN9^rkeQ7#58)5 zsHr@f!jTjuqF2bLp%lDC?%8f(beOYP6P2HnL)v*!pXn~@86(POZXMCsh(||51)*0S zp3$7w1a^(I_caR*O~{D6Mp1e0N1l?rDfaX2^70hXVx+e~%e0bv!mxY177I%TVOs=F zeDk$qG_<|Fy>D9lT~$U^tt<7h8U z{Pj*%DC$OM7!nD8^O*Mlz)78ALO(kSZuHz7pldVil@|8{nXhQ-U>O4ctED_YUQd^` z`>gu-auO*Z*=ah_c2Nfuafx?ewRqX-sCOn5n4%6H_@VQ9a$+OAp;jqn0*D zQBfn-KV!a1J4TFqk4lJy`e2CYp+&jGW|Q5!`m;{neJ|Fwfw!;-J>9njEgu<6{4nh} zTmyN*Lar-Ks!=eUZ*R4j)v55T^tq88t5{jVIRRpHT^&TkVM3MAd|an+oq?itdq5aSJJR;qFQ`2s&T8u)JAwj*Cp(Y~| zhmA9yX9FtQhwccdesT$hIM~=zb9)6%O^a2>DN~O06sw3i@9vRQiCPk=WS7kt6qf z-7T5|?>94dA3&+WVLHZ1UIYAPi5=5L;Qa;U)B-`T&e|}C?nA&Dp=|5Kxa^WQKs~{& zsAtx|1)`I4Tr{h9O4YTXa-}=bzIGs6VMB`ZfS(s|wi*N2{>NoS$svuftqd})rRY?& zAi6%~=_QpBjq;ITgi#pBI)5#3G(uE_fSEZ`R${^#EHh;-Qxz?3b6cwoq>bGvRrjOm zhsAO4p-P`uOCXd4P`(0Vb>MRFWNWlA^mPaS{mTYM!sg2zS7|x&oz@ztnt@Xl%@5%$ zEbdfvb!X4{L^U)=r17QN$ACjDuAL?T$LVK(%$WH2kzoQGu<586mPJNJ{yLVgOsn6j zoVj%|S8g5@Rx;3R^z0dhFR$amA|4qW{KUc{;zWTTu4_~s&Y_x_R{YV3yk3vp=U6ywqE|u$r%o30m*p(o1l_1z#J*|m|C(#24QGZ zIAmk+B3b#|_X}5G>iTLw?_ED7Yn+Py2hX?aFW_n@BNK73D3TRBW+Rl>{P)@=bnF`h zTK@}ouS5bik?y+UgfDoofV_Mdr&i$4V8f>np$I`mb|TVn#MnugnqCmSMGWQyjjY`A zxTc{W+wq7M9c+oc*t0h%b zQEzXYLygw}jsO@%K_>>Nh8j%mxBa{;Q6$tFD4CGAr=0QauHazdciSAipCH*cvc+p< z>kY~kUUZ@L=f$`X3{Z3g87Nwer)L3wDcDK->NMn;!3Q;)StM(otJ~(!&N1qr@gPm( zKq5j~f$$V$E$U~U+A@Q7z)^xdSU>w#0nxqwQ>Pk%4H~f@jT`f#(3un^`dKIu zfNV9@vTKy5Y2s_U#gDa$SXx4lR-T(VW)?G7lH$xcMF3`|fc|pu{GF~|J%UCZ#zpQQ zDiy>pFb~)>|Jgqj7)14vvz`+3H2|KRqTvwmCe0G0$)*YHW0C^P#5ltMqN z6clj`LR21CL=Y!Flm36_)dVQyff7#nTeahfVbvxtUxqv zOIQJaOBY1zoWtS19xd|M<>kSpjY_&VV^z+V9(C{RCV2o}x>G>W;CQz<`3c&sT|%NQ zIw-{^Kufe7Vo>b|wYJ0K7!D{5K#(wmFzDu{isEmaH0najCf>T*MPIBU>#yplWy`m- z7qcYwPWpdw6OHV zii6X(Z=5St`I+H3vGLmX-*Z`=GYW24#>oll)fEbqv|J5+NAavDng);VmZQEL~SF=yR-By9GR z1hJ&NWUVt1lk*M?gA`#?&hM~8s{*)V&;zG#OZxm+wMek4w7;0pc7Z4<)qsTsRx>yd zlS~hp>Ss8DzzH?5ic?E2%3&i2DI-qCp>Sv=qZ(o1{BLjzd*6K`piNC@00lX{N@(_PmD{jBkxID#6aBQ5#0C>{`cgqhB z4g$>-hsBJUn&Zx9i1zoYY=5;9VkB^s}tx5x6s7*0Ga!Og0GE@^D&R<^TevcO$23Gkfuezz^ z{DMfZ`^kk|>zYP>Y^VDO-5=3rqQIaHTqfLuV@N*bM+?mP)EEWuhj(HEdM33l-XfWB zQ_302AuC^2(jvM!+)WdITY%Eam5L%@hswF(k58;a*lU1O1N|_MQ6|!0t*@g`?wFfN z-|ly0R5@l%@?FJb7f043|5S_#tRylOCuRJ@1<*ztacUYg*x4AG@UxpY+4Ih!8@RQZ z+7V);fiAmF?J_3ep1}jY&!ZaX99 zX-likD=w65<=7M^wLXYRQ(Fr1hojw@8?dVc*0xLzHN|{dic%bAmGO={N6l>oHaXmv zdD-x%oD@C)oqvkB3o~@n3JQCFhnbB48!XB>(Deic zm*kP@0i%PC9JkdXbeQpgxiswmuPP*R2}6LF=|Z{WGJ&R-<)N+HDV?S2N2>a)(;l$; zifZVZ#6jdjB+?$g+Twb67FJR_Zr*1I?KGjBPY_-9F}fZ3A! zGK|n$9=3fg&^ZhESVxp5dF;vR!|!G;2fhxda{`-*z~xsygn)2#1?}B~NaD z!H)mlt-HJ<@l2@~eNjM4C-FVAy%jLA1t=pYMsZluZvr3xbU{q`ImB+NC5Bw9>Xd@s zF33fJKu386Gp(Q0Bb5DNa5+ILD3 z@o>)cj?@lc)D#*!McH9>h+`WMnZ6{8S3Mk8M%z(9s%n!-4 zF*9T+%h?JpxC?#~6|)uXNVE=U>oejdS479?-Y_pDWY#agL_jfPcWm>!6vawDPfdbC z+K$8hC#~o^5ni2;FxqL;prXk;qN>69YgPA~H3OJqvr2kHTd-WDXYgP3;59s_nAhdd z$Xtme{|KGT*_VaY)lncZ7cC6F&G}{Z{EUsVKRRF)X1U4r?&C_+J?C4iGo1$Zy$kbI zyW2;2AkcV#>^*&uJ2&ow+42i}$J=afYm++>BEJf4GG`Rk{K{aZH*ZKf3i3&!^7uey zo0LHp)d-PEM7z0p{L{WB=aq#zgh{hZhWBq6fzJ-iSj%1Eisu<+dK*iq+p}zJkIk25 zASwHd(EENaskW)0dS~Bfr`XaoHpeNIne(EnO=Kf@V9hwH!S{R8TcU`N0|Ax_wEM!% z1J27y(5+{4UFZ(OThE&a6D8GII2OCIIIc^}^H~cpkLhEVL9_wuFY=qWFI9DQ2|^xs zc0lhEqQ`&)0|+HIdqVEbgAxIC6&i_*NGlM9UQD2~Tx*U6SZ4l0r%=UDOeDrsEkEw- ze*k8%?1A-oPx^l%^yUpL#M@*Cu-C@giA-1I>~SMqHk@%xTPrc~7HN3h!Xf7J>7|@f z7Qzz;J`nGP!y)#a%FU;zkYkzIf{0lD{p6k?K}G0rA&*-;RT*^=<9KR`c0yl1bpaHd z=AkO6z1)h1);T3JbCc3C8H0v{8l^Wnu#*OY9G`HM5Hb8+8kuy;H2Vu?#yCG5Jf|8| z-P3!RnBc*~--fcrt#^Fo=>%8U8L7aw6)a2uXNh4_)83Ih^z%7?Qb?URjL0~zB?33;Sp08#%3pY z_hZ7bA@uCDt%h`2uim6C;r^>|Fwj+tPqDh0ENA;Oac`nSTv3;ub?b%>ky%Tl=NB)q z`mFo6A-vbVa4vEY6z;E%jD+`sG+tMq8p1&ni&aSx!=$@+S?^f$mBL#cJYX@~%EtC8 zZA1ni&Hy=A{b3)ymdt98tc|Vdtb&_a7Rc7mLP6~#{f=Y`ZCKzdwJ8z<$iUTcQ34e9mPCC-yAMzEyficeGh7<#+_0h= z16^k2#E9MYc15)cIM=}k*~#iqOl#@gexaA$d9v&^8M#Pm$+KgV^3lj6wpsMfF|4qp za9+%wQURAxt4nny-)dbFVs!Eh>?-)k;n-7VP0$TpsZ~<30&qyf=OooCpZb-DMak37 z&Z=KY$45?HGZT|EM8(AsyRw7WjQGuL-!Xk}Zo>Zklipl)-47veczG!iKmSeU5XX={ ztZlmAsPr;pg3Whf-X$H^5zMTZRFO8OzABO~NOuNR|1fIn4P`38P<t_4=BFqcXA_v)GixnFKR#A01N?s<6)g6D&$(o68u~Szs!AB(g~KCllccGW z1JlLJweoBGM;*R$z?AvEp@Rb^KcXEZISN{i9gJrHrV6hm!PKU`jpIdiHDQ*JzYJPZ zQUYBDA4+HW$t%oE!~#tM0PYP-1`Ot^tt;WwYaNi|a$GQ*V1{lX`Je5XIoe-ilk--5 z>uI_zpu;glAFv8XI4?K?7V!>ut>-dg;!i9keZabBCXiqkD|x@gYWJBJd2rI_5F*I; zJT4f3?9mLwS$;HwygBuE2xsV{zsGl2ml-Z_o&P;~VhcRU4CH@n{>kpT^OkV6KTat( z)P)S=-{=3KKEgcOI4Q|a@hO7%+oQ1l9M43$H>T_B<40z~b+Tv79}OzP`aR{_68^-EJkE-Og_(5R zsAm4}Wn}S!@12icf8(;8X8kSnUZC>vkI~V%#_a84xD#%;TEjk+SOosxn!v!j%V&@O zugUo6k1g-Sn7GdZP}IQSf;6qU*)xj6Nm5212a>8F5KMLQ2`ArS(qe<_9DPfzGWB!? z0VxHR&H5m>a1hfka zdCsM1tX{xe8Vj+t+FDY4jo#TQI4->I`2vE|dffF|evnGaIM?L}(3bjYlM$`-WgQOQ zABIP`1;I5bYWAM#6BXU&K{B9q%YhK<_JR~IrO_y<-)CFDGdpadaW?&d<~9)()5=rb z1_s&*X4=Tg24ggPe)9e`Xtj8H=Z*JygSD4a(~=mi7tmUFtCE)$nD}(0g-&?_xf|b< z*;kb8l-BrhvH?oxg72G3O%@<4V{1r&wN_H{^2+#87heiw+{DIi0s?d(F%4Rmq&c2) zPPtNlD}bF=9eDieiscJl$Y{|nzy{GWq;)M+Z-1^=oCRS|*CcLI3e`91d@tbh0)+h` zfKorG+&Itk(@XlVcw6(sKqV^*DjWT9#G$hk_gPIHL}OzPCr45^V>~)G(@VbG`3zn~ zSvi^whbGlJrx|vdJPQj8RK5*-G)iD}*QQI$AkZZ()&5l)W}xU0DJsub<<r&2sycW6qUkuyel&%#yvMSj;1>MZf(6Qsomy%+QuB9 zuD2%!yyG?vX)7xp_DwpFwuY;_Wyhi-&CZ!(7r{&cin+!@nvk)v9}vN|b?~eA1%&a_ zMtOO8Mt!{tptb?>rl^G4QUVZfp;zM#*e(k?W;O@@In$Kyrt>-GHs{dQjj5(>13%H1 zYh~iJm;qD3p0s=lWdE=OHV9){QCc#oTCLzXE#Io*;%a@SgsTa;DK8olZAx;MIl^PL zVY^syl&$m+Kd6}or+xO!c4bP~`n{e3gky*wk0B+~B?6yC zD8+f03cD4G2fnJ7*&h5sEkypstrb|^=68J2%=4wXQt^3~J}#P32^NVG<64NUHC^tk zW-~v3%-a8I0fed(C10VWgt-ej0{X(nyN++SZrz>qT`y;pWv-5`WgRtN(t#fNN{@AoYKFXG0$}WH~ z)6h?~%h7sMfnPqkGJD4mk!toeWC=D!^?a|oa;s?EfDaaFk3DjfnylU-tMCk`5N=J7DIq>A!_II+cdTeh z;?lpftFM=|PQ_m6h#<*`Yjh9&m6y-z+)v5>{y;VB$B|4vI^U62E)bXOehcXhA(*}$hK<*AT@Ln5Ka8p(_n6BVt|X&|`jZZo@;{ob+Guf1x!ryh z;D);^TkmpBY?um9@c%(DB70li)|@a8*bJ;k;q>@Kl3v6u3k#cL-nmH#fk~^b+^%-I z_L3bWln(+Bb2Sb;y?D9$y&<4{oY#MUtPNeQvuS@XA4Hx20QBIZ|9nO}-y*hxdV4|2 zCUgL2lbZVKWwjjPPv_ux{bf1ARp3Kgzaa_YQ||)pJqHEO*sFYcmSn(>&mRivf^wB3 z5Q%=#{2!jKGAhbwYttbO0@B^x-2&1n(kO>QY+mS$+d2v@xdr3*Z-%0>u_;C$CX9 zcj3A)JNu~>qGB!-v3`LU-@mZwbMaSQ_bF|NA&Sdaa?bA`1rdTosT~E)dVWs%^K@tz zhv9ZbW-=H@W=tRh)468#<}SLj5!~=cq@6@ylnnCtAP$%RvLH7AW2f+T4_*n4+ z!x1cRP}wC=iWaMld=Zp^lMBrA+q$7};J?;B7lt3ce!UfCxtNG9^&@a+tOA~&eAf9nN*FFm6lM~G$@}3Nzy^qg(T>$LU>205s#0%06z^8 z-3qp0J9r=-LcBomCf36zQ@Dc><}8rS&SJ~3(1XyJe2$k8=rcqCV~bDo!OHQOtZ^#J z!S#dx(r~>%HIYFn{kB$X?oN|%vvZn=tn5yeUv_}G>mPR?Vux_5cTP1mTzdp0v3soe zQuYz_g_du+bB2ICzE@icl9zlE2AS@+vTbC7KXqLMi0Epq$gsskWZyS55Urvg%JV=g`(RKg@&d%pPjG_FK}x&b9}kq|fU<0S$G2 zy_wg8adrVWSav%@G(vqOZ{GgLRU|#baV%mlmg>uY7A}5-lWgBLcq5KwA&ZVqeRF(8 zZ0WGGW0#UUu*zLZ>#J|q#2_WuVSXSh!qpB?r`CUjR&0JIOFZvLktsNOs?tvP+%0UJ zn#RW~3;!l=E|9_NP#7**9djlhGU3L*mlLeW-#Yz8Nko@5yibNd!^P!8jQ`rNa`})o zK+6tsbMT5Y3eGCroC`HD6obOL#Iyvu9SC6n~K3)Z3j1`0} zhU`k?@=*4;Rqwt8U2FSW6?=1x^h857IY~==_p35KJUrc3N!*t+wqkd4u2|hs4RxVI z>*ug*g%eq$;YDUKb^(P%-pw}!{H2}6yDfQjExz^G2v>*u)Tl5_A3yRT%(|*}6#QXP z95+m~LDOQIYIaG*d_qU~AlT`HWI4j^SM4y`P5o~)9AIRcFc)2| z4g=&fCvf>M#@U$NFoSEn4lTN=qMaUOY?rw)DVQdyTfY~83~VHqy!ls~iS(9V8-(8| zsCa5Ttjn=0XXqaBpl~pWtl@) zuw!4Avx$MO-xLlV2Sqfz{?53h1|b^{1x?&O^3?4gZ#2KPHSFxnPGTVw0SzFvPPV^l zin4K#Q6C_+r_|i#SLd#yW6`!{AHp(7#c6+$V*&Ph-HPG)6T=kJQO3*l?0swS1$LY@ zV+mg%jCd_@SqIi+S36ht6qrO0t|Q6Ohx6*xP+N#7IqDM1%bTi~yjEo4e|p-iTJ&rc z1LS$5u@n<|Iq8yJ(l`Wkv+rxYyCX?6Yrd4&*hu~$JRvXa3&Oz7ZYykb7^IStkS1&d z!ndZ69&wFKYi&(bFv8N-bbwZ{UOd%o0-J7_vJu$s2PmT*D9A;Q!yr(I*>4eE-9RA# zg=cL=@9$O+K)nT)@MtYLExOEotCOOh8icDSY4hK_r(Ppy38wq)#}CR@vAs zNI5epM#(FRoW)AfiCMCj`K)nM=v#*VDYN_>mRjCd9#Z_dGCQFy%(@=@f$06<>qAtG zu6w)lR@;Ys z-+EiBnSeL(KeG$c7Htcf{mXsk{c_bi^mumu_LnNWUmAK=V_{qCS#Dq9P4A%LO_4xS zZ4Cjr$Z?#c`80{;qNfrE@GB5vLTRo%Ms{SKU-fb7^XSkdY}w7{R@*qB;YJ>o)i-+E zYAh~!{AkLlvVabgP@Oh8^(Brcj_$R5?y(P1MHZ2p+~pE$qwGA)=b_>hcN zs)Dfum07SOxyeoALeiUoWFCPqZRws1GCE|`4U$n~5T(up+N)G&X%YoThZ>jI+e2kf zk#@U0&?{5$;QMQ(9aP>-&29bVU6MZ3yt?AsJi^QSa*xQWLc1PYnAT2#Gy{@J;ciTO zUFf&>g<&e(p^X*Ze@jFB6~WcZE2${_B+wj^x20Q2nU22MGK4wMjw23~T1=R4kI*0N ztmhV8r^G^I5q7fiYo>!XkEgij1Lm@0Lv^vchMql_M` z_}SQKi-nYVE54)Fy2{F5fNZjZUzo^>0EPiAmRmL_+Vk_zez5*UcBZllC#eMh2NYHa zUDk17`WF^GXL|&!SZpdB1yYM&1G6`>eHRhh1r7r(&Iq5XQm8{%{r58Be|&A|9o@-n z5mDM;x`@i6MRIN&9_mTAYsC+Q$y1nmg52S(l6q@mfQtx4rBKzq6Fvdxe5R0-;~GLs zi{Xom76G@0j*f7a52oSqyeSY05d_ZfsYq3{lB zSfDR4GV$#NrGLy5GyN6#GX{1Bnv^IH1byUkoO!cjn(E0*5JEOA8!}J3$Dhc+SFwX^uDMxgjb~KV9_-xN-a35P18OPhDZq_a3zr{RLg+CA z)hfnvGCwo(bHKRAtiiBOGAl^vjZ|E@J2$}%y1bH8*5*P|32j^tDu+TTI|H6X8}t(* zk+P7GBhedt*K4PzC*%P`N|)l(W@?gX`hkPdf%SLWUnTU56FbAN@R}J~>72~rn?a`Q ztGhcLEUPc3KHSs$5F>rR9Br)xcV6=fmfND+Ps zu!gQg4n#6$wlIpLn0+B6IY4Wq8##5mZ_&bu&gFY-Svx~#T7bn4(wqV3 zrt5v8cff+t)92$q3&u7+o+Z;b8&pivpcn^43^J!jwVpcSf#*``%kpo>RaVC;6%85{ zwjI{5b2_u7UjgECn8!zKNwMrzX=HK#)qA_xwZ~TsvlPJk(j55txduAkLy9|@xc2F~ z_BC@eTYvT}E?L44MZ4qAPQf$aG#9LJ&YD35aOtwumfQg#_-A@lD=4{t(M^u!q7X*q zH{WrF$>pzBtW&pvhSj+_$?to-^bA8wsOa>NZe~szR#R|47o1E?B;+q6WD!$qk&H2$ zSlspM#AR<6rly3uBN5?1O_-Y+%F1$nZ+{`0bxE*3e8>FYsjO=6 zTU#f0cv7C<(Gfg0#tf6gan%|h?*@drs1sGiUwxcgNoxXcFwU1Bn#`5rsH#ctT&iOr zH_pt@2M%2;2@)Ti3CGXRBi1**MH%%qZr=(ETX@UJtWi?AN~N#XQ_cr2POE%Swb--K z&=Ax1(xH^yLTT&ys7#WDjp}K2xtkrmhHeCSQtRnuG)e?rIexM|Ze|IP|NcF%q_{Z0 zsAvd-r(SbyB%)Eh0ccZyYRhIv&ymJGROzATs7~Zkq^hCks5J4^RXWQWCTCPiPHUr! z6#{`|y37m0=fA1x^$nA?1oE1m6@o#J7LtYr}L^&N(! zdf!hHbn2%{7k+^}dm8x@0Xi+P8)y@J8`>N5*is^_YJm)BO?n&d!&TfXdUmaOnDBly zeZgDhlUkc&TE)$+YKpG>HSY5`nALJQ_@nM!fyB`UXOiclp<{z_GqK6JdAHRwzJ;v$ zh0e~GN9opF!4q}wL~V0*<2?bXP*+iF+@R$emUnMS;u2!Z*8XxR#NBzf3S@5OB|Mbr z%*nIrA;6M(Nm~SF1S|dUN{X#pH(4g8RysJ&DPsAel;w|pM23za?nGZQg80dfmVvpN zfEB`y1F97=NSw^e+gl9Xp-ng6qT9}wEWpq{Sy{9D)U71068}RJ+#)fQF5T|;FO8eB zM$?~3JR_MHm*$2ND{O6$_Br_RrrA}$xQi(nu-rm+w}FMkS=t0(x`SCL@R}xvXc$s0 zaY)^5h-Xw+5wM(xA4@a$U2ho?cb)QQvquwp)A^`Qx=MfHidbwyc&`xA04_pbrL@@> zG6jPTgdg$lJKs=dhH$9bXv}5_W@1n81j5~IWGC_K96}-#@P)J2CPwzxi33X} zjNdXa2$B0XpQl5H%!bTihU0_Y03T8%McnIgVJyW`!3F0IVR2yY&UBBXqP7Nqn zX6}JSOR%)x!PMS*2n8{TnQjSYq~Z-8iemP;SgC~M^{sciXyvEB5cVF2>M}~#(<>s( zgLl#XO2+ik{hmagErNHbW6#v03y^o4&zjo-z}S)iHAT@NtIKkzl$*gian+cTLbGF1 zX-)rFC32KizF5LCm2wCgzy-EN5`eQyZ zsqft94*|q?IDxsXXghVCapavuq>2CtO zvM6`vR@W&>T*pNtXU|O&Tz7p(m^61cbeyN2#u!p`RHPu-fc4I|A30r-hl|^ce($qG zK2J#;2|R>WV5R$t{YyApXT`F87PUAGsEqc9X>B`$8R$;(xAP;mF{_Q9rTh5{6s?zS za9lHK*-sIn`c#^uoSW=dkK1OOX?}v{qcfCtTn9DRMaoRUUOBkQb|VgR;f`?aX}e=HVbELspL^&JkIk`sM-e5fORRU;eCeaWk$o* z=MT1)rXHRS>dY!FDFLGNko_gYaU21&N@#Q(7{!;hw(?3_C{iJ+(C8mOwn-Nio-zS5 zV2dgoX5HZkJfPjW13s4gr9kylagY76B|uJD)VQ0EW4|+q;@_&1mVkCpj&Hyj!p8>Q z>XYXEz+%}DH=S1ZNB7jufC|(C=u4zytbj%XT-E$A6`q! z=hInhTpV=^n{vW=-;aMz$-LC!18IPYGzb9`HozNCQnGIma2uqs#d>-30a^jnr~UFj z=?M_M7GP11%Q0CmJwW3=6+B1l#nIvqiw$+nDY8Rj2;Zv>iKjy|&Ds1e3Wx)tPvg!25~a0=<@Uhi4rOwllE>*|I%VU;+9gE^b`faZyXlpXKF@KN}(9U<~A_+|JJU+FGF9`-?qfC@d=TQYoW>!@HNp& zER6d%K4DoK@!ML5zY1wGu~kR4@Ij&6_R}WFpMKJgjnz$g)ReaSAQu$mp~D2+xJ28M z=5Xp88L5ofir!AteZ9PqJ@PyFjAAuVCw`SK86y)EbW$mHNoYi=&v?xk4SzSE{fUKz z1@s3$J}a*Kj2Sp5m|LQj7P`Ec~vYye-q?=bz+DVAOn4k#_uUNLTc)K8m0FM!+Ik*CxH!?~N zo{9k^p*G5nma|I_a$Il2^@?%3fo;}rT72BhCN+K7AiKlyB^d|u)SE`{IROxGZ#A~< z$vER|Q3))2(U;WJ^tdpnaa4REARtKQb8g%@GdC7&TPYgcrY-_tjbeo~Zh(d&1L$Tc zxE2?StJaDVP%Q{}?5aC_=}*R&b}k(z#o(nO#H(=)F;_NHJvR-_G6(R39vWU|tiL+H70I^-+tN&dZCJeWg4fq|dBPPZKQD^oVzPubFzsJ=0ItDs_=lM7~a8A+* zw#R~Rce_2pHZ}7a8NZ#Gndz(4^A_XbvOszIkrm7S$!o?-2~ZKWx!W5pR&Npdc`%QU zw=K51QdJ}SkBxa3m!u$#6_lSqI5|~DjhxCJsqdN|gGx*3{9f6Yvu~3R zH$KQg!ItS^gJX>jP{Nk3@Z*QlfNzLuGBOh<)fgqL0_POqpbJ`BD?Ykb{b|hd+F3gN zO|4%?JC{ua7H0y43>yumrkQiwOR&F6298D03bBykm^yI2hQs$G|HOC9`bV0?tW|ra zJi$Q?0onlora@p}{>7%I)ft^NssM1-9d^qTsMNnttj6xOWVGZmf#eaOU0){aDidv zJ|$g@$VRPg5!b$$pNh^0N3LzbgAPBU2?%@>B#zFri}KP=(MAk)b#+}@#`zNeQNOe@ zQ_5}8twqKKp@4W-y{$_-VN}i<7CSqC zb2P_5$H?deQ@_c6Zs$yHNNW3RX-*WjLM-g_8O9LsSLTkd(XFPQnRsAg+nCNybex z%FGAvGD?sZ3~fKYOKCwV{>Q?ErmyI6YuWjql$NJ!N=il=@#~=}KNh&WxqYCFk5)pW z4C=@#8uz1~3-mc@O}y}`Lx6$GFDRH=T>QOo+<;;n`?JW9*mzne#4W&0`|@+Bwae8m z{mRj#;)TKyFD+<^j(3Lk0f#~U6N*n=E9yYQ;jP&gQ2w|qzImG*KJ=%?^rlQNSkOVX zPyrGE3591)aG#XF#F&Vb&LC8$oM+&;XUi+Hwa#DfbGW?5Bb%N@Il&SPzDP{O1Ae=8n zuq6x#P3w;J@X9wQDGiV_obW|I3E>-PsVpuA1X1n~&8F_hQgsz>3G*SD=^2$0o_dRG z!gEm?SyTRHBXMP#4ORsv&ZSMLJ@{Y7Ml^nIzcDZn2z9@Xh4OPg+v+oU$dsXGxKzZS zOSF;oYHCkQtyC_vRn@zEY-rfv=PvTP&+)00JY{fgwq8)wWllN;mT+dq!PK+<3S3}B zhchIKEACR`2}31@uL3LT^Z~|O4#_VsK5DMT!0Imck8kn53+&*LvZbO#&Z<}y_Ev+Y z`d2Qh>0a3n*WBC_dn@)ds%jibfq~lW96WJx&aPvZ<=Pxxkkp65jz{Um+)@;0wi>`# zBs+v=NyI-liV@MUGrMx6#!xuJDJLh&^JHW*w7Jpm;F{O%GBzH+C3VfPLGaycP>9yVw@IBSguK& zL|JTe&vgqvy7nqtRMC%X9Y1t>TpH_K$FS0|_P zfF(|$VuqE386s7^y)|u*ofk1Goe(m-{7*Ww9Ab)CC{dtRY&*38hdzpzdEjbtmN5d{ zpDs%kY;)7?At`wO#gCSj>D%5(p)392s-VlC83vnqr87-(`$|RGwNKtH4_5yPe5LMNTk2Zdt zg23)@#z)SSbH9glaf@O@ZW-Ar=>g7p#$S2CvV54Z;69^OyZh|d#cA?J?qHyYOoXsE z^oghm3{vcq+a_cP2y%mjQ~Vip3DGNxXQ=wK((nMPgY}arkabJJ!7-x}!;0fir{T~m z18|<;l0VZ`SQdfRKZG1W(v&A#Gl10U5%*640dQJyEvC*B-q131-R6vSs z8=PGJt3EftbGr5SP`s6)>%VPQfT(*vALxuP68kd;$HL_=L;#daNl5|H z7o^AeAls;RgLe0MrFt5^|4pPCbL^B}HaBV#S-Usa*X4Lf3!92h%9zMv7KtC(d*n9# z=c>0vbvW|RCbU*j0^7|wH=}6APHr1on`SLB0wPFbyg{uxE!o}m)&+1wpy281<~J8? zXf|7jTxyA;5k;5}w3V$za+`6o0eryoJN=qWs)J@WV-c2k8|*$il(e-0JUKf#l5OjO zi0^C3Db_SbtjfZ_q@Bs@dtb+nT=TdVh@(S*e;Fbbr*KHbM*Zf-H)=Uh22>d#p$q`` zlD1MAAsQ==7;_Z_=6%<^d0AK5J~>%urd9=By>O}dNQ`C$hRo^oR9DCFLZHLJpp}oV zGbpcx)}KzbuJBNlu-6`n$v1w%#G!Z4Q(sykA_A}!s|e`2DTR2>${?_47jokuuq*_Y zwGgrR5m`f>Gt$xs9(x@G(}{a{yG>0i_e50$yLm3H_nTiEYV5s5Vpi3z8uE z?8y;V3VrWzuw)I6n6C)6Ax|5X^7})LdZ#Dz#_P4T$KH=Koxw=83F?PotFz1u%xD-Q zm0T=can;kh|40jNHVObWnX>qu1#P$8c39Aw-c7AETt3HUmGi`L+E#j}h%WaBRk_G064Q~_>agWD<5@JRt))K7{-Ebm0cy`_EF~N$rqdK@}n#Q(F_0WgeQgP z+3+)tJp$}m9U`_tZax|bgV4u=#as(ho1N!aC-Z>4iC?G8PX46!S#pg?*Hfu`chyXk zXZrbitG`duQn^jgS|Gv0bJbhYO6GGA%J?QjrQxWG2sofCedr;d)ILKbY-R9Af9&z# zA5(7M@OVHw5=##}xIpE74*HLLWQl^th=)m(k%cAt?CgvTQAQK?_W*RPvXeH{@iGGa zKz*;}2*T$BN(Act;@L`!lb;A!lhdMjuq(5T7-$wHb#=}$eSeiJq#X&eNrnkN+|s@g z-!!Fhk_$i*6oiaimP%9D5|D9Q%vjQh`{Qw#NgiR8>ru$o_P!!Vh#6n{_sk9!C)_Jn zN`GnwGC|}dY9i_T&%PXRnnHUMO}4i3Gli_=e}DtQl5$+jCo(aFz6j&s@(3|om_gKQ zVxv&PSnEyJ4=zqSDdlt7Fm|U2+Lv6%Vr7B*Lqc=M>Py35^_`|+Q9fc z-JZ$H{DTg>@@|cwMz4D7i0Rb$DwGa~tgr0sQVjm$kGI8GqDDZ393Ni`(8ARKa!BbY z$eO6B16_ueF`>5y6Kd(~3Xg8P1zl$po>hmRe49-5i2`Qw;Eg1^O%m|Qsp^5OEEUs0 z#pR#{P#2ME_9wK)o>m|QuU<~mS-CUjQ|%ut94Vd+IHMhFdhNu2$HaVAWt2#w1-}1( z(l0fYzUcxR&m%fF-v=@xohGPFBB9h=K4;o2ku0CIZhv57^hFDC5nxfB{K=?Z`L{7b zV5Ebjt7$GzNm!K`{rB82aY-@3*VNWdF=|~Q8b%W&sWN+Q;g>Z^9EdjX(1l64d zMX}|d@>EEvh?#?|n6{09qhreRxfq7YQ;=9%2ag~a0Z1wtk@<~2n?qGS^g2eL#7rTY z3ET|X>$P*gt{a-o?T zIVjKzCA;Fo&6GxKZgEp-?a|{h{c^D_Dk#{x-cweqo4eZa*G`+(s(X`kx@s#V8O68V z`c%~bJ-NJ$uSTFraar!-IWvRGMl71F0@RnCEH!2e(f-2$8D*$3pwu0wYk9EYj2O|C z>G;wQKwA^F{P59Z8sp_3KDL~5ZwOe~2{OhV}YkE@R zkD7OkZ(a{boHGMLe8_%*_O}Je{YgJWw z<2)Hzf)5{?h}6Vm3EhxvHqUw9;&n2gBWwd02T6Vi{dffSJNF|Mdr<8@Qe-@l`u#^6 zBwuO;H@Y(VX0zJA_>Qvv`c4z)cJu1t5I%<9R0C@D$#-HaRo%D1Az z<$QJISA+G4$h~f%$csa}ngVUkJHCvP{@+BVaKX)a24J)3>e_(vPeszn)Mmuf!73}* zoodmIsrh~ZZ`|g={o(gOn{6qrkS7|KA>!<{8$LN_t6TkY=aFwU9$H8xaP1r&yRSe2 zaBC?WKIGLb1bJINY*vXF=d-wi>@^NdKyI#4)IvT6s~n1dP>w+yKvk=+n5)!vlaRY= zAgaPC^~$EIXpbDV+f>MO*ViXrS`yZ%(m(utjhOtC$^?>U=Ww=Q_bivko`bEY6<#F! zl-i7HG7qj95?XgP9WE(dTVUF`{iCiE{u$SYj+9`;9av2I06E1LX06i;^3lrFSq34t zThSP^?SR*qppVq6{}!lOV#dMixsY~NY#A^~yKGH1OEz?yg*a&C_V0Ko`uJh2M)mEH zgPbc)vl0C)R;K39fUMEApK103f&yxxe`l&oEi5fEOg%7$p|myQMOwmVQ-wVAx9`kp zV@I^)Xz9hd8Ekz0ssPCAqhDU2mRDAY9FZHKeBvgWGIzcUu9V3xlzp}JD0mWXV9OBs zA?(k$sQ`bX@l+>Osdq!%m64)w-20dJBFrUI)0qUmi1X_3FUg-b5fQ_8@_=!W!D!95 zdq;3iMNSH+liYv^%S$v_B9{vX{R#g5ZC6R>4kX*c6m6 z+il0rB)tFWm+gk)TfOBCqk&>^4x~64U<-Bv<*rCPf<-gg?!|Sxw>Rbs&hRKoR~CQA zj?HS12($(crCfSDP(Q^K8`-|bWhjbT+1Ub%B80&1qq#B&^GyT}RJj@`ImJG^IO?we z`5REvHw_Re$+$twvGUp%fxog;!_1F2trzpRLOA+Wol;Zr^6-oCj+|% zh$vnrEl>Gq?u|n_*KDe!=_H}+E$mD7N- z_e$?icYuqN#+1gf=Yd2t4zw6?KuV5xyC*b{M(?fBZu~MTC zNgUg^{j4GJ*~>`00>4IE+XNX7RM7SeVP&74~*Vz5?-MlatEl2+gLjzpY$4PoYlh^VKQb zpn~1_-3}e~oxJpKyHz#D+y%A$Ww#1`{qnN1?sA3s5RRS7$-Z%ERZ;p;4OMRm@-^Vr zKM|9$5YA$WF7J67VYl$kk7lK;ciq`pYsn(8CwtHCenWZ@#qj0f5(v}2ecB+@{!7Gh z2cAdKGA#)E{S7m($|D?Pmmzh%GsM3C=vnT4&MvDfde4x~x6MLWdnLq7!hC$Y)Rdl9 zlp(e9)4Jt7#`K6pB=IT)Z9lw#hdn2Ye&x-Wc)Oz_N*5pqDLHrEI>?H9KcYWN zo!Xe@tUpsUBhmXyL_o5Cp{_NtC6&n3oaT+&J~CubVdB2*m+teL^>__J>pcflc}CnD z&a5*y2EF?WKO#0@CkL#-iOw4lELtw#$?P+AdQl4Ax6@XNj3TpE^#5~0wVNGs_N;BP z=5Ukr2CGk3F28ADdc6B01dF1h2eFE4LWq&78z^ni+?py?lD9ij80fmC?4jECervkk z!;8lFHY}GE|q`(W5VZc^zA1Ks}bYxtk$NwyP z9{z%_B}F4NKaLB@dztVNcgsjg{j#Hl`mH;h*74{39xOd*9}=G)=F>?C6>ye()u^Lw zYY^hJo{jRRnc)s-g@m&}(`m+2SCyry+nt>E~8ani>cKJKN|74F6cl?0F(m^@<4-<0zd}%6Dz-geK?^bG>2MJ_L&{* zsHdEDf9P%9_rGQXzDrs6^oH2ar{JxMrhTbw9-#__@&0=8>BmIj2b^eVeS3{v;e?DK z=fh98CvtVR!gI#jLRD6nJ-|4sBA=nHAR!?H#68tFP!}-G`~~z zFszp3Q{PU{KqH)%du+qmc^v4yscnP{(0yL1Bvw4bB-e3Eipc-$qUVfeVj7zEq^A%> zH5Gh!YGeNx)dWfzv);B2CbiAss}K1&?fP7j`2!v_-UTggYvb{1Ho<=`Z?|eM^h1bW z=58C^b>#?w@sSH&p_$`qrE`KZ?A}^38{J`t6wixn z1Rr$WPClT$5r{fr=WV>g7nqpBBc21DP+^QJZ#rd}Akhw0PDa!MiP4Jl`E;!vK}W}7 z{>Q`^6<5{)kypN86SeJ(oZKLLlJ5f;?vwLPVB9mxSSQ)biC2s~`(}u&jhxSJZ$Fvb zJ0#4TBVHIl68Vd7`Ol6XWEkL>fezBJO_Rq!1BOq zGer-xhl2^1xr`{WJP<*Q#gLlVKn z$(75gC_>1YiL!DX!X^T0BipvJ0QISCVTNU|(T0CB)I8wTnUoMo4fHGk$3^-`)u-Fk z>^0dnZ3a3^i;j0$x`OYUq@F&qu17o4G4?-x)6=I3HL+_z-5*|^&pSJ zR_r$1?qll64qwN~>gW*8eh-k9l|A;i?I+MKEhnV;iO6Cy`q9#QW-n399-U}BjuIWlp@0Xhl_Dq zMsD@)CO&6W3NEgM%uHe(LxV%!a$OPaYo;?fw!)0+wN6?!CV2{{tq~@phu=N6@(mxg zuOV$AOx@=BAgqqM6tq3gSQH8?Oo1Ue?1Pe zKa&_-9go2E1m@cePPD~x+qY*~=SU zyqZ-TtxjV=QkvuR8HWl=JJ7BP)+bAtt%%`MQlKuP4DM{LsPDS|SgD1p!pqIFu4VQ2l)_|CeR?g@h1o#zn8Cf; z%N=eelfUoJh4>nGpf6PAHebZU(!j%*hBa+aOnknRv16RBhNP4RO^-sFrLQw|#d(Lq zUtbpXGkD3^1*$*%j@;|*ZmpefzwX>gjBOn#XGlacX35+JOFgd@w0Z1IyRu#=AzOh_ z2R+H-nhqb`h^ky&UwBYsh~pEo6QD(k%{&Wz@hukDFf`DSZ^O2&(DeK%4U=CUlu)0( z|9P=rMicR_6}fc8s)%n&YrsxsA#7-8EBhyEVWAnr<`_N?((M4$Z><)y+b^iMBP5gI zd|D`sDX=}W`S6;l0Fs)gn6rJ^J^V96Giqo1I2}r5pdmIh^UT6FjHi0MSHjAfc>McF z`AVwRNI;W?wcz|?BbJBS&#Qj;>VyOnpw)FZT?^ZpKCXqS5ttbGu#_@&ce=sm=`;ti zfB+oO4?jaI#{l)B$>M+l3nld%<3xp816{CUK3imc;OXh@)RNX0(oM0-lM^XbRem^s zdyQ^G?dib8c*EZG^fGu+`|scHH!m5ZkH(6qI1Cf<5%7@ecVTV{;g|x18t4Y&13zd4 zU|7$q*V<^|!@^dWnsNV$n_;y;R+NyFolGMV&B2?TD2|U}ASWc7r{)DKT9_K72CMYj z>NNcOJWzO5(lq+CWR=_SNps-twU{~_5;HbqGaMoX&l4EFZMwBlG+5G{lr{SGcS-)$ z@iO=V@;MHkERV-;rbK{ZP69x9d!{Zhb+jdR5VZlrv^8Xl+&>>uV>g4DSQUWY*}7n3 zD+`{B@Xo>u&1y(ZO+^Ulb8&UmhWc$a@}V2VsE#n->-Jn~488V*eT0IJ3_~u`wn~>@ zXyu)Om~rZ27Gb!0Kp2ZS^RTt^;%iG%M_F~KcT4%h;}Drx*aQZ}etn|P8f_~{dVed| z>^xl1neV;aZldE%AJzM%=tap9Geh95kETp_Ot{pls!aDC=kW%_b0K-CmCkAnMN!+P z`Tq3!aw-D*0)nJ!cKmY;GFzC(Z^a8qq8v=;&nmfpi#j$)?LSu{j&7<7tuS~?Bcg}~ zZ>o%%9KV`DHnnH;Q7w$;jiL1HDLEdud6tUM#K-9S+8gq)qP3qsT}Vhpkw~B88juIU zN}ZO^_`G@P$;+wo58UV!9k|(jb4w42 zFnay1MkkOHtOxQD2j!r#U#GJ?$W9k>93SgEZc8g+5IXYbDOs9Z$))adh zpEZBHi?@1(#JTUSMRa9{QQ{XrUy9j0z&KU4BZ7*47%jBw3rfERI=<_OzAAKmA4OeD9YdG3@l4wL1bVx z-Ry16Ch4v3Xf=mRC_#FDS9V^%La%8~980kf=KN%&tG+!(igVb4RtM&bHi~R@2rARr zYkxS9?RD`I*(dHEFw{@qEn?ev*s!hTU^=lhM>>9+ARmCu`SBh)*VH8izJq&eC9_=Q zby8|eW&1{GJcc)}H&HD>@_m<<$JbuJXF97xVk3!UdfpZ8XYIx#H^C1tlE^go$(8k= z4Bou!d|=k6LZpkm*1JXnCcZx^G%l*|O-cu61X2?NKMZ@Z;bR%02ZKO<ajsY}YWd_RV2|PG~ob#(K8{Cr6oM7ssgi z$4f~T*op;KQ{(j2y6l|{na0y}!Uvi|QPvaYGhLnE7b@;m9ELM?B{gd(YneS_WQt5N zJg($BA5N2kclFKAN%r#K+7sJ6di z{CByNAoQ!KzO?jdOe<}@$wbF``S9~eyvsy*xE%R}Y_&avrz{#cF924fHQ-RiWTzV^ zOHnlDDp}(T+6@426T%__*E_smw`v^zuo0ZNW3F#0t>Xj`PBu69FC){jT)}~HhZ6~l ze~*@?w8qgvK&`IQwgza%wLRrBbkq6W@dH5RRt5NS-YOhd&(}+xuL7lIMI271bUlWw z^zpc5{qUqUQEHYGc|>R#c6p_{pUtpW3vsYcoCQ>&erQx^%K-43e$@h7vcu`}lBrqd zNbPs3KO5K|XJb=Zv@m|FI`6W7VB$k$lsPtCZ;!LEwFMlk@Ft%pHTNu`Cg=CzUjVyK zr|$C#n7SLN;A!|3SvF^<%EIy!Vt#?4lYn(pz@McAv` zrQ$`@Ij1`b!EIleS7;^}qvY!=JSn3%v3@VxWQ&VTo#bMWm>6ZeJFGfABQ!gATK$6b zRhF&dQxP$kk7l)JSG5$&Q=TD*ici-B+~@7-%dB-Jv%6}^qg)JQj)zy2!k0v>mSI;` z3d6LtcTxryG{CRO7Xbym5JJQ@mk+l3rQU!+do?&bhAGI>2g7(v}M_={wYyuch z@HVC(?)j_2XuQs&)zUcfjK?>p+k{oVa~nTy*AH(PepfWaW96aHZMy|TZg4Yiw-nU6 zEr}W%0lF{!YUwO=EwXRgE^_3=BEry)yT^X;Rr(TM;nTUp!-+g^UaDFt$!ztL_$$Q56l zw|;0uL1(MlpY&!+Rw2jaSYxII3Ss4Kq>1H3dOb%vR^{w#gX_mm@8IQcr6a@%3iqQ_ zv--l(M3#NSsl1r?MFbWPeYUeim*f=W1`ekMdw)U>GPr(m-h*A*-8eRUHmO>iez0G; zPdA?6aj%Pnw72bdmxgG%PQAJy6zpcW;-v^|d><-ns`GMZSIZJcQyO}wQoxdj z`Q9#p_~Vv&9JD$-N@Q0k=K5^)3Q#@zi@hR?w*kvssovf#czFR#XxpG=9zC^ zKXo~HJ^Q|cI!_sC_EgSY9sfTr010aNO#x10$HZOqzKV+tR}OCCq{};#jmS2NRAiEE zy(vy#l-|T$)3=$V77|z*B^uvpi=YIw+M`_f!-Mf2?_ESwPR1O+DT;EvnV{#2wu^9T z#+x{!cckVJo??01MZU=?`#TXPs3@{-U?(vwiAijKM}CH&JIQc%KLZ*0ilpO@622S zLRG2&E{je~#85$pS0I3gYtm||mZcaFw{-fsuYxrcWS#Bug)0J2BEF23<>op;$Rpg% z6+LXug*leCX!jTz%J@|1ITQRp4FYd-TSKqoXKZX!NrkV4=z2B?a{PCGl$Kj0P!zva z>C1?T<%lKyb`$+e)D*qGj!sAS(|+?eTSRmF06$p!UooSmfoJD9wX~&&k^>~8i4B+$ zI5YI{LVTLpx7kx?A$Pg?s2Wy=iGD-vjHK|zP+lWrx@Gt?cJQ2@XLxvc7_{UfA|h9N zd_{zl5m7Vc*XeQ2WjGuZ6j)swA`rtQN1|k(vz#wCJSHj@(h5B6YCdSkLI=CG5r=}w zt9YzMeZ}8>1&aK|Id(Yt!5aOX^aaV-*a;8-H3E8G7m02FhLNNwkswvD5Fuzus7Y4Q zLY7Su0o@onX%{^;W9OqYfI$M*^EBuPfFa26@NhNC6W0-Y5mg7O%QSx|SE0V;z{$Y@ zDF;W~KT^Z78lq2~ce;caTY#MmR(_*WroZ$J<0X1%q6qp%^Ao=oV!PL-$CeL&1K6&GR6ZsBj-F4NA=kHFumTA4yyDDS$DNY3_{HX zpMz$mPN`2L4A}09=9;~!XPUNEkA#0j=^gv^4=*oRt`ZG?bwb6;>`F+lmvYl%4{<#& zYY4zPu(gqbSf!$PUYqT0@Npl+u+g7i$y)1iXWcoRf$yxa7i!Bikj;t_TUP+FA4Z55 zXAFl?*cAbT^NH;j?bFB|V6R;#y#6F+mV zob(jru0v{{kq*uc7f2#Vz>j=wAl^HQvc#S0a419mw2-Gn#|7H&(&u-`YMO!ZRm#BA z5R$U4tXEig;~9=uS^=vuTI7P_R-QHFH%z*jAH5GN|3}nYheh>$Z=iHaNJy7-Bi#ZD z(#_Bz-8GbSC`xy?bPU~%lyrA9ba%%+e!lm2@4xd5=NZnk*WPQt>kY+UHt19F!}13m zFR9J6a)jVTtGw;4|7E+NFcOo_PE06r5UzJ)X^eXDGE!52;zP)pal^VYOg;>;O6XZ0 z8kB;6CdhKDyR22!Ih3>+-R6sjQqk)c>9DdUR|1IU=%^wv11qjWm7AHEC_n6T;Z72! z2A|{|5?$@C0uKkMKK};pvrO}$PS#B$#Uo8|VDv#~Z8fA&XV?-VIU-wXhHZIJ^xD zxNHyN2kV}fG;QyvfX~0GvK;#*;JwK#T_~unz>1CQ=dc+4`j5>-ULPp3tGv$-aon3c zq%mK{FT?#?`1;O)$?H_>2Mob@5lXWRR5FanCQK>!!!|?#9nFB63taPcPeF7S2tNSk z_c2LHU+j(>>M350oxZ7ohq>Tb7Pg;?@YN6!m+c$G2`7=a;Or^i)DnfFR&@h8eB+cr z)1V{ItXnE;A~=ybc{&!Q7xnP$OH4vS=7g;QKHyZ%&0aZ}I!HFp!>h^7H4%$ggk@de z8MVw#24>PmWzU7JQjnrC%MTFM{{hLpy|f5$D;~n+z__H2jH%W*U5d1PODuT>T)HDW zJ2QjtlwQ*;RcEY&s5H2%=b5oiV{3ur9VcNgby}x|xZ|u>0O!R8K?>q($a>0ONPDapwBr?YIm<(3Zc)mY>X&&zp{K-)OqVjg+j%>csL>1#SML;QOQJTNLc&1-S1h?H;IE9Sj)F87Id+ zS2KJ#IGq|G87boRix?H{?}t7-nnDDOFM4|1)JJ!bMkuPW)n_m3w!yUQrgOVYcE&$e z5Zuw%N4wS9`vV{zZ^$dcX6u2Ee!gX$)VnwN`_~nAz=LVfu?jXPCv(*?`3#6k=@WX9 zx_nsqF5$J&>u4d?9ib?0PeH_0urVP0CqoG5G^bG6`RH>jk^o?-a0{zz-~3bG&^CvU z^4=>utdgdvG&?Yyl%SDIX4EAJTWar^tX9Mfac^M;u2F`9tJ#l9RVq#;^$m&F{=!0| zySL2tT?u+bc)g)(9fBu<<8E{;a~o0WXPxU0riITx3&!dvTXw*U2cCbKBiE>C1gL|G z=M2YUODoKKSKQUOO{D(J{PVks{`^-KL!F78;uEkKBX-EzST%UQS9khDn5@O80kAsCrecUqnM~Bzu=p z=frYEbBiQc6t}_3OrCjqeqIb9t{{{12N`kfNk{PV>P+oSF~rl?e{^!T?|s_(0C65v z3uCMg{x=@@BMY=9k&$lwMzn8_;GeP7YS(#1z}qgsOl2pWsOCK-!e{sUn)d}7%84=c zd7vPp2^vJ}c=FL?D?}Tbf`y+Nvi>A*zAry~jFX3bmbRs`588a!s>L9+lrl){m-wqMav zw=bd+z}IG!83(bxmT+)`l~e4L?SwIsvDGYSkP;H&@~3%lctSe!s6X^HEOX2<=u}`e z7tZ0^Z^A2k{hh#{nFGTD9PFx+r79ft2DQe58o8CXIxTAoJ`NF!sQ4ujY7cxOoSWZy z@$|;g(8Cy5SVCdgKw|b2#yS`UgQpY&Ir%x`IvNk|-%hHgixweYM!e zA8=*=S}9}*@~kq_a3fr`1+EPH+rvnLcgCN431}XjQTS$0VOPGlWvA_Jy?f_}2_3z7 zYipIW_m|p4PLNT%&b9dBut$>~Dy!lr;LofLFbq~xe%H24$*>N>5=%dBR1kUfCAZyQ z1xu&I%U&eC`10G|Dh5(XE1Xa@*2ut<%F%&Oa`Hr)e{}8;+}~{DCOhsBI#mV2_q1+<(H92flP13%H|U=^(N>HEOTgwQ%DCZB z^gIL4Z9DYGeZVI?RVaLQ&abz5mp9Ooe8oB93R;}JJLKn5a!*~ z9W_Ex7au!$j<7H24?F#%aU=f4L2hi80`Vr_d z@Y4dahwyNDpy)I-yeJYEFvRb?+mkyMOsB0By`Pm~{BN#-vgCJ<>i_iV6TGXd5b2OU zDjWa|R@xO6RaFH5eE0W!X7RJlWZAL!Vu|nK3%PeUo&L(Wy3~@uB~ad68#jP6RZjvb zqmy3EpFj=4{3 zC}Q4722qv;CZq%Y={76d&KtLnR`&L8M__-vf)8+Chys?TjZ3;L+@zO(0!S_+8ygV< zb4Zge26Ko#+$3pj-fV$7!m_OFYRvS$t;YD^fJrv#plaHewqv7+zG+{7h#OeuNGj*l zAeq~}V@>JXJ)yOAy;NIyjfC^BFM^}BwHDHHUcuFz+p`6pWS8;Afv$E^*V1JKZ)353 zcGrLU;U*3c7qD4`Z+)v%O?!lD6+q-JG} z0O+leoo-^ohtduin21Hnn0GRB;TncIobXF2G2FKrr68%DWvh8b(NRn6)H`i4r6DCq z@;S`f;84G^j$r8jXfnm6OJBWgyeg3-rr_TVngl){{w;n~1rj)Cs?CPpXU$v)WYGq4s`SBbgsz*+Wtm^%IpNU@;op_%eR04KKj}2u5-LT#+>YcsqYtF(m1%O?0SP zW;FYBpBUNwEq`6;n7g$?_;WwCr)uZGtLd_W?I{*n0g366% zJT!DowOcoIo!Z35PUa&1OOx3rJ1z`9@}XTN&<3k)j>9G2_YlHb4D}0sw6UU{mZikW zs}``<^S0^tiq)LDImyAV7OEVaR;O)|>tAd|AK&ZrxsN}bNFlgm-d|!;EnKr2)9WNL z%UeFGy7{RGWvAGc;ryC!XcD(vlbF)Yn&O&=VUs#u&}9Gkx!-2)T;cYuM{44D<%jUn zJ*{A}L=)pQpIT85Hp7n#l8!bQBKlO)B)yfoFG;O$ko;ih6XaI$31Xjjj%&+(Q|%}+ zy6>7;xkb*RwWF)?44FtmC6#k}|U;=gA35MjzGDQS9lB7Y*Ogfpp(@`y7k3h!mB zgj7{gU92y%F>Yr9fY)5w_Fd`+w8_5|X8|7=#`bTD$NivIfOhev`zVs2eVh$}14SRG*J#Lqr$ zq#kjBfWsHFHbyI>h!*0tpz8sD5wd6)qPz!n}xt@W#x16^Q%E| z7jVE~OQ4_Bs7@HsezQ^28a-ObQr5ngkUx=C{KNelP!(QWT>Krq5dalVIx#lw?Z>D{ z56?fntG=~&LbkHfXR4S=)R7nH{F;xRx-y=InC$uM;Sn^tUgXANH%{ z>sN2#6vjSE=Q4*)$D&n7eMEF%iguzgA#V*HSBRRp+QB_45)JunBBktcjEn%wuU`DYDKf@5W6GqBQ;N9v#pVih*0QdS4RKeH9h%Vhs^x#sgpXc@DUx$Zt^~71L_3 ze(WC(q6t?pOw=dBiNb|Wh24A~to~~{Z{8*(MTIOJ%g4VR?^oA+9 zVgsB;3k%Q6o$WC7$6@6b>)t2Ntcqnp@sxr`xLC=`-{YrECFPWw%7QzmX~xu*Wrt`pb8GIk3%D+7w` zre;8|2#RM0rBmM*$1$o5ljb*}2X+EI;L&1T9Dt0$-B92HaT3FD##O@=+A|8c1D7As5@bf0m@)b-X z6MFbv&pU%VrI;**S{wUER&k`F(T9gXM5HNAKvXJi&4>fV6o&j^&L%A8YjGdm*Zg9& zQY*_MisIg zMrcU}yao_TPrfw}*H2OBCtvPldU*~lyy~zcf=YX}mi+^rfU}#<((7cosl*SLy&znVLCR*EF%Z$3z;sixX{s`9j~tFc zLe|rnkBRHDlVkp4C)`8c@@%zgm%S+$)m>&nVXTm*jMvE-y3A)T*LOF>Z~MvjtVs!gRe4VmvxwO8JfFdUBJ~)b~ zEWgpS`a0*R+owQ*%JHMRk|`7Xue5bKb)TemH5H_GL<}xVc|k3m5+4dY-qe_s$u@;y zmG)K%BI-XiOqVn&{Tr{@MQ1p^OMvUFiqv4gqRuj;pN$o!d!q;NPvtHeCw1yf$}X0- z>(EA5sPT0R4xZEB9kveb5*$&KHUcl>3l&NrbsbZNVds^OPOC>1*?yJF{-jUXS5(M$ zB+=CUQDI%{3sjG!Wpsdc{OL+~&_Fn3#6e%IU1EK`)I!biV$G7m^d+Nb@AWzQ`t}8j zF=!2G<5<{vn4eA8_dUCVcVe8&x!G510`_(EwUBg9p8o1@(r0j}GIfp{e-Mu7=KgUh zPYScl<$=6$QHt_f?(dGt$`$1EPYvHFE(0G(?^%+=QQ^_=0<^0MvT zGayTn&k&pm9tNmRYoJ!6h7>Lf8{bD}9cCpi$K*JFoTCwaG=>FOfMI^5Wde%^MPvwp ziD01jmk{bJK^`nEBek(v!lT{SmU9!6orru3l1cS)a+2xEKum{4Gtrily)JQI&9MGL zm*8EdC@$+3t}*1KxHvjG0L|H}eTQKllK80n!|$uZ32=Dg;bY`NAPE2gs=wXG7Eg7t z{aN+k&;lOP*-z@Z_w(*~A=E~cIB)B!%1{(k3J4_@5L>Ob$+4tSucBsT3ndCEv1kbz zs3YeUbQa&m#)766?%x}|?yhU~m&~lH9fB*T?ED|*RCx`37e1NfQv8LzfZ;Q!_*qtF zUs1-oA4}ds!8ihB9`#L!I0!$m1n(IyQMo9ohMut%iE@cF98D7*qqKQcz8Yr}1OHS@f zOlqnuutfm^|C>V)^IYsxO~mZ3N2!q%bto@LNT)2+>6pCKd*tUoab<%YM{exzE+gyE zIs?e} zyqmP4qBc?JwD-azm{*|0!?EO;hAeu=IJj%4c?|X zqSNOyek>BBG)hy;RDIIwv!1oHFM^RZ>NrfvxGq7`!r1miymsZ9KGXU z=PagCVdOp1pKFi+LrkCjM=QOgHV<*f>_2BQsA`30f3wfy{`A}{%pQEAivBa;US5MS zXCq8{^_h=W92*5GsJT;^*|b+HBJkV!kN9e&k>bQ4tuipXL>1`cmYR*4j4#7>r@^u*z01oY9=mP^J3@o

Pv7TGWe|!&mCh2Whm<#_2JrP%NX(pDiIGN&%kRzmZ|Y5!bN#0LuZ3 zq6)fU5fFHdOl?vB)Mn6|43KLrEiHjD3fD!-JmXzgXw|_F#bC}NQ;W7hpLO`7XT9{a zG&vI!6TO3(VIaUMVe_~EFr5onJB{+DtFJMDke5D@|4}a2%(tN_{Yooj!~xOTOjVMT zBT=qU^j2X`tQuUisWpIZ2h!~@2c{dHUYC-YMAYwGi}|`qpK6ts6ga*<-!8^>w_~(y zkDme3%T}#k*8HJwR`>2l*6dsHkD0sWCSmi=w^YLh&O|nb0wf*i*-1(j89fUtST#2} z-O?{7WcH8y*TVH4T*v#l0!N{b-?lV=s_eZh@_W)^GDsh;_~PArX*jLwa}`nrWI!-V=QJi$&qBiN#6nO>pfcY%2+3_Eez;X}Rm5;PW z4qOwaYRIUK3|c8U@~fC2X?9D_9)}QIe^VoTL_~B#(bfTVy_WtG-dpmh{&R5IL}D7K zX>If6K$a*d)uZI2*`_AewmJMrl$N#>tH*|10R9%BZ4nZMbzu^=qtk8Wx! z>p^6Rqh%ssLCYwxzQ;zvMY)2dqJ*i1O*{A0_gZ~qWn_dTZhbW`(>bw|BG0q##rU6$ z0@xRwSY;@(L#rRfOA^N6KmWW;cS|}v2wYrbf(wWXa1!I{?Nw4!uXRy=sVXC()y4?4 z>V-w}$NC?a4C)-oBRH!iPFqMtY_$wzWy12<>v0xY=5+186>qc)Nha;<^Un@-tDAyBE!Y{*TCs!T`awsX^a zwzE&DNNRCJm1?M#;hHT5`(sfbUy@m!IX*E|57y70gEFVfmInAKrRdT zrvOnFA43Q{Ik2YzaW^2BnRIF(*+)!H{N1IYSj!tO`ApCvpblu9kHD+dpL9lbHiI#apJ$gM!MO_ii?x` z@&#gotz}{Y4~QksJSPK}u52xa5??J&hr5>;D%ySIs>^!AOo!x1g(97fzSDl7$}`Ow zM;OG(rYd7KW4AL*tQVVaR?gmLW%Z#lV;rAU)j`9v)RrY6UW`{o!6T-`xR<61F_Fii zU)|QIrX9Kc$vNo38EY=Zl}j^x+T18_YBLJX{1z#dx;uMnTaa&7UkqkR;xE^((E(Cw zIIcy%#Jj9~&Q<6nlu63RX>NvV{@O4*JHpMYmEqW-xv`w zWoe(Os4%jHcV|xoWfFeCmapZ<*6v-Mj!149w4L5FxJp6%7{icGl%7={5 zP(_5V<9PIJDk37dOOFRBP#0DB=>w4p&wMixB192s6Oe|6E}TjzPui0$0kDBg&er!{ zjnz)-iNAVI3f@jOj*Lv9BES{*kHmV|p4Vv&Yaj&XD;gW=jQ}16Y-}G|edBiw9(33t zWI(b2k62u6p7!L#8N{hzrv_LOHzavY zIz0UsjSB|M&Q9!jYu&#xz_BYz1!4g5kcQ4YgiCJqMMnX?V)D=qq9aUK zZWQ#a{qb7^bC=3>q0>!H!^Jd(yK@%--CO-(TCyo0a2g04x zYK{A$j{CVV$Q%&z=>mEjPQBk@aFzYYBW;NFgR_HNb7?sm8Z!lUdIjJ# zTm;y8_fFoLomKhkD;F*sP?%M;Jl#MSn#d$Pz77Q7MdR&JCZ#CnsK98^4Zu>sMD?f5 ze(Pf~ONF{{8lOOtO`1NR+3pO#6BMl9Jz6XP9nM0`UY>pglj%Y(Q$SkNC}!|uwGuJb zW>^1K^9iE35%6VDg)gFX!--G;6{Q%CM=4VM9(hosKn^mVEOJ9}N`vd+><+#M5ZF&wGA5XD;gwR>y&v>MjlIfR5$O2R0G zru_sk`CPyDL`4Yv-u;|dr=}s)zaL+me;i2$y}FV|?A&L`%NC=27bHz1LGyn7`kjgn zv5_r{B28>3)G5xzlk1CfvdYu@&0X3>0K*cRS7X69EMv@? z(lRBs<3TClbjAJ6)Qz5eJlt?Z^si&LshtSQj1-i~iC~+a#ox>O-e?fAtvo=!lZ2QorPG&C9^Y&5y_K-hVL8 zBO$h@x&xZKqIFc|ewVWj_?i3<8gdBsB}#@Sy{~ zJ_!akvt<)Uo46rcgI&Qr|!a;utw2aeQj6_w8Ug%6of$~pWG+ z*&Z!71^vSVcjoNMJ9PycS=ClT({S(o(YiMrOMJIT*w62bSN&e6%5)MCmYbX1;O+gb z|0*!rvterqG6rB~zY+51nS*i4)v{X&6cigi4xXGOM?#W-@n|y%kHUieuzAk;{w)F9 z987*brbG_PMkPvfgtGdynN$hm%$$-!7bd9jTWP?Lyz!-Aj3Fyaep{?0K9OjgqM)(x z*l8yPosZT_aXUD3mXtQ$!iq{tsLBdozhX1ce}mxpe?UU&^SGW-se>xm}U;v@RVoMk3!GQ;}{>K3ioE)KE%BH$Nuu)=~+ml+w|=5DqK50K~km5zEyEE4?J38 z%k1D7#6?esR$u6%so`RE>V+PeM{dk~m5*Y#>DI>Ma7=vkuKOzunXO_R0zZlEFRi?(*bN(#zSKLZv~8K@7;|ghf54;FT+8Y14=M`FWU$ zE-G@rM-uN>TzhP{i=#TesuQ(cuG^WkrtN%a(_wNaxfJ;1fp+=sFOEH)l;!K;NV@N= z<~Pd;IlYDKl-U|Hn?T!n46P1d5ge5nntyp;raPl_;Q#l-SeQhxC0*nws1;D zUthljF%UQs%GCHtXWx`Vv}^kECg!Wntqe6fUR=z1&|C=*+%X4%>n-U)5j64>Bb&d^_glChZ)}5K`qU zg#^C8uIC&vI}VH1Z(sBZtgEvLZqeoCm$y|xnQccZMjV@Nt}jl|h_v|KbN=Wp`i@;R zF-p|h!o_7ecJ4Wo+{aEme{ynGEuNU6q`Eq-oGoDM)-K2&S$dB+m!WA&r@7AIYFREv zB6o#Uj3^ur%t0JFNVnf-R*w-c51ms32oOWXDi*tnsc9DD%fdkrU5m3-uPpPC)B)TV zsnRfAUd8}7&-j677P2Fl*$T$<k|lYXNd!Eo8+{hk%|YRLA*iGKQCeh9c25CqOqv4OOc_2rAim6hl~Y_61liW}FVkC&zt|Y2jbIjJ z1b!%s$2wE6t-#1T0EOEmq*3f4uZ6q)uBj^|)yUeY`Lf!%V%QP{(XhB^&>k4GJ?S2U z1`YztHY4uaRUfY9nbe-=tLrMM@ORoT>Wt(=x(1OJy37=j;=Sblq%`%+}1T{tc!cXrePaoDcg`>PHldi}A%40fSm2T*3R1`!7zXCKcczdQq8MT*K`W zzQnT{KHuT8ge;2}GsE3Hzm+jmv&qhk)|V$;JXXEoVI~T*I3@-r$BpU_B)Uj{gID~u zSfp6q<(8I)c?f61t$t2E#`3%Sgys)VNJzLo{t0V4UQKaeF4}J4K}*j2ljTq%#OI4@ zAwh0b3hJ9u2n2fEFsJo`LCrJ1@UrCrQsYXo3d|dvOx6wrn=hUSp)$DIPt}$Ts%B=4&EIqoREnn64)nybm{f;@RJ8WiWq4`D0GRA z)DQwqeH)v(^zcwDpQ0Moy&(-NYc%RQ7tWJED>HDgsDNxb042s?9EfsoYo9#7y}5~% zrXeIEsxNcP-vyxw7L90PY$dXmYeafFN1ILjHrYElp~FL)n47a8F8cazi@w9*J%yj( zT%8`&JWdB@FSX<*Cnve}MIX zKl5z6d-et5yA=!L05`tAzP`q-SUFA#{`P>S9kRiORpR~)M-?r+-#492q<*6b-p`@X zloGKSo$_HB6xt z=F`@n%mfH`XD5=wo-g31+lnML=63Rkw!cXv?Y|zY6qXzKO>!-C>(zn6i~zE9VE_SA zZ&g2e>HfWErpeH3zc{mIIiNH8RzT`?zS)cW!s`2L&TI^bQ5^VJRUtW~PXK!d@*FJbB4Gz*5L5{~=j^v>Z*4723rBjpNFn=&{+f@_t zyy^hO^wtp@feMj6;GXZXS7Af%as*-5Zms?M$qCo~L5b3{kC~a!7t$)SBpZ?A%$voyHdVI7?luH$mrH<^z_tFTzAQsnAl(t)g!JC5BMhxAVJCe{UE=uOu87yO#|%- zWI|8jk?-Pc^@&YgxTX1pDJ)?qv9*H6=8(c+o;})hQIPnoLv7->pnTPCb~O6!C2z+QQyZmZNd2_6wM*O} z=@$1k_?9h&zX@=Lc*+e1pbyWIjMS8ny2nX5_7u)OzEuyCEDJ4LB6@&xL^}hxVcb$! zH0)-2VTuu)y^HD(>D^quy&&vX5x+f%1n>QZ06VA#l5nTgye4m`+ z(0qP-d#i2G;d#Mh{L%|b167m)*K-#WXi6~JKB;Y(J zwtbgvn)sN)0J*kNUv`Q0z1LVQ=hI)dWwST$<&mAdt(bg31fO;dWc+m=&_vJ6n_U@| zW~|dp=)?HgUBK^T7G`tBLl_H9^1T`S37<0 zkcJZ^k4kc1(?`}q2U(41R+t!+J4M8f?NVc-93>g0P2TD1m=~t^+#nqv8c{I>iF6qe zE!ErQ=bE%^AG6ifXADncf{u5>GaIF(T?*jL=6Gw`pY2TBQ}lMXpqg;XWy`yAs_@Gy^n!h z-8xVah8Of<9c=Ixm%(*%_Fg}RsTu{To9n?34{EZeo4PK^IjJ$~F55z*q{fiV83BB_ zj!}bTj$xp}#JqthPOe#{nBK7M#A33sNe~G+$l&3T`ty5(*iI4}@rDnwa@370EwKFG z^qk6?nj6gG@Ev2-FYbr&=AidHd!bE&Z@)B5cfBRvr1%;Ya}- z%Ej%Z7U3*uH!W-_?TOUXnIoZZW@=I+YAZWhxLlhj9aWjLCOH4n!CbG2b31L{N1^;O z%R#KT&XwzOhqV(Rp6U>1L+sFj&8(m;ikI4uCwhLBV+;V(CQi8Y^|(k+@_5cpS`P6J z=VUEJbn9y^0fFs3c_5@s>=FM6>A}C@zs4UPK~GVu#cYo5x5=L)}16w3M-f?4kKLAi#hBm7?ujd8ghm9b47zG-V&gr=A5Yyjt`Jp1Ki z6d3fw|1=x@o8z?uf31$ur32e`URcF;<*VqZc8k$;)eQT@?MlbR;*;thW_Bp9=JM#I z(ps+yZgXg#mCrt{sI@@aRNAc`5@vo6&U5SY6O$;5P`s5mS;*2qyb2PP51hvNq^Xku zcILIZR<`Mh4`(T*wf^5W*G?3omFW6~b2}w!@?9_iga{^$msWS_$ObwGAG{6Kbp_s2 zaoUq?q>}ke1USZIxNs}fQr_~3y1Xj`34`uUy4Zx+AT4U@1U$S(nfkXb(aV3aRJHht zvc>>TH1<@X=GGemS*XrLv*LpwU>X68AOM|Z<(o4;xE@vXh5=f^cRKpr08E?#W6aow z$vET4?dc05;Nx)uij$;y15&_Kj6&$|dU{;zPb$?dBh~1Hj~{^>@>vG%GaIF%)joso zYv%3A=iNL2*ep=W5_fl>`yRo{MZ1#}R;n+^k2+aF@Ieuvo-7jof4FUEx^7x18()B! zKQNIg7EEv`Bk>`tM^lWIJ?MNN(c=3|_dZ57maR|}Cq%WcuO#5TaTU({7zsBArEqE# z``9^!i4_P8gNZ54ueCJ?>2^=DD`%kB>v83=0ilC;hU?0L6E5&6=9ubOJ-3}8-#fRQ zdO=;Ab%gWq&Rl4Y93+Z?B4YuK!DZj$#QfT&U}bf(8K`L@bhWj6hf`SJy!pO=e4GJ; znub4DM2zI)AFDAQE^H6JbV*GsRMOH-p%ls8Ohr{6?C-Fe>Ql#%gQhkWfDy;9B#gb# z??8Hbe4AdRm^|JnrW+BLw491l1OC@6q-eBD{lv8g&p z4_bvFA)y@nr+PqJQ4-}(+q29qzXh!vdxyU{yI5dEhhOMzWOL$2mf~)xe-L~75B86a zcuM8OTV-QEv^-|_i$5v69yyQRZ)mqZ*oW6dDrPF)28K1+8o(f93qSB4}Qrc+%*CmEYQ)9P!!4MC`+O-;q_Cwr!OUS@zNI2Xwtu_F?|;Bn$= z$_%&xQ#NO4yQ(P*BLng?Zf;Wlv0W1YgsMIivpL*J&!HK|+?CM}D|2zjh3$xqMM6S? z^CzirPnP~niJBe1c@0w0+5-yob#n26xGVdE6Rg^Lwym8E0HRx34GF90baJ&h>NYoe zk^w-ki$W?->5mjHUEmS{$KZgnjn+6|hS!sWkBJM_YODY3|M`Tx$VG(r!c~2FZ*2Q| z^4JYv`m-{PX+ z{|_|9+El%D%wb^l&m^=kG9t{Xc$+lz$uJA%4q%-i+)3ASxyHD7GE<^9O8$}x`z6)p zA^hC9q7r-J0ARt^lYi_d8~0}uRs7Rt8>N_V)8i{{>U7p?^vK3f#B0LNje$4YiYMONt1qe(-c2&WUU(6!* zuCUnc~Sg~=>{yDlpWrJbC2}%b0=(sbWG%vHXTo&%Mju zK0Ep5Mm(^KDjT8bcZVOnIK19eZ(RcOSt5qLoV#ABZn1>tx&kobGf2TuGlz=}*|rua6w#$z5aI=ih+Et&G2zQdHd5^*9C|cGQ;u>)7!${~>%Ck&ncz zbmZ>q*Y-=-k1)^A+Xz8zfCUjF2P5f8VMPTNM?>U@|LXJ~8BnL2b8)~}xXT~)Q1l(4 z=z%eDn?rNJ@KMdxwm0cZPnPF8*S8kOHpkf1#BwPaOu|q{Rc>OQe2ofKJq~+2Ga=;7 zSGgR9Qc8|<3*H7kYW;CeaTW8~Dv#&m<73(wX%0@#be%c#K*8T!uH_twSJy6-wn3%UKUObaLtjKG? zeyIm7)%N|Hf9HFNxh5ps@po$7WGMM!UX}NGA3eTdrT6zY2k^?5s52s^o!#EoNBDQX z%?Y}?6kB(HhW%{hw1Ix80NEu7hye5XAsuMvBu*KFEsX*Pt=dwOuKy4b zN$Voe(#!iA@Ug7o>qZ7f<6ivptc;}VuNS_0P8zWk_+JjtZacP;k|FHXmY?h^^L>cS zb7wyjDG{q)9fy{2@1-vp^tjm!hT~s-5_fs^dwHhxaedRC+&*2rlC^V|l$NGwMJW!J zlrqfUP%Uk8m=Unh14D%gX~e9OVM_vl2Le?44Opf_z(Ji^1#S{rNm%3@-rb$msA70@to^Nm&Z2q-bVUHw~^S(^!ez6NT^ zfVEw|g9SJYw}fg1Zo$!y0+qjy^GMC-t4z{wSDCZ3jecpdhzqa6a>v>B?;yg7rJH(9 zQN~Dzzr3&oifcAwm(cDManGgnVJ!j|fUQwy5WEA>&{E=+P!dO^I*TaBP5{$9LKwPC z_HPr>?$W5 z%rB^tlDYn#MdFzL+Si#NVs`-VBqS%#R2~9NJJCgR5$Y*&ph!v{=%kgvdU<*_ z#kSgmU{b#F-3y@nd<^;gp7G~Vn^`%ROa*vy6|U|6SrTS|ec&`UMLCFp8Vo`w+5wl> zbXhdj-^&valvz133DVy``yz;E7Z(29+%yJG_Ddu}S-(Olov{GY&_$BvRh$q6VDRc{ zZcdhl_)zR5K2-QfWa^Mp+Ave7E(PoEiHG?U5bou)wvvj^+szyEvaleZI9nZ;Y?GP_ z_Fp&=72B?pLS>)yEsJytGtJ{m5 znSs_g;PYD)BzDKNRbOdAQtlsjP}0Xv-OYd2*qSBf8h_CA@uRD`VMen#o$=)w@f7F# zR}{UQ{G^C37@rqbNvMeBOuZEYhQu}b1Bqu9q>z!{Gz*qO*4?u+FE0 z3DI4)jx)XR8#2!ElG5)bpWOZ8YIbG-uxK-(@MOEeJ0iFi1kl zG zeRH#e$TEzOk+PsVgXZ4gQt_p&O#~*f`^WFN%vqAMXp(qSJj+6j--q)6)UaXG z-RxS1gG~+DCKJMZ-$eCM+SOHHd)uJ7rC+B0!!=IGT>w>VIj?VaxU?xyJ-&fm%MN3| z_?o7~wWP|ZX|+*X8QaJKxZ`bv6f4ARAE{^-1HKKSkvnnuZ5toD7;l|GD$KPAq0bn0 zB$q?p8!%+<0h`se=qV|=&t50^k{ugenm>yLC9pY6k^*QMBRkeV4pg-c2pu`!#x4~T zGibPuMWp}UdX5AI!O|*4;eAXt01z-9i@-j;7<4Kb8WKUFP<~QhS-CJG5-=C<4rLS1 zTUyix8HZRQr=~u4krMd|5U0CvBR*}60NZo*%pI`S`1dvIU1Gd^<$U9Bx z`O;_}lduTLc>l<9Vw1+rnJ&G_gB>`26+UWA$!fquEpI8U-0W z1f>zxIbv|9Nr&qqM>RTDjQ1thJ7#+)_XXK?w)E@A?!`qyL}o4*)EN%kZ$sClNweM2 zRjFJB-(PQj(Id0aWmh$&x4_11KFIhETB(ytwBx`pqUj*$_ZthJ?9Nm+C|27X#TdnUn=bxrNJZwHaJyN8w6$ zm$f)`(`Jg5QIZ89lXZ<7=CYzhpUMwXQ-^_mr|aL?$|Zkh$DKMM)78_mn}g$%zW$ay z;gBARcpvBJo*WvfS-mp$sh<8)*MNaNZ`R`+0TG4WRy}BaYd7xg8|}?(xmGrSgaKhhGH}~B)?kH4ij_2$ zNfw2c>8$T!BbKjV0lyTIYIVi=HU4wMAHX11Hl#_1fYmTLw?2oO@3b?5t9~Q{HV$KT(Fo|-is`bUU zsHfjY4Ki?&vEkH!Gk_dA0*}c-+%)^~sHLJZYb2f5>FE6YFMy1wsJlXR4z_)%rO}(| zqJ*>Log6Rakcq;1Nwx}-m@8CyWt=cKcIdtYtNA28xete}?DV5;()aB_spk+>Hu}e8 zwnww9Uu&-~&y2cDaSZBvUuk_`c4Vy=zCXAH#D4Z#LrZxNoEAJhs}l ztPZlD1;7Z~O>^hDAYF!R}#mG&{8o$eWN$&L9-I`)qpWIPLUVZvy<$f5I z5zpKdtS{(-lSS_Y1+!LJu{mOOzV++g(_w*ebDQEdawSpj+uIszKt-otNF31EgBrf< z%%nm3Vc&XlzF}@$%5-=yVL(P(Vh~aG#w5^9VntE16Kt#Z=Z?9PH7I=7tVI?{pS2*H7$MOYYOxy%`Io@ zgwG+sT+8ymis6js1m}T{!OFx$hDQL3wl+5hpgrQYK@HUX8mGp3WpBx_C}=2|@yrDJ zIYYL2X=EFd5lx0wYEYL5ry^W&WfU(FAtG$92%Qu+H^p=jLg8%C3KQTxy|Ai>iACpH9+T*{t_6*TL!%VFaVLlFBWWQ zXt_k%X(fMFZN^bUaCk#M_{10{^y+-+2K-1NQlC;o2T4M|ii%ME^-3G1l6-B*`ukT; zT6$sIRY3rwdCsXLo0~0IWAeXX7Z)CT`~VlbdA*`SNA@QV>-;9O0I4HV(AbdXW6Rvi z3V%)}cxgb5DU`}@qx_aM4?u9K8GIA4U zb52|!&RnYToc0&7bssm~61l5&sDR=y1~*fcr=?H&=jPkh{gbx9_z)n%X_?TH^(M{s z(~;)lI()-;8M=KN#^MzDl1j4PIF4dnI9&YA%h0+>AUJY2#It+- z_>*IL(20PoU+mk)!7bSVTfH3>D8rljC9^jUA)^3 z@B&VOTZsN;TxZ4h0<3zzjd7|&x}e{VDM;9T>#UddU1*!wOAWu~?G%=*gWKi7iEuA` zl5k&7Leh5(%#E>HhIWCs$uj}Y8#n^*YZ*pg@YfDVT;rkT>Of2q*|-ZvdjH9W0O4Q= zhQpR7hO*lQy%3)dy;!AhOzlK-D1zB*R3+z;^X~||Z8tyXt3f~CK5vlL>qR70I(SXY z_G=lZmc~ft+IO@hV+(hE(nmS3vCwb0$?(yZuc!o%muME>V zrksmr;uDsRgv7*fWmX8es!t>a8UU#S950~54)EbXsA{OM(!0HpwKh#dCXw7Fy4dhzvN(NqI89 zzpozMD$g>QDy6qAAZ@T&NnQR_z1)mB2Wuyu8R89X_Z!aKe8M`X+2b7<*$VU-Nh2^= zIo;Y$tdJ{q<`5g{u<4PsY6NVl1V8ncVdkOHiD+<#b|%*{Sa zt{dvtIg~6@OSTjySE040Jl0~3Ssx#t)J=N9>U{g(e|XJdw3$}4V%t{UA9EcSJjtyunJ65U{7!j8v##4ibVpQWE;dO@wZmBW z5dC`;bjH-9(YN42U*ihjl!m|g@rO`n!FtnN-j3p5PqD;K#{B=${pb<-&>cI6QLOpr zt`yRZya?aHR2GyP&QM&U_k==3EPejS-@19yT`{5FTv-8L(POZmdBDtJ=8$X^Kr zdt{MUZU2&8RNuXjsf?%g?Jk8-9o&t}Iz4Gh-=I!w_STFFjjC{qP!2Lz98}a_a7^re ziln`{oJ>>Lzw%?;>?Y`(ES%RGT7m(XQh&`5pFo-o257j32DcJlJ&)p~Q3Y*-^)6ue zR3EZGmJ)aI;U7MlKi9x22NJ@*v2i9oqb(HQ9#8=ql*gwhfI3_+44_x^Bkv;#^9s7- zu0p#T>plQi0}Gi)!M}s_Q%r6=h9tBV*bpi~qdPQLkS5iva!;14ct*KM?7z@S!$+^YFDF6wl zOp>v^v%Pp@Y49G-9n-M!>PqSFG}JKKv*G(MGfU%>iyFXK9L^pqD)GDGX3t5~N4}L$ zZ?3Xz(Q2$^g@r3BtTY+yKt5j&u(lJ~UD+{Sr~MHR__CaK;YAJ(qo3Fk)o3N@5SR|W zl+LF9!FDPG>d1Jy+nd|lz0>sqwZF9)e=Y-w5n2ETMH_7J(Sk+`X=IT(L%^qG_Y45~ z14LIg;Q3c3EP^Ku`E*TQB~ z47vk75=ErU%BrnJVsIy_YtHfs#pEW$#iStq>v_DuY!x8jlsIkr56IZKo1c;s({D2o zjyx(#N(umk(D{d0B*QB%XmM%^Ge>dAc}kJVzEI-&De*`|tkj?1LN-5r)@NWef4oqj z;$aq6AMD2o-jFLiTxk;4GTMEUgTG7mhpAnFK39@?Cus$wtq^B@K3 zI)9_7E)sX?^9!Ae1p~JSb_uLngTRBpXse9#+7_`ygH$C(1ZO4czB zrA4ey^qbCFF0T4cY*3My)Bli*rwI>NZRTB#3U3Ya+iiywQuM%!xp*J`Kt_zkjZ+wu&?w zEzYlISFw&9{+Jo3Zl2bc$Ns?pg&fvDAQ@;+-X&qU#rpBo434nDc5S&0)^27TlfnNJ zhd+0{L9$jCt9qAQ#lnK%N-_POfr_?*hc)Hu-khW!sJ$H!oQ4}%)bvXGA@e6)R3QW+ zX(&PSHpd3r!JfuDpZoFe&0tWo{W@l)Y$8-S!DRmjulC1#@V@v_VO*RC&M2<8sPIoy z(&z#cfX0)|Evp@0v{zMUx zq7=B^*TS_dr9iGupQ}H*>ylAXQ2rBjuS>EaJweMmd~lkc1G>r@J10+(_9y5>hSy#b zo@nGi`;otXMhgTRsxg<_eldj;Ck7A2 zwJDC16#-A^yQeFe+ovnrsNR>KN0WU2ke~|&Z+tdO)ppuNOdn~FS#Y@UD6DEbWhvvy zkuDrv8&v)udgq@Z&DRgB>M5vg;{u^7&&E(ym6L?q*I=l+u4Q68tCN+5;t|O4EXgR+ zc|uuy=e3WCnpo|y^W+imb*?2{Dgg;u*~>}P!gyLbY(uf3hOC(AJ$6wkQofvGY5cg& z7$f2EA!Onc)$hUB@ju}c<5M}?1n zQl3l{PLh?*omaJ-_H`N{C}Iuc+sGTFe_B*S1WcVel7=~1%gbS)WSx^`%S}1HLA}bP zk`hax`p{VZ$g2(|bHu4;qZ=`ye+`KipZv$01&0*UHPFF31{(J{giQc56`or=j%82j ze2}hu)EtzQTDPmx@K&WPF9{lPD!iX*>;tj3j*ciWo)sXE$#=1dhfT`FFa0P>j0mSx zpMP`Tz3CX(oj3ZwT{nz0N!)A=q(7BVj`oN_l7qEZSA<4scJ{17=LU_lX(I12jSb$9 z9sVFh+_`Pw@TdV@Cno(3kC0JmULo4^HB0PGCk_))aso%H=xSeSS$?{q_7l!5uSj?= zmd}>*A>WBf$hIyGm^VJmj=2=X2R-x$c|*BfJCzS?$wx(`r8aF(de_I>0K-uLIRv1d z#JPG>RQ8@TIh)pb*{Up6a0dDvM`^`vlmFhwBd-{M$VwV9w6m>Fr9&t`=st$X6SM*o z=)Ju?6&021X^Ar+y+8FaUy=6#n9i67*?A@qn*GR&4~8vNJpH-2VD52P%@2&c zf75Fe>G&J#*hV7P&Lmwdo$U$DT{z_Me!WM%zGETZ8?UDC$c9KV7i4%~Ir-jndcQPs zK)R0*lt@oZM?3XRpW>ByEKBs-tbPk`xX`@uJ!+GFzohVe?lq^=dSrA$9&mTGPrvry zD7xZ%e=XGM{csVFZ?I!lMAhgQ!-3{gRPxY|GIqa1CN z8ETh3OLz%@q62V8Y8;DD4XDi$PZR-FRTwu@xt941DF9~97EVg8(bgYxsv_?lMkQGY znwDBoY8SVx<$lVrSp5Xe6|lSSgKZ$wW9JZSp#4D+cr<>*CMwL%hN3llym2@_flrr5 zP_!PgDog3orUuml%@j7W>S17?Qvz;R;OWIq7Z0oK@zBkM-z587zg*PuNg>SC%8C^o z(6Xh;2^u7)ROxc%!y??YG+KnEG0dgN9c9zgH5t_JRH;p|WPpi&cts_&9GhyJo7HjQ zWvBo(sEnH%!9Nbtahwai$8j4BAMjCH#)^=f`90~~pEg(IuODG~NP%x(0UjA8x30lf zMvysCv+50$+UtejOw&>6e6+Mr;Y#Zvw$uq z4Vh%*3nL{c#hpo39p~C9qx2+I%fdmI<1Zj*L7+DB>etp^KLFu=8%(-8+ujkD*6Cc( z-W(ivzLb;II(|=EI+xA(dPNnv)-$Bh8a%)1-112G7`3lxFZ8_Wz$KM^!e=}c0yani z3Cud^T|Ttj0$|pjd2UDNHO-qkZq23tVF6ISsmSSf9oRKzQ8n>CZ(H$f*AgfaL~aZ2 z9awwb$YxBX#SKK*?p>?u8yb$r6qnN*FK;)G(OHAs>R>y@j5{Oj$8Tw7-K7ZF?0BP` z6!wC>wMo#>(4fjRYpHM1TJl3tWmu#OPO*v~ys&0T(u2`lTIJ@-|r_?o-`~k zdTup1v)438h?_wJ*i8YfZE!F(Z2l+iD_vByd6@oBWNW~q8{k$35d*8DL=4d8=T{t> z(-WKMh^rylg8-wK5wncXZIM?U6}+;`-XdqgXA0AMt-F%#D~1!vPXKAM4QlG<4w5v9 z|MA(gSrt;`C4 zkBDQr5^j}3RL`VZAaE^saAcH*L=p~St_7U6Qi4mjGHWkxbb>4cj;J$kHu`RLG_jjp|mgEziqxDvmtHi zeWPq_r9)LkL;i{Nj~}6mv?iK1qaYr_xW?3zYR&5TXoa%M3%@t7fTUtN?%U)}nC?r=dxM_1OwLj%({~ zEX)2LiQshE*E&C-vm@h^oisIxfcZ!; z5WsGNo1HW0!>n&FS+FQw6*zs+bJ#XGSjZ-%2V{bBUOjvckBEQp`o8hcfBq>q8;xmjA_wv6!!u^N<&K#wsm&K zN}6<6_(>EMJQLfwt;M=I|5*qhcJXYCV{#;dauVSDfrNjBrtdJvIz5gF-{rr0>hxUi1;*1gOdF)djs>r=cgF%m zSVhG|oBs!`$;LkuP7oa{z}P7UbQ~6-xempRY%=5(?GutnmnmhE70LY3+_tv#yE}~g zu*Y}CBE8KH(m+X^_IF=dNN47$oi z8;bXH5vwT98oAgdgJr9obd{U?xTLQ^bXaPvEgkc;1cyxOi}rS!Rz@hs->)Cnt0|FX z;pzR2Tu+PO@nI6WpyH@sqD)#Zu(Bf*f56(h>8M&$g4JrLI~&J53Lb-3q16PdqvCH| zO3KPmLwf%t-5)gXXP^kgR@N85wM$Kgq=4)=3_GpQ)b3rU6yv8wlsc~QFSd{af0tZ% z^Nk-xl_N+lr;*Aj-Jzem`Ekzd zITCz4Kdb4iPT~*(n?y4d-z&dA!hf+f0uL?J=7m+8`9}Koa_@h_4P#}#a2JAj8W zkR$om)q@l53}7s{jloNzoXV%N{+U<@Jtb`kmVoVIW@BRzu(3j0X?cXtq%~qGY6y`v z=1uVUZx8S!J28*hyD6jm+8foBx3SJ$@vscDiQldN{vXxMbZ6k6sWX_NzH2`56vn zYs#3)fq;o3wF=MW_>w4_;FFZ^9#&DB0DdufkPGyOu&{=J;*+s=tE;V@H0z==+%6|) zLx`naxm!Kk&0_G(xjNQ1FCqYOOvW)Tb-+daMStmOx2NEjIyp@97NK}p7_8F^hNhoe zSojW9-azoV_DW)%$LZo9sN(?a>~u2z)Bs))qN)BosW-R*e?tR=IO_IFOH}dQastw& zm27T~6)&?0;D^2_-348?+f2+3qY~0lcto%&0V@jD)^rnlgT?E4=ADGD*Ys5BT)7Td zIgClj#E^JaNz(V{2DoYl`WFp+(q;kkBB1As7#e<{@R^$+v1_x{wC4SpFe(UDUTB9S5Uop8Ixz0eh9-&(t2Zn(swx)+Chz zH{sfzccTW2${DwsFPO&doiS+Mj7TOkDGa;~5H33Jw0+%QQb-|>FKu_b9&@AZ)H@E_ z%mmCqj-y3==$Vl1?>aU6k{zwvl>#lBP|^dgmv4H$!CAsD0vB1{Xd!q|JhZKw_udav zQcdr;!Gm_0-H-#Hq+agTVO)j*i~k@?LJK2sKc(z^xwzzwUmjgNmKG6z(JL8`+;AHR zVw%+fUv*w?iRJpYZTN+iN1oFZ$Iku`z_|jOrsAWftubTWcW5XMOaX6oiBa0Lnrfs? zexCq6LuoR*Dff_}sSVH#m;qTeKSl9^S8wKE=z!0G@F!RK>RV}Y{uQf)KRYGfU7kA_wZ6{)m{p+?Zt|z;cJWjc@$V@qKAmKC>f26I1R|ei8s6 z&I`+_Dlq_|cXV{bRX*^c_GAh8Wy%9HG39kJlh|Z8;3HK|^y9Uay1s_xeAP%GvIph= zMqb1cCmm#*43w)8v;YBB!Tk&LY_5Qj04AX8=i+tLRZb57j~`8e+#BiQ->2a%w9_oZ z(DJy(#z(X*g8YEDsd&LUKmDDID3 zUY>>&(hIx^qabYnl%IQQ$d^%|{BOiTEHQyGiKe;bWC&69ytJHk^Ha+A12MXWho z@C$w3l`%51uD%4H0T^3b zN9GiDo#_jr4_2_K$W(K~83M^|{cs>_t6MZagTow6uM?dXt8QI=z)?@c3lD9B%Ee znrft1)T0;>b{~Rt(Tyy%>y4b;rh{@kS-&lD=JqW^y%jF;qZ^#&$IK^9UlU&RoFvso zy)m>-?~Ev2thQSThv7HDp>mq}ZPDzLoVXvJHNVnMHntistW6IL@XS|lNo<9S&0@$W zcHUmGHoQIAxjSxI^)r~6f5Gx>-vGUw^AZKWZWA){W&HT&97~q?4&~c+yI%MIj1qE| z)dPUkq^_wcgX0ag{hW7oqkD_Lc`-USvIy=enU>W-2|7mPrlzLxNlAdshH+AC{jX%q z-M6W#!a{y{n$Q|#(c`0|f`3^5CA~5^K+V?S`u{1dbt<&%nm$}8v4ob$#Y0wQ{rq|8 zj|BNQ?G^l4GWT7rMq8$TVPqc4A4pacZDD6+F=^sv`qfYx&x#i--mv{ezI3w=k9)Cf zzLO4M?vm2qKr}UFL+2|BTUd}2FGx^o5da>{WSpFF0PorGtW|;FKI$w~Cn`C!xU`_n z?62LjC?_`#Bm*b_0QQ;`K0`n1pjzX^xsEmfzoCQc#1mTNpqK%>)FjL0wq)2a+}Hsb*tiSwbhrwHyYocCqI8#XeHbsk2P9p-HazI%)XG8 zAsv3tqfEaO{XIO%zH#}9rd@M-OgoY%P_KT(MV2da;`jnj_e|v@pl-@fVfIDQGLNc3 zAV#Mf>*z$LVNskOw?y*GJ#gvD=#Ih$_#a(R8Mv)CizYfksf-_>d7OItOFB+D{P=-b z$kE(tsTLIh!r=($l(pArSu{B3WKv!~G9o$hFMuP_f`10seqiti#C-$&xuT9vx+jJy z*RI8?Oty4ESa0`+tuc&jF$_bxk*ra5;&#qv3A^)V>)~%waA1Y0S&`U zQ??d+s@yTUh?Z~m5uOyuueAj(_@hB3>M(VQbZPfm&ro2++Lg$r~93z!C zl_}Ax1Z?Pk{r2rwj;*{U6~ft#^abQMtO#V`^<4wq-W4!=1Tb;UWux~5M0>8(Fy;{Z z6&Oso0KlgMbbN`G43ymrf(MlP(Vi)*YwTa}e?LK3N!W1{m}7v)D=r@1UjDb+fhdX} zLI;mIRbk5wHVgnF4xWkjUTdizOKXJc?4+$v`9MZcG}(I=9qa6bBMD;%XcIu2DQSC2 zfD?fPcFK8ju#Zu2~XSp1A z{Ad0IXpG(?e*K6AY);`A_>VE}ZXLcI=r?Ej@1BewUd|#Td6t@IWv;ajp|;%xj6YQ- zIJB)}J-=q~)u=@?!6cbA-l@QxM|!j5?s@N$yaENqk4;wnsWiloRBysR|HX5_sI_$v z!)G4xQd|?NiP>!{9Pt8y1M!LPWXqj$H!H2BLEFl&PwjYIxTd&~c?%BXs9{hl*O?+U z6Dupib#U}t#1FHMLc7)7d`a!H)rQ+ic2N~z=cx>$P3;2k2bY%7q?L57%kl7qk*Bh4 zk|vw=9Pg8I2U2u`U*A4hVx*5=9q0^$DtR)C$-7i1XYAI#wy`;7bw2!yk=)rS8GU)n z^r21}lVy*~lUn|)J0qCG^otoe{+nV~jihPPN$~q^1rd?N2wG27ljgupWZKY=1Xy3D z9KUldNq3*;=h@8ENiCno$+ADCZ&1X=Wy+do)#j~2+Vp-qvpZ#iy&IkO)9)byt>@cK z32Dt1Z@J#fe<#idFT1wFAqm-w1$)TUSab;y13(~56s^S z4MowYkWak!@p(L^MnLWWpP1lguVVdg<<4u$^HvD1pE;4lMn_oaE+yaSut3$* zw~De^SePIZ--%n$`uHpfA7ZN+IPA?kkfu^6G=R0-uOo%Q?h&o>3~h_|nAFzu(zilG zD>42HJv}$sRTT*-dfOgM%NJ5tl#t#-XFgOhHDteeY1fFq|m>!8w z0{tO8zBlK?>tPg`S$*gS(4Iv-jKktU1 zRK;U%Zf<6#Mma7G43VsORh&^}CebWkh~JD}-Rs1ra^s!Ux&E!Eqpm$nI+3Ted?s6d zmB@(k1rtbj+{xFOQ)C=`0BW$kzvUNt|$|EQo;ELRS*om1W z`AG*SN)P8tuM*Zpvb&F{@#D0kBP?HV&(UGD0k=TyjJaJiZQ}N87}R74YJa~L#t#fMYcS$3FKelKxr?N_VM}-WoBhX z%+Ifr{y^EWb#;#&q|7^Bta_~coPzqG+#|@LYMmb->>w235xOHiid_nc=VihbPi18G z8Xu1+E-LEUvY%O4D3RvXzbZ`6HsyNx@aw$JK5Z1(;WyzzHCjOqsj(mEC3}V_(QM_w zo_d4*n!v%}hed6S>wOBA96kO1a1@pWPa0vqaF?q=5()#8Eylcu?0XiF)9?$W&f9&v zPOZk~#=TzG5y8gTHiln64Gv4~$th#Y=F{_5YRX)T?1R?pSQLTImP=BXs0WBR4x?Mhm4(${_ z3>mJM?Jpa2yIvB71JOxgBSktMv$JzhN1${g&x_Fw`Drhw4YBF=0Ge`&9>HFJ5NsbD zSsF!0SQ_~Q|B7eNA=>v~^k5#h8^sh=pA?*s2hDb(+7Gg{@l80MBZ7E{c6U=0uu0@q zS;Gnoe(BTEA(~!2!dDXg_s8}X%~`j?5IC-gAmk()>*~<{EcclHflO5jh2K9^VpR2a zzemuQ6#adzlz#mDmsqi9ETwj!(|tH!$G<8z7F*ShaPK1<29rN)bAo%o(oS(+g>A{H zDP_XKAB_R!lIiK`D^d|%0>OM~88g`T&1>YuBnLlcxR-#NG(LJv+%oA#cFY)v^joy% z0-73Cx4hxP=Tw!W0kr~wI{JL%kR%ROK!m5i`dfp&CtK?vfOFuvRo&b7q4A;7G{W?^ zh{$`rhVkG@g6=)`=of7a!lgD3k$6%$Tg;L7Cg%nBIVY0rb>#?!c! z^!@MvIoYD;q#4S#Iq?QJpXvu~boJNwVrYnTL_cU7*`Y(W<@m2QEa?cKkQ|-tMyVTO zt*rUNo|fn4#%A(Ifm$i2-KWyhNf6|!P^fbdTDQglEr~yBtN}!IZ(kS0=js`GCoi5; zQj%xmvO+;yH^?Q+A|Qvyq1OEFL5c%b$&`r7JcL(&A$gFFr0glTT1fAm`mJ8yTmg5J z$kav24V4g413el4?vE0*q9X$v29_46X02WC0uGUGrCJX$G#*tHyE3Xcp%qs^yLO*6 zu=_m|6Td3#pX-3m8M-v=CaoU*;`G7TsAgI807wz$A+x^JL8x;DXkKo+l4^@*6vm{Q+s|3b&uJ#w_NEw0mUJw&}I z`{*FSWWhq;`z5KjooG)!#I$;hTu$&IQ6inf8ClU6fJ}BAiRme?H9!VdWrw^ zj9-$*ytQ6+ugu208ca6-X@vxiUWJo)kkY?8J zI*j+5qIRE+v5HHEIz1kX1xfFtz@c{3eI)m5!wa()#!sq)%I_5S3e2p9?>cT^wDEny zHvG)c(FGY>x5X!(hBcq}^C_H;o0kcRz2k5G1gyPx8kHZ;iQ z`%Fu&F>Vuay(4k1KnLLawE^KQ-HXhXD`^#!$t&91%vc!G7^>ak369yl+AHU({|31B| zp@dn+QVpF=SvWVFX_$a(@R|G1v7Wa>J)o!3LE~sHrK7sqmX?!a0<0T1_xG?8)Sr=> zTPH2f>=RMFV@tnUQ->ML7q0>bKxl*2)hmTsv06ioVPZIqfFqN^I`PfyRm*CN#dk(Ms!ab zt+Tj=3;NP810)pjWemeVQLPvKoI6pYUsOOd4V+NwE_0l8$0GGLsqTLB9edm zNao{^JZ1L1-~F0Iv#_quZtN5C*ogu;@MY{=&8J@c>QVpYZy3f_2gjsdDTD;faRHho zUN}a9)Cq7x*X(5?eU*mKES^3O1LjbAAJ!^WJcd+jv{9y%v>e_$RFpdCB`lspTH2+a z@>-t^77lWYmvx`hVx{5NkVMdPf9OrEJUJXKI-k; zJXy6}E{HPf#(l4nDkae}0*~ zj>``!Zv!VB;>fvuJ-(J-}9as?-Dciy(=e6StyFf30BU5nB=y97Qw*q!0 zt$WvoEHSL_MMQM=ZMaDkX*$qtJS|~p@~?!xM`R74naRQNw%(YLzF9S!A*f}dj}ua= z((VZV`tj?>@6LRbf?{9zo?zi9tLw7Zh@EfTVNH5lkg5@c zP%)LC`zu`(eg_P29g8G2g_)+ad%|H4(8^wKwJe|*Wg>ael& zd_A(K^3L`8#zxrir7fb#OWwirKS%jRKVcb4NmbQlK>>Fdje<8r-n(N<$5ovRxNiYr zF+gmubC;1QMapq6(=O`=w6|%jnyKoZT8of{#gde%X#(}HTJoL$VF9uYg|f5KMUoTc zwg1_*K6A6Y+hxH@lQQD{&bz(4OylFzUZznkT^pMzU&uif2{n?aBMUDyT<+|{&d2wc z?nkoBIi$;G_!Gj7DLZ^s1o2CdxVn z1pl46m8ua)moKEY)rKOURA$tu`t|s@%Z*yYB$pbKx0yh?B2#DrrKGNY&=gd#3~tA~ zESVDe10$m4-#@eJBa~GF);;d{WPZNn@40=U#bf*Bj@iz!$(kx6V>CHQ)GjFK-k|n{ z|HN@5%p(-rF4$`N-0SYtY-a!`l)n`k)vy|_c3r$9J2ct6p(@CtD%Xdo?fO?h6B)pGKUYr~jcRp{@XePWUQl}gw8Uq%;P%BHZh!m3ezonI$_PT;dUd>?=Av=V~_ zbe)!1ErZ^<=qq@s9!{j5<&dUt+K{t5rtD9#OUz4E>4%t$S zZW^pjo?bnpGu4KBOcO+~f5Nej@dwH5N4?}8^Hj7RyPtdQ+C2U=6M)Juw1*@S7{Mkx zVrOYwa=unG!ExyCHTumtEa}_s_wnIC)yt?Wp?qBsp0K;moX~B|7*RoCeUY_oJ^r#U z{DRzpGHHJ883XTrFTs7epMr6@EPz8csqkFd@u(qG`v~1p)6*NpHsvM1>*d#;S`hCX z|0f^R+2y5AWc0S8aGAzkl5!&b)AYIRZc!OE%U9T3CGv%dOY$u{3-oqFelJk_YY_kO z;mO6^aj9RG(H*Qk#((sAf9(#_O{g`vRiSdTH^gr&&MQ|VL?ZMHmMeqew?(wjexskF zA23l*kBJK=3BC?p5(ViELfdhf$_5F%{h}Y!|7_Ht&g!yWo&MNg=ngJX=qpEyD^m%E z-`Kp;cX8^UA9v>yT_jQ1AyE+OT9zi`y9YgV1HJX*On*~h%M~L}bOMU3$6i!NVtq_o zFnE0hvNccRxO1-8vp`QABN#R6`}RI*!DK>S9ir)bck`v9b<64V#_~i}bvQhY?tooZ zo6xw?_kTAnaNQnDBB?W#$7}R}CCB%2XJ~+7|57apjZU2kju5s?*a#ja!Gq)@TqVAA zQtRr3mKMEcmIkBRc$d_b)PxR|de#uq%3g_}mus!jx7887bg*T)?ni4HxAWlv^%5Zq zTfH*i;4!;3Z#J0FllmjYycEL1MGj!ShtdcGvKO)uFrg^9w23&(5LRpD}SI;oB!E?ZCWibusAJLXR)zq>n&Mh*7Q=wLjZB7XKQ>t~JIg zOLqd})df`zTdwTyY16$Z^NSS@hK*OIlX>^Kux_uWxxV zgyU}fA?ekg?d|n-I>f(Z>us;veDicr$N>>%F3E_6Q_*iAO2;D-0f$`3XD8{0_|f!%e8{+;8zTxro$;GbaSjv-A7zc9Deie8%|2;e3 z=!$@4bJJ@+iX5TRTH-3qrpi6Fm6ZgID`HYo!+G!Ag-YbjfvXBQFvrIQHoW@S&32xZ1}QIg87ozzFpWZ@>}epck|j2<~}Iky1O11dff z5mTxknhWUzQpVFkGt;bCJj&R%G6kaPx3UG84iel~!c|%lNN_rREdB9DTxoPHmH8zj za+)b9t!wN#3Vk&B^*^3;{2N7qQ#ga|juUVm9*ztJ*j!Y9%Ru&5*=d zCaK`rDN;xCQ<2@~VLPeUlv&V2N&VFAfQCEE;Fq)yNDeyZL#=~`~~*IIPNo_B{?75IX0K?m6|k1 zRLX!AOPsk$(V^%Pyyy|7;Ly+R*j0f&PFXcB0&&vlh*DOK+-$EFg&FAC%jpUUUOAvI zwRBM_$*mguD&q~4?>dxV1jcro3RF5Hz+TSI@k#ox2wizBwW+c*R|zL>UzjSC$t}W9 zeWMQ=7OIZV-=SKkUUDnH6gJ&XD>#(0NGnY_bo+2-n0E6-d`eN*(olO z@VE+6PO+S4yWTZVan+|rp_xjUXYFsuTDU`;ll}aCMjgbOzYpVEedMdAZ6c)(kA&Ls z!hUh)8xnEwi~%)04J|IVVv+e`=UcneiDdogPnY#-H<76v44v#WalresuTXp5&YCo5 z8uuf<9k4#X@3DpPnG_xXn;u-9USZ=-Pj&r;xH^aBOAq=rPPxCfx4FL(uI@bX>+5YA z_K&1|Q|Bg9`MDOl(%5*{KXqgPKCdVf=4Qt>FckY0=%ohS1ym&fT;un=L&57;Q1mza z@rRV>bQ6$PQaUfLu1=HP!LN~1rJ3_P^I?5BTjkt|0#BWZXO8CMbIvz9g;4#Wi2}v| zCCs8#AS_jK%=GS5T&KcOZcsgk>ccgBPki86jVk-0l-#D`kt6AmBUU#>`9h6OK&^_s zwh)2)w-8RI)y!2}3^KAO&4yDAKAcLT3R@1$9YVGnOJZf;IC#Kt$x`#L z=Z}0l=dBbE8#Zw=?G3)&p(>oCzons9hZ5IXuFKtF`OI~m-wX+B%Ms&T5%MK$#O|cR z%4xiRZ`b)k&0#)abbA~JNHPYjMMb5VD$)V!OaA;yP!cwSOlT-Td(p0{J|3;sQ&lxJ!+Nd3gZ9|$_L*qolrA!+?#i!&wX#zgxT}AR znbca&l%@F80a+xh-zYLVIx@?=_{d$2);$ri!R%>Gk<<+W6Z4A}&wCFHv2R^NMMb6c zEK_hMQ-*nzQQzlC7&X}Lpv&>@;&xbP`0jc8R`OHh=Z{aai*CO$HvSi1?-ZR^8?_6^ zXw)WY%%)Fl+h}atwr#7iZQFKZ+fEugX|&h-eg7W&>_6y1o6#iWS@)Xvob!@bM2F2Y zZB>q!--v2@s-7Um*-@40c7fAkICXiwJnxWD*{q)c3TFzgYH8L|H90dDKin=ZvSOVV zEsF|1l*?^~*vBY2730%8sjWvXd(vB)S=(~;Mwl?Ad9I_vXS(nSA}7U6mOW_alRwf6xy9zXp+i~S7KJW_SBr^ zzr;&JJ)h2BpYqk&MVoIHXqIm`HqPAM_r(y^*~^rJHvNi0BiADr#(upYkC&Bvs=Kwf zi;gOkErvjIwVkVs~?9y+WJUJ=EJAisPA-4$bkC- z=q>y#sx>4i2uql5m=dH3zmxI&${MfMrU7=?caQ6~7WKM6oDw4sVEP*!JpP`Y{r8R~ z)9Hq9U#S*V<|uhS4sLEHw$i6fb}rBDNLA-TP9GRz*Sr=H!x~sClUu*LDFCrg!A}8U`=MZ0#bj{bJ4Lb#0&-AFm@rdrkJk#lS|p@IZ;gE=RRE0iv+31Y>VLfgDv zdB5|gA%x{Bo69nEy9w167eCfUU`T8yDt+-04-$%>^gNXorvZDi%4-m6;}$VJMrF0l zhSusmG5b(vTY!w+7(}4P_9tp;0ymk~krEe&2a-Vs4H(W{xOlf~Nv%;rH*y>%`E^|P!o-MAK{2eTHdPcZS8t*Lq;sFJ+-zzj*L)?n+gE zjFEU9nz3y!P42g+dZF!Mp z5mPNrrrd7(YD{sD$ZtH~lfW%+jNK?MGmt#Aq@Lq$zR>5nq!Gou*qM*> zs*QhD_)dua4L%Gd+D~LYUhV_z=a}oS=slhVagkT%yoj|9ng0y4J9jC&+f6u^A2P~5 zSA4H$_LpmW!Gt~B-bXO)M))+bS(oe1Gc8}n32XA}ewmN{$QnOH&34;^m*Ki#u6im0 zt{_UvvbD7}AV+k@gDrycFG&fY$*A*saS&$IWKc2A!WeK zm=tw>KnJia7LLnswjXzG&)L$eTaox5A(f^Ms0qby(Ye;lnig@iau| zApKJQ<;7ylE$&#SMh%qZ!gxII97I9C^O%GL>vLlWN*LIyysC@A0f`I@oSv@D>27ap zv=5AE&iXBxpAe!XScpPkh$tCmmK|7Xh|g*bNARMeE_ke0MG777j;Ed=2|5dw$3ZP% z8v}g*biBKvZdHRzQ?9GSu$-DgZkLBK@1?x<$cAEfQVv2LT(p?(^rj2rp!&Iw=|&`Kn!Dd9FI z@=j{Y%li)*6ahd28d;a1e}!PyR3i*Zp`q?1WA^CYc$pEc0Daq$Pjjy_?N{aMn?)Gy zqW|z7pmmu%^2u|okvox--jPfs!8%~#a+v{(f>`(WWo4${b0~7M3pi+l3Y=f9+dmuB zwswJ#t#`Yru6z;^Uyhb)3v-mMDCu(a_i?yLvD&w^-}vST0Et*V@MVh|q5V@Fift`@ z2br(=gLOG>kf@3Fi;{_RJCen>g$YPNPXdytvPk;`(5%v$oR}d4V>>${D%W|hycV-Y zuk(^Xvqp5Vl7?)x2~m3Xpl!a?yAN0h&L7`u)p{?Q0kCs+X{j%iFdJ$DoHLE%?px)O zTew4@K3t%_-rHS*^LZIGVOgASyH+E?>u+2qQqvwYq%IaVy5c;2m_EJVdi1&fghWSk zJG_!)d;Vba5f){&Kqy5=JAwmK57YwPcM4cLgW;@ z@nWqdACN?)h5dOMKHkAbGb<%H-8FCRQxp@0qo>0Zz}j8+SLa8$M!!4mi5fB({oCLG zV1Z!z3E$nuiH0S6`aZ zWXAcd95n)be+(GYC}uTUT`!J7D~8cg{-SB{Zj_+SS9tXv5(v#OXOcL6SF zVqc+v)RVnS4d5)N`Bq=g8ij1d_lXg0yZ5Z^$mVONHU@Pj%Q(LH@j3K{CO~`Ky?C{5 z+AJRTpuQZ>(P=dMHt!@kMUAb}Y51wmy$}Lc%lPMY!KzTkGRw8ILHThfD%aG-Tm_mDf?|G&j85)4Ooh{OWLrff|9&gav^Mu z>$Z1FUS3`%@0A@p`%$VP`btB71ZREG&vTb8cS~h^4n>?t@ngiJJ0wM2zAROpmlA^; zCW_^^!;rqlkgETT60WXb7ie}VB&y%;f(4qaKAmnB17a5b@Zp!b{+#mtjl!9Uc-PbA zZ98XQe7}*>k!ji-;~_CLt$eyi1>RB=Q3GQK>LSuwTpo`<{*1ssf!TuC%HkswO3qC$ zjftT;JynOlhxi+G%$Gk_wO`)(ie0)4b7d7c#%WvLwsrN zFqon^dL%`SF|dDQrZU#?^+Y&Ep(0_(eEj$>Z~2VuO?vW$&h(?L*Q0Hi5U(>dE>1l$ z`Lek3JjQ;x8JKkPg;%7NSZ6XujRve@AZ>Q-!t#jee0;&eQkXV-deGT1$zivEuI}KN z@drI-xZfnH9_wowTTN7by@jY)OPR_X*Xoy7W=DM|J2?s{CQV3!G2D*FnE!J(j$MsSH(MOskn#>`gEc@lD?IgDTCJ zR8MvswWV!Xwf|kJ;;raTw`Bes92BYdt7$`)7CxHD3G@21$VwGC3otuI#9M5(J7YC% zg#%Y}d8rmNGqW&|;4PD5Zf-7bX8Yg2DV0}bl#7QK2`0G(B4hPnC!R;PKL^_~N>H%z z&?Hh~h7OD-(`5LQkYNJP4i6uH=;F~V`4v!70mBkb&k7uxqx`@80^oE){9U~;PH*vT zf0hsuvxw~x#-xlKD#yMCGLRzYPYc`J?RAiaf+6yPhv}5&o)ua+Vz2=6Pm@LMkHQxrAH&YysHqNvbi#AbKwJ>8=p6sMl`IRCp|Kme z^l_j{qete58*txn{VK+dA+jx7)Y==TX;}~4)B#d7aeCBC9y$E9UXIU1Q!L-=>$%7& z>}R%pNvy4V^u`ihYt?jyj8N;>WGPNyfb2imjR_MfQbmq}fJj!0ctl|Cc1dtsJ>eS3EEtN0&P}=UMoA8c|%z*a` zZ6s~OvLXG2EQ4w9iN=1*a`EG3Fa?q~{;^^H6fd?Wc|Do=6L>k?xRcJ;m#Z}h3&(W- zwRrsu-k6(A13sMC8h?l3X_eJM)%wAbwHL`{zst+O{X1P8;L2?oy`2ViJ7pevOq`#c z0o`{??(_ewpe;&I&Q%uTiv9>RcRK$b`#vc(`my`e|I=;tVM^v6Ay(fcO{OT9@z-_3 z)%MkXMtA&+jrY+L8M%iYf-S*)ZGIb!dIo3gdwl#FAV}q7|94U_-|Y)kUFgng=1M48qNaXX5^b@uur%>^CbnQ$`r(28quZA`aFi4T9%U2c_uA~_BqiZhR*Z8V z?d(vlt##8s)*vaVY{_bCUv9UeN^+7;;mS)ye=CxdFmZs(I7c=OkH>{WTjr<1gBjGq z!7=%Y2*aWdc|cu}R1yR|WWeQ02{t2)qFuvHHp;DP=@)_&VL|8PzMpbvpZI%x1sL-Td!%=5+rr45LO zDGK#A(d&&|_C&q5@101bpfhOjX7Bb5|DB=43J7m1%gTTYY_gZ15C~{Yo$LZyO?Q9W zaPNdk9Qrh%1a>2nUwHhi<^#a@{4+hqXSvKz`j@OJRFLVm84pZG1}32kLGEJ{7>6Vt zDQC`MJ&d0VNTo>&@|MOvqaxm4DWUIzny>{>2AMD>zCaC2dI8C#%G$9>ri+K?_QjpAz?}LQkgyQ4_>+K=%4|6~ zA1%LlisK*F$Dw+YaPnIeg@j-O4XG1nR=M#T(Uy+0v!b!Rt0e4cSe?R94u@m1Nv?qF zQ(xhwhD4urIO=h3{CgHM_x(!8N7-0dRaumIe-Awo zSrodIWX1yr;|KSQNmwXwTsfEp2p)BBmH)7u`Hjw0G#U0dKx z1d=ELP}dC4g9+;m3y~ys(sSO5=B3S))|DXKW>U|bs>g*l_1yY`p-lLfGmDpPM!N9g zFwT$YCF)@YpZWp-X~``>dYkp zs0I9gmS4)XyZUApn432=9ZQ6p zEe+()MOW-^lBHa%FF-|@@w2WRTj1JTfQz=uYsO3gE5ykjATYB?i@ z@hnHPu1Z4<5WaJHyuvJ?QRBol=)=M|lA=brAO` z;L94%R+x!H?Nw!s-(r4veP6M=SiMQFKKD_e~C-& znQcW(u?(uNu1>sS!2x&CXTI#e;`4`ut?oVDV7R}f&5*QRstApng?rCcJwJv$n5cd zBREKsvh?*hf#oL~tB4$a`7qX$V9j`T@OOO~e)=D(aP0Og&|g!XJ?u%{6dBf%%VY39 zRCIBBkFI37WDyjo8_yuYb-h?G>GY&cbAMpS=5QlLxQiz2A3wZ2cj0Zfl;`@OxR%Fo{#fjY5PjL3UNcLRwR{13jq#NOO8S%rUCLJ_`AzUjj0=VAbwd|H@ z2A9R-%&~^19N|vZdlxobNXh!h$k6o5w8iEUVKIf?Ao{frUR*KLS_2)C4RsnXze(FC zxvu(f3qz~U3w(c_5D4P_5C;?LRG}tm*uiVUjiH!LSnO|7iOS1yt%-yRVV6r?P?VT< z=TcA4f_jcBObrx1_CM0E!%zPBzx`878Ta{4D)1G^Qh@d7%3f_Sr9%I2a|z&ysM)BJ zs-tCEcqcJIbaAW6Bs{2zR+SuC_NDp&VUYhlf$%yT0QK`8%M?uC^qpd@Hy(>RIAU$0}L&L?QzB;^Dx4X^}SWJq4 zc{2xZ2j;vzC(aRlDi8qjt{pqv)P%sum|G6OPr!CsTUX}r5q7Cz%H;p=4oR&N{Tf1f z(Dt9|{zH1$5T5Xln|cRQ#kaA7fp2_-*KXyt8rDz{K5rlL9-bY5@{C}eR7rVJzbSeD z2?YWeJTwCuriIy8tzue4x{*&;kT!zZJg71{i@t zTHVv(-ald3!!>aKYFCk6Sy zb^5fin-`dySE{;o==*=z3(Fa4j6)@E(||C!)EZj?ICs#- zkv^><&GNH`pDzG)s{{1tkdRJ*xJu?Nr#brE)|<0Rp3#`CS*M zpw1o{ScswX5rn_|@_!m+_}%I&@v9F=i|UlAt=@UBc4K=d0lO`9Qk%!a(RSV<7%K|N9_8!D?poR z43(GTyK&=g^ERp3cn?*(L^y)!`zCqG-h~Vabl#0IS1CSO1&`f>&6foKBxUy=L$40s zR_!^d>pyKb>>pa5AI3Ydo2PaPD}4ItY&pUyImX9cbPrv9BkcPUboWmj5b)kvY}$6f zd0#tJUv5TC>HDrUPWEkkG{r7bwsz*+T@WjeG}*l3bvN%}w>pgBsieR-?@1Asf_$hf z94g>CjDKq&+qwtZf(f6jHzhsV@k~;kkw+udn~t+KH>KD)4XlU+U4sR-gYcZA@FC@4 zT&?w%e<2~nS`X(v&38F6tv@B&O=Nz#CwX0&WfT;d|B}ppALU|YswgJ4cMqc9;1hh0 zFPf-3Av!XC3ek>IVyW}0gWSC4ZMIn*BRFGVHZepYg~GzBYjC=uu6$nYIpuL7ytY%S zO55?zIzMS*xLPsc9tMNuT^XEGqgYI9iTH}ZxUwnxM+Y1B7_3iicmaBzf{p4n{LlV}JL_tIU_nZ~8R-p#dlMcZA- zS7vHN&^M-3WkA9;h4OyKJtuQpFo?-E6%-5VM%j{`RV^|~?!D&s!YNTh|Ps&}|F=$>4Xtudi_975rE=F%Uv@b5@$5o3{BD=5D^8tV@W{cCLyH z_!U`gv;z7cX+uL2`q{-vizW=Ly#LCeRs7Zg1s&apMU(V%J<=M7$3cOh0ME_du2CG` z^@5Q?yVqc(@g8&{2{Bs{K)kL^TeBuQ0#XcQ09LoQc2;lP=~uXyr`YsMhq8k^Btn=s z5Tr(;2125X>v$tZ*za%^uo^f|V+3uCFD)R&yk2c$hYlXYqMyeKIy$^M!?Mv$JKMCF zhe=75C#QW#)G(b~F15}dUQxpo!Uf3rvvY-q2YASILP8KXl8m&1c>-Wo&Cjl>a|&bx zve+;}Z}M~$8>Eyt(J9W6!nqwCge@KM{6v1+ghUB~#NT`(Kbf)KPMk1nK0*#Iv< zf`U(8A(W0o^7RNJ$o$lfbXXSl9klf)*^@?YU7rfO5XdqiEScxcv>>)=-WVhK|Y5#!48VGWb z4l9e_kOR>^>+yvB-i@1Dj}H$Bb5#RHTC?FoYG-tmg>J+IdWK!3ioVo zdu4LAL}YRYX5vT({3t+%^?11%Nd%;m$yiuguC_Un)v3L$ShlRE@p^LtLr<5^G_cCc z%F4pycKa&u%O*6=t$^#M$t#Hly|`&zpY;Z9TIBF8CKviX8ICBzF9V}GN6yWCS`d72 zbjOMGBQg1(%3Wvf4DYWJtK8brIar+@PVCn zlkRVNJ1{ycugVxv-4j)oyyGu?76%vW7=|l%2(;?2mKK-p{ydmdB}S#e51tY;kO79+ z+t2UPne07ypT)4P_fg}m?<*G@J)E1~cKAsnl?KB|DA&=p9nWLfgodl~`R*~L^tjp2 zy0kt=_{h|Fhc8sJJGZucBWXQcp^Q*gcXazHwr~Cg<xbA2|mwX z>6-1wHEXWN|I%~$wudBq?DNKWJY-Cu{r{2E$6?|{o@|c;c@F;Eh;f<*}Udskz`Q>!}ad^o2BZTZhO2rHE((1r4FQGO!_6E1V;;845wftN;u`5D_cB+mABN~olYj)&dO@eU@BwU zDvvLs;duo;p151hm zeMqj#t)i~Yll0n*e>4Nb&n(DplE09+Neuer#kfAM*X8(Q#K=HT&o3*B^6>DGI(d{| z0U(;*L5WCkM|Vw@j|+0uAnqiGTtKhL;VX*#ztngDFU)OoudBRH#Ndn{uSiZz#Cu$e z%amm-3XBFsVVpgu~d1R&}GOeTO+Qh}`c*-(v41_0Ot=sRk9tpmf=~Tb^+rV!I%S^$MV}EW zTrfAV2juAJ4&OP>7nuy@n5}R&{B{7l<>1UU-*2suxS&t7XwRVg)NHj6S-!O)J7IdZ zG?|!~_#Z>xobbTYkOSKYY&F)DMeAseqOP)J`dFxDnd-8dEGeGWc9owaF{tm7C(iQSUADKT7sP<_ddXVPS@rqxPzJQ*oc zraHB-aav7rNl8B2&N^>AERdlwwqBkxkzgWUI542@c4hb<6 zG+j#28j<3sR59jvZgu73^zP@VyBB9ci}Gc7WbibHrrpstY~&3vK?? z-+0dY@!^HU*M0S^`txCV_0YNgeDCVI!Lw&j-USS@f%XGKSLeJxEK*k6iL%+&rkKS6 zc~TS*VrO%8S8*Kcjt9F|AL?rUsO0fEZ?Np?KV9_b?cexp&D`&C#GJlp3t5GXy<6`p zaa^`8VO)fe;!9Ys_W1oG+Y@lre@Br}mJ}SPFG}90Ls^f^DREIm&p7dGuYsZ;u3Mg} zs3^1*PCGnHLG(HrZiltu;5O8)-T|IT+lSZd64vWIpXsJ%y%$9lW73(l0iYkiWO+ZX zx_7i6!ZsMk6C6i@CTeibIJ3YV8$;zL0tOt+0{+rqNX306CjOYfgJB}Q@o;1orbjKb zef97d;X@_)(HaH;Xle_F7-gFC8}#ak{5N}lmeJ4z2?a@m@V?Xx7&Lvo3Heif-T+>3 zAlNBWBNPTtBn%h)pjLTgKc;G0r$1X1xOv}tT$Aq}@hu4Mqg$ofWoF}J2gLQtiOW)*h}8W z1YiRFp%E~yKVGjI3`dYDsi-2WZA8912T>Bzm(g z?Lx_;H+gw^0l-`mXz9ez*`deUGRvyEyWOzmY3}6r0_>YX+#*$gaHn}ig8X|X$&*KJ za{QrT-QaXrqk}#5;HES(mXys7En&Ddk%V|FO_~CS=V+dlq^`|secJFaM|qS$9kn^R z(!hMPNa778)9MJb-r>xvoBz~pQK-MgS2}46)~5z<&(vq>PsYb9+mhnq1A5hFy|4N5 z_$n2@(H#Q313J`K=jsnFO>1`9~{T>8!qdwON4mP~1^De>^iC z=xYsIQUE$P5G+s(aAlHiwG}{uq`~~SFA!qk)w~W<&=e;ad{ZYsdo{HnAp-%nrh?9; z!QTb*#KimA<(4E0#d`|L#C9!Q`!+qhYXVNr4~4Jyq|n^}kSC{MVY)wziq*lXrk;j> z?(+HmbT^;#!CaQ0AwIfQ_d#K5R2ZS%A%%$Ke)9^Mn6l1sS_raQyEpZNKh$>S#7|0k z0Q&b>y;_0_XTrtBMWEjQHe-$$*xdnmat8nIPd6OKX*zGmsNe$lfes&q_nF8v$D8%4 z`<1q;stS9ZNOeWLx;}f(`)d)j9f;<}vQAA&7v%t^`t~$u6sil9%#!HYSrkF{p;R$Z zbK;a(xzUmgQbEg_st>1o#6{P+)clfVJ`1z=Gz0*PK-K+E?9U}8KXyTbNiIcmO{?v7 zV_MECSHDn$I-^PoIwIK;lbf@q$x`5$GG2#qxR1q&aTEz>blh;&-Df)2+N5nl7cvnH9 zPLD-u5&KE`MDVFhB=~u>?Krtc)p`OexpMz5;zs~5$~VHqOq&egq2a;d2CTfENo_oK zuB^`B3)qCQIkEOOsefPla>0(C&!eFOgQ8h) za?p(F4O!PpEj2_3^c%GG7L0!EA)p#t`N8!K(5C+?VoGBOhJ=D1#z67cBMO@}5)DP} zLWUv^aT6fH2#*O;=*W0`J-&_4!EJJP0Spl{LqsO@KrC(;!8NmMp>C_4l9O%9j@Dm&La}=XLxGG z>eIvOi#N!LI(?O>nU`+$BM~MMZkSj$V*G{=?^s$i5F|vgRp}~siM}$=#6Ng3)%q2E zZiM4PHKx3##&kNHr?I(t4mdJS&H$l^g#VPk)=JxN&{_%u6d>9w*6dZnoI_F+bS&1@ zX#u#k2N3N%y|VZ}6v`ePRT$}k8=(Z6D@!OVZqLAyZ*Q2B+h&sZ>Ps_sXiOV!?s4_ChBT!@aZPp%KC}rp={L zp@fq0qMSX&LNv8*E+QfgZF(Cp;LndbfrytHc(2hZFH(NIApK3 zW{4LFmnqL4%24e{J8fh#nbN*KHpS+Ulr9oF2>G@p-$5A*6j=R)o{CR;nqhcQxs3}NV)dUdqAqRK_@P?> z!EhAbt)jB>Cm!-Xz$ItL1K8#>Ywa0o6MlU=q&Q7r@)D9A^f=LpNlE&w8G!r-aO(jA zD#_SO0T7(QdW~7fZ8!MFp@238p`;;mZVpv2?<*wayIa>QeOhO#l(SSCV+s&R4~QuH z>_=z@FK7YlTNinqOBi5w&G>79iH{GMBobJ$GR+rD8v=g-n5|NU3ZScv5O_wV==!*O z=>j`Zw~v=&4gh(wXU9`-5ihpSWw!enofHi$8YQUDD3YI(+IcO&y~LBwcz-Qlc-4?d z!JHr=_bCD%2SW5%g#btJ#=&RKTdv=jT2qyiBWvka{>OPjIZ~n)TBBK@FdTz=nXdiz z!f(78b>f*gg&l2L2`k9DjT)H}+$+MO{Ybtfa>w*C-$t-2)Fc4b9gCs_Czc6eeLj&4 zt?Eo}FFOo%gY^BLlq|Exl`n_ZLv^*iEtBJkk>tVixF*qAb2UWeXDV1UyWF;4{|di- z^CN>UHCmf+FGrQ-wkh*z^q0t8uvXgHP zCR=E{xXNmgF28KcKW`#XtR?z!N(0ZiXfWilu7~bR)60Dla-WUZHb<}ALiG4o{nk4$ zp#ad~(a$cw$^E{ySrOM>>FDo*-uOKw#62rJXyG|^;J!A>P?4@N1lcptt^<~N&Kc~<&fwta&ZTR@k zPVe&&4g;YaEcKtJD2w)sUa^{uB8}WQyj)dMV~CQ$?bt*g30Oi52n;i5<**lK<_Rpi z*nDUy3Nou?n~9>e?zvuVRte~g!@uaMHHk1)!bOhxXzTnHECN=6KxQ+sj7GRZzrIY+ z2I?+ES+jbD+mt)9WtZtpatkgMW*Uf$MNQHxD&T#q@gz{c572wQRLjr7v;=6)(qnoDZe6* zXm1V1XE&IJQqWu+MYA3n+h#Kve_sh1~CF0p-^aCZNEn z)agoBl;H?w+xALmZ#Vb)xce0F_U57Mx8IV~UnWx!m8$kIm?26x#keX0|Eg7sGSw801BXTXXpY zc$NQ`3y@p{l>hdxk5#|f;eQf$ppC@fuh&^g>VVXf?_Y(mMUp}4h~v~^S@RnTe;y*cp2;K$zGnR=M7&5UVb6Z?lVklvQ7(N7B^`-JFt2bDa^ zIC`ucKfT|Ka6c1{x4F;$tnvEf-BNP{ZQIWL=DO10)$jPt)#J#})8WYD?7{ZwQQdQ)@ONRy{fW)%xGg`GZzOTos``c8>bXzI%VSk~!I^jPDaSAN zP;iF@T`&l^$UJcy0IaD#$J0Ot+|9$vT%5KQNz_JWvcKOw7|Jt?eIhp(!l3f z^ZGKuIUL)gs9Enfv=xZA(G)JEGjnoVrd4|Y7+aM(4KdRo)%w2Dx|C_CYgy-27bU;H zx?V5o&!kb2H=LfvVk6=BRw^aq;6y&w+Kyv5G-*VsAVB{ew8<@vT4ZKxY_J`{@Mvl~ zz@kP^S7NZ1S}fMkNI5;>-Wc+<_Dub9kjs=_r@Ukk!|h(kFg&`HR0*^vcSn;0HZ7*w zoAqOqfeUNxR>^@FnVCCE%wH$=?H#Z6Ud30l6^XkQf9ur5ei6^4thNr1id(4N1n7M@ zncuRoC^)pHpk^eIhj0oENB-5V!=iV<|BMo%tW8rJkt=TPpwZco(ABLuu+wCAcEU5b zSaZ%7^er2#q~t&j=l?!?1kKQg!hm;#3cdk#cznEnC+*l;9W4E>GsXSLX4R{px3^>1 zxoJo0;Z19D2TxD)>@@|~M^*{F>E7%}eCFQ3DJs$TkIm!glx(7{1rZs<%6wRgY?Bc9}`&FILw zEVsi59ey)93d)eVDCQbr+oxSmgx-L&IjC*@SdodHJ!IQARVY-(ZvhB~$;0Xr9uX+< zM9jKm$ei+A?S9w(`&TC%p$i%Ue2V){>f>eF*I@vOZRf^~oR04Jn9nzC-9~dP*6}5v^4AzQD+Ua{Y(IcONjbiQWc6e|y~0 zLJ2&Q&T9B_va>mTo(GPx2nk8}bSGVVJil+hUlL+tuSQB78roeC`sB`<{r8KGQPmv0 z-Ay06_PpW)7mwqkHnV!wP^#3+iPOK|TrC^3`Ud?fr-N^lNI1cgY8#j_C=3Q9Xk`L1 zykS8J1>j<7P+pVDf#~u*3J|*CR@)XdCZq8x0L6wfDS||-ozVwxk75qqzWR)Sqqn0C zefk0^bytck7%hK6#xyPhHaHwSt0>nVAIs0{FVr_>@2&FF@a2AgE zrrRG_zFIy6EgyE!Ij!YMzR4=`YR#F8XXR#5xw8+3p-y&H?OkI@tA7*Hn#fd+gXc?~p@RM11Uf6knt6G^R|; zOzIu_dA_t)L+t=g#h;=j~Cnku7Z4Glm;!3n10 zaSBqYREt}9ZLwY-c0bM{6EIdcc6PAbAC3m1V?^VpyWei9es)l_x?FIwT6;(?OiRHq zqIL^Y)yaW=J@<1gr@UX|HW@%dJB)l2!7Yf7SK#DAp@KOp>Yxh)4*=EE{i?G24L0a% zEh(%pf$;ko%ecSu_a6p|qy`;EmawX821-iG{M=r=bj(Ds?jVr>rz7ZJ$TpEmmS>Es zm@*{ak(+-ZwTLK|j}$Iz4&FPdYyG(hnpgh{bLUoU&&dNcO}UHhEA(%w7^@f0{>VG- z8AzVShn3SD9`~Z>kMsV-JKxhYazsnep4?~MUi%M>E^d0P6BASajLs&cq=fc;#RC+x z{@Wz~VD!YD&BFPKL_n39IMdVvXs7-Kuel{RqD6 zb)+u0Fkn1Q3$%$#)!O5sy!XU!K76|Ge^uL#(k)wWhH=d;EfK6=%PXq)hH-5VfQnGq z(~|?}9)bV*7Ql7c8fcom$_IJ-aY)BE@_3O2{3ezs4<0I27JKQIGRI4rzN3RdmOy$} zcX#&o=f~5*(GkECa{pUa;s&TF0mYAW>-1h9hXesifI=1~R5(KkHPZ#9qMl zg|K^bWnckZn(85-{e#^a-11h_Lkyj^qL^0h^gmyYq3g#ifP=1X%Es{>zQvgKfOT@^ zn!U}0$>V{!fJYm#G(ruJ1?}Oz8Z7%8EJ0u}L{$WZ7^WB=OvIU!`i%4sb!rSCs5trF z6S$74+(CzXO=>xDltxCZ8A2+1Y59sYG3cm)QNSZ8A=gTbD#Rh-$X7BHH&b+XhX&3B zA_}Z_Wa7#(DH)lF{d~j`HKgMyacUzmUT8W7f=YeQ38sV3* z3Q=)bQzoZ>fTF9ngGHrUZDKT-c5VN&I6gY*d*%iy>8**MHpj?S>cQb@oknELCl^Z7 zTI?n-nBM?{-|PyZgN&x-;adUK*qmipwI2IA?!VL7wV5Z+ivjZ?TZ*+p$uS5%aAc9tfeQk=33`DIGS@Q--)*M?mv3y5gO?l|7; zHDJL$TM)@%cw7{>;Av|;&8e^?Rbpv&^q6Y!kaGA+b@vW>v+C{+VaCkKtxM6#c`~~L z0l_fPrfh-em*2*ofGv>yLp+0|=i!k)HKh*$Ze}x8(BT>X_b;Q*=WB|YE#Fs%BNm)! zpit~Sz0RICo^P~eIZkmP^lbC(-(|^=;p5{o=>R_Df(5fdKfnf(QkF$@bTDO15eQ=A z=4CQQ5@frB#}9`O9UAlm;1v~lCyoS3NwuV;zwh5+GhjW^v$Ox%blsNL(IG&FWLwqfVt!UA6!U`2-4G6**q@5*7yHmOnU& zcGw7n1=<}hAv!5sTTFAO)cDIhbw7O3!acrg);&UJR6!+44E6Rhh+iR;?6apt?M2Iz zwpIn(7Ib&}kBybj3@Ax#x{gs+RMw*=25;6!{NTIn3+!we38u^aK{hR6ExCDaHeLyK zE&JGDyG+3S0amVs28y0kGVS9ZO{}cYQ~_=Yi%~1q(C!IPxf`-6ndL&!B!*K0hw|R9 z{Wj^W32V-zABMy(8EflLh7C!X%sY8Rb=p&d5SI#zKqf_Wv@}z8YocdQ0>r<_!!H>A&9WC_WNmyKfr!6Jo(3|u`A zjo`jqv6|(A#lL?h7xx}yX1580R<){i?*EBL4f{AahK74p59iI>U*|`%-whBJA5-b( znRo%YzPuP4ZX~$dZh^oD2(HIWFl>_p)WwLG$CjF1!cX#pn-Rj{ix`v)P{rdTWZu3) zD+VgM4_=wl?+nezapQ~!?0|j&Hi2+3TayNLryZI#A56;+jO;L3be}}Q{ypJNoH=`2 z;JzC!A6EE@$H2`U)u$(CW%CuXQDXT*YNdE1vN(@2*)zu+(OK{u{g#PX z23AG<%x!WnI>TbK?^#1r6X&++<{pub=@+eNXIOYRgx)!}{QgHdzUCiYSt=;# z&PWI^9xR$n`rU_Z$$3&Q0h8|La5p?`Y;4E3p`qX8KHbwZ&HPZ}A08d;J*lEsOYL zne+sF9_Hq;pp)qD{*VJF=Gc6UATwvkLeMXmMA=vm+A4|cn{T_0``0*If0EeP4SRN# zJ}bt?$P|E>>Yz{H%VX7^d14w@71uX&yC{+ZX`f6Zg7Up=}WH-49A z=geP5lAirHfK|2CUw*Pw z&w1t!ALq8|U>A_&_1$GMqKpE|pSK#+^27}$8dcFgN4UV$Yh4C; zHzRt@B0>6T#=_UzDVz z;b0&w#LGNZ@Gd%+en$$B})x)T3#Vi?MB7|Kk^yn=Ab#X+_Kj=w9({dcHR?B}=E ziO4FL1imRp`2CJr->(Ie6hHX*Km&aqHr_HmaoworDLKw#GO~3(mmmJb7p68i`jx*h z{ek8ACvOZ{GBPqidQ*d9`c4^zPMo~iW|w*{cU=REEMovSp)*aHoiXEpootg<$sozwm6V1Rr32R5Ie6U zgFQDoIx1+PQy1@FD32S=Y6+a{7!e!7ck>fb{pfu0WD`_0zhf({ zPbnWg{%rhLtiJ3Bj*3kyTXm7Sz6t&zCQ zM%Q!Y$cxrx)yu_Y#oar%%C$a%?O(oVL`2>{?u!P^mhAsKj=4Iit#@xfT+IsKb*2%2 zL_~sgB1!k~(B0XKX6I7zZ7csVKY@aK=MCrG@t%uNYUV`&mPZylLq;VPqU~E$l%kT- z$iF{$^gNyj`4Y9l!j=AUl-c$PZfzlWWCE>k3$Wr z)nUs?_~$?kOiObc-2w0go0m-lq@;TXlcb)Wg%|hoUHZ+XqloAr6^z~u6(sA+2y0N)AvY*HG$lVs+#P)8o z+hq?DiqH0KZM>-TYBr{!Jnh_chmy zX3qGx=9m9UZ=$MBuqXz-(7khsfSFjsr_}uBC6I^gJmnV}kPm^L7=2Nv6$#$@GEFA| zmSkCspGwwJ)hb46oMW?0HE{ftLi;6R*8P^#-GQfEJUsM-+w?adYAVDIyKE*c+0w^y z`S7@Td8b!ae(jB=v!{UTY1M?)*soBdpu?Q(2sZozKM=1xF(WPCiQmm#lF zV}bx+eJq~zZ?DHA=Qv*=+0%j4%?-?hRJq#g51_0d+%K4zsNtWaT6#gk-_sL^;YotJ zvY$CvZLI5k?xpqjq?iVt3I8Gp3kiXafSi_~iH_GTrKZL(V;tAf(Wv!Ud}Oy|&}0es z`USu;mcW;mymW{McK^y@#ELe>Ia)*g`e!8LDmj2?-W;3VPTU2mES!f^1$TjgJ;_q2a9yX z?`RThJUD;=qw;eW5`-}0M*5dl>Pe|5leDe|YWdLcEVFl91hca7^Me^w_Uase(tx%4 zcDOmZ$bO%=*fK?S_`ST+peF;Q7J_XCc;aOWjJ&;(YZsZ0n>lO9roz8RITy;_c+$1O zQLkiBT0xldl}qmyCYqxtjbX60ev)a;D9{RAs4z?YjRy8BV6@jLR|^RVVM~>(8ArP` zU}WDC#=6gnMd+H>;SQR>Q1ZDA4%?#F zps;_}1yR0+&dyxLx7gU&RhF|1pzecu-S;PW(e|=EgIpp=pYzkATBZ9m54ZIU{LmN(pC#26;++g(>Jp z;{|&-+u*7j<4*Xfw;gGNUC&ms6cfyu%xFIPX22AsIdAsP&8dl8r%u@aT{NpT=!QZi z=JT60&u?xfXj~qvpVyNGWGo0g9eYTCI=VSD>zu52X1^nkp_bj-cKmdCYWL#5pS_Og zZeiUPyR?K!en8`N*}t!-WMsP9Qjp;wiS!2Ttf-+O37}H1Nwdt2D?K|qZ+m;iLK`h;G?6f1G5)S}@&}ad{fSvBSE~D;_S-wr&_I9x33PZB zQo9_~-w+)sKCx$f2)ylB!D!zGo@0Bpn|hi9hs^%b&}gv{<_)HX%#(MSDxGdN*-T&WP=K)oOT=`@Bxo;9jhN4OImi@gL2sxgl?9X)-baD{@RloZ>X3Vx)@14ZVL zY7SgMu4*u0kdvf4iV~DYmSuO})=1la_bR^F9|U}K4x(YKLd>NcUZ zc-|cz9Bi~4?@g}1tUJ4r8H}aL9371`Z%2QXlv+(0lLu$11#n^;2fya)xjEj~2UDt6 zo(t?0^`Ebj>lzz5g@wl^^Q1IExsgrI0=5uxP0t{uSBC{J`~H`iMyo4x=kuRRz*_)P z?*<#B_luIoqKs-YwO?f4&~{7}FLe5*NRjy@0!$ha{(X`c8A0;OJIGgw3`EweZm)>^i8TGZ%l&Wl!RvQTi6GHThF+!x5 zn@FBiW}tDvbHmF=8T|>Y@)a|h%$l@Rq%`HunodiY%zC}Zl*`y1=Lp>JXa#h;e96{z zh4|apnt}1`MLjMy9v%|r(XrEs%6HmK@ShcH*tQ8fg1=D@rYl&Ac)>9sYM&)nc#O2m(d zN)Fo{dh5-u{10j7?rtHYlj@6e(W15dPk_y=(FAs*w}=rCRC{trBhv~Lkc{O@Bfx(? zq8-Ju_-jog~ zdD*TrvVw)Rz5Qzvlf_2IL&bi}@%VQAyeo%@$hY-MN_53d*HXn&LraFPc zRdrB1rRC*OZ`XZAUpGqDJWdC{DM)=E9ax$+pk5*2EYBl)h}WI)>jzvjN0ycYN)fSlv}}KCLQEt8$+_KvTEn`@CPO z<8@lkr0vQB?F0R|dFFd{p?rODUzl?DE8C-XVko52c4JEwkJD~V2y8f5JMJi7{>^tT z)LY^CZ_liC_&oeJ=W=!>Ev%|S2R<}~pVH0vbN=4mzCLO+G&Fu2K6kHRDrf?rJJ%=f z?)bFIlK{7fA7*TK50#T=uK#+%ZQ_mz9L|xf4b!Vn@K*C`N}uCmB%v$Yc_iI#^@yXt zj*N`p1h>cQ*2Ul+A{%IMV1{7VR%Ul zzZ-;(<%0hmQ4%?nWH*{0#cq18+$M*gQWHWESzMM*F27M}K`-%J+rGSD=#c&u_7Yjyi&BVs!<<9OJhw6vr1t*l za(7`j#~d>~HPK31A~pjZUD(45NaqI4grn1Lr~42%7`Log;E|2iGnnYz!z|$E zi}6TFm6;BE*@SLPoydokY!wHoKLUD)&)UGp@QiBx#VY}GNlMZ3rR`M}~*NpRH zw(Q-V>Uti*XJ==>HU9h|=>^!K^&-d2(FU(#pxA_Q%u^ii`pt%8F$B(X1IcFde#7;l zLU!PyPT$4F+poUAVF&l2%jbgSc|#=g_CP8p!s*2H^mNGKt~Vv9ozCULSR*)UpTvR7#{aUR~cmY_5~$fT|r433sD^0CDYA(PoD3eNx*0n z{P)NJ&`4A}5q%26Z&WuwI-D6Zf7ejUcYSeF*U1_3B?njZqj5YE9hNMmq2Qm1ps+%gIT8vTl5Q&(43u# zd-jP2jP4==B33Uj&^fBOxt) zc=@!|7r58zc5ZrmwwjX-YG`HqUqbL%ikk2OnewKOj|X`#vc4}e$Z*1*?WE;uZ@LZ+ z;6d2w#hkXFS;jVU2x?kd1Y7D=aiyJN-)8}W4LOEEPU@V-3m$NCY~Mb7i1SI^;Gu2H zikc!Q68Gn%$C+4^tEXm_IdZESQU_4L-toPOMwJa?6<41I@ zt#8ze+coCD=SLTj>r>I1(+jq>M;ex<-J-{>V>6>~MB0P~_WP*+v|0B5`C9em!ZF}F zoP|hmejS~^6(~(_BYh~w^r12%4;`m>y}r^|NZ6elJ$N~ zBGLQ;^s|X8UmhuCTlGwC{W1-=fivs;t-}}Ni;hL-3DNttvBv9CbyW7k?7`;j7r>?* zY)&u{&aT1K)LdW=$@17E5P950E4tCkn;h!ug22MU0`LSo509jR!UXbs1JL9J78e)) zp7`3CU0uz-=6(GM_}_>=eDHxj@pR&K^{rzrspj$Zo2%&yQBKtUs2Yf%TqkW`5<_Bl zZoGi@Q^nlT8D9?9IZZGB^uZ9~{Nq z$6e%5P*509J*aCG!d{n@TxQ(GIQ;6s!j&nhC-&G66O*`KX_Xck4jMT8C(4XP;FP|9 zSnu%hBEaX9l#qb+@sR>TR*BNt8kb{uLKJ*tNF5d&W#wsNp#`L$8ZC8My`f(3v&*NO zt2F-Rsd)jiL)vZ@C*TH1=7|+Vc+p}2h(7=p>2CG>E1qY0K>=**>iDSNgsJhj)#ya> z3m$XP5xt-jF2KdV{#iCNg!^ZChD$WZW6u0!@HC6Sj1a{U%cNc{chY<>sx1N0Rz`9d z!mhZfky;Cy4!TX^y)vlyzyN^ZuU|NRm1av^=_XRVjMT4?RtswA({R-f9P+WnbQtO_ zas)9Z8wm6ed0AN^G&F?(ZI-HJ?c0qYIXwJ>8<#GaG5449OFgbJ$1a)gj~;+Mn>spj z>^U4=S_9F6q^Lo<_kBo6K%`?{9+i9h+3$PiD`H-5Re8{pmuTCPb1C)kz+T9^e=1(kr#DP8 zA9t=c@=bJ2mxTk%>we}*!k&VJR(zOS=>j8RF~SWd%^|ueT{(Jqc2avDye3*Tl%91* z2tOx(FPUz=SW*bOq+`uOe>K^pIweJe!rJSqGBlpP!1JloP0Am>9U*k5PiDEyn#wtH3NsH)q1~9x+heN<-Na>LpYpwTgfeqY(I9E z_=Rv6eYSyEPl%lCCKdSG9yskpC|eq}C{0%yr3Pk8U<(KohF`=0_s*!*& znF#^nr6QV4gGWt9(EeC3U_wJFTMBI*s<_w$E*MkSNjF{oFd_OLJ}xvnIAXwd;g6O< z&|+8=v>lj&k#!g~yR(y@f7uXDhY7q90PUb9R-H0}M{RPeD=~`^ri+1KK^MQYr{_JG z&YzxqYHe#;bXWj#VOgJ+K}-b*FO#3~&~<+Dq(Zs3i)}FDhiajF*65f2HL5;=3|KFw z%A534%vjQS3S2$1!+yOv~*@;;$xW<#9GoB=CW z$Z*g7t!F!lRoPT9TmqaX0JSxm9l1Y!LVACxO@3Y<4?!ML51$gjs9P8%C6vrd4@vcH zz+decky$294!5MFBsB%UcQXa0{gYgRVRb%Qt3-5S)eFLdI5=I)IxZfr?VCpcti%1K ztq*a$2=O-*bk`gne1+sf^vkf|^B^)dhTLC0(79*IZs7X$Xciia+P6 zQ?j0!wdcG8q37!i)F6Ye@4F&4ie@u_GsvK*rtcDp_u*9Q{XnO{MdmbSW5i10`c`vi z^7VGM$jH3!9|_dx6itsYH}{K*k*BC_xB?>Ix4F()n?3bOdjMb9p7fxP!Jy#x6o;}aO zsvP<)$==QFll{0?sO0$iC()!K_`Mo!dQFu!aRFi*&|(E=tQ7V>?v$36es~!l9nEWR zCkgHC29GAdr42v><&cG~o}*M6@I&+6H$=ta*`KpV2G$3D;R355)@9Y4F^OG&zV~?? zazJMq#t|7?jl25CzE#)mW*K7H=dEJ-c`i=u*-~XMZQ6hd;RW>k38PA zrEqZKC#Ijw;*1GoDfxEmJS}f%FL$vOC+lK8)JPa!$i3E&2I?FMW<7Dx4R#cX9#qH5 zN?6|oXAc{no(OVviN6CJP}ssrDt9Y|qQ$g74Zj#Vp!^}cZqFnDxVo_L)0toM%b$*< zDTlmbbC#+hFxqZ(JuB0+DAU7BAtM;8Dk%}xgs3B?5R#E$q3nHz>cLR1&gI+J4w=&@i;grCqbPL$DxsggbngAVLw10%uNw#eydYD6we06knSvezHgtHH3(rqYIy8^Z5T@6^z~sIHA!*D)_$_U1O)N?hOY0Qd z@(;Gr0j=mgLVbPx&hGAI=DGJ9h;Nd;;2!XK-?91L^^)$qb1 z1?iBZ#S8|@7e%(9R8vO{0_Qy2Gcd~k;Us@$6M=7r`#|d14%xWezp()UdMapqWG~DL zs_%Y{L(Nb-;cEel5V;yYab?q~5H%(}?tOvmyJ1(@xrsYRk>=XQwfuF8+4S;G z!ylun5%qtJC!{QDIAke(EIsYrM-s616hd`wv5=9Cq+^TbzKq@QnGr^2l?2`!x~n2Sf_YT4`x-`{4U)FH)UdmY*Tx zHS#|x?uyWVL*DykZAjN3r;zPE??Hrg&3)P(q%yJ4Hr5g!K<3x*X zNT*wgw|vwC_cXX0Z_V`K(Lb3yR<58or*vtS7*jWH>$C~vLdrWzLLhPHBYBM#xEtf} zlYaViZDE8wgU4xyzgo0;U$Uo^>swsctF|?DeCWO-a z0p!c~38ll~#p$HM>$8=26lwYv)%PB?S?uJc_vaF3d2fBgj9o=VywKXCzpb=+Q|RM7 z`&tsO#Yk?Aq4{o5G?ZcEWE=dTlBFk$7O>`TReW zJ}@w_uD*WLu^Hg@2%_wy^qo%l6H{NxG*TiXAZ(>XRGI6s_jWh3`9`uxybhT(K76N6 zBoGfC*OKe@XOX0V!roVKG?^C(VIC{fQ2BT^gC4rJJPO$>gPROzv;Guq9L20Nk`^pb zc=BeU`W(W85l=aZ$XC`s-1cvSf?}Nsa}mzZRH2qo5~(NbLPZy~qJ|Y)-sMI+;Qul; zGXwL>*=2gr3!4+{Km`s}l$014-qA9>rH0-xiAdMf)6<)B@U}k!?SYlE^IIyvTor0u zn53xEv>D8d_=Jda><0RV`0#V=uL>3j_NqeRpo^CYH(xZr{&7JfJA6;M+VK(AHj<{< z@3%W*=$XOaWNNZd~8{{n*wP6N9w9#Ric~sG;e_^sJ*vv)6OlULVe9 z4;_n3YqzfN7dktU@~X3YdS)_zP?4!TOeJ^p&8q8vvaw-C6MZb*-nQ8t7kv5taPAum zgcQ)-K8Cp!(Xs-9^pHH{O;U}8Atj~E z^vEpgv83lIx~kuQa-?@8#eVmpfKsauYHcbwk^`0@Ak|iH5_e9lr`F zI=7LM!sXR|`rZ2}?p?(hPi|hlf5PMI^~ut>gHJZ=S=m>Mf`a#b1LZ=?mK0{5Z`Sqh z?VPjkP&@@%QwvF%(eVY}C+CH^^jppxIgX4}Zsm}OZWDWC?fyFQDPuaJi5utJMg~~6 z`*C^WE1s>w@b`Ru;&nFwU?MP~I=i{$sg-_+WAuOL2NX#O4MhxeMI#wr-cu?$tV|N` zd}ay}OCn?J&HE&}jO5D2(sUeEMcSqzp^TqyTFbfSaB`HP{}~;XMAs~y^{Ep^F@Gi) zEoNp%e>@jp@M>V&NGU9PyCwu#(t4FjZqQ3x?Ob*jP($tcs+Lc| zHU2ScSzBQXm}3zmmdvQkM@82Jn+iV}AvZqeC<~)vZb5s2)uo`t5`L*}QI7~b?Uvx^ zC?j^{B4$G}!ewSE1h&L+qC!rBAoJ@V0Ig zwE5j=S%W}#@84&KUOHCS?n_E^>v=CL14eb&$j>Nhfc zP0>R^`K+ngKba>Cw5q_#WH8;XLu9+VK|V6r#>FLLb`fDArn3a{SCdY6uq!_fk~LyB z=iig+%~!&j=&#LQv1H+#@fChjOIh(vwwM`(C@Gf5?q5ENhePWsevKxp%b1^OAnd>{ z@|Eb6g0Wj1WE@w8&IkveYMD^9BJWgv6b36d1WPrtig#%M$uCA&-hh@|`gOnxP$R+o z4)*Nw9v=MQFM}^q!PAS5LWN!pnEp(8!`q8p8yg5+W2S=dovzzoUs`1>onLFM(?dO{ z%f*!DGp29W%1a|3nvSNa=gdgheDAn(Di>ZXEjuk1V zoV>lG%C(o@Z#XkJq#4n#cA!I_h3$FL0xYdZENO1;i;m~v7k44j#Y%R{hxf%A3Y+J0 zsjORKYD!R&JqsuE$64N%cMU0Xb z^EE(K^qHbjxFhYMLMzPhhFn_!xlEU<`_2T?1*w$1*sx`PLg>m`^x0}}$-r-O|7`E9 zLan039_M=W51*^h_(b+$fyD<#Ct(KC6ntaK$_UtNrkxG5gIOte%X6-xP@k{sWWK)w zU#c_G@jhLR+@5cL3s%2+fze+7?D-<}do(-F%;KW7^e{rp==m+Dh{!mg zJ=|}+5ryvpPbWdk;p)sxANTw(enE*u2HNBmwyAl+sj-}1A3mBQv4S4aQ|h9r>5dAymT+T2lm9MT^Ci6t!JL`*^fJ(q+Tah)=PC{^#Y+z6S@JbA|nc4uh5|U zUCH^}N@fYm<^UD4Z+mUU77f4=-v6ev_X3dSuJ=V>QqRsv0k#ah;@2131rN5=baZ}! zwT3Bw6RUnlMtbL8Zf8g|StpmBy^^LKOeEQ4J?M;yYU9-vK-j0a72u!we=7vD%dI)h zYHtyJ5n~DW8;xFichOg38o_Z+EQ~OF%7$pGuVX4~yu}w54tz)Y{X3XVT&Pzo>^+2tAWX$<`}<$e zGS8}ipCd&6;9hPF-ICSq8gCKsjBahAW{6yZ$}~8vQ*18AjF|{5J#oLWu%K0eaDge` zzJj03*GV_**6C{df^;n&24fj?~im7W8|FwK5%mSEp%+Kzv928I*Oh0Hz@R`1^+~z_G zJNA1@3Rorr7(i#Z?<~@Nn;O?XDSE3pvcHsq*b$3!iPQTffv5(Ylzo7=oGaYg8WYrk z6*Ny*4@wJi5w~F*CP`_t&VEedOf+rrd0N7vfk<08apQ87{N5g9@J6$`sgiS zt0}+eD%g@#dcXLx`o0$KH`8u|sIbh&sGFnOEDj&Eq|9FS_+aM~1Rm6ykMC{~+PwYc zd;r_>OqSW*dg!t7bB3zgWqyqYlRs^id%&OLc}87X$-|c83Rxs)=q6yb@)P)h<>pe} zEP>4=NQmAn)ki7BzWw|6YQZ?B+H{N%oSP?_pXom1*iUs>@OHo!)mDA{)@b)89d1;k zF`o-Q95$oQZY|PnjRQ9U|M$;FK2+8IL*#d`B{4m)qzX9uG{wPROk z$$#4vXI6eXpLG4$+f&c1L5n)susjjK{YhL_;?LjHjnh0_wThqA3a~IMH`ePt_V-#^ zvI7f^#oybenWAAF-&ysa; zVAs`M1wZ0=Jar^M6898*|4k#md)4g#6-4M*`tomcM@7ICR!LCS((0L+!LDq(LIlM0 zSLJy_1JA%fK`Im=VOR-8r1z>nRy!Uz}%fZ=HG!d22nimw@Htn1Ypq3CnGR_}g8F_^6&3 zEcT_uh^UK48D|(HlvtJbH2xLx+WzXZdYWX5pt6-ASDlO322Kni=xrM<@CI8(4oI z{LGT2w=2@s4fCsVVvQxBt?L_LGuI;!1UggUvyAIuz9~O-&0LD+!K|)F2b51s$}2#x zk<{-v?@a(b11eXVG$LZI;9kEH$3uvUeO$Z~T!y*&E1zRZxwu)UY4Gh{8|3gHH={7k zlbRxVE z7$KVxBt?A>?X>;5m6fRNzMCYllg~@(;cqhktn8tnmRkCah}Sf8)remAH%h=H(;GC> zzD@fo^GQmOcL*@E%u7M=Xs@^~+gR9`B|(XJcMv0c2yijLyTct4Wdziih)}&FNAKEq zVdrsAh>pgPt1mK~^<(Hv;5bDU5Gb#k!Oc;BxNMQc&*V{3L67o7kh_`u!fGfMj(V<$ zCq?^f27Aws0quKte^u{?dNH&!NY6Lzil{$&6m_CcNTA)|K^j{LuD_%B=3(w{q+g!r?gdbMlLY{KcVh}S?Ri6%WY+#Q(( z9Br{R52}@6MjZ9pj|GG|KZB-q@_R`7DKp!YY}6SL$*?xf=o9HbXH8-sN`C*8F<#4Fap8EO%HjGzKCQ7Osl8_WDWF6$8k#J&I z?5`P(347jh72@`(;BJoY(@zU(O{K}`r-$}@CT_pZAQAVs~Q?^mOa>qx6zg=%f7C=reIge;aefWga;DvLY7bEA2_k%TVm5fy#Jo9 z^~9=4Me}4s)ka^6uan{L{@$DC%U8-9o-`U_%{SR}EQz>Qg#0Nt!(>ZiUlr)Kw$#r> zSmyzoFvt9ZPUSuQeXrMow?X`2hBrf6I{kDpgzzp3H{Wf$tac@8`C3$gVyGY5e@+1{ z3$0#Q!u~o}vW(TKl5wnU)TQ4)sg)*rTdGm6i;k0FV(M!&yeSV!om#Dj-yF zY?&M`R<75zcNBLktnnQosb?qxi)dg>6fIMrRHqBo#t3+^+x#;zMB?qzXtjAJ+o!&# zr*Gb)8@V;I-+0Q8hvPTecYQ)cIE`tv8`^X%gtbCowACNe)-9S0k=4V;NWK=pBhjh!<5 zpDN5@=OZnkeB`lbcXx9TqYA^q{w1g`49IP6;^ti!q}{-+xE~~01yii7+stgWogoUF-(8K)(+tM}lCCAZ;I?DpBLJ4n%I7Xx##u7d&`P1ObLG+6b@-OJy z2sisyKX!ZqsFs{ECt+gPQ&i5h$>!B{BYI40uxl`LbbQaDNIfaA6Sfz)IDgaAhJpHq z4z`^dkw>DXNgCs@SX|#kE8ncCFYE?;FWTfs^v4vbVIMBcj!0ZGmR&xH$k+tLJ%pG} zIj%Y7vo{vXi@bfVLXkn~2>}qnR-K!ho4?xt2tobur7h_NlznSEOH%d}bgVh#4fa0VjdG*z|9L}~WIRMKSvRv8zT za0Kix?_tQ$9pxat=q~4n{gRve#**nS$)5O;WU`A0{gy^bU{Izc!Zj)}S^ZV(@9?JE zIeKx(=d)r-T&E2G2K-3EojiTaq6vAGT-a7%Uj~zse?k7wZQ!4j|5|SwHkZ5f3=(a=< z(SE04D8{WAfxUj?l}NMHYC*KISMO642S-^;FFkb;x^1*h4dA=bWj6;Su+MCYXDAws z#3W+%ZYmRG>Y|5&P1!54f_+qm@fF}j2yA(@vA^v=JLHD-*%x9(;}mq(ij&ql@|j66 zqz)~ss47hw7&CZoqMX4 z3*(0c@vhEbGYdpbPCFlyO!*uIqO#yS7U>yY@f0(}UM4 zghWL53xgsdG6lp<+`@G+%p?LyWf`IL+jrF#10jRM-0730MFgj7y z`T`o=F%*rYZ$1*0DZ@#jN>CZ`6NcTdAlEM=O>d#4`k*7o+l}Qc6nVTqPi#AI3JH}R ztWc==<{#S^-Za5S1X1kzEmJ1KZ_F+%e6+G+1a$kH)>fi0l-A(Uedtd8;E6X#xXuHx z%vi8vLMWtg`)EBvRr927cB8Zh=y`CDFg7+qFssXO2t77ZHosB({~9@euf`kd-TW<{ zfXtK_g@~liE~FDM?ZLEjfUBU?W!uxEC+43DRAzpT3b~O8Z3WP8O{e}i>_8Q%JQ&ru ze9Up*$co?4ZBl~7$`8{U!+w`r??T|>a*Z9ngOt4RgmD<(jsJA$W4v| zhX^;@dO~o!q#EqlFmtk!T}wVasW<`qZoFddJ}~%j+Q}%!l^CdjU-WNy2B8XjDyb7; zQiH)kjhkhiQAEzZk4jCZRRUChg@ruWqqO_bK5;G|aYmDWd1uo*{nK&zNN|`cM`FZC z2sj!SB>8V3BM{w4WG#ow=U9oVxLc; zu7zMNh(ARu9$>=ys|*Q;PfDuB6|Z7F#58+PrEJjX?(z`<qbpk>-q;QOH za$rH@r-+D+?(8=V2?evNuhT^*cAG5ngUCA68v7Qf7vjJX)6FlnRJ1Q5D5_w1SW8mM z2Hf1=mM+LBu>Or2sCGvFwm^#!fUapYP+=M&XaaoZ~($Qxog?I&nfQnGBfkW zUSOV6KnwDn#o=hvYWvQ_A^cwUu#;qhwSIuZ`nPJ)>4=H>O%6$Kks(7N^N4_fy#b&R0(LIfy#V;JM%nD@Hs zBscGm7dXHXvu8a&426XdzjP{B{2XSTj6UjC6D2DYzR8vt{!om0EmbFwA7G40P%9T8 zj#W(c$cNQ>PU%nC{P4j%9oU;08Bucinnbh`4B;KqOOPBgXp!_xIF6G!-bhgz(@4C6 zkBs~YyRbEg>bS0>fEg^0_(eevQ2xH<2d&yR?~cCnWcy4b1_3y3obOQh{um2V{7v}+ zwE~VR$L4hUNwP@;zm^t{$76jvh>@l*2r@;YM&A~P30DzlS6cn}Ne*{@eu%K4#*$5= zw>1r)p-}fO!hFKuH#M!5_&iS}HtdHXvi>r$mO422dH&_4dGT#)`sxYI*q;0}*I}VL zp`~_O!wUIevMja=42BrSBjr%eRc~PBR~$tlbTo8W7|7xXeT>iaUmqm+5t(g@+hv!y zY`zyZ*AAP;So2&z7z-Yn)ZUJt$c?s{y6~v|V?JB6x z828Yf5TSYTG?boB2c`}a_% zZPD&XyZ7O#sM8aZ@BjW%r};%B$MsHG}0%_7jvM$5~;t%TGJQnONoR6_q97fw84L`j3YQ@Z0@koRAvSGQGYUsTk)AV>9 zQIGXmb zDxF2QB^v3!KSw@FFPug&iXfV}QYnlPrA-m(ZlSbQRP_3JR%beP`=&w}X!)ZX3aBJn zye-yo87em!JaG>Q6VE)D%tQ@^PPRHTai;x=*GaqIk&d`hXhM=or$u7f?`E1OiYZZ1 zNSI!1k~!QL7IEdCWYmba<(vd*z@rU35Q+JxA_uYh_OGS9ziP|froH>%*KzNo=rq$_ z9#!R(o@zXqFV;0$Z9diePB5V%aqGm@h;R(qHeJigU4%uuf!JWgBP`zPGOhI2yN0iXMPlZ zl}m%>yL9c`?TQ~3=ElXEsLFyi8{6{87$mc!FULkjkURmJYzE;;sBy;@HjCtCyv5H0@YcC?ntN5!Y zv?%{_boVu!zTW+3*R_ARzRfwPBrcaEtHa%OR0uugoV{LcT!*sFs@o6ww(RD|{w(~;E z^{XxCOPddBNUyg0Q&?h1s(e|F?b`FO+1*YW(%pWDUDZ&^Ms2X6Ub_#qx=l+;_RERd z_)o$j<7Kg5jPk~|kS!dssIBy6-Q8k5)(c%d!AQkrWq|f~{vnw~*P)=-w#At~&$>UQ zu+)0(SJWHnFPOYkMN|GS31O!*m_I28TmuB;y>fR#R;OHem5I(|3Zt!|!Y#$!Bm=`C zK8cTgf#UoE)hO{@P3KliOKoa-nX{iAwg!!x(VDCbmNCY-pSW6RyP6)=cZRtl%-ruPhAUKI(xCCkv zxA~~8zwQ#$3=Assw-Ty_Xlx^}&=x3@H}3pOi?OO!NHCQ-RTqe!URIFQ3y&XO21;8ZcqdKTyBYXqU3Whi~s5|qhe5BDh%U}rO=zvh^{ z3$dV|7dXlc;^`{?H8#;ESrm{Z{bzQ!g;@z-mf4Uwz!jQ%VtTYz$JRJFK&w3te(CbXN>`yw8QbFnhvM zLj6x_CCOS4tflhInXFASt$Kcu`W^o8i#Nd5)E7+OV z$Qf>?qOsk#$Sgn3+$Q{NyflzW`uqEY2KDU<6DzXn0H_q`yWCapT*UZb-|>!>jEiu# zyS~Rz{w&JJq^Hq4XD47pcD5VoHgk1TAlnwlb%$n~28>i)HhV?pyO1JpE>`3ku)ZU2 zl2d?ITf1jy-M}{^@jl_|CTFObOz6#A!TBxjUGoO(z{Wk2@8GaJCS%5k3-%VE8XY&g zAps*8L<)<^zkas@z_j1P=W;ZIO>@+9lIgZ?IC)4~Fybm$ ztyOm6oJAB)7@x?o?sqMPZTrsC$TrLK85g23v4u91{A#7pITJKBuc-*C_mQKU?i!gy zZ`o>;DuGoKuZ#t0h5 z$Bm(DaitZkN{+|;2^|)On9AdXLre^hM|>7~a#-kmTAJ3K?i^WOUjF&xWt|OJeLe@D zXJKCU6LSRw#I!IQPr#UJLSzfUl#4>b0tA!5&x@r#K6!JRe?+@*Nql|3UO%ve~gb)#8#E zbh8cTr@^wKvfA1>tvbg`Pd8aDNq-uyM58AM8)`cQvp$OfrTZq!-sz%(A6r~3PpUso z$ftx_qgw}Uomu_7MHce-2O7n7zV?TB)I*gYo=EMV{L+mh+zf^3iR&mV;M`4=C0>TZ ztmDy$551ZDyqg%YOTxu4F+VfIYBpI86p$wa)!sx+=VsFhw&g|Y+vYm~{u2{hPD}-h zv8E!z#IErc+hkpx*05-@^yGed*@PPpd|Xjo<4z$!yP5%g(`Lc2G!O-}dg22Qc!XFp4-+^f_7++rnj z2zB>%y{A7Xi95OS#lvp!NHy>byI=87w%!r0x`9(w@gOC%-ZPO}I{u<&Jx^04xO5HM z;I93=SeN5>(Zb8Xe9GD@rEsftU6Sh>8ZEVZO-$}u2;}H7e>Q0UnZ^|Su+;31aIg6TC4i^{Cl>eK2_Fu#Fexz)k-_AkLVne%aw1?2w>c~I8c3F^Uz zh=@|(yqBDU9-W{#+Q}T4`8mzaO);v{nv_4&IC409op%YA?S02aclD`*qKp#HCJEj+ zwynrJR9s?ED0$_Yf0d&<`PF%`+)SY()A;;FDWhn`B>p>AHj!|wy71>3oaqsj z_V*&-cvr60Dviz34%3z!Kz|SmgH5v4(0ykMtxjlT9JYQ>Y-Ct-vTxW{C&&H(m6ViZ z1mtcn`}O<67TOqutQA`3zM?a7AIZ31cqIF+FH3##*0jXeg_JnT)m#;4* z#q1NPyW^4R<-(pJ+>!y=Mr%T#NpN`B=EVI>28sDIbMuzD_uER_uW|C z8E2oXkvu2I4+N$8lU~{O6iowQjkS-3975MHdKs-)pNoDxrt-rfki<)C zz{TmdUo$I)IQ?Pw<-mbH%{jr|c?rVkzVXhUz2w#(d(0m;ek;Wb+!N~xgpVfPr7)BTZ!^Zjc?4Q*T%x*K zz>uo6Ig)xoE*PZD%5AU#4E%ueNbQrpLsU7?{gd?2;cS%K*yz)|W~(+RQTq1QDb1YM z;&GKvXx|9IRkBNv?hY!n*>)XB51Bsx1=l=3-@!XDz>szQ7cC~+&oFFOC%?6|_3-#O z7r0Gekgi`?>YDVJMgL`1}oFrV_$M=5)Ll=O)yNutlEmwt$Vy-a-U zhCM4dQ~dgnQGjRv@q9H?HqiFtIVM9nh2uhOXugx!s@>+2+qQKj#qx2y*iK5M)HRQR8s=G`1h}e?x2$dq&WGT+?u(yK}tNOdX zRd{5#a>hz%)2(r8CQ}B%l zzepYV>7~;iM)!D{`P^LnsIG4JOs3>Eo|^sHF<*@dY3Y`5Se7-L$1+iNsKNYs zUt?63+?phwAcIfdGt}d@k<;bOLzSpH9b+Y;@MWPO0Y(I<&qD$JSqGqP#3aHE7MK+E z(h}K8$dhWftkn%RVmRsJLvtH|Y<{BbsiHLU;EXuBMwM{hX)v5D^f9pT4Go3SV`$VU zkXT3lN!Wjk&&Ays8)#|q1d>&|*`1i$SV}Pt)2l$pN?$Un-QGAW9K~ClNOO`IqLV2* z@=g0ESlHApBkt(86Eg|+_6I^e;kdHscJUBlat0kv=S!N2cHu8fAxp;dHU{TOhh(Hc z#aYZyZ269@s+hYavHKW%7Q0#~mnra#P%NbN@Q4Xz@CY06ANthBf>Mj$ zsoFqZ!`#B;Hh@}GTE1j)b2|2}A9ah>2q!x0u5L>sc0eliZ~-kB&CM|WQBjP8Lnw0( zs16ug?DGEdn+hRgS7(IWPwBjlPAAox?Rdy}@!84AT#h#zkjm3p0zs$CY{MBm9CM3J zz#odFuMb+Kn=@UGjEn1~>QEb(t`xg>h%e9K>1xvAMoI51uh0bJ_~!q$0E3V}o+($f zKM%>-s&sysjrp)1Fz|!ajF1(St6+YwOh6s^r0>wS&7({^)FovPJ@d}^o1?n4#e>Dg zr4FCO)#-8*QfFn9c0UQa^Or=S5J9?lSqw$M*@d?0zd90NiENAV&=` z0YxsyIa`x;JQ5rsBuzGdgJK`47=B!tn;XBZ<~uo{tPvJ&=}f0Wx)hI!9GjPNafzh0 zwHuk#DA*En@KPS8)A_5m!g-W22jx#iOsIFo-W%?wH}>~i*H+@%fszR)^V4%Q%U`N( zo|4q0S)p#PF267#v?Tk{i30jk&B*|R*RZa$#_H?YI+x1NNr5)}&qqj)h3{i8XZP8I ziR?UPWK2viVhRWdF4o_`myWg_4%pa~(5mIzP8ym0uU+nmcki}Fwh53Q`Jb2FOrb#J z@7%X_a({8RMtz({_auT)nMNu9ZwEq>F>Fp4e+Z$B20{qzHUtNUhKdH_D|MQpN=s>h zI**i;6yO6&1~#SZ=@L4;E9Rw(jrreBvH}z*t!?`L1kBHy`1x&hApyeZiTlGHUxhy+ zYb}3A4&F;hU*D55@V_24;X;D3<66r@EyYb6W=Smpo%J~AwJOhS^@ZRAQqeufqu&5% zHdF%~)wzSGC6MUfc1H3|SG$1Qs=%{cmzOto?T&0!FnpjFD5QLNeZxexo$V2L+`aXz zgHs)V?ylc9O=2`HgaICFf(~tKz}!0x%zZ&UF^PD?7RMJCeSp(qh3e|A#T~rV>N3Wz z(EtEqf*PcAB6fOA+-|@olk<-SFfrTT=9Km7qNLTGFitv>J(d-}i!IERZ^L~s zkdQ+grf67fQ@ejnlW{2pK!~voHiD687$$Pc$3y0|1(rEk_6N=AR9!YgozZ1n1Rx)Y zChOta8MNmjrVdnG1eRM}!asNGlwM}tNM!bHDXvY^>t|C#HjBq=lZow4yxV{qp|cE>tWFL*OhSDU#A zgu;2y9QorijIA;cZEf_$cfAR_kSPy5LY%ow2xww>?tG`}Mh9-Bs}2E(-kzOt!$qj<@BJg8S}U zGS5Y)Q_Y1(LdaWOAG}|Ss)9&@2=6J5bt=Xse?TK7{7!xaVZ!Id^s`LWevy>fZa?4fu-oIi5)`_20maS>aRzU zJ!KOACrkR`X#^aZB^xyA{pq@Z(3=@efLH5~$s>^Pw@n!+s7cr%=x@ zuRRZRoQGUKig!0D;#lO7s!-T<=9|sMG>{nsg@uJdTG*_`&lB|X_WSL*cE?BQ<(_=K zg5dw2*{Yh5^CS9Yk;~(V?V$E>nU*%(%+b>cDcFwGE7akxB!jhYY&~g~hXxHOjH#>i_$lP`N^Nh};eS#2#@e*{sHA&;^Ksa%c5{{K`V<=1MDq7y zM`*U+Ue|-Q4k@GxzLUZub#&(g@nk&&<_AIW;Wm z>0S!w0_v|yO0m_Rx5qHksTV>%fL$T$<^A7y`)%_ql52glqG=t-MkFem2dSuF%E`$A zCG3ulj_#*5L)^}X9|Oq@Ycv7w21suuLx9?NT4>7kEd;=+C%@-norYgwDZ)!IK71Rd z&(-n4q$!dmBM>kS_sFp-?9e(S51x0`E>*%lW1^#uebwOB`@v$KBWQN4Jq&{NsiZTK z(qvAhSfTOtTb;wk@!aok^rvuKHad-4CHj-nYO`I=NN=cbuku`MNsKv-Ks=1?o$Zpu zZ(mrXF-MAO9oQZCjlH!k+9dkoZfgW|yxUJ$OU#m@&aLbBmUebUm6fRefOfLh`A8Xv zZTP3?0G>q2W3a;J=2V27)!doqG8w9=FtB14HUmab@N7k2;-Qlwu36$WMG9V~KV! z6-HY9Xna_Nuz}iH+M^;X6UYKbiJlS;^8ynM4X*U_bMn$5h~xxrhZcfwsdcHMVgM@G z{Dq;MCe}%P1Yy{HbRk2|>~yYknu&IvC*7L;`)Alw$l{*>O?Jb1BZ{qvteHw6#|syM z@e}MBU^7;8;oAF&njlN$E#>=4=J{Q5eK#wtvE=S!m|&er zCRzXr3+=>A?1|L19Co(}D}Ajy9)=06 z?+HafVmpS9V|x|N46osncA4{wez|sSN1@b^JpVZn8t{QQMrAHMzVyE=Fd^;wq z57QD7aQ_roO{8(O)}<@+-p;9fx3Dl=Yjpv}I-odism>e?sL>hE`h z(zN^s83IuJMz?Q{xFa&?bUln|#N0Erb(X#?L=VBkebB(%1k)`nqJ<(KKOD5bMa_q! zrmUzg^VoCNECBUQd}|R8k*?VBM^VtUzMOcErzhM{2{l^R22UN1WGAG(;yL^5&J}Aw z==Xiweb!Op=cB_b*1E~C&GSOH+#iF~t~Ni3pfOGI+}lld!PhLy)+KKBmG>3b*VlMN zMEOlk$w0R$kecnH!38kGm=s|RFsfaT384x8T|}so>f5TA(h;W_Y(t4G+bkTWj6y=sG$CXrTE()M-H}a|08mh$i#WkPtIQ61^E!k?Pst~6MX;LMc{H%8| zM?yLc`xz%C8zrR9G*>K9d3Ol~85uBdhD@0C?cgi9tSOjzV@RV)ex5G*ic}e^oE!z5 z1?}t8BT^#6FS-;2yZg?9LJWoM;2N)3lLJD6?RxSvRZLDbVz|5dRWX;&_{z%4e8CNC zoLrJ*C#SxlQqA9lVs4&)A7384eJw3B=r#ZJZyNfIYxk$j93LYh!;z9q$)gg*T(p&~ zRBFYV0AseoErr+E?nNUiR^!ZtgS1|P0!d9RDWGNJ^!ndyqz!I$q z38-xpia>%2CgGGi5xT^U8qJrVJjIkIV zBe$EOV@ZDDM~H$&k9x~+JB{AObNUE1%ajt57+u$%;sf7$HJ&!0=|;+Zpu&Ha8w}|* zuS+m==Vbp3=Nc@Fr8dW6?n;BRwk)TC!3snhXjc0Jj)^)T_!A@}^S{qLpjmdFQ33e1 zBopOLi^k@QpHNJt7n4wU6~_R zIaC+>SrqBoT_P?pW%noebAh@wl`K3yjL7fy_CTNyK@a!H+DlV zVgCRvJ8}z5i>t^0kz95Z1p6aTdJGbNC|4S#n|l+Qznkn2G!bH-%_-!;FU;8={Wh!o zqSSLgr!<5-zVd504)j_4$RIKrol;&t3r0pwV@XX*VWX0w#_Be6Qqa-JSMsvVuKL0B zyNQ`aNm?P=Z*(KyCfNSDT%8a{2GXn!_J0X&h`v5@yhuU%B<9_uDDD4H9M!WIVP38Y zGq$lL2B7&HCCxu%cPSYtzMUnwq^uCv)gXID&vG0nqg4K~iF1WCt!xDYrb9Gt)r^-Aq6T>tn zCe`v>a^B9PH0$2p+@sB|c>Yiv22q=awshF%AF>!Sa3vQDySCp;irT%tb|9nNDr;$t z1j5R}K!pIcE`ihBAaQY24h~eHMJZ}9p^>(=^4HF%L3gvhWj2!XoVz#ZqpxZpagQ)% z!cqW10`SX-S*_8WukdwH`TeEhABt(!Vh-JbT%m))I1^kO@B9Yp9Cs7k5AG!bf-z6J zu}F#$5fKT{-7*@=8g(lxTJa|!1%;+k2$JD8rlQ(Pv0k%p-}Xvdt|*Ywr8AEc9`tjE zGLB~oPQ;Q>+Xj>pImvXdekHO+<&aUvCxk8Ju(codq?!*4RYsn_FBNVfnQWJ>Lbi_7~y*Q-Xh;6 zo|rQ??=e4;EkYoeJV3{2#DxSHj-E}@l^71LcM#!Mqn}RY)Q_-CKr*g=f=!rb$}iV9 zTm_G<+q5m4(-oHJW+%1AsQ?KSK<4znpyt=-`;$sQR`FeGJ6@`U*MtH(<(tg(>YO~x zL6s&5=M4zk>fj>FbgROsVLxvE7vLfJ&bRUDdvo;KAl>&%e} z0QtuLZA^e3|57FVmb>Bv#qxgIvO_iZd`#}%yrt%(9tju#RJP@JJ) zy4s!mm|22#6E6jj3`U#7` z$bD%d-7aiXlhL&efOkJ!U&B#u6cwJt9InFwu)?P6fs(Rv*uYHqlpC@;8$on~!VfUS z(~~El@{Da~WE+-K{i2vS(Lmw2hV==bf%{7#pT;g+_nb3ZxayKiaSTwsiqhoutEcC3 zRfXJE0hO!H0t7EVj^mvyHNss+1KTWK2D=;77N=D1qd=6cDlA+Q2ed@w%Wfs8l4~LX z(xK4mElX5;JomAqjB?oChVk@d86B`ZglNuo-unub5EWJ}$*T~OAsH43#W{Y|`p%g1 zD>H(JM@;s{z#m1zf&#YUs_cPwk3ATufO6h%p>d+{Ac#*Tr(W6)>@o#OvU;m=C0|u* z&-ENZ&JU23JFh&5K%jeE>UqTvC->D0j( z!9zyq-wfaqaQ?2utA_P8HP99UkQ#J&-LnEcNC1O%bawU)unDT@tEj0B0DZKHtMCNo zid^8y{e`o7M3lLNC1!lsL4I3_A@S%&YQ#uP)->wsU1MP~?m6*jjqXn#p_>A|0a=dw ziRpMJRtMFKA~p_bv*b-FhzBrj>);_VeV*{MX+_>wW`Gfk0|K!5I{zDQ*mIpfp;Yv{^wvmyK<^#yf231cwhoT>p-tX~B(UG^ zHlX^Pf=~l?JNzRe*MAb~$W4SlU>LyvoRzVuM;XWK8p_2x2gQ^a2r&yO(|`d^m1O|+ z*u-K0b@C_z{gxX*m(joJMDGQ84*t;Tw&yf&I-f%LlS-a+(2t%*qu-?5P(%pOwv+Ny zH-RJW;~jD^%-d&EMw>P<0Jj?vDd*x^5AJ);#Dc(Fn?NPK6MJpn+EV_FRXk*U7ndyr z(qA9`5>q^fl4WQ=IPHgoPugV6-a9;e<8A?9YCusB1w}zb)X%A$(a}?GqTtz8aQ^7j z1-a0>e>q3^U-gn#9vnO(8=dU|uZEsa2w!DKgw0C&<7xH6F~Y13-0sooal&c2w(>zk z6ZC1U4jb_cxiH?zQTdmdOG(yk7d><737|=^sW8fPERELvysYjj1`YN{=9M7$k%(+N zi(lW)&gMQ!%t`pWogCwFr53g`;(Uom$i>NNHpM!tqnAu|J-W{YPzgW*W6zse+Pv~B z4wHQh>odkd#mZ%jCK8cT7j&W6`8O+@P&l-bhDM@j#az{yJAj}VWA&~1P0R5lo{=3$ z_Ge=wdcthX6D2o)ha5K}PCBC~Nq53nL=7ZrJF<}b1)17r18i57t{lDskww%XwKmCG zp(o?7p#$z5Dc+2W!vKs=g4s-GCq=0XP@dx@|KyN%N7XvW-w<0x@LZt}FD}dh0tUcw zVJ@V;Kqr+_3dXqkzlONh9CbkKh@uuk!BaGZ7c-1}dg1o&Z$q@Qus_eg&2$@P+lw`K z*`!VZCGKG*@8GSDJgGD7v;?b8WGe)ZKztW4HP0_@$1>5NDqP-MGKR3m>=ayaz33st zBBRRgy_VSLy`?Fk;{Y7%%wBiaKsd>N^Ei9Hb5};FLS{*hl>6`&wJ}g01Q526E?dQc zfq@ZCq-Ss}8Jd?G<#)svHbJ{vOjm)SIA27+j!>&V@3u0hSbG;M$2C?}+HwK{SN595 zVOU7BW7#6Ja!b~R;;nZ0q0eH8=gFoJ>2Vn5Glq+Q;y$e~*+vt~9aDJ^c_SRc@yK>#Q(HLc}mA-|r4F7eiM*r3qt*3pUJt1BpEI3!F= z`MXn=KMP5Hr^}><7RB)|FG>*C*UEg+AK?0|?v_$quHAg!S&D(_U9#x|)RJ|tX@&8R z^#A0RhMfNzIU*vEXXod?njbjFOjz8+W@opA>+p}Dq>8V9`MDc?whUn!r$#?4iz*DN z)J{;$y$kiz@QM(_`!ZjwL6LVi=lT?IDfb3k)a;y-fC`6e2VqJ!ALb@z@*(u2M7#E` zBXBT_8G;J`I>~$SF?P#8Tz1seCuE9?f3QM_91#PL-e_V~`E0vAKRvE)@$KhBecAYiHR7>VQ2e0OT%wBCM zhIJPYr=KtVn}OOnQWg3tv_GCS;r;l>uDL(q;dbcDpXZ0*X8qQmQ9^pbo`(&LdMoic z#l=#Z9iALOznsX!*V@aF$f5NgF#fbeKqDA)QbBNP5P+h;+`yx_JI7*=Vn#W|I) zKJyKPZ!MQn;1_7iu%3;nGk~P5H)x77B)pz|#W#ypPf98)V<&hh3ys@=^MI_oGSYqS3#jjVz}t$8f?VH zk~a7MD&TXbf#tIwkj$ydt)sY2Nfu||I!W%8&O^q6cXj}H zK+Lx@6v*68xed!UVJGo2V8syODmlFq{om0yM-deWCn1;YMK8-8b76KzCL4y^#F5(; zzjn^GB=h9|-ui3+e7^H*ePRvu{d}dtl3>%U;XEGD4p!l^N{%W6hJ~xi|ch4~uz)PaZfy z%9Sa=c#S)K_?DMsnh0V5WE@$3Z)jn2H9+vePPoyBv+d5L_=lB3GCarOCXJfQQ^JSy zsjk76#tuuUN|Pxjz;jhc7eaN9X|kI&j|!gsYM%a{=aeDum{&N}JpO45V(yh<(8 zavZUFxg2V$&Rv3lS$;37x_)fS-fe(3;Z}HJb`yG0vDH?_lea-8-cP((9oHavHE>12 zvuEVa)*i}!^U@GAUOk(D%aUC3 z0)>FP%}RY}PEJn3x&e@gz)Dsmv-m8c9kiAJL#!NGKZoHQE6cDPcB)!tU_5X~b*Jcs^IPD<9GCyF)}=0JRAIfq>EoZ@_Scg_Q*m z$q<4{topi-VY<#Vz3|6*h-q27QMU^=2@)DWNY1zkWLUQRFzNHu&WMu)b6x}`$%EPes%ILoR~C0toPO#3Jq zU~s~5I82)O{`(ndX2*LO%AKMD7K|M2E6=$4r2YK?2>zQtL1EVK4?otD>dyB$^_vF+ znsyAl?@Q_2%ipB6vmcqGMsSa-b$HVd+dMSA{u)=VJbSz~0{tFMuMu=i-Y|=HO_y~} zpS`{Z-i1sWFF)xl-S-cqKp^w%?jOWkL5T7-yFEH)Y2DFN`DV5KzZSsn{fZ)i*drFq z)Si@?4IUS=%MQvpJIL_5?qe6ca`Sa2X?Gm*v-dgitG!B0Pt7F%)ATC0645ZHw#0&L zy*HvGI7#lLUUx!e9@F;ME2H(8i~aRj;pH+Hzy1E<)_b>ymIQo_G+7t)>{mH>+oBKD zGF#dj&|jVhX*h0ub>V+quWJ4cq34j_XRD8)sd zDX9RYB_8=4OLCQjJdVw2-;d06z8DtfTj`VnfA37wO@Ru?uOkZ>NbB)PZ^~^3`DbPS zsd(9#nSXnlR%Vc?6;7I2is;o?hPEqW+mMbA62w=eA70({3|j~^*zM-)gezYv);2h2 zt$+Arh{hd~nKH;40{(oG!ZsuhwB7=tM&BXpO-$+#g3BYKa17Z+<>igL8I*I$GX{(c z^Yatl-t@f%{bYybO5MA4JUl*0q{7oKu(l{r=mPy$Wf9%WxQu z%CRG{;oa#gU~x4QFh(o%jUIN6C~dUfau$BMaSLb&#~t!fU_Ru2s*0?sfx7U|7qw2cV+VaNJD@ET9 zTAVFot@M8F2Nvz$W7Ob?d;|opg$*uffCkSUK-938_pcD!I$Xv?^xGTppfQPFj+V#Y zZ{a;o?m0WFE!hkNZ?Ndz9;B02ANV}~(iT@A81ue=;uL!NbdC0wXy5S@ci)7Z07p{6-o@;ttF-^PwMU^hsGtOz( z#=zI2bbp8{9|u8F!Z(^{KOgiYnhWGUTPnNu_^2YLZ!2n}HGcN9r-Z}LHgrM)LY|!Pe)hC7`j6~h3#(EEkUuI79N$(AoX!im9%|{fw>LDYrZ(&m7hAf% z4gt2=oA^4-hv%`SyOp!?NytDu$DtQAhuwhJmpgKG)VCXJoKAO&iw;MXhq`F~(Z|XS z$EzrfmWI1m_STYrSiRWPC zy@TJgWuLDWzFGqS|HP^qix#;CKtmO<$YGgLY{%{dmjICjFglIAwOs96l;7Rn-z(|q z#n1cDB*m480|BG%4RecJ{T-S*ui6dP;2($fs&;l$rbMQ^hO)kIkPrYa_W&pB;4LH3 z(!wl=Dwv%Oq}!aj!ee5-eV@*o#`2wD0R%EEz&S`w%WA|L%rr07+7uf01N?b@<%tAP z3;llc5H&X+GG*9CF>2VZYP4Mg68^S-{N*ApK)j^Uk}0*c0!soEDqwEI>arLK|75x<*Y&v6}P%6W^XW$J|1r9qV;zXQ$Eidm=Y#7^7`o z9*PPX*Yv=|NiZ>AFBe4ON>yIwlo(+jAO%yoD^ML=W@YdH{2ObS!g{jxQ%_%!z8yzj zABBqV!F`AwLxlm_=GJa}xE7!+RYunYiG#Zsi_YHGU&U&)OI=5|Sgf>o^nw-}1_+dhdX)h(SmWb2%Q)@G9U)24h`T-o= zw~JH+NMnY=*Fzdno$&?Kj^9$*W_Z#@gCJ(KA=D1++O=z8TcoW5OcognPBN9jwzm32 z*p-;?21w7!lnn|0k#$#|9ku)sL|Wlv^S=Ouc=QGPpcnu-fomLSFj0wGZY`9-Tk8w= z+XyImlPGm;jec7YK2lS-4EHPF1OHthadJhn-2#)gBz0vy!Bi1<{#YIqbhSQCi`XUd zy5(8$xmK`#bzoRi&>uKz@{X1fdN7e6(4*m z9yv=QjE(2>sGer#n{~DAk>PU2)qK&&R>BPRSk`?0x31aec7wb61!J`JebjCdF~jKs z;~LL=>aHV!LHozwLruI4IrikHTAwKZF<2Ya?@WbV6qxdFBXzUIH1K{Cs)h~oJ~#6~2*g#fuZlv`*VSUf*bCApJ8NQSw()rCYR#T?X1+Tj_~`6ZSo3k-m=m)6QQ zS6N&~au4FC*rnWy#*YorPjopk6#LKl*PbEvymZxIIzY7xdhl%PxIFA)yL5*M>|ya1 zo@V`!C~J zqcv~t5bL=CRKHIj({6so&7cO4l(TK46v&dX@q7u?E15K)*!*;aqRlXF0K}_mrO28A zlmYemwz|eWEns6&$^#`r2+t6IJwll_-LG=9_(cJrCQz_Hc4V67=2_y%I@vLt!wcQk z@%zpuO?m>4m=ojt0rV6Ky0C1xfzr{2Pe13Al4EpEJx)W9wnH1RtmWh;{*QE>kQN~D zFY4!wAHTYH4_dE<{V1N^wSAGOny-?1<1H`$hh8rfJPyMygXZh^C<8`+8p%)GtSuuJ8irOdi5>v|6n@@BI{ zI265ClHH%s8t6+KnCriB+^>4#CnNo@R9{(m$3sKW>ui3!@sSz9jG)RdOoNf8#~(L( zNTH`3iZYfX2wO+Q|26B+F3$B-YqZP7`h+4_2*|l6W}jbXj_Dh(n=)S)i2mCho_yVh zWPZ7hxp8n0FPb7LkqU7=n(XwLDs(W2Eq|WoPjsN=eNdpInXjTNEqy^5%2^#i*An;K zl8tutX*^|~QTiVp=6vL7P@Lb-^I=@UDrD^Ie8zTgH4g`g9$RMqkvn%kVg4P zk;JAB+!(t{r5#M6U z5fQE6pxQ76M~w>(_Vr5y8H0|&MswV7k$iCx)-xrQw9qgYUle+=CdK(><}~fIVY~t=m;WA8^6dDvd-eK>W5)f zIk%=^lUy$8;6v#z=;XG4A#Z)_m2kb%o22e(w#Ffq+!T~1)0Cf{7DC& z0peW1VFDLFA_l-{^9uwmz)^qXA9mz#2BKZbh+Qbb+D$4>vJNndwe{X^?02=qmrrJsB1=RbD z5z&}XqQpAOob4GpcDmvKq>Wwnu&PGo@Xn-P@YMD$OLN$>3yyvN=S+Ryh*k5ob&ZmpVH67rqXw|iS!#z&T94jf|`0wHf= zT;E%a1#86X5zBb~OcyAbkTrjbbBgv8_xr6`^Ec`#WLKO!Y zsbSK0{^|vy@mxqV#{i`gP)6VKVY+F?#PJCs`(E#XBS)e0l`0MHfHjb84RnqGeSePs z$k9K`CHl@qt2K2%Yzx^H9%wDN9=UzMGB3^~#b%QMJ->L~0c740>s0Yih;8;%2ndjY z>%Az$ksv_W@Oo7uvO%JKnd+WM-pv4Oh$fZrcdS2Q{{D87)OMqZIE%!2I4CQ7(9z?0 z?$5_?Fqq0<5%s05GAiJU?pk1v1HuLg)VP0W^(>f0i{9+?4&(Y7#?s2^@bolg)vq2x zr`y@QLDec26Ji#F`3tPPrIk60lNrN5t((9&rRX0}KPqUd@6(kVaz&I1KYWdKt8eK% zSM24VG!8%Lga9GsMBONF$DXg+>3zz$?Wt^5Ea?o+F2s{hLHf(~J>j@KgcUdqnFsl| zUyy8Ri3!VLo49Hs1+$|8E`y5H(Y}QM(7~yNTmq>Pl;qz{OK>XdGTd1eb&ZR>{P+a- zjiIlTd;`nMCU?>|9_WxdeLmGiyq>PEifhTluMAkKB(XI=IX3UNMLWK3zvoxJDxDjk zBnvsg;TUfJF?f6<7s&9Ma-nCryG_cbI&(O8=zBF8glFbdtF zdbzuDYd&n;p+lWYCW`8PIV5nh-f=ySoKPE=y!~ zX7?7IQBYK4p^hG~(B<&%_m00qqwph7imKK9KGGJHMo=AnzWG?S)?={0K5|l&=KoP{ z3}^cFA->&Ng^jcnbLo9s<>l;GxRoC7U}D6LKGdCHBd$Db&K~uW8AKmCbngYs!*z`jwiPXpE3xLul1S z0Gm*2L`d@PU{1u2)r&A6?&~#kCR?e;U87b;J}&}w^}7MM`Q{tiLcw2;voPc9e?tsC zDB-=c&E(f8J}ful4f^r@7aORX_I=f{OiHP#-^MA(M?@^wtXRNYNJW+Rz8Cm) z_N!oS;M{u9B`gef?$~Ck|qi|cdognP|TDnAO5nT z;mibZjio_gic2=Q|B&gO9okJY9oO@kOIIQ1*o-ecLK5C z#`EoVAprc}3`l`3U-0?f(oCTe?!5kMsK=er1!S2v2CmGcPkQMfUCL1PrtwGr=%11I zZU+mh)tfNViVBZX;QZoS=@wN&!Tj$42lfp!N4eO0cOsjyJ_P6!VN2e?qW z&FV^8*QN4i`d|6tJ4c*}8jz7g<0`pGrlb}+k<9DtFakJgp7sHiNkU)q!Q><= z@UTS<`N|Pv@S-u<8Qc4{jIKSX=-wRHZFI-cu$fOpWIR< zYnL@PcPYr_Pttdz8WVb>u?&MsVe*aWn9}W8n-Y@WTzDTE9i_vcNbgydx!7@Iki(*U z>%Pyi&Tx9acsM?=+kGi*yIjJxKU(w~a+_*|WS+hyPiUGrE>{r#qvPe7Z(5bl4vu!4gKm+0@C<7g>Nwq$x;06Zon=Ptlm(Jtg6AqvLPsVIH zDfI5$U^ODe)P4z-tmmqweUbTI_jr1~hT;@Z=AYT^6iI-2mZb zsyz!)ESUGp(T=UV$jc`eCUPMzs!b1|nCJily(>U5pZaQ1UHft}*N^NHIUaWdi}Wz; zWYIT!<}7u9lb28&P$ZQXtjf>dIZD--Y%0=aR)5};%>~AjIPitOsS`}A(%R7;(&Ajm zEOCKl!eM@x5Yz4cp-fovBDc!<3|nQljUenbp~AR9j~l;gYnQ5z zNG2xm?<&GWy1JTjL6@tu`D*j#-?~i=Ljqp=fwf#%cPla0K8XE>X)|EH`%SX8U6HPx zEmaGNn+3rdtBV*R4cDA4D=NkvjC=z@e69=+uL;k)$QUZZ%SeU#^t8C z>>P^?NHec@9L34rZO~_8M%W=}KHM;@mbSE3e!4FG=*`XVp6$OnBNjcQv$I9*EGA<; zew4arH(k;QL@ok%g5Z()w()OXl{C-+?j&QlmHR)0c5cL-++{tNFLFvt*sGFGcbyso z;8Zh2r?4%+v}MjeEh_ z%?kS|fUJQ8_P7232k8(0SQ0mPBIJFp%9~u?zJ4;Ud0~ZfW~Ns|td7R*(nAvP!2WM4 zo`<*g?{_xGhWk8fxVunDCksmo&v4l6ygdEC3U+G38hLd6uweeu6SPZFx&}9%C$>CV zjl=Pnu!SAT!aYkaRM-9X>EM#>M?r4cEN5OQ&J6?QeqE-9p#n5rQy$Jpi3xNy>%*st zX%Rs87l5Pl&2xWWr-2%b>EQwUOtTgGh^ax1(bP@2_Q ze3TLw(Jp1|gWbT;*IxWVGk1z>QNtm3Sf zP4IqlLkQ@qG)yH$O5;4P9h{HH-M?CDJ|#Rk*^RxHHyLkdd}}u$|7_UJPI;YP%8pW9 z-;tTf2i8=v@Qn`cIK9AP-LW6q!XH5r?@8iChB76e0D|y1sE{0-d^@ILL*&H zP1{^!BH*UEV2-Oe+wa-9U#iVt{oA)N>+Ij|Sonv=8}50aJp6FR4-3*;9&O-s|ozobisHJ9(Y@7%I2vb_pG**A}@+{33 z(Ip;YFioV8qQylZ+uYqDR*R5CBhb|A+s`pUx-V3RYX7`+D_RK`r&jOX+Q$W4n)kgj z&$lGx+Z)4U+oRw#Z!ZzNAMKEr|22&WdSbhbIw@QFjit9V9Y^TUug=OLYGOB?gl7td zB8IxyJ=Dm-!Reb4A$#ivQx*gWy=I3_Da7@xZ||SJTW@EUEG?`Mf1_F-J2C9De-HP< zLqPX0)vb>}6tpr?b@)SXN?e0R(8b_@jBg45ce-Clce&3Ywb|?>@a09DRuX0RtY!$? zHia!O2o9Rw))IwKpfZ1%@)|QBC7Psa`tFr zviH>}JIQjs1Lo*EzaYiMb~}4}N}v|ihT|#6;j$q`UZ|uPdz^}%B1ieT>QA}4l=8r3 zBB5tAj>`^((jLMTOAgM8Vcs8JKPK@veMuaa6Yb7ue`7HoiZ6N#SW;b9fCYZ8h~p^c4QJ>|sA=T6Sj0A$2vbS=-;7jfjMSH2&Y8&cXS4}!b_Esu^h znbG>c4tB^q``cWYI1x?9sdp+sZH{yGSE>s5{b3~L<{M0Uxb`>HR944JuJ3ITD~HMd zNQ%2#UrZP(tj6~$54)3gKTS_ejH!r(>J&6;*yb`SIB& z+C}#*g+T3ISXa;i)lO+*aS)QP3zz+i%ddHy({_GR(YKNd6InMR1 z(Ua4sIRSD037^**NnO=wa&oCx9c8ul+dvJC*USv=Mtwn|!@9?ESWCLu6_S`Z@6rul3%ZyUk$`@f0kmmv8>*V!rPm{r+IDX_ZyBP86H>}e zLRMyK<6UJ@@mb@ywhU5IQ=MGG;{Ulw_e38g#n*V{>`1HdyKo8klI1xh$PPwIVKB2* z)Ci~iFBianS-aRbnYu1*bfsS6amd?lhazS2H`1!koLrwYq z51Na7qfdtreYrjFf;voS8?A9ZB|Nq=-ykFOOhxUHp1=~>m52C%jv41P8LEtb z*DtH9s~$Q+GsBwfJGiG?cenF}_G$gJRv$w4Imq{D@f)#M$Lj0H+8C{gzecA9B5iz= zUU+6gqHuN&ixg+#rkZ1Ea=#sFUq5~&4Z^07bCFlGUt`H8&peQ4vsv?mffiz5U})y? zg@N55tRs9ReRT50aG<2hFw;i0c=_$`81%TT%f-()9b8<92K^500wHxF9t+#~Lxh zyvQ^yLZ2LnWh8&&pMM+?Cr?Ym>g#rxTD!&ypF>f<^lUm~^3OnePvGNRcPh2N&MLq< z`b>9*I@4kOcjRJy&}XO?$#49z-w1>h{O<-%hWf62=PX5DumagmY6^hJ zYsJn`l(*_p79`8*5EJ2fMZRmn#0nYV*>4+f^W+HYueOwMKff|U%E5V7v2nr`zP`Xs}yJH41OC#=pIa%R2N3j4$>QG9rYJN}n(jU|~;KOeFKW1aT?*gbELV3?CE7(Xh-3u`=qiHLe4o<=$UW)2#$CEfj~ zh$fK*hhuY7ou{@0Y$GQI{T;n>W)8FU)%nbI2cs1C;nWa>bQ6H#`zZNo>sE*eVw?JC zh+r396N9&$;$|9`y5=MhP|8E-Qb{10jiz;-#QBv9wG*NND?1QCdYovrdlr?dxsQx- z@|*+jV!}KN5${_r> z#B53L?bX5Wpwj;mqhr2-%BG+8cNjpLH@j-(?=Y1bG(;TXLb}}HqV{o)2{dxM1EYIS z(*?HM9dG@x6%__g3#`+#qd)-t35FbECxqrCyKbBLOgH@1ruy{4s;jLnYh9k+*M}fV zKSxKIw{pnKyM&@#%m%3qST>-+_bdodvg1hQai|B|<0n>uCe zIb}4O&PQn$&|#7efKGtHXNB(&>l~rB-8!1317r>F1b2;u-R?PgVu?Xj_p_q8Gob7i zDBMo8+NouN9+NOH8OidRjrcl(EBf(hb z-@GGDZ_eR##GaD!MYG1lNsj;oDnWv~Iyk+>{IrLmsaq-irip~$fP`S>i!wmQ)qtET z*ItvV0`})QjBjB7N=*UbEGy5bMjOexUCEi(kcX2vMaxs${c*^eAwe|!-+|D0QQLk@ zEU-EvRwQsw!6$iq%AZJ`A+{0wB^p$!(Ua-Uy(vB}FjakO-2l2bl%a{1rh$_E5~Vog z8hR<4p)CgpEC>h)G>-^qefKk9j3bIOD9`S%p1MpL(mowe8@e#Xt$rMpp^3SdHL{0S zw>^%(K74!DI?GJg5{FjKubqR2Z!v~xhW32A=nl`|ju{d~3)Dvk7N8Xhif5G>h69OP zz;easVgH<=B$r+La-N3RWpC~vdW+a(^8Q{aEC;vU8tXN;8puyXBOG@PW>)+@6EeOb zdD)eOTF2sEa4!OqAL%Jnn|FQfO$XV|YWJ!QS9M>?IFG4{Z8oBy`!fM?S==JcoVH2C zAi0GHUd#N+-YPkA(s{jbWmqDlZh}&H?T-lR;Nkm^#_n-7A;K-}LW@u6aF%0)9~m~j z2*vLAsZJc+))=c}p|!S#ab%wE{pJx*qlXyaJh9XnU4lN^;~NE*bup^V2lH4z=$bZE z3adHdf$XUnDuvZ?CDVWQ_I5w5qkjb9rz2`U{%+jwr(8L@uBrR``@OX(FcIv0d0r;U zvyIP((`Lji zHIz}%oFI#ZK#jb;!Gp@CO29m$c_p^oBemw!MHTCL$Sb%q(%rtv@h3Ad?QtbW)?jeA z6|nGvFn3vTh4Tu;d}-60n2G7(4)>M9`;ok0V+!K?!;7Y7QDjtD5!q5l(Tt$ogvZw2 zpFCwuh>46dJ;oh{)d*Go#4W)HC?z1ea;L+yb8%sz z1|yCLxI@t7cLWn7dsvnyCo`s&ByThzeL45{j2yEwGh$LwQtl+EW&2!gsC)Z*H+S!h z7VPt0jk*rDvSts6RBA82y{r0FO9LeA5OT)G-$L(upCtAv9`x1Vk$v7|L~>&1+mNl^ z1SH3_Mj7}rc8o^le!FX4PKd9(RJ>pIF7aC8we?0y?oZCwURbZSJkxsL&ATj4=yo=q zzXSvmH-+SEDf#J?dhDr{w;gK=t}Thb{W*NO3F%$ootCieCE?y43f62lM;sN9r!`F< zEkj%D7mvI0W3EFR`?aDVlzo1gaZdga}b`)yyCGWLbk<=JIbdtecqhp`=D2Z-7K)RB1qFw`Lm zPWNQJCE%>wI&DDYSNA%A1WTM(AD{{CC);YLx(rUPYeqmvpg!O_kzStpSF} z%lYrom8RJ-vS1Wb@1ox*)eTQ9Z4xnUtDFbFlH~&@1-7 zU%y)02>j_3?xE}#v9=bRomEEgscH#^%9>cyB%e=495g|Vhl4Ft24ZVNg?~yqnk1H{E5`5 z&g@3L9AB!fg=7{(+`vHb=5Zmgh~HuS6+3V4=Mq`tR@Ovmx-Yp(#XH5?QbfnO&vCk8 zA-+i%q`i(?iuP|I@N%K|NVjj^#kFTm`^13z1mwn#%bw?Q(yG<-yW&n>ue5WdJgRwp z@=D7UY&pTKOm}GT+SEW2Pb&?yb=C;Plg;>W!$Tv(XD@aufEs1fO0z8 z11O0oO0SRSePlbM;h4L_o~z>JfxX>B9A2-@miYI5mmu6->y7B%`qap-&$}-bDqVhw zGmZy;jBYimK+y4H8x2eyQAfEOOVm{+Ld|b`fD(tjp7!WZ?nDJ!Pt@*QB zwzJ=P9YN#9UwLa+Q-XPUjE5sXha{i3GTFrk>h%ytx?~UD@!BUhrJcYf-TkRSE+y9` zSxaHFRTA#=*oLH=1F93jqNIrT*7)i1R=-I)l1(_g0Px#b6P1wfbA7+Y+m;w%yIkot z&TxKs?Zkh10WHXmg6FobuJyeK%dx)hSDgleR#9Hf>L#UUzw&ra1dPTt_ocq+7oyDG zNlDc0fmOc8^~i4-t1)u>Nx$g13*!moEw}S28A>&$!>x|=<u^J)KZnsv= zyQMlVN~mJrr`!JFtd!ysWSQprBnEfS`PMYlAFTH{IM~4EA?q9tJ1VkUYR3;=?E9U` zalNEOvPno_Oew!7PuCd;FHMA9X0;cw^lizVY+a}G1xv#A5s93rK0lYYv^f5HU*&R< z%j17)KDLN29L+X=bt1RAerAn~evK-i$a9^ET^M6AEVgYyM)b6snU?x-_@+2KIbt@2 zW$nP7-LYCo#bYdGI+kXY)au?QN0V>_XS~Ttxuqy$z(+?X`2}G>CC7)=j-#Y#@!v>t z4a#<3A~kVY`a|xencJB39=%bnQdh_d^ywWVjGr!PA`&U7H(FhE;yx68qc*VpsM^|6 zaR&2ZplJW>SdApn2BB4CwX}e^xabwZw+hW;CKAKy)vmPxIMdJ<@k*u6p~$TggNcom z$=3Y#e`P7R6{mXTtohkYMhqS%%52|p0U<63OOR7Q?7tiXr&hUzP*6X_g>c-XN159=FBf=;AHA_ z*R3v3aIXXD;PI`=r&i;|lbxkgSPl5DhO`cC2bBA^sz}HQ*+}DtHSy!AX80gH()2~w ztG36qp6mXx37k5mQi8^Cd*mnj14p*0C!kUEEn7 zRn$~(P+amQG#MuK}Xw?);LgISkG?^v}Ay+v96(=XqqhWpP= zB|nng6#b6E^%}@>NVFY{H>jrBO9L@&b{$4tYrQsU3$hnqiyXV&WVjTzUt3te$!k*B zWMF-+yC0wXtIX|wu!iTKUW`Fp%2!{-)}yN^`>U4 zoe?p*Nxz3pmC2Mbzek^jwpx;NuUy*W1`Yq)+Bx^;jke(9v{z~RJJp1OoV<>qyL=&u8+!6f0~`f!ux z)lqnusl7z(H;rp#ZkJ8hF`duv0*mCdnw~Dk>&IbxC)cPZBtjXBm*JPCO=+%L98?*c z7xM{HTU1n0k5t4xFIe}hI|Df-nhv!)co0j}433n3lZZ%sk+thogFnWFs#~O#1 zIZhP=cPra()VpS~Ntf@&qt0StPnE=*^Z&6K&seowYaRUgI8W|kh?0!2 zO?U5{O69atsq;}{ST1trF9J{JN7xOuA^84WFKOlHbM`>x;n7^MglTJIsI9Z=Kd(Sc z`G6q0V3{mLL=VZFJ?`_OzZf>CGSj-Fj_G;x8zHQUr(HF7+>le?YS*|dq-;VT1uF75 z7#=O@a7pVAhIPNl%=x$KXC3XrC=Yph&+iQzmH~U?{BrBmGl%E}A!+)DKL0@Bw<`0R z$Az|*gzRjQAQS?5kCwP}zE?4A$(m@GrB|U|2QAyqdUuai^OhDVoZ&!eCP_haeyzr< zLA#wWMyuj|!gy8t7J(=!qfFe8!*v1J~7DeM!>9tzZKK zf9m-fsMoY3O+;;Uy>X+|hj|ChM$zHSmC!0xLwCFLBT~8f%grJviLV{$y|}}6Qws00 zUei_EkALHaI_!u|28 z&FbZ-8_lh-HWjCVXl$^dqszZQVH zfzN7!x0uIN-oekoeYZ!;1Y6d+UPl5!-Yzu3yMMeW#9XPRs5Apm=gJnP58??0Uu$Dn z*o5|=$pr<9Xhkjt)eS%Frg19?A#{`o;6 z!TjDE2V^Mp0D~XpeA!b~MMVr52))!J8vrY?W~7bzw-cP$Zgl_5-l#G03C_{m~sU?If zKll^Aw61OjnY1$yfa4RpRKK-;=brW|M+K9@87rP@QF zdd+F~P6YOdmak^>L}24*N`Pt(n(FP=K-Sml7UAFk6&5yr$+QuqQ%600Zo`cRwK{)+ zN5{NBzkZwwvQ8K&7*-XP8Kwp{0b^q7Ur~pJx?u?)DdoxCQ4u(QEMF*2(7Ep^HFR@G zZ1V;nx0E?IhYPqtI;IBa%2R=%h>I9!N{AGSV+o?vDx=wn%cK!yaE24m5XQc{i?~jD zk*yU-*G0wC4uVw<_s|oe0vq;^YS~@rk&?86|peYr2@Y@ zD^r{_`{Z)|dTkl&;r=TXUYip(>vI@U0$m zh~X{nl>6a!`hR1myB^J$1vzYoNi6N@12Sew+ccq9|xCzIhQb|D6VN__H zdSh!QN^mO=Y#k@2Yd&;z5OxR&D=Ly962*&xKem@KUcwaF5kRNj{o%7qL0j#|3 z2(u09rVqn4m_F}*R)$GY`I@hK=W&MMUl^p(h9-dO)r-F9 zgFFF>JJxevyEopZ?dO8&qUSa=jy^})=+rdVp7rCuW&^SxzZ*};@pf{$y504M1Z@K1e<$Y*8v(KEG>j|r(4#5m6zfMO zZ%$myre?&)PSDQ@h_h)9AB@x6e%0Y(wR8PS)ughV&@K!3maha8 z4_(SVttYVo+yekyLd6zm8Ub9U>>W;n{G|bn$3D9rI>aP-zFFV%cqRVE(I1a0B1QGe zqt$=GGANAW=aO<)VsjZd`cxR zp(SZ6`V zAKEA_3NRcX<;W#yMj!u|3y=_dk%*Btvemooh+Ap9X`Z5s)f+1LQWPj!NN5VAwm;tU z>#`kiE23&?cZ(1Usa0E@L+52A1{U9Fqx$2%e^5qt6Bnf+QJX>g^C*KK-xAiGPWBnI z%i)FZ=)zrsZ2;WMQ5;HJzZ)kh%c;{dx4Qf2uXMYL z=z8CRCZ_A$+Ku)tp4nlJ8bE22*w=U}vFUM>^E8yL)Sp;?0f07;a{=plE3~fh!|O!i zLv7qz*l0G8?$k=t7i+rD0yEjKnt8jI@f)@~%1TO8F29jcM=)!m1$zpN7JpL44@k)& zH;y8OI)zLBtpJD=K^6|Yq>)+^iAV_e;<`3ihJ7k5hJExeZ*Nx-?z}&Wch4Z!QaU-E z+S##9MKq^t5ZS~3&^kpvaYX)#hLAN~uC}&EN0%0;!%^1bHJ`0_1~Kb>v9;;BJ!pPc z{$*B#HP*m_Y`izpYkO4**tHdFt~e_7?fYjG7QCYWoS(1o8BCQrKVi09nM2dh%^0c0 zvMTq23pDOjN3SJa?gJlQgC`bwn$hgT)bmwB;MX)Z@N&;T6`PJ3^pXpVWmnA4WP|~1 zaz^z(_4QW5(B3|b-W|c&*_c4315AGtFfeR2{m{O<0z7?yJ9GXXJ;YL+Tatn)-K#1W z)--?wmGB@S*V<8OGJ4cLFX6f%!GD&QCH&30H(4Z1VnDOiHFsC7*V);z*1{bni}D5+ zg`v-)AjaX_e4w;kFk2fmSkDp{!QdAw`A+QK3OX|sf)^P0_>h0^CeV zMj1L@IhfL~)W-;yI*(oW2NI_%wqky%Ei??7zR2OYQ=b$WT6iJR)>Xt)!+9KhaGu7( zMi&u)gISGE7nQGv|NCemST<<5vViGsv9^^#M?!vnBu-CV3k9==_V(}9qNM4qIET7^ zbi@BTxOyYXXJcEFi?zEtP3UD8HfW^9?{blhlfgYaAyAUp;ve(X^4!HgtB&pNDYq5= zZ^!`>Z}(UI8mJk)-;JAUOFaQSoagw-{nhRydeYh;J%!X>Np;J;)nUY8|K6Tv@ zZ#DawQ8fplVEH2Kg{LR1*1DF^u;S`_tNFF`TY8_AeHWsBq5_FiA?lJhP$bN2GF z3b)Js`OCh>%*#oPCSk^Y9Y=(JXx{xfc=8*;SiG8^??Rdahn~dvV0d>;_fa!k&exc} zeR(QW6Dq|&a!jv5R37sCcMepsa(^P2R(h4Y*tT0CR9Jv1PQLMQq1%hy9lefp|6Caq zw`6240Dwy9c(PEknH&)Q1p>@}JJT|RGJNYh1pq65+SP&-iWN``NIM-l{pP|YRRLgn zKw|v%w#BjIvNS&4af>ZGm&-LAsv*RfWj20IUN2diQ5#}*Lc1tWxwh^wl*o3mFak z1dMI|V+T$r5uyS);;AoDCA6TH)(afWXrp!@HjeS+)Rf4M=iKk%*`V&p)GKdRr(HHo zv#)*F+D~GlY6?!G0#w_=FjKu5p<1rWZYJ@510^2E@ynd%-noH|m))s_=qPNxXmj78ZXQ-dQNSNOUe=3ktl z;I!2Fhck5#H>>HQvKL~9e|0=?-RrsV;6=Woc+eZm@;!U&KFnI$fB1Fl)um_Mnm!Cp zIT&LwUfDFgY?wbckS9hz%X|Bc*mx_6r+kbO4dRSx!V?^&YaseEXm!r$%pPIVS8I@5 zZWgkv>U3+!-~1~1;;DweU-to9Wn`nYL$EKZ-xPYY&>8yS@uCRNEc2a8{z^<7-Fhcy zJ-s{qeO1~+o@ZLVC361Fi$m2z`G9xRIGqzSx<-9~h4uB2p&@A~U?jwE zJaGvoa`_afGR$ekOonFO%6h}_*hDFPJ{$vvpD3%|rAPKKWlnOXe(z99 z*Sb^u8q8ajo^9caf$RA9Jh5Fg_3dyw92UOs(9=kZzY- zzjdqF{NG+a7L0}UqG?0VECNEW@+o;;7E@F~Kyh(Z5YKq%bxAFI@LQ{fLIzL-AYGkaToj|OWiXzQ zK+RDf!!!pHS%7)QJmQ(_Op*r+`pjTszcpzu7z^X%egnv|`M;%oVKEh!V4*?zh+h@e zW8n_awlwJXJmX1;CrD7GjkPT})^5&n4$?x$0wwt7;tz6w1Vni6ItKIFuy)Po{WZJ+ zLk5suX2Zu-_KLlNc@Fc}Tj`s;58uwiV>GJdU$T1txuH|eeMKp+dBr8~c!>3Ht2Yd2 zSQXzZ@W*uVxhUBm{JrtK#rd264Ji;E&aV=_G_co5;j_Z z*o;;Py=E+HW4%G|$4G%Y4Vao$u4Ia=1H0MY}2}Z7SqT ze<6eBn_V}nK>8Dj+mBFe0p;J$t|rfeKAxI|a6Mb*5)a2mqp$UKg@u2FNrep!e{b%Q zQ$GC&NekUazx0m4c%o4wIouqfia-dVmUe`))fJ;GL`1m=$|#_e>?u8;3J%ZD$eR~;{A7Pe{=~XWRG_=e;muW67$vih|bG?I$%7; z(~c|C=bi*E=slX|-37VasNGXQ=D}nMZDBj}U*Wy3{==Uc3(|sCg@pRQ0pXazG`H9& zEtIhHT5}atJ_kST?*zNZ_JO9R7Xc1R3t(X3zgS~BJv|+FSs&MBo%Nn5bBMQ9W!V4U z;8^G9yvz6#@;t($JH!P!3!qrkx{Fz<&XsUflr`=G1i)$}@Rtoh09Pox)RMWb4urDV zhj_$&Wz0&2kE0Z>t3B0HS`I;Vwa;QAhhmzPHnl8)Mhd9}>1GfWOpgK$TVa-H1vo+| zq_fv~_*z(9!bsH8xwmI%Ms*ZaNy#NUvEgl+UqCApYG(d?YBfe7yr>vlnr+B8U7apL zupELblHFgSwvR9HM7`+WI@x*Xh}Sktze=;u7c#|Y9ipNm5I8gxAb zI@Fj745$sF0t8qu-D~{5c7ESUql8*@Yx^@q zk#A-yNV#M*BUoJg1yTPGkCa>%d2>L)iUnfMt{kdSHb-NjDT$OHbrB!Q35jr`Hch&6 zn+}el)CoCoE-aq{P$l7ngVN32uBC?$(X!T<)TCGZ(Y+YuFRnx0gbyvru|ol?vQl-f zmj;Ww@@Qrp3?PYVwsGdGo9Peqn*Qh?@4BsENRa~I(UHjE;9=<0mADNNEHXS}^TU|( zDgM#{HqT6YS!d_(UC+G|&C77rp)yrb$G#hSJ9+S!}Zxpi#8?|zcZ3( z8Kp)zx#$L=y;en6cg;5zS?f2&g4YA;}dR;fzRkPdm zH$bKM?_O>?pUY2OL0Lt~cGDV2*S z)a6ETi%SYVv)Y7gDGs$U#GE(_`3Vzy`#`m<%DcG{^SNmGF=Lo=A!jS2Y7CB{{%UwW zMBI#rUNxw5`j6ZG(--6FTOaVn&Yj09c@(u8$~A$CITCE(88cD(6tVjlZl*&Xst~VS z&Vba9q_yt1(xSU%`6kGMnH5YnAqGR(6S9=~u5QZHy>b9u{uU^b3;^i6dqm2BL{&AS z_te>x9TIQbRa~@~y?BYBU$bc2$!_se5Zk!(Uc0r)c?tIe z$h)fE1*GN&Q92hn{lBnhCI$wA3*L;}i{LLj97-fo{WcaB$bcdlVB<4;20xHc8@02? zkjxrLA0E%eLR^%~a=1HIAW0%c)^Kng&}fr69=v?YDZ7?y2r3Wz#hzQFLeO*l!*Q)g z<2Ks0qO7nGsbbz@fJchvUh1+d1MstmC-x2Js?YP8)|wK8x#L-@4f@sV^`pY()>Rm) z7E}P#<}+_hSkACuVxP3jxNnm+_LL&jaKG;St$zg|oz5Y)ks+a@Vreu)Dw5L{xxHM% zRf7JU%~u%i-rAraz*|V+zz3uFLx>#9ToZ`I`<3lhY{N%Qjbqq;al+?)Z=Uy(>hD*m zu@mL1??u~?dfOb?;SHTK3^j8tfIF+0 zf`t@Mv&A1ctqity6H~KNX_RTCKS*-%0Ak-M{ADOtz7@cez4vNbCBZ47C#FVgFpp_4 zimk5$WbRkA`Mf*y?h9~cqm^ty>gtJqJ25L7ifk~{Rq`42l4+HrWy+Q8irBskQ0~cD z%W83_m?!-I&(_v{0v6hTiMMZ|bhojzu%7(}D+4fOvgzDX1dwv0l+8+GYrwtfnd`!& z%rL$Xh}zJQJ-%QoP6ZxdzXb&_BmJ1wEG%XU2>dGSxI?Fx8nh2&0(c^#`B-d<#-PEF zQ|u_N9A9N9e^TcE;|OzPF|jk=$>e7l)Ux`S^aQ3I@CY-7*vb4QExLgU$aO5{QxJ7sCS+sneRB{{jmp z=k}(ZbVFw)C#y_~#iBug){&0;J_E*Q3feFB%GY0*aE)l+bdkkLN~Y?iuk-g?DY$F~ zDXc8M?WY`6>1b)?w=9F$jW|umSdjdEdkrS7bVC!l%KBo}j#Yq?bLqWqz1zB?{fQQM zfk!(2W6!4nFR6wq(?g{o686Zo-AwWTc!`s8g@-p3YrIW}nx*LQVvVEu3)j<{;c~N!?v&WcXvUzcm_0nh3om-fEodAlMInw2BBXQh5Uoh z|86`Vpe%@eg65tq3H#swRJr&>!4$wdcl734y!~+*W^`ZnsB9dv8*B27Y0wF6p~h)t z4D**EF_^-)F7%02m0XuExi?Iihr8U7Y~!d61T<+)`%UW{J(fT0W5;nB6L;z3gIE<@Sf&*VrMQPOU)g1Y{>?7 zbvZfdz`=Xt$0(tZq#}YC>X1qZ@b*kbk^rT=~ZnrlQs`U4L8n_O`pxbDc_x^B_amA~ZDJs4KJw(jx56#)Z@ zed~U{=Rpi@0*)Q_v{C!+^La?cLExd$K0%RklHy*TShSMM{pXjr0fXs-Ndk5U4p5tW zUU?_TQJ2eRt!HmEmEBKgN1A3sPU>LzPiHEU13-`B&1cJ;>)(93t$92kKh<8@sa2Jd z1wI0{p*gguUe^Xb@@-$g=IFt^rp&U#h9rL1-!s@g?O`UGB2~mT$gzMIX z)#-WumuP%=bTsptmL0GR;D(d~o%|c~E_u$<`b0LTeTPoe z7RVhX1TQ&F#m@N1cRbHw=yk2jAK7N}smypk)892RNy>Zqee&%oz0@J%*HU`0;c013 zi4}G4K7G%bS)3QiNurn5$p1Ae#K}(ju<7Gtvc0}W#l9yNq{B=sV?jhjSC3_e zr*B(~!ey-TNI>v-0s&E{bC#i5#x*zZqI}8yZ#wYQN4l5zX_RYS_BbpQQ(7hV|FQLz zVNr!`x6&m_2?!z~LpK7_T|*DuNQVqaOGpSv=g=KPhjga`(gH&dAl)D>eYWrWedqi+ zf9D#8nZ2KV-|JaxJ@mGRLVrmezI8fhScy(bZ}xY4Nn3QI2GJk+1Z4x_15-$1)6 ze=$A7p}3`Gp36c{(Uv8f64sofWgg+tJ!LrY3kGr2<^je>f(_SOPIlm015KnLVF&w0 zAWrkc(t8s-!^p_Uk1a@G7KA}l%b@j_o-a*P3wwRXoc;S3>n<&SZe5j^rOf_IO z{tYDgDYWhsHL}LP`maa*=}R7xfETRE4zD%adEmqh?STVlo#qzInl_y~r>Wko@w_P} zaN&k0Bp({NLPG8x;-c={sQ;qtCr^Czk0v)&aJ_Fk$LkT(jhG;hgwf z8bR*eT?*U<3CaBY;X}EcGuhv=cclWql9^!pKjc;)i1$baMf zlZ?AFQ>>2emWb9?bLAIAp!&Dbxh_SW{3qvt*iT$^yDq2KrlLl~D9BfMX@94`XlzRO zoZN4(xS_MnskWss`@hSsSe~9!6Uu5GjVv*B!OKp(>YRqi?23-N{`#mYMZGk%ogyOt zyK?sAe$6>T-UxiLsB2aeOwihfqkU`Fc5de_W-4d%haA_^Q~CMwe(|54i!}#4ea&(B z!S4@xR2MS`UrK#X+$;DAyitS4s|sz7)a)v5U#*OBal~8Ik!pI+T0{x+r!-b7O7g?4`1PNST;n8T|%JCWC7zDJp zi~OtOedgT3<(6fe+M6tiJQcSEZ5ioss&zZS+11)i*6&ch(+_A`JK1f$y&SErxs{bz zZKBHhX_2Bnmju^al=+X8&ICLCn?unpSzge{wDXpoARCer^c%9KS24a7I;^a^tp&?@ z_pjg#e@LGjDeHvdMq#yI`*s#O2PNbE0k@37%k>;zY%{Q1L}0aqb3nzYy+qQI{Iqzg zA&epg-OZCB5)*t{Fq2sogMh%&WJ?uv%ssf4Iiz*Of=zLtDSM1#;>cGi0}Zp=u`~!e7XJpP@tWWp4K{5f3?^gN==|=K7=^Z-ESMO*Hz>fYhQ`ff z^_3vckw<0U>)Hx}X9sk@@xK$W3TmoZ?esoQezOI20I`y}HfpS9ePZ60KLSVjiR5MZ zKkUJ6nwqGOYLgSYnkwvOesa%M{#u%lQA-K<^+@jSYf&EqgHFz zM{HJOPWAa!0rfqv^uPkduALc;b#c{fZ&cuH(0#V%^x>8{gZsOiJFgXs^kB``F?2Vy zPiFIhItg#%^CiVJ9392JH=9V(k6D7AZhk;Rd?AfyC4}!2V@V&st1i%MsU_eFj*9Ktxc?#Wqq1H>C3B^$bE_F9$gXShUMWO*1UMYv# z@+yWyA{Q>3Tk+xDe@(-`9-{?OJ6nwA-@UqD`B*@9Dsg?ScnrzPFC3^?IWBJZB?oki z01-1fGYp{sQ8&-4xQvVfJ72oLxM`fVaI|Jw09Y8dr=GiXCG_XM=%y{MH248~>Kv(4 zzaNsBnqSR~aK`5&(xPiUd-3AMst4IW&A^jD4Of+UUM;Ql>?ONrxcTH%mfHSjpnpU_ z_aBnmEFpL%Fro98@En=1ok*k+@XL<4`&?WiE^ggm9PK5+<>`|N#EA=WhCaIb*4 z*+t78BpeNkMN~X|7EKO?6n=Yg?F*dHiyq!AYV=^GqB?ACJ1?DA8w5}EM=FZQQ!;zH zuzV{-ZBMgO22Nmubg`ZuV3tZl^M|%Zdb)fC=Z~a%m-{<%Gk!g94OfM}KXE5_2+TN| z(HV*n7Xw!6*AaNhjx0sG?zgkRKG@xsj7w}==)?xU&80y+(0|iT|$`KrNhh zxV(s1Q$$w`6r=y9wGHs)^4dWzp8VB5w$M3Xgl`XeS=nqJNLQv##(!VMLSI;D_YwiZ zzfkTz@A4@ze*Y>Tqg&Y{+i}AjkC#V2Rc}YDQ}Gk+KxU|8>&b%nIRi$^7Z!;-~P*aZLux6#!I}`9h#KYH% z0h{i7b0WB#xT0&u*!RMT?tH=<#oZITWNtn{;5VXD2ZjMqxS#Z~`J5^iz4Ce0^T!>tQHw^Fa+kWFdD3gzMe={n73dS{eEDGt96;-*oVxCW0xib_#Ufyz?`30Ew4$&z#Sj7(ZgPiF@N z4NB{nQ|}DtwxtN6Gbnt-uPuhV#ZAjoFoO7mz2{JZS8ez^gAHh z6!6~c2+1qn;=tG+Q=w2e0eq4h&ML^Qt*f^Cg|8t@d;D|6_N2`QQdYPeUR$JLEQ+BH zjp4~(G!)5ln^d%ZsR>Bd%p3q$1-2eB`*qbRf97+%n#~p8oz8a;QofS1AS@Q>wx_jG zenGX^r0FpTf{mocn+@yFsofH54(C`cu9)Or50Cy$o_yRJ4hf5h-uSpL#yYSr?6 z-d{#fF1JO|1N|EsN&yv{Kg{xRO?TRNU{8}AwmDMd&z(oU+QTea1hO$^?JTz7n=`vg zr*czP$a-NSvzIfwqbO?fBr#LgVc6s4WX(Gl@uF*Z?5^E@|5{bIu$v;qWn&3&vk6)q3vRX$yRb9(UveohzgIs)T22sQWj zV&dWsB?Yg|(W6?nUHl?o|N8z!a}A%isVxpDF?LWWKjNJZMe86*5f@-rw(W~#&i+nT zl4B@}T-w<1*czD+6}-&ta5Wi^A&wlDPh1;t_lKA>es~t(PJNIQ|=&~$n zak^Z$2*ZULr=>5VwAC9IFbo&B3IFnBhhGJ?8T?i`|4!&KE-v>au#g*s>Qo;}cHw~= ziKP|RB{1|ViQ^kn62&t=Im+$H)U6RgOi2PD0eoU9PwntCcpz{5XG`M#B-WmA7zK)V zB5D+?4%;zWS&yDXT#2$dgr#Y%Gg?bW57~4+M~t5L+z5dd6Z<03;I|eFho3is!aq&kH;7d;llP+C6gfp(q zHxpj%Ot|@<;pgd4OTBAu@@3XD!r0J?DfGMb@SUC>@w;{Gkmk4AGt2`roPl@?6unwY zoPpOqAHX?k|5b460oA}-A@>jnu#$L4t4exIl+ak81%e6W(U*!yAD=?${BiB;|7zPnO458#P;}^t zqD9!4qx^vL!h#S^$PC~yU7wc)^|vH|gbfXgA%;F;>X`Lt!!O_Nh{IAmi>Pvlh{y!^ z9T%{lifr#~I_F73NrNjdtlzid(vr%`4Cxn zH_b<3x!2p1SeO!B4$KW?p|bD#Pul7TTCb`MP z*%Z^yib_gK;2cgC7IVN9{XYu6?VO4tkngFF*4h4&@OKa*0KYPTMwFJOv=Hx=bm&tM z!JqvHbT>DEW`ly0X8BmqNwNg^o|I@6@>h^|a4MLDY6A^jqs&#R46fJ^rl=DBX?S?J z;C}?W^%2G(dhi$y_=&09P)>=Sb7cCFqe~$lITP03hz)->Vb49R)jo)jbArJibI&V< znd+`rOjtsJ)xa&p7#jApsb5kCYAOGZrC^iy zr8q4h*1@tDGHGR#RGRj!>59}$lRg{-+W%Lh15DV%1U02NZ!Bw{IR5Z?6@CM*KJE4H zp$}hhpzoH|65>)n-<}R&j+)agkc%$LHxH&Yx+&x?#Yy}bh&1=ZjKV;ZJmrRCkr(pS z1J=sRGL%#+7EnKIayERzwfOaOg1&@QaUfxbjcw1>3?a-=vlnPEtHs&*Hzv{XoAJ7E@`6;vDlzaUO?}Ykw^=5ytTky`=Nx z@o5$z5)&?edHV+@zKJa^eC{27b+vQqncJC|_I>r&=pl=VkL)b#8>Ep27)TSnjT{>O zx{KRnSLsE7@x$q#xCKm6l1}o1y=mdfNtmny4qv4@ZI4j_ollz0BMj)}JRF{I%s*B? zAobF<&&5t-SBZ6@5$$|zh`KlBszl@QvmMt zlFvbh7jQ3C=#;-dEw)tD1W86H4}C2I*|l^7)pQRtMrHs#{tn|yaV>OdunYxCGhU<0 zmS+ikPusabm&9hKPD3 zv4P48*P@x>MmW6Dish&EgE7W-%4Sh_eXNY>dq(h$PfR+38cmC$G$x`OXV=a`ctApu z`M)tPru&lq{xY%5yDNZ$tfnA%gs14=UYvDmeiR^*LQ@p&GkD-JJnRK`Y1zIn{RrD(O5n&Pf9PejGOC&7NdA(;D;}=u4k%@(a5o&nl2Trn_4!o zJH;0c75j%HSPPd)MiTucAR$e6&nZ-Fo=H8jMZ^CLq*>xp<;mw^{`6XDB64guGcwBC zB!+LsLJ}i)*=Ty{(DMGqA>c%UVD4!<@Wo6^Yr7t8jz`zm%l7Xdw?`}!lz9f})9US7 z3mqrx)fd!rf2n*6P)F&Dprfh9Ba4$&=ij6=k#X*bpnGWk;3C_z>A*>+hdys<#|$wn zlvu1+NvYS*a7!5E=j{?_U=$S;<#in!(HFB5A0H@q{x)r-T|8%8Fh_sP)x?QijvhDu zilvTh;()YMM#)Q)=!S)LpvKRK7&y-7=2z`P*T=qi@!~{}jQbiFDLB(m$<{C~o6jH= zp6m-pfb7Aho}Og;v(?1;9Kx~8R`@h+u+AEf3Y)}pD_ND_st~=_lZejGW)FOARQs$h zlZJlxY)|;1cj{rS2ddrnwy8EZovteW^^wX0t%izzzsG8_q3uux>>?@lQvH*Kp&?6w z`F^bg++92c#83VrqHs%Pnw)leBA;({(WN>b#5E1;nS%JhlVb(QC@8j2<{C`{uix?t zFN7LM7U9i7>-XKx^wb2F6%!foK#dYdu2!=*5r2_JhK2*pAJ^yW?F!1nbsc6uzep9h zdu&7<|9Co>;V7On5~VAHqcATWU1TEI&8`kf9Iz4@0k=aWM z3L^^Qk=tyjUBvOjRUJv1zj*QSzT3-K^+=a)M7!)Bthh&Pg zrDsG$1a`ncrIZi1 z^rxr1>)H#U5i=1wb|)nd-+rZe#FW|qA6v~CUw4=RIC`c=%Cc+-`yIJ5feDmerdy zh!tzc-s(c>2b<@QxR<;Z7Z>F~O<~T@wuE#Sw4_+GDG`TDG8yH7wyjZ`5B0B+uih+3 za)mqE*qy&3t=ueYEOI;KcD2(@cQA$mcjrWC3H+9L$imazoe(#qHk-BF(5rRAV_HF_ zI}GNtm6r2@PG3t{*W>4k^{jxlu!ewm*GyxHih!<1L*X>tVk(%PsNkoiK!(2Gw06Dd z3HsOZET#9_FFM!EiNevPjg4hIkGBf&DNEXaqsI9BMrl$?QV5n!Umyw>eK*~Yh<=M% zi7d)hg%EN(0^^e>6R#_jF^P72LxU#wa$7#7sJmnsyC#(%@Xf?{3T*N>ZLwrMrMF)* zs@nDSIMB}@n+AB~o!#A@{R`a0F&i5q6An9TItCNTEsr87b`*3>yY-}X$=hXn%+=OW z^d+uPN7Fq`c78GX0ACdxMK_Y<(VnM{ zO;CpqpH}pvgWKwd^IPFMw^KP5wH{=$Zn`JV7m5)`i($CBZX&Wl;7EfGQKfpmde%x# z-Cd<0>&C*mawY_93T}pxd*uZ9JT#eSfC+&6R$vU z70^@>)IR@p>U!CyerCpH&2_xRxK@Ua{&Y}@t_G`kAytSL3@5hu-5trFKSUtMX+Ou_ zWJf3on`B4>5#ay?-2Ms?!hHG!+He5srLdpK{#yD2$5{u{1$^{&F~Xg#;(gI#?~cU+ zhom-%q^_Sb7Ai_v8N(ky+-)&QphRKfQCP|NFzOzGx;)J_^@QZt?ws zq?1!XQPJl4h2K*qjD>(J?2w0k9L5bzlh<#3+ZRF2b{`F&Knf~8%F1HE;k3&>PFV!* z%zEtYyMuIQ53d@%@o#TApK!6aluopfmtTd@6kiz>gN)xu#Su@M^IN{5eiz@nBNFoxx+n*v3;zrj2$#XS-T=kVebKDVpb83I#&G9)pbfI6{sjc5s9V#Q zj;SK!K0q3FwSJ`5aIo3e2oEaDe3aqL8b2&#{iYT=s(nfH5uf({;kQn?YSZOc<h4oES?Xh^(c zByz(oV(|-KEF%}1kR;2HaC9g*a`&fpaxLq`NCe*qLmxZU5QQ8aVcsQsIfM%mU-|0I znvYBYUABq+QctFLl6`d2eb1qVQS@}FuG#2W!lFYeE}Y|{bJN2|!2KpO%e}-BYsLSK16xm$F(ADfgi+zY`GWNB{#dJsHW!Y`^5+ksmLkDUAD3|gYvQ%mU)Kl&4Jwqeet(@1IzFgi@c>+c0r~%HIsj( zi?&VQy+@*Y$(V!sZG;ys+NEiQ4p+LCjezP;XxavU$6_Rtlx4B%R#kR?+e{TmM#jlH2 zgdQ_UKh1i}ElAVJ31eyLD{(X+A~`UtKRbUy$;{>(UR%4=?O{E34$;>aVmTbb?@@`Q zWcEv&(Q{iJ-4POO=$~&N*g5VBusvt;_TFPlM4Fvbe3i1Y(~ad^b6{JbV6g=6qj^rsPQT+bO`G}2 z%st4)Q#t+)kCZJRNUD%1xr*?>(QK)zVWLY(R~|?<^r<|h_*F(aF2@bbZt(rQGS{p> z1SOJ>>kN>D8T4Ah2NBZU6_k2SU=C*i}l~8}| zlXrf{U22C2ySHMOdiL{$A>+{G}Rxx zpDY|qo{f(@m|kA)FH}s#`O0dXL(LZ*ondF2no`TrB$NBk%4aG*m4qj@J2~QUg#6g; z+pGfg{XBK1eT(HPk1XKLrInQhz--&g=bJu0_imnQs6&5li6wmh3W((rV51P`X2y!y z7v!470f)Y2fIU8nO+p+`-m5dSag3Y~93`w>x_d-c$B>vxH}{r_TFuh(y!R$@lHd18 z1QfdZRkI@H>^>lsfdJh^29>c=j&ds+_%qO|bm4VbWu?XLWMY_HflPr$_tLD<;i2Oj zJ9|7bj>bdOig`Zh2c*cJ5y`51DI{gWVp;K}La>F&^#_R-+s@DTLh>=}btSQtM*9%z zS$1|GmxP;&ieWHWs}b|by>`Axg%T$uVOD&pN=dRKw8tzQ6(nJQ`CP~EG3m)u?%OYL#3MKPI-1(U;W;d?e(nc>9~LJo~O8)=I#shCQ*4^O|c~Ldv?AMf9o^< zhv4K3NA-{Il4g;8QLfJh2A&)Wu!;P>oZ1@tZb%oefRwXSON`NS$;b*)(9nqA$I*4p zMMo?xfs9<_-Wdr(OslS3nSMGBVLT;J@{N$W1VG;hKV%I{)9%FLqJx6MPy=7-OBq7= zdCdO9gBY#YPwgonb81g|%IF*95+cJqF^1!AoKJtg$>N;W6LkPbSjkv_B$73F%M$$# z#GPKrYS`K~fC8r%--j9-=nCJ?sh?r&im|)JGpWOYF+{O#5}^ zl*LK3F3LjA;7kAR^D(Pawd$e|a?B_AkHc6gpQ9b+AEIC4xkGby=+jRpEM)vWIfYwb z1v>sQz3ohB)NhG6|2)CDF@3}r7PjF6=0+#S{8+4>c$_1Cb${=o@buTi5zVd1@(8T> zLE%1FWap7FI;S%-oA>obvnh4R_Wf6{$I0?J$Qc_i=_X40;=hMUhP>V>Y7&RryGfk< z7jcK#`B#ad_E&7{;#wR0z{yMCj2uE!N9U*&StQH8s;|hRj~W%NuXVymG+%6(f-RLZ zb!H{A<6xUA59rnwd@pIq1b?Z{E0Ne~#70Em0^lonVErSUD*bgDWZQ+7Y<_sG)#d$C zYr|Jdu&I+1v$`Tr4?8tEJ#!n%->;7t%N0zl+gkd8j=ccz@!Sow9BqbYR<9WY7Q|a#Bc|K;fxmFuiYNb(cV%mUkoCvumZ0^=$mKMoRH4MRhl#j{3zZn^pWFFizt`#h0pt(ggd=Ly3| zA_4^a5r9#kvv4^z??gMl{(Z>gO(wKDwUk5Hf!mcMvN>j+e%8p)PU*>Q> zpf2h)?5VuB5@FpZY5+CL(8XIy8Ay5%Dn&r$ECoWHQWSnntyJxJSp%Bff$yK$gVy!; zVhhXi54~q49k-s6#TQGyJjUAjI|Es6Hq=;cCo%cMB)`PP_~{tmhIhBwWiu~81U08K z?$5X8WW7f=$E9MPb@8qBaWo1J_?D*HpB~<0NYl<78k7@Q*+f_WniJeg&0qpAvrDfC zVZ|u7(fB1=S{pjWVARmq_~e`YbOtopnvxDaJ+G*%JFDOws$k(!=9jNeE2m{Qp=_)Q zmdGDTxeThEBw{y?q!LhNcr|7jST|5l| zc9fAaSs*?o=@i0^!(m4G)rBi71nHu0<4%{&WTzX~${|26@Wy>U+5-iV`-BIGx=cMVzC3A}dKQ8J>dv?yvt^v>obc)?$v<-ulb zLN=_ej6L#wO=?X8Zq&m#yLLxYPS1=qs_XPu|E*iY?WkS4em>71oUeZ#6H_@p)tS-Y;!&W+NbKi5R~7!4^`GMK!x$i$G)zoX z-@i8#)b+3XUoSwRN>3hxXd0C(6A2yByp2toetcQgzjZ=cX8==gA{Qd(;@L8?b#kI? zvE{%WN-b8&_)i5%<1E(%`vF44G#zd|apMD^Z>Fy660fXfh_I5aBT|)Qo#wQai{yiwn(6jAh^R*u~cJ{3+ z=lAn9V_@&Z+L-)fk-t7(h{thk`sA?m8Th$V+5pr&o3rNAVRG zA!L~cei2Szrw4Sgv>C=dUv^{ff4AH6xvOyHc=+`YB4MVob;P`gLm1R#v{y^%elshAH~ast7<&lSXd zh&hycK=_EMY}~kaCPR#l;_PV?hc@>)|6=DQE0Mqh=b5id?^C^Q2FArro%_r&e4(3o;~{Kb2$K< z+u11+;Eop6y3l?3A`94_2%;|&K3Ewj^30E7c?F7?*8quwx~Oe3A3_{19I-} z=t4t*e3s{TEP0enu7%6208*(ZCp@Y6v6I?Bmz_A!nf)8{Rud_ex1IX#Bg3ap{V{&U z2{*vTA(#-3usGV;p?MuUwYa$MZH&8D&sr|SeBp!t^MNnCb*W5&j8!xIC6vBzXL?h| zz_g5;)jbTcMp#>|l%a0hfL*AfM!Z@_z8UG{=jZn(UxB`M{Gzp6OrJ$}Rf#@)*cPa) zQ0sr|$UKK1$G1YkXfKD7))<_p?H;IC3p<6QSv@C4u`)SGul|rY3LBVhG;zPZ{;9B# zq3oKdK#xTX@lcX%%%_w%>?5n&I~hpxJY^*Ju8Wpo>oj#%`k{!~+Na2MXBzvp-EQiy z^PvH$vG2z{;pLN8ix1==w;S^yP1ck84y7~VN1Bg+`ADw24Ru02uRLxrdvc!t@Cldw zLNcShekNsp1x`1$4Ox9pt7P8b95@FL0lC;=aSI; zlrTjr`+BKRN|y}mLZSe($G%g5sg=r$b3Ti!q~DYgp2^RrQ#u-8fvvZ-deZ@JH#avo z?4(H>-Bv>mM^;%?*2U(N0@y%j23>*Sp>lN8d=yFCQ=cTgLE6eoZ9~{QfNiEVq;E)|1<>q5j8tb#)o1r&4zh?|#|zC{#+O zaZV)Mz#8h5yoPlyT@1XY5|QT%u*RlD4YnzV*|a-DpIHM!IFevlE@uj>@j#2?SGXJD z7_P=pRlOL2CTwqS&%8g%dv)^WK=sowsM3ioT-+cN_Hr6EIAbuow7-J%gN&X$xv@OJ z7}3T12?BmCY*UNXIbFs}LG~7S`EY4HYhAcsKG-QvKiLJ0J}K6jG0^Ef0!SmmzZ+7q zw+jiwhuHv1EC88ZU0oOnhN=CD)Qt>@%TKDm-o3n#X>=;yOHe8?`bKj>MfUaNur+6t%s*pURFt5i$ZN1= zq;ua0x1&4gEX~OM&Hnadgv?*pS0{G@sV@6QV$GL{Zdy8t0!P^3m^1~;zenv@$Ol81 zv9B<3Ro54Pj$4fDq^XirPqxmc#HLt*j_zbbr{X3*0^9)&mo3i{Qytu=6OT7ebMt~< zN|~*iP=uhy-40DhkKs0#_^-~+8_4&944j{89(N^;Hkl5TVF~4aAWagu3tH%t?GA|d ziTfuwd_m02M7OWLan{U56=1cJ#0Tk^jm9?2Xkt6{=Is zQH(BG2U+Qlrf#8IvoZ&;a#6y~@9u`>_D^x0o%Xq5mQseVPrL#G1G%K7QG7dT&1>>j zSFRNrIoQ$LpW>! zALR=)yuH1#F~9WE8wZLqI~m|GWi*iLn;;fBk*ZYgO0XgN%WyVlNe`avC7y!TXBu0| zoHc4B2O|A0gqZ+$@AO?$X#?F7 zuhGz46&X4&P=rseX9%%Lp4@+by!ko2U-a#p-Cusf+?4sc@35p##)>UqM!c}rpZicSfs;Cti7XWi*A)3c} z_m~FLG13-)&@&lUo~xPJYn8|xCrk1(ogW66s}LU*>uv7j(S6p72b%$(l@A&-5Jbnw z;kxOuSFHuRsrN2C^H@4oyIe={t1M5@KhjsH%81!YpzS~U(%qgeVjA)LdB`6UlDM#e z@QZUU#FEPTSeBNt3(kP(pMXU;n7)_pzjCUkN84ee6YexrPV)Mjvf`A+dgGl%Q`mbg z=+v54?-%_j1wL=Pmu8O!ZS2#91`c&AZf>~c=*+?!)DyA(n|h?QOW>aHb#Y)F`?2#< zJ<7qwSP9>cozDopj>SuH#@O9tue(CSs&cRLNejE}G9co1H91}ueO-bsMQ_zeM;Bkp zgyZ!44Jj)PMHZiL21@SBoZ}UA)YoPN4Sz_VLecWO#c04Z1QzqP`Z4Xve5_BxZ$Rk0 z2{4b!L(%{j!3S5xk5l=^4jNZHtejP4rioHV)jhJ}4@rWq!kge8JH=lk7?u~eF7YNA zX`&BV1`eAaWj=A}R=bP5W+Z?58a5eAQ9fhP!5LATjqB~Yr8B8r)|yGcGNlOJwI>FC z(CQBZR-dl;7I$2$DjCN^+pkPkeFl_C!$_Lx?A6Qby-+4w%gRb4CFVB8OoIE%?uoXx?-Oc>G|I`9Wa1{Vs7&PvDh~^ z`EOQczI+j$XQ6CSiNvn`@|v#rTu{_TPICmQu*3uA4}#rDQ?|_*{D>?YY6j+Y_sLWH zVTVn7&&I5;;7%xQteY}i?21EM8%Qr&m=`zLh0z7r0fv(FC=&aBv>$bK1=lkU>1s_( ztTQ{O98_35$x=l4fYQ!k))Rm~xDM-U|6Xf|!G&IrLQU}WSsZK$GxV{6;HgJ~vPUGU zC@i^=*9sgDIyEo*xLrF#Hyl|SEYP&*o}R^94nam0Ud$&ICgZh$As)CA`CtgxAm^r| zi0NWJ4L5Drpv`YWkSc8%tr_$rJadjQza67xJniMl;9%>4Ox6P9lDzYV;XeCd`Lfy0dQs2Sugc|q!d_f7J|Ah5P&6T{Kt|<14=j1 zV5-Ew>w0PCNvYYi{JV(Qe{0Oq?Ec2Rs;g$&JVf0h31DHg@+7i8Y&If``i=yL8)dik zV19_5=*6SA1+YMo+94H@&Z($4FX@b1G(D*SGzWI87 zckmM;$1#{UE-o&xg&Y7B-z)F$V~9?pBTe)`))#cemw|Pz)^5oBtPI@wu{7d!!aU>R z_IP=*JJ~{*hh4F3Uwy?G*K1zzqP}y~Z*_$v~-} zriK7;4~NfYDB}_sn4t~K&c7$ESN$y$k!EYjdZDifkoW+hP4$TlgBP*_kpCfukC&JH z3@Yi$?~Lrq_!$@6SX?R;T#F7ir>BWaOG-9JZwSVic@yS;sz zz3e(@(M3a36F|q>+NLrZ8JGf}4lHwiFBGBYOf>Vg2rRD?Z>+$%KjVlW3PlYl^iRZV z^iXrgdGG2z=f)L2#rj=bU;m=3%c-zRoe6d!XjV*K16?uzcIr5u&))Jw8OYh*4<@Yd z9vu=oB_@CKweXAg1DpKu#ONyUMUB8Azgp-G*k*ZT~P3;D;8Kmpg3mr7Pg* z#PSFL&IqDofR2DALca)WB*J$4eFjnhJ1`->x zPGgyP0zHr?UYTZGOb6HV%b)3vyB_U^A;=27VO{d#~I#5L09vRX(EfV1rMfrN~ZjXs210%x~m#^KXQABtskX z`fCBGh_*KIT&sKJK3y28Fh{;Yk~u?AGhDvxY%2V`Q8_hUr=l15E0b{m_Z3||W1Lxx zz8DGSIl4ZJMf;B>WZ&M(LAB#{O!khuF1w?nPP;cFr?ZnlTKWaOVFm;7a{dHYjb5sy z;S|#^MVfDTIn}Y2!;{#*RP^UPr1BW<9+vDJ(C%mBp^c5MnsGb{P>_L-Dp2ST44ft` zsrmk&#NT`9;2}n~(YlVN&Na zR$rTvHvUS+L`_!jZEdxneit?b2ul@N`WV@ot)mF>h*Ar_P!53rA`QS){zBBNgxzE& zEZ6EgZSoaP-3Adxy>?LT+McW`z7dr9|26=cvV&xnK~~*edAE6$ES;?);1WXxSqul2 zEayjUA=K|y@~0fr7?zsr;_WiK%PdrU2yt9YoisRedmk+D<(k~lJc-S^U+$inDed#J z5EX*qBB@t=3QM2$-cHE(4Ef##QR5{@`J@}`OH1cs%A_DTd;wr0fIzLjC) z543CpuBznc&&1c)XcC;CKD7;w`+u#i_1DzWiaR+$_*7;5yQvs*9RobPP{LpV(H{JS zgvET>ae$Ha@4t-;_ba&Ko8Z6rqcTuYXkNl@NBkEm5< zI>rHdgPeiW7rmS><+J@|<89ME-i^mjvPNnlT2k3B)*JKr8{)41e1ATF`VKG^l*IqH z#rES$JN)f$Kil>HBl@|1?%0EmD15!p|CD0wa4}{hDDSJ@;}_ZHPoW1s=7O5p?-Et~ zTVUW={O4wUCeCq(j3>Ylh20>3m#NEvYqy1cO&kMiv8)>#4zq!rPK95Hf~Vh3Pj`JC z`d2>PC+q*MEki`yetWH9DbTjT&rWCbRJWirjK_70P3#7676IytM;ICK809O`a^0YT znt=B}GqL0hYa={j$_C|PCW!?rRU3#-MATz0Uh?ieFRd5*R-{tAvmKcIZB0(t;BdW- zc9`O2Q`n#@?);4P*WX2b2Z9TWZK=!4beBiQ3Ou{))ITlEa#I5X!vm;yu+mSi`H7x6 zq2_yaPzI9X;u!+z=tF@Tk8-#j{GRgN{O z9fp<}hRF6|3xx*^A5nq+ji@kcNf2p@BuM(N8N}txf9{Mvr(7iVaklts7**^-k5|o9 zD~9=bzwY<6mG&=sl}z5jGIaB5;+)33UysK=hl>Xzt7Pd2sSo>z85ie(Hs6wclb>SN z=(_z3@CydF6F@QY6-=OJTBj}v3YOG)>OW@&Jf%)u(wCP_dRK>{N{yV&Y7?^tfcZ-Q zFaYn2wSf2JIG|$#acWXWj=*I4ce%?S6x=JeYe~V5blI$c5F|I6k#T4{UH`vL-sbki zTIaw4kmi9Z0bH2i>o}txWk*$PsQpZ(p%U=ocOOHI2}%iWX=!!|=99l#-LWgCL%{Zr z0KGNP`tAYWtAjB2tL0iotYwC#Up>zcfF0oZ?3?6VZ2>a?Kt;^W<9t42prudO(213{ z=+IQ1@z4RUC88| zIID}kJ4N_*f8p%v&fLNL{c^nbY)s%*mnb|Ky@vd+FMnq#mBFy7Y1JBHzx<@C@%a5S zdm?Ug9O_QQY%0A4IbcR~q>8ZIB-!2Izi3`68C9Jebma1|Vtm6y{S5;Z~$w!W>z^4M#;q zB{e7(fixRv-(ncab=y}^h1l}+MyFWmd9jLV`o?2O9 zL_AnG{Yj3zTdR+}lI+P=3F29#{xXDx^>pPodY*0kq7|6} z7wLxa=k!DAdwErkfae6@&D=aZS|1iv(x{8KRM>s27G{@7Pbc%17inA_b*T5#?1>dg zwTi7+9XP=Mxtk2Y-IVs|%^>rad|#WC&qV=#KJYczcIcqf+iX`1ct zga$TB6+=pu2tBmi>?vp+uO*Ki$e%iiASg|g%cEl%ki_aKZy|#O*UDu!M{5i^| zjbNl6)qehvCLA-4^Z@uE^04;XC%Pt=rXqEH-wQ!0t{>e|ha~K@1=mYkklfc)pW9l) zadgGTAB}$vq0R1P`4BArA=fp!@Ox;53LA&x{vW#DGA`;b`Wh7x5K!roQo07D8ziN> zTe@rLR0O2EYv}G8x;v#Cq`MmixL<$&`+V+wZp_{*P z&wn22w)$?1ouQcyGWUD|*X(ku=zISQ_D~nDG9=0qA6vx2zr;0pzB zgCZ~b#^9vPd}0Vs9uYVhi#p)naXbYym$#>X(_0jUR`_X}t&S?Ac?U0cLhttj=FTtG zIVzhuBatu1H_MTHdm69r5zPu91x!gjE4_0LTlIK%uF~|xz0?l7u1ik0id?latACFBT;jpDhQCGBf@H7k{#Fg+ zUgQ)AX7V}_y`0zd$2?kR|H3cp)%@N+z&gVVB_ev*>Y)BhJ9nU?yPc*l-4KT9ZIR93W{n?-r zA5Our2WJ`AM>q=|xYOFC-G$3L;x;bXi9g^@DjKnJwJw1dV8UD_2o+f?E|j^^@b{bV zsx~f}xi$pxEz5+Ab~v!-Zh?(4uErrZyxA6no?tL!f>YU_u8*PDBGa6-?iy9+>r0!8CYWVYB(V zm)46+sb!;d>!a2oskp7|Xo$bc^%-We+srL{#rUre)d!B*n`i1YgY|64D6|2$HQI%t zvc<4$i7-=3u;Hkfth@50KCrzjsDG1u&^y~8Q3h;4Rw4t%%;Mmcq;71~O~r658V$Y@ zP~3fwFL_E&M~8V38tXEq%~+i{C7eMJHoc>kx}s9YeQm;Vozi|iOW0KB{2y1Gs6rNK zoJGG5*%A!!tjkIpGL5gExu5K}B%48XM~_w$8=gj(?8j~o+z%tj;qdSJ*Y>^ERrUA< zM8}ubHnz6anJdMIcyNiU*<&4 zD7M^^E^A=g}v>w7+b<2x#{0d}G{+HS-Nf@qG%c8Gi0%dJ-KIVP@N}Bg-FW;A4gz{8o7!Q~6!RWUHs7R|JZ;>sw`3KH2GjVTpGSX};%Y z1RteAqYjBkUuu)v%OKr{Osm5x92Zk2(hc`>koCr4>J)h-XJqI$8ufshEunNS=DDc# z`2HJltdTfWR3xn52PxgpRr0AE-dkp5>AO<&$|Y687npgY#U%Tf(?D1+%eb<}7@Dg4 zX_eDlCdgKYtl02?i$;;@=;;1|7DSTX7~9Y!#++hKq43BT7l9Heb|FUzNZ8rA zEeNm0;u3HHhx=qUi)Eo$%lIM=PHpEMx|Zu({jY2u*!=v?nt2Tbl69EOb>k?Ce;D__ z>88H5iJShvVJ-k$RP-XWiK9|*0jQSLCx=8W8;cEUIXH7k0n)%^S>pxogkC7kB`!*U zOx@mewjQ_y^Juy&B&bYQOa?kRYg!;3yp)x)ij)&TU3W(=Y@>A~by{OM zdTpufbHcH>_#cp%G&VK{Z_LDLrL6ZzCkTaiPSI{+SMTwpw)*$zDn?bODqpn@DUZKt z+*_dMuAWBCqXs{MhTXQ7e79Qdhz5;2d`ALw8Y%pd-j21$NSl(5k!GC!&1Nb(p`IA4 zX@5XvpDSNKFrq()d$tJW8cSD{q=;a>8za@gxMx7q@nrkVbat+NcTm*6SE8)LfoT0a*ctT;2eC`}!4@+(z8O+}TDu zl7Y*sjZxU~{R%_tJq@hT1d31ia_ZXR3!A&Yw1}lW>o}4=*$P35*e$}lt@2vLf_cmp z+@G(QDQUm?62TqXPx(@NMkDYjw(XN|zc|NabTUzKKGvZ+jlWvuJ)QnUnx?mnfRf~V zj+1tFOnR}~N62N}^x&drDJNhjnoZAlAl2rvgVuO_Ep8}nM(vyA2pbF)`{s2{Cr5A! zAHsDJw~4%5837W3WZgwZUOd23=V6Tm*q)hp{;BtilI>g6zAL@#b74pqg@U&q1^8*X z3*%m^ua&^gD>fVM0xpv<&b}HDK=ta9ev@*a<^MW`WeA?=j*Z*tbv5w)ov*ln?80I$ zAs(@$8E!1Eo*NS#m$;p=Ju-J#q2O!zk1>x&z3~hJkEPL%Dehz8X}3=`_x%r_#{@d} zTHphy0cO!I)h@jkrg}Qw4i-R4eP#t_aIE?%o8>4S+M^dGW8aHOGZSLvOV_Eb1dXGD z@kj5#git}9Da>~XVLFxL2_iza(!E)9JbBV(ge99CbmIHLq%NrFE|S`&6TEY-C(A;g z(9vCvJv}`^(UC_{EkGL-@Q_gV(HS%8W+QW{D>63N+d%FDlhR!-(#eLqjtj&dGCii^ z*;1k39s#ti0Zl zS`@(Nw3T^pFz6YBLjO3j;}peAi%Oh;>9=L+pZ3Car{D14>!xZt%p&i9TRA=D}47mYGlZyt8FgX*Q7braPdE=(X*Yls$h3d z$cTu6F}Ew{uFnq>n2g#QnPoBc{Ks*CJ5Jgx;vE&Mvr^dZtrH8jdA>~-Lq6`oyGmd3 z_V!IvpN0*{QHaOcgoxFtp$FoZDkIOL(vMJIIg~!;w%m07G6#IhW=iwNe))#`h;Q!h zM%2uZ$j&h}VfEWEoexs{&t4tU7KO&`g*&&KqP1DIcBBh>t}Co=B8%X zR~RvVX^Cw5?UJF~1ml`=pw?#hQ#DX>bt; zpTWWVWZDnnSRP7aXJJ*D&5>haD{h6w-YE|hex<@gwicCAPVi@OVP-m=j43XCnLOOb z6U4H$zYp;_tv!3{?TkF%2@8B`3oTpP4AWNonRxQ#x<&lWIsUhx-GWdW0f87s@RmV0 zZ+S?_nA+kdMSIdXx=mSnPk(q@x?>U9QzJC803am@hWV!L3Ub8{29S98+#=*Jo5|QO z-VT9F`EOW>^u4~utEdGmG+QD?zlrnwF)vqte8t>WoYqntta7p{tSmS}tMsCqrrX{W zSfZ~#GWFsXBDQ%EeA)n!CpzaVdh|NLFzTN@ey1oc5H&y7Q$L1+t8VEM);ZU3m2tEvp>>_@+8IqX8%3oa$n=~Zs^UD#u!QKt=%L(B@ zX6!|MAJ74o$+Vr{anzEiB#m?cSsdK&+%k&1yCct=qx`x$ zu>tR~A)~Q_EgniC*&cW0H>BH1tYq%o0c4xplzvIkq%6UHwnhwfcIJ1G-(NF-Oiq3Y z7WHdu;~I=?_xb@@T@|{x@H&$Bykz0x@?V3jd@~j|;Vbx~eY?6!^4U^3M;4-73FxcU z*Qryn*$X5n;{mwVLKA9Rwy6Zn9JzAkPKH(KYEbKpX$=9VlVk3>!nJl6CnxmC{&SC3 zVdNzj$|71Lb>jk^n?~!H>9ns!V)WmFqgHnlByxx!JEN>kTp%?{j#IOU__$GN6#pp# zvNAKH0Fe#)J49fK5A-r=`1;eYq=pTeYYDIpM{65UlDZ0Rf4|2H71#3pQ0^Od`tnRf!ez!{ zGrl|uPbl|yN14uGSHL5Liq*=4z`e)9_x`&N^m~w)>2HB6#P)_qO@ZspDcU92TUWuh z$SG2;48>-!;SY(~eqxH7wlSvm_CQVj)`-|XPYI{CJ|>?t`495vFO-9vdqadW?7uy< zmB@|k{zs<}8m}c^Tovl{y@wIIv+VyO`*FH7`?Jtvj`W4}6cR^b?b{^VOJlRK+}JlL zX;{$XDgHTeR_~#~z;f(bmjWnWBM{#-dkZ!D%rGofl-N2eWzi{1=&s+R9)VI+7q%tH_JGq^86k8miwKe zS3rxg@L3RFQV|>rJSo+HCI!g!S?%rmg{@=3(}mV^{Mtn$$Z@FA$z$rA{-ieA%Fu{9 zCnHj;jReiG0l9@~4qRh&${DGJL(wSJGOaloV{(u1c;``-)Rh?Rrp0Aj%@X2AfQ$Uv zkV^aKb-#{CcT05DE>B;TqX3PCrIfZI^w3F!fi=ZEzl92ey-KDz5#K_{N;M@ldGTvY z>%Redwa~v9Qu+5BoEMS4Wb|28Y}e9qR&iE@7`5MlGg_``VBI&8orAkIXL(Excj}yf zhv*l%WyH%h-YvKO4)NW;vH8H(wnVL#Tmm>h{Bd)?l!cQK=)t!n8 zS+fP=_@+cLubTEDte2^-_&E-RM(_`VCziH{=0|SNG$gK&rRTFRPjf3n*$3eLbM-HW zBc~VBevJUN1y8-*?R_Yr&sgsH_H;TIBzj!nwm;ixI_zOXJk zt`Y2<3@CSAkiMi`C+ZCP6(77#YJg%&^rvH|)BqgHZF!fv$7e$5s zk$$bL|8BXJcc}e&Mx1RC9vjXlrfBkf-Sh0#{nf4K+c$g^lu*7;kw1Ta4hgA#d7Y&e z=D3meg}fywL7?EznlD^MtEoWmD6mdSbX}JBCL@C+EB3LJkGfQ<0*kpwCY*;@o?o0Z zRu6kw3Z9k4C8s)*P$SwB;U@p~=MxYjaVjMd5g&m4zZ2$h62_3j3SOKviMk=ND@;WK6sr*d8!TlNFESmm5D2u^_$~0h3`e5_`Exfeb`=X^qPDYh2{^qI?MGlx-fiOlR)%sqRC6!g+bo-Ore4k z1G?d8j+Q<l)vxy}-PKoL%rhj5ObVxapX6zh4m^`G53z7YF}5&8LCI{Mk^8Egi&cVQgSvWBPK|m zfq5P1u^LCxSE?fizy*BY0CF#UrMGA7m%5)%;DUtZ5dpN|G)si!-LcUgCE(jznODxU z4Q?o37)#g1EV^kEO=|{h`~YfPW-VKf=V=)^HVX3jgK{$Y!iEZ2bQn7@Jq99BQ-S5> zb-C+d=kM9eU-FE*&$7&;Oc(cew|eUg>LEivYd76Pe;>@*uet00^_vyixX03PI`8JQ zKQ~raIwYen|C>}HAm6^T+m^y~xrDT(Ts(zuBVFvX>0KGc*!r$V(y=$YS^NnC6V9Kl<(L1^&fT7iy*SuFjVN*0!274AlLH)gV z7@9L+>+bGNfxsn!V(Wf&?H>5TiH-X~K_?BiA;h4TQ4MU8ag+Ys>QZ7_#R@F1KZ(;i z?g{#vFP_|tfQpL|F0P9saAhxyJEG=Nm19$=niP#thvysL4#mnNDbNO6N+b(6Fy7MM{EO7#a4jY zN#@kuMS!UQ6LIC_CcE_M;rdWK?=HBuzPh(al#IaYKj$P-H)Dn(QA0GNvTzH!M$ihO z>V)?hV+(!tubUC^*2BkWN$VS& z#;&nqddM&{Jz3W9jArz=oD)EQ`-+IglSCuYfCKl2&-qb^`VCa<=_#(Z?)(n!tde_y4I`R3$yCn6RXkqUSN8{}j|z zk5Y61W}To@wsFbPeN>4AT`cZQ(oF={;W?kgRjI4XzcJYCLklQIJF>B}>|G3Ps*k#F zQLuD9WX0puo-3ZyJH6!DzRn!5vdZl(vNob~c>T|=3gBJ*qoxLndTqrf0_UDRZ0q5N zmGt=aQ!3hWI>ictF@_eniL#kMl8JEGDmBg+8J6bW)m~N0ECDk;Lj6A+~dRohq) zo?)`HlSV`I4Vz{=h0vb5naADT6*Q70JRiv;k|bPj^=^(V$OL_t;M!elWD91jQcM2k zCmK^;xLfst19h__2`3W>{)e+7#rBbS;a1ec2fX1eUT?*8A!hqU52BqN`Sww&xK2=G zmIKSBtaaeB0EeMe=1cACf}OF#tsOP*1q1O62ctDCi<2u$j3NQh!A-SV>ni-=tRBCs zZ9%-nM2NPOwu9myCeIxC*30Z6$wFzf1mW2M-Z1I05{=YoJ&}Cg}gl(tD zn$YubBSfQ?rn!>Q;~5(nb*tfmn(G^>G!{TSK@_9r<4>Ywv>&V&YZZeYYBjuVH9&4a z?0A?TPU)T1JkHDio!I}45|5ghY@jjyd=L*yz!HdP)XnLwAH{TS` zg-)3at|xXwySoLBeKvaaC<@*&-V3|R#vn7L`$I`i4!IB*Tr+l@*?4dN@R0DTx5GB3 zdI|U9GE{bEd2aW+x%t)j>z{7~^dH(w%F4(;9_KYS5G0M^ zfgngUNIbdDSTdC25tXaPRCQA>Xu`(Eu5>=c{XD16eN(DKO0Vr40@I_JsiKzhgV0#0 z73rOZF!+AG>0ixCGevl8|3mrEX4Vfgp>MRXQYPPc$WLh&;qFDd5v0ytx)l?2{p`s+ zbW#<}C_b9L^wq*bV!(Ucb|0jik{bOGmRr;quv+#1eeCwyE;S;+u`dSL{8PV6ClHMT zIJ1A$QtdoQb&Kvc*y|?}%N(_^UwkUw>}PLB$iN`jg;L`u`|h&_diK!p@cz+})01HV zi3^0VG2<~?u)-t;VP*LdAYM=A-Evc2Gwhx2rU5Ql6boCdfU^s62ZsT_y~WNv-0;ZMbOWmFT(hX=meI@O6e*N^D0wSFcR6)nj4_+)kV2bfRiJo1w7+vep_ z%4G1xkBtHD@nk5d@K@Jj7FJeS1qBF^1xOWmD_fk@1NnIh9DamHFNVJes_qTYS4ZCZ zsBOAf(&h@>is4*fm&#RFKR8D&9e1!~;Ud;>-yZjr&!+8@poT#n$wEmD$_2K$euyxQ zN~Ql`Ra1hM#toH5E!PI|x!M~nCM?CI;!^LP8Z14IgeY1Ljt9?GW=q;F)?t?kfYeAm z)qE_v_9=L33J;riGn#GO-~FR>{l9Lyy_O63-%XGCl9Q;ntr8;5F`ukw67ZLG)|hi5 z<}nS|R4H6=W;2xG>c{;<8m^b<;-kUU9sEzgP#MeZ>3YszN1xZ9hJNZ$6uo{ji#pHP za{Pe8R)W-&0;%8t=+Kxhp|;y!KE1<^id!Y4NcFOXpN)=Ny(!LxTHlz`zk&Yzc>oWP z??M#njruv7ns4DAwIjrHaGade;Z$Dfc4+$x+bO82{al0SsVGB1vSMG79t5PMr3*`m zDZdO;KnX06h=X!{)~jtaiNw<(vf6A!4iR$c}osL$^#UmcPflll?r&v_hR z`)BP@4E+KyS&A|<3DM>e#et7IpPQD!;g~=;lC7SMO%p8|r&H1$!Ta1RuL4`Dh&OPjN*Z@;CML=>G+))-l!wie|E&HdYbe562EHEV z@51cv?)TP<(`*Mm*Omk0c7)Fr;0!p!Vpy?wJdZDKA2v_m^UU6CCBu-qaOT+kZF`=Y19>6VlY={^uL` zB*MslBvYXjd;Ab7MlgLmTWh(TB*?l+8hU88WmoH0p?k=*0V}%g0NU4AT_?USZ%K>Z z^jF0gICoWEsiDRJUsIrjlpUx8_ph!&cddmAskhAH8~PH=Wx&K@=}!ya+5J@j8-H<0 z3G$l|4QRQ;mYIl%&*GvSQhuy;TQ7CM|Kb8HHf3~mwJWIMB7TS)4a;q`NakWLq;H_? zuh&nbXJR53Z2ti)SP6sK(5=gL4%TvBpPPw0f~C$dfG42Om*&LRK-Vw5@USF`v3DpK z8)|(BeoZdPVLNN)ud~?26TL-Vef2rE^rphMe)8wQA?p4iSj3T48M1;;@S>roPyH+~ z<^5}3X&SJ)OlHXoJYGuuXUPGT{uqFDnJBIOP*vF$)h0l#onr?4O(6u{_hIU#ew!KS z7Zk|>3%-Vy`Txp!3K#rqg6hnsl~h!WAB~KcGHL+MBtUYnpGyQu zd9T}>ELJs8a@9kj%odYdVb=??#pe|O`wvjCFsjBAY-`^(jzQx6QuVw6_GW~)#*?Kc zLB&{Vf3WAR3PR|~8u{a6?5)1iq%;HK(^KEg_}9#+ z$w_n{UxD7ap`NT*>wW*Va;60YR1=3`zPa0vdwpQUfU@*aX& zdWQz?(#yvgr1(t_l&MSRTb}{u)MVJ(%Ys$-*$REm$)=gXxi8{XM$e^jL}EJn>{9%l z27?1uUk&26ws$V8J=)S>hPhf7Qk*`{{|Uw94hHK5#2gQfkL!-zwY7gsT;hFD2PWNs zZw#=umtC(yz3{={1y-bQq^Sz=KpSy+IxZbYVVT*jAAl4K6vU{C;ki>{4rcxQ=e3Y} zmN1Sy=M#{i55sG3I^ix)J0N~KZ2SKs;e8d9*Z-1ys=hYZ<@%iZO|4F`ZA+ZQ{mMF} z&6@x!c+J#QBDcLHFVN}yjZ)B`c=4RbRo9aqt+h7UJ79`?pI&gg(=MaO?etTs?=5>9 zESy?%Nx;9t{I#_0(?figRronj5sw2^xgce4Q<{Z zN2x4@)%vgdJ^NnfYhWI)T_+w9RAM)2)Y^RsZMm#C>`4XlA8+70k^OsubGXj=hGO|7 zA0I_lhw8I6JvF3mymfUtt3mvFR>yguW9|0eg3Im#@VEMdllmF`c(_DcOrX}QFqMl8 zyO*#E8%U(=M}xUJ+x1H{K6&ZWH}^Am4u{awO)GWA4#ZFQZu@QH_H$6u_4pG46x{Od zn@5sudOYsU>DQYT&w>IjOLOj5f4=-A!V6tHCxz`7a4Oh@6A5Dd`^1h!>01}~HZnqm zyc!R6@PDanF}k;=$?mzo3!)RDjf9IVNHQ5d;PR*yYq+k6f0t+Kv2b_SuwJdk*Vo^l zGlY`;Ho`HLk33d8u1<9JyNdVVz zc^~Zo;q7MyISCJ|r%NL?xD#l*2z#fjtrH0gfZ+`ucsTp6>Y8 z76l0O`+efLN!&&7>}2KzzQhfe$}HJjfk}8#Oo&Q;;8w1Qw-%Ni8u}ByT8RLNqQH6{ ze*1y3?GBSd($LUQIEhWr#QVa%)~gwJfYcuQ9G;GfifR`(|0v;yj6XCDhje>boqwRe zy$)y~J%MriTHeFKY4zcAI77AT#og}epsefictSdKJVbwrjUR>vfEzd-iD_Gp>g@r9 z_0PXbUc8a)V440qzO8BW?G3*UpD(@_zec(nbB3PHK?QnN_4UOy=OFh-Go)Ka!zp*i z&8c?})DWXf(#Xn^2@!+JfG1+xEoel+^EoFX#3Rs*(UJ9L<7IoY#LnzK)OTx#4!M5_ z&2cS5-$5v^r%HdNFCOX@h`M%1Ifo-M-VFuMaQ5AGouZvj2O3hfJaS>zcFLq_l|#>) znbu^N>YBM7=IGLtTU&e#eq`^R8l@)v`xyIA?W=&Q#DcX9e=PzkiUG(Xzj|!*m}w`o zW->#<-@^ViCck$$($>)!?w~?SLW_941Q1J{o}+RxMXEpn;{IEo?A-C*?Dlpv=u-N0 zfD1V$Z0jM6M?B-g&8;}=C%tJNG{D~&s?>p?@`}BqN^`%gIX{pnl6w7#DrQ+p$dpv^&V9TN^Yy5%Q{G^~1>1^tuii(~>o%%k`_u=l& z@KxaN;muVuS65dJx6}+0nc@#WzII@cw95oQMg5in-y?M$yIol-r!aV++9gwH{B+wL z-G6K10aOmNyO;M}o77zaV*~7!X5%#g%!LkJ0xiRCZf{4U8E3e}x6t?s;|*t*TlD8c z7tnRp{#@cq!N0Ak~7!HhM*}jyhzAT#ih^~64Q2z55QYswtuEy}W^f$*)bx7f6 zfoO6Zb(es7?Nvh97UcmmL#(8?M^MDXL988Kz|Ws>fN+5^G4$a9QA8`LPng>$^O-qD za!Ko7W&wRM;RIDRxG&)ejCPIcZ&O3sl9uAvhTEfD+x4FfF_r|u^j5P1!_vx7<#aRy zqlHJoVWe@Uo<4V-$8wK0*plnnLP_G^%C07>irfdh3P(4@A^nBUU)1GWy!!5hsFy!_ zPyf=BKElzzoU!H1#YI^WZrsr$os}=k*fLC@hZ1N!S-H4qrUjD9E92>g*rTLMq$W(zB--lA75yT0B4M9JbNZN8Kcc%w%;@~m zdMl7kNy0 zmang$?_&8~pD}9t?2_e(svjfTIvUK@gK z-PHAQuM9vHnKHJYEorl=M}+NeUkTAh!V5l;>9^b>>m8=|S)zVf=I>?S#C+qqe-zkT z7b*;r#px*%qg!u!@d%o2Zts;nw9TogjlT7M=7sf-UN=mVeE%0{Sh1`Q%`0IMRBh(w z_1j_TI#e&7^^qcUWs=H5(;R71TU%^F83yK8%aIWgdoc+P^(a0?6jlV3H(`;HsIftq z$9~Uydv6)lv!d`S*K14j0>2cB`K7lYididDO-(vdFl>pDAc@zSg^8ZJX8xidW^D`yiY_St>nLg}2DIz~y_TxD+)sfb9Mm zx#Jtn0tli2bi!m8x8%LJ171ujLw3;{scVA3Dh4L2S%&TDA}r(pPR-YG+Ig>KWa5++ z6n=D{dn~WX=E?5+A-rE_2jrbhUW(uRTX`@+{+#RxOcMc|jU?N8AgvHc+N=Bmg@hse zATJEUN%=umvQDYo%YXs)FB}|!!`qlUEvk~$U24UJb%CbH#y&5A5K!k!$gH4ATSl?J*2n#^rq3 z)$VU`jgV5+|O8QE`nFk_itVP@)P8GX(LY_u5EU^dNx{^VMWe*4kWwB`|A24 zP{WmOtEg(ZUER_8F?6R$fo7H(AG3~^LE%$3TQA!whXP|yc&9tD?6Wk2)<8XBXqe5I zJz%p>Fk+PXtIdv z^{@&bMaQ;>eIjU-mW#u1k6@K_of2`3GXW{C?uCo1&Uh6U@BEG}`I^?M5b2UXC`Fu3 zg68`=#mZ9S^tw7CYD?|a2zhSAD13r@Yw4R0v(tarlqGF_EVH#4j5|RY%ee3FWuJOO zhxd=uGg{eyN1d4hYJB`8&()k6ZlT;e4nCc+tE)G^emw!^xJk+da$mUcF<0Y+wfXMH zw`1PEAqtBq?_M|WHRWBwbauQDhdrYb5Ndx^cZ@~gOxEzs3W|AMNZw*W>t^!nY<6v} zKVLSrdtWtE*Q(g*4}B}$3WeZ=7@CRplv{sQbaoC6=2yPPZ_^3CGHr)aaUCNa-+$!q zuTsb_v{|er2<^@GNcm2+M?0JwyF=YH0uPSVHnAEr$B*8jUc{#}8OPIeI|*A7Ds5Fj z-IsmV9?t_xxR{hFO#m;Y{q^gY@KJzA!M%`WOyWnSO}W9u3gd_s84r@K@5cx$JB3ujBW zHn#F|OnasVz)ARX^in6Sth8=BH7l2TgJm=HL>FdmY zyHXjHA?TA%O6-HG-_Y`A@f$vv(YO~Ajr+~M?}Lwzr+MJ$s|2NT*k6~E=cC>GiP^`y z0Uk80RXlfox6g!|)79Rs0j<6s!G0iZP2KfOH$4IbZVv1GUDN-r8OudMS@s|xsj1rw zrtyPB2mOf{lQ5*b1ALvn@bHk0q%uy}^Q0FqN2=}Hh)a|dWm=OLi8-q0=f?ai(2fum zCPP>kn5R7jRj90jFOdJTYF88IH+fX8_lq!SY0uc1r3C-^d+m0{!Deq@9`s(1>DnK2 zHO-%8itj6q!tQl7CR4@OrTwS5aDM2Q)s?_t>+dP$Tlu+l*Z6W~IKaDz`gvkh$mUoH z7evQuEC@V`{&~>N{;Uc+zvboEu;+=~Q}Sx~k~Mv4TU*kYs|0^q+X4udaEx~LrIDr% zf&=3$jpR4C(Ai?O;VU|BUFlr5IP-ng%}t}O=>pNit74h)@U76_3!efxIBb)_ol5Qu z_{sCpwkYWzDah*!Y2z%!sQQCRXido?zgt*navk$CF`&2?quD=C?Gr!a+W1<`ZoT|MC?okgpIegKa+(SwHVGRo6u57Ou-zI_S~udA|Jkc%2yS=-XL^%Xqc zjMA@9arHjbvn}GV;r#C@bdC~?)>p0(HE#qhaFpz4s%gs=Owmp!<@wRx^^(AEuQBI5l(@u&me>Ls#j#ajDIPguo=)Ua)q$M40$8MqYW ztU+E3oSdfxRSwePyR4SfH$*pXT+4sHKK(&IY|&GL-}cYtMEbmMBT(65MZF7OF}Bo~ z)grdO2GtU&y5U$#zAX#mg~d|JPvQyfE!M>f!k{N6Mksui4Q86BeF zvV-*Msxb*PiBBbUSyEw#egbbOB`NfNP~`m}NGm*hm~ZGo{M)xGEs?oG(FL^l%{((d z912dvg)jY5F-3}Yjo*5hRU$ga(j(!|188z44ByRIFBO-f^$>PzY-CPp{s5laVzqyj ziG~IrN#xa`{!5C@QayogXmGj2)v7P0bL7fEkzgBX;>31RQV+0YL`hlM$ccc8%8VG0 zcpC#Oos{KUU=qaMxF(Sutow?Rl9KP~YR#$WGcjhJj6{Hj4L55m`oesJSgib);sD2Y zbsvApOk7SK>{BET+8GABeU_t&XP%~O1x*-*umw)^b*$U}Sz01LB2>8`47NPx)GCG7 ze1~I_k&`83fx+B69>gqjO;&G?Odg$Ev$nSoW9vRg#^Fj_@bgz3ocmXFe58k;u^opU z!zVT^CmPt-0%>CoC@4I;wHqVY?(bg1q4B!tps2vdc6=Th_U-gTXf5VX_!yU{-&3UQ z{_ewv-Y4!vdWt4l+1B8!EE}`8wqjz$3>s%v0e|zyc%p8tqXkz;ZQ7Zu`Hd(n^}b49 zJH!&hPe5+tKzT|8BK&hd3qg=LqrWbmdq+p;E*bHIJX-ncCKoA+qjT3<=vME@`#bj3 zf`J0=L|C)hD07BKCDzGm+KM=cFYp3iMRnB7(b2EI9;<8SEjSWO!F61bepGJDJ#gyL zxrHAiES@-=q+3+d^t?|2JI?5B5h;CgZX=~OX%K%P;A{j~dXng!p2tB_T~AlbBxOBs zPuPiZW547x8Dtypj-{Jcrw0G`k-R}KAmi!%=%@2Mf2Z~w7oB?VC@ra)+ol|Alf`0%7^3wbW4Py*9Cvnir{?CqnVI!-vm;v87RF-;O-uPRKnC!m zR}+HH&mC5lSo0@SSW|bnfgnny{M2UMOUrHBPt-6%ZezaiQ1E5 zmh1)+5tF!7)}ED$H}3nI>k=~&WNnplz&BI@*+P@BsQM6=v1<(6JQa1O{Crbny;Fzv zF`R33K9+c5F^E~-JDfweS#8HqwVbysaY{$QMDQm3WK^8R>_Bh<9aPEcgixG&M1azV zvT{8c#c0Bc+Xj2UuOrK=IVE?gUe(7I*E=KDhLof?D7Xk3|fA9lfK~WsV>p#10gDQIfk61*KWuJM1aj~nhhKcS_fo!~N&t~^) zdR?J&s+wYKnDG|-r{Q1X!9+eUbg$vQO`oc&s(!EAalEr941F?M{>$6PbF&V2^z{`! zg2xZ6j*@@qLYNyL?Mzhh2mtS5wYK8HHU7Z60}QGjl{{oxqoxpUPS-k~pX_)=?0-dV z)f*44(b9Pk|L#Wqu_ib+KTp%$orUHzZ|y@AF~?q{n9EN+tA$?Fr!in5ZJDQ5)Jly% z0_MhHj>cuvi$@47HW9DhH3He(0 zh`?%b%}J~*o3gNrCz95ibd_Du5^!f*Nv=F2ux*IQ`@iCbi54@*$Y_J9n&dG~gOcg8XU?-t9g}IY)%dc@#LDuh z*e$1jsZg|AW7H|>hI&xl2Q%~!Y$^cV)Zid804L9Smv7hS1s9g-4h_b_udAiiJu^QK z;z@acu`DS*eu}G`1vV{tB5XLL--ToV9wy4Y$r?N=L{p zm_f1SXSnxTQYGGswV^+wfmB^(D$8$T0_>K${#eaPB~m;6u1BHW`CVWPjPt?g%VaTLQE0Qm#Z;rsGEnJfHm^T`5pc2lYBkE5;34(}(7 zX(kjzJfu}^rEoBIxH0PLq%~WcGS*gDch#1KyG%4Sy8F7>O~)FGasFs) zBaxCGPEJbdIE7@+D0aApCORO)m0z{>kY&E5K}7lCnEA2r*25jyEhj&4A3#K~I&B!c zJJ|ky%3b2tY<3~n)jbv-xlZ<5vKSgJuy1@GXmJO*@rjL$r~p+;_ke^`r)==Dr5ftG ztgRJRS$Hn4s5WZwj$FB7Pd%9Bf;rtf+@nCvV#S4>IF1zeHJAM-3WoukOi`|Ua>e>U z)e;l)Ev*5S+~GhqRmVpylkf{M^)JsYiVF!c<7iU3li5m|IW+xF6#Mn>XOs`3t%?f^ z)BX>pzB;I?K>HdCQA9eVyD#0{ap`WPySq`OySuxQOG$TJx;v!1yT9Xmzc=&!BQwfn z2G2e_)?Rz9%eo25{_GO-@9O^O_LX&3?kP55V!W2hVd|`*gpE{|@e`i7#^(IGOS1!- zBI%afJVTF>UY<+?RRnd~@E&z~GD*N=08YQVFRHv`$tOL3d(butU*ch&I~=v0XK37b zJ_KfR_r)#`4lMz@as|4U-wCJeU=Z_Q{tKTCx3@g}{_Fw6#xdKPnicR+Q zYh{0d0XUvCZ49sTPknd{mh%Z^+%N~04z^dX`~SEAhQ!lm-%9H`2t85>{C66GIu;if z*VR@(OR`QrRTmAS;t8=BW@(j*!mcBq&_v4V6Dd~6n|;jN+oa5rnx3hE$u8LbZRdQD zpq&8KjJAwNw*EqNpU+M*SB?QvpCU^)B?b>L|jmzL{h2cSh8r;>jAmI;E$@d_=>-gvz3$kAy5ht~@hGyHJdiP>w zq(?u+%jq_|9D_BqEiEiI00+vMY$nvWBQdFkgS=4MS>c&4^M3#7Sh0tMZA{@1lf%CGKx8E<#I+&loxGHomQ;v9t8R3QcN}<>a$# zc;Jvvn_Xe~$E}vzFQ$=qkIN(Ip7#H6uZcP%W@Y78Z)PJ+*}vyOrSG+Ve)y_d?iSkB z)#`ZD58U;&dO9lkl&9kkj3u#Hn|?mv|87a-YCOdGA-z%oVM5OO3cr5>$w5_{3JG; zOq()I`C6Gs5YDocoVxdusyT&{aVeR4-u3Z#*wVJBwlXrLDAP{>hV+xlLhjT?|&@i(WxXOk$*Bd99BFDaWgznz_j*Jf6A)TJBMJj%8 z@sp(HSO#%sIy$NFYR7IEMyckz#!v0OK8NnjVsXzZ_1L9{YrNsCR}TC!d_pI>l^N#; zZA}}ZM*UwAnBTvo+qYK_483dCc}s{yDZgJ89ErVITsKVOvBby08@W`k6Een5>feDJ zqI+z~tbyp!Ffa4b*t66P6Q5+8j`uaw$a4CZ8|Ja74L#gJJ@FKEr}PzDgk4i#7=7D& z$=Kxdbmao?D$M~0%`Z#(prZ$6WH)!5cSdZ7{3Qo@AXEZ}3dLibkH<>693b z`1bLBHd_0%TibB0b1^=prN8`SGpQut6s>>LZ^n9Xt{n$%md&$}4sfziK0y#8oBOv{ zHG^u9H1l2zkZ5~f&zL{k0G0Xbc)l~%vQpn*jxN9BODri-04{qpsUM2O`xp~a@|)BC z8gtZ-_#VM+X|{#5s??*yG_|@ucoeNQwj!F=>S3jnW-Y0`uD-F8AE*)A$v!?#!c$_u z6%TPyqRF`PJ!(ICHB5#t@jh^+)wGg&lKM&Fi?!H+I3q#NgFNL4n@o5$5<<75L#}oG&E( z>*hhfe)UH}Ru7F?P>I^_a}bNd%Qy=wo4t>P@X3xy{Jx+6hYS#uSD?YTzz&a>6*1SssS@LraKYV56^W6}omljs zeIm+qx|MLpt<@YG4BN{+jzPlym{b-W67q>uvg`B~=LMSvd(eJbC{bScWU@(&RYExr zu0(}6+%VT(ewGsQH@QR}L+S>#M6ANxnpe!+{M*b-Shvt`U}0hr6^=_^5t$~vSbeBs zNIp4HE4<+x3*L&mvl44 z#&y>T2y?#Q7~kfkoghp=^=T)D`;QFZRMc>}qwS zvmC)UpA;%2O>no^H$};nVuqzb@CurmfuxcE%^QIA9b}{48P((0Mu$z4D@0WH368Z( z#yd5LV3u4{^7Z|79@YM#8j1Z`QsNWYs+Uea;nztZG<;33spz{t0<0d zauWGLAn~p-pnA)-pfyNz9@ovqu8~+;s5)L4@%g-pOlK(+Hi|N_sswcBWE{al;cdkR zd5EF7=Y2$4vCwG_n_5jou~1DYv6Q^C^N>9kJP^gHQZoC~#ipMN9e9DQGesSKJh5MK ze*}{XO#%ysJMPs(T6m%>aR}>I;vw$rHvf`tN)ZSpNtW>U?StYLfSel44vQl8|= zJF2B3kC!o1yCdJ|%$+w@yE?s-r`{Q%r4;V1FJC<<-h8!tx-iDAdV;~^d1MXca&g#L zJ1ux@?3R|{9MHNq+40_xQnt;gQhZd7tHGCiD`i$E@e`)%<<{45Xl(as$%gq41AwKr zQh`8*UOYa7qNTSV9gRN>JdL1&0(k1=3&%tYr3Zp93Uf1qlV^?Ji-mUs3@tk$X`|Hd zK0bT^WVKfhqgkLVD%B``%LpNZ(lf2dyzc~|kW8*9;ssg7;E*UmV+G}6#4(Vjmnn)0 zF-Ro8;(iU;Hgx#dYHmTJ zXs&n@P7lVah*TL9*iDM80&Haektq&3Ep0EQoJSi+Wr-0nesA+{J=T>e$Hsm-M>-)V zR?$NpLk|`<_ymscDRqk5nv0tlvofTP)OZmKm{2$hqP0`rsZeI!knRSjB32`3ZiKOa&^T>DAr&R#@7%uG8a> zwDSj}Bx|tYC+qVvuH*JhS$@{+3OeroC*M#0o{jvPe|hpAOtS6Kxe)Gatzuw8BD|eR zI{zrhHQ6&T@Fh`ASD#6b#P(SXmklfOp#z24_wgI=Qf1zg%%&4xUD6Hx>yOE>7lg4p zCEV6at*dKwXzO2x&nEcYk7=8v_yK0pj8~U<>Qzf(C9nD(slMVvuB%|E?~MG#&mpYG zd%8YTu>JSvub(k(NNtZaBE8RKxfTg+k6ox~WXE6U`p;Kg{5v9F3tU=BDyXGL5uRFG zTh4mv6{~%`)vc5Yn>YuD5Gu!kzRh;oh8?(2`L-fX8}f0q!ihYn8=2Mn!)S%QM1zWT zJ#Y_*O4MrYqp<7n6uKaerqQwhP=QS6y4cZ=Aoid+H2tz6OV@&)< zbaHJ?Tw}o=ES2PVFfB>wlbWV5U^%%@n_W|5I2z!Aw5biYT?b{jR1C6GO*)3hDjPGA z+<@;5N_C+|P$X;I+C=EIz_E+lg(V=c0-l-u1(&NzOdPkj)jDAYm60r!bh3z%H9!wu z>tmaFULF9#H6LqRcVX5==$cmoKAsi2uW2z|5}(SH@K-d$maN)hy2;qQiS+=~O2++l zfv{E3#8R<>r9s((MbjZXux0INwH3Z$2_cw!4Ir|RTiDM+ZOl>OLTsP|Hp4IJq-1G7 z*hF7VvF{#DVZsm|`=T6H=T=24KbT~$3c4dD_9yC{snEGPkkE@#C}uDKTkH0P=@&(TNYkp#9RS@!ltI_q^|oxo(g2_nqfrcF&Vb{*ig8P*aBU>w5BB9?~^MLO;7f)M3UW8@ahLov&)$k8Y0wRX5ycqtb@XpEawp>ZBdxm&sM^uh=gejWhO zTT6!+wGmS8m|ZP$U58XkNfnEFW`y^lqkll8ioF=CxRG9Te>(bF+#Buti8AtAyzvnq zv9aBz$^jlf8mfiBLHhISeTPF;(%jEEON+g5s@90n7fYh)!Rg+uEi`xc#`P?TdX?|F zXbtz51QZmzpPHJcZ9mP<-D1bZsVJ+eGVv^}pI7 zXQlQJ4-p!&P(QV9bxLnlS|Pa-Hf}EM8S%TfZC?%os91L&Q{r+0!X;=f4lFgQZbs!w zwX3yN9X~c!)pW4(1@X~;iRL;nd#hj4m^VFQGA+^E20FXvfR4?VILIrsN<%UiFv0qN zrJJHz2N(&c8W^2H8ePM`5kJAlqWx9Z(2y{JhZTM$Ci-A1${|TiDJg*gKRM4)NhTHR z_8!Omut6#Q7W>^8f$76FCe}%MZvNn)v>Kw|r+gBAgV#WUk^790dRfvT&E+&zefJA= zu^Ya?=NZOyHJ{I8n`<2nw~Vw^vO*`CJeXXBg-0fx^-ka1**ey{5)FTrnENrmG4Xi( zB%xPQ(w*{AeVOBsx|%0J$RH!vL|g}?D&WxgTl2?0RW8lX&a*X}65T*%OhSTwNPzkt z;6y7UKvHUvU&b>LwztwFFJfP#r6fGk zq#Q4OuyGnh5-wt8>@6*)Tx9N^@!}I^6g8+ut5MypaCsNI0069O=&uDXH#mMQCwo+v zYL2W4m?SdEH+;-RG<8ciqb)QukwpfLplv=Z#1&u>cLoQU0V-PHbXHt=D4v~lPNcq| zr59Yrj#_aV*=E?$1*GEfxpTRUleifSKNQFXrZ2 zLlka9ke=^p`5t)&#>y6HL-vz1l4VXBG>3?qzMUsT{P%j(%VBvFxy0-4>Zm1R`ykZU z^T);7nxL-n2UYm@hcD@)LXyy1LvT6Aai-?0t)@4hZc-Mu~#KH~-aVQ)i~dvx8u zn|e2V_5OEyLrCuAdsTI1%VDsryZPR^XH)VQ0h>{@IGuL@O8p`1+6hDJDYSfRIPG~! zu6`p6*7M~3i{Y_^I<%y`!vvT&KB;>g*R`D2WZB>41aUl#3!9Xtg+MtYr}o2B>)$#W zM;K|rW>_aHss*cCZfJYO&{u_QY#4-wh1oa42Jo`gO3NtK$dpkYt8OCO(uzu5F;gGY zXiUf@{`xnmNLR7u6vh{ksi<6*l%~=On(^mEXWFv44#-v{~FdUv0*3Bm%bm92Vb{x!Ds@E2$b_z0%(O;uvGfC2;R$p7N#I~x_6=nT+ z*-aW$Cd}(sY$PY1Dh)ULmP&0=*g_RR4n!9loV=Zf96fy%l1uxvCv9B9a_-Eh1u9Ol zZpw2;P3(*d7ZUkU9?0?xpt}9USXqBnIFmXM_{`)$J2XUd<`!yh&Pgj>;eh8+L|VAm zrox$c!TH;(8Hg*%dWYEooBdE5m^${g;ng7g-1W(!WcM~iDkL7zA4x%>pEiP|Ca-ns z10^NvXD`oIfW+(;!GNMPwBM#+uiEx6_Z=a{>&u(b<~t8+%$J17Jl~z^?ho-5b|`yX zeFOYoH=Yh;d4@V61|*`H1k64gST9c%%5#_s^Yx!!uHK@~4`{W&DMFZJoVH3^lhnB1 zbRzH!Cdq10Qm~I6?GKX3FD(%q)v78oSpUAya}HCrHZEho{RuV`P>fKdUTa>k(zl33 z3Y!@W^nF&#bQ|-8;W+(8z@oGQtVI-z7zK~n;updvs9cDNQacRMs^8;tW`M6)_*s>v z44_#ls|^ars!F1qi5~S7G9NfarRXPRAVY~P?aCsM0bV6UBJ~lBbPE)BFBaD0yh@wK z@iC$l(jpldP^5>af&$Tp4|KR+P4DXW_w@q<#ZuD!pPuZ29Xl0oA}xlo!_(1)+x*OU z$5LS6{N6PrIQnd7r}jz}q5R5&Qvk?IPG3;Ky-9FnO$$H0a>=%DZ*LXk&-lFBeAmZw z?j74G8mRDa9uba@`ziyvgO&hhOpgt{i5CxPOTgl&7zL7D@x>n~*v8I7CzQ^-fTU#~ zAiP4(3UR|aI|Ttcx@wt9F?NDkN@n4Xs5!D`6*=*&dME&2M-?DrUd8F4S_~R##+VOk zH3=z|2Jv>FevWYt-)Yu>(^{m`yAyN5mIeMY|B%X8;=@{cp3y4|yS) z9&@q7Ky-1c0sE}@Q!#iCThm(t#F>ku zD%56QvECeYn|-CHLrHF3*O?FXee5r-f>>aWcjXukNi&Qd7o-Ud%R&oW?06yX`f&CQU5$reBrrK;+kzw8$1p(_sj>a zcuHq>HT*v6JT-j1_1yP)p?6~E9^ifbjN!W>MZ20knpQ<_%Ab(NR=rV}w&!ue$viXC zvxQqwTN^%8Hm6suzSH9V#X#rj=ayzgVHnjzh8XF@m>DuTkfUTZIMPB|<_iNl@{HeR zXaeg+MlPgN zTFH?pGvf|amC-zODQU{!)@JACy3fw`U5;G1e+2mXRn{KFi%JhzRXopZt}mow)4{TN zv<|=H@z+eJE@-%H)zvKw6}~g|o%+1R#AedJ$q8zvT8ckWb0a&PbB#{(4Dam3Oi8)t zwB~BDMnP=$eh=q8U)J25HaH0G=>Gc`DJ~Af!J)$>jJ~Y^OuiA?f+5Q96N|nYKStz1 zAx_f^IFq_jjWw?i?Ndqg*;fe}wuC>A4%Y+D=L$rPtWsEN35EoY7mrl@ga{ zzIgL2>>ukn@z|abIOTufjDc-N0lVAm1=m+srPty zp-7Et9Jm0+@KKKcnf+ZEI2^-LDa>1`hcim#WvgoWL9}hetP>Qg9OYOip(2lTPn;jl zvkPte#0T(9o}S1AB7#0y{|M|?aT>NIJ;kWJ`VPZs`%LPINXH4qQYIPa zfvf5`Jox*!1-h6PQ=<0|#OPO6?511k6u)>ddV6~TfE~Erh0`dKZgR|o(|D_rCt8Fb z!e@b0HabvWA@+)J;TVnl=nC-^tsiq|+H158<;w)}Qn`kb+<*Bb^ZCRs(2OQ>%K1Cc)-F>prChEwyILwvt+sl~1oe`JPhv7K0%|cu zRL!E0)0?Gz_cOsnRW(D`=IX6&q7T2`_w^-z!!N9B%^1|O(ceV$HFGKfAkr^`6je#z zeNs9*w^rkm{^`6NFV?MTFuoW$1m98#!JT5NuH+-MTn1TlHk7ziMAtvC(a^r~C@s5nIsx=(;_WT` zry!j&SB&LKGc84eW@1YaSyGjn8U*S#X(l!Av^LqfvKAFhf!bt`v^Bb!1v~4~AO3I$ zNWJC$`3N>d%2CC(kLxoT=?KuD&-pjrWU_?x^M(!zoKChgwZrp1=!2C zXV|lSvhCCZ43(;rp~hl)MNjdRy&(Kt?OGWT>c_&EjXcWTG$c>j@HT-=T8r6|?Is4r zNifF!X;K!mNGy=CTG^)1n<4vH4vnAV7UQnsm*ayu5-0kEdbsj(TrxDv!>rJ=x3+XA zEZ7XJ3m=jfSavU1Bb8s+TF3IHVlJf@Mnn+*{SiXd+?#ECs;f!h_T!`|%jD|L9!6U# zQQrN$cY4*!aj-%P*q1YPdtERAY#;^W1}DWPh~V_k>BDd~49!~Ia4%`(f{20Yfw8gv z(_6!s?^ z3{(96rs|j0=<8b^Cs6de+P6_}Zr|mgH9#Oi-F|7Y%2OA$CSG2Q-QC-!%evY}MC|NQ zCnqOo)|{LpHmBI}Ysg%o zLaY`kF|II_T;-dNDN}Kyt3@4Md_SkzS`(Mf0f74LrURnHT_+hHHuPo+MgT z4^}qinQn5cx^6q!u z)R1hc9teaV%|6M@FG!9?@GMds_uD%(u&`iMQZim&lO+8EEsi+=cqyPh$B}U)tFwzs zF+JqJus5$*eCTW%t*XXl2OgE6#Hxxu8B!}A{k>y z)L=hSZ>WP%3oaS#J4f?Aop$7zGT%=_xTMP(Dxi)$cy2IW6jGETwnVLyCDR~|6yxpa_rz=1O2C&!}y-!(Q<|{4j8%0X#NOqJ% z&W{*SE;QT4BA!n9k}_M;|B@mjDO#pB$IQto3Gh>X?@D_VmK#CnAnSh2q-sTQZ=)zT zQ_N^ZN|=!WG*At!!WM4o?fniI=H8eALyJ+x;B8i|58t5CDugVBRwG5)hnI_w&t|}q zGA6&l%~Px%_t0Xd%B(V3qEv>~pbq$40n!yBxN_T#eVM#tearl!Id#|SVvnXg#8Gk5 zu?w17QR|oY{$8ufC}pz77ol*EMcSqSW$0|qBep!5aE`1&0M&h!sFmwFo}fmb2UyE* zIB|W$#_lnYe11}--`XWM4&$rqSE6z$X!adsHPR&VAT&|DG+$0C?f}w*8ei z=qn!Arc3k6C<6O(M^^xR-cw>o2y{U}NePuNi@snDxDhP>-maS$3UIMG!ZCAt-SZ&g8M}8~s_p}%I|18RJrAyq9)G~%5|h(m z>yJ+W`A=P9jY7q_1@e|}twF%Hsi@wi1Zne|Ev?ZvA%Ct-qA1|~6z((U)P!<_8$}|x z>V!0Qfs3&>ztw5K!TVa|l`GMIBhILc8JQGg@}%5*e2FaHEJ0I^r<%;2`4)n)SrRZ$ zcF-b@QX$)F^q|aO!J}j?lM-=BC*^-}T+JZ#L%K+|HF)+yr-v({=f4k^7YaPwzn#CV z*4i@k7$g|5L}E!{0s{l@x(Qx7npdwY&&I&9{xcTF>sk)HbzE;Pg!G0kUz82 z)AZy>?zh4t3^?pfWH7XTQYwz3pEYN7e++4l&M>hC2y3{US8Vl28AG4 z)ofc_Qc^?y*q3IOhGu5bKr+s`mFL`+IzCtSv<^-c!;t*Xru#8GY+Y>VTlE2p5N?Dv zPRPwT02SFE)-Dw+_)2PcNuf)|y6vQxy4@_8cAxH39+sDBWnQ^yR;VV@f0vb&{aU74 zvD1^E#IME=EA<938gaOzG+m|Exk3LqEg@m7oOCQRsCiz--JP?l^#;4UyW4cRq2Cb` zSV9lcHHSAfadB}6QBgtPWdrpB_~nF0&HMT>4Qr5G=C~PP}fKG5Og?12rqePcumbsA@hi*9uxLR;P zkIl-G^Jx>FR}IgWTTJpI;*P6}K`1eb<_M7YXREhsl5JR$0WQV5R}B>^Bg`IU*#^0Q zLe{@HPJf|KdXERpzg7-OZGe`2?BE%y4NFCoP44+1pZBgM#pAdC2)6l8z;) zI%vbp%nU>-!2Xm1OibZzA;UL&c~PV8HBN4B$?$Z4ez>-5;yuiHbPX+?9%i>1z2WAo zONQU@+L#rACyji4hEd~X1a~$i@Hkck-Ee-#jI(qKA*TY;!KTk^gp#mw0*5{K$O0=P za(8;szaAfd)i>ajK$)GMebrFgt4qIP&DwyX=2^ESB&zv$QPsPRHLc zBOj}V21jyoz5z=eOQ76&q1do*ZEHY>ex-a%PW6jH4mr2q4_~X(tf)~G;N#@v1coF4 zy_uSt0@4!$C+9bxsy>72-zFp27M7NrZfAtzQTU>cdJRo@DYr4nKlk`DJ0^M zE^s&!bZZw~0+d0m6C*7r3lBRKXW?C7QZ}i4$O1tyr6o2-cb5tE8K$8Ro||JYb_u6I zNnt8cnhv``;$@Xf38WjuFD++YFw_MpT2G|NK=Q(Alk*`_*fH{Ci`Dtd;%TWj`$@uvRil#zFOu8-VCKnbYU0wY$C*BZzf1b5`Iv7U02>jjn2e_8Lvuh+P&;+@= zr#BQwPj+d4R(zacjv;sZ+h27y!bWp?*8$tsIvAYK6~brB&hJwgRJ7E$pHlnxoI}IY z2i;XywNDXUb^0nMujTqDzSxf1l?V2YESmyLr5F8V&Kzmbc^$GE9t&Z#n=8G)g+Uoi2F# z{QP`>{-Ri8HADyX~L0haDl9qbgjzfEU z!6v)A3xq9DPjP^G0gy!kR>iN8pwmc%O6bsVVg)Aj;27BgH0N->M3hg_4w|`pn919Q zRB^1OK`<#Y8*u<oR^9JCS8 z?9w7c(la6NX!Xr9uu{A?--wnWXM7{=Z<|0$6FnAnbD}5cP88*}S;~AmZD2UjMLZiR zNjNeNc+VmMU^HNqPlF(kjQ7y z@|_(4o}e8X`Z&W_-@soE-=(SUv{mgs#U!z7F_1X%j}KafDEio>%(vuyXLnN8xW`xL zzN__)OP;8@`%$bz*utF3>Y$a(G-(s+J|xSdFE=U0lyVZu({iZ<906v-s(h>veb7ywX$x1W8M+QWnTDC!$=WVyGQNls1dTVXo zS6^JJUAI28J^ZXfAsz6of2AOqg!}mLRh~nBVDa9vltO#+|p7~^erqx zCnQ5`eV!a>Yepy18?N%1*Z!uZ#@t;Xx{9_dm4#{9Xpewkl)Sw*EXCcJ%uJV5%I+so zq>AzO8?rW~deOZg`hl0_pAy1k1Fh{|$^UoYY^irlvLurlH>mV4=JyyOs=Uzdh& zxycAS4EcS3_W%BUV2ydURPps8YIN1KpVX%;V{y@e58{oyG*rRB+_Bq!4(prha{iMh zl;c4N@v(r(Mr(TPHuashoAEouR!#yM!A$o%G8Bv7N);j~|A6mnV^m~z zfG8&2?oUf_itRhN$rZLfH(fIfkJ!?JAGbQHJb z7}vwXYb;L^HxMg|9|eeX`P-sy8yK+E$_^<>?F|Mt22H)yFK1*04+g6i!R^~X!^P`| zTbEr}x9|vJ|raMge5B} z#Q_|Zvqw4Kc}IsyziuM^unTA(0K{l&$?dJuG2z7`ug32l=q+ECQ+8?Po<|o@Ozi4b zY_U|_Dr%6T>YtzzNy(|{T-yNX0g~+ z2~0$1%Vi7Hs@BsOgtgK?(X3Alb8x4CZ4kh|$HK*B(RK*yfx8!NkxG&qor!lPr=>(!=Dt!mRLQ&*KIih znA1U$#z(J8l$LMCC0F6*H5wu5WQKe% z4`SR|$LZv+n?v)|I2xS_KG$0;2t#2D7OubdyA-Jroz4%+p4}Q~v)MShP7=*YwUC$8 z#?V(_3YTE-`myvtTYW>u69^q(W9Pk*+7ctnPvPfhmu!`l^y^R0ye(cGL+nXtj^87K z4%H$r4}~|S(a|mUy;y#6b>+Xi={(tZhzusmmzrOE^}z z9@am^@%ei~{$l&QB<|TRXNlz=2XsGWiF@C{uV_Ec3O$K8xjD_@q{pjX9u8@*+jAJ6 zC~0$(A560Ibgs0|_cs-6d$}!v^=wL)0M*Bo{s!ly`v=ZNvZ2J50T+XQmm>~ywtmSt zHc3F!Iw!yd+(5;^(D7Rb7AtwbBVJz*i;m%409C^mZLB{X@errMTBl#JiQ@^ewHg^L zX{f-*-M*6!B^rTtUvhAF)n_e0yTzPiyWK@S_4#U5KD!i;>Ede*rNg;)0od5s0Ub8< z8A;g*2sV0qyCKU`MPQeDP@?kfP5pdA!j*X>sI^h;WAU695oUU@|w*)BB8#>6aPP>;6>H{U*Wd zKwkt7aJ&eD{q@t1BmFmlp1jcWPdKpY!Fl#sJ& zB{?#gytwGdqPNV>?8-PW*S}|W|F#o^ktNq*Wg=0tjRDJu6GDgW`M!$Pnt_ZNp?_!xCIBTKPy*Br13lq~L^wf5G|vnBy+EV~h*# zC66tTI!fNOLRFb2NADq7IL{AMs7J9tVx2th?~U;~kaLeaebhaj&b?6@IDL@sw#@pf z$dy1D3a|xKvNmZ%+zyC67U!jfALFh zMqh*!EA($!)VTdCVK*=SsK{VS7KqG2Zw-mU?=7oV>fL0d;_x~O&#vr6S&c9cm-^60 zv5)Rn(jvRXJ2(Vdopp(O$3n<&e#wjPR_ou$?5j5y#Q19Gy%V|N;p%}BDqC5tzi`w1 z4r=u}ToS+Q9H2zZFxyyU+dsdyYB$GQTQi9KtgTPau7Ysh{Zqk*y(J#;vEO|HerJce z(vjBd;O9OeGclYPv$K7Ff>_pf%{n--m!rfPFXOt%ZZ5=ApH8{mABgp;j&lk4_}qNL z0}7+!HswX4AA>vLAvnslbr(b2G=Dn@`hSUBx$xb*05zG6Vb#I!(3e%Vzl@~i zCJ+`J*P0pg4d1i38x7W_tua8Zau(Gbo%5yJN4AZr=f(2aO7d#ak}`C}>aYA9C4Cmw z*3Iz<2UuFOG%c`?Od=Nz;xr)^HwtupT-HHZ9eLvE2bt&U@LMA#~kSGz5eQ$+;kG%6yT;ifl#NeVcvqof5(M z{nOLD7B8ILv8?ZByj64JzOPtHN_>8TKLrRMu49l9ySwp4kilS!iNovU5fh+u<*?s) z56ER`*?m`1QUb~yN$5s^_f+K4apo;^LV^lFkjtsA{-l8R4HtI&q7e1OTAk zY136u=!{@rmGJiFZGXA0;`F*Z3qaH+7x#GHI#fnkCS4z~;Dw8Jm^N>@w%?Iv^?9`# z(Jw{)d0}dPO@Vno=*b{s5ygDVC^fxs%S@K_ zh9$i8}fHU<^6J_#F1$54j5&IYV}UD?&<5b#SLN>=wmE?yN$5 z?EFrHU{lcECce~$ZFtyEvJ^RRg@`!#OPhxuUe#b5*?SIlDyH=mGD5$$rub{eYP+|A z#d8=zaNU_m$nPz5RLfyJXg~>Xzl4SV`8DhBHcBnA6 z4mazN#QXPo0Xr9an0P9x+HalYK467JYrCMDeoI9W{8Ih6{%#n@;ShfO)Ku0b%=?%% zzSo59Y=3F-J}B!c#Fp15nMQTiti%QzI|(c78$xNsM!Fo2M*pUL*@?ev&iLdY28w63 z4rt#8{7Ek5b968HuF;|rnZG>iEsF~xV;V@KC=kuh>xLysC`q%gvatKfzbb4@4Z$xh zy}DWTp98Q6viO;50aewdRFns`+g~tTVPCBT zkdogM6Z*ebZE1P?dh|5SoHimRBZDx;|N6wUPyt-nSIrGgPou?1Tv-Lk7HtCfiT>rz z2ridXaFVV^2owqp_c*ZQ*eK+I#;uT3oa&s_xfxOxJf^3Z_neMNgTKDdHIx}K`Mu3_rr3U*YEm=SciBI4J6qJR5kCqlKUZDjE;|wNFt5)CEpxiU2+Q@>oct@^v040c(6Ow;X~h*57COdBAlwrb(i?Fb zQW4G{-eAfdf!EY7KU8TumJ~FQbpt{H2BQCTVNhR;jJPA2mwIZ2)~{s?$atu{hl{P# zjUghP0Z)mFOJbbmI_SHnMfE3J2Tm!OJj`uU9Ly9s4CW>k zI@6MpplS);5fK+PAfwl06Y-lw;_fG-;?L0SZcBL#UgIm$`hBI1&)o7Xtqm&Hm!Vuy zk~~OFNs**-rqZ!&l3)dy7@6gWJ7EaRk%jCJ#6&hCmKl+t?4YCL8Lys=;U87G~?Vbp}iJ~A!)`bY=|Hsx_MOF28;lh9*sdPzqcekW;cXxMpNl15> zbc28!*mQTurj?NH?mo-^`<-+3?J>Axtc$gNG3QegiIq)oLMQ>w#zo_NL(6s&Us^G0OXD%J_T(RZ0w(-1DA@5W;F~cq8 zG6m_n@Q+tkS8F|I%1BlvRWB!wyX4wpHYIO(w(ljgn2u`RkHgC%p&lRw4PHN5<(z6( zAdio#HqC{lO3lyxB&?nvJDAN2=3n=^c|?@@5(!wAx0f1KEt5maFU5qLk;Z82w4=b%YIv+ZuVY8m=a5pdgoFQxL`sO;>_19SlIfQRaI z`f^cFPymS=8o>Ai#RB2Ukr4!`V!)NwrvONBfj`bO;YrJ@@H;u0$;ruF;ec!OJr+NO+ws?ny5k}bue&}0UJ&IBZ9TqAB)XR0fpzT(tN zgNs-VXe>W17gZcLYXhfMQ&ST#W>ScCFp~!@sIMHQQ_=WW-V5IB!+xu!6^B>6$JJ7$ z@T)~@tlpnIPWJ>#teT1O^oy6fL$KE!8cP>s7&$awwmdG*0lS7BiXYx9=r22c;Noy` z`Kn--Qjdzs9*Z2@=V5~Sy1m2Rz}GpRF_uRZ`TB~zGT=OF28Pv##be zA)1Jv>O3Ff^T!ro!X}_hZpFz!a>N_&0+9fg4U@<)kJqArgx@!L^JKv^{Z+iej`1Vdoi*bD zBxc!uSLE$V1ZXf|zc)9h`<;R#zYzO`8MJ!>EdvxS1H;wg^cFak%O_5XX0#Bapb*m{wQVPku`;m>zdMxc+liAqMM8C=L4NIPq&lM@mM>8; z=Y8&ehkmdb`-w7Hol(kL&D2Pv{hazt#>oklTMv;xPtn6;Y;>X%2yx9{)EXOtA706?4GvrL^A8 z+S(e6K$0&_rF<4WO5#iM`%rZI-8m(3G+0YZ@qPEURFRm&fo@4P%fQ!Iw4f3xc@E}ThdaQC!uO>FH(YRkO32(433uctg5N$vjsH*A(ii z73k_|RVhwHf8n>&pzCEy-`F72Ak?Z{3mP7ha^s(3EyxuTkhZY+prJtxWzUUyw7_+K zIZktMMDPVm5?0iBXN-!`$Z&ElHR1J@t|VBoHVl z*IQQ#ZZ9`ZLq|7|`T6kmGbLX~DT#rjOZLkM3M}CJmsfB-4;L4-^Xv12kI|jCpdb)mf@s$c$kA+UYznKZV~k!7 zwcI^CsGfCfh-!@1hwkt1R~Bda9OcWN&b{?vzmoJEy^unA`dLD9=6xAY3Yg4ob(^20 z`OQq{#oGGx$W&L7$#C=MTvh78U@8-c5i>?Uk|=XRwSOJD%oKgZmTZ?M)dl(-8F)~2 zf4gI_4jr6ZZW#r&Ym}?>g;HHLOubqOR8I6P$rLIb- zY#(dGiU!AXyt7$%^!+{kyDVBzllsf{N~LJvZ6B{0Id8^q8|nTg23ph1tuGNix7!FT zlSp$;bsO|?+U|8Wb`&sylm>A=?mZT#@}+TY}7xMDXTOb{OpdU^{5`R z9hCq95NuzG41!o*VN}36y zit0p3f!u_iPjV7Nh7nu^Qm#~YY$1s37uC~iucE^EUw8U3(vA5-DemlDIM(R)@TBQf zQU`GY0~h6MWo^BK!%0tHCl?T(HJ6Rxqa?ZtvIS1U0oByTKaX*G_h)9M!O})&&c9o# zX`9X)^jdc6fB1ZJCqCSMdD=fO%S5fY+Cyv7PR$9~``VvT(nsFLaX_JvFh6Z540K)6{qc^{*2QR(|4 zurqtMT+9G5`5DR9@v^Arss8j--qD5c3!{Oqj6z(>#RXk{&?{|9%506!EJ{y5YC*5L zZ#I!Y^W{HE>Zq>$W5M(n4GnA{?ehBi`g{OW$@yiF(#rcS~+7$&QYqKuoIv z$w?KGpi1XBsx0fR7n@10bf5fMtI3{r1rve|WY?F0<|7A9OS|8c;1m?-%s=V04g8U# zm&Nt;}tJ3CX@K*WN7cfUZhhF&*VhV$Lvc>mJ)-1a)`If|gH8@#pE4 zS{Mc*JGLRkx)!RH%|LS4q6fK7+qQ0|Mow;8tOSTYZ8sgI^hsAoN7C+SEH!~4pdN4G zGaI7szxokFlCC}A(MhDYJdK&0ihs?0FRjC~9O6MK`s4gH!Ex(Fb`bzD3JYCEi>cC> zC});re)+-xZD|N?H1NhGZeGrP%P-RpOWtS6ISd%0ysM?j8qpt2K80VN*By}{0wE?u zCHg}CUn5af*Mb%>InS@c9>r`RUk2^pWl2q4w8j15{ksIA=E&t`Gy$*X*%ke-(>&vH zEJRjsuZHo&LXo6+K;vL(KOsj71soC=PwOJn5g*1~!1@4S1)K_!PEIUAZGq&he}IJgN1?S7Z893P=J3I48SK�kLhy6vI>-3K6JGoLHZ&nM3J zJ){F9o9Etw$jPr5ROzJ@mV=n9l%b-~ov)@ad6ca_og}$5T^j2C0W(E<)F5i{S3jZc zJE2zXFdmz{8okAc;jP_~q>uBbaN!tht_|H)WO2*}kfbYmhU)W&-+b;BIKfHi@KDT) z+=qwx${Mxdx{K0B_axJ;r=UD~5m zts2r84>45~q|~9&d{#57jT-T&eUN8nSm-hgdievj50p=1zG?e*Zf?k)el|mXG7U8$ zg9yHZSn}Ts3ojnU07dfVS5)DVn?<8~ccy>K#RZ66DXXlMIbi4HH1sje1flJ#lsO8Jvwjcw_msBI47gw$fM9;^rSR0`5Q*ln)PVjPO(Z3e+z%)5~ z81~8E&f30aD`)+g_hV#UeZYwpKr#yhxDKEM2ULZdcTadkL_=FqWee}W0&{tvpDJsP z`>Y9-9=xHgg17AA#R-1E(n3oZzsG}76q~J9;1!w*yCb^+{laC!ZBoRT|AeB+Dr69| zUf@q0JWpS=Nb}mY{w53)A|)$3_1AqZZRSd*WkJ0~#WX>IM?(~G^QNS(&T!srVtda$S84x<|Cl2gY3|=29s) zS={USdp{FqS?^Ef?t*!|LZduSyz#*${c0c^e-$J6mnna?|GA{pAn+ zfe(mdq@OZxQO^}Z9?xJf2nW{fzhACCweqq(_k8Ym*>LwpE@E4`9a&AgLg^Nohoqe$TH1lI8?5D#GLEWAZpq1F%2cxkZi~*1YH&Qy!0hq zmN|#&2r^do_E`VB$LLw`#5q?#9DbANlORV2R*_EAQ1@r&6og0}(l+SWI4(849DUCm zeSVp{W=Cu2++aimXvgoU`jH0e9_l8Rh1YCv4MhP=1DQ+qi&28%vX5^mDR!!|ju;IG zj;``$D#y1jA}Hb zDEmTOXz-ThP% zE)1nG6xin~MVaK0jQvy=ljbF3wUKb7*0sJQ%EIHwN4NKEfiC2-|qY_6%zX_Byg3)0MK zxR9ML^8wK4IWTBq$yrDl?k5KJ+C&dS=A_HSCXC8AMgw*8_^L)?1U08A1jIfqbY zY;+JFrI9Qze}rYII)MB$b6BicEhd*7UxR)sn z13s&xj&Dy_&Naw^7kJNuf70rt02*Pjb@eoM5ESrqyHoiIXw)PC=vT-oRMEm>er0La zw8ymJ*TOE_Ad{$&zyY??MnO4f{K%e1w4_9J~yw$9eWI|o8*?S4Ei*-p%k&aP~dMTLRe z5DMx+7$};~e}nO>=K*D53SclnaS{<(owPj>t1pngzj6gT0DJ85iKMt>dm{9VO6;(d z5`{M4nNl2a!=d45`-ZuLj_zQD3YV+YdMMs0?UCGI4%WsX6;sH71e#D{i}@vbo+&B8 zyxbjbMm~wT4@VqgRFgRm6v`UF#{;LTS@)W-2}Py7pX>Ta+O);ssYEw-rPeM_i`(XT z@_4ec$V^2?gY$5a5)+_VRgD&E*gSHSjO=^q=5DLoFB@Z?MY#e%(A4H?b`}=cK%0wv z`@9Wo!;EVW5a|h>a6!T_$=l6}3kWDp!x?6QkErgmI^swy=pPkSx_PU@$kOq(+xz(G zTb>@e@B$3S;GujUSzB0zlPdc=-^;8`&SSD3JCDk1ZBRURhKG)3mJ0DP!^Q z3ALI!Nlu|cxOO<5U__wa=a?1xUQeySv3@6_|7&4I6VrPs?eivc4R_mnzxQH)-*?^T&0Z+D%9OT`6O(%TUghHCSK(JqE}@ut zU$mx&kk*!@1zAZ+IJtC2i}fxo^-h|R+5M8By|4Px{DZU|RB{SxU*#DKsnIFYN+^`b z8R#0^_7meO_AOy0NMpx$=&UEBM$#m37!J1OWK$E2HGGLm#AKzxTk&4N2%)|t3Zkmo zmP87sChWI4X3No0iJ?Sc`K;+J8f@DX#1uq>1{-tP#q3ypB#8$cs~81O7#yHU>NJ$j zmCcZAlxbyX_DCEZ`L(-?b9}2RDOEgf2l^wYG5g2+vH-$m1N2R_fQBBB$gKd3G+%r7 znJY`d!yXCyt233C{*$KTQ(Z_lYX;3pSzYeKKb{_1|Nxetbj3bJ*t+)4q3saeZkD|s9Su_xz#~j zy^P9j&1vhMe^*SWQNDz#*?&~5`G19RWWFvzB&3VfsGmeTK*{5afcg6Qwc@jV zdia8m;MUwC4?72k2;a1|zPCs+6mAp(9*VH6Y`ld=#;gzS$%)Fr(sw)C!gvjjVszFNhPB{wG9U{VT18>fN37u@CV8|I^nB^V?8}Sll68JtI30wTae+K1 zeAUg{{4>7ZC7LDhNO1i=4A*4o-Mj_esi?7!8J(g@#HbswVmQMR={?_^fE*s0R2eV( zyXs@~cu&79Y`E-CvMzK)C1osITO_*E!`RHlzrrZKPk-(IX}*ON*u{2thx}KFZy;rh zc})*-V+Q^8$sLdFW>OU+e*3SYDY|4I!hV|Jdd%OJCqF)+zq{g2I<--N4541FM5HE_ z(txiV43?aya|f4bOVo*}>F5CYK()XjRVCe~jNE_=jVo};n}-fi?(+z8pwizyooZER zBc^wMyzNRG8)a`~+%doyBS>lA)#S+w|D2S8Jg_yZu?wc*E3_I7V^cxeIPIF(kBBu3 z%s^B4Kc;Em=!Ts&G2b0MT7ILm8S^du-LKE?p9-Ke;i!WhojW&+4&AXW&34V?Fq0e) zl?$nO5c5tqb)XWgq5+KoU`7Q3({xzrHRE4H?@U4Q#_TuSHHtEhZv4HLPuxvS-Gyak zxWTWlEE7kgOH0-&v2bB4@r@IU6_Qb=SZlw3{|4Xw=3x^S{#fBvpH^OmE#^FGSsNP{ z$Igcjv+&L`^9kXUk&5c@$xk&Ry(ru9@L#M z7$1u*i7twEc}bj#jFfdt)35|mwHNzn&dto36IN%h;^u@Y!*5%|l`c`N?FL@ob*-)N zAsWDNGOqwgA5w&>KX%AeBGg5-wM4YfT}8mnlJqe;o^3MioO)ql6G?aJ>Zp5I&^@9s zo}y#bLttI|QRKP*iTJPbK6}>`rvB89%-OKI)|hTT8jHLy-*E_cOvYDnWjzNAU-#^< z0qCdN2U~x^Xy~HTkM9XWtzzF^#@z%32#v|nM6KAGEH#+CR$Eg)tO>7OoEXMu%$>g| zwK#*&$#F4e`0cs;&&~+&9(DqSgH+AOH9pMUeLTPZoCzt_cwQwM2QQbtlZa3%*vsiA z*$lse_UEUVoMaZhT(IbvFV*86`bj>}e|NTbMY9pj!}-hEF?jt3zG1Gd^(k+1#hP&Q z-TJ<%5`u9ui~o&9*LRMq43ggi0;85=jDOpMswjII4?G#$UlVyi4_hsE$vD?xSYM=j|oZc!9qQ`yTo;Bn7J538zz5Gn2zT7Hdt`wd3(u&SfEy9XunCa*NKO& z_O!%@|CHBj=lG;;Bc#9mLt}?5_I@~wE$r^b6o0|g#-j(hbUsv+usiD z%}I}SSI?e3BVUBOq8G#sR=h|bS7LD}}OspUQZ@4J*OeET~mQFm_*ScaoIy#XEx2p7({mVrLOiw2HpjOANOFdT?Zg_M=%Vm_u> zknZ)dokD%-A2C#`=yikXfJRV4Q<|(%n-YZ&ux8pX?cIRz+|5tNNh3`MjL&tly7!ICR7mk zh8U|9fR*BaUy>P3rhQ`Xj@ZGTD4{W;iSa+rC$ zs@6W(Zs^bEZ?7u0EsK|X%_e~^w%=Hu`v#(w7|jMhlaRa|@F|AH)fk?bKK#rnSGvB+ z3L#DJjzZGDh&n&a7oEsq@HTS}D}Ri*ADdOI1J{PN*t%>dEre%b$!w8HjzY45rN1x4+Djf^=^0^S9 z8fvk7O{)z*-iyYi@YJxWnPFynJmEF+c|Y+ZTab|id3yl-rxLqfSJas!yR+jNo$&cR zr5Zn`gI$$QC91ReO2Y8AwDS0~RZ(@tcG-~OM^AD3a; zi3NwO1T5+FG$)^UkO{p#G7AK~2@5>ly>*C*co{uXF|QF5ZfC$pEH#00X;2^7xEVL3 zToR404gDw7r|DE!cBlNJ(A)0vHtT}~qFNfW>w|uT6VwoQJ(JKp?6k%&fIuCc_7OCO z_}c|R7=5=q3_eFIyvqoFM*9}u!MQxO?8-Ci!y+Ogz49JZXMc1Cfc2=7EqAK!TpaIj6|q zsleT+5k~`!B*{;n;cn83H!^Rn{D8RVZ@`!ifkcM`5P@cmwMOk<>hfR7YRzVPF?1n} zDQom(t%F6)Yh|*c6B(b=QC*k+_{TZUAJMR8NgW)0Jv`*k&auPC!)rb73>OjU*d@)c zh5wF7OT(YUg3uZ=rOAj2G9hU&>-lEY44W`4sk4mGOep6Bsn7=6BcSG@2Y5$d=6E`z z4m%I9wW~o4d&zoLosz=4SbzUtgONBjRgQ(<-;T$Qy>tD#0wbZz(T(Dc|McWMo)%b8-QKj)pGo?%Ap7>uUy$jnyhxbR?RUD&u5U#36Y zYm-;>Ya3mBxTu!eSOmte48{%kf~x*+fMT#$i==StRW!m+Fc*CsY|@nS1nl4ELYXpV zhMmDJHCQ;zMNpb4ng2!zoTfe~G^o7}HlSzdUWmrq-#fMZ{b8#upf~@j+|UsIbXLJuy!+z=3v|*kj)^Fsm#$nah936IdobYWOVZRjwn-}BY zi3sYA#@}h_&Ac;}pe(}F#;(Van40pVw_IzS>FxGXINwC)nXR^e-l)jva;t)bz}2AUj0ECaHp7igI}+=S_vJn6!=wobG5b|^4|^>v zr8?h!Oay!j;^&@XNq}t){4=OhfbCHGd^v@b3j-VP<%(+jBU4+~!b-z~izF~7DmFtR z|3}sb!oyEHJD6Wrx;pW{M9Ii`%>HVHb>=1XAwbTSo(Pd+@S#r^Ly#N%mW>IZ0y#6^ z!HE(a7M7M$H>NRj8PU;56PC#3N?tG-w`(w9Y;d%SzdR*hrKodCF<{zve=6eUW5HK- zYLXFy25wAn;3>5ls&8jx1Dke}B~f6vmnhP*{W4akmLM!auFJ=CNA9sPLLkew@bE@?Bq;`* z2nNc5N?nXZOa>9^Dh(z&bz4l<%=Llf5L3QILtTIBrC}}YV(K9hu-tgKvI`#s`<6?$=m>AW_7pKyO z((L`R!a^04|4*JCqv-JjS=@LUKKs(Ku{HMr4_z_|;2!L*0(XUIKH>Yf_b|)?q@(lG z$>^zyu|qM@_?nB9FU@`2WTbXiDtBaB<$H>akEjW`7n|60D9h7 z6c=o&PAP{LbuwRV#`ZsR*ikQI;Huxu^v+C8nSl9&Kvx-EBOU4-d=p zxT0D*qj4Yj2ST7I(9tM}yL{HG{ncK7Qoo>l>7hD`u`~FvC?wQtmZ!E)#MR*zmo(LR zMZ$96mi(e`&q4`0VsDEnWwqT_p z*C@_~vMi~dyip_e2vQs;4tvU-4%I@8p-9MTS3zMRnubR8?x^G1g7Ev6(@@Lr7_8_* zs~ga587jAjvbjWZ-@KW^k_98yo!Utgz`>SdV^UBM#ekTTaRAMlo1eEzn?pwdMx~EB z6j_UxW1>p}K9j4bn2ZP-AX8I5Ab?_a)-bfUpHI$heBRfE|E%vItc{;H=+)3L@S)v) z{gpf=rI3$Kv35Z2iz@pd6TU36lWS$qQJyT=a2t1V4$^NfZ5GcFkU$%j%fW6+PTzqa zMcpn5B~q=$V&Sb_KX%9IV+3e?fhoGm1_s5C-9%S;$7#USUTIMlJ%HCRV`;0FbWJIa zNNtgSRIQ%D7bIy@wKlklveSFu$f4{hvxCJpARl0aJ~hzNw_8xOLH`s8 z{-ed}f5PdsAMg(9KSB0NP`&q`y$3yE6c3{kzBts!Kj~>RRRrZ`#+gR=60(cGbqZ(E zt$&*NS|mq)j6gu*@5=HR!{y{(^mu)We6QTd1L@Axh832!!rWo4GWEVcsv zvT>8oxOX}dGo$_`KDNou7whO*VVa%3eBJuY4VMF(A~% z!`Slb8Az0^t&x+PsMCNagc!_9_t<>}qR&_xKtE z@tZ7T#e?-E|_Cf8hq zzaE$Uc#^p}KB4hxNA20+LAT2an{)bdB3KE(VDqauJh42vWesB?WW1js$@zLD*e7Ha?xs4Gtn5f(j&4N`X!~M ze=_vHr-KrifnL*o%^%M3u4Hpqg&ryEG##1k3x-_G4y=RKUS+DC7L%AcsWVd#^A-Fp&;QtCNI0i3}0Wf8akl@;R<0> zib7^)G2Qk4^|&?@2M>(A8uyXuempAPnU2LQszY`O70Oh|Cm-KrR1SCn~4 zp_r$cuO7-DOG<8p$doYD*sF-S$5y&Kaw1Ipu$msPBCyD+V7UZUd!oa;ve@mqbykRu zjlqJyTQ#M9pOst$>E0PoZO07O;etlU50V`>3&N6BOY|4i{|KkounacixaQ?jmn!eL zb`B5>R%t?GY@Q(p+YT$!gA**WU2*j?ekXAGIF$y-Kl-w#D!u^>$Uoiv1O0NeWBZ_p z^WxrHywd9i0zsF{hr73V?EeHYlMZ3eshz#a!vu=V{ECS=^-82+pDSKm4Y%>Csr1Dy^7))}CtUp;?QNr{;9f^DGeMhpPdGFv zD4m_~v}^0QraCkYT&{O%(1&6c>R&>yKlpm{sZUPpogkhm9(F3CWo2ET&(XaNUUTHd zwHWCPO%r>$ogWl;l-K8KM34@bAN%jT-29}jD0S~G-Ur*7!PSY26P|t~+m{2|h`UqL zTckZd917od?(Q^XNU_%Z{C)+;ySioRJV+lnBQa6F;PKPQ4_`zFyU4YYs6TfoW7kdg zU4Rd^QRhs=)7#B?`8x5QTQg{-sVzdpE&gh~zj&qFXxanB59FxD=jNB~?0Pn94tH;& z3A&|w2@x546vy!s zovZw(4`qwDr7$!i^)=n!pZQ27r$$IMjwW>#|S@uQHfpnI$+~&i@suda2lB1_TlDwK?so{guW#RH>Jd&rjYalY8k6FlLFOdWiYEaf@3{-W|L>p1M>}aAi2@?#%iE4 zgy~hS6Cjaw?6@Y-0rbE!f+p4NT2_`$QBGw@OhNodXq5&njO*0&+!Ex%(Z}Sd}8IO5FB@Nq=Q{yLfQE>kP;C#4^WKYXYKIWyZ9|s|BDw zai*dw%MK0KGsBBvLB+W;fv*EO-nU%>4~D3@2sJy+UY=LKf^II8n5yr`gQ_=IZ0|Fj zXx@IFk=^g&dt13Ke+WR#Nk8y5CXc1nUi!gEpL#GZXTyTIpNTe;mfF}L3k6%ZygZR- zwkqgZl@Nr_ytUv-^I?_Zdh8VPV_>k>ax&;4seLwR_wSwmJ3NsgkH=4zg{1IK&7wf?naA; zWoKaP>v2#+jN6UI^TQa1;nGp(`8${oT6LRW9t}^Qws_%<2zJ9pCC1z6W#K;K)~DP4 z-V#i;0LL8V^*_6d4a_MIet^hp^$x^&)leNDZ*=ny-CsDOH_c0k=Y1v6lXp?OgUyL! zV#0kz&!Nq@LKm++lHOGtJxtDZjHWNzqz=tgnm7ke}0M6xQF|V}&0gjq#P=?}tDEQP_H4 zmSaBfPHPym>;LR0PnsjiipE~q-oG(!(W9kvG3LxhcyD##y>jml!T8 zheu`u1FMSaucM=We1Xr*f0?th^ED_>nC92?P%sn$JFR~d-ynU5Or@do#a$-AAci6) zad40g4Ud1D`u+=($c!EaoiQCTRP>#c8ExhF48VnUsm0uk)!#sEfHvjsl*s&1+~kc| zxqTa}eOS8DlILNj^zL3Gp|5H*U)AAfDX@iRz>gtt8|+DLftx5Ko`s&{OQqT|Nby8}^_ zz7IS=E*)H*_V(QAN5^%cehVkZy4Gr3H-C;duM|R*x z`m!==D9^LCNkD7L(e`5MSX}5r_b-{fuH$m7W91IeM7stSB*$Vu4V#fiA*XisBv-77 zp(_aj>jEP`SFLSLezeSx%Dl9>*>fIQ<&tZ5?q_acq3C?jqapeF%OvQ&#pCFIPnDCP)r=0Cmr`whs2Y}XY@$LZm_J=LiT*{-fs>~ND1g4v{)4_^V{;QlvN% zA7=ht4&Vrj`*^x!uAxDn9wF7BVrV!8sE|3j;vyo3jw0o$>g1x-4;(V+b$#_rF-Bz} zK`cA3+iGJv6V}R9NsHA|y$bQk#qzim7+C%L8hkO8Jf4$Su5W3ox^utRm$=-vrQtn1 zZmRgpC?BugjPqq&1H(qTUN+dk0CSR)Gdf-&hnvnI6cAU!NX$ZO zvH>~iRj@JU(gmN!X~0--NGeXuG8*;22Sn<b;^TbLx$a|30sD&ojc82>5d0Zi@-hnRkLofi+4gSykJ8P=n7kPw)etx9ftp zh9Y}c({+P@qX)qmsoBeLP=3+f9j2fXKBW>6R!c!yS{3`*(PDKjn*v1n*Nx2pD)MDB zAWPf0rM{%y4^ zVz0YO2P%HaCnazzr1#~}LHv~K7UjDRCvh)*scfVt_d>Sjs|Sd4PqV@5B|KEB7Nu=- zD@G65KCcf}dtGG%kN>%Dud6-x26>i+Ho8KA%AgeLu2?@s%Jte5{Fkqh{eC3_Z)mLI0l7n6;Rj{|}2J;pyMvDdC2_q}JAb>#Y zorLwXoOaq8&FvQlJG<$picR~$5&e=f>}2;N;El<4IaSwoU*45_2P7@(q0l8>`Zg&@ z(o2}?Fds3&s&;z%(E)Suc2~fL8U?87hiSB7>X|3jiarjuOBAX}b=S>!(5xgCD)gyg zzn64NZmOGoxd2`pBAEgdWB>isMd?*+fK#eUr~w@{XEHs-7t~N2<-%K(1pe&}2{&hu z#Q7Qv(w@GxYoH`p{k^bI=j@S{bfnVofP)Yb8L6JOn}!6~NW~OfB?VKZy~Zv5 z?K)f%!zqmsS=(GvlWvnLVoYcbjV7SBdhne)4~rase3TYu)~ql1Twl;*dO$|VOhd@r zPTInxr01Ly6cjbPsv6}8Rhampeo+pvYyl@>{bEe7F&W`UjE~bKJynZ2=5Mmk{M*26 z6cQyOqDX5;N4jhwu{PFoL{aGfs|EP?x?Rnci`dGUwOFXAtahWE9zG4z;a-;nRpWy{ zQ=gze$ZwC~P=)i*Rgz;SF=)Z)2vXCm-oN-3-8%ElOwP-4&eXr>eGEYI|NRi6%n7xuQl zJ?_X(jq|8F0Td!X&w^$gu1xA*RmEmGssyT()>QIE_65^XiA{Q(85maz9&C29;S%cSFzj%O+N9XQs+3#wk`m0-flK)w|by;Vc|nX(h_{;XPBI*whTVrlL4Dzmhz& z9vw;UOmC3FH9Fptx%!}w_|8~!F0C-C)y6~lFg7s7c=W`>AXd%K)CP?=>g6RRO)ZQ= zdU)p#QS9uvsA;^$!HO0*esM=Xc*Z(0N)mU{0?9Mt#nKCmctUY(HP9MYNXyLwj#^$_ z`13wiS69o{3q;!~*6q0aeLV7>1Xm)(>5i%BSRZf`tg4o8KRkjXBNg0^!aJJv9dnnL zG5rkdFjgr$)#(Qh535ug8{|_La}#Y>DOW4~rSMSRf6ZIk-ZtNJD|jND7P`|nCfQyL zJX!SKisQNM5X_Rl#C`2E`a6PtmnIG*fLxfEn1pN%C%ij9tgcsO#4!*OE|>m| zEm`*`ky$!=z;1gmKI_xMPsjNgA5xUd9#MaL4y5!dIuTbSu6e#bhf7ne`OQ>^UTu%6 z$u8n8xwO;db}1n+FDuRq%^*L;p<~1G;9p2sVDaF0O6!XrZ+zzqdJR3I5h$(+R(sja z58y6^NSXUBA#XWqt+&EPE+gVs!BqFaOgwL(%sMHid{XcT zAX%N_DsMusbgErgTIl8wTKsJ*T53A#NI{XPc&Fsn)YRyTC7moA2V@G5LLl!B0`w4_ zM$NOe8ASyRp{pn{GP1I(k`(LPAGKf38=X3G?Nl~FLoyS)k2l>YJ#s7oc)?r4EXkuC zQuH@E>x)P;fexP0LR^hnRJm2KIw#m+i5$oI)|{UhS?WzoTNRdGx0_$h!9j1NtnkOf zRUEa@ExgWuQCnX9h-giSM&#t>8IvcQ+v{5NTqCOvf;#CzeTH9imiKR023S=Uu%4)G z5l84ux&IGUZygq8_k9nGA`&X4q=%A^682*8o`<%1ST5GSpcSPbJFrIwKbfE6jS;a^wKXq(mo+MSeM&CN$ zxz9pXFFB?)EZfF~D8O>Gq)}a3iX;w^TLcTNa>U8YJMW%3p(5Bf{^X7|s)Hp-!&zra z>~ZhQ?XnZIV!Rfv8sXX#$~xl$sre!rx*xi?Z@*(kfU-5MJXF@q$R6a=t6IHu8`q$e zl!w3^#V*sQBzU1cWzaF5Qh%nDginu1!bm#F7#}t{mK%C2A{vz|9khg$$+iU%&gUU_ zya!P=?Z?l=U{2bDMYJCBxdZ_)*R&NGG7&HD4z`s6tlRa^CZ|#j2EgwT4(Qk`WE>yE`K4@ zAf>4yKR%;8(l;on2fxP@CAAVHzoaqen5J4+Om8K?NTpVuVAnZ96>rdqp}9x8b7fxq zJ8yTs4{3r&Mwc6@nVC2WU)8~&iunY`Nmc3e6YlGMS8g-RTN*u7=FX|3GwKDv((W=t%JK4jPU2Sp~ruXs@?`){|SVMt@2c z+Y3}+pUM5M=1**EKlttz)E}@o9Qn;%fqc9(Sw1%XhFx0ynQ$>)?`gfEyn&nJ(;4RWx|$XTMrz_fg+RTxz})kkW}m%}{Q7q5zRZdruZ0^?VE+CGyTUsZG0pqPLrMTxi|T)Mun zKDAF_VeW-mg!eSYY+RXH2zmHN&0T8)nNrq12_+_w-0KrhlgW|iL+x6>x_tEh;Izdl z;c1;wN@m-@`7!yYJ&@Gebb#V!vQ|;J1zIC&me^XFWphLOLN%K4=wFG=`1Sy8Oq6 zWjqq;Jc+TaF%!8yd4@)J?;_gS8Enit>-VmRoOjf}ZiBqj@y*%uz(rb_f*%AWTZyfl z#?Ul@nb|=;&mXXTD%SCvBjjCm+00l*6>RDlG!N$~a?7@qW=N^&zgB95$K+w<1#wb> z_!CFxvP++7A2!Aho4u)R0eC;YvDgK1m+NNU_c1m%6xX(tT)>a_cgU+}9d9-qkHS=Z zIz}Hh?2Bd`6-j(Bcm#zyvoNW(s+#3np)`wjG7-$xjBwQ`CM zq1%Sg)pdlGcOa4|XV-fx%dvDF{D1H-%$1sr$KoTo0^kdY*?RM`HE+V0%Awy43p0@Ugjc zL#bOBud zb~}6r$Ae@+uZ(QaG9vR*J$*3MfY;=$+055)3}d!*0qKL0E3{%;$8w4j?3fl-+T-ou zyt;T3?ek|}WJ%@rq;0)h3?us3s;}AQ{McvD_?ErR`%L$yk9V?P;O`p$;9-Q_@EEZw zIkNZ`eIZf?r+a~F^#EP%Dc8tsN2(J9&!RYH(9*jVJpSaRro)#v@LPW+1p~`LPRc3hVp@|vGnjmBqkPQDPiPxuzg6{%z806=8U5CwKSM}i z&U8b6GaW1mYqycPy^aAmWqyTHyp5ZR3pFFVw5I%K!tdWy<2KLenl;%45|e0oczNaX z)br=TRq>@`b2dz&8WkX<<>llZXgou}6sQr8%oL|UWmv5UQV3!9)tF18&lPOgfLfzi zVWEyD!yYOq9|U`*wWi%!t7~VsM~GPQ){6DWOEphWoKX zOa&uFH@?g}iHPdys@)A5&B^C*app{0^M(ETlcuX2m9~Kg zH`7mV)(ajx6uG;pr@|ufsBzHgDI@ zT$nd)o&oy_*t7;Q!<%ey!E7TLmBzffaU0FnKi%9?&DC4HD0^XOd>|z0HoJANIrOy< zqyiY{>m682pedR=D8Z_#S^bwo%^svZSm6n~Tik!%EPxjhVoL z$0GH?E3H)hFX@RxnoCpzJ{G~95g}(H6T5bMbDmb(aY=e(m5gy@zrN0cs~b}-%owEU zo&22}>M??eX{KRJ@-i|u3H|)$HSVX)J*=l+3jHD1Gc}n=@fVq5)qQz!8N7$JC z=<2 zBApw=U)F`i%=4vS|LxIUULGTNk`a|eHNi^kJjyef5s&{~>^GNYp$=zUf0PF6lR~W$ z1#J%e4wBxTI0P`l&4#Uu033I6rL;yxRwW9z6al&CJEoU3b8l=6u^Qj940}u+muX{i z7q{GY!)nuo&mLZ$(Y`lX-VN1$m0W3Mz^df3J=P@RmnLiIMJoSEEd%-Q*14#Un{P)P zSdJ$PetsPG+5pz{p@sfCx?-L{vFlIpwb`tx0f_22b5jvb{s$RNvo%>v_j_Z=>V|#s za{uURV1IFSn8vf+@oI2?>GEbp;$|tRZAdMv=4ke6d(sbnyZLjockzlz6tnA>(RO|E z6n5BjM1)wL&b;EfnGON-d_P@05AnNbI`6-|qHH~icX`>*`8WE!=h;#KeeTcrhnlb^ zQLyDV){31{bF;JDdOodc&bDbZjH#Dbs8Li<+ojReXug;ynv}qaC9Z|Th<`4qxf-8H zlAVZ0yIARX+U-tJ5m=EgF~;;9@yv)5*FPBO^sZ=4f>^kxA`H8nG@KB_oA5buB;&VP zhB0*fD};s)y@J1G&CjVR3KTTlrgjJ%WKAun%0BqZj_mt_Y}maAak2X}RovoltBNKU z@E9zLwFglH1NJ|EI@FUa`V%eS2U#DTH&?*J{beOQYWkUr)B6J~N{KmvdxmI!=ctsk zu2#De5-(hu+`GJ7r^!2e zm4V0O#JqXznK%5JH#0BqfkETRky#CQ+Dbt$rclmtW!>4nC|v&2UxZ0kZUN$cg;1u7 z!l}}UloFAl=hacReKiZ6p)vKft2^E1D?wRX{si3Bz7fWMx;gLwJ?s-kM2!hvJ+^?9W+iz`Gn?kKuwp zVYla2f4&%B^VRNOu%ga<$QREt%Fb%{JFm)UugGAhi!B|_R$nNGM|uCbk$w>pchWFL zH?|Add1V;#VPP`vMB(e^0;AiIJwo&4)G(HWb2S1g!Rxq@tKyUsQh2daI&0UU{ed&Q&TN#WNLJKNR&v#(=2Q5isv{b zD=`oM@dy%jZ^e;ve_6u(RA^e*p_n5iPk*q8XmM^V?SiQ}2rigcav%tD58lkU1Ov&F zlJ15%TVuv}-qK?W$c35>yx1t|q)4%$VwjdR)?i?R0O$RSFyF@Yz$$7b5fky}$<234W*`{=l z0Z1=;6lAMUal+a8Rl1@WbGNcus^ygYyEUsb>CP-Aj4_(OM0>$0HEUPf2_%AgnSV5E;nw&(V5IDw*AiFAS5*3Z~I_U z$K&?yvmUPz`hf9B?G6PO?|+Fbh=uLh!~B=3wL+uL=RA4pSc=TnpScR!rtQ>TCducG zyh2z6Mgj{b$u5A5Wl$OUFs5tFebmRHi64Z6H23?#_~Bw)JUD0;yPZ|4S3;m*#omjq zV5`B<w~t(rjZIl z^~(7}*p=zA%CrE8_NZ_DX({^#cJ|1am#GgA3=$Zu+-A>Q9Ljis7*sFQLR!}7U8(EpWXEJ$MVC91ioXO6?d*iTUEC~zxDzy4 zl}dIL#p{6$&w^-eA1lU}Rx5QF-xM@`{GQOa9{b#NGmxuZ`M+_DUAiQa1^;BavgU)QzMg%FADid)(9=NXpK@M-oh)t+6QA3xY7~%W>qjONlLY#= z#rD_prgi2dIn#E$e0Nt@-^|z_9x>O>ymMHDMR%&foU3k+x>i4&T4uj8RbcW7+GK2_X;&eQxd=hJL2H=d)eK%C2B{ zc@@L81U5RYLe>VPR7&oqW|x{gj#D^!6}nNZ_=ajZQc5LY~6%u#ePY9#kaZnq7)~%w|lJ4E+86R3uc_}#P;cx?-mz) zam`sw)r?_n{Mwh6J|qil4>n2m9oJQdT?7y@ynYmO%=dsbtSIa6&3z)66zfGEYM848 z)%ZaQ`RBPBfAof84B$-3q3okm6KEMZ#uZ?I;4hnTHh8%H(|mgwS$8pc%`!{XpvpDg zIyQ&vP@(e*cR<-181Nx9GXuHhwY({MP&>@BP4#X(5X3_A#m3gnpR;+s;rMaXPoeSc zC&EPz3_7OzwrJwStqGg3Z*{=G*%psb!m+7kAGExOP7A+hFC){X3xChT-%SW)Q9JW#xJZz^gKHG~29LBd;HxohES9yc4WZTyLmigPR zt_OaW6+AHw66?+sJ&Ewy+{xUubQN2?$Z6{s_IstmiL-c(x=p`5(r%3!ZF3F{h*vq{ za@nNt>ps@`7l{T&8l&u^sT$^9yYDrdZSa3G@<*gZ2eBWARh!n(UT-kKyfw-F6%O## zm(+P(?TAhVO4#d>Qo59AS5c7T!qU|_f!=P^`FTIk!Ru?ui*KH8r1&~fZj`0W&6-PC zX}-tzn!S(b8Gn*~-Ont{%lDek@L~*%f1D@|TpMt@Sh-&|0)^v(h2z`iHC1JGVfSeC z%J2_8ga-1O=nLOGaJ_jQ+tZP)KZqI`QQHwHn4g#{3)jdymb&k0=XQz>yz3<;J~fj; zhgfMMj|dsFC=8}k+~2J!fT=ais!_TcK{UCRTStcRf=gwywX`s;>v2aoUdP6-t_3Qb z*=oI&SGjqE>4ST6v3ptgXSfiNB+1=spe+5wF2a=A@4Yha-VZNJ9fZpvfuh zKLRlS0fDwazEN1u>bF@fChM}_%m}J06SFFcb+3325z!?s{$_N%U*_!rvTbn{lOuBG zx47J}+x={97Ip+mzD2e;rg#i5E{_0?sN03;U0>flgkR__^gP6^WoL9ntaVxT&-H_Q zi8lXeSU;Xhb{r`@LD_efzp(@G`s3#!Ks!E>AANoJSreq~YG&K|mu4HIw4l51MKdQI zfLLS_#P$)cK&{8*fj5+KeW!aRHSVr7=(&i_L;E4vZYIy<4tdLj$n}F!&TAwS`s_yV zv&9n5UlQtL>o2C)O49Ajpz?bb(XQ1QH)oowZYCb5R~D{mrq`pOZlhLF_YYcN(7`d` zp9^a0+JAGIvNAzXwE@Vic>@Bk3pb$lkB-hWSN};8gkzrN1B)z>9n%y1Hplhp!l$ye z9O-f+LrdRlT;bXrc}_L1AH8ykUM-(BCD_eDitWmbQViil%QBTa7T;+d(`E6PnG=zg zj+fsoYe!POsf#sE}e$BSO{+K|x z5y@Uxs;gG_zArV((16(+4GXT^`~SjEsJM|60>O}7KF7*?i+=dAy@GskjBqNJSc-cyV`#H>My-A5 zL&cx-?If#GwboB#dDvJw@fslgJWn@wa*woX1qdaLYG~D~ zGp!w3wzN!&I@7R*(!GOOGDZ4;!RC~Q;W%dGy3xeES&UI0#IJV?uQlyV1cJ=2i9;Y%h<9$rK(6)J*XLky&j5rG=Poa-|QU`m; zfx15!Mtb|hw>b$!2^TT=FIbE~(vopleq2Gy}H1~ik;Zu%T_~c&WtTa{B z;#a+E+}au9_mNs9gBu$-7_ad8+Faf&d3s{>kNa5{|UWIvb**~)(+RdtcO;pN+9e8&412!D=wFevyD`HNAzRD zyd27_Bq&gWfL8c8kiO}9m-d|cYM1AKz&Kbo*hf^Q=-Y3Mt6D)FMshAPI@Rci4BGZJ z&x^{Cs4xSZe;1(5EGij5bK`rT#8C1kM2W9A&YrU;^(!dobY}T4S;{hfMOsUyd_nrb z@|uDgLLiBBm$Bf2^Qj(DWJkwr(+2+=F(hNWmTHWtLDQ+$mS)}Ap7P<61OkJhhbuh& zWcU4DgGdxSfssLx*-1tw)tt}bXAeu!r0s09Ht)EyCG6%%+*-QUMX30s4F*k8G@8+L zx!5ilz8gX$Q1EGF1(DgIujBopP9#4>iB78YZzAOcr3Ns$;fssg{)-FR94+DdxgTl+ zx0qQJ^#uBaLnmv)dW3UFsUxGViIHoPFVKn7r9534m(P!!U9?+~6{%Sx1Ry*~H3i^~ zQ&2v7?sf3qX|ff=q0Fu1Po(XiSPzY}$FAnIWpc`}1jb_=?FZoyTkMuieiPPx8JUeg zLSS?Xr2rO1^;&3$`R+?@u@eC`?uU&`+hIwB5mWDAEDBWrEJz=)Ai$aVt9d;P0Hf@| zBU}FBSIj;yLFEIF6vrzU<bAG>;DiM&bX^6iPu3qgrPY<5Rb_@0?rAwu3m?K z9z8{ZxuqrTC#@r`wpWcWDi=fVxn^K%W7XlgOE6@dXyUP;%r}RPalLgFh_!-B6vE8F z#4E|$K!U4M@pJR|<_m+~bi^hv=>K&gO)0gZ9R$!vbdmSyrLP{NDYiq|qb(4RN z>~e|mwFDVihJ}eq-JisN>+STTQ+c5kT@acdB~W722a+ zs5L8Yg8pr$<2>tIJzasNymELc{z&J+p0H5Kl_XdX>$dd_qwgF~tnOcYnL}NDhkmW9 zu!5gOii^pkXchQ4Q|poimvnt^8TYN>(%}vyNnhx-VkWbF($6t4*M!ur44hMlgG~Cy z1mROlE=2=y>q1GTW!*!LmUCVG?I%@&^Ok=_qIsTb#J}X5sWL(yNOEm%kDvDl2_V1N z93_Sq>N%B=7;S@G6%*Lug25M2JC)d=ltR*;IeN=)j*Bor_n)jV9<_`Pr2BGCSC144 zM>&9P4Lb9+Nwl84hTqXlJh@nwO)sKW<4fUmUTPPywUsT@%KUg9Yt#NtOPluK=FE@Z zeQ(Q^OZ2dd^qGi9sO{v!*v4fx@B@EW??e%wNYiuiL|Lo{c-XT71;Q({|M~{hQoey$ zIuPuV)#7u|#~fIdWGE+63V(~^x{VamNz0k3Ne)p45}ySh)u>iMIjko?v45Iv1F z^+DUrtF0ORUoI0zsVbQn3~&V?lZMbM)hF604T-IXF4BVY>LkM4O|n)?AK?T@{QPg5 z)8}L+LxGI^ap%*8F2=fjvEpsbHe4^6=)0Z0`a*kz+-zR#bG?s*od&q(EpyFQbYg(7 zOSvB1+0pr{#5)1+0U&YiBU-K7U%R$sa2Fy!;u4-*J4?MbFC`DkJYHK9PUz<-t)RW5 zE?(WEFZlh&?k=@BpleT@mUeGu(Vy0A^})|~Q;Hfbg-@}$4TsS40;Ns1U=T>9@*5PY z=%Z1v@h#~f$s?CQ|Q_bHl5envgqyiOc2sVluC8#?!7T z9Y;o2FFdxt+jAw16iBSRPnW3PnZVlqrnlO)YGGPMmE8x0zVexV6il9)t&kk&I9L4L zeYcmt(aSXh=z(dgmWS&dkMb{Xx$n0|-L{^^L%|sBDc?kJ50nkWxu;l~PcawENtGmS zeF@D!|1oam(*vxEgM;JStiAmZk*9CNoJUqo;xO7|7+4xkmJ!5kR};@KC!n|Qk30X< zCVvpo&&MGZ@}k~?EUm0m4winHLi$gXUV>VEHD)-NTkLuM)urQERGff3%|N6Vk+e{X zL*a}1qA&53s02Bd)ue$Z6QXgpX09^@gwHvhkJi}A$^}4AOJTe_qTzZY$Ki6-P8#kU z6qd9WH5N;c(daktpUB;*Dw}kR8BO3^E*t8Sinnuvpmh8Bfx`y4k_Q+$+i*=MOhQ5P zjHO8AW=dLMX9(9}8K6~rG_h8)cpy8`GTXsCVN zp_rP1ubBp89=$J7K^cY^6iT0zz*CmkV`%!78~%|8_p)@|_(WZE=i6{2WCph--$2BD zO{P^%e#|9Y+eCVR6<=4qR0Tt&>nY^hKt0^XK;SSRX$ouQx{oc76 z6+8d$m5SZB3gG}W;J3a;&f)zzq6`&NOzl1}^@zq#JSZlG$4$|}W!O>vM(`|&!Cr2N z{GKz%d|`&%HA>{Np!MCh+J|8efC1zCqKUig;#>3z>KiyDDA zBu;-nsScjfVVRhu5Rmp`QD$bQ0=W8aPq=Q$3;Oz$*e`gWV4=8bY17yLJm|X7g-_)x z`pm~vMPpX?409s?JZHEd%Q&Q{T8$-o&$T$mc8A$hnv#A5yc zDG2-27)}cwCFm>!IA32)2158AG&8pT`SE$PGkQ;&sAdnu(5C7ceIjXeT%@s|uT@fA zU7bDN=$cad(22QjFVe2w#5X}@~qVW zS5OTZbge$;MW-FG{Y|zx|CzL5C!6+yn|_^~6Z&QATLO{c!&UNo%HB1@TjSbolA@V^ zg+D#{SjmpKGdTb&l?X`W@X8ddDm&Z*ntWM#dC{Vv!8WxWwYKg|Nc#{4CK>koNOP;n ze#9W3mVd5XL?o6IJN#mz-$b_hsdd~+6(G8mcGbnk{+ZZ>PbXrwUD3_YXngB2?gvNu z+<1z(ob0fQU8azWAkTdxl=Z{G_lVHesgz%uv}6Pjq&2aJA($q25!`Yjd3trR^JtK+L7UsbnGe9}1iQO*t#Z?iQlsOuF+ zHJEf25(ys6AAE~&q(=>2TnboPI`9j+b%GAd79-bO`){>qoEY|geLZtpm9f{yEzvT2 zg@{p*5LtNZTSi^I_Pw!jpfiL}$LOV62?iF4X-ro3s96(4+fn{dh>SD|b6BwuuGXig zD^3vpHv0<&4ei#`k47`E?a4V}E?(v25Xv)7$TMoC`({6nVJZcpvwh~QTEX2%l3>8H zXGgK2G$P*-=akCMq`E%$TxN{m9^FTzt-cYgp5wm2cBXdPid*z+X|npO8&TQvPY~B= zXy?n41O=uQCp0>&Z}Yn$&qMv^$8nJF!rh9rYSSgZ7|ZJlPh*>9G%Jt}9p-gj8sii8 zJ%5p^gl6OpppEm{NA^f8siEmiFm?%m6??O*h__v35~v8s`E17uS+EhI&GP%T-MZxGRL~ zdgT$9UwyxnVG*IE4FDQ(%6T}dDE?m{-Mqj%xjM)=+-O_dcYd7csb zP2S^+|FAQP;GX}GQ-Z0gWNPu+v8TANyyX2z?5&5Ir|LwQ64-A?ZddR0$JlgyK}>hH znE8GHl7IxtyqGA@;Prsf$eZ~=<@Fr)j=@@6M>b#Onc)vk_r!DKq+E}I2nB#v`t>8m zU-SrjLLVj76`fz+MVYVj`BqY&@D+q-2hvo?TVLCPB|;rj25fWHGk4En&3jB$+z?Sk zy)w3KOu#Ig!=1Ce`PHQ#0dLPv!F&j&ay+)O%r%@}A0Cp;yZJp-^q{6h-hJwp`+aJ{ zFS;^*`};K|ub?2fR?pJCQNRDNX91?7?^-~=`zW~L4g4&QbAHP$ajw}jz_eJfggve#B);QrvO;FZ$d5zAiJS=8U9CmRm1;LA9(*fdiqs0 znK^U#cr9L5zMu@j*(marg839-mp2kj7RC=_=t_0StdnnW2{w$`s!f6t6m zcq1dE*cD0HncAW8bLQsDyO>EwH(zSH7K<7UC9owWt%^H*ZpU#yLGO`X*Wwv8Z*=2)lMK>n!fEE5dCJ6UILMSJ4A14My;C)cVclZ4}dqFpVwr6|;awm)-u~ z9)I|e0&en1P4_yJUZN>V>AaRT5>BpR0G!}qElDp-^XLt0d8>Le_k~9MD~ja^5}@9{rlSYhK3&(Ua<;!jn}8ORAV+(T&S`d^!l}2 z!2>_Sgkg}bzT$72^$)e|?SUsVQxmkdT;n!DP$8g~!0W+{cPod2aD_;NAqF9k&kynhI)Z7y`qGX`okOroM&$HCJY-;z*B#EGhs6CU%A1R zq3!HE_=XN&cNp0BP)5NwZ>G=ZHbr|}hToE7^nly-D+d7q0Z=(0vTZ@}F!~vH^TAzU zYC6H1uh`{IO$MzuK%Ez1JkN0I!t{$vXSo0|JJ>6Zr`WvOWRgbE6x*Xn4icChb}?E#bvW>+0V_AE8Yf3wP*d>waqW& z^t(X4;Tk@uY_+`b75r=cgv|Wfdr14uL38-yc&nvQdOXoGRJik6ug)+AP|@e=4@qaO z9r*xHtJ=VsmuI>U;J%$194@|p@3dZdJ{;eE`Oivv(ckae` z^{wkBCIUuCA%cOs_uoI6GKZcB<>Vm5?-laCH8l02N=!;BgcN%-iU@0&rlqY+q&tkv zZEd}K{Cw_2no;em-Y)|1WLfIR)mlET59Y|S*|e@_u9tfIXN{fBMiAfyF!g~H5U?J8 znyquRuDM|ylBAnU<~PXXHyHQqciBGm%`8Sg4_rh)M%$)5K5q3mG<~suHj=0K(}dT~ z%m*uA04Q5}ANM~RSNQHL4~;J0uT{M!fXo^C!lKb>&A&KON+B~mHF3B{`E7;7o=;RY zzr+xar>d=3fIA^QGGXQLy7zfaDAjng%+Wyv2pBx9w@X^-u!5bEZ$-X%t#FLeq%9FT zK28E^nIwm2^g~~Em(cz&eF> zw&6JHc3?9HbzqO%M8M%8x#|InNpjZI)J=pQq%#+>gA0tAegWg-Vua7IR`e^1)LBJd zz`a6ZV+8;uXkyYz#|W&!I#3B5qwQ^~!#@i`qw@lJ0ae=BV5La@xAyWpb&hRAGc)5~ zMP=1CSz5Wr)@Pouv9}C88OO%^3^Y;d(B1k*_RFZJctq)PS=%cq=E-_jQ`T?Z^)l6D zOMtQfk;;_U5k8`3QZX|o9ayD}*gk5hPYWEkjV@t*_(s=#>UCMWru{tlz-1mb1~|Yb zJ*gk!y!%Bl4de;_B27L3>;RI*563N1`XZ(zYTE5!zl1m=iW8DKs7E!2QrZ9;Fwd;E z`RjoO6@j;yMa{JMf@2JBn0#)*7IYrozy2$aSFEcn%OWf5W6fS6P(bE%&!C&d>cOD3 z!(QZf)7(r@d*_sjvu`Q*7ze%48Y2Q}*h?dVzkj_0OU-O6tv%R)&aYS{!Q|!noCmGl z4|o4V|L{L#!3SCuv}P_Y!5+;uvOCTlKLQ@4q_V4)X#v#?rcS>vC|zu9;v`Khh1ry2 zz)APwXB*?Og~au|bWDhxDrA}2wcD$o+-6OY})TPS_OI{2QT^Fz_9`($(SLn zg5HDjpx+E1B$x`X8MP6j_>-1nlj)>u=Q1fDxkj+khvc>KY^Pi!HqjjmDvd*bFJJ$T z|1RI>96O*<@m-eE9QtA}^?4o_XBkLGF21~(14_%YWE6(4NJSv|?YC~^4wG>aV?7d^ z&iGNlHRnEv#jv~A$lA=Ia&jTKDif-_dsnVtH0|vr7El|dkz(seWE!<%Yn5zu9`GRI z-JtxA(=Qfj{Ip%COWnQo{8U39(vevJ$|oj%p&waTtE2h0mlas&bxi>fpfa*C8?Er+ z-d-??E;kl9RR3S5E4)8v>gyXIW5$B_!PPa&rdHuA&pW}Ufup1Gm^DG+RULIoKnVhU zCP`5$L+i7URJg4EL=Oz6n|OHzlxQQmR#l4zJTA6E2x-^CSU4#^$~w;~w}=8?Z@-;b zlJ`I*3=p)JQ!KR?86pFWY@ccQma-skHDmJvBv8;|`S{{Kl7NjT-OtbNHJNYqaFYeb zs^^#JFjQPNY_^hq0>A|Xwp(pZar&J0JBfa7I1SBj@oZ8q$z3Xqk7an9@9q^#oOo9Wou8#N-uP{Hx@UI$GSxsu~csAvI3T_g9I+@y^PUXJGj zVkIDf0=y${-ochhF1V%VT7iwUsQlJHuw$M7ZR`X(#Nfq|IdYYi!P5lr zq@;sG0MVi^@1`)=m_94hHH$rayS89uut?%4H0Hi*m&y+wC8UhikAo9bgW(Zwq0=sg zp%@BkvvE{O_evT$-VLrl++Dkf)cY8()-nXSnbBsq-${XgInpG;Sej@qN_rrnFnR(< z@fUnq=|2PtUUbzdZ3w6r4exoX13#V3*YMPx^JwRg2~pNR~J$ z!QfA%0(tb^_V$m;4QHnoIF=WmDBbaNn@kpZ*DJnqF<|Kk1orIT9{w_BKG8rrM#n{g zS=Rd1HYYcC)i(%0n_u4~!*ZKZs+!Y^3nbjy5;)EQoL|n_bnmCDo)$8?huxBy1{NcO zCBbTWcP9spe4m_#&!$9#BUxKPlSMP%5DARiOF5;uu8PS5^{@=Jd6I4Dxo6?zKu$52 zYk2I!LqOdO|39cG@s+2=kYjtjipb7OU(8=FmjM4fEK-TNb8Rg_5YB007Psd%s`y@A z^CKzlXZibcb6ezi)F;Y#@~ySrUd8UK~?m0Xhm#V?C-Q8ogl4it>r(-mTx z83Wp7GXtm$5^fF6F?5JAKVj2%W!E>=V&<+4VcKO-cWG z0eX3c6Z7(T-E5S)H|y5^9L`&2D3!-3mD?4xbeoRmjy{lMmYtrPd++4rba_|=sW_X< zG|^a)3Wq@BOx$tOHL4%xn$d79MI@7KcrGYE8@+#sIreVd96mZ&R^Qre(9V|gJg&K` zE&HQ0sdSEe6hEG{U=NzF@ zKii0(b;orm!GHDccJ8;5++4OS(KK`w(CaO#1qWLk8&V?2zDoZnieJF8@)CW z6&A)+J$<9D1?`x9mAI35S4bS5l9E_*_N#>I8vqR)9K!7cyAh6}OHrUSmijj)Qwbp5 zyI=H7ojGQDLD8DAKhk+hyBIT3CX25ocY|A+3tBJ6wUNLlRifONPG)n2MFGWfRY(pO*jsNY00V z>z|Z`u`kxOuZxXeD>ow2-!3cg_&ia23s+*|OL+*G4OYgA+^ykIa%sIJW6-&4`M8MB zpI&k6ftL&tCzF}Q{O;8SX#)n*S73Jn#p>SzZ}Cf6TH7%Cx37u7n%Txu0xn{w2{uS5 z*h!zjhMYcoPP>@p?xQ%nY%<{=hJ$SFgNWg#zXfz`?C|MUM_}T^5a7^OWq19~@%n+h z0}7ggL{2_{`FxHM?r4;;t<_6P5~QF$PW-@FkOvhWC4BbD8OWl0jcO6Z$*c4)S|%sd zRa!Y%CBI@5iy!IevK30l7f2I=Xr9h$2=&oOgqsC*oSeGgS2Q2RIqs8>6`EthIrDMD z@Jf9vQUPW=EK=;^luTtnbHCK#=~wV1S9x2ZsCK&LLdACornWzj*X4YG4=CEM{6ATp zX-n%qmFwFgaIeZMcX0tFBh0cWMpdAQ|5L%o$1V02+qlQ$-B{9J0y1qT zz%+hunp?qcoI@`yNGRfO=I;u=Z7BfE*1vOlJOHvoMz*jgbY^!t;nq^b+43mcf&gJ# zXVzq-T{aYhjN}#EFnE~&RPa8t!Ot-kNNZ%4`+S`HO4s>VU+&1?5L=z8Rzq~sTV7D8 z*K7Vj{}}=Q*MU}J$i;#=(TX>@nr-5=wQTSO3dB#O_el&VZ>!(2uq^J_vbhoUd8T&{lv0Ieu~ zI#|JDgrLO}Bm=|78-OkJvz(bk2HM#*(}90KF)lx1ji$VPjD|bRogLrNA1G2@X(K1g zSl^l6XGF9}G+eziT$F8rm7@ED)^H9EmhVkWmL-ImlcWynO!nwRQyb`R2lAXM=8<$3 za|fjtY*4pnmz*)&a(b-yiM-!Ug4vRf=+}BhDs;y!>`2bODEb91i2thY8LspbaX=;` zP-q;7h~&JBVr_m3v~R_^-=|Zjd;Jx!eWROXEiz?m(&r#et0z^!8dEgNBHf z{H=clSOU{&BlXUB{)z=`wNB)XlAhk!>#`0mxL^Wt(EVb0pxwj%nyXm(2x3ul40ygv zPydttLZ3L9`2kb~aK=hBoqYEZrL}?7v5zD^PS$-Rn?yZf1e6QK-~jG1Ge0JZ$?{N_8+WHVBW4i-pEJ(}Ps9g_*A=-pBDL>UusIfw zEzO`MG}F96PErOT4RiHc>SfKw{zN_g33ib9in(9*yIHWOFLxGb)eH+vjXldco_ZT5 zWtN3ZquKMYsQ{Yx9~cPylJ=8+o0yz@-vu?&ug0zX2C5_#j?d4r>5;A}h`zSeNeD&I z8HK5r|5i4Nvw|z+HTYg83aUIN=unU&Ff|T)CH}O#MB+rzT|*ftg&A?(w$uV|vuR47 zUCb87|D2;AwgHyPphc)+aE5L!;Z@riJh^6jvS>7Q6zH>|UY3tshY^1YctFS}pqZst z1_eHB9P)AP%pL&Uq(PqxCm(JIrN4KtMldx=RPE=O|HwDKzjt)>uEz?PON%ZqQMQOf z4wd_9v)8=Cb8H#;IY$z_#!Q+}N{#~<8i93BPVPM`{h>*$n~%rAHdw*PrpxmS<&E|6 zB~`Gl?)H_}K)R(wx*JrG z23?TuMwUiG8tD!JDd`SDx=V8D?rx9}knRTkUhn^UzZr&Em|13dfA6X1Jm)#>1*|3q z7j-sfxeh$bRLwKVpW;CWMNj3TaoQHvbeTY8RY#lu4Ou&uX~ad;wqqdlg}{;)nVO^J z3Fh|5aIB11y35K9yakwJ+96TgF9uW@$@wL6goz2+6tPgXqNR%i_>@eebp9a7MdfTN znuYf6V+|Omhexjx8DmVo~qoe|C%-2s6UkmsbVjGjB=}F9=!#xm6o>(q0>;fa?(5Zvtkp zeNz;_UD6Ec$h1x#I+aclV(K&jeSo5vud&*Njn0hM4VN|(3D+dzN`STdz)+(Al!CCq z05<@jkKDDVX1@{yHWNxntZ(S}V2td^sSEy4SDYqjt;AU_7muG^!Lje`QM6zyd3x7~ zW?R8`Z~#B@^8a(I-)et%k;pNO;MnG3zuGnku(Ai-zcYXU2aEUBXnDisnAs)c92-=( zEQ)bQt@znVfYC~kLGzWJLAUxqs_?XYo=UQ*(>Zlc&WZ`NuHU@~mG{z8>4~k~RmwED zy6mxU4YyI?Kdf+yQTPUAW(+GZGQ{Y3Vu-tLvt`_3k)Lv^*W)fPz}IUR)Pmx~`0eE` zrpjzCVxp=%Ut+=l2!C22ZM$AFyK@E#(I}kC{{H@vZILVf43EQxf>|T*OFeBZt<~$3 z4Q0+w1J|EG`-K>|zjstecfmf_Z|nXn_Q(2z_jb9sy7sMOOt#^dVH zlGd@$Ri4G}jnaD!5-S|^Xxyc8MB*tz#=BDC4@-ya>8u~_wVGmO`l-h34?!KcvGD^+ zV;|@aAECT&M+Q7*l({AMu*!ovVY^jRh)SXU!i9)VY5JcLvjBOgy-%5rt)4d|$7rjB zUmo)&CEw5hfInZ@; zeJrcSLWz*2<;lr~5N<1N2O0e`stbrB)wC_hdU^{OJ_IYLTKzWJk86-ixcOYnbREuA ziJ~X@)AqF)Yx5MKe7^3>F@NCbw(yyK;H*#&sm`wOPg{QLTSQ|y&{ z%0(Smw0fMV^Acr`r*n-|sq){>`|L;t0Wq3_goTS&(`(pG&f4ghszcKs4*};G*e~D| zy8)J^h85r6oBEH|v?^%R?d#A$zG|7>?X3#X*s)!-0xo6h0|mx?d=(N8S)v}NpCFHa z8`F{f)O*H81YJF^apnhT14A1Y3_aHM>frPKn}&} z$%;xL2hOiI0E42bQ~0&+Ex+Zv{3O-8T=*B9zFbdJT)m7JSv7bsZn;%$wG^B9T=x2sC9?2K zSzhcpnEXXCxbuLekGg{CC-eW|P|-2}RY&;5*cj>#4`e@P_$;(56d7vLiE8{Xao8cY zbUcRa1_S6xZLK-|H26n#j60b=sU9kWz@;%Yv3kG~keR{w74Y zVzyZBr`D`PT!QPGIq=LqZ1SEIWgc%O$e1R)JH!zdZP8-;EB6Na0}Io1=y>!cd(#{Z zSkGCtvz4`*cY|V6Pm40nis&9K;Gqoxs@r9pRW_0Dr}i+W`6w<{zmGBI`=|{XWu4O& z2g*ZwEktl{p_5nIyi=x!6&|GlW}KF?>eA?HH}22WLW@rq{<6VB|D{MILNrj}o1U71 z^#B&3NdHAHD0}^mq-de!(%4KiRUo&=01=WSdl8*pgG9-*d--OJNBR9u;@si51(rPN zs?BuY3Tc#fX~-@c`PpZaccFg`9V5;V%py>k2m`kJKIZZ2Z1o3D=9f(P`$(r;BxYCIol?f-^k+NZuq zkSnuWZ9})RQdBNAlg>@kOj;;Z%bM0c%Pn5T?`sQp0~@v_))VyC z6Gmo>n-%zRH6``eoj?KUbY zDS_;YNH0WG>={Q?Y+|R|)D-zny6vQKX|Pyd)8HpH8e9Qx$=^{DnOwwQA7?~eD@clb z*YnkKs_AyrW>il~h}S2$UV4eInZRDpgtzi7JismqEoyr%o7tj$-<5Ut^pI_AEC=z;Nqa1|{t;Cz|HF0Mlkm%|vc@ScH#euv z3S3A$suw52rN<0gwav{V9j`y7o76EV(Zm)a*J(X9Dz%9bVr0~RZ+*ZlkY2JKwPLpxXTcY?qc}fWdakBFG12{))+pyvqbb zYgQX5(h4s27n=-&omFY37S&(EkofP!Lv=f|2U~VNH9J?@cFnSZHc)gnONiwqES70= z{%@m&@L!|l%{M^cvbK?0uq7)iE1R&XYjFQ4vYX2sinp}%HT&FvFuSeL2nV7keG{4$fpB7p7N8fz@Mx+1G7SnxvH?I}g%C z1iQZsX0K9wARXA~#?Ne*6qR2s_GpA&y>)Ao5f%uqAfcNPLcc?~ClHpWFMHm#@He~z z405szUz1^I{!aOTt$^sw}$sx zUwg`(YM72`$ch+{K$jr*{SPZx_JH_Xf5M)QIsGV=##A6)NtK=Pz;&h~KjRoME2E@- znJ7i7>UFuimFuVzmsI<%cbBh9ZDSj#j^AO}5)jCGP(0_qx&MBSa*q2Wa#NA0NB00H5wTvDR}ER47t`TV{Gj|T{pPU9T|xO<5T+&A zMhE*jNrceXrz_&?ZNR~u>U=DUPX}2{uF6`S_a0x(GM~TAbcr{urTxddn_d9aBmE2J zxTH6p8Q^~Jn(l)w@Zw{8pCT0sot*De;Hhq;&MdzHCzbF9%c49`4|#VR>)vp3JiDiV zUmcHPAJty+W!li5vI2>t?A)E~)qJANQ_z6&v*w1y?~S7wT^4E3Vy`O~Jpah!@kA97 za0CEOjp+d}F@=>iVa6k=)6?w@14ifeF=RbyBDpUUq(q z-LV78qI>)5QW!O|_ostuZ|-BVg*cyF!ZjP!t3M~+iI3IR11tlV=-=rb&l&IXE*m28 zxy%tPfyo6ct70Iw;?TvanwS+x7H_EqS7Nbtl7FkJZWoJJttqZkm1(Fja$lfY_Ng7m za7d(@OBKT@4elwA?sPA2LCuaFPe_kigrd1EFzJnE@j6ZO0;PBskR9wDAL-8uXdElL zR?GUq%D%ckBo)^Ycj)pq>AHf7kl(#o&$C+A7GT8MIs%^y_~R*`vl+p5oKiwVg)lH| zuhQlxR1lL4wwZ5OoTpW()|0sBrbi7swQrY*l8EndW~Vw1lb=#T9Mvp|C9SA^@8 z0t_GhssWG!O!r2zS*F@WfHQugY-!y^*mO=M;&5H1QtRjbJPt&IzKmt|8$nkID455} zbXzC-orn?*-XDczD&I;=(pbyJ*N9EO|HCx9?i{=F>EWh1mBbtbnnt7l1)9HnBUuzf zqg~o%<3KT&a{|OBxB{a)nr0_{UPZ3I-6pcKABH=sjdONMX~L+NUutq8-JV-}7+2l^ z#U%Z*wGvj@?%t8)*o4X$-_gf}1OwaGDStoGQpj_0>ThD4)2Xj{r|geH_GZG4iE5RM zi2(p?m9Y|4ouW#j;kn0v{P}t7)e7^62X+@P0of`HvKxlutkk{O*z)S{ms4VE!y_P7 zH#Xj=(RsPzUM!bmZ>5=DsQJ_V?X&Vl*t+7>>^Ie={q(HlRKaR5d4c)IuW80EhA1`W z2;OUehTAt9Wxks(SSV}DDC8kfm?~}_Cw6NF!Sh=>cUqZ)F=X_-A@Xt zyz~32DJ3Vc*Hd1AVw>q7@cXF`wHjsW=tb3QLje_gTFmg(t;k;HlaX?kF(#X(J?~`- z(cf5$e@Yi$l1jWz%=D1khHt2msH*2F^Mmt=`1YAu(*~E%_aWw@W5w7ocM{oeP7t8& z6R({s2;zmfK3wF9ZNq7|4$ha*UKfCfD!9pr!(viHf}dx z9oD0s?xXp6&ye26gP|k6O9j40X=7hr{226!)LAlx8|#3A$5<(bW}<=~{_kwwg$e(q z%PRcu)TD5k1;u?ZZ_G3cYt|OAivPnoT*!W{%TTJV49K@ zv*X{<(n~~qbazYVloVKd6|i8;f}yDZcr}e>KQi3&v!R7Ljj4;m&VXAwlG&Oybh}LR zEz_`AB^&pJR^hy*^3xZJ#Z+ zHf#~YP1u#rP}Ji>(C2%ZBZfHT*3&(*iIz-$vM8zJ@nxA7Dh&aZ0%#!X(+p5Wh8z?0 zP^ik+JA~nuA+hKsDun3p*61hNY<~nYfeUDwh}7W?aJPJ5>V+94nkreDJMM-APOnp> zm~bfvN291U{fl_-qRLCTt1HAF7a%;<^{MmQoym+JOe6(t2!*KdDxjC6V{AO-yZ^P* zWWqwHmdqA@A`pf{+5ffS=#{zS2V7KE2i_u==w93Gb`J|Jgu_xhliUa03#tX5>g^XxAtF$Z?V zw=54U=a^8bs}a)+5}uQm2EYQr-0bfxI(JTH3zl)kMj%|pfvG0Di|-H;E6gyfy33*m zy0k&jz(MHc^4aUHw0K#~4pQAd91%7U@r7H>9y#&oT}2v<-NG4G{|=CH{L3c;X8QOt zb6S#%FaSRD7>9x;wqL1G>j{sU*#o!#BDTV0gIYAXQ+q}k@^ZQCGZVP?H8b11=`vT@ zAZ*9H5wPHY`&_OF^G5EsoIPl?Hq8$+%+pE8kSV_jrPa+a{F!VI9gHFsjO|ORH9jf} zNDVVM>X~htqjTYF9~O17kJe+WK=X%OMRnU$h;dYCAvxo}KdZM(bERcG>Dm}_H7lun z&ould8>(FX_4>o*UH4%lkl{FUDr{^jYNXhX^QIKTonPJ;*`DH89~PnX_HjLI7|qfs zmagM~$6y@@B;H6Qyr5xo`-`bY%c_v!F&{|Ho}n{NTr7D;weto+S;MaBeDfg%kQDRn z0A_Ppo7#ZID}*VIR=_;)tnPqbE@kY;qPqO`rRZ7QFQ@UgcOfaXwCUwm z5X5)c?*a)nQ-;U=4rU3K&h1nLxK)7w!@=`sC&N;OswkYzKxcQ)Jijplf|~6WxC`lG zHXfK1{95+3C9N>yClNYA|F@#MYTxHOHexQXpWVTrS_26hVlnb_lN~c<%Lgud!k>oL z12h_0h{DpV>UsKN7ba3*&52X2+LnZP3!<1Bs=G^aKmyXd!$dSmuJBp)TY8Hjw&t46 zE)NG$8QXoYFCV<9QT@3d_1hqc<06T>BFYj~`=eTzbk_X9s7dwr@X-EXZ9T!+&sw}wKfEH2MnnvT(_>Sp(eS!2} z+dg=M$tk4IXS~M)S#vO13M~k&Pt$dc4K?o$OfcIv%)`vsYr0<|TYJd}*GGh!zp5|w zK2GXspWVM)XrFy~=<%fO_l(AN)G^zR;m)d{E#iAh&DGjeDo{0MV-T>{(_x2CBFAEnGaghv(Oh0^(d+6b7 z@e3p7bYCX&r$W`6nVGRW{V83ZDvsN-0jP~&A!;-2=tJ_Tr`f7;LIOw9EfuuJguVLU z%HP|V;mzIM+LV4@W34vlhW_>G@d2@(-B{<|38nK;v(29hEsIvEGr5G5S=kojr!71+ zt;9C*T`WWxk>7l84DWC7nP~FrFWxMAbCQ@1LCybgX<4^2oymPW`7;a`Zm#%_l2t0t z3_*N+#k{mplM+3!JoB@~49$Lj&x`!C(|#p;4SgNaRrTFteN7ySUT8y4yO*4KvE!fT z%8|rd*U$zQ-`y!fvd48#Bqec?xXz*(D^Ew%ryxihCkl7_EUiWCp&n;jf3Q~9YWOk= z3k69?8!V(en|ypQb#?!cw7rFpi#O$K+8r+WP_&$IWNB(dSd088l80~b|?U$ZF5J^F%XB@aB!nv7+PAc{yjrf&VxETPC5(Rd?_~c zF{?ea4g!hM+yo5|k`+x4Hlxpz2bB>IE=4b)%lbE8|Fyj z?Y8BSiJxs=qc)4P0QPghI^<>Oe~Htw^+z4@qV9VZBGV)Diok~2m!3qyugM`M4VjCE z<&IPX2an9j<6x!^de4?OHFL(z6>s{ak|#?`3Fa0A5E3qX{w#HdBZMG^JoEg~HZ>JM z5%mN|WUWGr&8a6`8asZVI=#1NgT=pHL@_Twb;ky?oPg}c%}fGwP1OuaEPGxN6Jz{- zV5Xuk=5*3($V7qkQJQt@(|(hZhpIdzOI2*`bvi1A6kSoMl*P~OymDlpM1(uiaE= zO?YA(53Ufkd*tY(?5a^(chVH1)_y;D)B{n=Ju~eN&RpDwkPwFeqH&r2lxNlH>DJ_e z&g98M-|UR7kOUVp`{iiT6t7O;Jka#D|Ct1o^I!%WrHS>kxV3!NX1kKdcX zhCjy6uxp#KuZN`s66vO?X0)ASTu3UUrm~DrmIk7{4wBY@4tg_U0h_0(}WPrdDq5NUzeY2l1-UHp*q1*=fqkkw9z)b#~o5lCudN zA~Afng}u;=zf}a@oy9(|CKhK!zSQge9Xkt>g(T*-$G%T~?`Z}|4v(*jAuP1C2Xy@R zM+J|rLvea5Yag0iD?XC3r~R@F{yxM!#@=FW{SqNOTln^sYqxM;&;GtLq-}H1)~R%O ze4IUQP!%6#ooV8` z_Vt9nGd(>gN5-So5ur0<3#fJsHiB*Mk4O{tOUEjiV$Zt>so($^cq7&i6ozM(wpS_M z#yv6w&rO6L;~|Nk``rB{`sW}%f}YQ57yN7b{>IuqC*cD6iY-9rA}k1H5<(sa)MukPGJuFlw<6@ zmE~?bSg+V>2Ygyby_UyF^YO20HR6nORg=jzmlt-IG?A577G9%TbC=nTWk9^qaj+Nq z@Yla1)Eo=;Q3z?8V$HQbFIfB2-q-JAPqinU<92}}Dd`}_cvC&F%la*2h7YR^*KN|KUAqQL>NMV0=YHkv{?f$#+v z>p?@%xMRwt2l;R|?9DT9Wp}?&4%|w8ant6;& z(ge5VLs0k}dzc&bSO}Fa)*IjyD~)?8W0p*IqBL{G4pOX&ftqwbl*fo+S)Q;xqW8dw zn-z1xE&)znMzASX>p0wxMV1_^?b{i#d$uhaSz0Q;LuM+!p3?$y5uB2@w>H9A#l0mhMV)g-M8|jOe5@B!u{^L zCUdz5Su|HeYqaHW3VW3-qEcVd#Ucn1O#?`+L1LiubP*DLmC0_k!L zi{uj%#Se1Wgbz6GP%n>}CoZPs`vQafRu__~xC_2q8J z*N3$icf^I$cwIEVXLmCV34=G)jUf|DXBAEjeeG9@$?rg9=TR_Zar7J+!U)gDH{7Cki8tQ;RVN-@a*|a zzEnrllQhfL)P9pH24tS=vtNm=_pPgk%Yv>C7nH8cY@M!fl(~1+w<0mNqSChDDWLy* z3jWTWH6Zx$s~yOVx-uyrhyjX- zdJnU9e?MRrz1HK>+GS>EKCx?BGM5s^GTfheffG^}3+FW(`M6A8JpE;@C9_biji)Uy zlHyI{3dH6IA|xC_@?&8ae^YCh+(04DIBHwAl!u=K!7+QuG3rO>k>|OWffK>?Dv1(2 zYJUd%b9W$DRSaH##9P5&K>GK!{Mh2?bFg~Nn~Lr)Zakq|&41|1tV*FVF}^Es*?69( zYpQ+lDVHLC(6sq{;s+Y*9f=<&#_mr6=c*SRRIO~2tee(fDmGtc%LJSK6cZi(Y8Z)- zYSnGjt`0V7tyyYqZ7Tv@!qtbXA8#7o{f+eyhhbXI$oBPh{>817jB|#)qiZB_A@?u) zAXx+s=zxt~?^m+Z&tUwNev_ifI>TuCP`MXIl_W&Oqsm1I($M)dVuYL>_v|v|@t`-f zj`EjQegsuXsa8{R%u32&B@cx{Cd^d|GcH#YM)9a=Yhi2alUh|gQFTWKFZbBq3x)&^ z1|uFq#a3w5-PMt{3^4)ncW#rqZ)+Ob@5*JWcy^e{QOK}zX(hPHBG3Xmo6?Vp$C(Zt zuYPP3Y!2jJe)`@R zMPzJ6lS6ogVL;q=B^o|GeOc|HPDISb*>G}6L=)0DOD(Q1@(vAN+>GL}= zFe06!#a2H@c1OyaJYwZ0Ib+;r%M>1&XTLeX1K~&J`yHT}Z(oI!JrpC?YTTC3#sj_g zeOF^_zF&Xdq+cFG*3xr56sb)A=;1MzXXvDum;~1x;GY|*X{?W0r=~vb2v+J2eON4$EIy9_%nt{au}?<|F>5Ij9}T=e+k2ehGHIom%C_8YjP= zGMqS&@vzW-z$zs%&kL{kwc{jN!NRf=>IWNoIX|&{K4Q&-;o&RT+qPqcD7zJNL-K8M zCzv;HS!Sl{QS`)kNuN#?-PA=usE7vgV`Uj?cQ=vET)v#+4d~s%>kmxrZ`2xs zq5N68347E72eT|TFjyQ{j0&d`rPIg8yG*)hiVYNR_WfntlkQ(t&pCIWcRkoBUDz8nv405hYKk<$d zSa``eV0$Z(wqKW!E;m>8NO^FO?8$c%;BZn}a-g)DC4$?j4rx?=7<@U{4=mGYb+{rsJa^HQ_E5%6Z0@94IWD z7Sp}7z;qE%(8V}~aI7X!^&0eugRR`=ZW#7@1frhoROp9l)~)f)z+r>A6PP_c&K@hH zgF5&1l@2M{L$nM7&s_BmO!y>83g}ou60ng4VCVK#gxRr(wzclW?W>59paDg=TQecs`&hMSnG6vKp(`?v+(8)?%B>NLwTNumq3?F?Dr|K}y5} z$0FTV+&@fkOHsI`<_Po(es(KHFPNGwnPk3YTOJ<453w2Ln;%Rz z8+OQWFlAo)TjvD018Xi%>T)NzFOif!n1X`3VBGVQcbUec6nW(6zJm8vPwkj=D^)`F z_9#&~UznfpP!E^gFx>St@}^sj@yF*vL+R89zSQ&%Ub=5=<-3`@r%aP_+>_umlp}K0 z-nrQp#ZXtbzdC$Y2z^&>n(J*U8`1G+se;)8)<*d#2eJ6sh8ZJllonW&u#_|He=O_e z(6{VR8G&@kO08d>)aa@fp5huf>!+1soMdL(~mY!Uu zi7D3Lo2HWi#tQ~@IXECN`_H@`NP+K)0}LiIbglea z^A=wIF!@r7V)%_Pdl~%8o)aq*6Uc@O=38)1PIJ_cdR%_#^vvl1?L+1a?`P{*D^@2A zlUS1pAPY)You}-pr&gX%)+kJjVc6j2q6rUu$B_696kO1MW!Jkmte^X3cmNwEcA$ z7&c-}9||?>ta#rpSsDSY+#>UsC~Yl%nfw^hbdlbZs(94Bd2~6h@fJm$cS6BX8tU#P zBkRjXAr1q*jA*?P5)Cf<=fDIPy51<`7vFwOr05G2za;hjwU-zynlHc}&aZwrjZ>xG zDss*;$VRpx@)sBV=bUg+3@B~Vgl=B(@=~n!L_C3AoKVMHy|&(mKY z^RSE&)h^wRX*f$4vX6vQ6NMSNxM&XWZwEPv6uX*#*wq5 zRDzRT`-4fNtKZwzUhg8Cu6Vg34jx9V57u}*?kH8K#f&91uR+>0oSy(Q?G`~+#G|j@3%-pp>{lUg&58VdF z^Q)01=BM!!#z88?!)D60JF0+29@uLOR`EZM(GL5PRiB)I@4g5nz3(=xxur#edtVIFW}chs|;#^yq&f(=RXFbm`y73e4u%*v>f<)mx1bGzAh zzO+itrF%0ry+W(uJ4A^WC3GuYVAq-Vn;&*<4bkXiSk+>FX2Hml_|*960HmTWQKC`{ z*GxFcltjBkpIH@Nl`H4)2*^SO%jABRp%1g0(^(|#K(&>xkxk~sX*r7B?J@pFm>UxF zR53?cqB^3b$_?I0`^zpqHU_O9@rSdby!&cfaFE0OOujB0dJpIT{P>F!-lu$xk zAf4#&;hm_7C962@@Bf(`ZL}2X!(dc2Pbv?i7gyRVY@PPuVKt`tXbFQ~L7L1m?zy}O zXOtCjgQkVCStZ}JLwUDNq<7NLOX~lQD$MZ}luusP>k^El}Eam$Rp$@ELz#dHE z=`|&9(=!$=n|&NjU#C>i1hx38)Yfza>js(m(8!28OS87{C@CI}L@*kH#$DSezsAU@ z^{0aXV)JeC*hrJz0HQkl30M1`L;mf=xH_1ZK~=)+(KZV8g8eG8c#gGURBUYxfStrf zM>E}j@zTCh2Y8wK9i#t)8IT!bLQ!(RX!lyC5ZP;89)nQ8 zYCZoZi~Vy0TB+t<2t$2;;CLk~5ytCWZSD3ElNZALUk296K+?K8|K10`VJV|#Z@PHH zAisd#gI~4HRa^TzEV+$pB8}j0`R5fex3o0&tZ8$z4oC(f_%^4iJNFq4o9Q|ko66ov z+k{)b^piA3T&utV$Ky+eom-c1lW*V!u=fomLJ6sUc3en|bnW&7z%jT51@}Ua&1PR3 zf!xU=mXWjsM^aVpfQizA&yy0`Xk)RH=-+$08az>=5HF6DmhR{+7Yjm z9YAG05R^-apEb%I+OfG$iGLt#j|_N9B~bnfGgy@nc2JNR9VQUD8ZrmOfPB5J}+C1 zc$v_L+{_%yssq404NY5cOh6F^%!1G)4!SMVO}eT_#^{%KGN9h(e#;vdaaH~fl5X-~ zaR>Szk4d|PK`Oxc-z+=iEutV@sguBg+F4+amA$wbN_Jw|9O3Prq?fI*=mPf@}Hjy=yj7{2+yIQ z{dhdSiOfzD8r%u;hq35xD5azDwFrscY;>Q%>5Xc^wC~9YH6q(lSrJNnvEykbrkjli zRviaeuH%E|WPZ{f+oL|@paAf_KJ_Omr-#6Js|1__VlGYEN@|EP&Ft5^FlnOcz}{D9 zXJ=&&O~G8bh}J_PGqe5ZWk^&YpGM0IyJJz`(mtZdHLX#~ap0$5yBKkVK6(DmcX#g3^d*|?aigmROv^>TpgJ}~gIQ1q9BDxqW5 z{@0STP;M#0GxuRK3Fyh#{@jgtRh8_*nZrsy2UBHbDp*nf%bZNJoI}>5)K1W1H1u4| zdt-htPN0|sZ-pmW8rZj-A|=qF_y}fKvS@j_jShNWq>2^iI<-*HwZ#uQ0`zxr3IivQ zkD;j+MYJaKXAkXyr{xP3oMkhp>m#tNcw3-DmrJW^2_?t)J)>MWXgX^`KX)S%5sg3~ z9D29kdrK=nY2rgTH5Zf-@$4AK2bgQJ)mzVE3+Qo8rQDwLID0es{er$uSv(uTiNUuz z0(gwj%}<)YInTwc&#Ha#P>y`wcR z?Z0S;*>rNKhNeV{E1v*H0betUot(3}F?sN76b zvUO5bFpsPT=5q@_9Vl}SgE7CV^(hUjMfXf)Nj=*kKbRMisS=^(%SLb0i3Sh(;I!wuKl}1p6_6XF2=!WZu9<(FkJ$aJsJp8ctNi& zb+8Ji3A_Gwt%8rXgX%swKlbn_&eLDS=#K~v<*w3W^*!9{1}zb)bOl|GH_V7O1HlUM z%P(ldLghqBJNII8CGlQv4$ILbQ+AOE5==C+!I?cQCP5DhTo>2P_#>CHCp;sJGcZ00 zB}OD!(GqKast`l!{{jHL+&Ti2LuU>2^*0go^Er?O%J5Jcvi?Bxn1tD+=vedp665#D z^5d1dgd4fAwse(L8ivowL5dqP45|}lx|~r#dfUy@)2UiIjZ}d(@1HPqlPs4!xp1eJ zoq&moD@j@?hRyS&nAxe8op)9m9GDsRVE8Z8QiPV|s3h~9H@oAL6RhrDkm`c&fy7!V zau%X5{Twp(5t+smzQpH34Fa#Day3F|&X~NLuD<@;Lba}w4acOEl(t>VnK7%+3`1O% zb9=^yfv|0%-$JZb{lc(tdn4P)!vk!4$ks}k55Q2i_Zhpa06r*b3Nd2NhcmGbifn$k(fK6_H$AvA8iPVCThVdYof1A7V?TjO# z!Jo=w7V)tQo)qja|JUGG$nYcwR(loa;or{Y-;SO#Tz~iwV1W1zp5dE4r#nJux1&`v z#$h}_fFyECph#VS5-hUq#@-Ap_7lZyd5MLHe%s1Q(bgn;oYz{bR7Vg24q+KR+#+9%K3>6T3fnI== z36k#a%o^5#Olkd9yWY?5myHy~MJym0&K_q<8D>BaLPYd~pcvN8(dw$q$Cp=6rYzAfui{4z78g_dwr#J3h^pQ_ z*J_fGJ>aJGe3c%#MdbVpgHsjh#<;THRpD2|4-5v&(y|pOPcl>>J)sQ8myg+2Azn02 zFZ%@x(>yhr0Gj@SS`DbcW-+z9;No-3IL<=L_q0eYI6N33;5;S&XRU_H%K@vg;n3(O zB+iLO9}!De^AeHb74qTcDTE;m1AR!cnudK0^~ub=yGYK%!gvI`Lq;0A{U!`eymJ!C z9{XA$BUueD`*SC6Z4{E*hp}8lOOJr3NFRPlTHZj@C*3(B9Id)LWFR3z$SywCUsa+o zR=&TMrB-Rc6((i!^y2pC*g@YmJ>iO0RVsQ`s59v#Nrm=`7~yzXaE}qU=S8u8w`S|D zdh^AM?)9erZ_}y0k8e0T!-U)H9Cv?>=UjK|-%H5J%dheIobgq{y{_Ml3SW_fE%3-7 znOp~q?okBDnjPw&tskBgt(R7RP)id&yL+|Hsy>4JKE`Q{68&>_w6RdzgtOc`;8$f# z9rm+l<0CpD4kufZd?KE3;Rx!7vmXPuL>7mY#?&d$`6yU+!q7U!Dl8>FHakITQ#;r% z(Zf}H2u*s7`P!KJb5<9A|Im;yXsU#RQ@~l~MaA37(2qnG$L*r}S4BQSi7x@Rn>gS)JDF1fg@Rp2b`PcB1FWShS7cp%^$uX zwPS;`F}+0KrjQI$?bUup;>yYs2%k-f)I4!Hl>58$feZ}+d+rF!;GnIc#ZHIVjZ&)r zwnTC-tdEM4jNRiE69Nlk4r5>)_{;?_Ewxl<1ww5k z&1-e^EG#8=7@NIrCo_9M3(54G3bW@XtNzZN(A!9Iad7*1Q@ck-6lT2$2naxMs0SI$ zTaoZy+7Re#P*-j`V6n39d1d-|35UVqUN6XkP338$-}ptR=X1b3@%|!bSKgzjo;Q-5 zBX!QX(V;17?}-?c$>K|(99~SfFFnVWVwIOB*T2cF=dpEOz4^)i5>;f_($bO)EP4FU8l z#i*$CL|vDbOq_W_!=;6*%1;1ALRhr~s?{X9N+1ozKN*V5jIPCtDo^2fU-V>|L{RXo z&tx^^_&X@V+U)vSJPVf|7vuQ8@FiOSv^T|*Qds#$6p(^Fp7nW{1z>~u3$i@@CZO%k z&Fz<*Od2PX>o*DtFbtsPz7$wgl)f0yPSw-fix<{y_u!uE=%MS3k)yHL>v6Q)+4_6- z4_0Zy?bsQQOfK2yZkB~*Rot*=-ZpKScR+7~@!{i}RJH9F3TbyxnWCpCv@uTzA^^!? zhfb)@z)_~FOPDnm$2747a;LJ=%+j>;n3^GR5P%kjo}T2Nv!!%7>NIuIC+C>8dFG$m zi6D$i5A_*oOdK!y{{`Ca{}K2JSuENORqAo8YCj-K=L#~|F?A~d;ukg0W_&4EV!Z75?2i${&_C$pEwSXP(m;_2B)|^ly z4SU&%81?L*>TjG&k(DP4Ze5ZgXA6-Pa9ZDxj2RJ0CKQoTAw z1qCA`BgA+a$WgN+)4D{CAvA~j1=-!)BJ0KqJRL}iPs|7X1u_A1ZvHAagE>4~M%c{G zI6~0ta6|T>|I{0b^PRWmsCZun)G6cmSJx-cY0+-Q+bZ7B;gz0${a|Y5)*sWK)o&tm z>lm+_E1!;EdrzZ{wfp#~X!(y$oDR<30DuyR{}&aHjP93Puk2NzA_{XEh=e!*h%4?7 zp>?btFO*Ug51Ql+9D;Kvui$=1@yS_O5@A%Y{p~p-OT4pANXgmg!D&6_fh42B!@^#o zQ{De1Qw9Z;G_pK$at<;TRgY*lwjZ~no7)C1dX1PqrS}y)iwZTOLDlGNa#3pgb^Ze)1Q5u$`1wO$fAu{$utq{e0A)mYcsLa~ z_8WDexbzXIYy3RB8R5R)$^30`5AqAP4EJ4Wx>)I(_x6cLdQ(9!eZgX8ac% zs(5xuZPoBjvR0>ix>z&ty26YEKQwTooSR8}5F5NY@6D!+O35h7W()@U3mLO#qgL&fTGuDC z`Mnh_zx}3Wqr|h5mS3r}xG0IPpSUO&rX8?0W66Bnn4eGX{bi0G+GQ&wIZU^1rlQILZgmfcH1>x} z{6M{g;=PCy%J>P>R0#UZtk>#l`-IMR2g6p^<3AoyZCf9BLE)^XF2P08RXr*aR_=XK z?7CN4cYI*$^K{sZ0Q_nF+ljtMg(UvOOJdxY_MM{C1B^Q|#pP*n^ zLjz=B6W(H>wD3)UbX3##!Q$P*3);Fb@}G8k|HC)~rSsPn{p5Dm&@S_S720FO?4i>j z(!#fa09EayVk9LMCA~F7Vw6dB=l(NSoAyu{p-ZoGVD|BXA*P=Yl(Yu6oMA?ls~=*$oNE7~Wg*!AZ6?lPw~E)*IEgRdVAQ@+&qlY?usaik+2RgjN9aE-p2#rYU`+L# zv%L?`vkS!(q)@ncqboUAc(d&!y7ZcJS^h7inj~H5m}1xyb@AqBoB%DR>PQ@=X!#^0 zjbm^Z2|n=bbCt*^zh^jY4OscGjrWXf-FRb1Z~xQWfL*jZsuj{&AO#A#AYEohf z%+00uycyK**_q6@|MT1HzBAsZ4c;ak7(>k_$Fa)DBkI>37FK_}hH-uH!sRc;c z<%ig!qPZVG9)raVk?TRku(rNFRGm^H@B0l(use4Bq?fW6>?!oiye-TG>mfVtj#{Id zT#f*MX${=Z+In|pdw(orB^(|hdRHy_2-18uBB(@&ygi!POWbmd%=8)T2@V2Z4h`X% zH_4ehmc8fan1u8pa5&HJ>DJq~N`z1Tb05gCXz|gW(KQ_y8_|S9X+BBO1&WD@7w2Zf ze!OjXC&8iF1N=)*4^M#xtCs$svac@(DU55oN|=tIYG)=^b%-}mrA zK`D`x?ruQ@=|&DI-5@EAq>>`t-QA6Jmvnb`NJw|ryZPLEzrS~kGyKP)aGq!H6?4rw zS7A}NzS{#Px<4$Fj@$Dm2Cf@qkt}=Qo&@kDYl=eMvO=ND}IV9!&Eeh z_@6H*4RDMl67T1NN8JF#Y=Us=Plx;6X8dQ}{OHtv6=}w1H14Gx>)%7x8SUW-F4`?&Mql*?w+2F;?%`il zfYnOQh*ruyTe+V~LO+}DEvBbRDk*`0y|Oo3QTyYOulaueaAi_Or}g21&&bH=xaqJd zDE09=wR>$%0Wiix^}q!2xnG5rq)*`+$%J63SgG@txo_U{wi=bkT7YiUp%-~g@_>z&G z>*M(Bzr zT|0k==SzH5fNbvXGXlsUNQg94oFZr&(3SYz2u@E=;a_-yP|yuF>as}5%7QY@8L-=? zkB26|xx>0Uyv3&rMqFBO!uWA>&)-?{<9gb9wG9r?+fCB;UQ|j3g@8jT`>-y1G-pPU zXM}f4hpzZ$W>_MbQxR7SOxL@ZpjX31j}(bqs64tyEpv5efd(%B#pbmxB$k0kx+AcY zj5wC8(^Nh=0_|S-@K)A6PyenRTfOJT`zDLVTog8(sJbL8R9OmhqCvZV zBGm0Fn;7t)@cxC$VObzg$-yHr2=w`c?kCiBpx~4cA)1KrN+Ld5h+k5|hi_GFIPmOI8*z$I!DrUJy3x z04*?7m0u*{<4jjh{I1`4K0Bba)&dMwU*vnBNHtjEI3g@^ePTl4H?v!vpXMMfs3#3ea#<%BGP)Ht^!bE2q2$-v@kZp zJ%gFpm0q`@%L&ykA&9cUtZ@zD;*#D@^evTe(Vz|q{i9pVM4gZ(H~cCgtk1+Sk#V~yUje{F+6%x5;J7NZvO7!3uxboMIn4~evrjXl8 zlQMDklu%@3)CzO6y%ee)>&IH)(f+>;bSf4<}C>ff57Y;#pl@?$OlL6!P~4 zgjz;QNDeH_^wK+iD+lO0%F0v6gH{ia<;Mrm42m{hF1`E|g_AJ&rn<%|Z8T3`SNF|N z$k*ew@vEzD{veGSH}`MLuj~+q4btM5rW}<34xZtZrO?i#sKmUyr@# zYD3~xmcLw}0pvN{>_E`4s%#rO=*CKM`hnr)XnBbnn$yj>Cjd1V>RD71U-mj%>e-`| zcbD@styo1Ov=pI%<{9BX)~y&>IO;>JF?ZTo(JGqKUKm`70_^O|B-Zw>BY)~42&%rq zcbvwsjwID?)?OvgztKf)BN$4eyET8eEsZu;0N;~&^NplvMIo_vFH4jBsDS~vHQ3C} ze&^?}y)?VU)YR$@dhtf7R)I&MAIZV&&v+61QNT2ty3n?zN3RQ3MuLZ>vhRFfSSeae z8x(>k>6n_d*#)x3qBAFIVMa*5IG5Q%s58R ze@I%Sr?Y=zibX^5WnpD~CMx%$T2@I36A^Cj@bI!xM`_+@F>Pxc(F(NCy$0w2FPfRn zUl~fKT|f0b)Rjq!6DgkhePD@pd%Nf{=X}WfyI5lvhfrGA#s*ISc7FbK*f4QUmQI5M z@sGQ1=0Ezx&d+RZ$3IxF!DfsatI#UbBTI-y!c~iStPrUjtxc#Mrgs&qy4AN35sOIZFiNK5o%#_tTjjL>1Iz;81IH3f5s0nHdT|GEp zT05>iGIK;_@a`|pqM(K=enOYVI}G$bwT1OW;18!^{!-mze+FYGkuV44Uc&RWFa|Bw#32qiE^q-*q5@? z@*2kM^WSh7brC=3QLr(B%(FU?59e|cnc6lq#Qwww6w$*R+(Zis9bOS8E^r_MTVt%f z+6A-ZtzG^KcaNA?e_~KBYfcgUK+t~tXB;4XGfPW*5eqm~>d#e5ex-k!@hp(hv$MnW z7tu4GeKjI078(2x*B;DI!KYJCu+Qyn9L=WD4iPg>)5Tn2HBWA8UjiPq5Tj`!ecWTR zG!6~!ob@rUtcfRd^@(TvqtTrgA2Tm|0ql!o`}}} z5C}9rBiLt{zvxE}*5xqj|8e4xXsk~Y7?#CYrpEB5zU$M47nc}Q?C#m9<$@Fm1}}5~ z*=ggIs7ANgXG5DNJ}QTx^yRU|0V)-fPLz_Zbi%ci`Ll>X)qMQftr+}``32O!ZKlH-QczgOH_~sb4*%XUq4wQ8x_%e z#GGBOxNF2XORg~Am|Y3>nYEWH;S`lSYkgMDXObDHXW{g2$k{af^&Qc}?T<$*ajMAV z=7*hR=P#>- z(t*xN?dhfpkt#$ilNdxtI3*()GN&WdsyK~pQ?SOPcfJ^PJ-ARXBQwPG>|UBOrJw33}U!M1kYFuP6B&y2!$)2W#oOZmTIJ{*jAQE9^czD|C68l zhMPE{FARPTiJ6jxyAy{$yCELUac1)+iS|t-110s#UQx^33{HQgcpFqpBz4bqx_Hn! z5ItROFiSmc7MnOrb^}9Yk5-vvMW(|cmR;k&&n;Q` z@i0uhI+k4{M>ByIN{f&fO^}Sm!>P%`=ydh0PSqU$`06Dna{NTdz#<{u z{xWrMD0Hu>v?sCW?vTc5cP7w)jryy+gw4Cj2wBY2eik*=@6ReKK5}mnjxOP&2w~Fp zqRft=$VtIgc4w(F;OqqYm1moGXQ_~-5W~^uh9L0!$b^Kah9K;|1cd_jedu5!i(2PkJ=5Khk>i=3;4igYW0h4uBJ!OI>xC{2;!l<-~P&D6;SYO{-vn8c_ zF!2)Tl3zmHzw>}@Kg6iQ`*QgaVrHfW`%DfPp%MdnA!G&HZB?Q6>ngH?10t|Q^!9(spKsutdc|7d9@mDS3YnBmSmS6n#MHnQlQd3fl?aF- zyb}Bb`M$c33`k7>)7~tQ?S7}FoaKBi8h*Lwe%|i4zB8%L?!h3BE*Wz$&4)IQTD&sB z!oup~kSSgC2UH5U^HQi@{Qt2KK7P*TH%!wp5x0my8^w=j9}^X%S02Sdc^$k;3S{vj z_`cM@*~IXb{2hb13x(8U{urIPLA{yO*dapz}8;h-EHW>%_MGV6BHveE*ln?a1@8 zOyw3qF}el@GWrSg%eybfb)haO06kLqrP;c^6f`vpP zJVYSyf^vfBHIc!n@gDI)O8^*cU9Dla_?4Bh6crb*P8Dl_kxR%~Z1z|G>djfBdfaW5 zsgok7nQ-MTI{?`AM3LmZDp7$Kj#`XpwfYrV zU%!cxgZJc`c5g4~_k-KBV6o@dE<|9DNO#!qRv9Rt<@3D&C^tK+)_BzR1?+C_C@g9A z?T;I^K=Q$b^^7NlJl+EjA3{#LX=Vwh)u!z0w89nZG~gFD(sW_QYL+ z$Zq1)PH!YxJ*$!+O-rP@h3A#(h#7Kev#=MJKZzfXsD_d_1F*GKJ30fm!iHl(Z>NQc zXeg3N{MqKjk%5V6Ei(0v0{lR2#|^9}R4)Y4&HY2fZmC|-o()#$WF^<=FM1a>g_5mU z+_Nl{ixy%LBn}ZGj)TG^ENUZr&VnsaEBEu$SX{Lcr~x09 zVpkLie93>8a2}u^a!j#JmR-VsDR+AAbi-A`R@iyWk*TSuP=mX^{^<%h(>H!EIzSgc zKryy$_fZ7A_Ub`VG|6)HR=-;6ekTWsqVnhT`ZT6G1D|VZw>CDj!8HXWsSaQmU?MCx zU4hmZ(UJ6l`X=3usy&Z_Dj_J%dyqMNxKphANDlKU^U+0L{~QM3P22i9Tc05oH@BK3 znObHzVCMg>GUEnwmn*QiD|9P`{DGfYyyF^@aIekGFP3PcH z9o8!a(iXj6C)xLhYwF|Zl16vgMK|P2Yy7fN9HLYgf^mNn^R4RR_LfIdZMSPfFi;z} zU|WhsSO-(71!HhL8FF$z9v?p553e39S~TA5yuX`%yipOS(*NLKj(&S9z0lGE_B=Jj zB{~yeGr1t9e;G~6 zuE!{l=1m1WtRk2^gAc&*0D5M2mDqBP53H7k97jXgSPEwxWia0t4!PJ=Lvt&P+7RN8o$ui$<=F83SQN6aC@8lacrM(a+=zOyM^|^9 z7t3Bnhs5P?K9;C6mV@9ChVg$hneed@z(jqi=7keJir)^Ds0OSXfn{uwWbDXIeZuHB zfBl_Ve|z=h8A#$e}26 zE3Muw#-d7>l_frQ;l&r67<8eR4@&itAO|eBI8oMXs-1Jr#V8J{x=uZ7g9>g{4QKaz z*Ha6G7e7DcG1^Y<+TV3QUP-&GVFZ3Z?hIYq&P^3yjTb0WZKE$~^j&_uKV0kPZ}xX- zeg+|2eFbs5{MHgo{O}bn_3^IzC_H!b*!+fIrO-HkL90O^mH= z=yS-_^dS&1!ve_j=>AYgH2u@4>w6`O)rRGJw51+EpWDY-hvObeEOQh=ce$gtqp|9WW6!YI{WyQr^eSkE!HQQ{A}5cM$-#0^2Z zWf00*2GoG>m7lu0x+bh#{@~YsKhBu80A4X8hG3-)@cBBc$Aw+xX40znI^7!PK3UMY z-)VuYEc!aDj#Diue45cokk(qfoCWjfwT8+SD$|OHrMiE z-`i=b(!vx6(Tq8<2f%OXH*99WyOtr*yP~~6?=`1oWZve$p3MPT_Flmcu6z!*OgARv z?phjG=!#^`I&2;)CIsqxae*0UhN=S;(QJu-!0=VBM3#@DuDGP+Iix_TGindG=&Y6o zWPbc}b*}U12x9if<1YN^V}MHE(qO8KQ>+2l5grzE!t~YpDQ#50bDrW3{ELRjS)j52 z-q#Ke>~e+CpMo?+_w%tnqkQUCs`Oy23}8&UZp9Um932|YFF+KPtM79zKfIpD65V!c z0-SNkCptpGCL*5iL8go-35cH&lHekGxNI1p??mWcVQbsm|G;CULYIKq(>~j!(TJC#5RY~~~wn0^H zr5fNK&nAdAULf*wGsBgEAxV&_hWh@4lTzP=Kbv59e|bXo|B7s6GbdYH;VU~B@IMEs8nIgXBh%IJt{N2!zoy(%WR(~Q^G&fGj~_>4*nU= z)&VF_+uJ0p@#A^Qq2!5+WfR}1YT-Pah{sLy^Asg!78$=;nz3ET6=FevBMC&Dh)0L8 z_4BLX7bE5e`Yv}LPOk0u*gf((%>)qle;~S_w3l=mye-D;YF=I*CTMg+Jimd5kf1^m z24PLB1e=u73P{-!7w4ZHe@D*DGzkh8Evu;sbaAWLeKYhb#SGp0)ol`rQuu)241OKwy}ow{TrpFM_ylvH#ImpZnDk6uv@1xTcRm0 z)a?V)U7eg9=IV46TH^<%MpXT2oP_WW5#K|kM_$>>1nu@@?jOERt|-6Tv!&1Bz2~we zp8tFR8k&Ym+S;rSZ~{ob`L04|FE7bwmO~*B)AuB)FVX$S;a?O8?Cv|HB{&`ZLHx9w zDpJ8SdTJj((j^hT6E0N%4?7dt=6*Ki1GR*J`YLQ##VMp4&>AGN$wG)zcO`~*-I^zT z(GNttu$RWR&qk)*xI4%SXBM$bpt;=;h=xX@d}?04gU^T~07bn>8A36DV5#Q{|ZF zYEE6B+9iHf@B!5e;eKGO9~o9JGPCu_2X$X&dI*o^&Llmk)<6+5Jg*z&X69sloTTWw z?K|GxIcS?{Zd*jWVNRri)mew#KvG;ry| z&~R!*IkWl#`2BPFaKk$c(p7XS*XUAd(EJy~z&SeynaAFBdr&+8Eahqyo-LkLgn=D- zv*c9K(h_P@=XE3wYwV%)+5!V&bDjymp)iF9OVX!A`^tAV@-lX*GD0I;p7%QwTx(jv zqcG&;`We{f6Ab9#kTmi}I8UsOKZoiEp4g?BDZ1!rqIF#}qu9)=-Nz>z91wxLO9N$V zu5Bn1^PAcGZW*c4BVmdCv}V6JU}Y5^IXZx-&Pp|P-X=qu4}yz^ABoEBlWHGylWTw> zPU5Nqu?h)HmC(R|T_yf+tmY8VxkM>lM6#PxCk|$3fc6#`xMfV>>$RzGHPFK?lVijy zffKDO!aQh_;(}qak7o$*}yT{&QKgs(~Q%qA7DcF`88}T3uB~)l`}_ek^*SvQpAG zgS_z-eeJPVJDutKW}YvQf&yT`HW`q{*z$hv5;oye6qS25*b5mmr>%*k)oU62mq@6T zseusD(y7K?(n`t(325)45qpd->)n3M!nUnGl;mP9IXL{X>(XSO!DFE(_b016E)^kF z`^6&gXl)>0#o)T_U5%NCLAksjMT(IwQmA$03bv2^_49YH1@sqGsMy+8Cf2sRPX|{f zvI2@CTbW z*=byk@x>$=A6$n)KM{U3xel*nH@}3&Y-yzTbWlI0!+06?aEXdXc>g?XWeyscpFW03K5 z0*gjS9MFLN-x%E?=;4ICekDdKCkyI;Pw{mC1iKt&ZL$P-a`Ik-K8`=eDjso4XMJYR zx`xYm+$2yL-XP_`p;^po%JJnzGTK{>%(-D^(Q$vhCD^7$v;Jq$_SYPxOd44L1z411 ziB#$u3d(Kp7OF;HibOGqCVT-DTqKl8<<35H;1YanQF`{qtH5EJw^;cdO)SV3KLxNX z;)CxMYJdE_BZkjPqk%#gVc$Bdc158OT1`3p_Y@Ta9}H?7@y9HM3h4; zhvDAgr5htv9h~PZ@L-4;+Vj<>%b1oASGtmScduF|-7|=@%}S1lo1T%Iih_!gX_^_t zh@6d8+(n(N#{~Vga}?(96~DWgMr?GMl@C|obQEE<=yUtX_AbON;fuq$=!@fs|CfL? zMd=A3dM*OfNc6P!maEw5J!ZxP`v5!^0r2RPP{aqLLgaTp8(Tu;eeZ^iPlT2M&PQDN znlt$Yr>e;SKN>nDrG=gOxeya2U%m87Tu0|7qidK;0`oxOd zu?-LS!OMWa63*yanEJaG1UCZe8RT0 z$PIx-Bb@EQfVblRKRkW)Lpg$F5Ri9k;v0r>7zkJqz&Lg?Ft1L3171^0+EX0FKDF^a zn`d(u3grs?)*qQ)$)52AI++&@^!`KiT#-jg?)+uP@vb~A@~xw6rK8b{2PcI>rR)Xd zF?}FwE8K!mmvBfq9DAzvj_uq)l`RFykik@aHFr+3Ks%)#Y_>2Gk?D)~gPOzAQ zYUj%{ClgDjqh3EZ+ElYGPWRMEOCmG=Y%7@k2f*@wB0o({SwfewnL~q(2Uaj0a z7wK+CD^o|Vcdd-?Tpc!b6oI4mEh4SD!=!@q$t$X^MSYOx>|L?)s{nMKu*ECZ94R~e z(L1lXceAeq!NMZWUlVx&0+2jKBAGz_qkPN8_3EZ36LFjIHc6{+KTZ$^99Dy|bz@?e z(F>6OzOB`=oHF6;w<42ou}zTUl*AOl3I{J-uv?7k%Ai9xG?)+?+`g9GVMYyVk5BoE zN7z4(9}(&R>>w>>tIzy9pL4tF_ZJQ^`CVWs1XYrV{eRce{ENx9$C-&5=%E28Jhy~- zjH<3E%+7>3bS=riU&G-~4p2lG$tRC5wETDtB$QWrG6A3T#)i)KC+d%%(W6K7pa=Ez z%Ba5>gp%iLu&x>aP206*Zg(IdJ{ksn@$W!xa|J9^D_4BMDE)Uq;QxwJ?CjuxBzM&4 z9mfrkW6?;!2cUDIF2((2hY|JPdcw42ggT4f`Z$v7$h*l2bmIB!HEK2C=#!gP^Q~=usfg(H_+WYa_;|O8h8<>b|kdYG(eLZ!Qp)wFYB1$*1ZOBlQaN*eR30(pL=ua#&xGnSfBY{l$F*D!)FDUf2%2hTpe z5azHD7t1>Qp7DNcvC?0Sb)frSEnpIfkgpzBW) zGRyZYNEO?90#cJ{6{3<7v4j&abqRy{H)@e+im}0n85uL|w-1da030brmpxyGUORx| zH!}TUU9bbgdDkd&1QO(<t>9RMlzU)3YiA2-KCo zV+w^Nl&yqNa=+`>9vNJF@ELC|B?pn)uR43CPf_TYhWG*Hp#q;V3ld;H!Gt|S^(yFs zq4_ikf2p8Zj!)h2p6ti-m3N@u)pxzuUA1uG@vf^wzzn1VyJ{q|m&)-X=R8`+S|6`H z9~aRUD*dP$UnM$i=V)%TwNokiE7xlov1G-*rID1MB#Ep2(>1r+J(hn`;?S3&Jil5C;0 zOy+BH-%7bfHhtuGKEx-Vj?TH{oy447?4&B3oHPdt7pS!S+_8Am0t@-Y$Z?2~o`E|; zS|=9*@^k+R>lF&0)edoj=Pw9m1R`EP=yf=Ry@o+93GWDb)g2Q2yNjY{Xb-O;Wz^>7 zLXN|?4k}Je$_O&r0<}FoEDbWX>k+QO@mTx9gVfV4UMpVy&t<{^2FtcX&cnscThqf0 zRg^bG%tGe4)=5%|Z^-Mi7R0)82AULd_RWyxjg!r2$c#+PhIb_A5NPXg_t+!(EJ6^mhv%Ss_Qy@Pd73EbS2?vTt$rU`D>j>>0(i*;@S# zKB{hXLDbLy3M}W+GV9l%`D}}%{@v_4?8Q!AVe!ZnGQy5R+m=|!o=7Ds)vo>NeHoKj z{}@@;jH%6pW=@!*(hJ+eD+$rl@XeTy$^{alFZ#(7PhODBXx{uT3iiq>sJAzf)Wf65 z;)+o1ac-o^m#}iQjmKixUnciL_5b7m{uF{g7NI+lL^RksY4r@LNgbOEIjoPGim75+ zJTS79Cp@(NrkLE1x!#mfiyoFm5$bI|xP!q>2*^Eoju#zaXs(pMvnUj?(#5$IOiZ{k z!qd<8{T*Gg73~RTH*M5aPt-9ce*e&aJsI>`u1>lJF{?yY->B@gP9a3@5hKy z=M-WVq3OQ%EEW25``k&7A0vCrrrP+KTEMeq8kejLZ*kjxa?xJO*QX0ExBFNGJTq-o zX8aiUxV8l76cppt6W&Rb@2h^%8Cktsz6`q6h1=e@8&nrZW$0$HWU^>w^*%-wqQdX9 ze0o5n!g&c^V%MF7nVUBD=bGzh!+sVD-=`AoaCFX@Tmvjt_sh;xFL-WKH$Rt6@2=i1 zKVoy|%Ls6#a-5cCd!qVIIu?^^=}Nw&-S2e_Lceku&VC*An_5ns?U~eQeVK-|1c9uY zxk>K97c&H?>@1L>wy3;i-96tW&c_KQ_3<*Oaksxer^ud~>|B}`Lnt*Gj%vPyf=8m; z%)!hWOB>{iDn!$O1|Eplgh4_3RBefo4YltX}DfMTAAp2hw_ey_&tXH@EKQj4FJ!4@pkEYg!K; zojty6TY8o}%n_}uq`O`X5j&pOT?{!OM)V(dkac_)3TSmmgbH-u7%~wAA;tX3 zn}1MBwEOghhh==hM^}=Y_SbM}R&G>xBxP15M#f+TI|8j04_~%ms<>7vYer)51UL-v z0<*zSXJMUlZeR4wsj2J-71nWf&v!jmbEcnXuMzb|ESaDEwvE8wD#y!V*Kyp4ySi

o$G{{A(juJ<74#7#+RP?)QdsFp|*=<^x14toM_Z*sj{&ZvoM6`gkMOx2){Hwaj^^2__LGK^U&kd?_SG``yJ9S%q@42-QCnsbLwnp-m`^JYUP{k(CQ!-mgygx z1KbdIKtqfqiu5|Sjt`2JFKi@J#0>>H7#?{IVht+13!dp2vFR_ST7Q)j)#c${Ihc*t zEU5$BjqI1sBh9S!>>vL{rzw|vuGD$jCNv=mp?{tbg)m@|KE36`Tr%t|fuaePV)4R3 z?GkErOI%THi>{P$MFge91oimMDx>I>wHV(C<%-!k1}75Tu1q+UeVpvd=|&*AuXTtw zEHgX3IS>8%cSN4`@)lSEPKEhe^O=n+A+gg2nd-u4k=D%y;mcy3cyT~x8ZOx{4w`~< zWw(ykdwEizR?qilZHW~W@aJ1xJoc4ys`sj2);3wAjq6Blxmh4uWvZ!hHYp^s9DI}( z5^reotE+on`{T!R0BDpkcOz`N^NC415$nbDv!|h#cE2+nj){4SvGCzE8!(+_@6IRc z8Th*1$>5#&cb&8FyMuQ?bFneerJbsZUSu{pbjNLL`?9prMQ{2LO-S7MpKBvc?1=dv z7r-k>AVDOGRn0$deo^Y?Ef;%{bPaOk!hlP)I>(ob^nR3$nLp0ZxSKBys471bp##cNNV}W1#=-J zE6CgT_TVX8o<72mH}GEXOy}HgryT2OWP$>!wgB`I4Ye~>@fHY4b17k$1Y?!m#l>1* zo2l2)ga#x8^XS_1I!Jm=EFHzgu?WN_=cE{`ED0QTl#_XXEoyh{z%mw~P;=Uv&R^aw8(-8sOfKvGgBR(ed`1+()SNYC>5$}} zU#vw{%1Cj8el_q@vS%3j3mrZCGi>wI$pqrj8RsUN2d^60P z>HE-+&&{bDcsr~A8hO<`GsajdK-6QJ7pm`|sLi7Cn;rXnksyqyM|#BQ=PlC^O{b_t zIUh6npsi_>pg|<6uq(u}qs{E`CcW1!zzs{QufR>$QSfr!@$_A|fxbK%FN@CC?9t0xMV?15Eo{re(* zHt)7_{I|1h8g#=MRaHpPy?IfL6mzwYCym&hu_VeW6a^9k?8SU;`K`UCch$c?1WjahSR)vqtN*O0O4N+MZ{q3@$Cq;D zg(uzqHymI{reu|s+u$Y3P+x3NzRbq{mc@iDAt}^9^ksIU%v_@vO3j^$Zu)K`tJuLA ztytMirGa;RQx>C1o7oT6Y;*iuxkBH2jv$_&%#&Z7lP`++^2rUeNsgjhJJVg*4c{8M zN)*?z8f={cp8*|Fv}o5=Vc7W89|6En*Oju-9)=BO?>Phv)m$m-q(K64{(H#*!}CnL zwuP~px6`2>A0h>F&+96sUqA8Py%!Cv%3Uz0pw3W=mnD}mmPRdnM??$tbQsLGNkwiS z_|mf6{gSvSKSD!uQWMvuid9NFk4`AuRYn4w2Lp{Ni95cG0T^Pit{F0+Ko{?9JtCC~O$GnKAlT`XCYf7(0ysb-$!;z|PK=)gAZtCt1 zV*&hnnID-U-vL<&`|HsP&&5GpPzg&M>j27$O>v-3k z;Q<#Kq!Dx196Ku*x4FMlhK3t#34=!2UmDP;`>KRSUsSaBGoGT6<>^C&qg^;H%Z`y#oE5I3_MH^$ zdk5{un=RIP=?P=><;(FO;>X>Y*bUeUvGmt}TqWY>=Hl_H@6 z?X4Lb<2|PU+oYk^&gA)TOe3S}(jPxw0w0L|hjv*Q7lajrYD$i@n7tQ&H8R1)14_~2 zDIUwk`usKLtTz{j103V#Oj%~^7A6bYM&JH zU|OqWnU`ON8lOXepz`er*5t=Fym&Tt?Ar)7|6#bzo2^Y0OjCX{5suzl9#XF>k8=E{ zlrXWfcGLhwM)QkjcHSnWqEsUu_wocYj0TL%seblq+Q*FUUPYraxfSH&CZzNiIc~#} zW`^oios6%0pXp%j^y#82B+F}OHY#T)p#1u2k#7hJbJXJ=0;Zb<;rCP)8`Fc zHB0EV#5Bxb)FmINT0#mmT{IchIS)E7QFmb8MVZkVF;o^k~BbAD> z%=53*)yjgAE(QnJr(4U**Q+D~z8%>5!Jt-5;yU+L3J1< z0z$Er)>Ph9Jw5sMOujyP>M3nbLooMUOp1h(H}^M7=g9VxEWy;Q3Azdzhea51d7FxG z3d$)E*D5EI87X5H56i)t*l$}~hanIBIl+86jloV#*T&rVk)QS{ zg(cMF=PK*lWJKQCZ;=x+Q=msAm19cV_6r9}8RpR+Uq3yGvV*=bte1z2w^H_t*Kay@ zmQF=k{y?h^%7f4`-iy0}_=o*Z{DYz(T5bU45&6~^#WkFKv01!*JFbQ)_dO%k;I4w< zD6bf~%K5+#jwhHX#BK=pZaRZ}c=U$-q5&F2=&*dTL1yV@ex#^Ml+kt^<4dqOTA2|P zgeo}D?v18(36g>UcG}U2#rSuJD^taZbSaW$kzZUU^4O2_%n?(ORt+7T92&gy!{sO7@LSX`_F4U~alS_y&PsGykHz*NlkpQ>Gkb44p76 z&{Yi2ANbI!8Q@SO)zaxJ~9<$&*THi>MSN*6%!^1 z$uTh~nahV@?asu*k}@Jo#`*AH#$ANQAH_k82L=84I8P= z=1{rJIrYS6^ZX3Fyu6;p#UCMOcLGeLUW(rTTZ-@Fs z;jBL5oJsBI3FUnK0?)vS`Y=Yx?p5`*z}8Yb9)%irO=vE1dgRq!7K6^^uWHO(Yu4zj z+h&@v@#=!CP(wpH+GX;I)}r2pg`euT-~GVfsH-O?d>OsD@#WSZi^`LLCsj(@6MHIX z<%~ZZ#fX5O0rD&p^NJj_ZOWv z&2f*iu+lgWfnW-2<$KINhDEhC$$yE;xy&#rK&%u)(~cy$y@LyQlpxLU6q5|a2e;4 zRkx8|)kIOsjW*c0963{62|p&kq$#d8*FkQ3uhc1W>JmZ0CK1cnt(ziy;hK6A2T$4o z_fMgYo~$Sm8}-(YRdmDGiMEdDV?Ijsubc;I*QHMY~;a!-*SaTDyL~gI`)_eMa zIjJkwpJ!{uk;B7s38urJ45UQ87@%2UZ7O0tV-p#ZEBaC_6dd@$yA#`XU+=C8A5vvC zbnbtUH}1ofP7lWhF#2ALcL(xP5l7)h(p!&k&=xCnXhC&__c$k|6=#zP&s{Dg%iDObA zTJB%yjcs$bZz}#FwHFtf%r{ZU^KWE~S`I zw;pWisPW#P%Jz9t?ad+Ep-Sy6<4W+|ET0$uHjT?_NGd~NZ#YMkmNjQ4Dp|n-LB{=- z#ajwQ(s?eB?;xeTzktB~eQK!QFNNspY|)W1*6|!;ywnoT^PiPotvr1LCUj5VEcV}T z_BN~cxf(E6s9zkMiIoemwly8A5Vy{nHVH6J7zd5E(9KuQT=_0cd|FydM-XnHef@vX zwd4uLX@tZ#`Q&ZHbk!wHHK-e;js8CU1cw}^O*Rqds*wrYNQ&M;Dnk|)E17*olIc?( zUfw3gnpZ{3XABK6x*KmBu(F0rqCLcw-q^l2)PUWpnwElbmWs&A)f7Ea(N3nr;AwrHJY6kHEb$nE+xmXhj4^v9-ZS#YgY+nRJRw|5OhYFKUQT&28F z*YN&H6UPBmy`qRo3YTAH7RN1_^_-mWz6`rz+`AETSh_reBuyvGFdJ!AxlP7F)QqI^ z7apG=CThEE1v?q(@-(X1F%|TLaF*B@l$Rw6z4^LIEc@89DLm1Q>qg}1$@ym1Z|SK_ z(~9C~lx!-Xa#T3f29D8JDW5@dfPOK)OcOK}UgD0nv*708 zMOF{EEtyt50RbN)r0XmSMFfj}@z7X5edB){MQa(lH31357qDPkx{Uk^{yDIyjwk`s|Aifje zPzL>FHI=mw@1lN{N^6z5E|_W@6|#4Khrj&6GnBuX>E?ks0F%?&aHH~_<46pK)%M8vztpKq*e>Lb7?83usXftXo`z-UaT6&eSqJ4kV=Cg-}1VVLd#HAka~sR zo##yVzIRZp9LG%3(h#M-N!&#ihNtU5IY(i}P2q87Fc!y~epPy`LL&0W2uY3q;kZS) z=CL!Z-32LrPUKCRDqiY3TaE6_SonlXa#wEggJw=6uH#$9oxg7@d;LN650pm7 zp2T-QKsGnsVa`c1?r&#m$!U`9cykS6>id6U>RM71ih((3sm`$Nr0`FLcRT_`d?t4& z2J)>~7?g{17&JC@JKjQivuigS{5MBN?(icvfeMKpq`lY$^VKWE?9fUjGGl$b?%5Ujx?HCo!9M{8a^L zvA+B0rtig^r%-_yV0Y)jeMT=M^tq+Kzr8&z`7w0nc|duy8*O|QoqC~}8Fp#ClZ*kn zl9EgHyQ=Xrq3HtXtLJAfGR;osh(js&R8LM*`uh69XZJdow9v3$sVXwwUV7}>HnnURs|kQt6c94k83vG-Q?CVM4C$Z8Nm<9qk4 z*XRBF{rS9HJgd9MecW!>bz{%7uhfF}TbG%(AG?vVBoX1BmGdbK?H&SY^On}v+(x7#kk^D&h+;X zA4}z0$9A^_|Nfo4ObD4;8pbyS}HrHXFsobs{ME&9OMDr;6Ez7Kqzw2aM*EpR8pP6sm z-1#zcIE5!4U%{B0@P4f<}8pOrqaK*Ue7ySRCUzZ8Xykm{OkKmOl)_&|uH}`<`b&&wA#y zN?qu8illEp-y=K{C%wmDi=VknOO5hal6WuYw;2WQxrADETx;eexY1Ri=Ae1aNcTTR zbVaU)++IT^hA#b-E5bH9Q?=exWwS6Ah)={0Dc2b3n?2^~Ym^bD#WX?10(w)LPsF1< z03O#O(RTbtUq`T7{G}Z=#j-9v;i9MirZICnS6%AL*=i%ftWGTUf^wb9ejM#n;AUe# z{2Y?<(??n>7IR|>{7LIh=Ed@f<%J2bD7udoy#2QGd0LDo;h68Ye15H&ZUdStf$m?? zcIL%@?WXVVFY}Mn#T#MvpqJLFozQ+HdnTE$3c=Og{sHGcibq{dGA*uLuuXv_2kwUp z&GDopIAaEJE*0e90eaj%&#oS{nq7Fre;vL!oEK}~C5#d}L_thV;2l{rRh(+%+Hyz= z3F8Po(UiJLS!Hq=k(!$s$%VWjtp&3lCN8F_p~>6R4|C$3wVNA;#_eFl$!@pzCN9sQ zBE8}7bCJ2CvlQxv(*s#|ko`~E%xaIhZr`g++Cnd~SEb_GX_S7_RN3eB7=;INW}ova zyo_G0kliEJTI9z}=l_KxZfdu>SnwetL;vmJfSWE4^f&+iI;-rxP4eu0JpSe?cJhFf zqQjncV5k@h?}c%h48kCg4Dhs+>U<{&J1GCj`z-Xxa~VMJU0=?s7Ns*8F|vyq8H#Aj z+RvxuPnynnaKnFP@$z1B)^TYkhSM~tz%?B zLj^j)SZM=#=Z?hU2Ywt+kuOI~)4-b@Xk~f{g6Na}w@hh7?(Ddmkc`V0g>- zlaNFqGBm=bHNT@UB^y5KI@i^dFp2V-;L>fx{eZ&i&08Ok6&J7PhJ-v%4Fm&lLrIr@ z^hi}y?Ml82Ia~w)ORTZGQpk)evj{(|r#}jN@F;AYd#*2(WCGm9P6scZ@MPmJRRpfC@ zoDn617x3qN5nu$pS7K{@%{KE(>=t6EScp*ng7x{DWGqglO_b?TcXt*?QEUFWr~&%A zRAbcJ7j)k>aKhfyxumHHd@iSdWj4b@Mo^q+LCHx zU$oZvN`GRz%2zugb?~TEU{-7KVsurVKPlJ=Duhc7Z*7$a2swo}TINJkYR-1>0-^Jt z&g@=ST`{F3zcG4r_YEnULMEIyHy%B|i58d^mAaB0qyC&p|&o zG9z`qB_GP2A~U4pY;G@H>S*z-I8y%8)wo>Riq_s&`_q&jOTX!W?YEeD;rKW&(cLs; zMcECRgL0)Gcs6+LanJn4XtWVk`mcKo0qaLgOMe1hJuME(%9SWK3D|=vce#}oNzm`U zYaIm%Oj2IkvtDj)ZjsmsB4^Pr$7H}3iq}t*4NyeGYv%UH%BG|a_JA;kpf^ClakV=k zs#eqBpaGmHIbaY5`H@fi<561=Xc6NPe^<(t1+d3fOV3YV3Npk~qy#AlTvmj~TPpm! zv2Md4IO+m8|BF8(Qm!cPkg@33hK;QZ)CFldD6)sO(pSZcD~p*N2oteJ^zEq5^!(yz|Hib?Tej>u~Puol(d3)gO0#`~i^FokC_ zhK7}NPUCXk8)a09>hSuc=i1>=j05QloB~k&u9*g#nUb}AQ3`|c!zZGk73D>+!Qyx`yb4SahbD72szbSEw@qb*F$?=OMotLpPmttVFdYwX{Kb|SEUp| zF5VZgV`v2}&Gp43DIVv>cZpDXE>LM*ONta=A$1N`vQ%Lj=hyX<&CJ~QRwy$D?+H0= z&~4v1g)-n84r=h*a+qZ3DNDeWt)hFd;({}&j>c&UB4jdRQ$}fP3W#@a@m}Cr(XHo( z{NI{wD#)bFoJj3{i~DQN`nbN&XyTBo$6Z*oCd3dCTJ_Bv29!yU6FWAq>#=Ez*xzHC zYitb;Y(02@%mche2o*HQQjMkb58OB=d+@M1?{d;VAI=! z-35YrJ!rQ&GoNUqx*+d@XWY|_O5u7?R&|@faW4XA#GH?r3e&DYM0W>+xA~$idOUr4 zTF^k}1s065qYzI&btyk`s4jA`iWOiv!d7y@R^1Kw7QI9P=%b}9<|Fqxh^ATMKIIAk zNc#T*B#{q#SS?+X&mpesIgOoJpJp#xoAzkTi;_jB`sTpGaqaR|h`|a+ljs$e@QdH7 z$iZi6n{cTqXr8;Ep0hs92riVaMO#4(L#ea1pQ<7fn;xf?D8vxx9j$N--4Y{_x(j3#DG~A z!PuY&8xi;{txL@Iipc-80Pays%?4=;lXi*-@DTe|k_??H zZN?2HX2Uz$#gV~qa)BbQ-MMV~2v*D62!S)dp)Zq@C*(wf3!C2Xw~&sSKEzKi6tUk- zKheZ~T_duVWHP1TUyDS`+N9z@H%!PXNtUXwyO{@Xy-dyx$B$CJME9Fx9|)|8Xul9$ z(LQ<_za6BF7j_;0P8@Nst1VJVi>E;l{_z|x8psCnc2K#1TR`Wxz(}dm_LHfjBgV?M z-#Mv_l4X%;VJRqjZov%>d-Qc2^i2{N&tWm&lu$V|p|&^ZP^b zX%k!kV3BVt>22TUj%pKW9+dDW%!NV|sBvxi$Ew;hFu_;NroztzeIsv7iOQy4ct%j>$D?}-Stax_i_rQ7U+6IH` zOCnW1T`h%!w9`*xH-Zo592-kf`rWZNrW=A`w3B(%j={L6%wwbfi09a8(-B z9z>va>1Y&@V;;XgiNVX=Af}ohYh9C}uZ(UTO^GK-`1^2;E7o-DA z4*@pG_3|Fl4NtL?4YZih}9!EDdZg|8{$lzuRZj47tM|n zXe}+tI5;-xpY(`y#J4)k9{^FB7unxCBQo4wd<)LZ43NDVm?<`;cG{r_W|%%6%> z`2Vt5JN)|L`Mr~a0%9m7YXFx{H}>ApZR4|_sY~?f3Zloi_Iubu^HOgzHM0%s8r8iq zjaMX8l)PXr_OGoIBda6(tY7f1>uB#wF-tmzPTWdVi?YmU{xpD z7$;8S=ejEBdJO4&vX3C0!F9`QWM=8$sZ#vA_c){7_ztML zZH3c|7=828Re{nQPp8U^^vGt*dJ{17SGhP)u1s*~yV&KC%!S-9wZzByYY%*3;Yd1h ziCVGR!-&D>Gh;5bld;2GMwIw3tuv|%w~OeIlPt-STxoQeXS}uGc0c=e(G@%I65%n! za;91e5DzSCYnKa8tQ&cEaazIA#-{ekZbYMZtqxx<6}^qG+^VFqhYlOqw{iY}bV4=o z|82KX<-eM^vD50}eIuPzXy@8_u8&9IkJGKtsY^IB^=DTE#3O?{$zi+Q*b4E1Yn@&2 zYZPuHLm+nDB1ozS`8L{$Fy6Hm~F~>x0dF=MQj4k>|-fVp9p7-yV|Y}6-A+?pY!|kwPl_@-D!7ttSdYS~ z$Y-U88&JFk-$ySiCSX6OBv)*Xl*gxJqYJ&s`AmS+(^kvpr zP7u>*sw?!iwV}Ro26|(v%c)-uvMYsG3UBagLKfZ73BnW{&~tyc76dm73G*NNDF`Cd zA3TWI+hSVUU)b=S)Z``cujOV_Bc3QTCkk;v7FN5vYWukJhRdd>6CFa=*R8rbpHhE& z$^Oe|TgzK>+gBSksZXQ*X?3Z>VfwV4)Ev0gBE2AEPO_m$MNoIfl zd@1NB3J1DMP${9U`vnQq4$&bB^CBjFu?sf%&LKTZ0x6{<^7!$5f0 zNB9R0yi4S*03gt({RfpoFC{zIr1H*cZfKM)O@8u~RkoM9w8v+HE|GhMKZG#aCgBl< z&Wlw~C-F&JHiYKz1Y<4}LF{!3Ls+@>O&Id3&Hb!Y%k8Zo!x>whkFb=OnjT_f1$&tzcDJE?QW_p>=Al9^MSI3 zH!F?g;&6>EX@~rZ4fo8Eo$=spXRNLvp-#+CifIF^BPwZr6egPGp)oV-I1wvLwfh!1m_i-pmKFMCAl-5 z3mqdLSB7TM9_r~c4E_+)od}Id z7B0xKO3;9rq@kYXvaQATbUqw52^uN-|E;O*;e!WQVG4J;il4M6UzgOP#aAKC!z=Ai z1k76+@~c8^qg4g<-*Uxq?kK``XzewMlATQ+b!%K>v6?;BxXH&$d#qM1zu;1Pn*R(! zU~et@c$gPY)BJ$M)z;6FRqQo-zx@#bi$iir=vBsIz$`I&NGKBrU$}DzLACAhozMzU zEE-JZ2{4j=!}f$k;^$X$fsUx!L$!y&6hhP_?l{E|tmlgK=MM&GqD(6x6cPpDb4Af# z+D=aU_V+)J4pqOWu;TmxBzr%4LnzxV3jHnNZP$A%4h38xv!((r8a4lUWx(VyZ@Dcp0bFSg2uR zsj>Y_B}O_qS)!IJ$3BTZZxU2TlmA2|T!8U)f;SvJ_1Vtee#DmW&=YyZ6MfzPl52u~ zkJtB4e7uJgH!#T8wJo`=g2ja9x!vfGESKS^MuLXitTBZX2l?2Dcz&TXx3jaEoLuY3 zHU6_z=fI(&i!sj=&%;{YNhWrr+vO}=uM`{<=A{@+=^zY98HzyEBWp&PqA+#AFRlO7 zGpFR&0uAfU<55{N-9%{k9K>iUMCYZny}r~cs;VT7zJQ<@-)n7$Ix#6wpcsxty?mqo ze?-!`p3p$5*ym4(*Bez`$!!L2`GJcVc@29fZN=lh*qf>F-kMln3jMb~PZ@82e}=t1 zp=GcQr-sYVaSRoNb^F$fA5!Q)$6nr6OH6*-!}=+YcaOgP&fskduvVNfBe)B}Tn_rT zZNK1xR+e`p)Zmb?UoAdUyzw0i9{;^4L`WDdM$N*fPB5=r)kOP5gT2aTTcv{z+d;HB zmt5`mD$2I^*~%&3d^MZysAu1DyLi9g95Gto-mJ5yBUYeWp*zwe@T4WN*{pPWggREk zGDg&i@tB+=>0jxo4F#H_2d$QG$}gOX*9N5qAWYMtG;i+n&?Q;tI;0)dPN;}4BMfl7 zE-u*UDxct^-6kJBJ&4G(ATG=vIze~t18=P6eLk!x7c=;pisFU5cbT1e>jG9TK6mB5 z9ojA4xy&cy zjavbAKF{~K8{M_wp635sB8Vo|n3i6L>!Z8rQTLwx>XbQ%57C|9@$i18Anfu?LMxR7 zP{B`vGq?)@l}K-PEV-R6kbrxQVF8Tt)$x>DetlX0_k>3wch9f~R5 zxh&gkD<8=C1@*j8hU5w;Rx@ab7ybMIT4ON%j0O>L>u}b6yyLH?3|vOgj+|&ca~Y{dt0Q?xH9USi@^0wt@`lbA+cF~ zL8Nn^VxgSzYiSEb?zEvLRJE!AW_Lh;Gb>f}nU@cL-fDpmf}qwzTw(H7)~FiC9a-Lv zzGiTt2w2t#A`=JtD{W{gGL$Be(6eA`cGqT076J2LSURk`9EY5tGVHB0CIs%d?cL9ij*U_%*`s~@cv+_4b9>w}b z*E!oqr#~F{+&{0X%`TdaTel=~IxxQrSU~~2oEZEWNz)M=#g{KB!8T61O2{>UN@-t55d%XhHNcJ`)#61${!ZG#9}e^)^KCLG4pgo(>hI{*153? z1@X@lB)jXgIu#Sf=^Plvy|*!Xz4-2{X8aEh7r%gMr)h#5|llA@Y`=2FI_G zXSz9!l5s=pHo^V^ON~BeT{(J`wI&hUq2DI5f0F`1%4F;)SAGc-;`Mljys-+o77D0Z zRLKWF_p6rsx$itaHfk2kX_#+HH2Hj?x z$rAF5=9=wJu_@M-Y8Mo@zk(N!xoVO#y4vb!*O5A^utO1Y>dkoLB>wo-h3|26&I5N` zEEDT$;QB_!;wNMr7|j3Rd@RvjabZW5BtXY|;`^o2b81nyb`F+xv=Hb_>ng6T2DZ-e z_SEGy_B)(8lGeOhMC=95EI4#qx5KBRIHOtK@alS86nj#-5tg(kN zq8f}HZaKM{A*JP3kVMhdv-q6?Y>J= z)3XMW6>%V}BER#0G6%{;G_QVhtFf6&DPKa9~G)(_J{ax1MbJ0H= z4K5$)!_slRANiCth^tJXDh7=If0WXn-{*nH{bf~(ZA=Zg%1ujC>J7MdO0{DsRp%6x zm#x(qoJAdI2m0vn3)W{wd)6Q95GK6`MAxK;-gyHn833U3n;f$VzKZM}`O_(>5mirr z!-4&?h|*e>ti+)A4u+<~OxxKWg03NXzf*tb)ag@Mnb@_y3bdad=7Sh~9^L!23a5){ zs=`QHtgFoabm9tn56!+LJye}D$c0kED{td&Mwzuy<`+Alo&eD$xO)KGM9y*L@?T6x z`x;0fSp2*;Qoi%NJ?t91kazAI^3h{6Ch1Y@KG&Q%P%(IXzWK3uLV0sHSzI=AWaQDa z_WP!m8rrg{D(2+rN!ZWR8@{|VFU0?!<#dWAn{M~OL15*oTI~MCxlmpGkju6>;Z>r5 zn>L!JW3vwfk1fAk*2DeHr&=gSi0eT9&)27~&XW*(9IyEN>Ve&Dd=2oD{#m$n;7Zb4 zumx3nxXEtZO-@@!0^OT};*DO-A8f*MZ8*DeFCdTY0R~fr=U5~;hsZzhEy~X0^K0FH z)I`i#3Z|%zKBb}<4BA@YX-=eulPTN<*7d`NGTq)ZBtKF?k%V(zu1RJ2xDi)glmCQS zySa~dBN#&cb(q9KNOSj=HGErIXyPBl`FupNp}6@rnr5oAVUP*x{N9_zfiY8 zJkVfj)_KL1f3shgS-YiIJcVu!1uB}6jKB-0)(@Leo*0}_O`9G4&W6WnmA|>!*b$@+ z_{ny{Q^G+kkL+j?r`@sacD%)?A7+A1*!BVNFat@$_mf}HgSgyTfg3RB_oD=gT5|nB z17<7Dafbl}z|bo2S5m`-5s3<;Ij#hNo6uE;;~adHz(bMyaC8SU;eTg*UHAEpwZ3L$ z@neOysvvDj_kgX~+mJv+4l_Fkrt2U5JefrQ7qNC%~ z$F)P%)aC;!5HlzIH|Nfu9~DX5+!fG16^SsQ!S*y!ZPq?Vr*$DlfNZLrJO*y=lN>nx z?(&3svlw#UZIER?>xx4bFtU&^3zV7LUi3UDS6*(;;=UEY$16sd4HfQI$RCnlpim8K z!wtDTjvoxtMabr;SP#HPF>O-cKIti?1y%6m@06X(>AQ2)@>0hn&%kF9j(OH*=&FL6 zi#Hnw=IR?zSru?b5g}cEOi}fC3-qB}VnqC?Y8fb`=5*m+y`j%11`dfofzNsm9-XNejPT4T#l)H(LSeQ8 zSBF#F>%0xzlJQ2xs@4Nn+EnfGTilcIpBxgP_6*^&E?8!;ZOrsh!^+B};gJ_I!8LR|nl-))SMXQT9r3RpC?A48DF{|4TLhdC_>L?Ek4Nscyy^a zw`xFj-Vn|-=XhBO}sv91bJe^Mm%%9``FhjyA{`sOJV9G;?OGu>a@vs$>Hd=udfg(TgVhUjC2<}E{!ahn0eEKiQEPjn^+p~mUmhwz`lQc-{s z!7?to*>KaYS!X@{|6L3esh6ceJK`g~&A4S|W=6E)>C#rbs5jw<9Yq7a_*zhate}Oq zD7@4<6Q9C4|Kr8P#&(Oazv{Mf$kkym7bc65f#KfQyBA*_rT@{i&(t(lUXsWpN}Jmsaxam-1Kr@DJcggf*+@|>AyUu5dBQOjvZ;>UW}dBaYA+w1@=6NSd3h~J zokeh={p)bBRD#fCFx<=I{=@|Rz>7Jz>EnE*^pxH%zK5~I4V{83N1ML1vfZWHyC%`6 z-#z8A(sixIo^AG19}ag` zO1sA;)|J2yqQHwIOW_39t#Nl9D7^rS;!zcb+p4-gfS7(cHdaQW6AmQYYE5TnXK&Uw z7nu%i1NHEdQuhxx-lBX84g&e#GsVfm6%+o%hc%)^yD#wIg6ll{+{fx|^MZh|L{%5g zL_VZF#58T%LfH(R*ziz8EuW$pN(_=!d?XOChAYbcb*lq z4cOZk;bwTL89U6t4P5z#t7Y!Ou$sZxI~QT2!O?`>LFVKzuE0M$PbU4JNcySJ z2VLT}7~+4d5-8RjVT#Ffi!na&iK}zWZH>suW<1?$|1*azS6E?47oK{Br9XKJ>X*%= z#etj5Jl8U|9DjJwGRt%;%*XOAPtvbczAw^N?@PcM~ zXTJ=atKC(Ygm#;PD|p$drigr<;YaBaXMgcS7DAfbF1b$Y`eaT!e{jGc`Xx$l1zhDm zH&=R|G}9*E`Di1koFZ{ek_zc=7LtgnJo`d3>+2$<`f}OFVkAVYn9_PpArga`uy)c6 zG&7M=s8QX9)-GM*5Jdal_j7Smc{MnyT1(h(VCjw9M zygifc%`5}10CQ z2Bmaf4hRh1M2kTGYj$!Wrn=6O>0?%iBLZMQfo1ELC+<;40*ageWVd=@5okZqt%|Ld zqfrglIl!l4f#q(SXDj__+pK|Ix7;<+xYa$?%0urXG?X!y^FJ-XTAW@qmBCYk@x{%d z{o`ZU)JdGHv!0EGtGi>9T+{}TQSiid>6lWDogb~YyYYw<9s;kwri}_H7M-DcN2KKg z$3z$IFX9B48L9gupxQV`Qu{>`3Vo5*bO1ZTXs1NqGD>0DZ=5?cKjG}g)mQB%n<)1S zL~OkmTa5#+57h5(H4T-U7Q9yR2$9ycAJ=M$6xjh}OH7cSG;L7O=@W2qaX!_BW%rg)%KMtNeTs_f;wQ0wZ z%A9*H&vNGf0h$`up?&a|=uvSnkGpwq`I^Sb3xw?4L375|vH`L@3BR15n7bn;K_2pw zoMW~tRPmXX;zZcu`RXYbFn_(mNw1C)0zw9~t|VP|FhW&msp^is8Sw?n^gJTNB(-m^ z+dAFK(>ONSwCgpliF4r9V0dTFDwtlAm0E;uE8^Qno^rM|{;7t{5;LYf(v(S)Qi7~Q z^lMKEh+#*gD&)S;Tb^Chdd+0};_C{l!`6;xbe5d)ru(K(Vz) zkNjza&Aiil7d*?~?~N+m@zPCHMen8se*64jG(}v^3WwUzQU$1hghcU>d4X(?=#P|k zw{N`DdtLzVI29h9{*R!L1^1@zVK9!X<;aPe&plSLkas^1T6hW&J>?u%*|g>FXz&$g zoGlf%m1nQzb|h`?l?Hggm&5LXD#HZ)?wa>#Rt?xpwuDb=E^2SS#6nvpXq6y zStpdNLkGNVi2m*5dS6TWzV+&E;8T6)z zh3EqXy-J&Gh}|lR;)16sQU=ui4%N&j5N|IItyG3oyw}*8{sVVct)YS99RMA<^hn1t zZ5h|BR`LySW#{!38f6!0d7Kwh+raLCYLd0Tw1g*pfNAS)&#FzVBBb0rf!>W^e#fG! zKXC2+l{aE)>8YZ|Jl|Z_pWb9x^%Wk|DqOBJ_B#F?~>MnQ3T* zhneiNZ6^KJ^@zmeN8$xfKyxNmyR-Fl92z?&vySPLLZlrO7cb#Ng z_We0uHZ_f#O{ux0X4vtBWl5?i&eZt%&j6qz<9zWTebkLJ;p6;gKzuwG?TNZsnKX)^ zafzLqzkD=z+h-ixUehifRLlSzINrs#?+AzwlNNP}G}+)XOfYmVW=RcBGj#%%&dJAa zHhp)wzVRBk7eF)1` zcd>i`KY$lBu5##|_sKLUMB!M}SoL`6WmL6_`}8&f>r|i{S-!|m=W4+A zXeV0*AL(q?(*4-JLcbPFLjV6@wFrmmw64KO*~exB8-A4uJan4c=X}C{J^tDLWJIOK zEeifPJfSR>JU@-|kkHjipel;GYe=SZiNb&7Ya#%m--AG%Q#k=lzuaDAPeJJq=kc#l ztT&355E-Kg{FyiQNoB!j%`ji#l@St$bL}TDHV-%0EF~#^gSQ}EdgUlO%nBw>?~1#^ zOz&qN{<;7%axP-+gsmWsB`QS;v$+OiL1v2qya8KIT-xX3{R& z3@<_ZVjN9aLU`g4o{_u62^J zOi3Y{O8Y2yXEAB~@r;L%w2NR&^c{$Z>+@(Thx(g>4@&D)2(^~#wVfqTYHAQWyEcHq zcBqchdakHa-y8)*|2B|X3XU%Nzon)q?f(e(6&W6j@NUJ)bIX6aTK%iglv@izB6)Q1 z9n%mjeLGa^rePw#U{l5y%kqMQyB)fB%(Zjc^tEnW>n=RXhpuKZ?U(-2rJEI?ne*X= z?+lQQlW{Wcp+1yKmo3OP^>`e@D=i0YV&M6bC_HZM97-(zjXP&?S6xc+(c(@rOL|7R*CeO>-OMYDK1 zL6?V0EA0rJ^Oto$s2+I+YM?`0t+eh2#n&b|i+|=G?^0z)4-jhJm2y7LyABji32M^O zoO|w2IPx&h6#>icF7v#BM0J?rae26dBvA~5c+C5zHf~U_RHbl*ARmMjT+gIyCp2D4 z|1vpFAkxVG8VVl0Vv3&T$+Tlmp<-}t3*ihDuo$k#d{kX(NNA4@fHk%$*LYr1%`z@D z+`fU)mi+tcMx04N(Ix#x$oqlDl0@S;428cZ`ivLuk*TBJdhg5+6D{XbvD!gphc;ji zwH0Pk$@a|FNO&5om4Sz}tLZri43kzJ1r-fx5nWA;G(~JsnzsBgqaUkhf%wxz>!#x| zO<4KmkfpAUjx(nsU6~O#UgK?%W0#yFRV<5YaxHGQ%J&+4Fs2hcGa?k@6z`ROX(LQO z5K33?zdBI>8deTb)+#{=8RuR|eDRl!xJaVKbz)NrJSv05u7cAhr|SeugCPDp5M4KL zZ#y{Qt1giD!B5r4AGOAPJb3QcH&TC&c1TKOH75bWJ>z}#5;7bP&iUcJq?9}pY0^6C zkUMuqWwZvdKZdB1Z5U%5FW}h$I2g7$d8ax>4-dArJo}m@#)P6C%RS=o(8eeJH{%r>IxY`35?37A=%XB(vNWh`UD@ z2*1N6;SC{&+t?lAXf9kY;(DBHpE?PSTke$0j)q4OtD>EVEBq+zO}MWg@Ou|>Z+=e89yO!u>u_CAsrog4!G>~R7Q~W z@1QllzHz=EhBfZ^Wv3_URtwIDu-rma^(A8Op)uCZcl`OZiw^TI+SC-r>8<2DSo9Y{ zz>&@qY?@2OC-c8FqF;35%5k9Jko^a=M1kI2R*9;D`Wfjqw6|M+2vAC6ZT{roP+XJq zzXrrw0IBC9dqMIeg;FB#(W;)>X43T$BbcEVj~X%6H&`nqus<*-jqXF;!eSQ?rN5YH z6tW~CM%PRyw5g2Hp|{O-RnJwMmFJ;XPEl9-_UP$`MkxvQw`Z-#kD-%4pnb~uDNCV2 zWWcfgD^#gybVW5Wb$MA?V+>E}pwHben8)y>sE)n{jx{bsZC_P0+TLrt(5<~HE}D9< z?r`ufBVF#r=hkS8>haGg#@uv{T5&l9IqAO#9mi$Q3{$N_f9UA}sQlLEs}E%h$5oe0 zzJ0Y@mk&Stl)orS+0Y(mkk?k#z*aCB0%Yn%3c(ew!N7}wJ<(*=P9IG@;}=Po+fS^5FD=Z_S_NOl#d^?uRbh(7LmRjU#|D-@F3LvUrr%SBp>34j8`W|>pDuqx2 zZkM*=Th7VBDejadWKFKy2uY!{KYBI2PHstc=i@0IQLc5n)Gy53{WFWuczCNsGMmF} zS5vEUFPz!&9chd}W4B^giL&O?1N+OH)dcYo*#^3I08<<3^w=*#HPx>FT<(@2q2YLZ z)HUf`;uYZ{Vfb!5sa35s! zYFAv0QW%-_QH*L}D66TDl>{dxk8RxX+hUaj^yQlQgtR*CgN(|}w~@;8Gd{D@d3olI zFEkgX6J~8xGQYPVkuYBooej}wftI;fI%#^PpT*;Rm?|++*#Ov!6gUXC!Ob#07zx2X ze*KB_mQc9YG;D#hYD9X+sB%0jTd)@%Wj($Nt?3xbZwW7vS;|dE4S4~fDXqU<{g;P- zPDIL|&>*}6zrH6`{Hg2sU4%o03n;Ex?&cZ?5QZ9$;Fch^h80BdXc__(nNa)VJ1ke@ zYJm_jR*W7*C+zR@%dQv2SMzZ6z;i~p-4#exvVF2k%B?y;R$e5_bJt4Um)9j?WmmM3 zYm-%3bxb1KYm=fQUKqM|L|)^iPBzC9@hlpGhv^p#a5uT`Alr>9r`?K zOGdLvbOn#Y)$6WMfqjHw1DR8Ft7Ig=8{oFR1(fIr@+iurl#Wgr_Bd*aSRXbvv2}or zoO-WT2e&rYTjt!Yt9d}8ZK&=zL+!1FK; z4ioJlxm!<|*Z+E266YNY%Oz9&3daGq!exOB(z++7N*t0_&-2lQrl-)KR9n$U4+Z*X zz(acAPZV^ro&77f?XCACaYhP~;q{ zKY|{9`O@8nvA8C8zzYb>n9zs!7i9J(bjx40#e$iMZ$WcCJ)_jMvyiQL=&1j`n~{-( z1kC+NEQe-;M^63Owf0Ke@@0^bm%Jt)?$rdY&(r?^s>F%;KPg4~PcBe{Y_6{1bSbZ$ zc|%&i&)ykWVV~dQT0+*gD?aA0LRmr3T<>wy=bHJ@S5L#kCE1ihueG#o%Xo_C-`klV zZJ7=PC(FS)CvJH7f^x63lKRy+IQU0JrMBkr$FnQ-oF*YuGJ+J4*Xf?2?(5ZBX)?E+ zGyDR6{t$V_{*XR9c(*d?;b`bHP2wI1`s)TibO~7Ey7n8ovi5+A8APAGd)umU5iChM z_y=rz>6OyJ`deMUw#v#!zfKNUzWSKC9*8;rk4zWns}-m_NZqhl_B4rN$1A5&=36~CJIi!T^()!xh+fF*OHbTYpeH6gf0$0_1T80`f!cjOAGpdGHg{f4DFSoEk}smJdS$pWo#)`B|i#HOc*`1cP2DiK{XbiRjOm zDYN*snTN?>**FXWBVp|w5eT4zK7!Qil3@XCV3R# zqvaT(jGvweawL77Cl&R&{AGWwERXw1du$}r#~z>~hH3=%#k ztOn6#E9y$e0$;2~^G6i$khwY^|57d4nv$6B{%&QLqfyO*I|8WcQnTV3xR`g&cS%Qp zHfq*u;|2(o#*~7%jVnqTZ^Cbqbrx151E0aRy#OI!_2oh z+GI50(22@?@g)R62PbSWOajwCWXE)9F#e9Ej2bEIIx&TQ%kN`?+ufL)P2k#Rt=GXv^58=%gTlYV|_2<2;t+~S@LmX;LKTY0nkxJgG z?Vmm_Jh>e+EA@=VCL0Ld_$HhzCqNX-siRBUe_L8oQW86FHE>-opgNrI4q_cj;R$jM z>a?c$2Y~gPWP>~t;#$wI`mqCQ|idNF>;kFj)ra;Au??cj!Uzl}e-7_;>a@LQ$t*F!(Mf~nA*A3sl2X*}rp z@k84s6*mv8@WAXrLbnhPEq$m5<{h&K9NmBTbA>(V=sprJAMlmr0ySG~2(t=}_J4`! zk(9gVaG(Nf2s+f+9=wRCo})UxRB@!H;D5Cpsf?~l<^$}pSLxYmJL=Wqp_A62?46&! zGVq8l<-qh)rSSz9j&k=kC;?9T%``ZoY#)idf3{BFes|j7m`y(dhaTNlF0HzdoHRZ{ zcW+@$-@7#3jyleLc02G@fY+t4-{QjWkETm=DE#gzg2a#4{<0q$Bv1mw?o9p<3@BGB z!iz;mRhsSVdRk|Cdhwb#T}1v|_o>Pe(EMNH|9n$2$Remw+db>Vu z&w*6qM>L#Fe*<`s3~}SPDet{oxqg%|PKFNW*wfz)YYx19OQleY)tV`^$^cYM#=1@1spt)hNjd67&*rRqFy7lSjxdXU_2+85;e9M<$TIhjr91!)&gY1ZxB zV~+0AD~lS-dft)VhO01`t|_C^D?qusG~gnJPDrC5(E=0T$K5UtBVGEh77u%WY7Ifp zh@Z$L0`>ued-B&8j_nA2bm^1q3!Jv*ZWI?N1N<-ZNQ^eu`0{7(zXNi%pK>f-iCO9c z`Ub~o1iKEJj)Ze_nn@)xm#gzhaz~qQ58*ZC-uuED=NhyXlC(3S&9W2^M2yXv!vF-> zU%t^`AhH*fl%T_e4iGD{5ji+8_{hUpQfe^^8+XzG4RIzGhH9!%Qf_kEaGy3f$uf{S zDshRnq(W=)TonsaGG5trGS}*u3B#5^9$?XIhHI@eTPO^Z zeU~D;ZL-mqqG?b1f8nX8{MLQ|40%^kKPC2@B*ng& z1yEeU(gsR`1t++>1$PNfff_tc6R$i-w#5uvX2=B4Y^s}ik_6WCzUrDMlMy2M6 zb5NyN%O>GSqK`yuo0WWH!pX9IUNOOKP2M>ETzl_{R8NjXx~pB#m9u9k$bu^tE_lQW z(F6r)E4&t6@#Eu~$b;DV25$(HnwDIU+aqp1zN9BFq~7b9oh74_@+aIMQQ^R+lloT~ zkLI=ar|m);y#4Sat=QSmET$z~$ej0>d$#%&bMH)w0g_g6+&n)^$r}wx0pjlpbKn38 zi322NhAgKfsVe*GOh{&cgMJ=M-EJ>9wf~2C?Vg@S1{;VHnWlS^86wj^HD#5t)s(^z z8d2%zQp2aL{nk3YeKK8M0hU=>X(}FbgVRPF$)c8@#?-O!Dll~l6wFXDQ+`GwjpwPS zJ;I`_ip0n9nWt2KtTm+P->FutRWI*-=uT&7r*wYF-TYWHGCTV{=6=HnnO--{yKr*3 zGm1>Uy`OFEB0UO>why^XD_ln!N^y_P{@;j@y$M=m5=#*5$bulqj)ert=@~$thgR3r zBzz5N#PIIBVc&9;drnfbY1vPF)sTBdm#B@Imj3OjCo>05$);p?=a0pwZN|_kT~ie> z$E&oE9rn=9H*@qWqWCw5z^=3jvWTiizg3LHJZ^C9U@|gqZsEZ;9jy$>i&lMgbrLidI)bk+O7&k|+DSCb@0&KIwT{ozxuAD_;Tyuwzd6P2ptY8;c*G=U4 zMdSh$xYlL_7h`-+y?pCpAzNae229{zI`T1?B|wD*RIthx}oDjx{;43+9D!$%uk+#q^APLVtaGS>k+_ zCT}{gk7Fvu(1}PIlhQM*yV7hxP^_w@{xIG8$2)&bOzWw%PtFJBr;SLm>%X%Up8e*@ zv^7yM09mk>A>rM;b5X}t-BjHp>+s@as7`!3tEz)<*KiuNq)FLV72Ac;EGB<(ha-&V zZibXHVV}*1evVTRe`zZ?IzHFZulJDT1U@A36Mt_WneO4Abv&q=kE>L3wY&SVn~SlY zqIshF8O$9PQ{q#0zLofoJJCA7=()P3eaqjrv|=0HiCQuf^rBwtIntCz3fZsrAoo!+ zh^MRlt5aeJqVHN4{V#;mNgx@j_PapWvyLWSdJNRQtc6?&{7#D{J+ zXrSzpLwvRflo6}u zfHGGL6n@FK%c2s`=xDBsJue=cIAi$5Tt&xhj#C7P1o4noU){A@|C|+PL4+3wr|9WL}HXjdQFV$r)AQ!E=|uP zs#r>;SZ0u7ibuMB=cnMcp6hGeE(8qt66)DuwJoE1bja1ipBKbtRo(R?H|XQr)_H&? zrEm!{D>Y#FizDuQex1x#JHjLJ2ub1B@=YvETS1A%&vg){ih$EN$?;W(4oCh+S2;yC zkQzLPQ@DEfWNrH0m@W5JgRtIsdBJmoNNt;$f8cl1 zPoKj2f3O&(lbLCvzUR1;)=8rid~=}LY|X?$skc3nNQ)(2gybWga)L+(lGmf6?O*lb z>Q!Phr*A6Jx@$FC&wE9uXu|(;0d&T-zWn;6Gk`p9;ROmCld7tkW4c4(L1Rlvya<}& z&|#$=lCWtu*Wg*s^P^1EV6INGm|AI^d2b%?s|{lQN?drsWs@bUT()oR$p%Q`1iZk8 zPu!IiBF^$5Nx-|mvi*FpYeaA1hiGQ3@V7ubTzAA}fN5a>jvGWUuG|lS0txne2D~Sr z9bBEyVnc(8$SL*Qu=A?Qzy9-!AC!DWhcO%EGp5C5z*@T9`>y=^;pbfIJt2);vlrGa zW9hRkGwdI$eX+A=bF~;(#%Gqx`3(%)9PJ%P2~z)+1U=EXa$Kbebf9vgtJg8M{$-Gs zDu)_RS5;!mMP9-b3i|P&H+c9QP_6#~bFs~JW1lL^CPS&fU+~olpCppy3Zn|FRyxJK z=!lb^O^#PbP3u}qXKdbXeElkNp+rIRjB%vfOC9l_Yz^Ny*M*v^$#Z%{v1|+wo`Arj ze`=IXVAhoYy7D879a| z>u(i^e`1(Ax`x)NpQ zNiuvqWyiDFd}H=ZL$V?^pXzP#H|z4qdNS5@DP~qY5-1I&Y4ouDRw>hblb~i-Jk1n?dZp96@J{iPUlb;v-gSx?QZ^vjFn6zx z#q5%KLqR0CrAafayl7MwJTzwCwaEk<^nD=$Ix(W5Ar!ujdOzw1)ksHM+-DwPG|7b+ zWvbpnC8ZfBF7iJMfjAbDf^mT% zqpqNO0imQ)O6OYO4A6srzRQ(W!S?HjVO~Lw~y}9#gt}G9yQy!Z9 z(vxi}hoiz3VmjH5uqt}jSbijJabl-8K~w>fhFZL1qF773rs zBpG9CczCH(zEbO3F6YG7e_5kL>qHvV@*^SmzQ8W^ZLzB#v0G>JbGgA~=-UsQIg{;v z8UC5i%cQMynmEAH4cDmm+!d`AJZazT-zv$qzJKl<7vHrb^J;3iM1`!o@y*izRc9$X z+;dL3ttr09_@|2VC{2v9xD`RuDy$V}T8eg6$ju;eR?C42St^5xW-7PsU`vxXMHD_y z@t;p`5%F6%!>`=R%xbGTW%4dFJtY?#q9wt4FOY`mt4*sEJGjE?{1yB`_MR~l{&%e( zc>Y~B39&_AyCsW=a|_9M-W)NCIEVBUK5!vk0PB2Slq33qks0i>Yr&qxh|5|y<rHrxbF5+L~J(_TuAy^^ow=1 zgp;G-wuqh&Hz#?NU%k+x;k&fk{*r-<7-sZf!^K+c_2$&0vj%usV7O4w(*j#d!D-KNoN|4~6VdK1N*Ek3=o~7|-GRFd28Akz zQ8rlwqYjnH_RUlkZuXGl31?+q3_9^yo8&zbFSnCiR?+T>icS-p7_m<}X z=QC@avE_Wt7Xv5u&7OxZ&JQx2+8Q5NZ)yA~+1LEhF)dK|4_~tpCaejoGcPryd@~U* z!D3HC+moU5*$qi8;h^VnES-hb-4-m??ZIzPv=ql7S}eFwbBoij(!a4-=uZo+cb2imNGF&GR=jZ7b#nX4}`Xzp4XSX8xKj7V)D zGCHgY)XnT3Q5$bT%RJos_HEue9p+@H@^a+af_1u6!SImVCLEUV%W#Vv$*WcJzN$CO zg*gx{@=||MRS463I<1A-mk`pcl9kYo+FKgghga}N zdYIU`A@Gv*cXn?VD&L0F8hrYm9zFz#m-P+rT>Sj#CDjJ?yI38TjYIh1e9|}>fDfeI z?-o9}U5FvTvWYubV^P|9$G6wtfw91I6XlB`#3J9;n(VFL`5fX@w)YH{1w?m)ph!K0 zK@t$#kVmYL3wqOj#Fg^xMi>M}znKNk;=6FO`P{RP<@!_$#77(;V4U#1I|LRyKO*TI z0$aE{--FysJOR{nz=JP4F)&b3!uE8gZYTIGPY>~=_N52n#(NA^0lSm)2t-wSGoPe? z-QLkXVgY=1&QS?V+B#cUaSlAg61nD7bl{A&mX{y+X{xPVpXJ0iUyBEDn;X%upL4o< zYz+Ixq!`F9_Z+JvxgC53WnQQYPj1iSdFUvJ!c29R*c;0k=D%7vI}l^Qj{6=h5@%Q^ z>c}rm#0}=Lah&b47>D?!f}L5HYykY0{!ANsx-E@VIBaDO%s+MM+xwL)ebSS`L6lXZ z1N?Qm!VA)kuRb)TRR;&A8bJX++b!`%J72+!kFazvS~{@XxQ)*7oG2 zeKZA}ZvVvgx{yfpsx)uql>ljqy+PsH& z6Qyn$Wf{r^1hT!v$lgIG(Hl&obsMPuWi!wabi4u;;C@A8@4-82_|sP1R#xzfbIrKi z5*$oVtU+VA#lab8D+ief*X_wyC1^na0mL)xw2bF8ke9-Wj#u-_GaI1fz~tFjI-(8vB;&&S1ub04rw zg_qC?0KRDM674UXSy_}^rmQahG3&_vi{eMm;w*OAj>Zxd|1t7B)ehQIoNM=T$z^if ztF}@qDrll$5{%a0X)<7KvC_V$Qi4(cZYn3#f6O7q5;qj|hMmWy*1oj&J%Q_^Bi7t( zVkh4WffBmTQpd3L?bR+!Ehs1`DrYE^@Z+`J@A2`*5tAacr=W_?Q!@jYCuX??Bzemm zp182}+Uk|*0R0*~cAC`k?p<)vxQ%nJWu(x?!c2!xAPs4NSHSUcngn#Phda=N$Ya&X z@wcPb{J1cqGn(HxEOykBhJ-gLLj7IGXRgQiO<1E4)`|FT!R>x6;By!>DJ9$Kgz&)HiI8Tauj22(HKFQx?sqgZbg=mvi`~ z>{+9!G?(LfgZRc%(CN_WVQZB)wMiAx!C#4IU@L1XQ6?Lv`W&{m{b@ARiKN8N0=6YX z+QvExK4C6DKSE~}dZ#33415}hGBOpvIY~y?@j{Z^-j9W@?1se{*T*P&?eW{6x{X;F zzqQ??5&YimO_l-~X94MA2#9tQ$?F(!S}oyl_<;7_(Ht0i%%hl?5_yoN?f+doG`oFE zWK+2SYQ&zdwpNxGczKYof-lC8CmEA37|qL5R5#V1o2+4~_zaztS7Tanq2+nymXmpH zhb0&5A7k%#xI_FsWO=F|O(h~EE1zUTdb(hm#M9h%D^H-Y9HFcLoLOzUxqR0O-`wU} zN?)Ss)H)k$Yj)m=cMlVurbynnQ=gKx(zvO>aSY2~TU~!?8j-^@<}dyI93!J6?&$Y2 zYf};op{x=TrKbx1zP{|9USfjw6O-IV{J_>Yep;(x1E9*gcMhJ%17cD`T}@5lq+G~S z;q%aM&$CZ1Snd+()LFCq!fO(bo=!V1fo_|S3e_Mnw2h-kdQv?+MBGu6S?y&3mwU`fmrqg zSzB96_Dh*}29lPRvigLk%)ZDB`1dqqC+75Z@JLU0whogz0dxSm?+O`WyBnNxCu-nQd(wkk)lkUIq5fFT zl~Q10tpk6@BXpOCZu`??xeIxvuI1RJ~ML^Np$3^{q} zeYIUMM7!fx6sKbpC;*tma3?Ef*WYPT5}lHQ1atohNAb0Lh)vv26A;?~eG z_*dP0-Qsb-?b#&d5T5nkTHO44_~1}cs#clLW-@i*#v>N$FOA_ML<#u8>Pp8PvTYe? z&ypr^Z(H!>WEdLPz*_6|umKxZ(`2nW6Xy+bcvdQRb0#KKeK!!aqmA=@8?u)wboq`< z{Bta62jGMy(p#08RXR$*UV5P8+j_g7W4&>Ggkp-QGbek3dxPyCHOI)daEN(FcHg6Y zT5hU*;Tyi4X4V}Mtx9-=6DFSBW2ca~-BV~h&3sadz0^?eBE4kR#O9a2sMNF^H8mwS z{9L#jS^DP1@`mYc|H@b4YM}}TX^HJcM1vKKeVN~iA?KCDwZtQD$ovNWs_+y(ANKf& zYvMqM1VA8ID=<@rjF{Ppi9NBPXKVq&Zv)YG9_3=G@M34uY-FRe8!tmvKY<_@iLsoy zJjFu3u9Je!XI3yyJ~w18F`*DTi~l5pDb;Ha7U?ri=(A&;`T$<>#i;^8_WtE>&Dn;EqOb89){SD5Q?oEiNUvsaWWs>*0VBZ(VSJR)D;Yzsq zn0L%V%c{mbuMJ#zOQ&))(8d?$xQ%$gw}9oPC1L87S{IQtOp{KKbybd($haV`JIEdM z1yD$!e{pe#FEyVzG5qA5OoY>3Tnt%gP{~ zB>C_VAm2!nEX(ydKpkciVpF(J5WXY5qz>TGrG7Ef|N2re`LxdQ2fWM2ZAq?*WTz_N ztcq0zRokR;0&VFs^fX|(%J8gc?Pq}(&~0?UH+{#XIGC&B0UT?kTy<^$T*9!{=W@F+ z{W%NsVYs*zkj>6=cd2MGX!4@>Q&U%e?rQ#b&zP1=F9hL_A$4@5lF|L7y;IW}=ITmY zJYoV^0c+67#QqeM?wj!&^f*oVPAU3>+#%%@+`;xU+sgFvQY8K)O>UsqK1cMy^ppmU zNsu6&Oq|HQo9hSPE@OleMaGTOL;7mpXsusxqwck5N$g!4{tDUGHK19F$d{e89m(0d zFohsIwUfGyHXFxnOaW(2yFR9R+v7VoNo3ZO5?LC3&epgZMY*!8h#a9+SOlJ#*yZ)B zD395fvO))mS=k5`qPWx7xmzE{cJB!$*}i-7`e}kP2ZkU676{tVlUn5*&!>assbGA9 zQ{eNV!TfIUT9zO@`cqN1+bTRaeoLkl;=?Yx>Mc0O{eW4Efb&9?s&{Kf-&r5VuZ{&D zzqjrX&IHhZYe}d#26q=b< zd=1>yc!as*yul-;se1UR4TRqvlp8}@r>qt%*iRw zAGuamzU)gtb;5olVR*HXwb5}kB6k_LIi!mt&BLp#3}-jM3_Y~xwx$0JJ>#ds!^mKAL@`h-`iU^X!jeU%mnzF`gc5To$%8Vu+`?d0aKb} zTBnV`kr=yBk*#C0FkTze=`ySzql8f^YtnIWS3^*6b;ja6;X zkPIVZN_6xKGM*0mWfPp)#ctGLpU25pf z1E(!Tyn0)Ufm4{m@bIha!EpY7i0PG!? zCG$I8mp8S0eSXsc+Xu$W=TkG)yoomRuY~-syBaA-Y<~cf~)PgXfI%M zRP!rPzWlRMNW+Ph*k?7FyaL5*ZxkGlzKOjD`$Xnv>{ZmXVR{YeOb({_QsA{ing_nTB~RunRi+OiYkh)83%*Ah45>J%x?sDWNnKKAF=0`!+AJB&2P z0}KXXZ~pGqap!zx06R7fWr$ytsMhr;Zzeipw+cY1 zNm7D;#Hg5 zh~fF@@!c=Ub>6Ok)3-V+3t9Pyt@b`w>sv#=tK}5pgU4mAj^#$4Fh36I z;-;|-(h9`_J8wDT-nFNOz8n|}zQ7|BZ+!EuA*w4MwoD5I5TqQ)4slrxS*fVrEFHSG2Gb zZfzkeD!+_hqCbD}4qJ);c+qih@!3Z77Fi8tPqDO;7_T#}n1hIZLd)Ajpr z3tm%^mI?Z_V6#ijx4lsmqoNB%6z=4`F2L}poMW0;Kq9O+0_S;PfR-Ch_!W-dd`We+ zb1i92M==lS#B_AkVQ%Ot1e>fgnpjDLIC!qKk9mQbqmV-BmquV3ljDk`RA zwW9a&KWFnk;VQ5q0=k(@g3hY8>`bZ((1|BqmcDMKL)++8km|wRZM3QBdZh~=gQuo! zu7I&lZvBYRhyiV7S;1$i#iAIWni5(#)cNm6e727gCVOUAq(`Er{Dg36=5XRz%&tcExyc>l(5~0 z`J8QYG^YNkeUX(zi{$A9lsDw%V@>|tsF`M3c!YYH3ZF>BN2<2>C#*E%<+0hwQgw(9 z4J?|XqHI((*oHd;^Q372KBO7E#Cx++*wcY&q`O^FPOMQ*644Eq0~iMI{a&)JU8v2Ei+%xzKx0Q= zlV9EC8D1nQ18v?cR9v_0q<~9PA%)@vR(v4)^t9M1cQ$gcqvI%rK))i`3x%zP-^Ar5 zL)zhTZ5yI2r{n4<&^OnBn-pE|nnJT;lw}5OT7^NPM+a)kwXtz4-I8UjA2Ge4C)v?T zA7yUWn!k3jJCs2q;e`#G-jc@09r8Ghxf9$OpPZLDvMvDm(2^I{$?}z#B+okm2k{!T z?Q*lrtfx4O-w?w?kRpv4x16NN|T$-K<|tms5e^k?456i z-5s`t4{7T%B9Z00vZ3jbSi^O#ej6_J#>K++TlSRXoPosVQDaj=rRgA8gnWUXuZ|${;0f})5ATFb}*-!@~tfY4g-@Qy-ZhE>2 zh_s)0)hqDX!zT_PY0y&;^ETF3YFB&l|;asLVAh(rdcR zw8R!_@i_(X0v3$21@!zS&&l?^WdEYNo$jEnc*(MtD@VOh3`K;2PK>p=)2rA;N+k3r zm#ye6FrZ6ed!ETXM1pRk%LKchEz}=4(a2Qf#k5Yh(jjoZZ5KGm&wLin zBfX(Ae;Kekt+)2{((BzAdo-{GO z%q-_%0C1+igSjkA#1g>)SKcxz!HEPw+4SQVVGVa>Q+p0`r;3(R1twPs7%f>T%l?u< zl)gBDf1L^Sy^#D8I$YJu`wHpM;{q(( zIp7C9Dhb%MFVtZ7rxNj81woiE)Uqk#*Ea99+Ub<7MTv)!f?p)dUuYRm%4ry}6QnLR zdnK)3T9k?~MSiWPfRF4=c_>U8BCl{4Jb!a()o*uO1Y`qPG5#E7h!m+ab`fy!K1yrZ zBPelkesxXt0g-LV-aJRB;{;iRcD3x?CjQ!w1E^6XoXlxXkk*x6TdSB&H%(&Z{`m3Z zGnnDjocFic3dei5+sI1Gn$6wGLyOfC>_~v)q?*tvj@#+o&Cq<*h^Z_7q`L*c@XuA0 z+>hKQu~mHI2uB7-x5W=DJQND91?}L2BbSs_C3uf~NZi2bt z)9$2%;xzV`5<4M3)lK{4=V+ClBVqsIrFz}@y_lTkOLJLQ*)p*|i6_<2Epk!6*Qo;e z!H{SNaP^ZuP*EDUy}*}}nC^i+Daea0N%S=aSaz<&ynCe4r7Xs!&?bk(i;6&6Cd0}Q zzpvrk;bWH*|HT^f3n5Jnb-%=%uYJsuro)drVcD1OeKpY=qET}^ttF=2LcY{%6-@5q za@pl&onNhCFcVO!I8z_aH4RbB@g1VQ(&)I>JC%NTwhBI%rSTYix$HBV(9v*)`n5}o zDSf-)JW9Wx)|XKFXm;xA1sD|dS6|gZRU`&_%Op)RcDXZ_dqcZ(Y)J0zbPvLF<|CqZ zQ>L!mo1x$OU3JWsfIU+AuI4>rogM6*F2R5|eM|0Qf_O2TtpDTuZhSCtjP~5wm9;9- z05&@J{A6Ai>Fx+Jrtb1aEv2Jnzgkc|*pXO)tn;T=vD_X3w+kuJzSP=U6#7w*V5d_rSHj zM{t80a(d`HZuVMe9xc#lW@&V=ea}<*htfd;p-~a$id2L`Q9TmQUrgItxOjqy!xAA2 zM#oH?HDWgJf?~<}=s(Y_#*Mns_deJs?2a~Z6HP_(2fY==k?xh7l~2ndK~NC5N~9oY zh)m`_ejhb{g3e&Ow(q>fFzdime#^8HNjENQPq)g;72Z4w+gLF;tc3ZEiSvHV{gpz{ zIYL@!I{%B}Z|$~$tcJcDYuowD<@3vvW%ro{+<+e_hSor~74bNeA*EULlXi_<4T$8= zy(Cn+tsffSZ=os2z@xlnuSq;p312oRb)No@w>AhNH#>-j%V-92cAObo;T^x3+<6Lx zUhOvm1p)^9I*h%k#Wa_as73V&>DF?dVHQqGZw;Nswx1X*BrHORbG%`ALB1CP@qt2V z*Z0o1^lf|skQ{L59NnagJ3#)jUup4A*{c?4T0(d@n%8))2ucv_W{xK0exnTuB|*Z_ zgyRN!vn)b}?=QBfpB^>`;wXhbz5hM=tdS{chl^{N>UXIo*7AGXdLyGYcSckU+)w9w z#e$e6R*UedzclBW9$SMC*Ee~aUB6Bz5uaM@f3dKaV-ot4n+BCi!0?)qwM@{q(4$-8 zfy!;-#|}t%+`Lv?2NG*uL___2V}6-#85SQOk7jwgZ1J@G?e-q1n;2J7fS1FhTp^;^98?RxM`c`DdweoGsqWl^K%h&jxs|88 zlnvOo3`imPIgQ?9+5ne&$wzYn6M;n$EGx(;94N4GZ@fL=Dg>`h?Rysy2kGP@*ZfAv zN#Z5A6-2tKz-qLWz-kIBZkA7bU-@Z{#BYbig4>unnsHvP_W7q#oFKB z?;ZU>qoO~#XtS_tX*@VXEmc(@QV!{%@ea$p6MMhEYPYlxuRC*y53YsJpOE>gYiRWE zcv?|J5=AinvaVnE1gU6fEFal?`~F=7Qz09G|5jP~>_#9LwOD=0B3B4gK^2LxfIAI2 z^k3pA70bYpVU7NwAx!5&h2SStv$_O`SYL2xQAKHBW20n*9*}wqe+=o(!1PtQ3A0>p zSnoWuZlKg^j7Z;ThZj|vVVm;O87UEUVCR4dQX)=I!7c-_J2DnsGxSu{h(w}jPd>w= zB>1BZ9Mg%RvYG10t&RrxfhoJCR%}o<`|${G75^TT#eDg^_xg|k+fa5zLYK(${%Xfy%|A^vGok>uTlzJw2 zvD;b~MdWM}(?j{wj`$cDY(>(!)bTf$Let0y%=a023$Z5vAwoX+{ebfhF z-eyvFylmAgpQg|6-@x!P{$s*Vj>heT!ipiQ+Y4*6aJch$Lp^*m0gl0RC)jbbS1tKl z-0^RA@)IJIeNxT_a5qOUU-byX8(5PqpsETaQOMbt^5xoPTvRQKyKAvr~ z*D|O!>L~=mhi^}omYS_L0WmQ#$ibd&w4dyhVUw25=P_xi3xNgto-QvW)}-AM($Z?$ z+OixR8~}pjcjfk{ZnJjBLf^k6CN^me|JsUfLR$Jh4H=Ezn=p%xj<&tp)uclB&gzkJ zxw!+ao4$W?0EV4l0D^nEf=#F{xj8v2aTNW~6crVH3SZnt>_*})#eo-%mFojs6q4&_m)yjp3G(I5ay>-B(-0rEHI;S4m)!F*&wHTp@*fudI%!T(3PtD?P zPH1~;(ov08ghAMI`_stiXz1^X-PvTh)vhih(ceOrgd-)xJ1X;cPoq>v(KikWdbf(;@;slP3#uets$&^asx-PGwbpK|rwPq|K7xvGfV4c8UdBL@sEMVo50?CMDg;Kzy33U7yy5qtbKSlGS-y z$Q^P#8Dnw1cXN(N{qn`dr_iyM?{}q9fV#1<@ozo+DVg7%NUW!`g~S?`Y{G!y-m$PI z_xHDFX{f=;SQaw0nUcRU>;`i=vq=U+XiKRKyfWQxI{pwl%b!G68`VqwNHlg?!9+%h zr>YFyVq;^!luf$SBO|r7hD|uzMfS=+*7raJV|jN@Q6}HWKk1|MyE)bpeo(HC)<p!ml!FB3&MT<<=4+6)SpJzpmH`FweR(1 zpGXg(at;ny$OzW6B|bO9DV!UAz2MdPs4xfmb3cj^Ln>?#XlHNF=ZC~eQt*5swEGMC z6{U!yMidt22@m%c2v33486W&Sq=zu`LaDnS)`5&cM~#U($F?HxH4xl0t&?+5VN(T0 zDnAdVzr_GztV-R5-eOCNiJ_2j<|5&8&-s?-e?Fexv$~$JC={Nm%EJm~^l#nJQ8^5x zv+sfoIWy8r`9(>uKtI1EOxs2^2*I!h(@pUe|GVG<^*QS6>$^O*{`Xe2 z@c8Z-#{aI+xF(A}n811d*8$CG!Lt8d{O<$NxigB_-o%ZcRv#@^WbE5L^ z)?(g-rXuop31j6k+yB1yzYotQ|342^IojFTL4uz0At51g1zDMyN=Q}j;NT$RnDeh+ z-omfNNdGPBNdGG-Z7VV4$A2w_AtNhGSx1LRnbt?IssM3NUYJ@~SeqC7?;%qk|MwlJ zRK22A>z7SVy5I|Y-a^sHZE-*q6~lkKvWk3gPdFAazhrV5bw65;d@WkQY%Dq@*UsTqoK>v}ZaR1U?%s4(66y{2>`Z}S?6{sEh-=4jcMVjQH z9nX_nY2^TkD|-LWPm{8k)78*4!4RoF*LExu+ikkqKg~{aWSwWTE&-;18@w9Ft1-;e zKX{7&-i)xsOZVR^Iz+cl66cZnUg5U$tYj-gtb(7+H^!ScG~od-va&8ui9XZ-0fRkH z^Y(q2Nz$s}cz;liWziH}oG-b>!Gk{CPxVs1=L>!B^SL4;7Wgh2a91m11otbrfp_MQyV}(91agfCyAvR1-Zxv%8$`CiQnV{yJOb zA^#nt&|kvi?Kq0SiLa`Er%G8CPSQ)uHgm-YG>D;}pRv@K47IpHb|$BEZaZ&gMIp6T z6i?SnM2|_ip9icN#|~Kpr&O&{NTa4B`VM*zsvr8x`W!CD{nkW--~72+OvqzR+oJbh zjiYB0eg!)eEeny2%sLbQ(iX|9Gy{nw$$2}+NSy6^ae%AUf@1JGNivT38}VWg&uH@j z?ay{=yz&lTyzjkKf#G2TlLdVuXL}ohxZGBMN_OMd=MTsQLBQjmcYb92h%mz(*p5`D z8*k`7i6EF@{j+Mh=hMD(uOGDuY9E=R<7CQL_YFmw>7k*y?SJd04=Gl4bSTJy1*^jB zK+;-@{i{^yvly4owZ-@gLgXYV+8)2^SDNfc3fk!k2dmMTpT9d?1)T31+}_G@?%M~Z z-w=GZ$5bE*WXmA${8ifL{5h1ByE>n@GD2W;WUlSz_b1L)p7n76VqgsDw>RK4M7Y9x z#`k|R-;^#OkHzkS=e{#GPS@ABl7{`Ga z#WJ8g{px$FD&{~kNmhTkY|Y10i$6YMq|a#Hk>};XMy!tg2C9~WR5Zr3BGIdAR#~~T zaIyxb-p<6fEc)P8I6{e5!DqgwK*lKYTG}@x7!FVxrChDGwKVy$`=#ugNm!lU_7yS> ze_-VfB44;yF4T>Yz4UO9QswU-0G!AUA(*?FWN2tl_Q3&eUeWK>dGupl^GiWV!i+)9 zyFPUOc_EWuHQk)RK1xX8Dr8S+2D8ddYF4Q&w75Q7>wrs%nRUkI(RHQ6(%=8HD;P*s z<56oRHd(YZ_=PsyxQ0S$oSnJljKjtV!7EPl?(;{?RcEVaS-)^AbZ${eUvNf^tn4In zV~FKICJ~MH0qW6tU@i3u=GTo??)dTdxuz7U={t=h`*5vE^oBZ8~={i7dzm{%o)s~OurmP&}BL_8%xp^ zc>YS}LtE%ch5-?Pb}T1LYp=+eTAb`^`5{S1FoZ-Bh=}8fQ2c%L_9w`ZY2^fkZ6I!K z>tIi2yY+_EDD~0fUc%6QHoIxJhM4RB#(PQ)Io?Qi%jt4VPGQo+D&VcT_sflq4H8+H z@Q!*G5g9S+%nX=rO^GZnVt(KKmioQwyWJiNB?_CUtUAYF(j8KacZTD5isg-VXZH1r zSdB}5!Tb%Ui(@Kkd+>?K*ih5^dk3SnfG_s4@H8IMjS{?q?tmP1CkTcGW@69^l)mqB@UdGJla*$n^VBVLxf`ysYDseUeR*TtR*P3EoPV*mppJ4J1W zbx!c8af>2Ejhy?VM3oFM(SG$YCS%F0|CVC(?!5c7aMAs-^-_z-b-1Qg6$l8p-Ox7YzZTz-#t^A~yBv$iq3;>}I(r-+T? zD%R3mKlvhrJS~Uj&n3R%&2HO~mR%vQfL;weJ4Z~m8~7+Sq!`9|51%od4_wzUm+r#Z zNMxF=eZ}b5%AVD@*$Hlg9(k9o1;6~Ri!0iB^_)I?=;E9@D&=EUiRFz_19lcIX#M5nW%`&2Y?-~rS9%pC#ns;xbDMr`jN9C}6*`sNA zdFG~cRf{#8j6lCb9I5N@wPzt{l9e95EiC(-p+2=Pb<*UmZf+no+JBlu%L*^aOb{v) zQyl?K^ok?vvNhw!{r9mDXkz74kZEb@D!BL)MZaQ%uBl_`RDBG;lhjh2S~R{E!!ibP zC#IN1zB&nt2^ekkx7?MmT{0sH^1&nzrW`;g=;-NrC3*i)K{*!05HoaIprUlLMctL@ zg*&GO4Xap7+8F-GlVGdU9E^p42H;s46RWzeU;Okr^FRnWQTQIkNzKc~-_WlOY0^tl zv{zklBOtPren;Os{xqjr&_g1X?Z@r5n{C8lk7*CESdp)ny{nnAm2(-3CDPS-r9RKQQ`-!JmeNN;*lFZj)ye7`0+}4hx>c;l`s+&;Py{I(w5ZN% z7o*cyTHyDrz&n|gEc{{p?a&hVbn=AZCwHWV^85?V*Lxnn(4%OLTl$pLR~es)_UiW z#roTEn<-n~9535R_H_~uih=C?mi65}pI%a~fWyhm)#m-PPYPv!TWRCRc^i#B4OMo$I7g4Tf^y_!+e z!>vxPF-Rv3^PAUnqPy!NAx`~;N4B~;hmgAQ^$s74R?t`Gc4Zrs&P16ARGGk3i&z1=tP9xCy_fFfaa zKI3GQ*iq{q?GJCSORzPVGf^iYkvz2>CQd)8w`er~+ z=Z82QS66D-mE8*Hilnd#cNE`lB1P}*pFNEW)#5bx-Krb23YBD&nDsiT^}@lm-RC-u|zhj(5PNN0IrSybjL?WoM|2DHn5#uxMZ z^x>MOmv+bZ@a%M!<5M@|R25A@DOV1ve)hl1&S>4P>|@%RK8;J(gkJNs9lkSNZ7uMD zV*tI~@FUSzD2rvEf`%#gM~|1RZ2c5+{VKfv-V7P&7VdK*R~4Q!N7GgU>+{3A0kxO4 zfHSs}Vz308NzA{^%>{mbUgRUl;f-lJNrvUyAtF21@}jy}pR={GfI?~?*;-D5t?q_J z$?{AiqD{Z%6{0LTjbSC<>|@sB-8fO?mQ)3BH5*_ZX4P7~{Q|iaE8{)CUGR(R7OpeG z4fNIgu5LgCn<~m-a`scCaTZcHDL=ia-QA!x z(%lRVL(B*WLw7d}UGoik&b{Z}`}_7E@8qtv_g?Q_&wkc=vl~;6mab=~{hrd-Tj*WY zAv`0u`i}^je~7usae^5sU^ZLxkGYqm!niK1Eve}@iN0ty$6G(QKMt~Fsy2BeyO&L3 zKzo`#=pVc8(CvsYnYrn$@?;x)tNoTGw+O8;>(nr{D5}JN2x(KiO1ZI@Mqey^m+Ub7 zU0Y-l4%+Rv4zf?vIi%2w+@ zuAGd5wc?$3OJL+#da4W3B*j)OO5(C5)xp|)hm4fc_0`UUQY6-so_>E)`0>J&n6CHp z<5JD9zbbelcPoOsNLk6Sk#puL$()el%r>!_Ls|>l0q^2BpZ9^&!B}<5)h!sI2Krnq z*4T~rlb)-nypNs}h?hc1oAzD`ZSdz|jz|&IID*?2Pb&GFPXx<{&~#X|e{_v8dNvD0 ztJ4$p&BdPWK!=ASX<~H?l54gs-3Fh6f@ELt&iHnZoHr<`x<5+zYE`*prJqo>6l$w6 zUW~1x(f4}6&Vvo$M+lsFlZ-yNh0DvH(U}DpbG`%1?$W%2-b*CQ)$;vAFZR}?%9}H@ zs=} z*!Ot9l~4_d99}QiK?+jYiCWebo~EP# zv9)tN;&{Y;TZFFKz8OKKLD!CsWw zv|uur8IG-2y{|>vxEZHeIAr}qka8{df^=AOYjfz33^21EvWQeu>h+(*UB zV?~qa_Y}|&9s-Y*-~7!52u-8}MOw$}NACA;II=GuaHH_n>$Opt{#4nkA8!v!t~)q7 zsdL;|6KK9ZShjlUp#PO&WP3rj!3sh2&5k|%RUf|<6W+QgSd{%bXyq$W<>{upqSmc0 zh2H)oFrzahJ~l4@zAfT4kk>`b)R<(gbkxdWen7TIBR7tGypUD{hqsw zppt`m)G5VHxjt&0wo5t!j&5e0wj}Fud$^V-(TPVkRFPa-qF!?1fiYXJcJP(L)UM>X zO|Rq0F{_Z<*(6{?=G!_l+Z(7!oEApPC*HOoa&U#D7uYB|d%JfNBNKk=ZdfH!yQ#TYqLsOa z)`;9?{Z0?R^z})#UaXNKL-hq3R9jKYz1Am(gxNH@Ga%O`c_6ZGWc^4CmA1_diD6D!;@6|tMz)@F5vFk< zkJbK~ok*;)uTOs@wnQ8%FD*^Y#1wLTe5}?|XFxPqZ^*<|nl!bu{xvYL zZmZ=%rr)(*#_H)+?T0#_e79y*PLy?Od(PK zhjjkD1y-In-EYmIV|k};G_5w>a>DKM-#x%Bc-vT+`Y_?NxH|90|H|mQxB;Iz-yGUE z;(+1OyXLxT|CxU|%bG1V*`U;)_uKG$@Zsv~?2mPa(G4K(;r@Pu zyVSGw?H|CU{`-W_E_yO&c!Ywk78!PRCWnxap5tTDIWB*A#&vi{Uu^Qp86KIA{5Ok&YTkb(gv@v9gH#`A(mIio1q|phSY^?i)-??+MI% zf`OtHz9ko_n!@Yu^ftf%beo$r-1+JuNjWsoh41snWZ=F74^fBLhxSfo?!`}!1ur=% z+*d#Ke7$Jmn8VXH;KLi`mP$I}ebn8JUwjiBD0w@yYc}5rjh7dNHP9tCPf#4o@seCO zbS{4OYPyH_A1jWQyFt6r?6(fUv^1E�bSK8d7i?|EwTtdM{TNVVaHiE#)M0t|yqr zW4J+C{SxVpqBuAUDOFaA_1)iJUQzPe9Is)2tapGL+HV0|>0iHkobT{vp3P}%Byc!? zc8D)E{mt|F87B(%GM(NcGYq7U>SEf>6uovS;C8=I(9K=foViiE1L1W`NJCF1rE;RE zJ?VMR46*$>f>iix>$}p0)DWRtSJ=~?*yoB?092I727jodFpV9(7Q$6f61(pO2X*M8 za^@=gnG8i~i%^{hn`?$QJJ1Rk>3HRotp)9L(;uEQa!v^I3R_y{T*NzShy;Dk5*tvs(w#^nsOb(-@O75_|)3i|}9dCZYW2B4$V0!?!lRck1n7 z0YTubMUu)2bh$*40B^44F)@K18!!OQb`g-_>ebtS0)*dkKZd5cBdzWt%ng3n!6Knr z>8%q-5#iuk{gA68WYAq@$q>FXAh2E|ReJ73Oqu}f4mYQKb(5v8v0mx8p#ybPt1FdD zKM_PHxQ56oSC%JDpF5vc0qV=c2!N&8JCY))f(8GoKg8$G3*k(P3{W&83%&$v*mOOE<%k z96VH}2QBYfzBsF_Db~4ou8zIq#;|!(6hucyXOKcq>2*9z0Tcr6)%Dv@l&!MpK2mwHj7_^=FH(`V zpPK_6wEB2J6>u;>$>M$ZnPA2P>2)ZOWad5Jmk^)n5PZn3YzBB2ys1AX%XgIH{&c={ za&RqN_F_I(dBdp8938^bjF`7zyVytLWltSiWVTuD;p648bXWb~dtS8uSVy_mb3N@} z={a4roL6!S!y~coM-U?^?zH0DW0ZvO*0}8+GaQ@XJZRju0P`~G9AZw#i#4E=tuYQq zT8-uKUHw8xaNO+~4T0M8qZ3cjVfYNGfCvLFO%^(yZF5vRd~P{ZzBC}!U>905zkYN( zX4A|NZ9H(q|hEd8S%u+SOqi5{Afvr~uf-=HW^;&jp*Hn;X zk)+R~T`UNnJ9jYW9=b58T7%%dA!%5;*byPpAB;}J+CardvqNv7?t=s^u^;LvPu8h( z_IrArN61A2OP zZFF5pE$g_-YZLLEElD-A5j6P3*5@8a!TOd*#WRb%-!#SQPSKhSNNBH@$z>nE7p<9aa7Q-asp;@0xY9)4CB*VI%yzOaOKa<4ueQ!w1w{!y#+VfkwrA#P7hKc7j8$D9e7s0H zkyWl8a#GN;#UU|?s+)e;qbdxkcQIjHP>$w(M`*vIcI+bGiK*xsn6&FF`O|NEI~^oS}KAs-z6bD9u?z(dSk@IDf38ZDFP>6y*vZ9G@<1B~;D4Y9G2+ES84m zKvh&nN&xZY`O3Ba!e*b7bAzRQZ_e#?W9(Sx%1$zTqA&E(EB4Gat0V?GVOISwKHyHM zItli+cLHMZ{cM?6kSnfID8pp493%~`L*jNr%q`_Wl8wF+u{nDm>@?oGeyT? z8dBW|Y+YDTkVu4CgXQfvY|klJ zPgtqa0|siPIZqBW??q@;vu1jHDzG-)I`DcA}<3c+eoZGo?SFNQ!_&Jc7K3K1Xc=N=q%b&rbg!OnN# z6;`FUY|qJDUzs1j<>b|pA~s_`64KXMj$yFDVGtlN_P;*No9Yga>pOUo)j?BXK*M=W zP}h-e=VI?M@%{W`d{+z<4aqOcdC1c#HMLR`nZ9G%b4!~3eobY`#3R0_?;Je+`NBqP z%Cp9>t8e{$t>pEJbA$N7ci@Ca%afCSkNK8TVupkX<2t7?w~7;aT~AxwG0=`e?he-1 zN4rMLx_%)wp?2;!A0tf4#OOr%Mm&u>g~+mx@P1_P9w9!Z!)W##3MQQ87w=_a~olUXFiX4}*SQGhVf@FphsXXjq9p{+{F*(3)XugLi1G| zp>wRVtzrr)*ZP=_f`LcSv_dPHc|W#Q&giaR43HA-_T&`5m&BR2%5*;iA7F#Wp%E@2_w3gPmBt&D@(GX(?tv z25Z33uE{u)Vfb*pi0(FAf+;#1a%*oA9oD=$5@ZWy%Ps01O^rIv2}tu!GMA$?Vt1vB z7e~ye60}Som?u`SZ1IHhwIa~qyV&lf9~eqgh{0RxKD@S(xuxbk5p^!GJ{$Ykc`9Mm z0OZkHUmfuWFYewlt-iGEC#sDY*#Oqq)Lw6+uI(FvXJkInBBb|Adg1P|EOn8ad(pFd z;c%Qtjd#BPR2byl-W>CW(&z3;*|Cl?{=c`zg;9&h0H+j!E`xLSw4tg+YQv4r+Z&XF z&suF&Bj%g-3{9(YB2gI>d$z`k81-7O@g@_x4Gk`iR(~O_uDLVyl277(sF>xGR*J?z zXh>JT>L1G?Lr2hMr`+|)-R}Dcqk(`#X3S!2$qPC(#Oj}YcMpmFwQ?xo;+c{JJ17uH z6RF{x5{xk$ALXf>u994(yUX^^R5)1`yJHGg%x=BdB^M8qx+TMvf(cO12%jd2ttE_3 zyl!PPx4&mf*OY6+#C})&Ka=!OM!IpGN_X&9rp@X`{%Hh_3F9QIv$Fd?%~|2(I>Zl57GSgE{94VDS3+Q;K1O-+KlshFLwkiC7%#^BnOP}J1a)bj41 zb^U%Htd1W4uE|6dJ~&W-!O(1^l}?EkKXBW&YB z)>^G7o#w9A=wC8mn;6vZPEA!DW=Du zB$tTa&HKnq*Cd^VMJW>2ZTMZSHwAZg=bP1JWwB-z zy?kv+zW686-d$;v)Y<}(N58OWy)6i#8THO=zl;2HIm)3EnB4tUsEqV-R{HklK1OH# z%}|J0JTfFl9ypoHjNfkI9s~k0|6#R6k(tL> zJFfP3xBERFHJga&pHTl_aZ-%c{F$yoKc=}bH?wo^KGD80 zy7y0A7$o)M`|#r3x}c?&`A;A%TBY;n&wtHVFc*zsuGroK)a@6$8D=(jH(_{>uE_vp@uH^!Zb|ltvu}5VMPg;VG zR6;c-6SGt$%6Yz{>rK4SJuT@yzcJtck;x4PfV?_XGNqq)mn!kRoLGkCXX%b6RI8o_ zXE?gxH|)vFBzh*wgK<)wDUG%-kNVm9VhxthJ|ONmWOtGi3lOLIy`ZJ8V~{HK(m-!- zXA(@Y&&=oCvqQ(^?sB`(=i)WM02d}cf_Y=@Tx2NBNhS+B&_}eWSM9gydV81L!va%u ztFAe-y-9ZE6>&Jyv@io(BLg>p`{V6(2dt{W$p^0kNVStp4W_;uhcIG0?LHJxHV9dd zb&PjUhtC2bt1L1I(TtdJQ^EE)(^jW*>J^BeUT1uNnOB?ab1qR;ltjt&`7T62vs8m?+DK%xJK6{C@~5+si2mq6u)G}`IFzzk zVRt7Is1$UaElT$w@DPfkSS6)UN;Jfb*{{qGq&T{Go()JJKTc`%$CoOU8q0uOJ{%+^ z(-sP$7%KWO!p`n~bcy$&i5vxV>8H#Xvy0yiq*TxSxy`&pt1b{#HAjkJsV?;Bl1oux z!sh~GTO;ruqIm_pt{B{QSxtF>aEuzg1>$ zl$@}*WC*r)_b?seSxhWW!xFMT@>AGvQOdL+M?4BDrMd@Wtjo%Q%8NC|G{ zHp?)D`bl;|;9*dgu5SUU{z_NWhVfz)nf#+k0qui(1ZZxb4j{IR7dWV1C@j^>BNy8Dw`6>3Tpj#9|4LI=4qE4gHE|eTs2N}*vhLq8zwhDc7^q9_c-l~lO zWVQG+TBrE363?ax^=I_}Hx?}qxNkUcDm_KHpVj2!%aSY5(ijDN!Jl2T5I zpqLPxP{g@Ag?jYRL5ng(xhC35fC6t|vB7C5IbzDlbtYoBFEYIkhgA9FrBGoB5MFS@ z{U7(nIIGAY3`vGG9c?>%`}S_|{mxf*PA)y&-N{;7^rKbo&t(XXI_vbMEn3fU1{CR{ zE)8@|2D)70%BErk0&RR)lZIliepVYQT?1|yHLLJw)H51l`El*j^h9^0hGHHa921y!dr~~&ZyPz~$^9_4h?M?7 zX1V`qoZ@k{qqr_f=dWA#pVeZlObJEOb?k^$3o8Xb_i*z0R)}Nn%^~|IAJj770A#yR zbn!kqH@WG@&;IQj;ZIp&Py$%X?YAn!t4QV1%J?=oDT?2eu76*X_M6n&V*$BFv_mTC zcdz&7$MY5mF84W;TYG!_-|=2*VtUUIn%&0>0a+Q%8jz~Lv%3CupT6aD`39#3KyFQr z=dj=MXqkfaG4=$JDqaUK3HPp5lx0Eqa-vn5hDnTlfPbQy1Oqr1zq4K7awgPEKydl< z{TGq1vUThq%xj31Kh<9yRAk5da7nk8UTdhEJP_J?Ld1Qm(^zdGUFD%#ICm+WKqmW= zXJDm2!FFT1TFBqa>wsM~RDqIx`TgM1@N^M0N_u~^P}<8vb-SmSYjG!SE|y>n<>k`4 zpKS$GHN_F$W7`Msk6=L%Kn0vWRm5B>x9!c3)+6EktiANL?e?qiyPHG&C8xcW;wPR$ z#qgum!m~@3)4YiTO+F1l8~y>It5-%-q}(jgc(CJ5a7@c9o+iNH;F-lT26nx!k2At; z>$%lHSe5-Jg%vE3!ac=6N{G<|(+##(%9#`n?zm3mCFY+LT$}r@{C#qRO0==@}`pzhYGv(qYdH?rYA(Yg?b4c-ro3V z1yIXaUYr<1%xhH3-Uxm7aoC0FNRbNjLO`e^y+eYRPc+wD{&55cp!pTV$*z|9TJS=3 zE1oq31iTl11vQ0+C!Ou3o^nV)-~$d z82KQe2vb!SzpJ#wWp=*z*q|(pNDFseIq|T^F{y* zyoRnR6YiPKR)olX>`Ok(#_F8+wHW*j#?+qeGSz^>r~ZZ@;={IEJ*WAC&u3-lw?lbx zaA>6M8)OLX*FCxETpQC=_dtNwICGJ(=XHUzGE*1$zy>s=F8uv}Oytd3nhN*qmqyR6085su3<9sLnruqedBhD-u zA0S8s`%uBi1Af4cv9A$2a@Sn#3{zV`FT}E9zXv$``guj{({$05vec{dEq|tmsA}I& zx@O-CzZKnWI>GzAFrPwfwsb053%9R%>y(zgsrJXTqNNko(et~rG@|2-5;?xe=L5Kj zMItequtC!$`qcIZ^N-sdOR>{c^8gqTYrVtQY$kgy@}xuER9ux!*5fRZGkDFu9Cl|8U zgQfEUOJ`?-#~GE_%nB-=Kzc9Py!;Wtfr)B&u5Hk!6vaU2KFq@b6XAhrd^$3(c?NUJ z5WJ>-2jq|ETo+qm8!v8pAH2r;5+C}-Bf#KbVLKl4F=E|Z*-228{k6hQ;j@Yp2Jfe( z?dajn99Cw@uzZwd2%quDR14YU8N+hX&hky7gd;;Fqc2d6V!7dIsOH5wJ$+4IT;B;@ z8f#`tho>h>@&Qcu^hP)lW+kg(w*djW!RM8lC$3x_Fp{9Pet{DrAVOkqKsevpqg?ID zTle6l!?+SUGrUi#5yqpGh?xw6Umll)1P|-X*4A2fCJ*RTu_G2%6?vZ#K=befYs-fy zM_bRz+>Xzqfmjp<^9kaBsm5o?aM!hM4*7$=v4}#TwJAI=zFBYeHbhbV2dBx41kR(O zGL3Rm(m?jFvpS~1I!MeL zW}8rKwqEh9W53Z%f^GzX@~WZMgWA(lL4S76tJqtR5QM$ghHeD?X*eZux_=WsM+`LW zs~63_dLk{9xx`+VGg~w$J3utDM_!BXohUwyZEp;fSZh8bb5D=W$A}pLHrLuyHup=Q=w{jU0lK zx9FeZ2INf{kdIgPH=nIzbw_AHPX$qi^qU&f!8)G~4|CZ7qOLD_TF9v!9y@~O74;D~ z)oeQ1s^8fwq6qe(6o}sAHr;BnkpuqFZ?pEZ=U#OrGzeS zq>CvM7#3|O(4B!X%`e)-Oc#p(U23ODh0wG&%+v@x_cat~7>&o@H6~fqsc(~^FxKCYEVt3~-m6uN*#;$U3ES#{M zl~({l&CaT8Db_lTeU{ERoI|b((6;AgG46wX;cJXro9F?>COu24z9G?t9)9!`9l4*w z{C1Z~a}s1E${5pOq)WfT>E_`{2Z)y6@h}0utKwbd=Lg<@oOQ25Lv&xgV;l5FhYw}@ zP#kcUh&?OmMAJ6Q^}0M5)@6 z-p0rre|fytz*14NOt5V>v?#Mo-8@YtO3Z>v3`jX#ll8XxRGktPSKrqYSEAl*lIl~e z$%SXnnDlc(V+583YnxiJdyroo@16}rv0=%8u3d44;|kWMUh{ZTsFSvKmJ{3>+usX3 z7I=xHfgedLa^ZU5o=gk^NYM1k1GuW0q4A9G4?nSUtVLG67sK7+W?YBNI@<_025FMQ zhi|eoRQeZv4fq$gNTntLt}%6KD0(JR=s<1q^n)K08K#en_8Ax#3QH78)!(uic(^Uc z>qh`^%c6rFvYeXK3wAc|X&jU)rQ)i)R9p>q(k=_>lLlv;F}4-rqX0j(HTl3acb0Q}asmHqD)M(?tbMIGaV^)n81 z>Np-ppkL2!!SWB4zgTzD-pCl#M5t<({Wp)^-k}Q_Y%bt0jTQS0Jz*K`{W@k(xyZ{W zN*xc?1Z=*hMp3k_tbw?aaWgV0K-IaQcdl(}sT3a18pHc~RLFs5o=OI6#zzeyLj;5V z1EnkAbPk0j1-7F#ZcSH_hop0i9%+$GhesTC;Iv1H)0X_pJ5O*HarEbwI{c*^5(d5U z9WeQh)|{)Lue>AM4qmwfpQsR-e)v9@K0mEMe7s@t;rKDBU}h+V!0rsU-`jZyK}MQ) z&au47EQ8lWU*|Djq^5A&g_<#7(N79tDx`#!#t(W1xI_#P&3I2 z2fEbzXENU6+zVxx(_F4jIM#JD!B_+wv`l*N`a<=-&bWi!1t&YHWHV-r8=NwxL$!qZ zws7iB#O(l+>tSg}%+m_~hE@D+L(e+kV=o3Ja3$y!r@UE{E29J;wP|VO!C_LD8ZwdH zcDx|j}mAd^m(}A4x^N@Cp=@*J*BdRIJv6X^^39DqCdVr$ei{RZMA=n`qw0x zSx!+Osd1lUcoA=3%8Z{8$(~yyok}g=Q>@m2swUWOW1ZUyy;&OSUK|a!rtNia_ba@m zh|;);3e7THr#*tnq7@p2O(ClTW5$s%z8>ynOscIdYPE=c$$9mwr3M!Ya=en!_mK1r zn${wSH6g^IorChikwJw6b+fs-KHbwOhbCQi@P?M|Zs*WGG>Wo3BL23R_GhZh5)Y>m zs-||;OoIZyz_J`Iwz@d>L;!0vT*RN>4fUWS>YgsqgZBaDmcx?A-f+4(NR3Y+^lop^ zMwOn=Kx~9P(*B5$kZ(rFXnVeGl8*d+KyTRR_&E5ceg9lf_c!z;chVTX;FjH9RzEH2 z4beP!m}BcS+cW$fnOi{V(>V`T8(p`#%?~kb>5l!gvPP%wu9-blErDECt*#AD_?Blc zOj^m>F0(q5RY!#{lVXl07h?!7j=CDk>sP34T>>R75s_o-752Bs0v*u3EXi=aeQoR^ zyV9n(wW$;4ufo5ax0SBUQTI;tau$Qy2QNJD(V?@OL73D(K?;wF&P4x-;V>|)#?BUd zCXcM^)C%#1K2l~{*frD_ewBe5UfZSFM`e^AdGUP^pu2UB3z?VCmITWYB^0k5K;(wb z61Z}u*RJZw8;EVsiqb^z0;C811h+L6GI;v7c7q=+rE|VimHv1k^d;KASTnueiTWY) zg%L&EEG_@}Yu++R>;Y~{!!XLxAf4bQH7?Aos?NO&uboqQJg&8tYn|`C_~y=tYnZR2SX zJ@FI~Mv2MtY|jE(nxOuHVu5t53?olmmJeMvgMh;dRR%G)kKL&pai98k%*_uTcr^2f z_#b$wc7lWulCI#`=mpXn<6q4lF|pq%@J|}~JkWI~n->NdeT$>UaN1U;Hb=jD;J0n> zt>@KELT=kqy?~v-eyj1ZetFbTu)pSR!ErWmEdOWyHZSXy=u=B}1-b&&S-<^6mbC?D zFGhf(cv4=l!J*8thef!DN)=kw`QBrQH0mILp|Lb5HzkPHghP21k`^`Pgndyip-yE|dX#X225V+u~d z+b_@|6E*UCP`J2K->a;ZiAterp|rJTOiYOBIco7`NnSB-v zuK8(+E$}1b@Ef}660YF>ZaX*@7YdSq7owk=KpBfM@ir0BD+Wh4ve&wCNnQJ@nvQNp zX|ExLFZ)Okm;wgaTBzeKfatHc+4itU9jR%$>H-d&_*}1AH{F!|kU06-SpCUE$GOY6 zn|Q&GmizDLl64~YUq5f-V9X>JdfPyR+r1kpUW?Rt9$}}54_+DdEN&)eJ>B^@^K6uF z7Ox!QY%7<Nu$wEUJZ0i3 z=c7d^G~jS_Pj(o)wUgc67+z*2Wbi1Tv)U>-7DVsWzn^bwAfaP84a-g@{1mHp()@Au zozN(Wn48;qy83%srE%H>Mc)zSlMB?DPn_wiV#A8JwtE*5#M>P)yZkZ!q0$I!`4PQV zuJ}Sf5O|~g0Cb6^Qf&U+o6wI%b?7RFD5Qpuv3X42$R$?cIo_Q3ssXPEGuCW~U{uLB z|HA+<`t8CqxZPoctM#vG>+b+_^qOr=H#6*CFYU~{dPjIs`TWm91Q#|}-|Wv*8>y1Y zf_Mbr$tbs)^Z4 zfjbHrLGHnN3<^v8Q7@l}4pl0}UgW=#O(AUJ;~Q@)vSI$AcNwiT>S{;Vzp@srM=W5@ z<^HKQNA3ai{ZJ~b!3O^A3lIyr$7*i$-xR&>+_g8vP#2oPgpdg-hGmN(@YskVt3%H=$*YV%om0i^oFVipyUr;k40dV??rBkvP z;)1yfa$*9nzCIJlC*cpWI_k?2iU|nMy;k$USV;*B3?iA?Z%>g=4?MWXgle*SJ0NO$A7`AxY|;daIhck_*LS)J+m7n$oqn3T1N)= zLm&0CzmBZul{C7SP7~Aoo@qVv4 zoFJwV0bg;v;hYS$Y>RN+oAc8G)?v%|?k4_j;nRcOM)ZlG!qG{D(EF`~N3M!|FBHjF z2eZ}8v(~+ixct;P4Z0BLUcFD*=7MOMcE|+1GdeonmByj<1->)90ZC4-)1)c7N_VvM zSBXiI1l+V8Z~*O?22qt@0xi3GSb89k6=f4f%oHeMfbmN$Ioc8Q{OsHwX7Zu}2gl*d zkf7hk4UgNLuT@tAA^^860X+amNHCt3<7q4`xqh2~_HvT?3xWKsCYKkM5|y1SS-$kfH@wzKd0J3!7YfnXNG#<>qjd!=!jslHA@Yw0=)YDmGu!$*w1I)ZGf$I+(ouh^-`Y z$YEC^m}c9U3Ycu<#Y`1dTz|?}pfW0`s%W$&*w!;9Di2tCxH;F=b7;rRmyqJt4X7_X ztqn(DeY)^036Br8#<(2pi4Uj0wWnwkI8U{DQsrP77(QZuRF$?p#qZuFaWYXk_<3a4 zlC;;iBu&)RsQpbn1%`m3gt;Tz=cBPqHLPp1<;ZxXBYjto>s2ven%~q*a)W!eCpc8? zt#1iHQ}hz%PMS2RYrA@F!koyaG1)ZNBPp+ZWE`4ry$a7BNPAXH=)FAKir#kuq19!N z#*!Tm09=b(`bzW&;iKBIC`{Ai$bHs~=;+=$XkWAlOP)$RM?EfI`P_MK>$%vvVZuak zlxrLd<=5JGY$aErZ&w150d$Qu=2-@9bkf&T>ayhb8;lEy%-m_vPnyoC)+-g_j?eNx zr`qy+L%G%^Cv9b_R;<7|xm9jpOT27BSkC))-?-w@@IzqJaHG6HT8vwZ4B1ppJ*XHv0=qdK;2|Qr^dHxo!NgIAnYN?STGL zg;^#V%{tkTJIlWek05X(iSuFW5H{X6&asIn6TxY&{-I1Y8MmKxBo`XwokQPj3Rt#v z@lkJX^BC{?2GJ`k~q zVWE@0^yp|&uaG?ZjKE;QHFK0LknWF?h@``2SI8J5om3wIxhMh92=dot^~&2bvR!7E z%}W&fq>_CcHH9jf+C?#PH2vS66a0`0ty{CJxJKvhTaG%f=`Vb6BT=_LH9@aZ1WO_i zURzKqF?^8i(9`=igP?45I7y*1>-L-w82?C}^0e$raON3!NGkDpWGZRWMA6fDv~>nx zG>OyA%?HD1 zO9MP!JDhF>x6UjKA+5Kp^UY7H^nScIn137h1Mzwk(R7JV*OaV1d%)4ckb0bSjHRm0 zYK%qJk)w+Rn7yJI*K?N3*{%PuH)M`6R1?Kkvpw2uA}GTDA*S(B=HLPhdm4ffi5ix2 zg_G;zEd~GLd;XkB`ov}b5PrLXLrLj0+tI+u-l7zMxJ=Cb1~k|Tzr>z4I!+`5d>SqN z_4M?idcIc`S>dJQ*FWmx_f<#>gO867j%3jUv(+OxNHXzE{$nXy3=ia$u&}UpCMsx# z62krbP%L4kxh4Y%(t3;|3%g9HO=v!nGmFP^6V4c>#WhMys|-I|B6oe;k8bFBe!T6G z(zx*PKMmC%<|S1fofd5Tj84dwV>*<=I9@x*?6|4nLa(aEnx}prbMd}8f=p3mV*j{= zA0K8;dj9GFjFoD3R@uUvS(=-VTMi(;LHp4n$~I<3azwP=GCS>)BV$4Mv^?F|V&GG; z^%b9JbJCQ=cdX?|A625yq@9S)cHrHI`?(1^JUqgPL0((iRrgJ1^ z^sFDeL>kRDn+c`m2Q42@0-3lP989E5f^D9;11RQM99R7X#wcG8|K-cJVo$_D8DqUR z%5~a&H#j-PzhYcy&E-(}`t>Dp7lqPYPrW@6s+Vca5kpR0MemgZ z5VlWzHh0J;VvScf;?%gWuU|aB0!pL6ekB-EVN0G|Ok@PZb!nZ0XHK6wPv3lb*W!B7 zC}WZQm7FS0d=`bco*w0XnS72J06y^-V~I99$!GQz#!b579oVvzZ_FnhGhvWTXU#RE ztA83zxI-Q=5lv?%+f!l%=J$LYQ%rWSSrLRHyh9!+MEnEVdt#M#_M$LUIoVai^?=+n z5GRtQI;k;{;1uicxFL7t(%#38-!V!(=y~L*kH+jvfch7y2Yqq5j_5DE)@QH$Iyff zMoOp7qR0~;PD@x*@=NR_3h+-J+i%yYzw*9_9I$hAZMlu&+dLeiU(5z`E|>?-;76T&d_edKfln%e^gZZ z^OwJ_A2CzStNw6bV`La7{}2DjkHY^;ge3C#%6QkoLu4$}dw=)z&uf6e-yF%+(irJm43LHpe z$0H-N+W&yWJ~fe?OnR@&W0g|v$+_?U&WU`N^YX3%QZYM|Rga6tWRMYCcgaJ7`jpMD zPIrI(P~8r;vYf89-kEJm%n}b3iQfI2Uzmfs=7sp(#D>&6GA*q%n_jCNGCcV%`6RLX z+233M0FjmtT)IuVx=^yyk9v?&b#Q+HD7Ne z12=lNuI#s@JZWp@jy2s=C3fvfVY!+Ts(&J&cN>0SJkj`9KZK|Q{?KoK(`8_AV*y;@zuzd5AdX%m{Wpm@_- zyjO1q&+cK?t71J?crlMM&-ZTfbpx}{Me{+wQk0AiL)Fbxi}V*>NGXv-)yIpzwPfT0 zF3S0Z)cZkC9ILAzcr~(X3{8Qgdjg>!LC~`u^ros>cN6AO4`Io}nT&dOw^)!9jf8ch zGva*LcCNL|UIJGJCB)%P z$1#Sc^H;dptw9*VqOp#0C_?HUp6qF3Ge}>M;VqlJN2e58$-ZPF)K!w9U@`)3y`Bef zt7Ox=@d_BA&Y!#;o&GhrXLsiFp3KaCap{52~~lS$Zz(F^;T{1wwz} z8-G^T=1$U%i@zo-*Ye7W)7b#s0N!{@He)u}oiwO z1hyBn${sswdyh0GPRMk%FU^~~Of79jGp#(wb^v;4Iyq~o3Von*?#4b|gp6nB_()_n z^Yz}-T0FeMc(^!006jbc!_}gdBLP-qx)?mDk<{O>)TNtIYRpG!mS6Wm@pQ)+nvuRE zfOar7qV<*KCgozY>2NdZ(~6AQ!h%{%VxY?lcp3a0o|oKrWl(%^Ncfp6&L_Uvj(a2) zv}$*$=G^QF3*ajWz{qh>laxw~%??L6ugg19GrFC|c14OSFQ=eIaDjco;A6s7;7RR=<85ySqCCcXxMphXj|w9R_!IcXxM}!QGw9&OYaScKI<+PdD9NYfY_MC2v(RTl2az zz+$JTonp?$>V*+Ni()f71A}wz=3gZqsB3w0C|5mBSwccIR!*T#v!F3*a$g&6ibZgJUskdP zhW(|I>}mJ(ezrSt?tR~2i)|l8JCVN2L@0r4ZvwTq3QnmDI-n(VJHHNi@ghK(+5V)5 z4n-@QL5HU%rvr2`JC z*!}@$!&Q4wBy1f>Hai}kwQ6eG*7}}~$~fMPja+ZwL;?YWu*PbU-MfX)>>fQ}E8uTG zHX@GR*e`7F31kk@TJMj=tPxHOxF?$J)(X|gAaT!thWBNB&qXaE-Md$#Xs)vlX$B4Z z;-R`u=PwU;8lr}?EId|^EI$6H#+o_VC=`luPdP5%1BUX(VqKe>@s?KCE{3uA!d!f| zR7d$l_VSXM94ZEnGvIQC>q5Vx*o@W2Dhtd@8D0z$r&Zz;#6YOA*WRem%v(tlCmxWC zwW+rb6iU|>ewPhr`11Z2!OJ%o2-YkicohbtyWRqGR+3k*$MPcjF)YrreGL3T|6<8Bjcr)U+s+08; zhJqE3yIj_kj2kHw>~>_HN4K!-{|`~V7<`VdDYkQ%~Bb1A&FeK4Tv}Xka(<+Cm`l| zotOzah|mmCTX%M+|DBr9!H|elqpiR>S{D3WPC0#d&nKu zrpGrs|1g3`S7B|SKEZ)9ekQ(0wT@D}5{Y-W;mL;+%C&ZelTOXXmed!9PWk{14`07C zXbl0MTpdH{Vr{=aE_J5Ke)-b`-(viv@xjUDZJhgL3Hf^2B`KD4Z+dBEtLxmvp^r0_ zv1^~k-Xv`xRkP9c^voicIXJf99Cpbp5V-AF_>nA$Q<hPP27%i1|FqNlpd$exPGL;fvn%Tc-h%&Ugf1{=(yT0PSJ#+=Tkf^L|*;$9W##d>hNWZk3fL*HeO(_HVil8OE@h zh@pK2oDLn<5i0A}qiZfnJwf#h&GS0|_#b_D#3Od5li@Lk!&l?mQ?o;|zxXNPZ67Yc zlo7}y2sd#TGnU?ge-SYy;mnxZJ+wKuzVB0a?w;KLKIkZ;sDbyleVi7Se&G(|L0vsd zhGz=r-f+w`j!dsjyN8Tb-|MNqr+o5s^mFdO*`EfDXmUM~#&V()dX0t}51v!4D+Bj# zx%KOfkec0@^|*bEUwJu~I+`I_MQ(L99q%xcFv;Go7G9ig2tH;&|1FF)X)%izhBlQA z<&>{L{+-U^EP4fsbSu@E{$9YVxpvfhV>YjT=A&(2%lj6CF0~0w`c8*g{G&s^z4e-Q zcW+D%E*{l#Uvf!S+6q@_w@;gNfn7@_2Z`(lG|+RQ2@wyXPIs?dw>;oP&%I3R#)dgO zqT#z6iL1N&=Sst&m}hOf4H<6O*3>qUkr4$+LZ%N(}ri2SkKlY-25JM`fJ#Gp|=Vita{nruH5`s^04V`0`1540(7ER z4QqYf+!%GFHhx+b*ZkJe&@OULf_f#b#3#cZ{YitTJ;6J$GwzZey}jmR_!x91X*HD= z$|T zbc}o{XEIg$UEt-nSxQ3I&z;t&yWBay`vT7o!%}b3!>`QJ<;E{9u@0_osp7 z9Lyym0JFp$QleVHTWOqx<#K|gm5)vJs#8g;>0}X2fEAn^IqcvuYg~o7h~2>^HIuKn z4j!n6Gpz%oHX?wB35C;nGOQFr9abYT8u#A#@b2WVm z41B0eR`+Bs0dcL3aaNGEvqjCM7}U_om({yihS=i~zcueiC}bSXAclOy*>N^D;d|&s zW|0F?2Z#F38csrQq2|TGejVWd5Hvz1sPU1}YC4(O<$?G7%-CWi{ZaT~)M|#z$(n3V ztE{rtF5mT)zqB!>`P}XP8hZ3t3UpuL_##_Egjzh8In=94v0(4|%B5BD_4LI6Q)dj0 zGbqN>sSdhE1-@ScuJ}bOiD@zXu`X1uTwTiCMLk@tueuf5NqH}4WLgT=X;HjE9zIC} z)YtMT1mEg(8v^#oNu|FZiCb!>6xr26I2F@57s2>ww2veI2IxW&_=fNQ{o|w80wr`d zRem@L`tR?-R0nPE#6HB}&eT4j%_RFn9J$@@ZhWiak*IAjEppB}&gU>GBLk_DS=~=# zUfsB@n}dVHD9KUl>h`T*B##+cb3zxJ(csqQXf{Uqk8J9=0iwTZC;`Pc?Ws*{25&^a z20sw8dCbo9_IV-Sw>tzzep{tBsWoxVNlxP`=$aaYi7k(-Tt@|yqU}1+i*4YQq}e%5 zS8=`|s>?H?VRAI-KAYbcbx#q~F83gE%?lwTM*jpJjUV#EVr*_7@pW%~%XZRz4dIR7 zdqS%pm@_s{b}y)ss|pOVW^ukt>cP;tJ{MWrwGRK3RV6J`y!ZVyT4au_oP- zZzBFe5>A-udc=2#duF(2qb@F^Cct>Ff;e5s^<3>L$F=dgnjY#UFm-*E^BN@7WFko}RfQ`s@(O8#nE&*(WmTrR7r_bo@*|Za7oSH>Fdd`lo%$`k8d_cg#&V_F zXvD(LntdP*9xMAWs;@=_IEL9#&%VQZ8#+VYNX8Gf3!zbFpi6`r`gQAl` z0~7JFkO8&%*_%^POl0%|NvKBG#H3Qa8{wvupSlj5m>5w<3a=zS2?=gGs3b9yPxR>} z8wm?i;~UIYJH*M&C&ym@z^l<=98RUcd5{1yey>jeO$<(IxolPr9_D>-#VMpx{i24j z9V-(W4(*pHW<7s@^2(Y9xA?yOzBXB0^DZ%{%&oVzXELkPD*0qRlLDECHM$tGn`%XK z0zG_0jKw8`{7ATFA<@R^jpS2PYE^6u>`Z9w!E}R7 zW~QjDIDW+7I@ld1KDZo(Sp=MVMtkt4!h1~F$^$Kp$)&b83+Kb3a0UT8ey$paf>-!Y z`!>ThwUNeizJOcEX`3N@_h%}-0x1h;rNMYH4ROm8t4)5gduH8yah#Iptote1Z=b9d zKf8am%$yu9(=6KgRV6Rlo3^~Gb8*!&WQZMq=T^l^Cb96^a*!+vpSj(!r3GdQ_k*c( zW(HYCW&#`D5&7TJ;*ZGi|Gs@4w_`TwNG?W1L}b`V98(JZb8~xE8n$ib*CUL#@m6=e zzZX{L?lmo+R)VySYo*KRyXr?Ty$|2Y7JUP}&8BW8#H`W5V%{fFQds?|kFL`>#Ftad z@EI+UXmnJ2Qg56dOE@v=1k`UwntLanz;*I37E}=gjZUOxe8A5u%~qEl)xlFW6IV>a zqMjEJB9iRk636p#L)GKy0Ma01M$cgu0nld@{N9f6vrB0fAZ?h>n2X_*;`3yF1hNNd zgzohk`hh&IgZX9@_&br%LJze1;PHF=-|y{_`(^}DYgsqnwwNv1-+dcV zCK;=`x`w~SizjbomUL!!f2+4V9l4HXHlsf#u=Cx!vsON9@9+6aeUPeeVdIx2A0iHB z7sOJ%Q3rOLUhQ!({~Z}8s7e8Bwd}@^=$Fcv@#|~&j-kL9KuUM*{s!pv{oeWXa{MMK zzq4H1qS$}bXf)=y_sFq#O>?NRXf_*SQxFqfD*WcU89|jQuOqn?qHKd&d|2g$w z39_wBP4I9y(lgWlHB^#{Duu>Nbku3fA-!-pw{54$tfH^(MimBG{6MaY@tkoeXE@0* z?>tjgC}oFDMOEcc!S_u5+?4S(Gyh=0LTwIpkCoQHEC7xM#Bn*YWMT@Y)WtK3VL9Bo zEKIId1uaF=k=d%_J_!!deuJx?z__+nSzVtqTF7X6U2ihJ%&%H*E)0eRlSUD_<^Aeb ziY3P)_}IvL7|hcWlMDloSUz+mEb#3TA$RAnTq=zQBx6e?a(q!-k(qhrEj=5 zbh}MP&i;uce~wuY?7+>%sPO$uAbM@*Dgj=bGf7(xFGqF)OW)|^_ZpEfw-g+o`fkW zvNK&kauatRM3Ah{8SL^BsjcA-4>lIlUpn=XtAVqa^uN_r+H(!7pcQW|I-@AT3y+@M zNnt5na`PVXoi(rW1y?>7R+~y4&L%feeh$u%4`@w*k2`Sp4?VTe&zu&_`xI}&nh(ot z0MyYNeo!tD2@+0Hx)P)1eV%6nk_aCPB!X5RStih$6YB?NXOT$H`@_GrO0~W)OT0)N zIyTGL|CjiAP?5i=P6{%N{)g9+6_Qd@kAMCCz46@5?Qu8RXt&dmCGo+AJfePneoQv& zFQ7J)Qfsv+x4DVR9Fz4lK-!y7t^cbgOh!)IgMlz319?ok1JeCe!6qx4CC5;Ma5c2( zbBkFcd(r2-JExsH0BvO~MXo^W!g`wrxkCOZshLEPV)aKblARY_;9IoS$6IC#<#uus zJ6tcfNlzmFMV17NeON?9o_yYLa(n;k>dW~_%s(q(^o4U9`D2Z|wAD@}DPs3klEA-b ze+daxeOCA6%_JdVUyElw$i5|8w}Cx{-ZRWh4aD+bvEPzI;$Y%xsr9w-X_Cs@tE-CU zW5usNRWNdnJ+c1xqVs=n5tlm6mmS2z3HbYELVGv%&0jta-u&WdW=}U53p}Dj4B_F( zMGH1EE|g-d~L-XuN*E}HoBQUB7y8bne7b&8e)PH92KLh)YC-di-hGBJe zPSP&?A49t25spfcFA^%58}?TFj}r2(9h!FL`_D{kidB9*C)l#8ws!X;h!RJkL{ZQ} z;Q#$y6}m6uU7}361oU)!tg5c={R`K~`h303M{VWfjnxwq6SM^_fBhj#2p~%l$G!&s zhv>`Xm_I{ak}s6SFV|}6_xl3r`to2W?IQX?P&AM5_vET7`oO@z59i+j@(r2AN0+KM ziIopFxwPhVIU7Bs`462R@98xW{bx)oIykETZBjn=)(%Q)%6933u`S@A8-gd|zqUaA zkAL~N-#$&cK;o4(==q-uJUa3h+W-Cef75@tBulRJzsdivS^cl03~ngr|5{`Jnte}} zIEv)%f9!G?!?n{3U>LV&eigI0sXW!{Rz3}f2GL+Dp)a9_Q0(tE= zB4SIdoRoy#Au4nTk%Yzsn~B+;$U%m?11~F*(;OG=x#I~+6tbHU#@l)b+3k78C=FKh z>285b#GQoh!z}Qslgg0Z4#(t)G=B2tSGpt)H=ePH$y^+*s(XyVsqm_xj0f&Fq@~lG zJNOxjWLcNDoYIEG(Oz6*@zj*KyUKpqJed&s#Gh_E#LGdD$&1xQZc?!H_2hh~{1#Bd z%93gX=>3nnrA(RK2>fa`4*&WoFGT(G+FSk|qFxFJ7t9?k5k_}`1BOi;fk74SQ(&M4D=aU01u&N@1 zvmc~BH7j*17AXG7{jq4J4K_DLAe7u#llHsx&<>|#*QcY!v=FhtPFgGG>)GA>F8NfboEHU>%M;sz z!lwYtI!GA<-7pH2F_W-53HD~#bIIs|0yfO6tHzwB@!>5U#`~MFg%sr?xWB9U9F6he zwbeHMH70l#NUTt8gif)DmC59o>)wEd67u@{7=fo+D((Q&(3R%#o5TWFSA_%mC$ShwbU&N81C!O?zPl&g!*oJsW3uzAEfpU-0>9^1NR zp&`j%gpU#Q41O|Xj<_fH!O@p7MQ~O~{}r=1GlH1d4*7Gu8iD*AJ5hy+HCc1~YX?5# zV>Lgqr?_iO1s`?b**71z_L$x!HLD`|MMR64)ucuDtpyYEg>A6f)#oy_y>)}8w5>P+ zET;6~d>+Xc!E5Ko@rM$sGi^k47{=1{uo=Tq$tN_{tjFSqS)+3+ecPVt#uYW)n3c~3 z^3+L{v`EyMZP!?3%@rWK0|9l^n@&O>^7f^Sn|==>hZhT((o}$+`+~Y6l?Lp+r?45r zBgVuu{6VuxTG~{CyxSOkgHw*>^Pwc1tu!tB6TKsS+GEofqpK7H>m89LcwPq@k{--n z3$IzEb_bM*(EYyY)z2`LkX)3J+p_vd9vyf4&kmQ^KlTK@5fGqRG9-eP2V%c4KDfV- zoEbYInQ6u->o{lI%@Hhu+&MF)9ZXQK5!j}^G;La`Z|I$Ex*NNcptNhFa?YP7L(r3^ zJ(&9n!n2AGTfW>n%Am__^afSzhv&=bX@p0Vksa`c%%3t;s^OURjp+t#Nz;_uKzWV5^QlhK>{TPxpv+y@&lT@i~$!xM3X^u8< z!if3q(-MZs|B$`x0>9RT;6JQUapCY=>PsCA;Ol1e0f?!NY+@G+(|8hAe9CBeVb=NK zYe@}D5?+bwr0y1E0`xGS!y~77va;b(*$t0M<}>cUu>j`f;W@R@_yK`HXr(Ty*7+)fX;9Jn?ZBa*_b zZ~G=s=xw4bW`v78#i-2UZn_4gk#=P|O&NCCl6rzUHtNVcTOQ856UEUeOl0>ST}*BGU7+XDG7V_c15WT9*QGuZlZu8~|@T1R2?pp5Trcxw*T z1p*zyi0%;X`q?9qfkri}Bp;2f0oOLvuHbk6ax3cW1=y3+jNh=3YDx4hMz9)7?qh#0RM zUm=p*r3Jlp5^}ks2`l#Eog^(|sBn9||#j%BjtwNAGqgYWf8#GD@*(eMr)#gf|ViQ6cnCHFS|*jrkmk*B$OMneuf zf!R?zAW0Dk&#AK^op14)n1Yo1N?kEtr}rfZ{lz4ED2A?h9^_Di5%<7R&NZ0A6{Ldwx^u^xSJD^HUC3d=m`ASCDNij0exY# zx|T%)e&Cc)PmIXl+;L|Q=VRnE#EJ-%{LB@r+J^lIBWD;Puz7_1J-lN8*hFlnH9Wli zZ#7Ltnqyc_<4))(Bq&y^aPI;l8Ts6KjBU<5pvUWdE+5>UQ_ML!$McEy!u_JizE$03 z8)M|?3||(1)S7$wS_6qI(9OD3R`+b%kMseW%>nqw!P3cC?JVb77ihyfjv=(WrRUj| z4;ANylGxrr+vMqlqQ4h!dFNujC>gMCLNeuj;B+*BA<7+_h;Y1M(6!^r0;!q{F-dk> zczX&xZ?)L#*Rzr|Gw>UR@OYE=@oEI->&>7>5gaqJvD{eK_qr-%C-l_ov6DB~V;{>@ zOw;p9{WIKBb(fs{p;VdnFeEQ8Zv7q_yDbqS+R1_85^Ukq8V+(fU9~FavXK_uV&zN* zN`as(utwneK#@O!+XlixPwGw#IkOSReNJ%%w5+~P2@P=uaNjctg6{wCMnB@yTZ{5_ zmn+qFPx|V+TSKLTC>ig&$JW6PJ4CA1^n`!gjw#~g!CZJ+$gpeiGB)Fp?^w(q)K5HQ zPzq^oG3@;aH)fAx^xlWUBSg~yyrEA2QCa?olWr zj9+zrul*Q#`wPunkhhEiD0k z=5YH1rDTc9H`)q;*%Z&{xNu?&WO({cMugJ^VWV%jp#~KDxu*Y)#kc4ZDKT7nyyqQ@sn z8$-D_u~VtK;lQ+YpBE!BAO--t5g^l1QDp!ADF`?3j_UHp8(=mf*Omq*2T3wrEYF{2 zNnKTGpY8un#}beW2-%Aii)$$FtH{D+z$MBsc9p~WK@H$5XzH5{-J8W=3c!W4*i>mE z3Xotiz9|m}d7M@1nG%Y#sp(nkiM~;2C3_u#FxupRa`%osXYE@bCmM=!I0WY zPt_!Bpmc*cxqc))2yq?N|)8DoNHf@$~Sox>0{$J^V^ z@osDj6Pq6h8$WGXkh{#zZA@kY1ZE5M)BC=b2VQ6i7Vatsw)?q=L2TQU?xl*XH!iB` z>h1H#TRX^)ND||Me88_Jou&Gn$P;kZuD4d5V5YJ(lGq+d;km{MB&GBO`vBZ#DjlD- zm5)ZBa~!kPokRgv%RMsZFp66 zRlRfV1eOjhx8ypyGspSD2P6-K1EiY3}knCQv0~2eK=6YcM2rw6Ld3{^kK;Kz! z@K@ER<^n1kW5Gu;*2&fy9d+DM8(*oS^Tss2GYu>z9G#I+$+jZ5Chf$meg6tm^_fTt zqfpt>dA@mwyb8^f3vNl%^uFfDe&?9RIv9BHW(GG+NOR@8ti~WnBhIlMd#?YHPD~pcS8!=B4wALPu9A1(`!fxyB*Faa8s>L7U)_MqLra z?Bqx$DK)TntPK$e&OR@X{sr15*vq&j$h2VRq1qh^c2}6EUwtLYd4bWl(D>d#>%F}g zTk3LCm6&+dK>{LAnt(D%^lV&6?ZShy>m~6#>H6rKcEJK}yk~s4Ph;+NBSt`v_*Zmh zXLRiy^{P0{YDyi#}hR6vB~1`ql)7r|8s zvos*^F!GRdI}V>s_WtH;jmKP0Z2^q*IL+?0Gt-BQi*+O=K@Q3dm7>T|!a zoW+~6dZXX-Pyx?>VBiEB)GW5a^Y7FJ-k^}pbYH>HG04j* z>!hD&q3uBod`4ChPl8Q@Mp2U68RAc+z4PlNUY7AJiz{Too)_OE_V5v9s0R1-W7^+} z{tn|IV!nN|f)8)|XII{Sb>zU|NQV#DzW!@eul5t1 z)_{T*nnBzecgP+|&2qi5UpA!1FW}Yg9Z9p<-emQfrL`H~vo1S#ikD2|yL~xND1qZU zo#kiFDaX}A%lJ#lCU<~E6ZhqCZLSs90-9rI#l6vwiq$ch2(3wv=J>Z;NZa;NCO`l; z=rZEA){7+??MppUo(^Cf=c?Lc2%>vtKCfU!wN)*{INe+q+bxc`qjXR6CWE{sx4SF~ zeR*X6ai>g-89ZUk$EXjzJn3m-?|51Caya2F>k5t*H8%|5pIIr z2LbnZ>GaMBULNRoX^lZfPgWOPUVPVkzHqcUP*~pmI?Y<1eSx`>hV&`tILu#{H$2j+ z&3bm0v?ejW=mSeG!+{h^YqD)MI^x(V&iT&0&!h|C8Ou(*{cp&zP{ph3Sj_?+{e5{3VHx?c#Q? zDo--5KTF0M+#U`Pw^;A59fG6l~CMWtY2Bxa@%&BMrQ|Iz58TV|qnf4HF*&*jGGjt%^P;cL1X4Skt` z4gfv1`;AusstrqE5&(uWJ%W*R*Uw<~DlJa%IM+koD>TpnJ?`Uz_lEsXT(Q%6P`TXS z-;R|iDRzex5Rwx2_B!;wIsYV1=dL^@Vhf_50uliS2w|Q zdo&R|zQS7(U=y%wzAeKv1< zcu_YjC#M&#D3^H0g+Dr%=L1(53u;pQ!Qk#(&?Dg$zDfei_E2~|>=F_Tne0VB#Rb#> zDur}c??_rlymyz_O&-i@9hLYLmraJK1s<;6#G@>WGp&C_9rL_%yJYj#FUFkVsDl2; z)zK+Km>*{lYf^X?Qe-Xyb&DK}+44*JHmH4TlZ!V_LdYUNlRk5LV8xwdd;AX*J%jSY zq3XkV`szfr2=B!CWKeLI=`;Y%rPknUCCBj>&z7a>gKah?(b7yML=!D6JKS(^#7mPRsLUwM)=#W^&C-9DH?DV&2$f!P&n1cy( z$LV$EJ3Hp1bo)iwNoj3>{4ykXNe7S6c5kfFFv_Z_J^Ma#wd4=O{G8-<{%;qLM+T5f%abpCZ`NZN9wsp zJ?&*_dCQ)ey2aqgMhg`SJ`acOH{O!gV4GT(8$333-@LXX2S~*ij)qPfdD^s&QyH9& zq2O9;bXkXud)~(*%)3K}uck6?Vd)4cm+m^U7@Nj^*wd^GeY+7(!Ub-F?TAiA@3Hhb z&Sm>PJbPr5mxd$Q^O(-Y+fnAbV|jc=+TrCJ&YgzG=J0K@a+O*pp&6>(N4nIR#GXA! z&MOT$3Xhrx@sB_YdQpsnw=Lu?%tO$4#MZTmkckHpBk*;EHEPz9XyXag$EW9OP!|1> zn+kLqxid;$gS+OqIg*dk{Pbj9d%EW9Uq{JyrHr!WF+Z?7Lj`QLH@23=X4Ra*?a-` zxces&l;ic^!~7jJPx`|i^JAkXwy5=R2RNGn_`Z6G<|=hNM@=PakjRC%Q!;LY5e_Qf z{s66lUC3F(YurD!<`-mByeb=2tsmochNF7{jQBi#Q`d1^JK$LEln{1I4oVW)! zMqcJhLSlSB|6U^bX#h+LuPV1W8O(UD_ERR*Qcra!@+x#B0Sie?i3aK9eh`c+(`7*= zE}4~t!aN8pb-xVc9u6U&-Pr1hyOPl?*BX2&T9+(x??~yOG9cfgA(6&&lNdu2I^%cD z?#3Eu7>A*@WMGgjlBf7tywsBFCv=mr>aw2zmV{&}54^VaB1qnsX+M7-rvT%QNz4*WJ^_wXAf8zjN7blqri|Z~)-9T*K9LNEI zLf!QMz5cfoP2*^%)VUQF0=+S+&*ud|t^u8w03Bx&yMzSSfU*v}ZD&O!4q+OqlT*4G zl`KUHK0QEP{I5z4{@jlep|19}Xo93x#7rZRWrW1!(fk&TQZKVs3SX92P0attJcWi9K9VYljkWtD3!|GR*cPb+u5&^S=DY># z894G13QKxxGb39|Um}p4@XmXlUN>^K=0m};>8*r;epDV)$DuNA6zd$Lz)g7QJ_JeLOQ3;(z@)fXkXd3O1Pf=EBZhcM?4YDvE2T5 z-bi^&Hk|R?_6`cXsf=7(!}?QBUT^l z6AWrg_K%7Mnm73HnlRg&TVE;WEd|EJ?XbCQgN`BLFH1F@JnfBgbTGD7^5F76G7CnuHb6O(AEtC1nDg>Dng$$iei73>+;gbTyY05TW6_6WN07#$OnWSbgfB|YL~VD(;* zu%?@ReAC$4Q2JeK73pvIj_}RtRlR`;#zk9Z{97(A`na{&FBjBFkT8@g#djM3qw`x! zOeK~&l)Ppt!iDjy@!ywxCH9DjwLR_2h%|VY$Tu z=sAmf{U8O@(2ioS{YO2uUw@6te~3FB50m*(_$95hEp77If5s(ybr@NGLMXh&m0a zeDajZWr+y!ysxlDjQS9D<(^_g`ly9R3%>X&(6V#P+|}X}EtG<LW%AoX`?LHP z8*z{cR{;5+*rUDT_?wpc%RN!L(bP5!5l@qtNkthgsV7tKKwnI)E-^n?+hFWK)J3K) z64`?@+Ba~r$+nib$msy%Q%XAHJ!l$cI=!XC?Ai>i@2Ht@8bTE`ekhvtAz^h|bjnA; zNh*=QU}lE#+O#Nsnq{DK{$_Aos!2a{t7Zq~sRWz1D~~Rt4<__}A9kim=de?3ga+jd z)EG#8BZZ@wsmuMrl=xURqmpLY7|lIGp_?J$x3~OtScNNk9cZW2T+5L87=z;}=MDwA z#(B}!z|n(c-iU<~3UNFep^hwKTZpz|Utg#wwx}kI_~Ssw6 zSE_6Ab~SiXzK8uasB*d;=h~auNc?&EYhgp>U!Ad0-(`~Xn(e1N%~h&*Y`sYCRLq#9p?-KTUq2*p}hmktH+LGJE0k| zu_Y_1*)kk>pJL`_?<^!K<r2Qv-KWV_Ioymqda0ScRRc8o?uK`12~lok zW^A`qa^e!rg^Wu!l%++SdXP?}hEwjiKKXceChq-^Sd#iKzr`v#Y!^Key27tMinHdu zx3y0mB))s7;H_gPHWYF_?)5sf4?QH=S|=v4Gn6@I&Nm&N^43&TWxY4g(_?hY`X`iC+CF1X#;S7-Qphz#=8OBt0Wp+jiHcq>=28u6vJvc0JGG%Y-Y`= zY1NG`bBoCcCkE)Ra84M>Mu8?P@MucWRa$micUPX;dpT#H6Qi4&2+w!=+?|g_rWP)d81_kG`3k!oDL`PGm zp&;`5b{7wDGE+UF@Ic^kBh(1_9Cp>S)OaWXj4T&CUP=rW^egjmNfCPO&lK~33Yqyu z6OvSUZMoqLETF}ryF3g>f$=R^Pvu|~UNy-#AiS3mlfJfZVzr_-p zIU?t*%v4VEocnlBbarppP$v&+x#!%Y{F;s*<|%)1F*#PENQl_ZS|Hd5x(&(GgDTB~ z-^bQS(1yqO{$V1INT*>=^NldrW2*pDL!=z@38fZ6rW$1Md|AseK}y;|^AJVU>~;v8%@wmGx$VqfPL`FOu6lr;YL5bFnMHae%vdI;ao zQ=#C~opL=JdeI20LwnyuHbhMi15C)|DU<;fZjKqsg_SBXRsbl#oYWjtD; z6mCCfF5fbvKT2WzEm$r|q2v7%_7|)jL#qhEQ?=Eu0BMPOx>Y?&?h$rQqdXLXqU&pTOPgycjKYrZ95U5)^z2g23%LPlYdOvphHN_`V01sN~979L&dF zL(-%=p>6a71;ZN&(!{@;ZWbe@$FMgRU2lt~i{M!y<9n7qqCg7zW-W$bYisf&_YdK! z18FHP7}`^aFsa?OYX_ZCP90M;69a~&!-nD2E!M@Y2Q8lLI7r^vfD+;a>)S`+m4Nt> zj$Q@u;nvgS8t3l`CF*jW{htel4H|WPaF0de#xp_s2{PoQO28s1$TFv9oczud^n>z-to)9JydB;F^p4cUJpXfH;(JE$8f5@aVTz2Us*I$7%OzG|2S^7QpE%} zcJkJJ&F#iM-HJ#Lz{zXpinvF>N>U%78rc+%mylRqqRqGC_c(!Z(f8>(S7Xfj(X`>Y z<*^{jEZm_zQd~~g;f8NXZD~us5TY~ABM5_`@?&5R{ML=Gjz_y5O%+7_^A^})e`Kd@ z_NdsXQua%56$VL<;Ao8&V){^Uy;V#z_xAW%5E`}u);*M{|D~rZ)_SOBv%ZM3SE=Bjpj?0S@ zwSVJU-wS&=EiqJ4(JdsXPQ<709mVp?utbe|I;s$w*~)2-M3P&TRn<7QIPZ9F_ut1e z3Dh8&j!@0Jq5wv8@q!OJ5@w?DXRk%)6na7b+UpVz963HhGM++Cn1Af|%Z*GrR@Mb@ zNXU-+0FS$qEW4fljI(s+g=F=)#6ID@YBzU-H01GXhy8xorSuH)1(&H6v5`l)yh22# z6v&a3Oz+BYWg`e=R$Xq1c8aj6wYr=8^YLWk7B>2N*e999$-z9*f?+t5*U&CSx~7SI z{x?USwO?MM9eIr$(J;q8`)c$)!!4=NNY%;sQZ2UCef$6f%3tDG!=*p^mZtYORyryt zI9B5K&=kDF7zv6Q{UA-`S46sMdIT>loTASL>Zb@dj$c_OR}GJ^I2-4SekDf41i$W> ztvtDim$&sgZfG6=X|kdn5Xu|W``dL=w{p?P+AD@j8l&^0Dx29*PwPMDvQZqrL@8m~xL9LMexMQ};2PX*d5te{#S@D_uJ zGC(Wxw~cqV#Pd#-9(CM*2zDtv_IjKFj0joR`k>h*Z<@3n{flDbEqxAM;nNrKkHog(AaDq1;{NhC*i*HX705`W$1ati zLh|`4T4u{Q-_O^fUI+3QUnyDEy;>wQhGU;_j%5euzsGm`w$4G$RP-~#f8fD@P}2X` zYaIVMv)8IqPrv*f@|R*SC-ItE|EScS`#&TORbjxK_Iv|kfcpL) zUH=$e*%NIK!>yPdJ007$ZQHifaXPkb+qP{Rr#rUI=lmM?-tmt2e?BA`8GE0-t7_G% zsKy z0X~lT|0^B^M-5jBOpmgAUc@smul$!Dy*QOGOa(hhn@vzJ;Iwma>g&s6eQg^0`pikq zMJufr8lVEnL~= z;sA`7M0Lgik}3tGQ}2<&UrC81dFY59-E2s%%m|m3JjEdT($A)b7>c`oTv)tcokTw| zJsjRCWCr3GxCsO`!CFI(MOuck;}b~+z;8{7cMgYteJq1_Rw7J~4AKBqXp0BC+Y3C{uk9{yWDvH5#XFR7k`x(V(K*n>!`%xMem6Pq z?8{|e`~dszY)0PUmzxa_l^wjH8_{vU89_AY9I>%%a6(lxfM9Wg5JGi_VPP4({1t@a z8+QKb*{cBWybzy|w?4ZS57`~GLI_9le{2?7~#3Wx=3g;^&h4{J~QIxk4{1qX)gRKxR z_HFp5Y3!ZO{7i&{f^nut{uX!&jy|mK$drIAv!*l@j7)5u@%y?vLwoB#sP6~HEm#_3 zB@c<#1<^Eq29Wm^tHb66U%DY2#M_Gxem5#}mD~K*Cb8#>pCO}JkXJYpt1 zVV0*$D8hJjOIf8JU_qI2C3riW*2AHPY)Vi&0Zb;#Z>Fal#RA}wG-6d*&JKrf1ZP;u z;cEkQjHh)mMQWqp=ipo1X{CT-6#GDN)G(-DC*ufMhYP+CCYcsIJAOeB)?1732GF2x8ILwM}cTEuJS>{

?i8?2BboCA-UICKK3#|CRM@`ZANjx!6|+tMFz?jTh%w`aF4 zO!Wu>mXLA=%9PkkmH9F;EPDvOg|~2$PHPg+v%AIGZPZpKL-KvqcW$Y2(2deU+*FjDy$5h?9c zF1?aOn{4+g7Q?YGD=O6wyIIdOZVx~VHb$>=Ww%Jt=Qv^IfyHldAm&j<9%Ww|%aA6Rku8YOtyqo(%k775&LaN zKIQ6m@ho#2jDpyY8GWr2=ydgv&YkaRz7zkII6aF1CW&st8)+H~1%XpRuSo>;B( zxE^ITNRGYBLf@9AXuCr=1Bg8*#o`M{!*daa`TQ}47{vJ=%}xZqm_{M7ELFBEauuA_ z?L)IP?oeU1X+)VYh=->kzo3x2T;If*UJFi>Eqxc15`6DGwwsch&SR@0+v{2$GHWWb z1a3%T8XTjrxaQ#`4l*mU=St-$;@CQpD!rdGnfhv$cxH?kE=Fp|Ko1ajLD9Lc!j#=S znYLyj+s=F-(ym-e4elDzZ31 zcm!j=@Q~3{UHxnhL)oOxR&R=cW%7DlVS~8d^Ja(^hQ5J*&oElwjU+u$;Gi%(qSOh8 zH>S+aUMS8DKqvIjf!!dhfGqj8c)6K-5X@VD)klQT9Kp5uU1Sf}C6ZWqjSe|k$wo5a z3$F3IV`8--lim0Bl-e80kyKTE`jc!6L&?np(cB%D|FMU6KFA2r0AWA*lIydG-!!^@ zZ+U9sHZxIIk7V4`_-|biRF4u)dPT3K%u`l@LW@fe;~z)T(G+}WfD%)#uX61~66c-g zSK@yf{^Ca_MaK}ZoV`H28gfWD(bWv{Py5ho}&!IYyE zY;bIi-o;%IWzdquu3E>-5eX9LsGl<9E)~dV>6v|(Rk!A#WD!vj!3K%ZIvT9L1_8Dj z=b!OX^xT=}noN}$&X80aRl9NL#O;lF(NCx{in%B$HKBs7Kh6dwZ{W5Bd!W|6l#-A@$dl1Uin8k5Z-_09IEg!!D z&F(I>qe(5YG`w1`!63QL2}d0R-shr)%{E0{;^gpLo@SK{oi(YSPN3@ zFC8!?`tg(hgXqiaD^OqZ8zm)WlfYxSnwpxPo}N!xnT2%_kWdNaSkjkoWZ{5Xsd-vr zA)8}`kSwUxLjMi-QHMsr?B2iJjfaeovE%yx;MCxo<`zg zT_ZzVjFp4zpWPg2DX9^JA9?*teW?dl%iBwf-!tZwBQ5^()!H895m?h z5F8~Jbxp-v96wMMgCMT0nml&=1!DtKj^e51Fg|~*>75Ibfq_9vSNA6e3#ZG)w}~{C z_b+%5ms8v4=TYJXy(1%Jz^>Z?){B<}%Ffm{OaWD9rRuiE}B0 z=xeiZQdU}2Wf)$^?bgQ13o26IWsB>4tQAfI)C-_^yE>e{4=H7C3>&-70VUH zjxCIhjk8$)oB}S{Vp2BzAHadKVa0NJ!q!1C7K|%cdP;?o=+fz|F#{$OE``7t?F1TkQwP%6-{qM`iSVI=PelT~g6)H-~aG>()CtCgf zU>1Z;BuKM@zq9`D8*M3>y@J)|{t5XHhtoHGhTrPww<@e~buD}%S;ln1D0RlClj7N2l@042MxN?!2L0La~(~ta&FDsJ77QMV& z_n*V{EQ0v!0a!4lYvYxBgBRfmLQV-}yH`dJ8pkFfUgo$fdBRiMx)}GNNHoH4wa}g}JNw@?wwPx|o1qmd_jGq3zYK}qSO=+93~-Ly zYkSg*fU$2)pMMj}A|3PwNx+R8Ln(ZZk(p2aL&NyHNM1&L8?oNX5?cy*>R6Ru+;YHK z$>Uw>jR<_*ueNhz7;n(Dy7Z1H5bEk8WqL=L%KfywN*sSk^;CTsa_7kM|2UHzpkfyL zsV(FoLm{|TQ;>#6GboU?H<46$u})#SI^)W%ik79Z*lg|Y3dIpiX}h|(y4qduO;Apq z80&Np58z<$FK^VtcB4t--1e0;qZdU!6q1M&Yq9o@n@Ze>OnT5>Fd#ZYh^XQ>b;NNp1DY zcS}AQYN3#hr?CLHLuK=>BHZ1$)m|I^VO%C4|Gr4qFQ~m2WM50)0>7m|o3mTR(o$yv zKj8R5>BHKPV|Jmtmn8Jfh>2GG5tsMgOwwl`ny4dRrZV`HF{k_GBX6Lry;Cf$_M>tl@ z0@}j&6pevo(5^sZo4e&@#PK89AbV=%orRgAn|ulzXwuQU4=Mg>mT#3G&+Z1%(9ra? z>OnmdweZyo8<78)!VY}H6Jo{sA5ZjV$Gwg7;Zg_H+X0Fo)pg6%Dzc>lYQddqTVLH~ z^mt5oP{-huWx=+wvAPSQG(wk?x&x3}d9oO`*d;z`@D4ENSoy=HE-U#YSD(g0PlRdt8AVH+{6yXh7c#KFWoX7n6eeMBtlx^b8dHL_)OWbn$kmF zU5F^{fstneq{{7|@*;`((s9e47V}lTD9WuYN6s}P&n(V6ior@TEiqVPb*4;`7o?9v z<_KgmIZNO^-#Bi*HYxD5^bd#xn65T)W!?oI?9vf=Uz*pyHxgBvwJ03HOOGG(HRRr@ zCTqx5J30)W!s6GlS#7$VezIF)p>J11PcH}Zm#Kp_DrQbR?eXG{;Th$U9vZy0*0Ct* znuen+I`AypAFnj?zntnj_8}~*t;!B};N>}kbRj3pDForQQ_R;92N zKsl8v_xBA1K%T#}kHDYjL1~KL<)`Ptj(F`~I8g=_{YtYtK0t4OamPH!qgV;y4_?oP z#bfOx?C@HhD0q%)cF?7_Mje{2pAybA{~(1Qg+p=q1fYj~Pa2&|;m+;_ zA7Eo^WCCl%LD!X@L8(7{N zq}~Lb*C?}H=5glHw2#4JqiygG4(BMgvpPvc$%B^MP@q&N;S@!oV(^$74km0ib=acN znD1-RxzvEg5RjJiDrQF^LFQM#f3+po$Qtt2xi02|^ggD^aFGp^D4`?)F~%{ng}m=O zmz#|69Zl{}To}?gOei#F5}3qg6N8Snza=dSFOx63R8jP>58swy%J%BMH1I(x(Z&WV z04>n68hrN(d7kQZwYA3>c*BrvdQ_3q6Ys#OkbNrOPwu%yk;)x0su&ARs+xjSU`+^ZCa|%B9!@VEZg1^v)H5?xWRDYSfTYyOK6v0dW)M5 z8+?+k%<&GGUs+J}!P4yX&saj(Z0$c~$g&|-TK;NsUs{jd0t+bqF4K@xUnR+u^lcFu zcd*w=q!|rfyqBV_z}CtOQ@u)d*5uiVp8&_+EfDJ2-Dz+C*rw2@^LTZ^|Fx%E_16A^?V=1$LpQ{CLJ6H;d8Wwtz&C^VUcxq72%CA!H8X#}NutoAc0+ z7k&{AC(*?NVY#QW1F-;c=F_3rBK1n|Kyj1i=Mk@$LlvJ#Z=9`V!2UzUq!Fl7dWenv z5gmJ@NkJ}6+oxVvXA`gv#WB-0GrA^*5r3tPwIQ>#niEz#6rC?{`Y%8ByG zj0EJx0%7~D9&`0o4ZSs8I-ex3{Mrhp0Jrl|SwJi+dm)w(Byyo(fid*UE@KY;v>bR0 z=Km`U<_4KfTd+CY;;~f7PLyF;ZC@@pb?*KX$2k(nG3F6eT3UH{wM~3~HJAThDArL5 ze+EXPP-rF7S!Hu*hAn_ZIP-g zZ$$llj^{p(b$ROJkdKJiBx7KFQ)ZH5sm6G@p=5;|6xwt%B(enRK#7Z%@VRF?J3K)M z6cmU2#>7VoM1pXuP`R>q_R4|J#je%$)W*QD$C&Nt{KxBJbNQG<7DXFs0Q&h%updes3hi`X@?x3}w5lA>a?ddFu5BaJ(DHD)uhAOq?S;bpkEb*F)!P+e)oJq8 z1lyk7u-b6e*qc?lST?S9Qe`RUbL6z!ayiviW|ef0I1(;0hA>opVC#`m&! zV8g{OE<9*P36nQB^}H%W;QPc}rkV#3OE!WQ9Xt#ERfREjLV+}Cq6{pU&@fbFGmfAn z0_SxGik_hwn6Xo{5zJ832uZID=@^St#>(`$d(r4O)~azBI&QM-c@W$8TyAWtWOP3O zBFu&P9c03TiAW{0egP%~@&=P9>z@sOasJPl_Pnu`-+u0*Bw#gh33hGodY>}#>kyf#@i~GuW-%dgB0aVjjpL> z{4f6bf#KmF%cfQm?q&~t!P1OWqr;1FWv&mnX*gqRox$-hRGG0+VJp=WB? zng*vuWSj}$5;{x6kLJHll9Yn8d-*PpF4!?tio(cvN2Z4hV_%|*cv6)p&mn6;lWx>v zGHH&}$&%7huE);+;`i12zEbD&d5`Pimp5|FtWxw;3zLF~;`U}>#7l-4$mq2a?o$#I z-^T;Cg#zgrcg@z^4hDE$5glA3!*5Ad>$_^PvF*;*@if+N_$yLfA1N{gx91i(<7O<` zSsRiEpQyU(t}pPsvX&s?KKqpbjBeXF_HV}MtpR*q

j*YMy30YT%edqmF6!OJO@D zJ5c3nXEF(Nbq71ffv}*g^O!^5m29eaqco}}+#V_|R0IwtcP&{CdQN~m9LwS_S_bLl z9%6I`r{|JR-=QSn+Gt&*c}6vkeKMJJyjVhw={7C7vciuNSum;H=}qM^LwA(24dgQU z3|3?8lxR1u=9*DnQ2}gSMx`9sVCuIv0(e?KJmQb$l1e|OEpMgy0`EMgX{EDO|Gq96 ze~_G*zaIsVKY6jSY%AdU$gek-Y}1BJK*Ov3{b<2uX+HwCk|6Su@Z@6}`(DxNNtu7( z6GKreHZ}_vAthye_HKlZ2MU>0F@rI-M&qOH!GW~b<03jBB*K*L`AB0Fl|NWU5OHKB zZi)7SRDiCcjH1ldV-M;3g!uMh@>5GWq(tT~ZJVP4tjTBhM$>CGWr%6j{7%Y{AW7g^F%UDBAR#VU!d!B*!Jb=G^ZMzLx9nC6za_WjJ( zQ^O`b9s{4o(s(Ad%jLyuPNr+<1G*=KXInB?|O9{8t4?|}w70oAV$cq@itFAe)R6^mF~2PI?a zYO?9rTCFvdvM_}9*7i`X=j7e}aZw>5%_C33J(A{&X)sX>Hf;AFaJ@4B?iz80Unjl3 z{0S225RF*lqmouzJwusHX6<{dZm&}ZCWz@U#E|g8iFs5fO5<2Jw{*C;II7At^Wn=? zkyw@RL%14;_z7$#O&xN`PTwsYRWR1|sGl1_yIx^L$0z$)xOay2f+G?HhlNZ`UncNd zS^}$a3#+q7AfcgS@>x<|9v1ORX-Z_-sIMv!x$AHm#E%8HR^qAQ^6NJ$oLN zbyC<}E-ob=l=ZXtT|pWPCfg(83Jpl9lb=X&2%7rpx(9A@TPj;u&K*6x!9zS-QV2#Z z1i5{31)@Zffd{0-xG-gF#8Pia*y^7$`!0-VYBptdV{Dk6KGa5%PFU7VPV7l0A6Z5uO#N66Qmtr5L}p;Q|39gcF4sCGqeOKOz3^6?ay9W99jbFz?lg33hp z4nlBG=QIO1Y#BA)+lvAMkL0t(!Hx(i^9wz-Z=j)ObtBLTP~Zj?c)-RyNQj=ETKhqD zeqBuzaf;xM=_inyC8@~Q`*R$-HDl=AN&y{^v#1o z&`u%y7f+|t)|`D^_53O^Nxf9wy0#1B)?PO=OYV~d?-H8s@L}Rp@%YGGWXXpe;RyRV zMZsN6apG<%R@ctw47|iq4p!{S?L*78iD(BYKW87|apv~sCLXDH$Vj1P^nmE3HH>T% zwUEe((5vxgoV?Dvet8+(XY~wIL+=DA6&^w@9k?iKzhZ-m9U)BpZ#r$6#vM~!^CKo| zU2ohv5t+hc_>Zy&>T<5jaE>f1W2;(trkieOJTL$DOq)^sIilWwBDgsbz(c2IHt*1I z>L*xO)_k55+65VlX40BTn;;(vo%X7S?enasX0M>^=d?rfYxU0}Ll~H2wm6*Q(-g@! z(LW_)W$7UxKrpxudGWAG#9J`!_G1BK1@7{dc88@HDp3gSE7*k+HM7PsMNgP^GmPo(esTUuvqdrAKL$SEQ+BvC2X_1wNDDy}?ao+BPk$kLGL?@Th)1$s`dmeE zynNsu&y<#DI^RKtUKY!KgLBW|ct*4dw-b^B!yL%2y0*r9!G%*u(r6Y83yD8F3%hng ztn@MaL&V;KAajTBJbGjJhBsh$WJ4gF!X^1*2ddpRmr1Pb!C_7qq>?kq=yX$|V^B{$ z6~@>C#l76&ax7rcpS@1Hs~zR_wFMb%JOG#C+8h9AtJK1_gj~*PMg6}#bO6~>d`|d0YZDyA01Q-R=pJECplw-Z` zxV@|tzFh|f_XdhrsLS=$p$Vl+$mcy{d10$V17OxJWIiIu&{x`_IwNNe1XO>K&*a&? z`C@>=Y&tR9mg0f1CzxV0EYhd8>2dCn2q7h*YoOq(-r>DBUpH<;Yw)^AS1x2E&WfBL zorgFH-WU1y+jjNTp&Xu7>8hLciL>bA$vs*lHhga$W9p&Ca zv?VtZiE<}cVJ7nBjx}(3`NU(JY}g>x4&L`|j1N4OG?QDZw^Q~l>3$Ou5fX*b^F6SZ zIFv*t*4Eb9!!;|Pw#Zh`;ne6z$?zoc(Pbk|WQhJwl|v2Q-C2itAJTZgwkr8ax_WQM|NfAb`NqmSLoQs>Pr!z z?0LCPrpAB81t2rIA^8d*e~mCWq+>Z?Qf5yX>nK$&XC@!8A;t zWhK1gzY!oUGoA{B1s6bP*af@WnNJgb#r6o{x!1&hx!pwSfULJN>&dDsw7U_b&-b_0 zU$k@V^#SkZJa0q3(-=(A0e8LTp<9*`ZP?M-rDD&C4GP$!H#nfFLR=DNRK~ z!{qKf_%vnqV*B%}Sg9yARcd$X#goUz>_?*P5YCa<8J=n`UJ%l1^YySjGRzdtd&(*K zSO_+5KeA2G`coxb1>T_+><;rUHI}_qni0w|@bzgS3{gLqD>$^(G7|`&XN@h^S{z7# z3BZM?Q@?^enM(7WJ&sxzvh8n(jcwfhH73ke$$76iQ_&ib zsfn;?6@7`fpub# z)_B5;{27E9hF$)6#hjSBlh-9Q@S*!OJk9CT(A_E7I}QUEDOCk+Si1zTi#l9hYLK^; z!TqjCf5DH+8sxjg$LSfl&WC8_4a4L7b2ZOjw@e-iCDzp@r`psT?&5})NN_YZ+s`=^ zuJV;2x7eF+bX5>56E|{U%T9RFMKvS&{ajnUPp+1&X2L61Len#4yg)?{tW?HufJdL` zr+Emyb?%xB1D`4#^z&9{WL1_!p}PGtG&)y6*ph;Nv-cSzivgp0l|Tl~>Ri*Rk}=F< z07DewbT%>F7LLg~YxnJ!X|hFM=QHm*j}apMkBTzOb*2O?3@@;`u$z75=csm^Cseo6 zh=Eh%E9uZuKK{=ybb8bz8EZ3x0;n1KREIwghk7rMTfXKAW1mi?+J&{q6%tfzs>V`5 z)wj!ZgvPNt@C4Vzk;`R2E1z*S2Td(Sx`ea!_<_NJw{pgrmpDl|ox>l$vyNp9eeDTnL(47-K;({$=t&gX^%x9Jsy6u zXlst{Sc_GOb6e2s)bx=3QRum*Fv|}Y(8*-fdRx%B32~PmJ~BYhXLc&|4&rTlXN?y1 zuFX48W^l;4Yj|{GM-#g-S5isabj&NAlsXWD$@gWWOQd@fuldOMrPIwStG+odR#e)X zJ>a1D;l@9&Y3M?4zK7y)&5DCL&)MNtoA&-3#NIhnCGaC?bd{URD#oe)>6tEU$(Jr}-CeQOS2=_s;(8N#S-N5wG6K!5 zmFQDmN5jQhH9tOqc-(ws`_I9&P7RF3G&dZ}Y|}_i%kANLC-``15&6D)Yme_5%`2_L zHNRhJmiabg<_`{Tf?{K1o=_4r<03uRMi%?Fpq6(pPGan8O#Rg{`jhqniZuU@H}{s3 zLEViPoD9r(C@mvE9rL>|VvK^mn^I+{xjxwU8XLD@7nz80oP;i#bmp>Ig&pPO#SM^K z%SPCUsQmQE!dF#ak@xC#l^5-Pj{>1w`JQx-$&-(#uO%UQy*E(5g3+7lJ~u*1<0^Gj zOZXt9qS9Ha@Zc#&GR=Yh;;0njPM_R!rFW*u@;_7*=k#37vYE<%|OkVl*OV72rhKxHl!>3-Z?k_rBOHn zV+M!^U`eF(e0?mR>8mqVf))^3K&NN`}$jOq!d4G(v3P)$oINBcLis0GWv_dN%El}g`pVANZ3%S)qf`F(S202!&cSwT z9r@)!1d6uU8`i^~bRvMfB$(`m5g-=i;eo{Te0-tb-s1Vos%t`b&nnLSAYzN62PFqH z%+IjzJNjf-tNO^^@hMtm^1X{_1{`qe?>F(O*B;4B{m>w8&2YEI8ZyirzQ0J#2ch02J-J zdwTm^1n*VbFDOceK?OhE_}TP zo#r$;pIlS4ITG58r+BGhfs05(-j5I<1aUBRhBHs3^lvytoyVv}4YO&y5`op(=LgS8 zV2|%Jz?e2{0f}?2%$4{G0s#SJ$q^S3-{r%%ci=W~oE6;UX1uH~C&v4KK|qKT6?>Lf z*w7vGpDE{j$1l-vI{()7nEuPzT)yi4tmG!k0X+#t%5Dy%K#Gl=m0N#5)Jii-nNR$S z*RjfliOW~cbr^@r@$WN&7fn;==^eOI^x{`)t9n-DL6Pzhq&4--B!`<;zH{_`^EHA) zM+Q3OXpOE&*>1g^0mqjTQ&_XLaM4YQ=%JukhTcEJNVcn}cau8k)PjFaT*qpqKFogv ztu*@#EnRo96judJ%iHxyi+#uB-Pb0$g8;XpZ9(uDeZEYzZ87mA<&r=|9;_TIi!KiP z@Uya_pvZupYBlR*;u9}|Pa5jAdmzzjLZWiA$QMI2-e|4I;*}h-5zL~C>ql@!LWFjA z1RiWLkEtu|_(!E7V?s-<;Hf^;ieMK25hWXZk>_=P*~zA3I>%QrQzTc~rn&(|9k2rV zk3b41CGr;l>`x={>_C$t6neKoYhQZLH4OP!1Tj%jLZJ%2j95{9e*6$J8t38B4=IL# zhH#vYND8tal?=#Z8n#x)@^>3yB2ox=CW+Ng{-1!l4GrU>uVf|7b$eimnvws(sh?8q zC_9xxU?f_6M0sH=WPw9RGzq*znw6!GC+N ztu9eLW8*>yXlRf9KrlF*eAnx}tZ#&P+`i3PHZF!{b)~opH%EzaadFj~tTVQU z9`ic@c9Ze_8C)P; zrx2b9n2nsX#q{tfQlQ%}3wszh?OmE3cSUEK#NFoDzgJIE25RX$!D6!ucDUUF(HB7Q zhB(vDU*llqX6dQgn75b{C#}^4zZRsBg|RPS*La~i+QuuCeRD{3#-bPP45xpsy(mh- z#okRbcw6xAa~g`UILx!C%+?J--|0Z%Q%d`!~W=7t>N6ZKm)$J;N zh#`AQ=I|Ck06y%A)yofGoec@U-9+i2|2tmmeyE9?wq z^=?H{q|Q`&>W~j00TyGd;Gn z4Me9{6K58^8<%Sk4i$M${Lrz{mHoy;OiVpb;~X?Xa_sPHC-{cYcA-K|k&G?&TBvJ( zy#V(@ax8FEHL(r0|FOp2R)^T_8PVoMFd>tR^e2~3HH6H{Iy;FUC=#VFnZMA?rQyEksV#H*sxZ05AXUO{ z?WbCwoVcXDdY;Of;gQ$@6D3Jlpit=7`Se*X-R z=UrRIkRseixiRV98Y8u|q;0& z|9yh{jH)DpI~$g5H2h6KwfdY`?g`}bh&^CnZuMuZo7s?!b%fD(qGSA~>D3R6U-wlx zJ-+aqv&zVZ2XZbBl&m=6JCHE;h)F=FUMw&=Yl=@uc+-swfypA$7C{!k-QwGRmnlc$ z9W@$sSKi+1mt}66jjgS^GO!OQ%Yg9Vm_>LZj z!QL*~E73f$SmT%cuts(^bf~XXODC{5ZXjy}g)}A8vAf;Idg2K2s%+|dXpc4R{^e$=+ zq$bP6t)K=6*JkfW&Ph_!ScrH#+HoB2aiU#Uu%zfPC0UO$=9F9R^lp)xuyPdkr!kbr z1_1GGc7}8-rwKdb-st~ur|&|)9|mm6rjVOyf0w|PmPepd_I?MNqPbQ%mj=E2@s3RF z0df6Y;!dK5Jhk*-*`|jtb}EB`Mw$x3fAvSeV}x1@(A|&d3>-KjHFNq)mQY^YcAc@_ zsgI)TUR*ZrBng%g$ce_i`g4SI2EODQG7y?tccST@xa<7wUCxZ4!ruHDu0X?>(?np%fbxUx1!pWG-Hmriv(|S^fH5uOt z#yb^(H`nL}t3l}E;n=v)c5#x92JyN>V|`8bMx(z z*re`r0et-9*v#H@!1$pWWZw7FQplf4!n=pw!>M{CuPJhPVN&`3!N$0NjB=e`9@

z?I{N@{t^`o)uU*GaV%PY5N~Y~`X~aWR%yM<`bE}b3mE?&Qh>{iTmj9Cj*+|_6w8ox zeha_)r36+dOrZ)_zZCb*j|yWJRDyp(jKE``hytnh3;nl$K-uwO;7I)LUwn!Gg*Bex>jDYy+3&E)aUd~<1SAYeAWH3dvxb%&!@h)*4=*95>e!sO@>$~CQ>h6mWITrC*rAwtHb>G?C7vM-E_e(;y)8{|nKOnAKhc8cV-}&z*ivgHg`qR+h?+RcJkK$j1 zG{a&Oj|)TEM-zhXT-;U*St#Q{xGw9#yO((0GK5M$F;{N|!(_NEdEMLRrHKF9GxC;S zAC)Kf9GPl&iKmjz?V|Z!zrXH7{$uy^UflN^tkvE3hl$+(g%#~;A}71X_mHi_b%~t6 z`*mo`v1sa7+Oo+W&%6HX^M0OG;XJ;)nIFVW1b;BCSrq@=Fn@a*d+0DJEi;|CjxxvASIFAsh%Zb|;kT5ubVEq%9Y!PA3XT|~RY+k^OjZRECJtJ z{^U+#arqM4WF>k36X2I$b%uD*YW49+1EX%WNsPU?{}>69rR(UbQC?nNP0f~$IQ3ao zmW9V?FjLIi8<&4+!4DzCOS3hjalJUOm?EjgMlLoMx7yPD>eOPLjyfPnL3&)|4?GSy z({`wV`5%^m@XJ4RpOk1IJpT6t6huLjZ877DAA;LTON1#@iL~b0U}N#--2A>RH?X1K z*Bqcp1&EVAqp2N_^<1KNyJ4@)HzXCu9#7nLr?Z?36W*(Ob<3y^%2a+dttH;V9?LG2 z(_Lsrolsz=cRf?fEFeU*_W)IBhcR6%<1YMgByy6*klON$n+JNuq&0Z@!{R}^b9{F! zsioc<8u^NKcDu>p1YH}H>)YF?u zYazPqnbd{&r>%)6IeiV9&Rh;Z7dM}BrOb4t<9iCpJJE*#PrQUBym`cA|A|-{Y70mE zzW3x2E|`fYw5zeR{qO9ERj2yvX~9qH#~r@;51YNcy$K2m!lR%huI0RJ|6e-Hm0BG8 z{iSHe7<PZ-sp)5bye?t)&8t$8dtuOn$nDd+UACP=-FZCL)G}`FgCb5AZ|{DG53-+=F>y zQnlTO{|rg~>yd2Ha%S4e%2Tq|;^GvngRa!rJsxN))Eh<@xq%xEUL75sSYCQOr?b=i$zAA@?=~d2XWP#t zOD$71+*s_6!EU!lX0Ad44`-W-Y5P66&!Af`Gb*$5@GUjiN|ARv^Rw%c2jV-tUG|i> z?7%plvzm14n40++m6c$hf+uTdD~NKIh%A3FR=o{?+kBz)c4qYY@-oNyboIQWtE%c; zBuwb{G8{Z^%1C4E7#0>WP$rICv6h^Y;yD`qd-n932pa>pV2EMC!P&szSqt`{2~`DM znv&6I{IC8HL^h-eo~-$n@Bi6}81T>xw38*Cj>%VtBfn2!!W7M`r2C^R$JGI4*!HC_ z<@DK;2s}qS&S+J#Tl4oamA4b8tbZ5De->&V^_!m3wFl^|SGR`vO|0S8kl(itoNsB0 zb4y~#-!wYwQr*wz2EX*aJLBjqsrBA|aFU+gpkJ;1$|q|G1r8ou`vu96H1yM12TuCW zFJQ3KB6e`=?mx0~dkM&?FN(fl4uIf?LLvoxvWj(>JdfHjbd(LXnwy<^z71_08DYC` zabO{wSU5-h0Q^*U*(-U;O5qu83Tpe}l~$x7;;g)#IwD@O zpeT~gEEQ%SnmXq}m9{QrW*qDGa!<0d>je8AtFb^#LPFx9B`qBZY!!y}X(P)fntL<` z_Iv!Inw$!#*X*_*X6XRid9V>`>~qQ)_bnRsCcXw)rXaTS7$nGDeaAV0*7`6(AFV!3 z$cEEYRL{s{7Mpm9@yRKfK-Llf*`B{ZMcHDq=_fstl(;NE|JS7WyVPdKD26uNx|_MO zZN_pH4W`PNZw$MJ6T>vkQkk9ZkMy@(tP&+;ObhwPsvAwDA_MQq?5mwSav2MGCFTYB z6hvL!`i#;7Q^9&U0$h!yULU6~ucv_CK&ZP)(=B0K+ zdacfTQRMaU_i}0#z)}2fP)ftQu7MWBYiDW@8k(>!x5Vk%!F}SHQ;FFu3kNqI?|u8q zZZk`R@i;q%As0Yr|L&L5d29 zbQO>$qVx`mROwYZN-v=Yq$5%uQ9uxo-b+XzK}zT#qV!G@N+{AH5I`UxEqoh&-}jvF zJO6*?%C%ee%$~ibt@~bUW|R4U%kVd|DiLhWgiz;&dQxiVC-&H!oIN!`)PFD79G%4b zbrON4KlC(Nr3|#ujd~8%X!R&E^hH)?EqG#^xn^@}!t~gafmE(hi93!34r3M^wYlW1x{nB0 zE~6#nIwUT;)+t0U_6-{<4x-+bY7#Rt9 zXEO`yvtQON<$9=?UQto{Fx#Vvx@@!N;i!}oswj)|*x@v@Nxby7{!C$EmprGm9O|08 zt6^)SmSNRuy-1U~x|Wd_7m=Z)Y%Eg)k(ijTHGX91Ztj`RwrvHe&6ZQ_r!B-CnmgdW zURYVbsMb=C=tad{tlh$NYB%S$#s#a^Qo7~SsZBp@)pU@ZHr5`Pg6Kb#%vDe`RWY0K z*Q=5(ao&%xgns5MJ&R3$J@3tQylAe;=utTm8ltH!;8?cHU{MxVBddqMkuEc5BHB8~ z80%cI4PI|Z;1~s7G*v&3h`0|Oa2O&mbWW2EmD`Bm3$s;KBnL< z(5M(4C{W(goY63~IsBdL8W_YMfAPJ$PUp+kwf(Ie-N7F;PR@n_1ABrPZ*7F$XMX!t zl%lXLw0xjpK}Z(8>C{|}yE#3T_mx)PI&vn!B}>ZUH(bjt?XEtfl=Ddq6S1p1-~=xX z-dLM(_8RGL5XL=#~t0ZFdY`A2}Z~;K{3-6N^$ zRecCA^f=w7m-qLL#+Rx@v}wa6d&51e-p!U5i0Z8T?o${1F4@jfzh|bN)qbB&|4i*# z_ch=3R)_53(Sh{)E0rZa`tc&CyZ!3{dxwI1oorH*FWn`MTrfWU7>_LRe9OMcN{no2 zLbQlcfj!=5Z&fXw(7st0TPb1Jx}5LVVqrBSrp^#Lqe;^eQWb#lafn`Ncv?m<{laHV z=7-DmIcSJL;-&_M(wAm$J=VTZZhN31v>3*0_Qa>hdhRFFQIvWeC&%CwvR3}t?lJeX zMvGCoaRF|>Mz8n3gRrhr3Y|4XB|$BJBN)=Gl4w#|vK91XmTafSCR$ssB6v+nkPX_n zdAqPr{bbZij{SE@DV9nbr?(ZDo)J(~9KQvjOOslS8LU3VHljeY(t}SDH*yF&dxt$z zOXjS!YVaQH{sUR!QAYY{>)_t6^;(yIw(Mf@ehD*^di774mKcP{9jC9Y;7}?}4JS37 zVBDKw0`@hW|9dxj-<(%~Ll#FGW4yMe)-#z&#yLpgD_ zwroW$pq5dU9JiFyL5HK?$Jq_bI5yMcVTYs6nS5<|q7mqrt>{4kPS!!HUOEXTV)y+a ziCv*|&vZ-GcKQx-)U#7;B(ZaAs4T~~XWt!@e_V{~?@#gF;Ay&&CBTlGeC+44;!m?a z>2?O!xbsr{Pq~F%9W5&hg#%r8*lXB#U}?v}9b?T=e|_X?L~rzJd?2x4P2O;;LAlYA zxs#CNlZSoan*UQ`$F6gSb*I0dR+;%J<8)G6G~y8=fi<(0hBS!d@MV-3?i(mj@XE zzuKol{Vv*-1z|D^Ksi&n3C0ifb2_ci;OLUiL7#C0s>ZQCPAhTdO3rZ7q>Od_fY`lz zP)f?AXDrfWsysXm(48&xbGs9IwHa7d%8M$xONa@a~eAQ-I9!_(bF&X zEU#9XHKDMtZ1S__Y9h%LVZ4tv`-vh2n-yfs}yphnoIxFuE2%3c&(31Leu z+Ht=iFOLv!$H_i*#y6m4N3a5ELIwLFks@`vPVylIF?%L{Pnvs|%bOr1!o>-;_CP|Eo+n zQC3AVlnBu-sUEVL9m6E3)RH5foE?pUEnBOqE4Hp3{d{xR`NcPV_P@miY{M#bMdj>QfDnKN7g~oT)f(|GJzR0TC$qrSwRpeex=i2 z-g(&g(0K&@Zp81b@bKVFrS??h1x*u5^7mVpGr0eOECh`w7W9&deB?C?eRyoZ>|8y3 z7pws~TsEA3-R%Muc7rQpL~SP>)?#y__yTCqgj=$Gwb z^MXgszJ|Ls`+cx%E&fy%sW0MhpQsfA{^+c(x2r2vdq6iWv&I|ydYPr>_i^yF48ex= zbw?24gLh5*L{py+DyPy)F_=-65E2}&=yP@TxFQK|3%-5&?l{O(27xDXd2UC zi!YdIE?g*S=Jnpz$7S*ucCYkBw1Yb)K!o4b@6siIUWkR%>LRB0J{o}!htIP7f{a{W`gdZGMT2WS3(}<~)05EI zkiyMlg5$LOfm5uTPCfCEcU|;g#cXu1&#(Sy?NHa*l0%V^arm=qY}S|O=-v8(VI+f= zPJa>|@D=q;gN8lt2SbfM{=+5k$u&_hp|4Z4;fV)W zQaS}kaEf;!M*XBIPY^Yr8E8-*(f@ip!43v#vpizrr?M1!gnet!+_HQ5iY+n%iuLV zRu=Wtqt-yP(c)%WxQFwpoK`;yiTize4&`I)QBcEPlUg^6cgzDh@>cE9 zG>EXf7mjNusvKMvyApn}DHn;_bWl>=espKK0q8kar~PJ=IjPuW>U0d5M@2;aHqEmO zV%pNN!Wi>I>uEgWI()-$Nz|BetUa1N1oGw*SxRrq1(HCAnI?bS7{aQXd9w&e8y0#- zJPtYo*yYa?FU~v8#Er?C=hMKVsyj&28fU|8N8qAPnnCd^Es{HGk$f0RHW`WK_3&E# zxhwy_92PWUmFDzK%-3{9nTpNpv4lUb`e*a~-o};O5nfOY6BPS%_ErB~wikZ?bOijp z;h&R%c9DLGcz`M+Nv3}(o*QoG;LsU(HQCZh?yI<_J`%*w&kti!F{t^ntlp8%A6V9y z_+_)l$k58W>@OX1o=&dqiOFT1HX&i*8r$x~*E9us!jv`$K_tk9fJ686^?f*~;1|G{ zcfatqiw7GEVJs$~IG4D8tFXzQzmmW#Dy;X_bBKtp_i11}F`Tf#5HGQn;-%MA8=2kKTH^sE)D4oB+e+52SfDrso;G=4PG%tHDoIm8> zf36!aRX-*@r+}_D{;gF1{)bQ2{haLkPoOaLDTw6-PGc0uss3|SVG5XyKk_%5cQ&FZ zY6A$)fGd-x8PfILfeticW5f0QO#w*+PR02PurAjGZQz?O{wuzYPF+58^0}U*L;1}O zq60HV7~Q!(q^rV8zm;deI~%kcizzeFcMbc;e_FiH<&ek8^1o+tKaz3lLTvG=&md?N&nCOLdpIw9UOooiO=5ru z!`@dg&xe!fu5IA09z8}BwKt{E5a+3Z8^-1LR);xe6oEqpQ9G<}-@$(({LLIip7Ryp zh%f!P6GeIkNgpc)&OFk7v5`R8J3V`diO1<$0~=6jBhns+GdrP&tu1Ljsg<1rdNXnx z{110csUD)8Eidtl);}*+Zf+6Y+@%2G=kAy_z5a5OmUcmw5;!$bBn=(xbI}J5>&{;a zum8GZCQlR~j7E>D^*?O@dakZ98LQk22BKd!W<}|ns3-aLiHyCC3Rf0={!MWyIJ+KZg%NFUgqTbN5lxKAs&VkU3^E0VLCc7L6aM!lhdb!#;d?Jr&4YtGty#}13iR*GLujIW^cGM-Ak!KJ zg#1zZjK!=mgJ>d)-K)9aU_kV1_{qIk3A^WtknaAcc5lw^NwqyyNw? zqRH6@$PsE6od5xms6U1AoXf0wKE$v8ugoAo?KYmI(0#+6gQ+=i8_JEg$IS=_mMZzC zC+Z8M%ht)$xBF-taw8c-b{8UG#fQ}|H*I4#J%QO`<*+LP0gfB8InGt|P1BPSDp%rO z%>COJKs<9uu{;B1oV9V}JRDqI9CT7rHuQLRM%p+Qn_VF7&Q=~G+qhcsM!&kLi^4vn z{PizM0qNBsS(!YTSj$n_t;Jh#4|+CZ9=s8n@1sfR1N6vjhGSPfcd25tf&V9GNJuXS zcqFnN)w9s$=?XG?q*TH-t)r0qTg;8V*TW@n9-4YBk6WuXxPqO-Xxh^$JBGn~FBNtzOS*(di-8<~uEHM0WOc8}00GSP7(tG@3EJ0EiFB9Vh< zt)E2~5JV>Fvg~Snu!ZOepMdm2FmcA zSJk@zyFCGBmPme!NS^1C8MQs#P?+nWr9q+>i{!vVf!8>H5VM#XKx7shD5`@(!r}6* zMRI{Q*<#qZ56ZzlxR2D(99+Uezro5iIBI)Q>Bu%xzDd3S^QB=s6QeG$pNb@AAC%2Z zO==dXuyML)W6hnS3uM`qfq;>odVtwfnyTCy9fbRQQ08Orl#w zRhwrr1_Ihp@ORbNjeszrro^;i^%6^2WlaXbp|M6*NoCqB4`<`x;~p2&1;0g!deiL@ z*CkeQ1_V;u0y2n_`uc#%O6qFA%xqT3t3AV`DjBzKe+<}JyGt^mTjROd1 zDybu!nP|0B%wo5}n5VdtYb?#)NMLC9L#KgYtF;<&vC=ccF<9u^%aY^-l*2cAsfUUN zzUNl73gaL-c6>f?q|+A8>eY8Knff*8ydO2zt$~Jl88$rnkY{R=CWIsw^@pg$mDFYN z-RAUWk=z#poq!sNmf-q^(1hy~9XYV-``DU(ucYQvep&xsivZ$+JHfbR@$u==al8y` zYkT6t>m>=`tCR3bnYKH|!<{FJRoTJXEpnqGO?h`!M8SQjc|8&Y$>yEYw1$QvZeMe^ zitf`8goEo=l3!O>AFk{%ZO%~YyTl-~>Y(LkS-Uy zi#V0yX2sAYKYh1s0q!3<&3QH`hk1N}UAJLF`O?|mNaH)E{rO>a?+4|x+l@iYpVvOL z&+7fYi`=c@C@mm%Q_aX*_V`({*1!Kor5HsjwjN(zgI)})wwBOL?CWrz>>5_d5bO2A z@wsbzySZZ6&2SK>Pf1Cqb0d$qvS=O96y zueviRSnN<^`qz3x3CTFEsS?ly=6;I|@dIJMw6-t*6;<_PrJ@zdRlp?UZ_^w) zp~iGJ&v4|_`)~>0Gkk<_Slje|I6^CLO1hZTM=CqQrw=Z*U{Vs?h6AC(__QlO<9eOXP&z@bZ$35i#;IG&BKdHGpD zQVu^}2TaKk7)9bfc2{27Sz6&09Bf|fb!UTrQWnF6AG?hnGyC?EyQ1f#x!0HQry|Ze ztc+a!{!blZSrSSQwVNR9yIkERV1yi8GBnvf>%2ij2L4CSXdZzL*hF&~W^p$aolSdJ zi^=pJXx?rB@~$pN)?R>2=H3S^aalm+JyqR^Wq#6BsjU?c_Zgp=*IIU$?}; zMkN`Xtck$Go69S&ZE*YS7s;G8YX>I#wgv{DEK2oEot6><-Q>ZJdMaS*jr?Jnv(kc+ zCU|Kl=3`Uz`g~)D^Kp_KZY1#I6`EFab`dE(Q1h2#wapNyGV0_hd)a2LzLwOB;>NSS z1)r@lUR>SYeJa-p9V#aFvWFaSGz?bT`>@0tO1Xu2l% ziO#9cY3bg+eM{=th>c}0*)E`fl5DU$(*Acv^nBptkTD2|sO%vF@{uYC++%%K0lXYx zb@(mKEudNI{GzB9TKaeA1^f>L9aR7d{0mqKZ?fw%lfqa2eTU8*B*`$q;12&E^Z%zz>bd!iv)l$aP;r0eY4!8D(dSw(gu3zL5W1p_hRQDjpxcsaRUe-%~HRune*C8qEIw1p;e09LY01! zJKm`BV)_e~6@uzo@8$gk&^8@`BoIqS3qZTj5fgKtVcEL-C*40A`k0<`*shS7jQj)a z&+YVm%YIz{dKj>~GY~`3SWoX+RaM0wAn_*>iKpGa!0q2c_-@ixfdwG02pDIeHuC$| z!Zp&F-;w848pu6+ee14=tMmW|P#YBNfaw+_OC2-0(MK3e?pi2h;~FbjwT~W|U2Im- z39u*~5Ch8G>G|z5un4nDPZIBB0~m&Mn}+i07drwC^D%a4|GXCe4d`JavoF@=fZ!}F`HYt&EBs$Z7{NfEzZb(bG$w zIN`C_-lJGbS@#FhK9P1)s?E&I+y+ZZN~TMJo$Jcab%=A}3_Lo#N(&q*6~sEpj9(yK zO#VE!b~mai4dgS$)wzbtTw@B+>^}J49XO&g|5x{oq%&SXSV`e#r6Bxd4Gy5b60l_! zjYfdCBE95;KN$&&p+EXJ{gYYOQGT-S;Bu0yXebYZr&r4wE#%bco;n|lakNghQSF3c z%GRUSDlSzTzXA z4LFhlg&x1EahcE)z*^*rpYg7ZN8(M78#-v#A(z%sM)&{$pS^nR)eL+d!=mJ%izD8x zVQ&*A(qt?S%oo)g6@M{_{P{3esxp}xl2JNoLbh6wH@1!^5Pwpav-@ZdPBM9%wjT{v z6rc;d`D+}#%iL0H)sTTY>)OFyTPC>a$~QtT4y7Txa4EtsLyF4|#>_LVnk7Ci@PM>5 zD7Gv^c@|)cv5}o@96nQRpK?Y;FVPrIr`Mn$yKCt!uV5{KYeEFcx;ST)Ynj_h3xqvr zGq`0GCayW8|K9Jj{Z2uul*iY@hM!4qaK1YI%`cJ~3BU9OR}nUdF@d)kJY0{>{`g;@ zvtis0Zb<_F_PoHQkT)9$@|wgR%|hOBFRu}}S8zGOEI^Y{@b@(PLLL!U$Z-UbEB0)+Oio1*5) zo-qj9WGcu~t6Q7pk!Lw!``pVGvxRu){tzu_=3V{ky)=4f*Hg-7lFuYi_NrnU2m5I6 zil}~UUcBSdWQ}R#j%SumRiRC%m)8usuFcrd>2qMs_81GuIn8(Q8J?@LQ=hDHOpMBwRH1VJ ztsw6{0R^+0m!ce0)|(i_poL8ti=z&Lf;t(2x7KR=UG|>Uay2Y}4{12+wG43WzJFRD z1T_r_N_I=F7rjla!Z;E4R0spnkkwxs!l-olextr1n*yi2IOEFdxg;PZ zYm;pmv?VC1KJt<~GjB$~nZNr{GR74GZ`}4c{oT!Qv^(2E@$lF9FbgPaH^RO+v#1e{ zFHr7|lBt(`E_m6U274f2Ryi$+k|?cXlaRbhcJkw?jhVjcS;M$taM zI*+6Vr|&rGTnA&&C2aOSe$F9mhUeD^ltoOBWkJJ_akw zLN#XW@`ss7s#e2V8d+7R;=Jlx+)nd91PE&`yVdpI4}U>VCB;{(eQT0Gj_X{~V$I!X zWm^CKj=R*33Za*t4bcw>te(%Hhr975_HkJ1Fo0OA?+qaZ57f*^#1|K69z3{UYdN$xB+%od?t*Hm61MwHVAB zGW%yUJpR-=RhL-$XRDQv&g-9RH&L3S_G@P$6AwH0R2#+kTPH~Hl|`Y1P3U(U2bG+6 z#PRKn9r1_gRO+fla;q!^t6CO88%~>PCu~Njw5f`$hgqV^#pR0+QcnL3VV7C+vi#$c zIMt$@F=dR5icj-zF6oD~aIVvww$vl3osFJ-?VBi$Wj-55CV$3l57Kgs9eX8Xe1K1x z7X@U8`^DJvHEJ12sM>RK^Yhln;ZPp&wmiI&x*<7;I@TmX4hzwdqAY1IyXSe5G(6&C zC3~i8Lbg1z92S#FFpIb(SJlMwENNeLM$x1JX?I}6?l$-?=yAyP_*{YpEQ)P7gE=de z&-o+1d%+)4`RVj`dJ+nU0-M7_3$3iR6U@T>^cDqPEoR3ZvvYVwvQ7>?;v9Wsqt#x{ zwi&fX5vxfWPr4y1*KOxR&E(&)=S0)5g8q3*Jdj*8k9KJnHksVYb?JR$I5IX zY*_L#n5*V?UYgZRu9#9pS7zprZoXBT8NVpLua~g&%iW3iUe-W<;$zJ+HF)cAX@+V- z-zpa8I!d!nOc{k~ZM+XDC}tAr(wR2WUdwP&0cJ}F8yIF6JI{()oLMyJNrV4!R@JkP zO@UXUj}nb`dSEHhH3@$E;-+iT`YPONdf7$~PqoxQ4|U$xl>_#gu-_(i9(jPvr`qa& zObJOnmuO_J69cT|9BzxdnVSIiRr9G=^4TfvV6XK+!q;;5_0+)VwXi0;fDO2Db(@?- z-IJ%rSwhe+am|5=%X^vmcVm5V>&NbxYuNbVqy?OMJ+`KO!05eEY_h%j08)_9HF|AH z_$b+nv$zt6O4-_FuNf8;)#f=IkJ^A7Gef2Kf@13y^ejY|uF8tR3~aB&Te*~@nLp)>4cryS z^$qYIBWbXRpq!$h94<*@kiUP=Clzuv@*UM3!B9(DD^VXDsHC)6Tq$^f4JOq&TZ)xi zg=3G4oeAxq_B00WOnX1INfSzvT{Nd^{bfEKuywmRM3dX(T8ZOMA7|DH?hg7vuQy=V z;kmTQ+zwa*9S1TcmE44FyRK6)3fbnwKVd$%5Rm+1my|zg`de=9tj_9tim>-9WGvL# zsE;gs^Z3buy^7Xvsa{`O?3Y0op9)zo#znFZJDz&}n;xn+pk18OtRwl*|zXceb(m)C1 zt8Z?J39<$>Ei0q=F{_f6{*a+r-$Z9I*K!W+j6!(lE${INH>QJGVV{ABZ09p;8}wk8 zL57@4Y4Ep>W){EjNef{`g#UfV`7TU@my3d0T0i<=(gD@1&r!rGX|g2~Tnldvt}xB6 zQ6ffAqNNKnv~GtY_D?xRUcHcanJJ)geqIFwE3YI4^9bM_vDdgEZE4;~><#uBjK(M_J#3akWK+}L{G5; z75Z(J+i>VZX_J0;?1KVJhuEgTlubsR0!nQbfQxdibH4>FWALEUlY(?6ijwhWi{@l4 zjV)yL9PQ;oAH6!$KM~_HcY0>=GJ>h;y9oY+Eu5m&A%-I7hdC>Ha?~^YWpx<+N#7l7 zlR4}+Y(t(9HbtI}ulIoLn-$puvkSe{(U`?&`=7UJ7kABe4lgBghTgf}($8?UYm26< zGW_^UR@dd*QFl8%^9Q=G=0xHpDg~s2fO>WBjdc4*r)OlNnI4Y)I*;n?Q``78+CO$u zUYP}qUP+lrxlB%N@=@CA8ahV(B5HchUir>NB@u5u-dVb@3g`Zm=!YEClCpcvbQrlG z?=%7!l@FE}ZfSRTeB49l#oynu*{}}3SzEt9>C*d3Vw~po|6ntE!Htx4e4O5%Tv?o)cr za)O%7qcrj-I+w_(r`Cfnk@Ns2_FWXh$_X~c;J&{xftzhTlba1a+*z^{yLE1v8jr2W zkPd}}Oc7Rl2aU(vremgxjmk~wB{@k*h@#)z?5YI6xq19RRAv-T(eGA2TDwXBndlEJ z3yR_~pQ{6h+Hp1US&xA6CJYMs$=nP$eRKv{Z0`sA+o=9+`%8Ck>+mV@2qYH7%ssPO zt9!y-+W?;XsjqRCJQRyu==zeSv&~Pp;T3K+iKKO%V5Gn0t!R6gr;rwy@$z;hUeyj{ z)^;mD5h%@`-9s+5HwuqTL+r4XApRigsLU=p z$rRV#IDeYe+xCtz8WXyA#X8?**0OM;8cNzq7O}KiM9R(&2VPsoIAIW3c63U4=5(^gtmlwh zyb{DSv`k16Owc&GjfFL@36gj`F%pd$9oe-6&ck)M2c=GtKY-52S9L`}k{+y-@w(yb%d7mC{b zI_AACcWt?B%Gts94ammKJ8El1qSBSy{N01=hPr*ePYs7RRFg$o=_dx*E503nVO43- z$$c=$ppz|l9UgQm>mTp<6&ljf2UzOpk|_#TH(0;IR|;cOZCqHUpd7(KQz#1krKnDZ(>hxzwkBZn~k(HH| z>R`&rRDg#28*-r>|6(w?o~J;(R|bBu0d$x`k#0JM1@N}%PZtHeZ62T>{~cyFn!^#p z?_FUIbZ(lArA)Vi5vx(DUl9G%d@gS2N`u-}Benn@{hHp+G5=D7L=AHgyJ_(n4?}TcL!@|#4|GKcwnu$Dj|nH z_mX=)q$YGAJ*hVD30*1pY9`=kUVOt<66dxq@nxN-VI<8q0#?eH5Ld91nr&SpQ9F_W z>Scxo-R}$t$ppIfJ0xn)o){$9sqh{As7|O6=>9093zFmTUc3w|sW;qXQSo}}O&6ds z*s|SHDB@V8P z#Z6fx7WNn4Ane-p*rcngUJd!4oS2l0(rFw;C2^ulv+_P9Su53jKyh+$E7v?F1bp)b zF-1`ddu@`2=KHf#kwALfnhBWHEtno@1@whs85CdJbYL-aEZ7@tMuX zd^&L#C{uI;*aaXv5vKlB-~MTk<5rOi zym`6$oFa7OopeF08xZRB4qgl~xsLBlw zh3-mM6C;JgmN3q4hJPY3L2s<3by{cHXE5(5#FUoay$bgT>7_uDfG=4gY27$*5^YyM zGiFC$On|Sdy&Fi6oYZSrVRAYy_4wMI)uK43Ss+9u#EHS$QvU9XFSGvLlWVv{)m1M8v9eQ7S zmtxm_wP;a>P1~b&&M03?<7;oi4X_#TokHvt%+jxC(TjBLHqXAfz0r9zD$CV=RlaNv z3E2!X^?d~4Rg1$CMPzbxFEkIyC{2Eo(!Hywf}}s37_X7m#y-8PFe*|Lq91p&sZCN< zeVd2(?r*TVUbv7;VW}40M@=t4JyGxJ-Fjf?ym_*0DGD@e!u$Oa`ZkaaCCPDt z+Nb-;Ys9OWhEqh?&Nx5r_Hn!9Gxn8q7dY?!e&be4w7h zE$8Qft8uM3WB;(l;P>R&eycodL4KTmLZ}b>ppAw9QgYxFaVBs}U~taB<&V33m~&Xn zIr|Oa87`N*W~lu>>E*SWs0T#i+}ZQT$PdDWyQ-zkEhUrh<#%^aQ+%VLu)|A6b$l7}*4+#h$?Q<%GR=$1r&ib$F3E)btQ0)YPb5bT%V9Z0 z-3>{_n69bmfyjBZ;5UV)6Zu@)LrZ$rsh7$g4{UIWLmSk{6TDa zofX#76F;YT?O#r48JOw*m|3plzRBeMwUT~1PNXS|);z(jMpWgCfRx?s#{#O;V7uE< zwy(eK@?zu4NmiagFJCbWSEgRQRW78VSls!+NsW2;^+cTQGmKv0WatEsk#zJs4eRX{&L%kydi=MHh{1kx;|o>zpM%+g1_aQ`CPb_@5p&uiDx*zKZdt@h zip?r6y3Z@iWzzkwExsS;U=Ps}sJ&>OFT*D6MLj(I;r)w(rZb{nsytARNf8z2CKDa1 zzt#!8wnrazSC3L3src}eewE9|Qg>W-rgM6G+m)A*mY1THjVi)4M44>h#0YhoZ)$&Z zf;@R+eZ3zEnn)3_;!#c6y2dle-URZ?)_xOKbTV|1cUj*f=K_E6sf~|EAN$p=O0M?3 zh`6mTzUz~ouHp&|SGgTz+;BZqzG?P#!G#=(A+1;`R7#$z!k};Fwy))=&exdBziu|o zc%*hylTJ_herWsB@I=}y$|*weX^LIsC0Vxk8_XREwhhg9vs7I$KYz*2{aQKPNbNL= z`_}d(-l^x)&*X(G+4)ER1jyR=P4#^28>*WUOLF_C&*L6mn6)?YDd@qpKTYi=s+u#O z1LkQXk=N7-HFg0ql~32($fw6Z2TW5PpvTTv6#X|B?4Id)$I-gJUt0DDPu(>J$a5lrM@L%ZBvd;Lx1&mg8w$@ML?O@WKoJ-3zw&ed&>G`sf(6= zPiXOR7NmyRM7oU~-sSy%>DgrJm95RLN7J2ySCMX1Y8u-;%%B+p6iAdW8c^^Cf@0exfP> zsN%+kU)~$>gJ-FXOK{1TC5c` zNLQ)Mi@hX2-f+0{{Xu;!vpBp9zu9_5jJZ7!68qn)SFST(rF!}eX2`o1G?jjxpLe^E z-Xq&rSgpcI69Ypb@yqn&sY*|6Qt(C^-mvGAa}?&pFs{(AdM)yLhYtkJ?+WB9+__GT z7?0zyy3;U{p0q*}!u}8Z+wx_84bqDVI1{&lZuSaW>9{6)&heYn&m`L_VguDfLhrD6 zdR|g{q25VR&U^40iSMH5SL6IiPfioHpv$I@Ebt(0Qe{!Er0RCzfhL-BhS{Y?X>=MW zxLqG0CyS+Q|2Rk`9pwg&9OQ5E{btqkh{~VR{r7Do>*2&BN_`AI@=wC|r~*pfyL-1y>^UE-j%#^j zFGf*Q)hqh4aMRtV?0;TIVGiNTy_dZ7Dm(PU&yXqUjtF8t^n3j-1Np!eSWD#CGmY@> z1pK&A)=vq|(W}uYjrQ`ZD{<1$r@5d=z9pr&IU}zs5clmwZ`u^SzN4#Gu5n0HJu|fS zp(|Bg*)^L?Te;@$z(j%YjPFchr06W>d5vat63^vp0O$bqDf>`zdAxRB$?2Lo-;TsDnfslv$yP-?wcd9{xNTCe3ttl*xXDc~P*m!DXuklbObN!zPpc#^ZbTU_&(luwQvIzvU{f z#(24p6H zd~H2#&F#Tk$Nq)pSsA#ME1gJe!gjzkzG+w}CTz3oetm;qvJJ0;x7=I4sh?u>`a)wc zfZ@ve_U!VEaWu!)jVe>0Qkz^ZP)F)@eKGOkUjLfk1GTbkwAWK`)x|L{EPDT8qn;B+@`|1P9-yPr2X$&o=nZ)b+u%N;X1v$9%+=s+>T>s?qPIq92*etIGXm3vqw|J6So~k^c#ESzM}~r(+4(|3ON!9cU#xx29L1JIFua z@~BpMt4_M}SFQPMOLFY-r^6E0U3R?Yze8~R{S7hE{}Bi#&`TE&zA^?gYc|>pL|q*^ zJ|ltNQhf1KP>Ibt?Mmjmf7&>JWuB9+yU^Kby!zT3Qbf5UW~l zqQHnC@5Yg&gKhWq-UoEsB&3g}R~59XkBbcQ1+jNkE*E3OlrHAIRDUCVRps)dFK-^) zYmR3MvI$E0hI^$Zp%?#yt~2)v!oV>y8ZweT^p4~WGs!)&ZG45!A%BV zHzay~bCq1}SmTM~xQhvq7r3w@idtt_MO={jjJ9zZQzea%MidRy3YdN<@T1-spRDct zpo3N9(fz=Bg?XAx-Q4w3-%V6;i??}ho)p>Xbv#p*!joG9*a1?hMSG|EN%DJ7vS|Fi zI*`pa*<@T=nB@6MXC|O=*(Emrn+Yq6OD9X$J+(JX1piv@y-617w{2dr6&o&6iiJPk z;#jM3tY&*KzB@W*q0j8%s?(`3`jPi&6s)bd^`disTu~It-1U{cR~hUu)oA{9fNy&V z^7j2qY|azXc0O}5z5}KXNPpJFc;7HLyOvAO(;)HE2RSttebSk3uTWa|)`vA*8GD%; zPw(hcL-o|T!gYXAviG`TuMq>TuE!%3%dYfMZ;M+u9F@ah_0)>lBSpzI=K@6#OI_Q? zm=_lsIE$#?-y2~3Wg2IJ5WoJIcrYk`k%ZWKcGODw%6sM|Ra-8$b2ohUaQ*_xwvXgo zZ^^~3;KSD)PUOfLiSpv-h|% z-<(}ZCd~L3w~GDeBhF5vEFTR5%glRz(1Si4xx(f1muUNIO6yALjkB={6|Cfl+M5Lb zX4dhz0xQLS_tLtI;ArnmXU`yMsG`}xEATtipg059+SuD$e)pJ&Ws}pXs_023($&(~ zAN9_vq17+cFV3lUPi2R1iC&}o{=xN#0P^3t2qI5(B=^a5pI!FgWI-x~K=v4_tB8q?% z>AjbP-lVBC5eOv^nt&2Qkq!oK&YZjVo_o)C@A|`<41Y42wcckv<$Z_8KPE94tvxl@ zb%^hKB3d9H>H#<5yfmHRYvt~ed#n>OYX|3i-zHh{q8_rz8(6%X)*``OCb&{F^nNH! zjR}X*e6g+_i)FsK`h|Ep!aB^iKj`Ib`|x36{Gro9nUqW1_Lm@gR!%8&XTa#@)duG} z>}w7np?s0YB@8|%z!U2Rea5-z#4?aMTCm+rn!RlEt+o0FN*<^^3Y*ETLU`EPw+)WA zuPtthb>BpOvbM#wVn+Lt*`!=LT$6~&5=qS2sxYOS)6AVDH|KACD93D*m%4b{Tt@B2 zZDy`~rISbsj}RitkD%k?H`C+%eM`KO<$W6zo_60!ekbBdqusLHwil+sE|O|c&G%)o zmq(!ojMY`5HUUJn#TR5@zRKBe4E|Wufz4%sY;Avu)yRU>YFC!-Dq1=DT%LKb#4Vtt z&$dVBE(_!m`x@G0h*iINN(A+FF!tHZ+Ms)ks*J~2_;$jtZ4)hr^`JT0N=l=Bca%tpo-PKGTJ}a+7W5$rG_@W|4Uqz<%!QQp};u zDzuX9>|p!6U*&KAo>FP$+3EGw@-<7^_#cve$meg z!$`cDyl!(D@!n?8dIvNNKMWxOghA2uJX8%a+QN{zGF37>H_3Za{?}{Vp1&lgM%*65 z3W;ciUFcK$Y)Eg_^HoCbMbk(n3FLgx;tinFc@x=yrRHoj|ev#JdjO-?GLV3#0dA!^4PCpRaG2_xebX9 z))DsFy~pI5q^YD8f$c=3p7c7{Dircg414Ei%`e9h)FM*wASYi97A^hxDEU%l7GY5f zp>*n3&6$?@00$o!KG`a@7~qYw_PBLgHd4WT1KPIB0%$u2U?q$3PNt7-{ zr!8Zv>*&|lS3NyMfWK~cVxJg#^-ism zIVgQ10$l%cGlZ6he&1m7vsR$oYSTVL{#ptx@5ByAF#jcScvSlD1d8)4GqV;4LAEmAuci3MqfRrK-%fxx4%gPw_2TdzV;M z`VI+0pSez9v{sFQYYYUF^?h-bG_D@{aJmrBEtKMfX&~YZ1}t#0&Xua!jZbpD4bW8M zSak8vw~o-Ks=OEFL7Tk(%g@mdST^Mpj^Z3-Ql%X4&BuZ?*f|FS#-VS>0BGdWg&H#y zUD(!}DwKKQpim|z^El;8ZxRS@#PAl8L6gIf`ll)SVUU~qI>#&Mny*93Z)3zhy?IvjXei4lkfOhKCZ-d=ddWoHzDvy zEiZICY4P;xk19>E+E^z{YPbZ@&u$;+5vBg|>!u}<-d9I)G62ZWB3gTj#VfLL>_Fgm zF8DnPVHpD7wVmVyLxhU&15@Pdrxye?A%|L;t0L8v%zm93Sn|`}z+)2ch37To3Ev>2 z+IK2_+@03H1H>x!Hz>a%{2g7zKy(#b$cX3Mw!&IO+m{WdG@;H`0wD2#SHS2$!6xiO zaD^Q#b@L2%`|V7`ZTeMU$mph!)llowgw#icT z7LR28|3j$lyTy?Ql2?P0_}wzf2l(mT%TJzX4SOnHt+SyOB$D=Q&H$7dvTN^cto=O#d54 zGQIs!vNELSaDmH5R|SIZShJY6-O=TFwVk{^|8Zn8NYe}LLB;E|SoxmS%-=ex!)hNm zi~HqcHE#8H$zSufandq)6y>Zfa!^w=k~8>NouP95meFFuyEoDO=be_M7)g5{*o@S6 zC;7dMRz*N7CWwP$kF(ZhXI$&ou3o7AcXmDW!uML9PK{cLhz)r~O|OSNKvFBq^r1jMGYd;&wW)YQ^<%JE`OV0ayw zWl68z8O~PzbivG|_d_qhhqxd|+VPx@P6+C*6=@m0H-_+kHh}>)F|m;3nL_(`Jn>*~ z_3`8_@NX_>T8!;hO5fOy4s~g_wlLu7#?}g#!AK0wefO!-J7inSf!(P4C8skjFm&gj zc4^6Q_k?+CZqwY4l*ch#jZ_D$501lskx>~ovs+_)K3@bM)%I2z0IZT6;wz=rW zftFLYl}wUM#YIDtk6gfZqTn7a;TAkk`DFk2d>ck8{d=K0qWy8{0(Up~@P#WFegji9 z_WYUiTf%VB+Dvh)j#Ix6e0O98WVzS!pI@3{%aoBoW9vMoctft8Kh}>L(xqDF%yuQb ztteBLx(>6ovI++{^t`Tx3(`%Ivf;NemAb!&R(qHS1Qj&94vPuW_U8Ld5_yZM~-~VtGn8n zxZ0Tw$j#$#J#k*XR9d|5ng(>j3F-{()4d9o75ofIXHOR40QO#1S9qXK=%&i-*Hx~! zuK$L@@nzRXc@a3oKh(nQyEUQQxQ-$KQij=8l%PGz{-=k-aj8h>Fcy~BSaC^ zy$<5{{oK8hq(Ic&{aT^lzUR=eINpiXXMa1B-sy9X~Ujay5;uL5|VpK^oV_v#*TikA~j9ChGp>NN)_M zOMdb;pz*|RJV`67dnu?`j7!xoj6yKjwJHhV-9Yjc=Yy7bidliIIWOT&vgkBqFR($`+eU1e!d8clUSzzXMy~078GWlr zDp92Pd!V^BWm^Nvg60R(xEsjmM>=iC0<@nwP0^ z-Lw+dry2IfikBomA0fM^TA^`N0`U(0ioE-iQ1=>X|%voE>jOZl2J|pXyZi5?Gw34U@79(sO?r|WekUIwRj=&7!>I$ zmLmEE{V>HVK?TR_9EnVS{+{U5s~Wuz#Fp(u65gRysU+Xg(~K4)(#^zi;mY!8mHQ^| zfTffBT&lZ84P2*6LL0XHka+6_DOchO_2yY8sYOllo{}_?znH#>AZdP)Q{>nF{zING z!d7|rrHaR^(nv2;_gB|N0V_TDQ=mm23w-K4E`EeSmHAoWvU(0*4z0KC8Nx4kZ{Q{@V-i?@zCQ7gH+uDV~jP73BJe zA^z&=e_mwJ$Ya1>UFoUCMER*DI<(qjI<$@sdM(|3dhs~C5^>cOc`^~Pzo>G3sB-Y-OLXy&@Ddf4Kx?Os?{0@9zNULa2-znZnx>Q(@)y z9JGfY)R)deEK0f}D0?LHBwBNbuQszEVdFQ=nxXL^6>nw6K-PR54C34v7bTgO)MV(F zjGl1FM>rUi4dyflypi^f1oo{59UXsYGeW>;%cR$+Q*j@9VYBY&v8b zXeOU$5q20bXcHJ~o8bu5rV=3nW|g%1aWe{jUofUGj1XU)Uy?4SDGL54lL$=e)pnUgLF4Y^JjU`*rXg5 zvqbGanDY#d4Wg0CUow7|50g5UySsEg(Y6+c+BHVK=yD*qwv9`cy6%z2-!i3h;a*ew z_)8+foKNO);ldJig{B|!M0VEgn&CmFczc)E(mDy&IKEm1btD<5r}l;1`$9)#IUk)qlP$E@ZOFot8V#NU47qv44h6EAIFu zd?dk=6Tc)X`#9#Mn*~|rs*qV_NAdg=?L^o%_O@Hi#P(HKx8Y4LVxu;NRdLJ*|AsmA zZh4u}{=GZGRk&=lf0TV4Ai{V;@GbV>XG(O*W3I^azj5)~f6hA`lvmDI<0N@TxC5lhQy~;;re4X}OV-E(*5%8OR2~1~;s5;?zfcTO zIhqsUx<=1c@15zj5SLVR?O;qlD{DsiXb+6k062NyraKKjva#c!l`dWX%zPE6P-e zn*p?^G3J0}^J47Eh+c}A6kW(SyYjO7~hb1t1ua_j6k^wW>93orSHfjKY zDf2_BX8sBxk)P5X{a;=(&|Zk){K>)I+Uf+5FcNI{9hxIv$_R4zFAl%juyrQK<`96; zdzm1?1-Ko_DlwAUs*Rdv(4y?~rfc-)0jK+>EU{20kyN;pOlt+)g$SjX{vGR8GIV<` zB@P}0lh@DEU0nYPc<4KvlIgeP?6B8=kwRc`j#$?Z0ve^-a7tN{394#eOxD%mB-VA; zepUo}uTidk*t?z$kb@!v<#Gx~2b`bpkZ?=hT@={~S`tWK$Vh_hr!d$Q|71wrmd!I1 z<(9acU4@Q#c{UO%)`!kof&(94%U{j`@T%z&;_Y{L&d~L$m_wX0}8g&-)*hZ~9*mlM%Ys zei>I#42f)sY~Ff1_{myK)VoG1{BpxI(iNvo00saW)Lqr!Zt0`6ML&C79!tN~nnLbO zGSPs*iUj|ID(mhB=k2#yX$Kh#%C5e7H^!M;$3CGw8AewcBiX;FlP!D#Y4YAN@;O*_ zf`{?<8b{tKnj!C<4Ib?Ww=EfX_P~d&dx~%ON7#1jNmIT{*y%_qPu~;xWn>?ZB9osk zSx{4~eCv=6PjQ_5R%u%lgYM3aVt+nnhCsTJTMWf0oFcB#@&v?+L<`*f9AN1Z-1oC>YR zDxszydR<;(yJlw}V*egvO)Hr*kFStN+}l@ouYcx+?KS+hXIA|E?jZC?=P6Tf?xhvvi69Er4e5Vaa_5D5nrEbSrBp_b;}5k;Tba?9Af3PORT>4e^sPDZSTnZv(o)tTyx1Q8>!C{@^Wm(VO&+H`>wN!NqHThJMy8bF7Tm3y2Ypi7qhv2@G}5#tp#^D4;AbS{8H3sD&iYh^MQFjD zkE@vtxXE#GfGHV_Q?0mz-gWZNs9Nx+B@-lQkroKzyQdnSM?zU!tEC=)%*ndn()Md| ze=*_7TQc&1gqP1G83t3GAe^rjI=gZVA*U9Tn&~Cofh@}i=dU*%O{lldPa&EtuJu<&{ zTf7i_!EAKN+2^Pi6Vn_y?qBcbmQGy#CNv~AEmsuihXZ@~Re{#mahGZRz2Y(M09LJ? z%QtrhBX0gI3Zwgb_9wCDqUuWNiCz71m_4UKVD}9<=pG;QnTwoXL>M{X?^@*5qrVQ< zcmECXOCz4#49d>>f3Az$(~gs+rz?v0JyC}(UZ|rg!lV6kHngtJ19gs_DKptBH>}w- ztic#Jo$wg;j9=XSpF;d`>_yLY-t}xw7R)ZekA(N#m{QqS^?C9#v3&XQOaWcFCZ1hm zcWXPNi{;1$xs!Xl*G{8y?O@HX((FxklTLb*>-VGArhnK5Q&NA8Euw1IV=8Zs9aAf5 zwfNxGTl>T;$H-bBtDn}0|EK2QB0BS{(`@<4d$~n`hM0BWcmwcu9Lw_|8vBs6E##@J zTHzY!^r8tV`|*oy7K~CVL5}U!ieFHd@2LRl?8{}t82{V8v0(~|nm2QB znpE!;nNjauB{`DqwxN6J&Y?=_Cg-Ci?T#N#G9nDy2A&{gaM}aNXIotK0ppv^7Q3eF zY!jlNB&x>x@_KB?0>5-HM$V=T_C*_*t-=~+GAC!Tt`gpQ`?58Cwcr8oS=l#I)pG0g z?piBJ!%btkAUOT+6!R_VIZOK%SSA?qS*|AN&1?&YCR1&@ky4HY*tXOBnIexhr{}%l zHkPNew%wY{k*2xZ%H5d!%GR8WRq)b`p46z`t3fIrVH<}u8K~{)UdQn$_{mckpm>4aWJvb3MeKnAFp_dTT1CM1K53=931f^WKc@&aJ@@)d*JUS_UDh zyfW!IYkh)@5aHoSfO*BANtb+)ljnp6>T8o-Ihi|emz5BIoqn3sfUtP7vwGDXriDa#bACEJsp zJzZ{p4fei7Rs!+b(v{81h6rst&w1XEG@+;xT#+r$~{b5-Hz3%uxRPi=XxN`7>MV%dVt#5M=EpShV=!RaLlTj8=!P zMZE?*)zuegz<)e%zo%M%;%=t`krd7ra0B&AwQeH#{6-ydlXd9y`X$|JaKaPFe!*ic zg`xPo9sr>Gyng-iwg$l{|0A@TDl-rtevHAAU?Sh_b#)szp_Y@CORTe%2eYCLTYOfg zYPrsiu)Y`53sV2^tmjD+QRDb^d)^+FCY{31_(UZmK%mWuOa5OIYV|@qFJ2JK|TCZP{VQ?{NOk+=+@4ZpR zoM=Je4Pv?(lZRSW4q~;{J-ogQIs7pKcaj2aW13h`P5M%}S?{`gtByNOy7%+Wbi1f3 zC<+#`I6qs%Uu-oK`>4K3;Dns<-SA;Hpu+SiAj?si8?`(`tmBsqHM9iwSnw!g-%9ND z1896&*(xE($Tn_(B(S4H;l(*As2%q zHgb<#u>!-STJTA*em>EQMdw{6{-}8N7HcOuIuhbV`fT}=C&_H1-cmJQerLgCqbCB- z?N~`9HE;a1xTuQanxHFNnC0#%&r@(Be_-YP69i|;E<;52gmkC1!^G@mOG)=G7Q@@P zTYb3hSjG(RDcX4(ET*(9OpuzZmjjlD(a*u!YK~j`51aQuSU)as{G?Clz}OH%J1c$M zb>QV3Pg8l#2ysSwsKOrKkJD5|RU=#gs9D|5ohqM)OMp9kyiMHNyV&`0A@@e67D1+N zo9)!jjtw1Es(sI5&5G%Eydi-26u9rurJqO{-}g+te0p9is*Ztn{`vTcW@p--`o3 zR7{*sZSNzw$ZPD(8OZnF!*;S-l-QYma`sDc@Xi#P5cNJ-4Y2mk8?~z6Qwjpxv5Fmo z(UWRRfM@({Z5qMh%N`T&$Vmdr^^DivbJ%x5-56>sH-b^?)(S8-FQykAg)kcbF~O^8 zr?;R?uXQS%5Brf@Bimgq=TOeC-I4CEj%m3`^T}VC zkdbp_&QmxV3jPVout;K;)ge_azSf9e4W)c0i^S^^q4VD9BpA#n3%4R|6ISNXA#c+_ zVfM;lz0?0*kbgE%{L5027l)~8vYD#J?bV&y^Xz*}&pq_Qk9nXj(UWD?kM=!gfngWN zkHUetGtPy55MF-a;XhpmEXSF~rMrpm1=U{hKKGMj&(&@n&Xoc~#NT_Tx@}lO3=7z~ z7EBfbzA2%S^f;f@m0p{zJqlg4{^mJZWprPgH-E_A*q@$*+{4x(EJ@UnxWy58z+B9UgesOlh30h2#Y@}cqsKKPDI`1^V(pHR5w)7#$oxSsDpima(RJtC$w4C$av6$wskrpw1W#;!H`=x7%nv< z=jZJY`)U?P@5zy*F^zn`1h3E*<(8tAY7zW4$FI%0>`Yfh@{GfF!pxSHNcKlS7vK1I zTA;J$i^(+3rnaaAk$2^7+vj~HzIKW}=;zL*)V2mLqdXHg>;otyQl_0>vhIz3-9HZE z-AHZ`Uy#nyWY*S)28;Im)m90WdDPQ$wMolk|7g)Oxt4U9Yr#O&F#6(JcD^O z&g)Iq67W@(b9Wp-Op;JCywH%M)vx{nIlrpZ@@e7gEHY4ZQ*$V zjF56u%(1BIIEsYmk1&b@&Al7|s*n9A!L@RTz-I~{8XXW&BVsYe`3KJx3gwa++W3fD z=F&FgDSWKFd%jrl%Aqmunk-vgf`b?qs_!f+c(H6DcQa>Fq#+38)&0}6-%>$HtyftO zDvpGnZr!48K&X)xFXrCmF}Pu3$FV+T>^T4mWvSR+`DulEqQXHKGP=nqkcE|ng^g%E zJoUPtI_5Hb$}mgHon!CybgTkoStR(ahP(PMy*hq0DQhy zzJ~v!JMl0j2)f(I$K1&c{r7txE}2Wf$X`elKfOL-mn68cd)qC%bR*PA;U_0LL<8gj zp}>Iy72dt6%KwS8u5NbUs&Fy}aFjn%$usSr)Q)EFDfA z7(p#96RwMp3HOwa^gNacuM8x~3&Qo5IjHOhHy3yyH}F`c7O#I$&{c%GLmQR_sOHZZ z?H0Z~oa|u53cD14nsteGs=eo>G0Higv}fj!j?5VHfvJubTE>!q$!bg}l)eedzg)|C zQ2#_z^_OI!_S>kB{>p6~tq+st4h2Q_bhyUnYi&S0y9**1Hna5%N69|tHvy(3_^8bH zOK3Ub*-uopu_{tp^lwtjAA01aF=23)-o79= z0<(wYV!_=hw48N(JHpbmWLN+Vk)5CO(N<6Hau}kVPa6d2xPF!&sPPHa%(l?hwd{J3 z{{}{Ln~7ObC5JZai`DBh?U<^SiT+@+o2!V=&xMl)qwU9UG-Jw+L6pqJ?bWh%L@L+& z)BtD)js?;VjXA`4K6z5zV=zK&yyD!ojKO%d3j%hRoG^s^ z#I5;TlcbQZ6a)2YGMF8dKZIUS)H%G>@|!+yC1NScCT0FCI^2B)9bA{2gMvbvokR7> zi>v$iZm`K7{s|ehzdRwZ)ytRLRFO~X0`>W8TN+V^{Fa?0mq_@@akUT@U-3C8ALwb< z0t-A~5%{gdan^)mz}(;#nLe}JQZzal#_622Ns}gVcVmKfq~?{!HD#ZC5c4_=vVFqYeQ!p;oc!Fpnn7UGfGZkomjaFJJp%PSGj)HtUlei?UPiUX$pPFZuQih{KrmMtfRW4#x)~-%UG) z&k{w<9YM+HZjxbhkX>bZIC5t1@mben)s}AWUYp^K{LmCVEpmf zIPvIBTX(-ec!hyg{w;v`%T^mRzG{t8P&|X0VClm$%pC_J5I^xt0D1i0LyR#|8^>+y zf}J4W;TMOV$(TFDs$Ac^8j5fjD^l@ri^+m%W`I^BvNWx)K&wc8S}zKG{%P`Laqxl2 z4XP)C{K~+$1uc}%AMb~E??|B`G_}UFZwesQb1BH-69hGYk2L!-bo7J^D0FYbsnanU zTO6INd(s7q)pkUF`5nHTe;mraMY~+)+wY@NeERnt^0#Su!*A0{#BbB8bJHrwbTxjM zfRXU-gnPgXiJh8mK|lIGK!L*#hpP>Tt2sga|I!M&1O#!CG9Tyjr7L+g!G(n{NY)Y0PveN9m)ZokrufOd%o(!f3s1 zOE?MHZ8Mw^?M=4ZOavb=mr!AWZ$WvFuVl1>--@ljn+H9|gKAp+lHJX}{V5D00QyeR zTAQ(&B=;zWHul1+yF!aR=9>>-wm>K`ha`rnW|$)O=W^taxjVIs~QL&|mbtFPI8i)0+mH>*VKe zB}&w_^5d*=g|E!@*5Y8TTp%tMohG@05;1Z^X4qp|n9Hu01+yci<>g}P^a_s~Jq=($ zNLD26CE>7Vg6fRTvlXmJTX2Axz$TuC4q$Nnh(}*GH)7no_i1dLHAjk4R@tQV%le1V zp`fQaw2HcHbj+M#vULPS^mU7uzv<=vJ9^WPJUy3#B>$EA;Hm0Z2vpeR9V7n!u%!$5 zy32@dxlDdSW*A!K%<3!_diRtt0r9jMBzgJmnW4+4@Pm5x{8Jg5OG^!hCQ}Q4l)| zSZa_MM=AHp071*%`%D#c)()|;F#f^K0M_q+d6EQ5TN=7>lP7RnyUz zqf2oB@hCan->1x1aBErD(K&uFKpMZ6X2Fi;YA}%q&5btP2g0xmNGwW$+%jka(RiJr z+=lw_MVP-t*)u;P?O$GiiO#)=2dWItjd**_YM;Gt?cU1*KLBePrtMAMmk~t0sw+OP zxBRNGZx_Q}$^9#UbG($b%vAOtj&YYDJRGQ8HRxsjUp(W50bXR>C-Paiu8&ZjNllUK zQcrmJHv~yu1paBBhJtduO!CFz0!i2>kY^U?^5{6*ed{0G3lTq+$)->8S zxVv$-B14`jYGXn4EaQ$pFv@zz$r$4Hq)ow3?stPPMvhZBn(c&g#vB3`BLVOmHVWC*=eposNZ*gBdDub**0++ zvrXWEh=;$tW+|1m=chv1qHyEfPP3VukAGHvp;EXS6rALSWz8SmHkWQGGr8G+zPmfc z`SL`J60?5pkGMkn403IU?C@@Nc)bD3P&kcKc564kIVfvUQfGps$P;?mw{uyt_%_57 zw7@`k!_e@DOC=S1?<>2OqQ_%0ca`BK@&$JAxOLcOdh^={r`aGwqoa)Vtq%u(>leBr z4+5GfO}1Jmh)Nk_EmgKM5B%7aPY*ot*_vY?KwO-`7z~n;0loG+-7&Ch30Ry4T2i#P zP}mDW*At4$S+fMRT}+0ewk}@o4De!HLD=of%I$~kbHY(AHUpCONtd}Vq#!-Z!QH&F zL)Si&4qcw61YBU6AZ` zmbRqb#K)xUYiY60x2L=9_KK8=5NA_?RA1UZCYkCh5!eK1wO)NFtbFh~G2Q=McHnzu zx_tKg$r8B%+S&l$mVVUsd2?^uZsFZRR7Qqr@05%5a9vtc%@&=nf`nJSR0!G$@_oJ0 zwI@t*rW+U9kJMJxI}!u@-8pyiI@xGvX6=xt$m219{&Cq23qv<>F*rn;t{H0hv4~zk ztquZ~K)C}s2S(^{dzNZ7&!4XT;$8+`R?KCCkgXZk;X^OiN^Q)EJlZL3U z*~e6fsNy5|FZ3F!St{hOYL%YhOs1FQ6L@tkt#6m_t+RJ_gi^7_cgZENus-vOgd~x8 zD*7l5)GDlS3-h^p6=UX^|9bGVyr5a7jAfW+?tz z+e1#Lt$M2vsA8rAYwOe`|EA~swF|xonELSLAtLh|c@cA<4y_Pg3x#4Vy9g1L3^6|j z<|jVc&5t672D^R%3`s|kl)udqaq>K<<)WtU?sdg!LBAy$2~dC3>p?oY3|F-*5t@4upyO*#^@G1%|n6$pKdP7JGUTOX_4Vc^lc&OG%em;L%gX@&7m@; zWg#+DU(ly1#h7Jq!fVkZp%WY4O73>5;H1v2ijd@)AZP3b#Scmm_io2$ffEMBoIenN zdUu$}3IjoaL~x={DES-D8^w}{XthPYTPHP!MkumH9j_k02Jx)hg-25WY<($C=7{11 zp-Jh?3}MhVVDIhI-eGV+d^B{LVct525JSwy_KUt({xv? zdpPT4MbptR2A%4yRM*GR%V&+FrahhC6t8ho7ds`K_|v$qRj*|JJ-ONS`peM0?>}ljQlV38#s#6FubI;0#X?wkb6(4f%VbqN zUJFu1)YPScE9Mib0*xpL+k}Ufv0OlunvHw<~()0TTx?OoF&gm#1dyEnwY`>3kvZUBbT$@vto)ALP-*p`HHW~}KqlOnYal1!S(7rOQC8meOzo5$(*GHatKW7l(H zzCO3hLNoc*7$~4q{fuN-S@!1mS9O=2j?#(@<#xl`LL z%6eoT&*JV4bDCSm2>?1fm+Ea4Yu5s-51J%-bU6%eTy00<3zH86W25{kQ$U0`)aV~~ zG?Nk6;#!QHgpX8zFx<86i!>t>fRJ2TMQVG+f@$__UW#kHoBKP5==hdPh>k$PS5Mlm ztNdL*uW!VG0|ze7hqK4Dw-h_UD9OS^G>Ypu#~J*?i62Z<$ey>jIpcr3dgPYY*ClZu zzbl)t1h=Eu&jptpYo_hrzPg*+V`#@5(J6MUNEWik|mweX3@A}r9_+YWQmZ_5wQ+;5WPCYW<> z0#>r0JzFy|w*3jau#J$--M3zPaGJRvu;g7Ap(xp!qnpcvL9PWn^Ab+&2+tFingVea zjzv#dJL?IfTU*YDrF9$R=H+mQs~hcVnts+4@iM#kPhiM-K+4z#jnGJyl4&NT?JTRp zP&>VCt$|J4?#1Io`p!3HK#327D^>D=(e&zYyOfGyABD6nckr=wOw*QT5;bTTwZfpD z1QxILT0a~t)JWI{wfaK{dm-9oc`Vshx!LCShtM&7&b0dC5(09-2?_ zZcopFlbk)fo_AjJY)=#_l`==EzYV~Z_2o(=@h8oFl4w(L%M}I9Ahl_Xf8$5Ax|a9D zh$dyZcB~00EVbBBo9T$^W9P`yqlP04vzxSMAmp@TCa|pihePt>1v14!bcS{rp?QgM zACC^Cr5fN|1+*t|xZcJVjd&2fmJKqFwzxTECV&ohk3Frq*0m9nhrsSagw-~bw==PS z_c49Ja6iw_}^NwDSMKT>Q6dnJ0~y-2GSL)bwpAwp;B3mjy0-L&h4T8e}k63FE_Eu zmR`HCTPYSoyrbUeBsA|xLPO0gNqjL#V3<;_&FCFMtui5F{Q-DLx~FQkri8{z9E1B5 zuy^x6%N}F&{2cj1e}8&^t2l@nh=J7a2P)8f_S3hFX~7l~vPlVgKiQk+FGAo{+DQt` z75GKv3~^Uugk~8Mram0T`YH_!D`2HlzJzVH;bvUUSl6c!12t9L)3RthS_Yoa3act`%H z*jeci1d}rNoVm8%jYKKn^tBzU|XtO`6;lV^$2N^ zMC_*>c1(j>t<9??>z(_QmfKRsgQ*HeEyLU;VanpXcf7@QA0>_X0$Ot{vabnmm6IOa z7b8K%X}m1d?NF&SE-x~ysf|f7R%ot^;~x3~S+gYw^_F_Re6k=(h5f-hL_CL>`-X$f zohYjqV4b3j85^(;EwB}~3`GB1U*;Xr`pVvC`G=h$?%}jQPV$xtT?bWB1j;^*psL+*aWtv zD-~$pj(xp2ZEX}w|B+ht22=hy%mbEyd&@Bc{cgeGk*A<7l3GvBcfa73l+>yFj~_gq z`_?SDhUH@(mflhaxRD*JL(ls_Sj%2vVssNpv-UNMswHjQ$tbzL=#fOgqb-^b7}Sqi zmM55^s8|TJQ#NN77h+O;bh$2##2aGMewW;s6T+xJQ~@wtAVEfz^YdLDQ|79 zyCy2~GPPc;Z`-7I5$;n7c;834C4K7)1T7Hsn>PdOdC^5 zi~Hncr}NpX9j(@K_Dl_ZSxL;oTl2A8 z(Jf*V!n^u@cc2eyAsmMt@sJYw*^hpW4Z7tm)&5#e`)t4c#mazp^ z_406|l?(=XZ^_MAh^)CPUFGKInN3v%B=nhb2FLB&?lRk%!~}Xcrf%g-@2C zfY1;iz%IFCav+wS2pZDE& zcJ};r&t#IBWbT~%T%U8D^A%owfWc2`+?TFQRu+b?mapJ-7M}_l=Cj@5Yu;l!V%>XZ zHM?Y#3=}kf*Li2=1XB?GytNIdgZEi?Eo) z&n$Pv61@KNR+PlP5pT!G5G3C!O1Kp?%k(91pa&V)>Z zF6y|UbI_ydat>dA*O_kR>`0Nal<$Bl5(8?kH6%n z?CnR=G!^V1ff+_?xN@qirASTLzTNH1Tt@PueJkQbVo^vz<;mw3Yy zb<09ryslN*S%5S4m=A*Kx|@2~<3V`a0uV$a@dyUF7Mj#2itW9K;*W!58X2WzaJXvw zr2NQzH$yWUJ@WC7U*W|V-bPZ&X+mgyJ61hk(JL^cyKW2)$ElD8T{+wtuN8c!DLRvm4)*W(lI72pb%TK4`2_3 z5wqDcL)k#_xgfw{G@K>u4KI~+G@((F9h-_B-vRAjTa5MjXSo7b8y%>Qf0&VmFYi?C zqz5>X2z9~htz9fvNeOilB&=}J&dn7h?qZt zt5$_YQ@*{MM(HeovKP?bJ(<)<$`j6OkvHL5TB?@wUSL`^N*^vwU`3N!xS)yVq&7+w zT!u`8Oc+4U&EieiVO-2*q(E$x$Q0&wWCi(UN|9lKax69mY*Ce3Zw1t{g7uT)-C0;%oS_ z5UZ?bJZR&xk+_MYmeu@0_ggT%L$ zwZ`b$^&cK+hUg@R9Qb7(8I-t`vFsH1)1QY4WJMR@yVKdzT11dGgC|9uaY3xi2hvij z9&ENQ@9Y=^N&yp_hfw9l)sl7aV32l&inyzSfubih1Q)DVY_%c);B~B<9?mU@<|WfA z>vb&u&`lWBrb(#f6v&JpXV|Pi4DSnZwZhW2KWWA_jduGR(YlU|xHXf~^WEY$M@>sP@ zgVujQp8@A82X)1@*OPvL6QS7w0DSC78uos>^)(X`0*@Nmv@0-OQ9;kGKC*BThjM`$ z9V}`jG~XZ;wwvBL_hvkw^i3>NBbtkU#Jq|X28K0~YmIrm;^ zKp!UPj&HS-Q^Tlg0O1iQdBtBw0iuS;u3~*qU zCtn8MA%9bY@|cSm%49U!@WYR(7Y3%}(sy#Tp1^y=WLQ7U{cTR`*_Qz@I%PdZbrXmg zhiON=-cbkl?DXv_WDEVD2`O$@ZT!3PL+c+uwRbh8iWdji-<@bBSt*o>xlCk>8tjky35PDX9A}Uj9bEkUQC;=?b*J z=y#*D4SHf6j`{3;6XS+bE@X7Xt=q&U_LxJcwa!9@gmbijnP2sW1*o z0_OaN*9;4x8gFvwFr1UZ;m>tL^37jQw$ng_5ASKh-D_@x;HesDAr)bMeVv$Rk=mtw(gL|70~6j8%D zpVAi$iZEASq}X~+Med+)V7f%j5H5eZ#-c+y>y)~JgKJmgKZ2!5+5{&;k4!F%p^|JW zOq^D+9ct>WFDEmF^{=q5segfuc-e4~JOsCY3VYT)j_h>kpTalZCyKib^b^MqzrsPw%smKsiK^>V0#BgW(^JJ*C{JPVx1AMEm#(%hAv(`YEm|Xn%$v)^YGFFKpZiBAGy3rE}r0L5(5>0LT z6Ey_8=8t78u}+T>dA$wQ0&y7ZsW*p_z8eM}@D1HGnZhGmZ(rKm)BL%o-1j5@T~!)H zMw+i&C%g$>OEB-5B3rUGLgSMHooh>{*XNHJB79s{88}algchA*KL2xij~#sM^@)Em zwaa2M=Jpj#@Kn5eyiBi!myj1h3=QITYo965@-csZQ!O-kykk_FCR3oCrqd%YO@L*=<;91;%a7GecDeS^AsAA z#4ONI!bS{N!1CVmH4&lCfG0(Msm5#qC=Vy{tx<|I=j-7eU+iZlJbI4!CE4Hmf8&~b z>_g$Hu_1IrAmJnQ16ImVIMjy99t78PX(a}}*2YzpW8CwPkNO~{ba-pY9MT~k8h2qc z63=YqW*Jj?Rdx5CLul48dCPw17pJ3b()t{~?%tNeE3qvDssxc{Ny8(xHg(Q_{4~e^ zCYDM}^gapJ={9hLYKGuD0-0Ur;Ng&%W^NRVYFzq!syV>d${G}F5`<2QW9$ijJpg00 z^B+Q>*cNUUbqO!TBTS zrao(MP;EXv8q^Y^8m+O`2RNdf^ETbH!cRKjki`fsvR;9Tf$xGoHQXkU8}|4qM{%vI zUt-gJ7nvdt;p2^Vl2?%vq#+F>)8^|7)<+CyO5JW2`s*HuCe}7*W0kL zR%zX|*4yyws?sF1%p{gbw{Aq~@S<8tsKfLB3ICwl)0W3!=e~u%Qw zZ#X}ibl&AT_do7Dxn9iZ`4M$Lncf@U&%O(!dfHj&#Hrh<>1h9-Lj3W(UR>W_m$0!Q zEkIYy{-MTK_l`hx#ox4Q;q#Y;P2;ZD+;t{7L^TT?a=-q}&;2JZNH?#yB~DYW2T$(A zh)40RB_8L6)=h72>%MnQJo?;sIG;QT6;)ML9U9Dtu#LS?qa~s+qORUignzM&Ra6n)tRh_j!(R2L_{sExPG3v6)J zABz!bVR#q>xcGxfY*~jk1UL1RNmgeU+vLuu8jHHovPASo?8Px`fYFFBtZ2i$|Jw_I z!JwiutyfBV%%Za0p3}idat?(|LZC*q^xnnP?Zl{v`mBEfmot(NZNgc~@2k$mMp%ES zyCi*aqmvZE2pau`&H2I!uW!s}VLvway^`uwYWb47k)N`CaGO*X3u?_$Dh63?4jl|>DCc)4byC;r^TvB3URJhD z5Q7&gEl$;bhYm)5IvPB9x41sPLWN!iaL7|h9r+{bCjk20K@`kaip&-1qgvN060;Lb zFTyV+YgElulT?tAMF-S=%-Z*^r*ZwHkK8r>r7GATc9*e2o;E(MkDT9v3T;4#7hLJ5 z+ZBLk>1_(*?JTlRz^>)z@4T(^?7~&d??{;<98gUM? zsm^R&9*1dVb!2oz7v;RvkCxz^nq}wx&CiOB{C#8P|E7Hn`pPfL;}x@PtTl)GB02vW zSb;TdNG5$x@7FuZL)&ilwis6nocR_pV5!W64!w6-ODV+*2jjLD&Z()if8^6_;(YYM zQ?vI<7&$&o6!!C}ukW)V?QS+J;;TinmGX}Ep#rG8$_DcX)(_Io=v7yI@CO zP8(7JEo_xo$~0vhV=8jnetnFs{ZC|QN|gRLwdAV^;(AjWw%kQtaMg4&aPokx8+f`2 z{J_}tApG?jE#MZboBZUquO}h!zNr6FD^O_lX77o&dn;Dr1un_SopU$d({9THPr&Yi zssePtz30euDDXUGEt-2>BGUQOO2*dI)dO3={?#6O%k^R4i=LB)Ks3`+yg<4qgwX=$ z*K4e`TSC8yi2|3~w6*ZS+h4Q??vI@Jzvvze{{-Gj^qO8Tsr4`TA7-p;-6#q6Jg2Ct zLm;GzVxl#J@s)`o<+_v&OU2?C3c`n0HJ>oGN!KGzaSt#Ai{2Ww)9|@LX{HrFqtGe0 z5R{+m_dCos2zO79!xu1dv=pz3sJ4R`=G2msCXxyc^7mzyebVcfkCS-SR5bkV&?v0r z3iTU+)XfO|>W%4I-W%`)$aOfW{O(9bKqNoC0W2NEj@K49r%oT%3*P?dk{SAWlOiP8^>#e&L8zA)!Bkk5W_67{CwO1eE{Hmi_KYfccv~;d0?uu-LL0O=!<6TZb+p z>nZPCPz-Zw$ktbjtps+fW;<^{T8aLTK}^~V1=uK{-|7eKY90ElB3_%UrQOL=ceu`a zyROYs-YD213>+FwAu(AI<&YCQgLVOa<#Kit)^|V1tVPLq{5b=7ad1Yc6ret!7Z$R z0pFe%WHEyQ#jz*~;IxZc>)_jqhO)M4?=qQ)EL(Mc6Cv9O&*0-dslwZ?8#}xc#_F6= zfo~v;;fUsF;2#zh$69+MoZy^(w7xU%nz&@Iw^|HpXU2vWy#Xl%`d1$rYl-m2ulgNE zX8%2Z!%rO~ztxX>0KBfCbOO0K)-Oy$(5fl^?|{fiH8n(ce zzb>yCNe~i+henO1$p^Fur`7`L5YjA-jf>aq+*;FP2ucg!DAHyIbAH;pFfZ#0-zBqs*fow!=@D7y>iM$~rI{ez3u0?%_@T zWU#9TVuJM5&-5>S0tOfgG#J%}>r>&-{H7m@!OcFCa*3i&dzV9tYPc1lH^E(k0qb89 z*IS_6tIjMse4whKAxoj`N|%(lBTmxi8!1hzZ>P2%QMaS@vq}2pXBnXk{7xzTLGY{z zV8#4GpNi2$*=6nz6*Pov!l2KEVm!Y$`wRYfZ|=*Cmq*X-%nFSiA2mmf3X)a1TUr?B zBmaO^#I|V8rhOn1TKp14#YX58B zF8jIh{|f7ki5JZ`StFyBwDiEsEz+;I8b zyz9Z$ds^@5Z}Hom*yQ&6MI;?K^b}-zw;)bX+|lLV=ju}c?b>aR zA6LLZorYs~kbdTgq|XXvcsThc-a< z%o?ZOyRt_1Ns7zwJ z*}}`Izx4tzbreiEQlORfj-Ysa!OBEA?VE;+*J{VRzBqP0>-fn+5M(EqH&lmF+i}5x zBTE>(ml+dGFw7!aRPBuge8F`^W2dB_H4%U2CZ|WEyPZzVa3QZ$&ufWYLjHLi&{D+u zMT*F7mR25Xf+RF~5iU(tr(0*oMmy?Ff=aN2-=;4gxia&nehseOkm5Q{o9;#vx$FIH&vFs=vU~Ov={WftkI{Lu*|ss zCJ4YtHI_=o??o6pYBe#vd&KIhF{Vt9`OH@}*4W7_=0D)bAvoz6sAw^)0VTao+8%i_ z7Ce|ta%B-3IEIw5u1gik*{I);ccVu^KJ{i5EHuRRZ^=XDKCH!FIMSJA?Q4&-dgbjM|)@n1_m`Ux21!P)ICn_8+BlEh_rb;@=}&=c46>THdByLi2N0YArG zpI69H$*^!nn^8c2U_KvZBWp~TK8?Vx!9aZOZi&nA6hBEToi|jZ9Tm-XWVxJcJ69yS z^nNrcD>R^U^~xM!BGU@_IET-|Ls&_5;#b&q14Y{%myD=;`1sw{_Hfci&9i4Q-uswM zE8{p`sjNc>_vh4P?y3rI$GD_SdB=>@Aya8**TDWIcLd`iJ3{rDfWmjz?h@Rpb5s4%QB&om5)?klN&UF7wm3iQ|E@dTRD?wTdqO3MJVsov3d;#;5RZvRQY`h?5I6@b7^`;xf$ka5X8str?5%+?{$WSZeNZK@t zrHY{X)Wt{7?3KNr;u9%xAgi*nYd#1i#z~LlgWdSjN-3XcK-` z^W9VM!39{aZfLY>VOP3pVZUFmZce^-p~~ui5n?gkC#Fxhezyrgrcbd$XKy!%y6)uv zS_foc{+!rwzMte?_X@mQ>+88)sq01Y`*-rhcfHGf&2e8^aBbXrWCbtQ+Hi;opo}X7e(|$5^%oq$P}<| z9YD2UdgarK+Y@XWcmglDiRbQ>xchbV@|fT3$zUPspkU~E)B6*{W0%(xO83E8HwE{x zI8ETXefO)ihw>img8N&~ivP2eD^9GBR}g^U7IBZyo2heV!(HR6{68y&V;_o5N%|?v zFeoZuKO<6%0$26c7MjruW>V7l@a&h+fm<&Nj$kNLoXTvia^OgPh$PFJHe0GE1w0sA zJQsDSO(P8oky)i`l97rf7Z4<-k9C)8EqBM&j_0bL%63z6e9v5mQCTn>{-Yl(1t-%v zkPhM+XsgmdSCIMZDo*?&D%AX)EyK_?u}h}oZ~ORwTn|S)dF3>=3|q6bdFJppx37B5 zj2YkT?2EpCAkqAOEvM*S1y=79o^ql%j26`aO4l@J@5>}OXDDy6Po{frGs1>Jv1z2K z41(dcXX#j!>YD2h3GOm`uJtmK)Qt!y>L?KpLyo4UA?3kJ*F;ThQLfbPEeD8<6@4>7 z%&^nECB!5TonEGh+cwKKpy^WBsZJJU-W#EzRGwdMyXe#Q+F6(tv!dav5k?>qT;ty#^6sK;6-Lc_ z883rBQTBp|^zAzG_y?I+^YQOv1+j= z?JfXGu6)t;8ilMdD=JdBhM+!1EZ*!Zy_D{^9O6Wqb7qv;HCJ`BZsOOn-GQYNiuA1M zt)!y|4>fo$rFjeTp|%zFag^Upy44g=hj^VeA&c-BoA7S+JG(V0c&i?Eg5FB7$vZAW z1rlav;shtvR*r$T=jsg~$7|>x6w)fT-3CkT{m5tDGk$h;P#}B9{6d?#uPBk5y^YKA8%=q|7Q)(-8Tqa{|5sy_K1(ZSt*o)o zPFGTQ3#+1po~BKWKcuQvJsl_6v&J21i`>CJ@|1D2oB9FV-rv%}o7booXTi`bjz?u* zzSWhQykbHCG;eCnbY1JSs+TV1ku)IAQVbyT)TUr@(Zh)aZDXoTDn30!wA|lOl=1c_ zxmlWs%&X4Sd6InrWRstBOdK^;RE*&lm+0qeQ!$D}%J#Oqf@!Gx502g)0VcEAkE?H6 z-_}PQO(xU`8#hSfX)Q6}>)=RnYAcs4PN(#}P4#heX$OHgsMWLQRaBjjZ z7R5?~Wi}=@a$h9&!lM_@0^La9!lFPm+FxmW{kcobjNuUN@Q#);hJq|tnq4s|OT3KY z3nho9GTD3I`kV^qGpKus0jLVQuO5gXW%h}tsv+^tCrrFrA%QeYd%?sA$;h*L2&umT z4!|(7qg}W(8f&`~HIt06=#}{9C0HvCY`+VvaT_r1LS_X!QuDAXB2W*rqu*YmaACZf z#6!Ap)V?}IlTy}RJK~3$GKie0Vn+J(b z4Nq^su3sK!u8=m^y1m;8y^1}023>7A8`3tXd4|w;P5K=jDYhCh;)xqdxU&8YTr?l6 zo$GxBNH1@&DA(ar_eAu0RNT!olBcx|o@5f#Fcd5vvX|>QCr3Ov4hq8gySzenM&JnO zpUIGoMgZ@e#Y;Vdx1u?$m8e!G98~83`>8^dpwwZDZ-B_w7*Um~D+C~xq$pc{d3lSW zE>7g_x2#IpYgZ(2^BkRkRSJ9AzQiWN2zv>df30oTtS+-Bhv$G<&pUx>w_t0FN!#b{XL+Os5q?cN{0SLa#VLE=eKPeSwwgmO znVJSa2;Yi+hjr8LYp3v7QOxcK!xsOY}f%46HU4ZMZl5!|uBXlA@vJ zPDjwmxokO-f}K-oz{B5x12J@$G|<#IRp8M#}aN98{DyzAt}xX6f@4FX_mXlZ_Ma>P>xH${pV~Xc1)F zy-DmDMG2~>sFiDFl(>^>Q-vqpW@}0*zX{#Eed=W4;lbo>L@i{UNS;?-7;_yL5D}VQ z1buBd5%;`zqY=v`8uxD5?m)X)f_(^L(XwQ47n9CE)A4KSQyNJkC5HZTU%2BAWvg2d zne|@@_r9#wmxtgXKkK=34Jqs`SRK0G9eVnGH@-9yQ}q`1@0`>XH(5SCEi{RBzwqts z^mP<(^o(IJoe=IB5FR?n`~~$ExK&*sQje2zYs)v9Z$gcz1de_;~l%{p6af z^DM!irF(zk0eC;`{NUs_xRM`g{CczCzD^?UD&Swnrm6SgQ{2<-5ZzY6t$)wU0$1mO zu9i-!48v{H#L&afcG;;jJ+zLxFd6k3-i(kCvIve@Ka5^W5J)omJ`o zW!X0Md@FiO7f2lVdrzDo@ZRY0jd*y^x%~gqAz1bHc(5Ukzb2&_Fj8-C=nK%UP=TxU$1h%*yIe@aDKA&+Y)-feN8R-AwVQxV&R^r`-*56 zyO#UL>yh{I&MQDHU}&ZGZ#tH9-%8JR?BBM743pdDKe(p%1Z!bW+iIQYJv))Kvnx*= zj~i=uBI|*78uxb+_czzm&i~g>zaaH?D@ul!Fd6#A%BX0V?X);CB}kdJ-80yR#ZZw! zwBVEcu7)b$SE<#Z$ zW-*+CekcQxb4<*2PtB3Kom{~Mz@XKe_JpR_D50!pA6uwS%RaqB$r8Ds z;a*+8OdK)e!jRg)*L)KZ6&Zdj$la|$)<=)Q$U6b0bxOFQZa8%jCuO$NPA*cXQUY_t z*Y-p5P$U(i0l}G4wn|0A-Ko5B6`BLD*Er*F0i;q6pfCu~m@Ik2O5NN06T|IGO-2kL zuon=@R`Py_5$x>xNwb<&J{%2e`=Tm!KvO{@w_Yw^84c6~o)$=hxDYW4Yve-h&Z_|v zj1P&VAHxCOpK{GR8F6!)2-R@K66s&oG&(Q|1KI1pB|WBY0?wl%7sBVsrD#S0r`t|Q zcT8dGf6tH(hXWMT97nR~?A8I^dw%8^zp&=9zJyO{IGWsBMnm3OJrgQh;;Qiokv>TaBJ1?6}$Ho7{Tp33S`%f9f ze(V!VVsx(Ocu4&>=kzwJm4K&hCpqjSh0;)6ev_FuNy(r0l>WwbR+eC7;Ll_Z89WPY zu2NA6ovf;@!ss%qTzNQW_Ox&UIW3`~;&Mxz{rMR69NU+9PQvV=ut81_734~`jwT9R zBdmoesUk9WN9^12mY=N98NGb&g8mu6Xx2rU)9K~#)JmG~FaQf+Z?9D(TZvF^bhv|s zC|VW(nG~8C_Oc)*TUo3?d$KBLWGK5Z}Vbvf1Tap&oD>NgMLa{^y?dSu=!ju;8w3>Q-D`?M$+bPPOMbhnpC5iPLra z)|lk^{xa$EJ<5;weO1uyt5T4^I5(%`JMn4tjDGD}OX5Pyd+6QjDK-C>|I(oUJq~RT zh63-0PQy*F!|QI(Om8^Xl%@h5UYP@5NJWwLh0hZ1HziLRYLXdpXe3F-|JuxL0e4T1 zX}Xb%;ckbX`TB6W&l(9}4`hDjjC=&KDD?e)4J`Gmh;#V60iWutAqrN;W7TlJ2-qrQ zmHNw1!-IGOp~y++{LWkI(2Q>P$Eu|L`7K{XuM_R{2#dtA90RHuXcXB|`--Z1 zNQ!wsSnXs60&RH(`b}-m_LVGjVcc8}p0o*I-UC!11-@6yePXj~NT%g#jM6z29aMt! zDbbobtvHDN;toSW3V$37at~Z!a6Yk$opGq3fIz6-IfZkHz`5U&dc!5Hc$i-Z!uWQw zE*_vLlL#etMNrx*)^*wv?451rMPIic*XD?M--gZpgdh2XZyVJx|M~W_7KtF{A&gND zg1hqi{CcG#sGRnAT!u=y5{x*E$Cnmn_?oSAd?e&OGslv!Ftt8)5p0Lq=)Lx+Nli}7PI%hu3^ISbzh zWnsC~A^_EzhjT((bvR}Iw(oOQpGcdr<9`>27@wMaO(MngGHRVRM-isSz@ir0Z|-z5 z8c}QlEnZ#8*hXvaaZ`3FKa z@7<5x-UYj>K8THBt}gh?OWH@PfYO+GTHQ`owvxviO1VOlz1=~HZU`55u!cuPLbP&9 zC@G++Y_FuFlW0Xh%aX>)+v{ zbZxOUqEKM*2OL4g zid>9zIH>ZUGo1c;E>7cF1yXfU)%ZN84*?d`XNAFj6nq%U)+@*)UK-FjvCeZ&YT=c) zS@8elNYS{{Mx$3|a_fYmTa>U+KRl>Cx@e&NNx);ySA?#2a_sMTn~ri&^&o1>i0<~E zT@f!~YwKN}=k8JsDU|#zjoxm9ap=JERq^|@6Cq$<>qi2_azLL!v^rOr+?ME(4v6Jv z$715|H2S0wp0aO(#<5AY0yxYfLN)M|bN{!yZ8|FPA@0jc2T${RT-NZSX?G5RP%~|x zu+%jnI_FcE#9yw?)abC!asRg$p!*+t&p+m;$GHkRk^k@fBeGQU-_y*0T_2JU>R|?H z#LDR^W>M>mJFULJmoE0rqmbXudysn>?#O4yK#t0ag&5a<347Oj*&xhVV=gPM2;9)d zR>&gjACV!El3`0Fru+BVOYBd2Zi)e}88Q3xk0a1z@I@i{b_}ZkP2`%NM~1{83J`D5 zM*X=Ni9P`JXUrtPU9s)eCVY5yxs%Tzp|sE_nP9Ewrj#^$^q`1{-|I%EEuy`pYZoJI zg}GELi^}wQTrFV-LGkrluAB_0a-t?N&e7_}H+;Ppu6-fiEALe}U_>2c z7ye$Ua<unEXe(@>tb*;Sql#=xFLlIr0gGCq8>vH%(VZMH^IVHINvy3q8^@el@99 z{GFdHdu322@^L{P9oC>hI9%5MCDW#4`?+cGy*|;c(^)QDW0W`YY|lw80`9f+W?DJt zin~lVvS0H!V`YMhkvb)vmRlTHR?bWVvwKHn-^hj(j*n%OR*s5$EkH=^+}$$t@yE$S z+|`5(5)vKk{@!XLGbjhjmK!&|8*dk5NClSIxvAoF&m$(WYoZ8SU&OaGAvgTsq{sIS zO;VCi5J0)Em&#U11(F(;>$3~vbF$7iP{je?LWm*Qn9=7EKn5u<$71!k%x-8snccW*l1kdLXCGAG8=ic(sU@>O{)o|mN zwyA$heQ78Sq)gtrxx1U*wWp28tRM5CV|-0My=FC>I=W2J!BE19fPn}n)<&&{t9~gk zRT%Mw;sx{8xO_4mzHX+{7Bo*2FPXIon8(828%d?q`mRDxYDj73&s1EJOnWC~xDrqO zY&g!1ss9Vc;-wtKb`U}r9Ms>JDh3PF13YIxmsSX-mfPg z{JY*&IGbump~J5+=%e~*xhBj>tMplIM}o#T-`GJOACg=zFrXk11Cn%+yZiavKK+>+ z7wWzg_Fu;GdBc%rFCK)Me{leEURqarsgNH0cI*1vqEzhI1Tg|&;cDt6ALlx}P(X>d zCkA)K{3~~`xfqXru<6pBl`Qqm3@!vI*lcAxYrgD=r$aA(9B_MppeQLcMj92^Yj?pk zAq?-^i4*;L>qSQ&>Ol@k$4Ejfwn>f6IPOx&L?x`FUFPSD$QWo2^>g0M zX}@+a*DaF_u!>2MGUGa9M9eCufO2l;J)+@s?JHbo$0@?goonJ@`s-XMSB8Yz* zMfA(J>o~Xv8 zSg+iqMX%1JqrBK;sJzZ(CLzz)(bVLB>LdIwgn#Y==UM9hT_K8<;JxtukB0RgHjSMua;5sb~SK&ja@3J_!m}FT=+&?*3gL%gE52@adGs z_lv~Li6r>A%2XyL!_?c-X9|g-j3VKgtgFgygf&=|pQMWa;q=kV#(H%9R2_(XmVx3j zMa#e?C{ekFxnTb0oFBG~DAY_rbMoHLO=wG>)iTyq5{)ELu=u;v*g~fm7Z@3_t5jAc zK%JM0=Cva-f5XS{OHRr77%`n5B`@^0-4tGWoNNA$z}x+^!z+r&L#cs(^lwTjjsyuq z4lMn_u^XxE-zEk>_U`CzY44`tk+j1Vqi{6&eJ3l(HLwm1D-M0s(e6|jkz(z6w%zaO zqBzK)0|DWX!BsdX|X{5>i-15f1mfz-4L=wXovkl}A zE%;a+u;Nl2Q^#)qWW`OKmZv2S0|pzB^RRq^_;RU2EmF!3KWE^J?U>g#{)OFis+hVj zmg`d2Ws)0^j1kSca6B?25!S3?3xn8=>WSBTOELdgP?&CiI&i@2EpuOn5%WKn;JRc( zofM9?WL| z@I(O|aXQGpu*ju%QJv`K$1+^WaqTT+u4bR`tFh^+kQr+4P!27#R$v~~4Y90IeC#m3 z(?1xQ>~0AIJkz&q5Uw`o>^B_`+Zvk0VnO>{n@4vg(2LP`&%?7E!Jzj7Kbq_<3_e_1 zA*jHUP;Kdz9Iu?DyL_N;p~Mv@r8V8{BX3^ zqJvw=&Xy0{?j2v#*LjYRK*?GExZoCXh5-do<=A3Ft1sRAEm|#>RJ1~c*$hpgjxNCi zfxG?L!z+*3!|U@o``dc0x+D8ylf4C9y1I+w|A~M74-}@C8XJ^;VP=?Odvy8>PRuZP z5>A|?8JpVp+Jl+{R%Dv!SpInctvRY;>jKoHwwtM~v(*b`)EbA@g zth6@wew?gh)*#`}Lk=9wy2VPJu zl<{ZZMLu{m>05^7G2C#o%tAk3nNM!caMs2ENmWb4mkt#@rB7~y(vsD33C<$rh2%5s z!eIE7nG=m zKUhOaH|~r*7$sr)`Q{*|pJ`2?xFtWM@iMQs(y)MRPUEk$Ud%73){al!8q*P6 z0CU!nj13E)mTYa4(&l*Hmi9VP^VsPwi%wmG>DG<;6xo?w4e))Xum=G9H_41iRX6NX zIPt&AUZXy5o);+dxyBwF+{x6{_z?;Em=QaLhW{c5;JB= zGLMpMUEDP5Pu^n>Vzg5o@)>9aN-2QHA}(Lhz08``{Bc%IUB)o?`rKE577xkF`*9Xm zA!$A{fy9ww$J(RDT+n}^LN9@gimGer$Lw=w=`Tgc^OWJKchX2zz}lCxU-#YEuwPj> z-N?M06~-*OE~2GtJ%aAfgWn=E|8@QF;x;KVMSYWQgtMAY4`~))!YJSK6dX?XBsmjT zV)>o9Z}7(F@e^-uMpqeym^r!8IAA=l6!D`>Bp_*i@FU-QAb~2$4!&U;$fYXKcIrQs zNz-$B`A=8x|9#;vwO`B(_v<8uh?C6P|8Me7*J@pl_%dk!f0u)1trBIJ+q%V?ZK_gv zqf0u|p+$?Dl2X`mGPM|TVPqZKnVNF5B=NCQa+{rl^k`Yy4cxAu?~bBUNfA=Kxb*A( z2~MaMY$I0cfJo~8Ic&!>D4*q*dj`i`Ob1*N!f;=m->}sdZ-Ei2H>4UZP&irI&?L5% z6t3|x%dPCM{v1YGf(StUD}m!9_oru*0*Ya^JZq{T3V^)4o50Y#{x!E~H>anKKvIY_ z8;)u!tr}ArfH9SQFm4DtG6sOOur=8)du7ILUC2@jo@qR`jshEJBYVX#m z?{i{9`rsQDVp-?e7;)?B(WH{98x5f7)*HSLHR@^AL|>Z`d}zf^r`eh=m02JPdZr>z zAkc;bHs(L!R_cAt?!QB3UxhJr z(MRlKtwN(DnnLno)L()te!i4UI5&|}IkZRJ~(AlVFAxCEg^SLE*4DQSyQip!{DXZM`Bq_35t-@Pe!9HY%^TY zulEL!66ZwdE8qH@HKj++B?Q7k62+S81vXn2JH)GDO>{p{a^>megJU zux$nxv0D$PXJCRJZMbAdr=IUtaUPp0XVO{yTQc62NQ~BQsON!w?gq)ZrZoTYO6#GN zlHvFi#x~U1bX!)f3KR+TmHlp(-!*WYS`HvP`dZ_Qaa(dtL#>DNEb>ghW0V4$=@o zh(8FFg#j3peNLbpVoD2#Sm3t>FZR|o(I|JK?8!?xa4l6*7ntOYio+ZA?kKg2_Sj)4 zx=au*49z8ZtlBr=a_~|r>D0I?g51}rXu&SWU5xr@tmZOH`&N5_#OPuUtR}F*p=Bww zbBAgz+)Xj;&Jl6>z!E&=6)L(4uYFd)$bYl|50>+hxrPe6dP1OFOb{ku(94>Yjxo97 zw0`cxHmD*@tWWsDdivX#ylPz>tXPwm3z;8_q%1N)R}ViC$c|Xjn9yVJNa$rmJbo!}a_Fko;-iYo#3Zjc zVuC4I8JwEq;kF@ri(h?F4*lOWpeGWI)}4I&9Kt7eH3LBbe$RF@b9(h^)vo3%mEd|c zwF{b4Y%n8&7EAX;2+rx0?4GWozcZm3WhJMT%%JV8iuYerT7>Pen9P{>PGq?SfoWkKf-jZ9jath@B`m>83H$7<*$WMuN`1hfM2TvCwt zkry2rDYl!tHpEhe*+Ag)K#qS7^wHZb=P)3bvnd5H_-GPt@r=9j?3C?L0B5It!lcm z^wKqId&G1y+~{o6h0Q(O)zvC{Q5Ajl_NQzXI?h65I3mw|b@NnHFs#!>3u;KIWEDA0 zfX~czx*AXfx(Ren0CT3}GaQ;u;n4?SREDOK;(Tu8qxpB>`89^VmZW%2G6Us#5mp)f zL}YtJ!&D`JQ96tWr@i`FxyU};5StqtW#BuI+vlhVc$(A@uqrHJ>oBUykBlS^_ZC{* z=?L#}7P-s{cc;zM0LFwh(W=L(jj^&&18p=)R5ijL8k#7(A+9*`p+x7zdAAatPnS2CoH(7M1Wt5S*`n` zJVyF(V>4Cu7xllQ8I`9%5atJJ*d;0@P26W0rqw}7jnA=HE~@JH+Yb+6vENLw5zh!G zdnxjCUNuc+;EMa7$>0531uG>Ox)fS|s&%k#G6U3W=2>oH#r)}fH)f$K%1N=JnDYDZ z8837Bf2aNbep)h23`4C6Y;u~>F6QW zlV^U$#NUvk#6fObgPoVs;PA_<`8MbQ8w<3?<`J|FnDiX5_#kcgh4igSvC_)D6@FtR zns9q3Qk5ROyEK`N3rxacGay0=kF(d1L2Z>FIHSl`Q+JM=tsX$9E$cvuGC#~=79QmZtlyGvssiq}k@2r8YiHS91bLT@+Y&8|* zGbQg_i`E_g55B%TsL6QSmJ&MBL=3%&5-Ea!B=p`pN|PSx(uwq5f*7g@2%)G{=}kI< zKmdUNA_1jK2@tBGBl2?Iopa88@1D8;`sWZ*6$nrP2}GWPSyojZZD*2(WED9{jK%|dP2?$A z>=DrKZxB=Eu8W#-a-5qo1Q|{^WRpe3{!>c%^Toov_9k~pUhX+wuicTK2>i0&(~G`? z%?+cUj06cVLL!zqpy#QFNirZd>)A=ViM_;)XNeHjKxe&Ipvf+%UMpxfP=R?$P5evp zHe$j#y#F1r(ogZ#J7uBgn)+)M0~Vw4N-lb(yVDAY*e{=Q7LfFB%^uTjHu~}`h03~7 z@|JtPIu?tMA}iLjt-PB#rZm%hd*;(194*+fzkJZ68=+AE}=Fe*U;k zn6PUjxom;8qpTApsY0((+FrCQxe8-4#62z3zW|~3T53+Z6_Z&Fj0nbN1pdT7k&45U z{xH38G7Ct$la%=QR8*jGI4kjqsJ$q3t%X!Wp!X}%&Y9FsJ1zd_9nX?0ZEMd)<$j=M z0G}8+3dpKkMNsAYp16PRbA3Kw3fWcp(LXya;7;{gP7zw5p(4p-Y8~pj zhl9zmCNGu5bF9hb^D`zVJvrx9x7~Y^As8{i9qEh{=sv%rl#3++UwiibZBudhV+rEh zd|4(-d8;b0W#sF3ITGY3R@Qk0tj@`>PT@;?RCw@yglyHt2l1z$ABJi?v`&sC=#PeS zJ=n|3|)Qgrg@CFJopfthPZowUz32x5$7`;9-gymv%Tp61en)PH_( zbQD^x8Y*?P)DQ72ti&a_-vw`rlrR9v$)8}>i^!_6QyJLw(_rr3^^=1th%^<+Z$E#o zJvr(8`B{on5)kP;l$@?y`DszoeC$pR)3+r1VQ`te(N||ZA^t|bm`AHPqw?oUcQ?-| zgY5J+&`?XgwkLPmN9t;APs`MX8 z7UKSn7*|gs#rtOqvS|_JwMc)hzt@eY&K`biv&|b{Twiw#DmgnpsZhwD8h=kC-za*- zcLl5L@c0`2j8u3imPgPV9DD;zTVXou55MvoV& zA@bw1Rs3)k0Z91WkwdqZ>h{E2@cSULgm-rk%wRr_=9NcBgHF zb#+2WTk1EjQRc79%a`+Q5oc#fbDrw<)4X+6>TftNlSbansUu?q1_=zu9kP4a&z}Ck z5Pgr7#x++mq9u6_UO-v7DptV8Fmdhc(cWW6NB)7jgv6#4o8(z&!(P{z%&12)`a^m9 z@;ks1#7tcH6Ic#2lQ}M&p`x_&OGO&}x{~$VA`8+OamPhileRR607kWu_@aiUg`$-G z3>YgFz+i41oX_OyL{uLWY>{pK^Y?fDHSwo7F+t^Us6+}!YM7RI<9ZF)g;~J8s!wFx z98gqT+&$r@F6uP+t}nG#+Rwp%aUTU6@O-jXbK@v(>N9tEN91(^XKQ_suIq%(XBh_Lt!S8W5mET)q5|siM+P5q`BRaKHFx6Xc_!M zl3r9zxH5iN-hGa?deCjN(Sv6k-{ybtR0L7KCV3JRSVXCYf)qqwSSK+m?0Z5vQ=ppR z<1&WhF=Ii3!{XjfV>62nkE!7b%Tj}4-gyF=pLTa9LDAx;f&!3fTssiBI;5=cqfrwc z2=%jd(IlT zROgyu?ZR2L2ll85ZYN5kwrH1B=Bl60xvxT*xJK>j5YOY%5a1nyfgi)h(qC~!34&9m z5)EkBbc6TCDx=LBx*wRBRe~c|rl*r;Zbl-7>Wi%=jnUctK zbcJwFDUci-Zs{Ep-%R9iBI>1cEZY&u~3`UkAaa>3mZ-mX)6WZL^iZuVoHRpYz-{?EwGiHti6!&$fo)$Cr^I z&wWcSpI#v8ZLj$+toBy@&GWF=R?X*s*QebN&daBN;h$8FWxp$|G>u*OZ;tnWDX#E} z*Z2qWasMblcFq3?!dTDd`ohjxRzUZtnK>Zp>hL_{7u#h(+I{c`(lr>(ERytFo5DXN zFprMdbbMlhFk{Q6Der|TP-F?q?_wU?bL2BgvVg$hcZoVX6d4i^57%`l256}OGPDre z2^kr|PZ<7&Ty~(*2dVu8#yr^B%9KDCW_q)xZ_ zC0n^poMjP`bj~KDULS?I=Tp}oB2G>s-;}YLdB^n^{ZeGiuu@X<2g5mme`*29ttmNB zfLtvQZL{QZ(TB}kfoMorJ3U< z@}{*-39)y@J;95D2@@AeQIu)FjIVg7ua4W7w=y=aWV{o_yQ47x!`jy-Wr>3%wQ3Br zaXF6qy0q16h-ILF0MG^SL#@BPMM7|xs)|Vx1^5ciAt66k5^p4PtiZL>sZ-J|f-XiW z$(1XHqhio)dn+V+V50qo_<%Hv ztJYr8@K})b2HWsxQ1Z%NX3v#FPo}a|M~%;2O=8Ui*edhoJV;q-?mG@(%_PQYe1M#D zcL?us(+PKAlT2umyC=(dm zs$?_XUwO(Xw%k@~NC6=8;VAASRu z&@grg&*rPwku3I)<|BQ>l#}`1LIqu!_Xb8>S$~E%e6ZD=@p?|H43NpZ)_D_JeD6o!x0z7e0}U^GpwBCuaRDAr48OcT%BT7^7{+APWkkjgs_kAgG)%6*NeC~ zqQ+KEO-lw$E5m90WGtoecm0mQ0Rf)8WHqmP3l%#zAbv;ZI@E#!y$yKuHecrhGs60mf?v&{@(kEsW5z9sN)j`9LH}d2w3X)X-@Ka!!JOAyt3nVk2*eA3mkOFCgE~kD7!J2~D(Cb8 z>Lb)Fyl?piKVU~z&Kf-VDv8YpK|-Jy=%*boNu_q}ln!sd z63&7;`V#6FC_^V770)pjmbj+U>d6>h7Fc6E?Jz1s;bYL8%$p|hx}Hm1V|2}8eN%#w zG$Yjn7H%paWBj{m1GG^i^Y}Ok%EkOlE)91|R8M zhoOJBij3_lm_e>~92(dy)RMK2(f8;}I%~obbMOjOjKHS;&f?J2Fhyr_UVv?F1(phR z5Tuh{il7;-ED3F?*?VW0&8k{9Z0WI*5aORmjJjx_`9T(F`qM*)IxatNI%2%$X}_gU z(r>wxX7i6bt(F}11m!8G%ni2Bk&$0?ZSg3x8LcQnjj*YmVM>KdX5k#`o@b%l7Lsr# ze2;I@#ojf4gaV5GVDuWnTcN7gy_ST?+FqSCV|sHt&2EtL4ILgX^ifT{(|A*pC*ab? zpu86tYX(NhA1~uQOG2eFeeGxrS`W z5JDKB{p+7HXy&hc`|JC)JmP0?G0Qmr_f_5?umL>6yf*)ppo>vQjxk6;!M@L%<7;<$t zX*Oqj_A78vt@XaZRvR{q$c1CX>iq}OYE~?1oc&Rlv5C^!xZ=_y!gtCStATnk&f5#A z#sT>t@mYIDs4*aXZ5oul&%wHi4mLUEJpNU0z6P}1C^=H)wMfzxom|(M3_E8i0%&@f z=a}n`H;8Bg;9*@j_X_yzuemJ+i9n#L>v9i{8qzUEr#h7o^HKS zGjg$UUL~u)#0Y^lX_lN_MsSWXt}7aPibe)EvxOV7Zi;;)T5Qr_3H;MF%Oa29Hj+Be4yF9Ss_utSE}a#_|T-wtNOD8 zKLH{=0{WZJNSg->5aV<#Rt*#d7c&^y$O!KSB<~Z3?H}sd)My^OvN#l^(1h@mkcy}> zC4nn5_&|~OCPd@T?wTMP+4{h=xly_F56pq9R65%o)H26bUnm$xpH;^{pum_!`$zYs z5fcdXXCYKI;TKaAlUJpezO5o2HPJo3-vKP`4E1Z55IZafO*S!wfbY;` zsA>wo$U&BW0Uf5~9~PqW^}xfh0z5c81u=G@dXMTWq0}RenPY*DcYr)GD+|6o(3Hui zh`v)pkjzoY)0J>C;dm`ym>U|f;WU8U5A-J&~J+K{cZIOq~ zQgw25ur=>Qx{xrus3KKKtW)@w+ghDM^av-{+G7_j>1J&uMzG?9UX0rMYQ1qc`lT`0 zX^XODl>FvFMLv;BU;pJ+c-e%9ws=I#G=m%^YHBg%7z?$fSI`j7dv{8VP-4M;llpp* zrs8O6n(3;P1QGF&)8JVvpYJQG$VPgztMt?TCUF!tuB4i8dvNtNfX0?NmZ4ZQi zQ5lgbJ)CZkcDcZt-K(#$JFXYeO6&2AzAE70Jqy#o{VL1wE?i`$F?x*rb z=Xnt4LeFb^8dwQ*#bM201$^#!^-6)NBNx$ya@g?!MXkG2836dI=yN1!i;H`B$Cupn z!jE%%S6~#u)hOkC`;QF#)qz-2jOPbzG(*hArkHEe8du1TPc`3Ll9MS}#mr6YcWyz4N6nz7BV1O}ua-&Gy*)s#ik93=VtJwXso+vA3sh8n zB}0er-y1{jp7Cwju-MUYSTBS@*5%|PV~J9X4umNrC*OL^0`m^t?>!M87sdoRqlm~!CKeYAnT2F( zS&)s=^6wM<6M+23<#nOG6QJ!kt3`~xloPLbjr3rNjCqIOYpd{pih*TDejYzLS3vn7 zq%i7&$v-sTJcO%kbDFK?esFTWVbp_ff#6~V>jJ5EnuEp9FO8pktciA#u+Y`R?Qt6v zw`pAic@}PNo>%;qSh;@H{atmgR=b+KFx5(gkhI<&261n`csRX%0^7uH&;CC+&VNBV zg||pmqiJg@qld+au(Z%6hoPd^umZZ#nXzB1_;{WN-1mukEd2UFJ^GZ4*|>~amPt4D z!khe?Jl8Vb2fb6oU6~~GgV7qGk|NUGnGux(eM;gOb1hO?EZ;sUy5$YsdomaBGa$m3 zV1SFErHKQ&jUxTaf8Cu1A@V=cNoU8~%ZR)dvN{hVpHNm{AZDrmDW{n}+3V$71rp2f zr%`6*B{2bUph!sENGSgPS-FLh2{O<3&D5cogje)kc2GT9x`b!HMLtm>0u!20?bFA5 z4pNUuX>ZL69ka@i^|D4Ywv>>t4=ckRhVa2`vLAa-3(;a2#wwsnQOE+P=AXSh*_fM= zLG2SOT_#K>W)p@UFQG3SGmw3usRm_*@l}za5Dr<6gzbQ4E6u1(W+sfK-+4v`quLAG zN7gk$i0Zwd^?fS{cA`Os=c+I=80C?Wv8dukYa;eh)`hkaG=Yd^xbw*zz3rQR4N1bN_xJ9`JpcP=OJ^?;pQSYZ zD+zO&YY)I>u-_ivCpbPA#W1MWPG-xq^P%32zrK^PYV6z@w;Tk1j0K?}7vjot5%dlH zfY@87T?|T>i|tWPjTV7>se*LTu?cI>DQaabe$s3;JM99o!-q6PqVDQLMJZ_{PF*zV zM1v%6lk?v24Snw1W)cYoeYH@xRODqGi=QcwO^;nckXFg++kkM)f2vyMMVFjxWKFk;R5i6}Ys zMKh}O=q`FgYY)c4{W@3aHRWua{V)$PQ-8Y9?3v2|V}q_QBT}*+&bQmXeXe=+?$|ey zgOCE=v)s;_(+Tf7WiaXT^%ACg0#_!j|Dwo?+Gg4!DYY(i*gPOWL)`?OUFa=>)R8*; zo?FcbKF&YE5W9XONRww5rd~!?J=cvp2y0u1)VI!?wWGLn?oU`m+g8IE$b^rHM>@Yn zV00Wt3nK$JS5*5wBC@ur)urlU^skEDe+ zh|$3z8>EPWMudNWmBSG3E1TvxB)iZ*yde9XDR|eN!4YO~)ZGq~;kHMp!lFqRNU^jt z!2)IGSbpN=VVmr!){^pTBFDK$f8?)BC}ww;|KN=)2e6f9c@I>p4eUy-7P{%0W&UC} z_d|)K|JAAdZ#Ut0-O*nELZ|!kC>TKGs+!r)~?s zsNvO45q5=cYd2biy5F1N&b*%BllHZ$KIm*1ZBxb;$E|` zDLPmjf^x#bk#@~h`q}L-CUZa%_4VkI){cf3`}E;{r7B4ooN&5)QMAW&wBUgJ{UN3g zSWTCk}@>2Lw%7!{+%ADh2NSjGMf93U~JaG*#GgNSr(E?(`w>bFG$w?~X4=Ukg zb&vRYazDxY;c_wppokVzl3HmS+Fv{+<>CXvSB9)DYY4}H?6KZ~iwF3880C53lAIo} z(UcEMi?V2!gHHEW^^+O=NcY(hP*;A4CP3faQy}e>xP0bT#gxZb29jN40-pUwAW$s& za;N+rn6R(}S+CA3)9N>@r7f!{lUfPuSnU#2J@s7)h@O`q6guSVxuq?!@3t{()aFQ4hzm0@b=Jml8iK+X z>Hht|b8%Vaj>|*bwv`i6ko{UewzF(;2T9?Au*Msh8m5opK6SlhqUX&h%&BMW{U8%{ zpUSu(R_^%n%2xPzySaZ>D0kecx_+bL-uIzrw@Dz=yo%V7GTV)0j_;x^%+ROZ`^Da* z&E_?t->kv7VR5kpCB|;6d-vr0DCZ&XbU@L-WjvA!RB^q%^X+zp8ZGg9TN$* zKxV>mTJQp;Bt;SUoC4s&pOSHP!r?2$WvtoeZ>(be%|A-@;YdbW^5UQdKNyY!9k3g4 z78-UtO^$$A=~5LGHPA-PZ#1JS;we$A>X4HTaC7!Z%=Ie0;`%uB zphhEDyO&DrrrcPs2q_)PLS|VW!P(N3cuS>7 z-lfFlU@?PQlQB5=6=bbF6_#09Hh>L%&%O>(@&|So%K@+N3on?vKAEFPO8B#y`oO|W z6}}du>tm~6y0YLFMsw>~>uvz>q1c;CJL=@xr&>_4KkbgE=oEQYT;4FIb{>FZ(g1WmiPjBew zR~66d&YNs?qZ1Rk3q^^dW^j5+N%TZH0%yGhng+fZ<7*EPC_f@f*|IrO-)~6 zguPM1_}8e`l5rWp!)j^q4GzN|)`>Ey2=V8bm6m-&qNu^CC>&A&y1)_lc)4VtvBkFw zZhO=E$j^rI;8yTLmaV@f?c%!D)Ka(XFH2pd_tOGHP22)mYN4$c;2oXL`|+-`tp)}BpSS|S4ObqTE^3ALi)(YQd@du0(gt|Xm%QK`O} zcUQXZ1vSryZM_sPbP z@!+kr?op|)n2v?OrXdEtvV9RzHInUQ{{w|i;>R9(p)thtQ)wO}6%?#biDv_@Y%;5s zsr1mFQ+SJZzR2^O&Rkg2+kBR64*v7-`}WcL$LT$sQRV7Ph1tvlyBjY&{*4L$|92O^ zrs--wb2M9pzjcRQ%6#8GgMFMno++^l?PA}-{4;&^pVyb7nzd@6rNFBvm)XKTZ``;v`@A%6YY;Twl-O0{m8V1G}1xfHg zKHkFS5LzN39mMdv0cUtwy?JXoyLpduV7(j0RF3eU&o?>S;Dzvs6FtaYTXXbG-c~_u z%4!>cQwO7wfwnb5k8qn0cn9k>RCRiLA@?X62^gOR1S$+(Wo8{A>f8X=G4O>^uC4v* zx_7T_pUVJ@V4KOm)O%UBDm?J!V}9sFkuLK`eLDM&p{ebi5562ykQ@2l>;qZUXxWs-fWS?0XXy$_at%6nt0cBv6mXA@wE77*Us8qbkmA$AnzB1(;1PVo%0utg^|q76 zeWV9pTc&n8686d3<@2jKp-H$C{f#8(C|V)!I46Nl)s8O^f@}=#23#1dr0tK-Za)Kq zh;iY`NB&&lHI*1@?gv8EtG~iBQMaNPT*F-jhHf3S11&s^HEr|9n=+OYncHxxFi{g7 z6(42eMjgMT61lZ-TWb1_^j{vQ=0iS3^X6q>p818ni?S zhW(>?C5JGbw7GAd;;p0XZJPr?!LL3$w^B?E>6{I--&oHkd9WnY9P>QemLhyI?mdz&q+&Zzi0$qG=Lw21P(Gn+kNTsQk!kX33P-vS1Op6 zt@a!{-MXEUb6xgbo+D&iS;sGEd>Qmn`rFU>szFbw)^Vwe6W=d=HW8RAP)1v(t4mZO zL-f?_YQ%j-O}}8M@PJKrH&iv5e6K0aOse3hovrmxdzwvWlI(2JI{HTHq=dV~aD4U7 zil@YyV_;xrx6GdJ`O3C5<7Fv=mZj*gFh8>Xt>9>T zV?ZLZU0Bi?4M7=9n*HpUg=EibjqHo!b!tjvG|O26zY%?U)j5WCNuLVKlB#~w(`orr zllObXxMh;>G_x|gSABP1$0vmDe)Xp8sFQe(wC;E&P}#UvDdj=Sz(Vt<8zN-jT6u|* zd)OTNHEdj^m+yLbR~8}8#cEaVSa|JJ5VZM&KfXu`4f$~CY(J4PwJ0X~_*9mti^)Ei z3&>|P0;Wen+IrgObjDrKrq*FFr^@TR_Z_5R5sOtZ>HHjyA(%HZX;3e&+oU~y#Xegf7f_@BZ0+6T{i&fAx-&w2Zvieqv_dh2(U7_jo{)4}@$cjsAofiqE*C@075 zqCU9Na#9A#)P%z*d`J|4tYtl^=fcR4grQUoqkc#pwOYGa`_Y=K#mf?D5E-i_H4BN` zMgBQ_i(-b7G*f3vzepl#oZC1E=r)nF8KPKHN*ZCO&{v9wy+gtHIL}U1FZ9}8f%8Mi zu%w(j>^RV#ULeWopu_E!`{lMX)6bUqCXo4bGO3o1jdX?ou;22t+3Haw*5Oc1i6@*P zMWX{27Pl$CgJu9xHB&jiHY#@drB$vpIQKZ3m?myJF11OU+CsZfO)Rm`l_dQe~Tw~ z5Shljw|ghRMJFGYU|W(25PF#P-V2m0rE%1TK~q$9gvW9oxghxyPxdBMsS~p0_A7k> z#kY+1vqJj=_fwc7*;INubEO%a(&-r=%-jkL-sdJyo@NFM=|38{PXh4L?mf&K!{9(Y5+`%#Y{fJ5`F}2hp$E{hFz=qxG33BRMxi=gn^*3zKPwazUj4}e5uKkoo5Wb zft!bWUd5O9akFsdmlj0@fOnFQ$gSpK#Ci0d6{fB#`!$>DNx={rkZNh=1u%* z`UM?O(C@tcd5{sw=kV-p255Xu7k!<=1j~!Xn@44D04}r-nS&-6Xd~X5BWv;OMqT~j zB}4gA+m(l9SUha8JPRFc9Un9$J58qrLz|`^EKW&`z!O)$uZj=Oq~w3ez+UxDv0|ok zd_myj?|tRs0ZBa`P|k33F;V+QIxOwSVD3!`$J!{tP1dUr8{aY9S0D}a#T6-HgSWTs z){fshTkknqM@qmjNI)Fnws2zA8{85q8uMPagxMb9Fbc&r7w=2+mbzH{h{QMa4p`k> zbGhe23$OpM*!EniJJgm|bS8e;2Mw84(tgYL6mMlUb7Q0?aFA0^=7dcrGZM+eAm`e3 zMigaE`2?gbe*!+1jI8uM;KdBNiEKg20dP!=5=yle^!GHC`$14!mBsTb(Z`OcYVots z3uL~Y0=8c2D!jQpoYNilM`n8a0%u%#T>JET@_T@ zw1MJyHra^#$2kj1Km@puZhK_qsxvoV$k6X2w6nc7GnXLHmaG1=3O>{VO$Nehyer@3QW29_g0T}O%c2B-@9T}YIg^=7XZcn7BA9PZvEM*agB}w#i&|z z%>8N|T3}dxCm=yEnZ}2=BgnEas_D0U@M^HlLp3|4(I_W>qi^3lMqIowedkIzFe*{tR1p<*T1IU8 zf~<3ty~aPGQAH((Mork+fM;YOv#0kP1yh|F`Plt(vL1NK$%Xg{74r!6wF-k=b+Hnl z&zt*o=tdy@&4?f!e*(qV)8nc*(pmFLM&Lj})z9CB>bVrg!BzzFnu?sni>`|V$d9eT zdA3lEy+TY<3V}hrLB!OS^`65xH4mH=lI_)xN#K!VfeoKc$up~+_D9NU#X7h9Z?THEcyHg%F?r#mg?d@%)r27;Kq0RP3Gtz zE1`qV2Ly4Op8l&#P?mR%x531Q7kjDvO~2OK-_FxYxVAhO z!^CFq6J^|t%ClZ4fqb&^Ft$`ncxNj4sQ>Y2N$2Pq9K+YfadQidOzP160EGZ|tW_?@ z59p@~d*npHO7a&)c|E2^8B=_+K<5 zALdt%J11YIQMq`Ql6D0%!ar@T%93+KXIFQr9zA(Qo1d_pi)me!J0*Wc$O7F*N^JYb zNN5dLq`qL~(!=pCuWwUIK4~DSN0a$v{p|&$MYsPsSNVIzKl%drci%LxtX8!;#je)M zGm=n6{=zD!udfxQ{%864Z-wNQku3P{zowpdX4ukCiGrH$tXgY546^~n zcyULQ-GQevnGQn+8(x*t@}|XRF4J07Zkxn!lizeyqfDQNaqXkn!Yc$s@fu#Hm9Qfh za&i!B=}y?g8@WgXfx6ABUsL!(rfKJ>4yU6ZOy?7h3~TG%pLcEgNasFPB<@s}GXPGa zWk%k^3Rw;Yj~ciHnild&HbTc6$dg=Oi`suhyAp}HlD)QpMg+Crg?HrBJPBTK+xE>3 zv2O66ygtUJinZP4RRh>@W+m7{N9hd2)#fp51LmB`NmFn60{I9_FH(acY}p?93$V;8 zaeq|`9!C)=aj)CqEYXzxHg{}Z_Jntd6icnO#gao@E)?3W}u-&{IO@BvVn4d) z*{4)kac5jKgb=Sz04p{F+E30mz6JR|wtZG4#o`#}9D|%t0eIz=`8xQok*^_Rzh3?p z6C_Z0io#D}GOK)JZ9|7au~}=gA4;N3nVx@zD#rR0LOFPf6CgHgL;knvJ%d7TFLOS<7XI0ou%DEFQPiqVI1gKj!q&Px~iEX zsjN1L9S*Moe|mCCFqbiyO3dDgVf|7qb9h!mtgXP|jr+8w6 zV^0S}gsQi`kwPfAQr%LH`r-%@nO!9BNV7DKpa3?^e*C%q_1TF+TeB~@T%k)6tBn!8 zv8}gIQwDhN;z=8Pu5-h6{#U}FZ&pQ3#UKob_x}PhJe(4}Q}+3HRmZ5%an@xAe|Io* z2hd74C9t9!`QBMp#5a2eu6QFy`qhl}>0IX|cD%AgLE;5)xKRwVl94ZX>gArVBU<4UDUv79qKSPiYu#4Bfc%xg8p;k8 zY2pi%*(c3nc!AE$;P@FL;tP~YVq9?-ZX0Mzi%}V|WeruYsf{71GJU&Cj+q>b+iazu zu7;#Lwx`0^_R50%8sB+fV@ReuKGLvJ zMbj!gAR@tcL1c&IE$L62k#tn56*%_oC(8d21h-Z7F_7o%+@sl-XRckkLboIroLAPL zx0&;;L5{qT;t!J?Z=7>YmH1nSZ*4j05e+mx`WMl3)y(!EU=_S0l1@Su!60yvDnZcN zTKgzWtZWj(N)n~MdhICtzSbd3AgC;`+&@h6l-$~02{|#VpHJa$ErybS0WJVrS}W!I z+7rWrGf(4d!lE)rRLNZo;L(fN@E#{ys`6!Iwxrf(1w13;mmDjRZhb{`5f3+ig6%$E zkNfC+p+cvl2ZQ}(ci9NWUjdd0$+1-}+8>b=W`yre^jz@6#(&$VB zcw0PrC36*u9h>ZaM)2=u8w6r5uEWWh}Qs=kj^ygo{R$y)+MT@A^-Ijb?Uj zOLCL}E^KT|orLF_H!`A@tcu|H_(k;YEri3u@pRwBWXLmwgE%aLSR)iF0s45z9ZA^4 zKRa28N)7g2GK+;Z9??1=`lbq~8B~`48WH_SIhkm%B=iGATeyZ5f!emgDIx)IbtH-v z6Q+oPR0YQofUx%GfJQc)>mmf3*!`tv(z2haUI80#{js+hFc8#{8C(HgRKhHN1?gY zWs*8JPU6A)CTiJHx`j2wi7`VR@F@@1smV`N)Bdw1@bc|IPS1dKATQuq_vZ(Bm<72l3s%DveY)qdUd;HN+i%_FuD9^Q8rb|H@y? z&uITY>kI!>2E*%Ru8*wJFH@Ik31iE6_8J0O%`bhYBt!OTa>y%YDewb!;Obh_w^QoC zAI&>pSAtOL+{~sW38)Lb*KcbzQ zK`9Sq?`ro>IKg>%0SFjDboY1Eh;xr%S5V^-u9yg4g` z^cL#AKFCGo?@Q>*^|bZyc4UQzMn;X)R}>c5IyCxoMeQ)X-fuP!0w1mMG(RWTP0@H_ zrHVScYqfW^pcVOo*QB$E0crg%EKw%=AEes2(;a#?mfhE+qtHMrPvD-1T?(;M?Yt9I^q@C!DOm& z33fNM*iRnD!@&-4lBFciex!`XeNz1$v$ON(8%==06;`bg9v_8 z@10fWtFP$>t?%(b5O26mBtfn=$L;Md$-#=ZZ%YIj&b$yc;y%LqEd7)m55Ev-G8E7F|=<2*(aYeSo=ab-D9a9jhSYpOI|@NCY>zSZ5|wCATD86pGSk>c8;b3@bhp?yWa z`QM9UCVk!*>QDx#*3Vz)uX;e2FSYR~ZeF!9e!1h47;Zc@AHpq;b;-Yxj#TXm6hlw> zhi@|*s9Mnz5G<5TSdhWhB=9N!P>E6*b7?&)K3gh(e&mr=2aykY=|-`=k(eh-sd45{sa?RJIOh^7cVf>iS1ag$x=f}!pI$dTmKkM#AnD`-nDEqNV z^6?FPVlxi~K#N@Gr;2!hf*UV(q~t#Up>^mft9FrulPU%dn=;o(`g}eYlh@E?&bB4O z2NkJf;2lsqJ%E1tY9J_y--)QL4%XgR#5zW!+P|Ci!NMkr{!srUGW z*~R?H<)6sMg_kSOry^6V@*@}AkG+3ZR>MmpYkyjuhkXA}W7V5OM!9Q|3<5Hy3;)Pn z;JtP5ki`gbGi}-L3TbEOG^x}+ zNm0{>U+ez;lg#su?b@8K?#(iIoLo`C4)4Lqc>!nW4Ni6<^eoF8Ay4f+lh+aTDk`Ug z#HQrYKp;VSuWIa(LRTOwGHFN}O@r{g$cJ%Zf@N}?6O9C@n`a2lpwA_1$rYW!LUBhC=nz}N>!xMcfy28vgIvx z05!^|tNQFLz@T>URTYBW_+h+? zSWJ6@t>d<=Uiig=vkh5Y&qKM46&jqNsHIMH#Y~fe7hY#M-IvNhl39F*QdsT=TOO>{ zsZL~FD?CKna0@c3Jy{m*o62Vr zV_(MG#2Z0NpotckoF3I;@cv*Y`N{EpAD6Aq8U7@xbgCgNna8eO_mnDnTAcE2SZK0q z!y`9+Hvz;S@i@KaMp5EfCy^WZF=(UoQ>qMTfFkjyu=3*^Z1TnwvXo6=Q7Ax%A+v=w z)kq1$;74y*i1%UR4gQFONr66fsKv<|&e)p8GRTEI;gbnPs0MSD6|_IU6(dqVLQCZ+ z)b-QSFp3Au5#t}TJHJt1vlZdha?5JE%_R}|FsJlMQlQBA4G&JFh`fy>2jQ<%H0h%^ z9#xw%hzZ6Q{gvHt{UH^bi=9ha!1T74oZ|v&d=r+eDUW5DfE!~>qk(zS+fUNP0o+CY z$xUm3qmQ&lSzRp&N=6O7ER2lzuSdx!#;?q1(ofX8xn40U%miDK#MuM=irvcu4B(7T zd?rqW1ujzSz3579-%2u_8;ngZz}m^7e=|{`{{idSa*=XVM$3+8$1fA$$&?>2Nwtjh zqcc3GE zAbJUcAP9-b>Q)!M_ujj#9=#=^M_-*qqDS;zS3;C1i$#8)=bd@pcjkG%Gr#?3ea84> z*FD#LopYUYuFCpnl>>VNfIqQgYZ$c?ZtbI+vq7psghK=va#M#Y=b7flZ9tD%yt5+q z2R;?!RpL6)<7ASaNwJ9-k*j}?M?y$En9 zC1deC&lv*$u5C{$bd|YTE5?zATXO3b%@bGJv)f9*_63Q8}+ zbm|xiwi1nhq^@4X(pJH1VY~C0h9Hx5X;CFDJuY=(c%c#cF0V#h4LAhBOx z+=2u0O9Kefi04?v~#B_>Bv~^ADsLd)9VMDbPJr3vNYzwWL zw~AV4dFx-nYKj!SjUO!W6~J7dB(AXf7{2cUR?Y94|d<}Esb6u>Q7YsS54lD@{Rrg(^q|u=ADLcyf<@DpO0f`i~ zsx+WKt*<^)w0f2@Xq6rI+Ne_;#TmKqY{lxS4Gtf;*FJB+6d8TM`)FFEdnBbVXCd_)(?xiO0 zl;iWsaLhpLypb2~a>QJ#UliK@AFEoDvRT-Q-&eeswL{?^+Rj#^4n)Go&HX zZB=sR$yqxKd{j_@2O)~L=?u5e6FHGlgGT?xdK}p+=6(JV75+hHv$Nuw zuj_}uj%$Mf4y^9Le>1UQ_RNM-ncYsGFwBid_Y)p04J+UqL#;6Kj+ujV#uEVK>o z?3cjfE2EoSlXu;F0ggB5&oyBcB`tISka9RE`xWxs?C*{J{}%E6KT#hLT_JRBemP%d z@U^0A$=~j#@N-RC#Xs8Si?ajW|A@m9E;jh3QtTk#Ol&)4*nyN&`#d+AcfXWFNhp=Q zN0vT5YJJMaCD=-<5Twx%Gb9&!y{59T&5 z=6(C687C-MvsMODF^lP)c>Mhauvbnzu9;p)J2QmQupX&;OLdH8n&|J%DiMZdr5=Bs zCLYyDelN1S|JFU|l%v~CM_*%e87-B5bT7PtDJ;OYQtLXiUSqZk6$pRDM;erXxTBkq z9*1<$2`}|#|NSyLI2|73DC|jwaE{6@`quS`A#8|;-;s5FL87fxs<395!c6-R4F9n= zm1!9c3QgaE&$nEuBpaHUJ^DSlWf+yWp;GjVjFsY=aUSXRv04OYJPGkGK8*|1x{^Z z=izJ&mZB?#>T&y9rF{@0R>UW(`f;a)_AE zk9)aF!NQI=alTSNaVDqZ;awFVkD9zbTD4ei?HcZ^&NDLc4=D1=2ZFP3;_ zVM{HKGCDBXEF0e)|6Pq!QZy-aY16F{B-_)1B#z!tIXU`vT_pASZ#T6VPGU?G<5n*x z5(ZeF7c)XAEv*QKP%};KZbUD%{qnfp4u}l8m~iEv9d@=>lb>1oDaa-Y%&YJ{IJn(o z1RkG}M zMW~@3C$2Q9*}!$;E0aTF>x30a?vPcCtQA3XBf-;ic};D*390VM$XkA)vraZ?{?>I` zJV{k?L1#L_kb8FkqGi&aHu|~z$pYq9$|Jb+aeS^n+r%Ku$U7xyLJ56A^co%-K`uu~Ecu&~W|ttob+#W4<`1v^EtYT-zEWth z_<`&?S85^CgF{ml^WJI^1|`8}lNwZWn_>PhK6(VA!C!OMa9E5`u-rN3bb<-jB|C=X&{gAgw}U8^A}b1XHJpz{?DXE|q6{41l13`<|*x?O8Ku&t5@Qz0rSHn*aSiTc^~s7qMuT=TP(I zUc4$u@51HPpTer1CI_9n$zo!}|N4u&>ZQ4QSlk&o@*^^akfTMiwb*6xLd`L0d%@zN zPvK~1BU2W9v0b@^rg;&}3>?qv(6jdO#B*W0nTuObgj`k%`(J)E zTeb_t+!ySX^%cs?@48LWO{}XhSSDnNRXv-r^M2ya(Z6{3>4zOs&_~hx&+mQHq2lN3 z4zeFaXZ)axHP87TeCA%y(@STGZJLwR;gb=SVw1>{h%e^%;Ed|cNVJ@o3HNJhyPLiE zBhehOEdM}uACoSY#WcTA6J|RcjzceZ} zVOAfOWDKQ(T!!Q_p^l)Uv)4x-DCd6s!IakpGv7_%cahI=YTSOZdH~Qt?m33|cW?04xi9^{Q8p*Qy7f@sO!g=HciZg6b`5-RD-re3E_UP~HW>9*-L{#jMoz|IB zVd=u3Uyc4BZDT~$2E$jEglkTmttjf)LHi8_O&S zXWzMi`!l~5Us=+_^ooo@Ai$wrUQMUb!YDB>!4M~U;zXXN)TXuJ@0ojAcCSeGx_1Cj z&b%*;t5LB~4i)dH((uQSYg^z;b(?n*eDeh*eU-Y=HJmjsyQWhoD&uPJe#MXJ{ng>> z>FlP-FKDdcGGWF3R!67qVs2ICmve2z8Uc4GET1izi*tMx$U)ha{`z&V#;6$1c|7^E zRe9Z&?H#INMMXFUyg>GvH|`F&wiEPW1IdwfSqxeB)&#;FPf;o_jx3QEQ^R;u1;3S( zi(WQqyNh`SuX?rk`bd0h<{0CZ|!wfh!3sR zN0b{7`;W-g-^ALRO8AV!>vc_*TKcBM?eaR!h<-_hi$#tj1$|@i`i^BxAeT)pDJHlF zTq%F3En5chD?YmeqYl^1kmXZB|l4?_2hF)EX1O#JDdojna}? zECyjKLgf>@koe-&z1Bc8O)F)?`+~w8G5pz$bf z?Q7%SSZ0dhm}{H`%FePx)kLDYEHZPbOUYjSe-$7-JN^K)-O-% zP|nCdx=?nrgqdE;{v6JqfhX!Br_VgY6?Iz8uod+7G{S!JA07e71);4 z#FEO#G1ZDMgTvhPD$sY`j%=C)-@FV?N@ic~3Wi3vYR~kaEUpHJiZBX<8Oy77Pi|*# zTWNA{TNAmInCfegZXr{_s;NJ=wr5g&IX(e;@K^3c3s}|g;^r6xi;2wUwU!$qA%HsX z(ICFPO)S#f3(`GPT6(WZq^l9um$1(;cCFJBH0VPigC8&WHA?S#D0iqgU{X=*vv_L2 zVTa_HV|zi=6YBzOwEw2ab@s`xs9ps4^w+OW?5dFs6^6j%{pH>noTs~QA=!;Wp9J*8 z%SkO+V*>B)rk;5I^_8&n!iFKb>PBLii~J?%*uC>UNJ+P)f~dnxCOm%bH9`Xef2_>w z)KM1@s(W(aC_M?J3{?CzJBts7fWyfs4GGJ_Ntok^mY6h~ijSG^0V8KkntF_kimk@9jVZJ^nXd;^7=vJB~q zns+2$^5V^Vw2%i?p2oN&%U)J`1Pk)h9K3hAY>b-gZ(3j${qEJs{0PyJy8T%Sn$zk) zY7&7k8Ft*2uH#8zW#gm@TgPH&-uMLZfu-CncqINNne9%@uz14(QtDN@J6+vQ4jW&c z+L-yUP{R4aT(ZT5%$N}598i#PNB6nU9_lBj^A*`?Y(Io&Iw1;;KVQ`^dzy-V?St!C z>y0ZCHR9^+SCbx(Y7{5dh?QWsdqHKE8JkkbGT(J9voaI>>CIXI$%vha;=3P727YC) zm(e~l=MScyGMbc1bp*PxdW30DiWbxv{rpN5w_Op&Jde4Row34@qx@lrY6VeD_wKR2hO=vV z^V8#y*95i#HvTh`O_Iq1$NxAU2Dfx+lk6c+eG2U_m~#L=jO^oKE`Cy)Eb5@+Z>McV z+LlTbUgTDnf9rwB4+W5KS8ba%UkLqQk$(SSF9|(i5MO!dPsl?fY(1xj-yA2oFDz63 zUm^Kd@c7W+f3`FiUo}91BUMQ@Xqp<@YG78lH(-Op6+E|P!?B7Nei>FzI$#?#54a22 z3VN`xsuR?a`Oo>l0t{n3f_7N#C$XgL*rBQEEU)01ct79+m}Kmj(WZW>kZoa3SD&8J zd2wOAEv=#nfEmgDmh%vogD9N27p@0#M-;m6%L(vRryMqA{_yrC<0cJ4U_a;G#H5&= zVS++U1m+ERktfgApV}qaTnSX*MQml;gsS#ngN{ZR>J*x+0lFNVWs_>!GMSc=`q%%P%kEAV?LzrlfoL~tEMSP#9mBKiZ4Ew^Q{vRu8>ri|jmp8~cNJfydtV0b0Y~2W3$pehgBk#>$ zOZYEg3x7y?pV6|HiTkdgNjGau1~zoGh)hZuSm8_c3DYqcmSBJR?a4y3Gv@Kk`FTqg zrG-$|QrgR(GFgj2u|g46XtWn*E$ZNuwFGro=xeRRT=&5I-aIk`ju zncvr{lv*mfS$dsW?AG*ETfykf+P>rNZyU>_Q+=3TOe#FxLV%Y$F%#UeH3IPqthA3} zKY6_V*4$^JawhS>^0dIA?Z7B_)ekBnkU6iR;kL||X5Q4#(q2Kt;VU4G+H_XbWn~Hl z(M5t!|7>Gp0qfs`*H6sf$fvVJ$hM$!(&Y?6<$~FT5;6 zefODeFYnSUMgZKTWWMePJ^R`sTbQvW%{GJ|RC+C{uTk&lMn8J?cB8|ufs|vFO)bz@ zcEfmXys44efs~<95Wn~Zi5Q;TDjU8S)QwGOjxrT7TlVw06_x{t4{r*HSp=@3(D zKm)l3F=5()n831V6%mo(L*sdz9D0Z~ zvKs!u_Yzm_;~{$2{qNJbz#No-jXFf4U7PQFRwzKQPuO+J>=lq8oIQlkurKlX;hYig zvDlZ#UwTP+s=IlVCh(r3;WO4l^Vw~4H~3gOA{-UtEN|_T4pgx6(dsXR4fFD;&rlK? zrN#>b`OH!z3Lq_lgtaC=6@$HrMJxTB3F zj`1J<{9AarlXWEaSJR-zWVYvdb4b;_+-pqL@4C-RE+I1iKk&=o;-usEddZT)n-Kfi zf~p(G&zI0yq30ogOsoGlZkwHSFr@>#C%n@8D^x#GDH>RIrDsK-wuS%nk_=cpwPG#t zVU8ymoo5gOr;3*Uci8rpS>kE3z(T`q^DA5#uXnhYnM&51%^rNhQd>x3j; z!58z(BdsIsDk_$mVbAi5g$GwKN;vD|(v&Y;);VAfcgC9NVay4P?*bkW@@6B1nF`O`Aj} zScgyLsdQd7eZliEHRpgcu`?72$Movpzzbfe~SsN5SjYPruUva7PQgrCwabr zCYvnu2xD=Af1h~Mitm%V(!Rz*0MM-49^R?BHlyTyGTb;0`K^Ej*P_X=Fp@O_e zr`eHQ75yrVp>QraefyfK;OsQce}_`&7p1*u$okANT) zBHxm$Ws`Ma-Fhldw};n?n#e=R<5!9JbqSkNc1``Ah97z7q+VPPy%UZe5vkGJlgA5P z50SLY6_AM{;%#JN8yD4Ea^U0c4jQSo;)MXJ5zFEZaLr<|fXo8K+cTbbGlk84aGy~NHaYz*y5cXn5=4Fncx0fRGNEQM>k{ukqZ)w*-80hj)dLMTRd2KA>N9{bG_n!H z637FE!kV*{FR*oU6Be~))6CnI2cZff-XJVQBYDukbl04pY~e$1p>v5-1k}-vcd8jl ztJ@Hf0}tOCOqhXrJK=_&Sx3K4XK_fu6y%H7CG}fF7n=Da2~mHWBj{a+-V0{HQffKo zm5<%t-Hv-a?nh8<2Rw&~k;6~$-FL1CDM#$eo{;q(@^t(~zhYm)U z#wcbPs|l)9z16YuKA9WAGWejq_u-mf>%mFE%2A?0J;!EcB{SldMxYjTC@ei4@-Lu@ z0P|0JR{G6d`I`Wsl9ewxzUkqf4ZgLm>UaL14b&TjFKBdtWb}KyVSZv>jW!O6eQ+z=Nnwb`U$T_?VcM2yRt8bYNxL3>TjF~?s;S%Mu2e~j8udt^q$$xlUTuzf%bcQq|k5-Ne~S0r$6#Vm1-cj5U%rr@+R#1KxQk zu*|6enfx@@g1mH>sqOD|=hlH^*qlLhRV18{LwJQFve!+=&4**Fu%Pbh))POqk0M$o z3X2__?wFgr%_j6UiX;vuzuaP>tEnCa$Kyugunw`Jf39<=jKs((e@>cCb&n`girpW> zN6>;eBSS~48Q#Yct-PHe@ICe$Upo$n4)50UJgU(!={(cbGv{`-@xuNpAd<|tx9EOb z04J7c57LD`dG85cBHJPY_9S)FpFVWZD{>+o@XDX=6s$Xo2TSyRkBJ5Uom5JU1(CLw z;YBCaCgAcX@$GdtdnY9EdjyAoMFhx2vE`(ojfV|5BC2InJ`A$K{JM7QJ6))U1?`FI z#Mss}A=(<@&#EkJPmY4EKsxH*gewiCYMT$=>V={Qif2 z{dVtu3yWm~A=g5F$Hsvxz07ID^v;(lm>_I(?oJA3l7oSkl!xldICL{6COxP94+A+w~L_{IBIy=wz8e-@u! zvRrb7*%@#Qj<{Ol7Za7d7Y$sT@;^f0$6sRWbQ#V$B{C`U^Ump?e0^={_0z*7xCw6e zGi$UTqeV!mgq8FS^LCk07Q{Z=LT1BMBrZn~w6S34C>II39edxjWg9qeR|fVYl~+k- zL9Z#Va9@3Yv6=kao!MwfjYKvNOqjxpHd%c7k%AP#P&!@dQ0ua2k+Ai%dbmT{ zn>db$x!A!odHAum>CEqw8IR<)c#(e0h%@vD&*4a1*)%bxc=xIc@(y0~j2BYWBKZ;m z8LlTYiJ0~CwnqpWRc8Y9N8_&-nn(O^<9`LnIn|N4 zC1mrV7e6?T54gp+9Qhm?pP&0%qeRQawYW6n84_PHi*~Rvo~t&@qUo1Aes~gWFv!jye6+@6j)q`%|-K z?l8A9V{o8*m3nM92AgrBUwT$Ue@^5H!hDC-Sg!k?@>jHPXqvCSPHU zG8s1j%PzlT8w-(W^z)K63z{#QB@S?R{lggH$AOabugw&HT8EvyvfPvozR6r2!Rwu_ z6O6p=iVS$PVQe{`-#=inp>7O$FuB=eI5xK#b@}hCb3?`6J$ldvNmK=Vv);t_@DOh@iWm3ceQCJIS5^AW$vcweaxbKkdXi8DGVMJV0y563xlf2F&)nq_z6=-)OCw9;ioEK{r{i{zD}THZU`* zGpf#qlTM6%FBXX}{s3TX_iqI2Yqs^uE1?f}y%5Etx=hdOh{DL66L{5fr~42UxbN82 zsGw|a9Xq%iAnE~fJ-)X_*X>h6J?`kKp$OUp=IjVVsh>d3*KveJPz5HJlaFu6KPMTqDbVQh?HRsdG-EZoPn@w1dyT_23tbIWGn*8ZS8$mQ zVGknF1ceKy=5_SS8B=r=k4YQ)S-iRJHcGWqN9;I9dVY;oahA@gnDz#C1=@iG! znP9};L+DetK=b){3BZ~cx(#7V!DUUsU1K@J1Yi006^8g@V@a}6&SXY1^y5Q#Yo?wO zE67`C?*Q8+qDtoUI{c{bx_SdCe7FEqa&~di*e^X<6b?_vE+EB^PgjWp$X7CK-h@fr zH#(r@saEDkpPD1R!UArC=Sxm>8MxEi)?3BQjQ-V3z)bl$pD|1X1O|Senn=-k%ReV_ z{wQ)oAqM23^Xj~wBy4_j)URK*jydnKvjdfKC=C$~lPmeQ=3a z^G7BE^aSk2Y}BOcepsxRj&W-y2kI{iU!1B-;jh5RiwDHiD>D-T>f9d*)nyY|{vBQf zBE^ilTbKRFMf%$Xo;EL{JEL7-Ps`K&j;?gM+z!C`r6D9%nC&d;0j>vs`Pe_w7}YV~ z;8VneZL>*VqkS;u_lFTn9+;8|+NxkL$H* zKj;Jyx`TFcxJOJ#;e}rgq91(&vLP*CHMPm!Zt;DlsP1vhW}|d6jy8?QyHM>KT9r6* z7coHE6sS2pJ=1~x{>xdc8*Y4tULcd6O?E(0gFhRCLDvNNydP4f-l#K-r#ZcC*^8N8 zTHoZmT-`xS2-fmtTSsWIqi;&OhK1T4y*_?!3re$JBUJx{vSqO#2LOTFtI0b)P7GJLxo53la7 z`>gX3H=$TkSUk<>FIfX9lVBt>;w8GP+6ev!I8_KImgg;0Do-a#l(^LmcY*~2(qE?+ zBl4X+-pjgt3m?w?=holi;{|xH-J*+_g7Iw)pH6+OlN2i8IJEY<{n|YpEAqq;Y`N2R zAghM`+S~W|8uOYETa_=`ym^jrS8C1sitRHi)!RGq*O=RAJPBjUBdgT2}9-H*jUU>FWIt%jqbx+h*5GJC4|I!KAo4g&I$!h6XBex^BL zF4M7Q@qQ6ousqVwE714&&mLV?{!1}jI~*K(cgO3$=@hMZ;}-s5Pnu}(Sa%O>QJ(`r zT^(2<+x?K;JwY#kzfG%|10dtso*gwc+X-Vni^q44t6GV}-d$L~y*H^YVLJN!9gQ6h*hkGhso&`Mj-?{m7@p5mGY>3kX>1WGUhH80mCN( zbPvbfAth+PL8e|ZiPS7TDon$0D+K}8^+~rPW2oY?SE?n`TkO35;=8=SOE@MEyqO#m zRp)ahV2>|GlRe06axn*%i;Dt7=Qdhv1knON7I1K`T-FtEv4U@JziWH(T6h?iLgASA zNlNiVlXz_=s0`GL7uX!u7H?Bi7j{p2Zev_d5yQr#^S?x&75fP`XOdE?^QKx_WpB40 zQ|$i|m6tOUITygyYV|U9@)m!LmbxUvC0GyfLjptFhoLVB`@|QGv!J=Qljg(M(y)qV zgSFN$O5Onl|A^WZG7x8m<*--{E#d_dY!2^VwZKiGNkZKVo4=Eg=(}yd?kU$nTN-P?l zzw+r`k2uaIA&6 zmFmzz-P9DkT)m_M?Ysc!_}QH)vU8}J#6^7Xk&kavP&kE1JdOtlp-ueXe>t{v z3QZS?s*a(i${c$>!XrG~y0@ZHgERI+E^E67ca`h%TQL>J%h*b;|AygM-WOWHZCXEC zcX#AAEIfAR7fq7Zmjix~a`8mw_Krfwx2WqZ55w~B`ndaF{EYQxM4Kn>ztEzcpJFz7gy&OgQ1hbc5W*avc~|s9(*|nF8(Z04wvX{8oaYGzv3T? zV&+_R>gLiC zOczC|^xPO}dcATNU)I|{ZT;5ZQk0=6;$~6Z!jt5o=TMw=nm7Gr;G_DtgXIL}Bo-WNWCDl6lY6H_9))vDA-|Z@3xLW_m zhlLzAIrVWmz6ZnqR5|2fNU5Hh$LHw%MUSIhb&OFnTg$7u9|2H<35%reI^+ZHzjjVyC^rz=-2aRJ@kDQU8zA zS^ZB8&;R@Nn~?3Q37P*x236mbf4Q`qT@SxEz_k6x+O!=!m|U`R88ob|t5eArsP4ik z%H%FL4J~%e8;=?xplQtn;VNkznwMupKD1>lrL{~vygD7o5*>~JrWwk<+f75Yx-Ygj zB^zbN(1ityQI9I{R=BktGLFgEAAP2wRO%kGyi1B;m}<%6TV7~oF8mDNX={K}NtdRM z(b2y()`fp>@WpNC$yk^)rcUXeHXN~sKsw%9#k8yPdB^y*3j+Mf#4!o>7m~vtv@Vv9 zlMFyuYCRKQkY117!lm|V5`~6hqxUut6coOaq|C}Py^)VM@gh!1ga1^T*8HOpBsnCu_q2&$FPmi@BL zBldU8k6Ps2)@5`{-!co9y&P|m4z0s zJx{#a6OmcDL#@khY|q3wx=eHL)s%&igykAoRpF`bWnbgmDhHvQ4h3YIp2xln4DL zJnjPvJgWDTs5xbt((=~5);Ps9uRor-&bgTkCh40hDQRp3sqsbm?BIJZT!1XUR8ISA z*1eR{xDNYx05I3WJ5zf~gBdrT`;6e4jc)=6(shTtdqKThIIJC81-$L+6|>ecZCj>b z&SPLN4iJ1I^AgY&xmC1}4Yb95c&Qk_V`VL%lz8P@h-!2s8xle9?RHEBH%b}3=(?Eh zlq^66xv-}?dcHIEZt9G)v+?2IDNy)uws^eur-6&$t3pUH^4Aj&F^B%lEBpLm>lUd! z%0=wDLtJ?kV^l`|nq9&qEXgl~=fCzpGTR4kPg%Z`t7w!Yb{w{?r+yJ_j3u4nI0YjB8E9leE@DFnzpCzS{Tc1X{aG-Pm?dV_ETbva!GI34mb694G-MU`FT1zRk(Y! zBz2N|NW7A4=zCklPvk8tvZrVLy`d!Xio8T>g7z9jM`(lz0g74SYvj^g(vNtSjhngD zZKrP2d55FVVB9A7Vi1+$Af0kxj)2nl>CZ*MZP)%0ex}!$l}6}VVd(iooK`2sd+jiI zKHIg_x_b9N>vxn&it*_OZ-=J*$sm0VKR5_gT1=DFPaonK5v#jXzeY-5n0@Yb!4QTD^N|e}>LgRaxFmyhi^&tiHw=*e|q&Z0N z`XCp1P(miT<8WBh=zeMOPnasJ`effb?5t-4M9t{w2;Ne z);nN*>@cKswCTr`z&2(jrPwqJ0S@j<1gRwRFx>>fE!)3y{qCXPo7)CGq*20aQ4N#F z2!-VOiS3I{B-P^%dZ62$&*%who2>sCa=jfemM}1nB89%dPQ+Vp15E*{;vsc>k()X5 z7FHpeoc0AWPUVqPn+LYU(BjI0n^8-*905}vdAIJcNvxIVg=f5R@V{W-qqg^olZZTN zf};f7n0F*SNx$&V!Jq=@WP4JYFk@h8B~396cEr%eX{tr5Hea>i220qpITw#*aMU7x zK}>^-RLLbTvMW@>sxoEB@6dBF1v5aiM%3T+!@(n3zh6vV6Q(l zbvEp_rGt?7%2wk=BA&rTP(o@iWupckzOz!IuDTIfVt;|+H-%uIl*vglHEc#ef*U7d z*-+4zgBtx#8IEI)wY!50*Xy*k0`nac@v0ir#h`z}D!*+3q~JI(T_KarunhG0Bw9y@ z;h6t)z-U+);+>z_dHIuULG6rMxwq5M5Xb2LfQ|Ju=Q6(sb5ByS*suGuV$LBU6Vlt5 zcz4=1(3;{`%~tpXZtPrh%$Tf3D$)MqfnuHXY%75(}vd03(W`LlSx_R zS=E5UH4icSCykIeV=q@M@@Fi)lA3;s&vvAWPlKA>%qZ$P*lJ^|reH`d3Hno6Nitvy zo9~SoX;_(QeD*?Qs54|5Y$_yrj2t#eX%SgC#;^L57{&Dxw~m3mPQsC7p{%&MUw1A% zQ#NZNz<>R6?XPk6+Zbi7E5+3P?QUdNmQ%=N5U8DiI9Aq(z~d`j-kd9i-L9K<+-CQg zS9e^|cz`x`6bfb)%U=--#wiVY!DDE)CHi*k3(~p-RYJ2*1P1uK>Q|&CwayW%mWkOF z4@j^BRW(VKkG=rx*FYb8wCv^lLI2%b#g#@jO%7+v3CIzefHlIv=%)yK>b@Lmv9BX^ zCS#9dP~a(41CWaO2LTZP<*aSmQb(O*nIJ6gXFkwU7cpq~Ng3#tbRyvWM$ocQGE6@M zl&Vou%(Fba-AlQnQz@k|YCq;}BJz^v;xX;uQ%QA>YnjDhJBucpP=6CS+}Qg)xqo^W zp_sZl=vkFnghQdh-O`(Yw%;LicMyM*`<|Y%|5=s(^K5KN(*_}Fq zSH-*bm*kTfj?~f_;D|Xc^6tzPYiPvH*?GSr=G|-_JdQeCqIJ2?K+)08ZL}S`ar>~L zxC%!4_>p+LeG?{#;;8hzQotC4Ac{(L&1topEOyc5{MGp3Rl|??eMY22@H_td(_xZO zW;Gxz7ZREM6lljlzm~Km0S=m!gS{=dyaKtpv*|pjUJLzlmQ7FKIEv{#O?mM!7Cx2! z_4}%YIl9XJLh<{A#;$)Jo-yI#3yR+3HMXf&oja&3k^&u);S~ts0@VN=XEn(oXx=Lt zbpc3&j8Wr|$K`{9Pk2@Fj;B+VHP^`wbI*ZzCO{o)TX9?GzdnSMInwX8-}cr3#ewB} z^Qbdv>Tv3zwYMmrpd1=gfVw@f4~OG)bJ%j2tPD1iyz`-c6wvCpn1AqpHWylYEgO48 zmV@f&+*Y6+>zhhl*W2?X1wu6Tt#r2ePv&CPlcjKW_LR5%y2cE@k%`nh>faYr;l!0Z zD1YrMNq%*Q!5v?x&1Lpyq%MZ<-83hyaoRukp7Ae}TszoW_*Lyhrlfudg6l1nFnoJi zKZY5#I{o#U(~h27UEN!Z`cQYbD`cD0D_;P?Jn<#M16%36R1NYQ&rRxT#=bw4*ZU9` z4-UWefjxc8!(Nw^#*Bv!8b}Vx+KshumTgsagp(Me8fudRWQPQteGeHsbE8VKJ$h&= z1yNr$q3>*hU~O+J{g8Y}92qtbwc-k#h(wW(Zjqs$jI(Z!#7cx`MyZ{22<3Oz$- zZx?8evr^!yy2sv#*w{WS*L>Zy)uvX4C(!4t1?Zo*Poo87Uez4XiRKY>AQ=dH+|A@z z3095+j)rqAA0?Enl+Xsnwx#DSi8c93CSDzxm`c>mN1@$nXl`oT-S#vOPi9+lExFHb zS}>tG%qTh(2cYt<$d)v{01)P>XMtM?PjW1yXiZes=$IQqUgb%~GBdH}KeC{N1{WSE zjUtH_Z;uO^2*NJIi<&Di`}0HAnpgY3a{juuZfB3%x72%kR8lLsQVgrS8V%|;wS@)? zM$%ZAtZ<6LtmuUlH+CBv5rxxKxX(WXdnj;1HqIQq`2*!&UMYpN$SV=|1=W-d1}|_1 zDJQO^$iF|`6xr=6tsX`C-`BFIqOb18MSCPkYQIFF!`4xFEf!{}eI!A5_6KID`jU*wPT96ur6^#@c`i0*L-%(S(s zTX*fUZS;s29j8K%YWz3n=B*&bGC~&`I`=^18nyFf+riWj@*P&8313Uz0P}8D4I&_> z%rg1m8&4q}^;C$1g&ZIf!%e}4cpR=Cs|EP+5Yz|HZLGJ=sDMOC>I`CORoALWXQtq z)ZOF+_|IbRC>v`M%q15!Qz4hU1k`p{{{+b9Ka_p7laCH7Re`m|3A~{Kgn^t)G7)j5 zXoDS(^YFy?B6&`g=I}wTFt+uzBuV|6x=~_Yynz5E!f4_|gM|wLf9WYe2O$V~D6Vpq zebvn29GVWtNt%|V!b-)uy@GFc0SGy|EA%#D35QvOqX@nQRy)8E#7i-*h$8>@oL5GZ zxX7MScIxUt{{u*wHL96c-Ht(Ar04FGrMq~kppsSqn?QpX zT+{Zp97LEl7d7$)CA%9SGtOr!gcl~60>>MW!~&0K@G3El-)+GLZR3}WofK6fT_MR? zE+0zql;egG*kN#Z=;Bri1UZGHsLSw|x2xlTiTN`dYciLhjgd=`E!cEyUelL7yUvkp zzTD}N%KI2l>qhMbWdcRfuYtmz0=IJ0yZce1kozmr$<(@?=2siW$;a=-BcyRQ?p(dF zi6~nS$~qsFN*iA?u8F4_cQNcT6e4|8d_gUj9_9W zuNfK-m}HqfjQscucN~&FClwZX?O&Og`6w8f=6b z@`1Gw%jheCXTfs>ou+haXHlTr996!-dZcn*p6zn2V|_>OWGiZPY!c@H*Pv%Z=@nc( zPSIVlb9A~H_xac0ILb#j%v{(%b}^xF;zu`HHQY->MV0DK9=N4OS%v=}V{aMNX4q{3 z;>F$FwYXC>XoD7tyB3$?F2xB@tWXG62<}p}IH9z-7l*W@G+2s5fyvC8d+)3}-lttv#QazT)1<`5!am(e?If5z!Z84%Kg~f6^{J9okB+AgA zG4VK5wlM=fbw8va(lK46FyKbGs`C<^1%RH(gQ|l6i6=Ua9 z+$a>SMIBUC&|;DK;~?;dbm4XK=p4*@$1mXG+|9vvqc?_>!Udzy6mfH3NQx(lu38%2 z|g>S^$b*wK2$To<38w zi~7=Zw6G+>JsRrf-^?%hBXg_h-62YHL-^LMmXvEQ__lM!M_JdAu#(a$zqwi84A0e9 zk*z8O#!Qpt@R1_Db(s+B-$j56>v!4AT(P69iQZQ8b>4vV#Q7qaj$fC`w@6mJIx^{w zjX64bMjUzOzneBL-;*}(tx34JcB)OXC(0^^P;-#pqGT9v;`G?D9KOxODkr9=)?0zd zcKToJiyYWI+yo4hl#1^b*b2AY&Y(X+i(QW_FR<_xir;{7HOx#j1KDt~8RT)%A~$wX ziheY)WF*C~-OMxBIL*r3+h}PKTg`{7NAIMa!5vt_5J?t!7zTD*y(P}mw>Q+uc7q5% z6#w(EDvq{WsyNWH_!{^ll!r3Erhv4znxP_#yv(?1=lfx*o1orXJ6fS=Vp3e!_g_yE zoHJ~i1)4`m9dL5K-LMuMzczIIEqzwuLzHRnMU-noi@WZbj)Gs%V>Pr-ipwR}vMe{& z=*DP~zQ4N%)N@F>r;7SsuS&@eB=FzwQ;;Sc%#C$hCogjWhjFK8=T2B^`Xs$ci{dEPtN?Lrf9-?ty2 zpk`W2FkXN~@tcCzl+tQV#v^%Xhb)8OGn8!{Qc%SV_)@-9s!I<-^&%j(u~8%dr>}f8 zJWjz8c%wEq=WN3US!dig+z+3(us3J2!MloB3#P4g(TCINSBGMXEBRta|CbhE^h)uR zF=CAo+RN}v3Bu_MBc>ib=)hsiieW(c++>tMb`+1$FiIhEuuBOqAveHZn?l2}KNy_H z8$Tw~w!2P6rvumb={x5|fB>orc{HMjUostQM5wU}#Ge+@izO-i8G@*jVxI4$ zSGA&Z767WQmpwf)O&)&d8@rpe-7-SNEX>zM^`GWZLsNfLM;w@5#E2FU4588o`HuDu z@3uB8V?0U31F5vDAX}fLV$S_fZ`V08na7hT&T6emf5RXQ7Is6Bd}O4fRE#cOKo#s% zkdN#6=WYd@h^JoxFpT^g^L5v}VecLVhERp-h^JVU_4GLF#y4+Pn>^ajSzCS5=gn%k zSDe>cW#`-IuU%R>INmpP{(Y1jbZk+4+?tq5mT0MQGO+8CvQ*dK1;oh!d|qRqtbWyiDUi?3nNqb^ENJ7{co?A?^jQm|Aza%|Cr3pa}H5;&%E}%26LyRLc}ed4Fwso+1jk~uA}1m9Epw=Ewx4S%lnt>XMRDRaW1JamVqJ$RiHTOI!~ z&>90Hq^hHxB=e0P<-3p+wT_kHd6{MtD(@gkp@6~bQWDVbi&zbT=OTR80ygMsF)g=PXoS+44%lmMcj^0>3~vijukHgE=@b9r=rQ2Pn~ag!uT%@N~mEYmote zkdH_;M}+;ByeQ!8ca1Hml~$)A_SieUv{dNkA(I68QCOjxe`|qQf0hX`c6>}2IS)eSvV}=kP4kMc)>A{89!RMzxjnZDf~~_M4&m`HTaOxU zgx44Uy}0IBMb_26`hZF3=mx*!C^!95-O61linh7qNjv;}jO;-~#gP5OO5q~sI}!t+ zoo=h{Y(81n#!XM(13nv82j36hETEgUj<3#3vn>&%xU_NXq#T&SVI5mfj)0Aob!a2L zn97Qz&p4&4>qSIpYD(;ih4KPD8X^$onV1WirivbQN@aNeTqQ)|GCV>`d-tHSjvp|gyGy`<_Ge`%!E zMOxrN$l+eY=xiy6$%T90$i_wizo~1wcfnaiDxP2L!DySJ;TOURXU{`#YsW6{?x4hZ zyVij7PSkGV%vp(5)w7$sOUammj;qm$H}a_JOG$6#wdkZcR~EYH7Ae{l0>`^cV}s;h zPy7WHsq3FOczP>wDeprQzvLC7a02lo9PC=EuwX%6V-lG>nW3!1DbR6nim7XDH<)%G zEfe^A!VUTkW0NF5YUJkdtA8uMg4SclkOi)21X;5AN=cn_mrLmoP>IX4iNgUe0-Ijg zhJm1BiT){V*z8a_`%TkJaKP==BQ-o|_tIUA+7Y;J#W|t-ImskDYh1k?o$l0_pYEDy zoyV#GZn`=#*72tB9w-3av+<(0sD@LTb!o+Q%=m}x_42pqA?%HZWTiPmcqSgC>C*hf ze#=Cz!U&c-f|-Fat7E~Hrg>bcBe5KNxq!0{c(u|K(?g+=R@BObinZ#p#hHb4`;myI)-Tf7LP|e;rOi z`DrjXG=~r3=<2)c_9gG;cNfwWS6t}q!ZJizQ8z4T<-&67>70HTGRgJ z{p9|hul?q>lY%lgg%%#x5P99|i_F45S7EDV$2bA;ZMxmYb}659yA?#fwKM_yd$-4W z(p<-i$Ud^~YtbC&>0SnZvE1vEHeJh_guEx)!$-5x5{u2Qb)ijPNIu7o)(hQYZZNlO0@siN0OBM@vSVCuoXwVkg)h6<%TH<79P- z*d=hxA?g3@86=rFDKfB_l+1&(PfwXuDZVbUN8a2eaI}gP_fi5p2f4f3r>f!>fSiy1 z-jmX*ctk31kch8~$M{vVVadSvCUH3@aq-nSzF&H$f9Hytp(Ri;Q%-h`|BEMmD4zj0 zi&lzI+;i!2Fq#(86VZ_c(VEmQgz!O4!r}Iyaia1V#M`tCkX$Sw0Gq9<_`Kk2O&TeY zlx87fwFqZt=M){SG?N}3g97PzZ@+&>tMM+$XaX_P%jc(_=!_Q|RM4&Tg~U@Tjn{<4 zpj0>K*TBHwkNvB#(etYiZ+kB>Ob=YPEcZ>bB>y6j0pit-WGb8(OsrEjzi==Dh((eQ z3a)0};BLZfZkE0|?(>kJm&`aG^3v`6xFW#zhT%lsL-G%AXbHR!Nk$<*7bwRk z^8UvWYE-kkuXp$jK)F;1({|?;t&uX-LCVI*m1tdpsw3MowTWgmDicji&(<kO(2RRvC$V^{LK}XGp?;(cmbYGrJbeNni4M1Khu0$22S7BITE;_Y% z0SCJLN<5-b-oel|H?KBgcoM~y<kvgE@K-9)1EDM856h^XMrTtm4FZjot6wYfm0yC|(hl84iQER8>>`!*OSMy?l*dSVv2o^;hEjq9 z&3Bh{Z!Q=qQZn*UJC+jwo~k1q9}-5cy!D&08D|wZ{>gJXa$qxJV6EmEroMWM5i z*K{1jOXzB?U%VidnLL|5roK16Ww+Nc*a6aQ6#C}R$QmTmY;Sv?ow$q!UM|A$ieDm> zb+%zns<^zOBjqwOko5hy8rN5~G~E*z8B@)>jckj<2Z2>1CdajIoV{SI*+G9sCr+ z8+w*3;^=KeZ)j}H`yG!jQHyWB1{oQ^EZ#<2pxyuKdW3d_o( zz=ve@WZvC;TDP<&@C`kpO6{eGniB1{X>r<%JFo~ft!|iN7jLHn_~>Dp+RNfTGTALo zV#c_ZPL_Fti?n7Y;>=)az>qrRGxLYDkx~-D*>cj6v`Tphr_}4Nd);@2FB?37vFGAa zTXIhrmu?Lc%B#;ipkd2)s(fx0tzb%bP&!`R(zag!ttOy77~k0Z>>8y)y}Ga-UdK>4 z-h#@}!a~wyg`w`^8_rBRv*+OG6jR{kmBRrdoELMJ~R8NF?Evhsp(29*0oWJvmY z->Z*!k4;rYs`5_HmJSd!@#?nEk>`K!hXW|Ja!?PSYjKNz_O#S}VES?0*ar{|Nj0%j zbkE#*xK5B_KMh8EtFW5tlJ3ZFA{_mRo1RIT?xDvo$vM^qwAzAx!JWVEquFzyi+kj) zU{47$&{}*l>6n0+%GQqO58hDsXCWls%`4d?^PPt89i*jl#h@t+yGl>*Ce zx9fY8xd(qTT9z3kP43@{m2vsU1(r;Uu&Fs_=$Zl0uAN?oNA?XT&Cbfqui5nepk#*> z-s6(#7fn$)8@GNugpG>QbqpO8PHCS)l@1g$wFC)VOXaQef5U0<747d76;3xo5z%Uf%G?Z zB&V3*k3<;&phRHA2X7J2Gtmrp)tH?k((sw^5aE!`@1J%9pRv(*lIt0HOnYFFl7iLM zwFc{+w{Ua3Cz+4HKSA7n#QZp)-J|9pm9(5Na#=N!loXKLjuGxPqs20r*?-oT~I>PYx;g}YB#^O{U_B*k#-#rMqv_+k-W5eHRE5k7DQp{*g;uMl%# z)=#fCgl4+DjU7}qDynK(^X_tPk8bI4?I?V@%oc+Y_+5Qe3|Xan^BL`aS#sG>m9wYz z6&3AR26xrS`cRfq8xYf135^2>J`s=$w1z*yay_Z3i|pe=M8^3Z42Cz`v3-@3K;i%e z;mm6MRFXWwV2{#N2BgiRhVif()%}FmeCVM%0+No!eNiJl$8@TQh6Mk(jg$TfWsTL| zC6Ig<@Dsm8(Q;#8e-jQ|1cbgYrP0|D)&FIyyf*vRZv?p@E~hYEx^|Q-t_L#}I&f_W z9&X0N)xa$kwr=2n!e*|$@9~U{=fG(QpH9Pw>GPiA>wH#f4GZjAO3LN%1E6 z>BvZT&4B@u`HR_EI{Du_w03`g99?-B>47J|73RTJO;$>q%IE)42|Z=} zWs5K|d0j$aZXP}GH)8VJ-FFY!=Kq+mAbBHo8E&E$9?*L}zPU`C2MG>lBa8Q>WW1lt z)oOtPN4(<*_d#fWwKxtiO|}C@&|rn@|297tLz1iV$dqe+7^Nk~#dK$c#(%TqEaH^R zJwYKwer-3S)u_`)uA4knu#c@*_X;@kTU(GLL%^P?@f{msH9ru#HhxhXBL{iRrT4*| z{9G5H!zi#IN#N>LD@;`f@EcjI`e;=1#}GD`AtOv$iHH0Ri0Nd0DDbT>LB_IUF$!Tm zUOu2;=}jV9*}MsV3}er?yHTiS@>HSXTmxn|wb@0wuO9ar$hQdGzdWYCHuXRw>&aiZ zs?4ns_)>$H_*(_nZt?Za<22P}`4CB|{^l&Aw}9e-96vkpr9iAg`B9UUWR$+w!&}#R z{SWi`e1Z6AGsi=R@ycoiRo6@#Wcl7dD+^r$o zczjgRdP2e#Sk+fsNA!Bq2+eoKMyiJN*5=gUqpI9^%DDN!jlhJRFX<1)ZYf4DR?A+e zwl?HkO04k3ezh z>rXIoE>4PQtsw?rWWL{To5KM0s!f4z(E!|-EHJvUd0APgk^3ZH5TYu+lUlOzWuURx z!s?4>rwUItriJ(8GMT#%;Ij_93JX+^<^1oD3@Aiy;u3$KTD^Rp7}*KydG=w_B2Dd6 z0Xo6Lzdqmdrf~FkB!z~a;r_kU(UWc*5O z?Q|eTW+BNj$xp|lMAaw{G~mfU?P01!FJYX*1N`6tOmDUs4`Z1|_fmSBx`=1CTgucB zNXl-&5*QNR1zC9+uoX{WudZ4!0jBs?;|TV@S!F?4@7U~kBCotBIxhoULuWAXQe=73 zAwRpDSYA<`M;I9H-fkLgMCv$L+LaF1nvyk!m;G!x-LZm2v3Q`)X{n#gwY&qOst}$| z+A`w@*sO*V@DMZ=;i#LxUH=7PaG~Tni0O!*QncC+i|+JtXyb`NHS-d57m7AJGAtad zq8t%M-+uQn^<<(>$5m0`D#aT??m@LzGhWx|w0Ae_BrGMq{++`Q%Q$GheU_qivis`r zuvOrvvQTp>dLVuSE;9U!SBNctC*Xw|qZArrU+f}*rsF)_J9v=ZyG;Wzw-`+$YMCy- zf5b@?t63EEE7*FH#;8Ju4a-C~p(qk8-DjLmVGY|%r{#H3(Tz!ad~7u&LO=I51@)8< z#yTGv3h@o`JG>e)-NfWei~VVFGTl-m6$rC)Zlw@wBzRnfC)frf#ev`;6Y8)m{%V6i z-Pc=35;oS2^9ziM;Ad97S@);63;rY4XC*mXmB~(UDr^6(*WmZHx$&3&7Pe;@`AE1C z30snSTNQL!ab?uodhgumo%o(XBy%!h)@*T?E{Ih8>j|ky zQ$I5wT+_6t&uy`+2;o{Q{r|~J0<-l`vd-<6CjTo|g#VyUmL!wisWeeha)};O!*$wd zfSoGNJ41n73o*TReo8qp-+zlNN);?TwBnBN&5?LWZcH}veV0M%yj`_6iQ^WArj#Rz zD(-v3GB(U9Z|l*!czTJmcW)du&cr`=%;5uYp^I)@bGg_`?WA!e1>XS`S{gEv6=(5i zK(00Uw_h56ybkIm{LS;dIX&myn+tP^)yh=>uP?X6PZlL65uFbtS*p08*7M;}*;($k zveYNc-u z*$RL5M#Y`meYx(T{gRo0a3w_KIErqFY$qnr5Q%3q0%wMejMW%q8|t zy(AnuQ=rdB$xbSPTJD8~YmB-!ss0$wKVSjtWZ|k30newzYLB;Naru7881YZ8&H>Aw zQ#K0%`IasQqRw1t5+`DMGG-s*VLhYDI14}aDG^)YgJwC5%*1}6nF^J1$ysy+BgWU) z9L{Pde)D)XmKu)pH)|`suW7Z@KM=+#Vnqq@Rp3d`-H&0w4SlQRU za>Le@G39zgkxe<&D}-FuZCLhFXcnv%+Q+0Y5k-BmV(m-@6n}4vR!!HWoTRAGlZ?Ix zaxH;QK)fqMiH4`oyl11f%AQj>>B|_hux6i1WVz)W&V_*|~ z;{MU)-A=?qDgt@CSH&poid8VB-?Ua$6NkNQtQl-OTq+}h)K_jI zO4cfD^JKM*TyyJne-t6Hu+BHdWV(5xvQk10{owjSKLi`r>jamMV;OpAUl_t}8k8M0 zBkq2F<^HbO=Gd>YN0g8P=T1*tZyxJw@=mWqyQQ(a7FR1fV{f)3Y?R{9gL?FW2MhD8 z=eLV(Re@N9wZv&-Q7X}5=kvKBnCDu1kQBq>H6_f!Rv+a>hi*5x;ZX3LL4RTr*?Y*; zcq&nv?i-?|0Ut);to^->-N#-m@Tp&(qPmIKl+R)YPKGR=A!1XZDtzh2IV+jnAL=B_ zzvqpuHggF5ds2wd`0uQGoHAI)vkcHfUm-kpBLHg zT>xt;nXI0QaPM2+P+Gx;z<)M9T28eM8azkEDJU+4(lBDhWvi@7!uzvm zie`L_I2}d3vVJsCPE3T)rl)e&n&)48m=2ui(b#bHj_~aDUJ4Kp zHF8CTC6~SchXqK?@cqi98u|2uQCBx)+I+Q{D4gqk08Yb`P#4pmG_y>ebOPdA9XnV@ zK3x@3wCUwDudarF&9&kZQP{U z(IjV=H}KyL>CSa#^goc%ixDpWi4hR*d+2xMLylWx6MjUPx9A-B?|c9L+)k&zMa_AJ zMW`MGi%Yi3W9D>z4%ntL_G~C;uWF85dIKjMSW7;P^j8^k8g+v55sXK^D0IzuSw+g? z(q4BtRCJ%r1&Zh3~ds*p-caLsd1p)@OmFF6|AK zqT221&&f$4$%*D@A;Ep4K??igTuyY-3>pNDWi+BOK>UG{56Wy@kLRn>Xfe8wGc`Wv z`ns~7Ji}iY&3-e_Xr)yq#jQ1Wt7o5;{#fJwFD(Gtd?k2+-f;&fM0%Fu4O6o}+L`S@ zI1yTifBX1^uqL6zPCNk^IzCa%IreR+ zHB(Sir;GcOX(~?jr{WDVvw}d!IwpuEMh$TM!7`7&t4}5==pla8*$LDCESBQZic}$dPKat`ReSJdTbx*}yd#V&A`&I!u{6SgEEf78KZ_ReJqFq-L@{e5M!Br8?DU0E^ z4H*Xigv$8Yp@(4ZciA5ay_-=mHc+FQTq!!k?Sm+t_SCi&muP-%QYQ}AN44O3dPJDE zSGt?k#1oA&QrI>kkeN{ z0GDb52x=ka{A_6MpPaQroRe6$wU0-CB-Q=!eavhU^)p~H;@N0;(TZ+S1C2iBM)h##d2nr$m1xl4&2M*^ zCQ|=z)xiI#2p;%zN#@$y9_4@aWanMxo0gcODz3-`(*M)~=3m}l>x0o8LDrRm*jl1I zX3L!i9l3sBU-|2Ectg>=^)`B%L|5A!Xk{Vwuh(zk_tom(-oGaY;_B(w)@LItP_6ku zWGBoiyL142s+r0Wa(I9A1H$NTbRj<~=I=#t8UpEm1vXKlQX0*}Li`1k)J0GfE> zHd?vM;BTD2z};L4F-zi)$ji&Z#W`kT!FbXdn&ip&ZH9ErxR~err@^KkR$dON3nZnP zA@Wu?a?IjD;<$C~L4K}Riy=fSd%kW+9oLTJM4d@3w7BT3ZyyZuP5UH2*VC6WbM#(B z94gzJkg~HY8?|M<7kB^sT*CWGKrh_=9*6 z)uV4hw5CU+7JWal0Cwr4dqLn`Q%d}BSr9D5XH1dfnQmV@0gwjwsrRWT)8VW-BZ$6|6_QhSgl|>*{u; zC@oaK(b@8jgOknN6D)zY{~jOlS3+&Xd*|PxYPMaJvA}VT;aiJ?awfmdk1bUwNFK%G z`yb?(e{z4*FN&rYbO#7T)r;{KoDqM2QrFm|K;lS2^$-67h97iwEPJfq5MIk@qG{UJKMIHXpcnC^cKiT=d>y7Nx@~+dGREotpsS>R?V*#<<5Li z&78O9i9Q-{YDds`cyxK^uf3)7FjO-g1wM;NPVsthb>wH*-#p(IUl2nRIT=}fx{Au| z>S`74e>NaLF6k;k%#N!;HX5$?D82#LgAKcSVpRepT}BQ! z_k$QV&MuE#peChqX7F-j0J?x4QQD;4xrcLkD&`e;!USTuq!*26k#4 zQ)u0~SiCfY&o9b%66D@YN9mef-fUO9=Zft!vsB?nXyo=UOBGreWBwDp!1T^Dsd{`1K5*a7I?Qcs z(4eh|BL3CPHw)e(owl||$6UCH$%?IQDDz_`-+y5IqF%v+tZ2uvp0L5M#n^AYIvJQ^ zJ5r^mC(^Wvh)n-hO{o&Py*{qfFq#UP3+nJBCIzv$4%CgM6gPv1j7^}OK8Yg%FEK4@X^d|_4 z9Kod|pC}6S=3{+~Xh2fWI{-=+&>oyx15#=O4*IO_W{4UJsP*p~e^@R=dM&!5_PKS{ z*Gim{^1P|sDmTFJ-|-N)_2!}n+q&TTS`fWca13Tats$;|IwJWmcv z@l;{b1)=m`y?o`hEK!f-6Yg&O?+Ipg#kkSu;{$`KNd68+`zK7wG^O-DUu*b8KqQC_ z`;%)}Q#%`kz~88H!g4%gzK+MfU@Lo0(6l@(qXADPHK4%{zQ5Ua^f|k~&P4kpx}Z8$ zRgT@XV*dToBoEo67x4Az*C8mDP`>r^n06Qaq-t3cFyj1#7|r*K_1@s)qa)+$^wrRzu*v8Vv%DM=C}^WWor{SJY1+m;lA2-Vu?H7U4AHkRm~!ePSYb0&KiW$ zN;%~vB$}k^R%pX&4aqG$q>6E|q~up18s$_c&9ydD@t?rcZMq7p#AknHb6PuCcyfX4 zfpl@B%FiuXFu27l2qz}RaIyzbMI@oq=x5)Gb;RP5a5O8dY=g$32Ud;f>i)$rj=za3p z-rgtpIE}IFD@MMO;P9^F8a*d4WI!#z(b(O}$3bDBr}ekyJGjwzFa68XmIiTd2GDx{ zk7fh6aU3r=lV>5qP~B0_A{k@N^WydvgCuq*ipsC;>9)@_Vo;xiN337esKAoN)suw; z&lV9X=y7rt!VcSqFpy%b4VhD?>V9)BpL<=1FmX$GI=@f;P~0$DTNLs6_ z!n10CkU~zZqwx>}V6ONfq}c9Pu?jqP*_g zAS!BD_ePm$5xuONuAAfS++WoeJS)74t6Mq~5;?e?BaTl^cNtg-Wp2kFqqcZ?Bux~g zyXh0>|66Wk&VmGnb~^n}{-WAnk^Zihxu|Z4p)M08Ia?1obxZwf4lP%0IlMrw?fagv zxt-V?)AxT#tD17Nt`Kq>d&F=}N?8qNkq2Wl?5&&hi!3#p5aEAZ!A7myn^}!3g&3p` zE;g7*qFAN1MfpH`DJ9f>QQZ!BskLeJ;;jGXZ$ySmgrx96EzSb-`@H{(%j$0~UH{G7 z{f8feac{H#tFror5@gN}H#}+mM@;HlD2Y0rpoPGav5t}DviKEQa;>T=0Er?9jgTJ3 z<#g(`l`$sx;Xo%mbPzXzja^@zY#>+pFEl$^9#<~9wB-y6Ma2oH_mgIXk-&0~kgZ9fyj;=P)rqu^V3W{R3N21Vb80DaXuP3F@3y@CrM& zOf45HHwg0Cr!e)^`**D(Gph5KMPYi9c-yMaTY^wj>Z+;0$!XFkwmv*6>LA{WkqCe$ zWWVnLdEJvoT7zzdOLY}-;=RgVHn=(c}H(#Xbn& z8sqHACO>JCrb1Bzv3Cs!9`6^G@uVErdoqOJ`kyE#w(gWm zbyM8^#Xba!@3+=UeAXQ{8@Df@<>JBJxM9yr!%;z7YvPYk=Tj&p7R)Tp#egh;A35Xg zDoa-A6Uafy_g9z9;UhFra{Lz+_80Eul!gT}b$opD!UI)#`<2D>a`GkN5v&nMhho0? z1|!Q=ZZPn>3W<_lAyIP@Z6eR4+imeW-;eGn3n7QFtWt5v!IC`7V#&?!*zBYe03Tov z9jK|t@NmDc60$FbBk_m*BP9Z31C2zXG#E9%J6HQ~>U)27^bVBLs?g657A}6B*&5^h zg;F#sPpV7zQLO~VmJW`s%a%Oz)(3uqEmg5nANn$%qEs7w&5obewg&bnAx3902Eup3 z%caUXC2hG-2|Z!~pltu(k1`g)=MeM6Gcj`mR$pCKEWNic0y!QZ5kw=VU1%{Z9WD`m z##*`R=vm~8;L=59RmOIS>JyX~4S-##*dkzb4EMJlzTW$`nNf=g1hSS1NwgQg8kllf z2jzlzr(dam+aoN^K)@i<7rYAI*8*0@FgfB{KbhjgC}P7pZ0caBmVVASe1byh`)YHr zaQ0v35fKbzo_rj_mrwN`HlTAooD7q!_gVB!rh9H>MO{oTZ$ z-us?b_uu9yWTF-#>0MygXgkGlHfyLxiS(vgy_h$%QG!m6(4IRmk*BRqe=af_(16K& z@olf0TjJtyCxH`Rn4O`&KkJvg@Q&vqbXi3d+`OFqY;L?cJ1R3D92>tm?ogVH7bywB z@Ggp@7>__poZQz5bWV4aXj#E0#lRFb=0PCUUiurC8~l+q_5l+LDR9;3;kd-A+i<@H z^37dy=yeD;x~H$MwnBR+9p0jEy*K#u;eLgKd+>+)balX{myxK@)pLy{V^PQAbeIR| zi#bl61EVJMyN9abs@jlZ)I5*gU?+6pF|XweyO6snPuF@pF!4l`E-mBE&?BX`VUdBdRdue;g* zI|DU5N&Y9AZ?FcjmD=k3p4?K*BRwa*A&;f9bpZRmCOQQfoy6AA z)z|up0kS z7E9VibYr7lB{7ZpowtZ~1VCrpinQg(# z1lA+ozU`YxGEx4unnTeiD^o6zpZo-Vqs_mD%3axrc3YUGnAWi=6{@I4>Cu-4dY}+W z(gJwndF=fG(l@r-;@pE7Bl_PBA)052w*CqD9b`aq{*L--!c^Mx=Jv+7WImt0=}kX>DqZWwB}XNtr&?HK=Ya>KuqyaI ztrGq}8pwEKV!%-WwDpKzoJO3J%^Wx2b!Xa-CcWfVfY@OG{@#ZVEPG zI#A>Td|K&5)w!I`)W$WTs`mCyk(LvumjoSM9MH`|bgjK1(BP_rqB2{Ww56657++kB z{)^-ZncWEnUuzkaGZ3DtI@h-DNSqJM>x0rR&tihLY%$|#x=H_ZBZ%tS>~bD`YsxH(^V_DD!a&~1vn!Q*DdMV@9g#WcPK5$ANO>o%X{a7 zvyv%8Os2=AgzwH$gyY{K?;N;dm7&Sr60Y}dNSaUnVFvwE|Gw7=Ay15TD8qyMhO1R4 zpwzJiAs_CVc_lLa%emwswANnqo3=h{@|Sx^LKaGETNJWbmzsoFbeew^H)F?y(soPu zF-Ar8?oQ0k@7^GhYE>V8&`MO>Vc*GqK6URpz#2?aP4a&+)R#-!-60cSFfgXkdE4V1 zgnH?65hycEKQT|8dtcSNI4Uln8uM5Q7-o){YRSYS8pZSRsNi~ zr$^shWx%IJ=yER<1>|#cJuzOUgevRgQQ&s7x9`?696k=gCpd(*;+@njxx=vQCY&m3 z>$21J6w!{^vxMxjG_HB7vdl(nA31X=e^1u@{GzF)VZ!E^%JR`Px6mlDp_8}MiDI^H zse5Zhf?ME7N|HeZr5na#R};&Hh98-5U7K5LH2}w5M!es)c={5y%)GS(Uwevq@?#@x z9XnGWWG#{iAaCdpHdA{v6!>vOc@HA?eRT#oA1mnvbzaP{m`6P)#<@O}(Yg6c36C;z z*VC|&#@5TvnuefQLG_nmxaDQW4ef0Po1c4^P?9Ge4wHt%fERk4719idHK*VG6N8aq ziB*Bkwb~K#W0HHwCG~RyAep~^cG3Afnt!S`&-&-lsJ>5csOK#F4Ga8Zr$ysHK7a*D z)m_Qo6SMSBhX~7v>w`oaiV#-SKTd*`Rt;|mgxmd@^MmXbkL&A+cslUtbODoC#+2Ay z#%X4ywKG!nsqmA_Ug*{R>do6PRRgpluQsmh3w6|yUq+qg7OWojzGqEWZWv?ZwaETE zT>CrVZf&(B>nnjJ;}HrLdPo-dGiz+Uf5J^)RFWy!>uqPm_0uyd7cj&zg=dw|tZIKl z-`w2Q{a*HOfcK9ZI)H?8l`JF1?xgU2h^u|WglTg{&jrgs`1Jj+B;llj5G}7c3ncx< z5*OAdK81|FpIfy5k4)r1Euu8GmUk(B#w+Mnj-0-;c9H`Q5~od1GT` zKH2Kuy42N*QTm~Z!L*5Zf{>oeclM(a@nh%CKNUROS`TsE1!##;O%!@4xID)n_EV^`3Hc_ZgP_Cv3& z+=x?Mqy5cvFu#=fM6KBNGrcUo?Ft4#*wQzEsMvDo?%Wl~Upy@+iIg;AH-LrjK%#fL z7hq0(qs145A{QEptvNqF)aGW#6F1g23ufd3oUO+sKIG)G5$9Sj<`j= zL()D?J-UNWw`44Q%R=@uANT_JbmziJLNW`<>$kU#W!v6>2|<1YKVcaD$!Gh8z}Z?) z#SnSs@TS|kIZ}QI)i<*fd*<1IbQEH}Wvv56Xr#fMch!X0u&Vd9*hJQEd-|^p0@4v) zn5?^5?r@~guH%ze)rrTJXjqRPZ0CoZBrITL@HMGTxcP` zsV2ju6Dnb@ca5jw3(O@IMs||NQ1T5o4}IqAQIyh+%{F@%Xg&T~`A=HaLd3NHhU&}V zKr5mhl*|JEU$u`dI@;r7(F?u(@URk6FdUwXQW1rL0%b|EFVSu1dHT1Tkwn&-9tlc@;ZZjigb4WsiT3T$bvk$<)O@kG z*mt#;mz4a^0^LoF8OM?^z&$KA##`j9ym|+_k%7$g-nV-9dOJ?u0$ZhUCsDC^-Se^lKZ?BnolW21%3Lr9>xqI}X-z$Oebv6&@+X6kB3~4j<{tYtNKvHiX3;-wVia4@ zdXR-XBBTJGXOev#*!X73YlEoUN=|0G8Qw_<80kj)cqI}q`^&cvV9l=qy?Uo|7xW9P zdRAhDC!9}w?5u|$s4}#mTL(n0bJgKL3I0+&YZwgtCHp?_5@A%*g`(Qb|08RVzkdnx?(6nONR|y~a%_NKoCIKB=u3LbwX%n-^-sl>s%$FnYt3$Ll zuf&4_6wRJ7U@x@u%0<{nQx&O4g(%ud5KFO5Q`ac5j1UBaR>;Evpsk$~Klf+yOzb$` zDT2CRm*S(bFj!KX|G2I!5;%?}5}$N_m_zA!vR`3%&LI-<>g&e(He7Mn8i5^7P4{P; z0A6gBgHL{9w7*%Od=K|%Tq>%Bd{tf2co1g+f9PWKLEdPj@mPReQGB)*KbPg#-KgUk z3yLab*7uabT{@76Lk`(V(Z0@u645R9Mh%J6(I?u+k;eJO0q~)H_-wyBLzerBh#vR) zTt6M&lfgvFxqohZSKPk0#Y2ZH5MHXQok2Bk@0Lr_9au_*WCAI!vtDQGTK^w>ePvWz z-MeRSm*NuKDO$W}k>U=;9g0JM;_j}cl;Z9##Wg^nc+uh>T#EbTy)$?2tp9q~>@Qg- z`I4-hv-i)Q=Yh@dwD{v-R&4>^wgKjF&;>jJ;{%>;{_Hb{0iJScYX=z`^`W>bdE}*wKkVRtNXFpU2D*0YDv^iUD7EtvlVia!kgbW}04LmLx_VVlrmi_gOO1MnqZN*h=QV zvj9hPFwbWbq=Xgp+bvK5EvLtdkK7|Ts>{DCk#VSfwzUbNQ1r-^AA|o}g5ZY?@X(m9 z%r>w)pxJuoppD!`#PjNjw`fB)^UVwgS#!X{JqBQ7{2ICEnU(B}GLe1A%)GEDi6FSqv81D4HH?n-dUn2uR?k0&Hm zCj624HD9aT8|P20J@2=nHadi_mxh7Qxbf{H8=|D6;wV(-mp?a~HHYtiJO)TFCtkKU zJE->S(q*9gleC3rYKI#T)_Qhc?LWBif8#u*DI5AN_UPq6hyLSXr^BAvz38Ojj$q^r8@R8<;s9Y>>4RofNTQRBrBfYLdL@b%`(=jpnMzkDJfk7<=u1bxk-LDDzgbNnDn~A&c zzM_M{#AMvf3GW&i(;-v@32nl%qnKP{Vuq%ip0lFvE3t%^-HJz~4wncuE^dR}z0p?`Z`)BZ*3 z{+G9UYFr!sEq>{BC>U)213>ppx>}JSHR*S1MzZcdy$`SuQ9R`cd{iFP6rHgjGpJdv zM?RW)5`ytC4SN4w%PzQ6vloNlbMG9Z*lSHWZU{s|p8J2>3*D6HuM9&=j8T4w{ zp&sszKjRnRCAbYyMFB_%E2XkZA84ayz1yjdFSlWF8B*}eAINdxC5aDrbK6>EQ?<36 zjnpu2DGpeyy_gga=qrV!AMYwE~I@7N9I zD%#p5OOw@=1U&Qv-olcHcbDQl0(D{_{}OSFz>k)nC1c6#g}zm@5n#@pKbB&^sz+J) zS>!pct#pg5k*G+(?fTm1a9MTM&sh!-2RV%(-6wnd=z^)(ogSfl*03l_B`KQl9m|h$ zaEQ?vcBc&m6>R^iwk z>Fdx2Pd!Xqx%m4X=cVCm$BVSQs$!#0Nh~59{X3pd>y8Unlvjs*7`)LLPAu4ZMLCgS zOd=~vCl!Z$-|ILhxpkG?C>uBBbeBwM610Yi7e4bYvY+1Ow%lD$8p8p)eSE_!4xT$* zP8I_%WJF=DyWflN;oPFIeHNN*#7{B$1vJ|BI=i5dzN<%)t=XjqulMx813Le(o!8ag z`IO4U?6M8K&m_in)L!03iIEFf{N9@W*)L%dM_2^KS{WmzrudpWCf8$rQ)^yOCxGqD ziQ}B3bxbHU5hu+z%$;N_@LLFp4E60$!*;e79>$@pD>q!#E_Y~s#i`XS_^$QPPI1GJQj0NB7dIy z59y=WWA-m)DPtH;b}{`BTECUwNP&`zWhJW?RNL zipocktyUXC59w9wi|ohokl-*+qc(VLaxT@Jgv+# zR$DoGy&yDeDf`cro646#CB_uJh4RC;qAp8Wu%`aRM}$h@A@w}z8#y4?g;y_!wQ9fb zmRI#Y-+#tdOF1&Z9Bs6nlv@;@NJ4od4rL79aKXa2V){3Mb>#;s99B>y-vDZd0;(L#Urgf55UQjzY$oJiMd#wghY-^@K_ZIWnV-Gf z+7JP3Of0hL%|?-I$#spmflMaS0V;n}6W!goWxPV3{mMX9?^CaW7KNycNICp~gB7x% z`OHiVRE7(a08eP`rY?8V*2m<=AQb);RMuh5L7atR+$V|d6WDmD0s9zrKeDjIEQ~sc zpZ#9490di-1HcUft69QFg^`QGO1*?y6X!b`k+6X<(+?;(JK?B0j%-rw z%CH{&rXSQJHPD}0aA3v3u%A}w^xhanL%zm@#2(NT#+R<{XI+aG;Pp4Je^a+_pJq#| zldZIt1*`|3iGlNLC%V7o);EjUT*F>?AQzn~`0Wr%!FTVR4Rd4Dlt;d`tBl}TUgc!^ zl>A@vIp<_a{R{7Ui+cP#!xfj7=k-Ob83>FXukAuO27>KyY=F#8H4Dfo%nQ8Q`*C2| z5dQAxr?{WwgMZBTG3K#wi@A}bQ-R;#4g&UV9Zjo{3RPW$8vTM9q<+o|MHm+oFgJu* zXl7Gvy(k5t$hxI6_vP{oQDbqpTmpGQG%ILjQ|N)AS*#;@87Zz&2z->NnDr$xIp#8T zKNw7)>yn;`yl^ zDI<{2Q+XPhAmz94f zu^{=Yr^3TlA~Y$rd;|1l*?=|e?PV$6uu-;PQ?UX!KkqJMfj{Tws)~v6UQv8Iho)XZ zaX{vO?3xHzx-tmsh%og}5*R#W11FuEFLPldKO^b@!9?0KX0oC;59Tqs>WHV{?t$$Z z%T`;=PmdPzh+2&fJ}b`8_Z&n>DZFNCY^v<<^)ua1_@BawH^YQ3aUWS7&B?FefA&ww$k+QdP>m_dhrQPJcObCqD2;&!}G zQ=24pTv@NCL7VTwVAndiS1z4ag83(>l1Mc1&xg!6mPf!qCQSv?lwwTDBjd{qqH|HR zD{UnFn5K{X70ZbPRBEy^&u1*B*=1!tPJ^P9*DXb;9Wwv9o{NYY(Ga+?@!VWrGl+f! z<|+25RcBDfmZKm|xTENzSfI$ZW>M-B>4gmP4%!`3X@~<^MNWqKqLyi=x{CGHJJiuFq_jIlPNGFi%LkOP z%>is-M;Ou9kRcjSjWFev5j~vPpL96?ljexZ^FXru&IXsw~v4~ft zJ13gu6>ZTv9ee&MgYm`ey^-^r2c{$d(In2Oc7RJfI(0buotJNyd6a2jO)_H)94$`A zw3H_cb+M^nZ#o=mIx&mTMiVcQs058|b;xu`p9hc@gd>%b&G@xq4FQ&5DbH-bYuhm!N{GyAT z_5+537YR+PvAPjVz)as*y-vx-_jQDOUxEuiLkkY;jTKRUYWulhBMd&Zh?O5w8@gFB z_pF%4qi+&TMM(e5o<+_TUvu`sp+G#*&1>aBU&}p`V=OuqGX?V+)yXcPI$;$fv^*yl z;{tDwESYMJ-5Fp&+RfcPVU~l>kZ*IsTulAVGD%0FPpyyuUZ#Qs@rNb)ne&1OQ86Oe zxt$7_R)qkT?&4?8q+Cxn*m6kWCU|HS_6>60A=raYBDRx+*k*w}b3H}&Dz7mk8zZZ* zOEaMKhQx}fs6wql&Doy?k56{vZXM>Drm}-Ubc<29jfLJf6`7Qih^bv`V;8Y4C)2O~9paZO(ZtW^#g9hmrKXqe9eU;}x6wGa!dasph}%(cer~)AUlLC8 zEvF8iPmtD(Ir44R10HQhahDh46~n|=xUgjbKO2cI-RnY#qJxg!VF4sDaV+kMoSmkETw5Zg^&qam|QfA{k_8 zM8%JI&5lQpIQNfS?^UeaaLV_Tu z{}#kGbio}zJ(Yh7Z$lPNkG9b)+5ZZnl}Tarb53==gCJHq1ecWsD!w_6ig`HFS%JbJ zPN3Z1^_S%T#5MnZEnZvDXrT2UYgYBpqp_EsYO9JhhTL~4ciJ9&VLH^>w;K*r*%^*6 zr$$M;b`5E8y2w1Egaas7M&7aAzT?-7W7A8a|B!68$cB8|y0Ktw$#1W^ zKDF{_J#+K0_Dp~tVQ@U7Q1&22p3_5wDnkmu-XbYJ^{ z3*Z{$lCWyi?bS7OGSmTnKApkFnUqZ>Y{TBP+F^~b1t2cYSv6*u3ypuAF3xy$cT6so zOO=$o)>44A2Ozajw?yNx;i&ztDMHm5J9er|qYbY?FT%8$(%v0;LLp2pPg9oxHEet| zibjA?>(^=Hks=~R(#l%Es+#@V209GRTyHa-Pp1*BX`s|a{TuVU5zOi_tC&{$6O6j* zh+C^SW2d5NS+I~#1}A+xE6oOCUaF_2ucuqEN%uvK+4|~PeYz#HO*i9L;0Uv%szPws ze93%<(Fli*W@nH7meS*ui;204Z>^KBmV0cBVf-<3Mau!^QVk@+Fkx-I3Sgoja;(C+ zvJ#eB$ZSA$4c&kGXh7ej+Q1u5kV3H>N8vM&xLUPu`eb6V-lxshd848kx}8EoK`&^7 z_D~xlHT0rlCWt7AtOkQHO?1aNFg*y^9@|Fw1pzL~*?y z6c_JZe0|+~L*;@Ux7k9UF*&cJfS}wjs^`b6WZ~@QG>bIfqw`7u@&uo1gZPLcI2u1A zY35S$ExBr`1>56tPh(D|m9MF(pr6~CZyDOC6d1ZN@=>uJ(K@8xADthXN4$)Z19~BU zqHkgI$ZQL|a_L<`(DWVBFo2l4Qb|3LP`0yY&BZeqj%jIf2%Ed5i+^h9VgHj?OZ(*? zVe2{N*xGgD?Grws{5c90f8|Tl&O+)1FHoo3d5vzzS8sI6YX4kf?ejD(cB&Qu? zmSMihKN}7MOe)nHVBd&1u@BD*7>o;1F_)0)h@QBE6VFUdUV5`xK3h zoGi6Jj>$2?Bbui(8t7k!>U@`SM}6savQ8DKn#>AO+q)SD+I&TH()ABN?4sAV`lVCVZhapYzZ*>(=98@QElYRJd~cbnz}Vg8<@?9SXu`SmmS&+jwp+Se&cdQ?VL#IbG7%jk5?{#eG{tAIA1) zTm${p9~HnTgACi`lnl-fiL(~KxUDh^*`1jlY5o^iu%)@WWjZj9krMeKyQiYJS|G{hd8uJi###V>sp|oIcwAQmJf*NzS z`GSoi-9kl05_>tY0-JWb~*`@5e z_=EU>tJiyb@QN`*zAy^EoO2)CSN1v?sPFmK=E!7p9%?78GHLsTdJRG=b$Bns2iQCeo~G=+ zACx7k?~vsAG!*iOd2HaN5Rv8R<>_l+kA8vIc&TRmq_B7`#BDpcL@i1^F1wkM%vEcB z*Du6&lP0NRMo^nwikuQe4kkhXeXibZZp@fGujF)YRoP{JnFTw5!5#uJ!B~7)xKQHS z`E=rd>X&oSM%j?o9mzZ{pI}5q(fLK8eaw$X@$T-y%x06)M~m>x>nu70ChuQCQSL$f zY1>TA^_>YZB7>zy(bh3V&sTNORue_<3Ny+oHv}~^5w$eUvD5NXul3wt$V0k<1y}Sz z635}`OWc4WEfTi~5k=WIty0(}ZVB_ZK|SFIDIs=r5s655?bup6PP*=L_uC9L!p(`3a709X$c%gbMLfVD|C z*ZSiEYzoH>>C1}rkG`M1J&4`KluzN>FxY_=*Oq7&-@QI&pzR=vHX9{s$v>@KM< zY@viyRg_3A;4CcIgKy(%1ooSQg96VU^@4T2E9T@vS4m|nn%zvf91WM%h?S=+ODiDH zFL9m=VvLtZo;r7X+l_%|hL7*V7UgKT^^-so`E*|A0m1;^T7C=y?})QAzc2?qK1>sZ z5a^IPBwsvxlJInc%lqgSyioh8m0Ixj@-lk+9ez0%i$;R$1l|aDf`XSEv&3F`N-G0( z^Du#!7$xb;vzDinRuit6z7|f<8pR;bq%~5_f?GE+>GpZk?QKZ=!E;wsAs=C_fgr{< z5HgZek(PLI;~FfJyh)e6tpx*7M#IGC#m(5(AtXJH!XlIeShg94K=y_sN@9Bk9oVI?3RP;pywrW~%SxL>?i#HbS{MWV< zS;P<%Vjf1dS91RWPfGRT($BuE{Z6op|IZ4Pcrz6h6Z2pZ^Gw5fI9d3w^loV_uaKm* zWM+!SZsyLbapT6a+T#1S19~P1@oVgQ#p#qgJB6xSRql6FS)5|T+2L_V{*gtR;v;=j znn=M(dQ!thjc{K1#XmAE!7MTaHEBGS(E|xtQx9vPBHLQ5nESA7?FsEz72lR*DLo6Z zkz|b`y<)6@z_V=s!%vL}YEg}tJv;nEm~Rs2O*JgN{I`uFers*EsV-Tei2zC24_I12H%ep#QrBo$| zWTNKEC6N2Q!IoOrm_+d66WX|PJxHMF8e;c89_lvEA)%q*0R!6~=dcz^o6REg1O(n1 zR+rqJ_I3R9^LxLgs}WZ5tnNVC))2pLpblKG97SSvZS-0CZqwdpr3g}C9BxKC-rLIp zI~+o;l-p>|#o0j)qaXw2rRyday>0!iw?3Yc3=D zSCMT&9Vjp!zm6z<53PgFaSy4R=CVxqbTtvTi-y&-(fo%VY?KJMzD6!YrwnTh zih8IQ9h12Gb39+~%k+WLw(O{OQ|o9uf6&O4|m zyE@37S)V44(gXhaNF8|Km$K=~Ez^8xBi83jf;;>>?A9}lUX1|9F75+uUrns?@;0H6 zKuw8I&PefOxOFb_T8Hq&t=)Tl++=0eUdG>ww`ny3!>9_HX+Plp3v<2rr(`V_JYQ~8kRt4SB7d{^RBP1HFBx4Twm?uTCY&7W0Y?T5qU*&Dm-y4TA+B@ zGUc+AO!J8uyVtsI^`9S22+5!6VZwDQoca45Ss_Q~<(d(z_AW_SRs> zHYCnRG1>aq(k6QlTr=>p^Jp{E1cZ|Lz4fk!m22A9oV0j`pB140#v?Z7Kh}f1 zwla$1mq-@`Q+(7sTxV^icM0rWdXqF++pRq{3sT4Ahz+zBMD+3mVChDAYz78d6RT*6 znFo}D$Of4VMqSsEj9ysuWI{VqL>u!9o3#)a=;(Z2C%g^9#2JHS)c|v2%)ft=j^;@w zGX}XmB|Yf!3*s?bWPyWDFnh_L!y()zO6P~J!Li|y_+p|I_aD9hWF#q!L(nEk(En@YB-eXWsT6wlbA;?EI<)Q=a;Y}^w1-m>3twyOsNq&W8FL?3;t!( z%WH4V9^r`Xb9nC8>(1UB^TqCt^}?zSntqKaVs|)XiE+J1ESZw$tyMxFM^MW(PWNpo zTwO3OCE1oMw#(NEAp-9hP7@;l;ImB3>&r=~_)vYAI|3I&(Z(=8a{WGmUfR~^f|%>Y zk0Kxi%0*7M_XW`2f+S7J@vHhcB9_e3M&46Oxoxqwt^ zbtKa+^O}2@rENUDI%bGR*QWQ)RM<8wP0^ZxSstD)fm(#tMfCEl7Av14frpy{Wsyye z*bd`cwT~B3B-w{ObDPDs$@wRkCZUuveEikmaswrWx&O`roVLz8F1Q)y6Npj%l{TH) z)apw(yqDZ&R?j!BwlI}v312`|qfjMWQVFd$It({19R38zGe+1zN)>vGhpH<`EC8gbe8Sg#z^k93C~!zj>EPc+ zDfJI5l>0WIGt1+|j}cM)YiZpVeJSv(h|CB3<|Dq0pVoJOBTMm(r!!Ee$N|UL45vBR zQ#3!x5cUa9+2?KAKSAv8>_j2Et}(n9&*$6QZx}vI4Z%)h?-NuS@-ZgTJ)R!x1!4^5_E#OO6Zv-Ld;+|0 z>Z|^UwmBLma`d;eoX($yQ^>RI;HN4R79?_tb;n%S9<@vBMISC5ZyA_^x*9ds&ROwOA7aC105Ui<=tCEB9|K~7+iNAUPiZSm1Kys$n(hedeFflz^4Cna3q zB&tiN)f}icN5ypviUiBoAFE>Nhmgg4lQLk)CCIK*umTfa)>w)Mu6+`6dseBLfq|Y? z(_cPc;SgXNM)|bB>_1bmXA^H<%)?1$B}0R>i(z#VJWF*Uy}F=)XlO=hL*EbDRZl3< zywE9zcg6W>8emagL4vy)?uSG%O~|J^dmtZ*)blxHovGmEnQ%1?9xWo^dAkea4;G0gKHe zeW5gcCami4LP8LSPdqmEF0vDR+5DVh0*rdV6@W55I)-bJkLSs1*UNQ>u*vuKP<}c& zR7z7gR1kvb(>HjToCff?Ys#jQiu@1>8zZT75Xr{`gCUFlH^Z zX6zf;q4{UyF%rS!3(x|YSXdB;;yvUR^angw*(qo=u-g63L;;_#_=al7*;zo zI|728EOgq`RE=9TdPy(L*NvyI{f$-Xg+Fm2hU;QVB$~WRoi)v0m?T2UO5e8v7>Dtq za~^^Ki)P%)nwGZxZkdc|lONKUR}7UdK5yrj*E(^MB&?n)UM-n^2&ziO`{I@AnAmVS zg%_kPK%o(Wy>7@(4OkJsr*vT>*Np>oQ&kh6M$Ui8C4V~KAph%{w*Ab0a$PY9o^b(y z!gtmNudx$6o%Y9}4Z(WKF3Py`F)?b;=+f=^ibT)pH^ER@9d3}I6|p#UtE85Ly!?IpCNKw;9<6n z>q{GQuX^v%rO(E=n5&RwdqzH-Y>*d3(&s#ntzwEZ$%GoTS+_h6KRH`Dp)GZLS~tWH zMzS}dKT54ri`Db;cMd7w`h{#=z2|i^AhP|UOM1p%B@R#oh-smKJDGj`e#tW5boTuc zt*PFxXXKK=&2^sb9a8j#C?aNG&Jng=1y{ZhYXf5Tjri@seOO|mFA&T}0x|Vl_VN5# z$4L1#tfy279p?`+wGwJHhhT{dfOm$5C}!8 zYfK)kRsD4#!B^hdKNstEUPMza)dc@~*lYq#JOQNIH1q)lgo~WGjK5y%Ea0}HwrcGi zqeA{=ljQH8_%eXR@QEM?c6jv4{4#q7G$GaYy9h%V(L zx}XmK+Kb1@wes1H=RL32y_mf+3#M7O)xw3)$HHcWos*TjN9bz?ZPA}twvCiB*=2Z)wqs4nVV=? zYNXy&*Vf4H0=xS72H@o1L-zd~^an>$ED!P54Z3itMV_pS(TWKyAY|NGDJ z3~glokDy-I82U0hai)3w7+Hi4R6W;WvIYCDjP2Dqc*3?l5h_-XmA}_%oUiii!noeV zWq)Rc=lrfehhh!Ryd=Wf7T$W9GI5@X^0&6YCEy&;=hBiTs0u;XP$-g*0`VOOX!0+0D92|Z8@Tq2%pe{OVhYC? zJ?(AdV>j*jUFm}k|4uk<2Od)#Ru&D|iS?xn{jK9{o9HWch#CSy%zYN>>W~|x&1Kvd zbL~Y=C!|*D$OjW8C3Hmkoqdif~1?rN04JvKLGy5($X4{T@nBhb;+016_JwO#plgCZ1tej7>dfh zuc@p1(kWXfCk!3HV%v}`T8UEc5L@m6b4G=Fiy!=CR&#mz!@ZfYEF89h{*MP}9a3l) zysk=xBuW-+apYU!)%C}gy8P_(g{a0Bn7lGP$g)54Rq!+-ysx{y$kyn1F7v!hnymb8 za|Vg&9OI!z(Ug2chI;ucBmip;iPrtswtTi%xdkd&Zc7{NOqfh|BSz0d6uK&G(2cz=kSca%dk7PGuISdM#0b zN^I1RxCT_wN2b$*YQ1%3{cHay|6RStgZ=w0RFrUcf{Hx)L$Fyl`ofafe0IK}k5D>U zUt^Q8i@|u$*~g}Di&XY&Ca2-}l*VzDPQFb|2}?gAlWWFX7zw#-=ipT$07yg!M{A{gOiY&ooPz15AkGIsb=cG*5PUi`J~6jVgA>U{R}%yxA#SY;~E z{9NA;p1~&cS24JYkI27_&~dC43TQd-f#H22nMfxNjjWOAGcEr8B_|Nu7pGQeCE|n- zaHOlcLfA0r>+!Wu1k94;(CPLRbC?tag>?isgI%aUI(aF_b|2;0IK_%=A8F12{m)(l zoiXDEhsRxaD7S#H5-A%a(G!K^Z{oKnyZsRINI6H0gfM>*E!bY=^8Q|Q**-pJP59*; zvyd;hklEF6#-B#JU$}SLSC4l3x4k1p7y<+iLy(tO+^BS#S8Cwu#3up6HP3ftVKLk8 zCC9S*15wu9zV%B|L8yY(tm2^PKYLlJ+A+I&;7Cl}zxjB7&BcP)72c)0xpRZt4oH3q ze#7!Wi79Tv&gOqI)s%;$*uX~J(d#!Q4huxZ@S-lZ^NBECi6xOx#EE}4ZD6xXVpYY* zNuziUU7l$(FZ+y1dEb*rD_bm)!c0KdDm`QRtKxb)FR>(g3)a79zx9PCFoz|<>FMzE zVA22%j)5H97)yx;>tJ3;61+J9Qfroq8ZK%}`p(q+CO9+^-{C#hvqc1xi0M3XggH3N zeOM!W)c!TdOW*RYwxA?tN-Ogg{SI2YbZ`lSAI^{xkSU(jwP^{kK+ikP-ytmM*jd1T>R20*pcx`i>Q8ZTVebUGS_&xpjUHP)?$Di?A` z4*Eql%pr3K_6TY)!_N*G0z51kblrpQug>AEi$4qx20pifPj&xhG){2y+Qwb;k@m56 zQvOEFp7&ar$#`pE43Yd5992ZtB}Z4>l|=swA*gAh1#;0oh_TN)%WJ3_MUNEphZk~G z$pF|eY)R_pJ}xXW*QE!rzy-*qh7`0L(73?d?75}d>;@i>#&U=WAWs*;AFCl|t{ zg67}Jd9k@=Wm4W6P@VY*ejK}oN!nu#+T{epO*@)uDrgX=iW z8m$IZ>FaOV4=BCtqj(9?sr~s*d>#a=$AtvXM;OLxpjaz-!`u5_+NB)w{KigK6th()|#`Jru zeRY>Wwn}VRoQZdjz`glC^lq-%`*9qjD=?p#B{`j3B(=XR(l z67<7qR@T=M6_Ii4yk|9ojRRIV?0eDdJ~hncoN zmk*UY+-0nwibc594Y?j$Td+f7CQ60Ucu^82D137G)6D*qoIEWRxo0w_)bg!ZBk1Z{ zqET6hy*>X@HigIh#~uOtv91FF(a7Ftp|vo8lYuK&1=M`=XdoAzvgZ_7G41(WCLdZj zklk!kNvYb^quS&+xgMLUp*xOoj5^#*7F2YG{7$U@$v`KJ?H?LP5YxrLdRQxUk!k)P znSuZJayD1@O~ZfDJ?5J$0wWt(J~9)wY6@!6 zBKS2klXB%_R#F`d@5)a!#Oh=`M73=^%-@iS!lo7-`91CKKlSO!NYKh7y2cc&RPD9W zL%%+rpha4QC#+~Tx%3YAIXH+h%5oS~-ot=I*lLQ36_QMivTXquyQ@cmLQzmNO@Kz7 z!Q`NM2n?OEw6SJa5G{Z8%zX1MxG{p_dliCk+qF@mG0q!D5VqddYR*rqP;grx%j~>) z)DVV>;TNDiFXT}<22(sR5Y~nI-mCMB3cEG%>J+41X~x}(DFpCyspB-fB9einT1e-9 zZ(VK&Z*RqIt4gW;K!FGcV03O40>lS$lIkJPY-7d1V{U?;Kq`9wX_#DT?8%loy40s%oz4X89v{>ldr2VLu z>J+sZ=9ZqKx$2X%Z5ucQz8SmTDeH4lqO%44CW~`!VCyr_C}i{;Xt4Wus%U1kxamwM zD=7%M_H}RW=Q{}((O#r{8}-AJ=&y!v@J>+Ky{qqYT4UyNx!tt-bH-YM zINwuahT-pi_xM8N;Cy3M@0j)zm%Qhxn+S@!usY7mAlU`r%2i0AWd&XWaT;waE_QSd*NGl`>m!#kuO;GAeQiz4_-I;5O8}M`)HrVNU7mJdmyN%g( zY}oskaCO&8r6Z`SAz^ihXa>_eBd;_#;OWbTu7bV)Y$X;fq1hqQx3GL@_H0tK=jA2@ zwV+fbJkjnc9T?tqG<3H|nzRCKKONfjL1E~2!Wc)rI&|fn3fiiZJ4yJmEPw+DG6`^r z*I6J2O8LH@dlI7Q#5VzHD&p-f@OR!CR?sh8x^nlCAIgvFB|t64>3;07)P9pzusNEV z8T1@#==gK0WufDKm+`Re`f0p$uJXq>llycmrJ64y-r4*!P<3)bAzKtO;ENalhl1fi!OA5A0XnC z2>j#ImbDo|I|R3}&#Frf+(X3UleU9;|4JS#|ErSG_huRmmL0kDztlOaRc{u(4R7b! zANId6^t5>&pJASJR077CU1;K#OF^t`^Zd(-7cQkeb3MnoVhF*TjRn7OpWw=7Sh1{i zwGY5HD*ymS&%29T=T`GW>WL<>RI1F3HwoB)69n~ZO``k+!Y@8N5c8C+A2$y#D|L!* z6P*dR$qh{>t>W7&E+npD!S{;luATf1SsJm3JGJ$e>hSsPz&YJ#HGj~AD2 z$tK>TzA>Lb(igqDt>F|peDrA?h`3=68)&O)GYNk|y6bk337L4PKThCFpjpzz^u-4J zrGZPwsLgYJ{W#@RH!vkIkkp7QMiPPv2nv{T&`VIt8V!crN0~6>@2X6@Y!TL=KJqe$OcpmfFihaN4-ey5z&+yLwXu zSCQO0toa48_vyPc<@x;xgxF`;CaNF)3zQTDF9UR#O7SzG`fFkd9ok|ay%(TUHLZW(5OC5-jitdJ&wZx zNms7P+?RP$E!jxM-t;Fj^-|<|GN>TZU2UU^0VXokv&yLFM=o3>#|rR6CWsYiNIgQY z_^3j4o-ESJMyA&=wto-x3PFOHUL8n6$xZd(FxBHjf|>!xgrri!3as?el4%e1gnBV^ zB3G4YSqNYX;!9wo$nNE86>%9F|F4GBg}qZbeZ8GG^o( zP!-7wmJaRR16Rxw0Z1~BHtHDW$_GPW&c$R0Pli}fig*NiB=XyjbrsXdlaV|e-(Qw$ z(~wScHOU$y?IKBLE;fOo`9WtcC^4yPl-74!HzBg;t5A0Rki6fp=v?V=`5C=J*CLFF zQ`*km3~P$lEXR@pf`vmcTOcuyk+|?({C+0yhAw=ENRCy(lieNqTQL%)ZhD1Id{sBr zsfFzl=%@l?k+8(X5n3;?0C6jgTD1T&q-Mi{(ZTz&z_vg__P9cuOh?cc+HVBuz>yoKA)ZPuMcUvcWcEvGTQ zemRJ0u;Vf&b!y_IL7HfKd4z~+k!@x0z+_NTyp!g>i=748s19q>c7eQE4e?10jXFM4 z`a0t~$z$8UaO*q5B0K)h9sP0>U}`hHNcG zYHE5ColY_%W{jgMUqwYYHv(X2!t`9?17J2a<;6@eXqOF~Im&?NBll7#EHxAQtR-JY zYr#Zt)N7jLCXvICuIfq_+i$lAac4HjI-n7is8K)8+L=1Y>EoMpyStr_MRVeOlG2T0jw$vIgdzrvd6%4z);hrf z0&hJ+ozGxR1Hgq;26OMc=!;S4EJ4U*!5<}2$4W>!hLx@OGP#bEiqSJ;{{YP7!_oT0 z;ITEZu^o+^>u7@<8<}Ah5R-^-KRvF34DD?!E+mqIn-f;<02Wy7#*JSWmMaPMGoT%% zbV56Epb~Y*tVYhU5_mzb?4nk^$@9%kRKOjm#Y(VO_!X-eM3P5@>tIn%1gj1qY_qn~ z3u!p`lRSzL8oHxqcvi*db7p=(wG;Tfho|5*g$yVu51|iYpVZjV3(2y3%O!z1|9;kJ zvR5umE_J7@Npx;8yJ9*3nD>!Dj~_zDq!$tjTtTFf4Uz*{lM7+B16b`4^f{(C63ZCe+p7OBgEuYPptnn#C&iu%ifcyOkB^9v79h1bHLYbf zn8VGYaflF2;D=+Vgi-ZbXr4DP)4T6hgM|UxJyNu<3ie=20SuOJn2*wY-Ir~RAu>4| zb}+J(;KphXOt7v9jerG9d<2@|us!Ke-ml&c^SrM4@%Qc8#boT=8#ddNeOH9&;zzvFukGbu;b@)eaZ-#}OI*;C` z_Pk}@oNA(2R}BaD8qvVVDFI9>7PXxMtLlwa&Lj4C6bTk?%uKex+i=zo0dtu|Avc#Z zPC*gu!7H2d*$n8TZ9S6{F$D8O$DK>|!o4H7l=K#A;{}C6UOr+Q_qLGdi_wMet*dw3 z3W86dT5ps0OvsV^02R4zlcV;?yk^Zg(Gr=Mw;@j7zsA|S);t;SM{l&ucegUZ2jyq* zb%D=DT}(lAs-{IaiM{muO_+*Lie~aYKKxov!k(v)wQs zyFRkiCu#tbVNbP9J*+5{U_)+-bKPWp6FW)Z)=R73+cNRcvH4?R> zPl($uVOv%9B2GiFNTGma(12s)hs*mB|2VEL0Tx#Rp+VfzH8f5jWUM&)H4@ubi0Am1t0gD!af-{}x#rN&6Uj7Ly zFOofF8Q8eJ5x~~pT38$&@N_7mb(M2!_SESS+U}#tDX-@*c(t`Uf?=qApQNIua)-sg zLdSxw(}37~!bb45EPJ>Un}+V4(BIPWE0jn@sVjlaKaaUSHIu;%;`704bO6^lp~n~H zNeKERgogH$Jy=wYoGO}hZ$K!LM<`jIg^Tl@<&IAoER&SvZq}8Mg#ww#pD$pvu09hx z`*U$Qx{RS!J%li>IOBm@-OF*rP;x)#iB;L zl{lbyl1yC8B_As%4s>bmJ@JW1oCH5J4&Xuc;EU;NEeP3W_eJ40q_+-q zH!tU@Ehx3xMZP>C9U;@m+2n9*D~erBn)_{C{I2r zvy5;L%NNw86EcH=d`lhr@VHK2R^MH`*`M`ns_$Izaa1otpTP*^EYpw2mm$CHil~oR z2qV#NOiUDrn7jr5FRs2itjYgvdvu2|qy`9rq_i-)yE~*&K#&-tyOBnuOS)USk(5Tj zAq@jYhot1Y?=PPBeV@-C+i}1K2i*6rIIr`(PB;$YR}ZIll!1YY8*tAd$AWyYdA2Sw z^o~_d0d3X2uHrTAhpu-o6;_rmQ4tlE1|989htJ7Dx>9S1Z0cnQll(RO|4LLoGaNoA z`(Nks3tJ`TuLz1s6in!^8*Hf%mT0ZmUDwQ)dP&wNlb4dgjLOpG^ncXZez+NAvQ+J0 zgqmaxB8P9RcUJ+Cvn>0w!ra*O9GY(kBt)BrxUqRyc_pzAr)ckymoWLFcYc^BLRl@ zep|a>8#e%@l63q&rn=6(|6H1=%rpK*ja2;6 zFH=f6iW#-!>OJ2;g9p{3aksc52W-Sn26p`Pc;yj?7vgc;Vk`Pl13Vk*8Og&T{pML= zkAQsu z#+^lDMPvEG5+w)FFsr5vv0tP`GP_jm9!hcgbBt1XB|oze{S1%1N76~|Dlr0gX3wMO znH*@)2!pVo-~HO2@qegJ;Ge)D_7>I!6UVM2tW64^z1S8!M2;)k7#2c{Bn?(;KniJY16oEDh@!1MJEF) zU?~Q+a$V_u1AhApbUpA5=CeVEkEB&C*{zIfHGW*8{-{AIXT3?a$js zbR7MatHpoeNNrF1E8eB^q{GbGlcT=$^6#;IRCGbzNiN~8Z@=VMVwt(hJFRz>P{P#S zDLUFKWaWCcZ>8*P{81yHS!?Uqj_wQyaMA8Fl9+@V!CNFmQ2+r~KA~Jrsrc`&{RIK$ z9>6D69bVbO+cyEY>+w)SlGBcK8yAmHDPa^09<#cZydmu=+9pe)dMtKY8V$hOUwrqQ z6I1|~3SUv}p3@l^P5;G`w*@=OkOK8 zA=%pzwSDan*crfSfoKtYNW?UCuw+1eU;5RX_+)H}EI{LIan0Z7`<}`9Ju7P>Nst+k zwM0&Qyy@ErPQ^-9No!a7S+uAw4ej-#pT=Td)muB`j`u5sbz&T0(-=9uIH*kEd{vECRuvKBt!c+1c5z zP>Lr@H+T2&37b&!r(0OyaXzxX`qz2r*z1oZVi_Ze?BAFYOMW6YuGUYVuzOeOVc8|#IEQ&5jG@{Zd5<~aJM&w`LACV{EO=8CgJG@LG?XQ@!?$JiSKdS z{E-RO`9D7*knHw!0}aW4>6myb=>EGy?RRs!p@G}^Fe~ve`}J_)UoU$)V`MEL^x8Xo z6(*Ufc#@52(UrdLvrQ9>WIy(>OO=02)NYuW`#3B)UvinkjmvIN*Bk z_waq6NRFMg0wmw+Fdx(5_4lV|E{WeeN=<5P?0hGVjT}pb2$LL*mv6u_TQE1{^~)5` z8rGlaJr6hdy~EuYMcBXBRNx3o@B^X0&?D4H;n|G+&6M*9D>oT>x{?k0-k$`>)+gL z!A*S~XLK$YrS(3bc5SSz2Nfp|+zA>WG2HGom*rKY(JxD-)2DYSFI(z~tA(1o3%(++ zF)T}H>U_hb&`BEK=4OU|5h+!jC9V|7QbU&O$A2|9J37Qhzji5zZM(&lZILt5eTL&_gmS$E^7eK1rS0S-h+*~j`LYupu?!U2X zfr||t=ASI^hsoi~Lijxto|Bf^MTTFfe?E<^W+}WyGOGR8x~AL^cgIEx)&qijQS)h0hhBdycPKdHuYTZ5!^o!q?5rtd%7gxm%adoAky zV1G&SQZ^qlr-MK4?%?DkXh0sxTcRwjua(t}u<*_g4Ru{sEgbEd7Kpi&J%rkV_d~ zJ&WXF;r2mJwPlCMD%P&*CD4aOR2r&k9R^mK_>#a!2vv3orKBTbHY-8_aUg41Ios)@kgFm0r=dK?W9h7}>x_ z!e22mA~Ol^aN1J*!h+ zV9LFhVkB5a0s8>;5MPE-y1>EYw_lph;davleZ-ef3?^jYcYAKBPxD2OwMSbSf0(}J z*a2$@YqDm218)(>y&Tqi8Oqa^@ZMX>AsNwz?U!)dbKHMB`0#~Qz2upkH6NfY11njZ zST25Gu2#2mr>D#}%PNJPx{dZZYFnbA>D;zh(=UaES%04sJ7uRFIr)lqGswmODJUApf!FxlBF z(;5yzw(cTsOBO8~E_PBahu$tB9!y#b+ihIUYsV!!onoA0?Ab7m zT;aUbC+;6_T;xu}RUoll>ZG}2I4o3Z*3ogv`z1tL4!yxixY^KX5T0mc!I?+GD@CYO zZ*U^ndZ8+v0v#OpbFP4-=4FtoMbvFIw;F#-I4^6PFeO!NxO`sYxDRuL5+z>x&=SZjH3eupWO{G1tCm`yusgDK9mHqpoJsPa>Qz>S9QeFL8}z~dnjH2t_G+~I@BdszEr4WD|F>6o<8EQw|Nnz zluWNa=8?+`K5${sl;78{4`cfH>r||$O*T83CmuujxinfWAybv>B=+s830BR4W|yZi ziom!#2CYJW?Ixwj1Y1Em#1w%crG;A`{AdG-;8vf>uv=hI<;9l~YY}bomkrV`C*hde zu3~^3Xbnqa1H&b!=MbJWm`-_&D^Fl|J^9ObL+-CbblK#B5|GLUVFDAr`meLx`Sm=W z9SW0c_cMD%(fi(_aWeweU9dmT$hc zO6HNKl~crvhAI~9aFM3>nuP0KRr?-oQrS&` zc`p^|TI&b_t#wUd{1e2(db;#d`aVDNzrr?b%7L4V{q-n~`dFq_)OC7_55`7jVkM(& zNzn5y?Px$v}@u@{X|HZgr^mmG&5X3&B`=n3MAr)coQg`@N9T6G4M>N*; z>bVGkahfYD4^Msj7nVVeUzecw7_Ow@IJzklb57uR(-RL;qT~pN zw1t^aQg~t~VWJiNozUIoX`Y_1I}DGL`{>)AL!^)&^&-V>oNd!+xL=tM>2R3WWQ@A& ziMs53YtlivzIP-8=(Qs`@Y-{As#MU*+8rBDZW)m=;mdRHnU(FouA6qy?n*xAM}U?g zc4AO33}^4$7@PIb3|>&Y^e405uU=ogMH$MkIe>o%d9W5MjfB|myg(Bn#|RE8m#;0n|tp=4$#(yo4WFa%pw>k z5KCbsmX~LLjPKp7ZqanHR2~G{9npqZ2>@t5_+--3b5>5QR7R}GMYU81%{i(z^Tz97 zLt`ppJAYnX^xtgyHKa{tX5S<}V$j|mVg5>U``fJVvzysu@#GbfQ^*rhLaT1WD(+)i zDis&uv)a<|-_vf?Lf|1HEZh)=I8ToAZ~FJweah{4GZw@)&gb6owymUD{Nu`Z>0RX1 zfnw>@5Mik-Xf#_Dlt|(W*-K;?`7NtdzR`F)p`#}>>4Mp4d@Fxu)f1<~ev7%wsCsrd z$s@%TUUo$06e66g?WU6g6~LNMqEDp0VOD|?EY{mbKaWzo7%#jueTA_ z9DiuFe$J%%Mlu0rK{vdCF5-gO-dEXMH~k^+C`DZjR|np}K!dfS4kbKh>C1*gK8cbO z?+BYlT7QrdDF7;OJfu0TS3okd~5Fle<4SI{i{P0{-GzU%Ayz1C(24zhGx% zw0E-DN-v~ux^1ow!_8EqqgFA^reN9oGl>&XOdXpD-Em~HDZ}$;gHa#>J4q7eS{FB6OgwnH9B}&1cgZ;nDqKPqWF%%UE zM8WZqD+3l6^I3l2x@vr!_ZDgtFl^FPn@7j?eabv& zFqV%ZxCtOM{N6iw(h6%Ol~%_WKaokaK)3qbA@Zd@wa#`ctd_;qOF!u6G)&QIjcTUA#7sVoESMz6os8B&$m%=RZk4cl&Fi z95vo69*ihhv46q+z@*HJnl8jnBf$=vXh$p4j?T;f0#Q6443EQ5EkrkHxim>754mNl zo%fsv&MzQSpNo6th7L7{Th>TJ_AMEh`7|Q~rySkWaDs<8mi`AjYzpdtXUGlR-f)TL zAV2jty?SxFdn=mO5071(f||1Rv#36MMJb9Vi;&*5C>je8jVjY1569#gbJrjB4$?ts zY>rThKR;NkKl#2x0;C`$2+KhXE(6DeDuXtS-z(EU8)EgqZyhnX1AqHje6=W%!SEVI zSkVPaU5@^BtVu&j$$$GDco0iG6<+g=%A=#MTk<#{Z62q@65rCoUW*#fVjL`}?~uTs zx4;oQ?TE44LgW2tBd%fo+fB;1dy-?_wyC6Bqiay$y4MA2IYg_Y_WKktD3q- zT9eqMf6jXQrkeucv;67L8ztB{Wh8OZ72s_po{NftSh3~oK&;phWjlfYaj)kFn3Is% zXPj1*6qU#J8}Tf+yoHGb6QF-~dT19tg-cGz(d(552ZIR$&w5%lnPhsfD`pGVYd(y#)wkrDh zJA7sR`p@o>$?6@!DN>Qy8c8O3-0IS};{&GplWbd(=rl$P{Dej^p`7Ym4w2MTmSC#k zE$aCX7`qhLc{c0)o?|zvNIe>}AnDZhR`-?=VS}`V9mDL6nqK9-27P!NGcraP6Kr ztf|_)KP=&A9I`U0m#YOMy&khzz>%EF#3WE*Lub%|@Ghlb2_t!{Q+7-c6_|>9Y2vG!p0EB+inAI4mr_X>GH`{QWYx=nxKm3HFL`!d&pDvo*z z-3b~E)^H9bwJyZ209tgY8%^ZxOItlgW@}Z6+P1*9?e&P~*|$@Ytv=H`Dkt-KjU0*)x7xzhWwACm&>$i*srK z<4GXTT;u$a6>jCk%m&`^gwVGSUE0m(ZqKdnBooH?D*a8CjfalAJ#xnIw5sXn0c=FZ zG%Bo$tj{v-mc$6NO<`~c_xw0UB_085Lx}p!QtrX`TA?6Jv&#i24ZlA*8ed?x(eY+5 zA3GpOD|yonWCiBqED6tRU^WWYRCIl*)(~PP7b6W&)^c;M+?WyO$qiGC$*ST!aL}Fj zi(lcoK&|oeBQ@4Hk>=FX^)@}f@lN*>mrqq7^H;)O77KRxNAgT%hi$~i@q)i)E#jPC zD3fzyc_cKE8Yk@l!%c-d^x!4!lcHQMZoDOmi=i9%)G9u&yH1wbYK{q516oI*?VPYi zrKJJ47JHr!X+@WzX>P~H&S@m97dPI3de_f7aR&boUG%(CgiyyAE2cBARUIQ-zkhhe zrt7!i;pTnGvB(F`x&62rvlWp!qor*(kL%p!ur4} z=lBvMlyXC|4nwpZSuFrAdH_F_xQ`>Wf8G*Ish*hnA}JaD3(_sty)s>E%AJLC%u~n& zn}c%tokOvPX5V%W>39J?-cAXpEyzqPo_`LB$76%yY;?_Y4+@N8baG@_OEB5S!es}q z#&v|1*-(}8&`lyYVo|^X&qcg8+v9ILT;UX2NjeuywJ2D?Gksbt-0YOgW9xE*!CsmK znf7`!Y_w;oCg?zmf@w)uW!a-X7FA;V$py((BwsfEC4pl(8~3m~sFkp^9oevLDu!#i zc#~1LwapbPek;`a)C=7!@p^e$Hl`9DT%wUGvNGWyk~1 zaCa5;SXHotLWKy)%%VfA2o0WN8Jh2JEJ}&B&&^@Mk(%}8dEG02dUWGzzyanxlBU;< zqBOc7j~vsK{jp+-3+AmMUB~o47b80AE$ki;QfMg*W{>3K_ah44tBjM^j4_<+HO9%_ z4)5KUG>6&ugwJrub5?r6cx#~GIQo zYrPq;38-Zu_9C22r`WM=f9+M0fYlutfpRdKuA(2KQ1x{TN`ndom4>Kp^7Bo{@2O~O zi`vrjyBI#^vY<=pD{r?phz$ISj#$yZb@ZxnSS1e?x^yU;|B4cv5oNNKJ!43%_7W5) zQ+09a=T%7d;_JTni{g--Z~KYVpY?od;ID>^Sq^E`006oUkFe@(TK%+3cbg7oMKyD+ z@bAkT+-sg-Tj3K@Nl+<8rrq4cHtl51Yl}s`&x7%iHicoyVmD4r&-WDHMegg5;#w_H zM(8RKOrgND0d*ViA{e>GYWgNzMS)E$`b?KzoQU65cA6J1r7L04qu4IxeZP&1+{swW zt<%O9e)CU2yhM2%jnlE?KfTRoOpu5g-EyxLfOt|G$OJk7`vh?2i|V0_Yb&evQzS@qp#c`C-5{fq z`JTCEAqXL`fYvui_H=+`3q~ow8>T$e%_eVlVNR!Tqi~iNQuH8D1WcC~nr}*c|6A?Q zixMw}twMMLF9hw2?(l~+o@#0pvHjA>equ}=xp>bL;nMT)_!b%^|FViA5Hy!A zdlN*VocVX=!kcNMmB3!*e?m;<+r8%D^lsg2mA{-2EfS+AF8d9O`Tuoue^ZNSVdikT8Mr%}i|X7%(CVM~0zEmF zhtf6r=WcZW%LRaZVqWcuIUb`O(4QTOGybP|>*C*PBW!b@*u;kv&?x`x3<4%)CjoTT zxs>;AG^5$zTe%)S)d?$wJXadZu%vPD5CDK>Td}jF)%KUW#I)Nu_)*cpeY((V>_hqs zCBDYDHQrn@v*6Em3Ib^bm|r*)U<03h2xa=ABN(JeWHk*03(A`{?HYW0jVnriZDKg=|4RO3bd`AO z*bb4yqV8;pXma?xb%+XnRZ_Kd)hE=yVDdI|2Z+ogq+P~PQa;#r>*D8%*rc~6cJTO# z;I>r!!VlVmrp;7a%G=&G9?b>3LKnXcQxDQd15`RdNcuIaPB${GD!pRE5`F&VEIE1e zl_!NJW#$BcT;sL%3RuJcX3sP>Zs`jnb6w_AGThQ^KDRM8rsHm$7Zo;GeDo6f*anzr z^D;Z1yMG(gl}r-XJKO-tjGo0OoyAtxWqUsB~?(jgP!ovBvxsE2S?zdGV}lM^U%(JquG`FXY?BNu`fY z(p?fsJFW6H^YDf)tVvV;p)-}?2W9Ai@M-K45N-O@y-U!aNNug()w}~IcgcL*C znpCn)!>83^2L+34_;N)2w5n^cKdB09aTpv7l-dU)Z_?XbvoFe}?2#y9@S=GK!8(Xf zxCx35J<6;>Qk7)(`$bC9Ua)edha&F)M1Jxep|zplq?c!oafr60Q+7=RJaGuo|+N`er zP?|`SAE26pDmQ_T0)Ekaxr3DYbQeoVbl2VQ>8pB)B8l}HiJ{C962uM&oUh(#w%!`)^`-#{j< z26Ej#%M4iQ(l5e?!}AT666**KACeM5*WSF)H)KWL)f~|6%ilK+zQv(eL;oQ3yb`R< za)gTufS=*deo$2Z9P>c<{H_=;E2eM;Kc7-ZnKko{dIAt94}itGr}4GgNW4f1fx9f? zT^ggL#(jI6{G1}Q3l9*c75zhX%E2<5fjm0aJpaPa#O#{~3r7w;643WqgE`+Vtcnda zmSz7b6LG~Fci(6gf9PDyGPG?;Yv73e2k^T5@nbSgU%%y-3cy1L{I`&9z@T#@aCl$B z2kY@jq#Ko}${V{j5IgXu=N|M3llbd=7G7)KzK8aiTzi{YYU+V_VzpIFE<$3vIHL*Y!S!yQq{Moad zC}HZMPTD6l@!T=mA-F}TqNMIW)RxUDv#4%3L-L~g4&V5@O+e|%JTz26@60U9VGJ&% zYmUbtNoP+f97ZJ=+|It+i=H4z@9Jp1sL=BHScfH@JF+Zke6$EGbRT z7;G1=OQ8m*dNIP%{dx+wF_ZSWarnez!JjfFe{o zuXRA5PjU(XoMnV1##O;)Ca}sRT0fvwSKLgJ@c&$inF#hge?S9_F3jP|v)*Y%g<<5z z==T@$K_^+nXP^|KEr(B3Rcw7C^h^`4jp(`KezukU{v%w-UwZK44{CTa5Mhk1bY8}S zyX74Zp3fV0npJ2ir$cxXY60gGjB>uuTGoW^@^G_pS>qaITCNS44!w;5ch#WGe^Cni z!I6=`S?$^2!@*0T7O0Jj{501`y)!%Xt-=Z8RomL^UOsT7R~@$18Rs?B+-oGzeBO#%@%R6dA3P5U`lHiva)l zoY@NNEL)VyEE{WZOaWp~21+^c?lEK?JrpWkT0z2-xXqPL}Qw%n8K6V{ML<`ib!b zPHeZ1G=T0DtkaJZ;-n%A42a~PF;+khh1KJnVJ~cioc8OJEi>VJE6pbNCx@ z)-HOWD#M~G+Dwk}$Y`SS{rJ(w8E}@nZzmITmNVC^ugP>}r~eFJ+J4%At`yZ)2(DQb zt;~fR^`YcWf#TH&ZWNzGd(Ko9r^QUwSD1$ecWxMv6`v)f{o;*?<~9i9g`g&E1}v?w zc(K?{h}C7I$Aw%XOs-etafBA;bHSDz0whtY`bwnsfZ97Mjg`fYrzfJQl<3&;JIE^b z)>jJ~Up4t7Jz0`818=RE_XEWgSomtmody}cIQY(*q+ew336J8U3}$;9rVj9L*}vkb z)qhod9)Ui$1 z+jF09F7;Tl*4GnwKwfAau-tw=e{&~sX5T4=qRA?LTH8b8902n@n>pfXupmtcILbPc z=zbt*ZNZQf4gcyrQF%HXc+Ko`4eyET>4tm?z2NA6%sKh~w%f`y&_DsSJ{55Mb%QzZ zFVX4eP|)f+YWD@!TDbXL^WDa%Oy@Ns0A1oyB`|212--N=iRr>8OX%*12`ScVSEGCdmo(3KY9xHokarC#r*WuSwn$4v^Fu+y zKNazOjHFR&q0Oe$$=j=w=tjD7f?xi{5a!)~C-9YF6A}(c1OwhmBaLL`1mkgHDE2ixNVF zcFJXYNNamU`_m{H!8GF4EJ=8KaFq4r`~iPm{j!YRa!9-a{bpn5-VudPKCT_R^DbL? zEHozA*^k^a*AxRF>f%J1<{9aAyNCktC+)UU;766r3rW&-Dh6g}lCCXk6J@E~l79P; z%%Bc!?XK}G2U0O9Zo0B?hdldPHO*;K;*?X8FpohXH~1mm5#HVC$t#z=qib6h{NX2f zJcaAW;)E|I#uU7@vowM96=l+LuY`6QBtC}0vj>T=4`-vPnWtG=m&c6xzI3%zfl4J> z;uNPyW@%GlS1js1dvKv`!V*9%RP;&Ga7{^kVCjlV7bb3EqV%ZHvzHYMNATz<(D~<}QlQIf|&15wRC< zP-%sFjl9F7!e^ri6+XfgdNJf3yn$Q_yumumBv|f4Jw4mDW4YBn?}&k3iOu@vaH!%@ zOZrXm7t05(;86k%DITQbyKAgSC<0o5AUW18+&5+M4TQ93SY<8QEhoA(AU)7ykronm|hXi?z z8XEM?4=^wEzEDfC?j&zb3TUh8z2~Zn;yCp_AD9!wgUQO+Hck`!(qwsBb2_e{=R5f2 zh>A$Sgn4|0XZqsIY}E^env`(8k5%?TPS1;xIh8Y-PhQ#CJn++dWZ zM>l1LXYWi_D6@ahAO8C7QcM0k;V$fsH%mPSqed!ZB(gmoq67wP|Qgh-fQhx186Jo(=14&#L-qunXnLf zX=eC`+)57Gi3|2;hXiV~E6Lzn0i{LX?L=ihA9TB&&Efu1mB2NLw{_xHC8#o_Fi;m} zv9`b*-)x!!7l37w-hnCizT9+2rUql(9bwvNNo!_^$5IN`sQBVfd2R@)WB9fcPUz+K z*EdfOHMFU>?0oX(jj8ts4QZt^`Uhfp zQavO)h-FEi9XvF-;4YaJ@kspj_)wd-*MGy!Vs88U&L}LCrPF!7C`t9M+-y>$L}S*Pc8q%Exs|AiMSr`qqCvU}>n zwtkn^Q!5oIq(QvrzPH63*ttro*TR34MxJV{#3-2kRTgz!dv&v+)9Pop{Qec}bYPbG zRN%O8jLx5l*8lGVxaa5hwb9~wf#zfJnC{u{J7Po|8I8N8ahY}DzqnJm zzwPk{)!u$y`+jh86wGRIKK4Y}eLa7@Y5s7`y+rEA5j6koqkhi~2vpAHlcyBI2Rm~_&qi038udOZ;jZenDcVK?%r z)qT>byt_G_A^!b`*9I$+^MzF&3>gXU{H5G@a&ZpO6XKyZC>YH59I81PbnRg$gr*KbbgKNEZ$jrcU4#m!N-p2 z_v2bIyY1k43E97#ja%f3`$?hTLEEE}O zkXF&shhP!H)Z4|VBI1VV2UX}Ht;P>od(iu>L%s`ZS)+IwQqPQSX_0ln;)D zGdmY0$9tvUxOBnIS06gdA~V~%m(pX99#U#VNZ;g3k+-ru+A1&wscTv+Z1%VD{NxWe zdy_S&xn2g}yTD2RnJOEd>)QJMVlgjHswEr=Kg}CaJ{wDq2fc?5S8i_Z6FTM|tcO5& z7mbhM^_5s)(Om6}-Rq))PX_iXuHLi0tqtZx?F3a9?hmGI5NyIkynLNXhc)Okug;xU zz{C!tBo+QxyeXP2G!w%E_@Co?R)^sE_eb{pG1~9Er3k~@G<8q3*?`h7)GM&tFUcN! zL)A%PMDk#&{e~eW^-B|BsfnX{hnkPd`gbSt>kikl0Em7b3wqa3uR~8MTWNn*k?L1Y z8U+@^5!h#sv#7n(0GX-msOnY5YjNj#{Amj3#mD!ksml75()7T z`6kf2Is^1B8)Hk!jFEqnV_Wlj91WYEJ9FP5V~|y-!CmAvH|c9!z>z+wDJjOX{f!;w zxg&%9afUa2od`b4?wfbjYy6jq@Sj)Dc;Po>?@^4*lX1*Nh*m8I=SCX5N>2tVCFv1n#G=H@z^Yc(%gzs6Gp=8?y=VbX zxyQY=+p9CE{;RDFAJC6;zEzb~;x?Li9Zrlrp8Ne;3@EL=TuV$+(+1RPUqynyD;`GR zA4n8s|7vV<@Z4vn-{~WSG6p>Gm>(p3cjgpY-1?{EWZ-SU@zcOvt=fw=G+Bj_$v`3L ze7n1qgX;^dLcqG$scr^6N{=?bK3Ylaq z1(i1=MFBEuAy}y4E^$Gfs53j#Rb@m;^b8*EKy?H}I)D0;8H#oG^1l}d- zO(Mg64Ml5);r7x*OvoLzoVd!LP)AVacJfHuF)Y2(!bsS%B%GwY(r{}`)#jdY%}XCE ziTZ05YiZ>qYAc;T0)2Hi+ZGusRka7d@&^3G{BQb`>U zB(wptt4o68TVx5N%Gx+iaHQW~nl%xO`0gnbY_GPK4;4fsQt5jB3$tAQ8Q?viAgWw!0ashyy{R@X^Y_tYgVSK zarhUlPtv1pJu2ceUs;&aOQKN=KZMP`N`lnGzW-3XE@YY9$!8m1%Py;!9Wcuj9{Uqw zg_?Hf2)bCLNP}0eihq1`Ceshy1JEFhDJVWZ*~MyA`?1$v_im1g{ z*I8l=U_V63@9jRZ(m0d!?09=!E7=C8N33Qf^o5CY9J*igP{ z^da1eTvVL1IKlebiV0weRx>f2eOA-26w6Po_4P}cOys3N`J#M}hNVp&PdPA^To@?F z8b07va#x**B;P1&XC*_5V*5ArII8+9|HRtx=-<8e>l1qm2(rC>9jj)F*(+Wt*B<2P=4O;csGjd~KdiV4bPl-g>4BYg|qUH3g)+ucTi z)9LVrKmnJ%-~Of%5NuXlZoT-I;zYOeY%MH|@?Ts{r?__=@~Ea~a^Kr3{lqU|$z$^4}NV&V#%+0ZXXRD<5g^89 zC5{Tk29r_sCu-un=#&?Y)33|KEG~@k?_pPH+DiOrL^&nhJ1nnvRS4ubFIMxbG+>oi z)Y_=pF9eY*cV@zV=}oy$e?Y2h#U@-$mS{5V%Qo|>tHh}rri1>epN~>PyV9@b#04-4r^DXH}kc}s|AS|{w{X^LyM?H z?EixR^_qI+3ie18a#0t7JKN*RIzr4kV=A%mTA@sUP_!xN`sv+#~HW=e@5K6ux=DLVvuMV98dZ z2-wI%%BpKl-M`iw|1+Pty`OKZW^&bu`7%BrgUURMT^*62RhA=-6e0zdPe$myE2t3S6Ur`}|1~LnpdyB( zrY^iWOZAN;9ajxAr%&ctD_^!60jhr(&iV5Ow!Q1wRH;_EVYvn_nJ7RvN}9eC9mWu> z;nWnSt%?P0#Yhq+i66x}KxJx5|c{AhALQ0zugwixYtEy-H+*XSU^DXm#84 zQ!b`6?f}zJ8CBB-M9M^UGcwWY3C4;Hv7YP$GsEa6fub<_QtmZ(7Pc1E8pkXF`y0;8 z;DBWZ!9+yJa^fb(@Ivd~_iY}x)Ck*C#2)PRN&ox3b5kq<>Li6E2 zb1IL2>4_&7NT!nc_@OQs9>a(7Gda5^~i4RAzpP!SVW=VXi{g}D=Zaf;5qLds3<%e32TQ~hfw zy|&!i+NPzGpQlp^*1?UUbG}SBDg~GAfKtg)I&@O;-Wicu-ajUom2y#EE~?!G6A7`u ze2up+@;;FnK2>crbU~gl>NSA`Jd~v_vK{#i)ky;paNTw0}XYz&}ZKZkJA(i>zlq!>L^#~om8`khUF1yHCD7zSN$2gY_ zSG7NE(_Sk}VpP6z*_3i(0yzug|5f7#n07)p+4H1hZZ3!7|09eN%C z|Bug0x4K&cMfCILcdCj1pyMcQ;$MeFL}QtE8ISU3e+ z{QC0qVPaqBi~EmyWb|q8YB;Y;na3+!>ejhe#lISaJrdpY1e{29p65u!INxpt#^yvx z`<{#6uhc$7-gI*v^cy{%oHoG|5X2C8Ji8|`gmQ={& zwt3Wv&t0Iq3!_&;>LbyVA3w>28vrIbQ|P~0i5r4%m|3I&S0TL|tHcXugLC=_>> z;1Zw|iYBap7)&RjPKn0-StOyNX9Q=K(hB-bI!Ha2^zjA>1Tk`3!|rxq$=4! zgmyq0>XUzX32xZa&$dAniQYRJzvy*gnorj&tLh>Mz=Y~`JWcxb;FHDGum6Z|IN~?^ z&q7P-$A5@$th!F(eh%)aK8$k`5DJt@FC3O@8eawlu?D#)TgUba3;!ZVW(@AxB3YE! zOiDP_6CKJJ;MpiDwpmclw7r)|L$&$Vc-5=5-CiKVLl8hVgcDjiZiuD4JDIKcUZgVG z%FuA%3?j9S8*9Zzh)s`1Sw)75#^4meaQuPui~3p)9Z&5?I`no-LJ{cOo-G$5?JM{1 zf2J3QNawW`Ft`|{U7s5u{GU&NLx^}u|9M_TG)-2I2&hhf>`PkXD#2fK2 z%wICQtI<0;gU*{(vc#%Orif4ZW##U35@{=zkk>y8>hCuWj%~szu z$>hg|i&xy5kAuqj1ijWcc9j?mj;fBzsh4}>;3TEsA65s zV#|w+;nyi{mpQ)s=_mL)O@1`Ul1s##G_7UMcH+_h$RfG}5d>cNz5}(vV6ymIunt8h zc%e?mTRY4-PRvX}f;O*Mgnjr1IPS!kwQlpKaF1=2R>`E{t?OqR^H9*7$+8$rbSu`x|Su6G_o+mZGGhVlam? z54(diZ8VL$fgwU_?Ro7_>iBaQ_9 zb0~Ad+b*?=?+ao{zrLFjn{+)K979p5;-VEuJa8kEnKcXEOZw?rSKB^mJ5I2PPveX9 zg;r0GBF{55!=DAQYY9}|PAyZ8wH&wod#0D*-Ua(dQBZyLfY z#D;)bbw-ipH9X_)`&>=Xg4Rz(q{#yES-YoE)dO4QD@4e|D88SUU((h{A-Fn~kGM#* zbno?=mAzLN7Q(&EIKnv^s!{_0XkkG@-v^ZiIfz>SrIKtX#+7DYpo+7?k!~PkWVRCJ zJy0dZFyLo%*HiXlCKGwjM=JMi{d1;ZW-+l963r@SK4uh)s)RS-Zdp^i{k(@ZO(76w z1#Z)onKXr&G@o8*vOF84nAK&##?FsKic?n%bmlq32z#x{k|vq@yVdO> z)QBS`{L9&iqp4nE&p%XHSX!+07;^OKEH$Ad=Xu@lCta|KwE%etteCr3sQVZXcFQ-lqd=SH4 z99fKW`tl@f;d!-RXOHh{Ic)-P<*c7@<-*A1Jh!K>O0rQu(lgNLAm-{Tk%jF60Y2~? z{7bxNEa+B$>l|l=n<#KIy{}BK#7QWq>f@>2e{__$bDn9}Ns8%`iPMI~WjHCMy39INvXJ3|fizV%p8 ztB{rtdj03$r(EGF*imi0_!y`KtpDcw+i{^TVU_@J3S#2>GK zgc%s)-_Hz)DM%*w$;Npm(k9Bm6lcqaZA1q1QU{z9-vK8lm=9WbJwqL+^{xZGcD7S!#q zvgpJbJgh~oCz55Ox@AEkHS8_VW)$&Dgh8II8&g5>4Hgv#p4V~CO6+^OutboFsaWk@JVct+Le5*5TIZmpb^@L_^{4Zh3jSP%RoG)eC970Ft^>!N z8-}6_vPt8`f=G9@FxSvDc7q6mjvBOfvdmHa52Fq$re%P=FxAY^rAo0v{nEAmaws#a z9I@Ji$RDset`izX<7c9}ps4Uo;veT|%Y>DeI#;oM9YAH&cj5^;J`p z^N(phARUTtG9Wd?G*WAAa(~AOb5POx4Z)oVrmRcOj|UFyHv*I>SwUa5ktL+=`Fk#H ztFT+?nEXXsAOqi7iUxkfW~51uZVpKx6*C)hH!+h;r{^wx%nFL|=$CQ0RnIDZ;W|Pv zBkc~es|d1XI@2>!K$el(YGphyLt0X2bIk`ZjW#}@ z4Ooibd{r{}*3Z$J%-i!P2iDRrdQs>PjY@g1uzBtzz!0dQP_zuk@5tB^9rIR477g?A zu2}%Bz5X740tCt*t^^ZfR6Fc7iM?VJb>c;Q+1nGYp-|Ks|7@Bw{rc@+^ka}px7e3K zV$Al9oRDvq5pMZz0_V%r_nu5R>k{KW}9Qx+XJc?o1tv*#L zgX{uv(3BaKTQ?nGI?3bdf5hMr94;;zmoFPS8C)CKTq{ zvOJ*P9r6aT9a#{%AUNXU2SO9&8$$VV{soTh{8`;(S_I)(u*622eG>7>%EOq)VRz{#ZkTy0e;(rr|C3%*VHRs$LU*hpvKV*F~Oum3|ci2!mE-jDHf0TTogeZdJGk zeAkmw$GCDSU4@zM9jt2a$@<99AEI=6U+pMciSW<6YTNE|)UvX)($va;E|xc=C=J(R z4D(|iMEM3js|V=cV<}+rO7@ZLK6@S-nn{bPpzwhh6&<*^?B?liscC7s^0VXU?Co7A zLW~|b;P?PvU~#mZo>EMl+=JG3gd#l zg)apEvr)rWL2(f3jT=&~)EM$tQ!HvI-=6hmP`&KIFgAXl%W zHNX|o5FqfQ@#`>S@ z0jzhHsw#{nmgJ6i{=Bv;6e)B6SBaeE`t);rLFru6Ptn?@3lf{<9@@o7X*P6JoPGRU z=!{$4`do(;cV9la%N>haWaNTq6e=s7NV%i+oVjrA2v6^0=@2i3y9U|6I?e7287p|Y zOG|T~)ST9YvlRq>CEs_Ej7>zyGCVA3*EF8AHN&DjldrlI9)}KfZ+e&#=s$VHPDn7& zfBZX-G1alz$E-KhxaFEF-Eun*3}Llr@Xu!L$k_g*(PVm6=diQ`@f4SmK+73TPbKLb zxOl$_LlQfzokHjrqknE;Nk(^|Xk5bC%7JfP4%7TjkSo!R8LHUO(ma3PF~m6!w=6ApI>{Wpwfb%!Hb3BjfMY6>X+3SGBt# zp41Nu^2r-~+u2qfb3*Khzd|HrF+Sb6fvWhyQd1?fx<-EHqCq+3O4RE z73px$Vs8(99=;#Yuo*gjkK5GNHGg+fC|vP2-V?LK>VAFtQ+(76tf12FkfCa<8Beps zIkv8}iR0HP4c;M!o<#w(Z zb)1(+az;H!bNukE(tA&8?P4hs`8mjvlst}4V>c_?Tp8CZ_R0oSwzjRRdQ^TF3o0VB znReJ<6NhWt_yjY-rw(>KNSq;^*RoNi`u&M@4GO^d94K*p$PoJb{%Wv-td zqPgy6i) z6Detl5$XFg6NhX{Fh4l%t_{7UszQ;PYy_l|-0Nj&t17N%7Iaq;FZ~K~i7$w&SQ%Nt zz9XI11IJ{$hYJfI-Zp54Yd3l#^cd7p#eUcN)bg)o=W+?Rc6@Cp{H~5d>PK$7VM>*u zh20AdZ%#MQ(afLtXoi2AT!Ro!!|w_Q;10qsy>pziJh-dRX} zzaZubWWG6{eK9mWsD=&h1?YeT(l+e6{H)q4H}WxK88e=KUxpM&#wuv78pqOleER8Tz|L2qR}dH ze;EpmEbFw|OQwZ7$TEBOREf;1tm>kHIepNx4&!`vO1P}5EA4d5fz8hga*dVo?eWyH zWtTj0VW^&$%S%wGu$hT0)h4ZMI~E%gX6N@ZU@D;BT35}5(=tGz6OwWes-U;MIJfMek zQKj5%qJ+QiIi7zF?(MCI&rvXfSg`48*M=uaY_<62)YD&Gdw2dMRzSfBb|nXYl_7T7 z^KcCLM0jk!!Y<0p$F2BVbBuW2Eafaq58R?+KX~S`&@472i#6WfuDj77{OR-gaMk;S zLu#J6b`>R^#kjtG)S1R6(hu`GEj@r=$=lOy|t z%3tG>)))qn0-UyW@N4J7EI|_AHFPa-+Dw=h{)-FD-hy`Nk04C z$-ld4<2kH0t6N5a-H5&>=xV6i0iJID8`$)YiqkglIwY@afT-(^IN(5r9L!!cFuhGa zlkuW*|0mV-e1?-gndQ!c<7))#C}o7N1H{{_BLZQQ-xL=zwjlT8MXX001Qx-I$rPm0 zpjcQg07w5w;QQ?5inE`msPU#%v$V2grXHrVHPfoM~Sk#07;e4nOH=KKvy6NTtLl572CtD-jf3LLYQE~Fc6xj5xRY~CgZLCU6-^=;K^tHRK zH#l&hu=82V0sX5aGC`p+|4&*SHF_Zj3T_o`kFfTpH9Ppg3f5eq-+FH@wS7Ga9%_j2 z^0iKtY1q0mCk9V}dm~||CKS>9SWmO->+S9RP(E67W)wi_ZQWwbcXRpQyVtE|%9F}< z3Bp*`_hCH1c+=D2;lsYpea5fdVzTSIr!?5=QP;Y}PV3%1bzDPt!^4g7(-5WbSc-Va zlWFsV&v^^J(dU)7PZ3W_aRJvQUIFI=8+rF1DW5{WYCnD0@a1)~9uhx#YKHB$EMBep zbI}0re{nozY#ROV2;e>Ke*VvndOMqLyxrOH`1w4p*TL7<_ppXzu&TTC{I)Gwy$=}D z+1csX&i?PU0nC(y5szZ)dFo@Hed|uw%G!U(RrY9b?v3jPS3lF#YNI~g1TZE&>`?|3 zUMVAf{J{#X2f3_7fO#!FczEn$XiW%Cqc&f|LXLA1riP=LeP$&Q#qOavjEtfcoYN#34T9BdLRIkg&3i^FD4U0xsl*F#8+8HefNuif z2{^&9V>e?P?@hpF&c>;BO!QG*2__AT;8S}fE-=$4zzYWT=T9r^nouiQUBXaqCQXN^-HTosM zeuB^3!BA$3*asuq4Cb67sZ$y#QB;6;w>U7MN)DI#5-F&uX z27h<^9tQB);!-=F*N{vw!-a>GxRCB^*v zDVs@cu6=73Q?tssW3Nle&d^-yp|I(l5gasc7duEG`ocCE1X)Uq-5Hphr6iN=-p;A| zq33FEq&ZvKG#|}rf0&z#4|NFFSIcOQ8-MX;xoe{l0r|!3;5Is6Du(&`3P3jzlRd08 zsFtC;=qMN8hdNhpsqpvKEqgX20Xon)$Q6B1aiFFfN>01}@)qJ9}Iubul$YS@GKGgSiS zA=xt3o)DqP0^+M-Hv2b}YxDD@fZCPcwJ?XVC=UsjCtE#jMI2@D?wEbl>eG%A`l>HJ z;JWwDa~|bz=gjrH?qvJcNDbLSr`}m5Cz$iY4?h;r!j=Gx1gv1w)sJgB_B>&5z6baK~j#}r4%TZ*V82R z`Q3QgzDu*zJBMIRO;j5OLqh@IJL-Occ-!`HI3>A2JbaII2+LtF0x1eHkCt0Vh$e7*Zs|hh=|r=-iKYYc#6)NN;_=u{15VI4`*7pDbLTpyjbO@fD>Z{K@1{BTmXgoni>cFM1AV>cX2_Y{V94!e_LObB-BDgUSZNyg)@{y z)s1%HqjW6RVXd$#msMR9FP_EEh#ZxYb9BdNBbzpo(12fp!DHzMip?aWU$GY~Tp*;W2aw<}6@iH3@c_IW`Ki$RGr$Bm#4D8>Pxk6Fb2}Q~`bSe`lR?Wul3}$y zQB zacPt3H8Tf$JV5ZBxhJu?bY1aw18EJnK|ql=$}-BrO89pix5Y@4)q(-H=1{+VlNO?{ zAoFH7#Mf8+Sh_AKjws@C`X2mR$`Ib%nq#Zog>|RY<4$80ZFF~`P0B?-1lvN8gqtX~ zgYJsZn_eoNHM0Q*|{;YTf zo@FzIynbIwOp?DD8O>BRD`&LQ z<=*9J-~06-26<38H^}B~#L~PxIPUa&yv5y9Mp=~nrtToe2=%b%n!L=Y7OZw8yDka1 zM-Gvx2{;D^JcK;I&4D4IqQY6U1WSG^WZBCGVK+Jdys0^JT8I4y$am`=JPAXP~~M4I3OU zl|OiC*5p8IiD&M%7*HR_=Fl@`wNGj}#yjiCwVkL~@NsWeMWW9tSKX4d@&&#C^hhav z)N?f{>tb$j08J8vMJ$~!A8_s@45BagP-(zUN}l`ncWQ*Tw}L{h;aB#azvc?l&_7s- zT*hAA{SBP8zWil=vkHRFug4-O7Y9UX~~&rJ#&zTp0^sF8Rs z?sJaKZPd|IppGQ~3s?pkE zyYz_<$Z_oi#k+1bU%JGFH9H8KlCE_|5PDocrl5Ux78*jfW7o0`g1HU)`BQzhvoJ+5 z|H6iiIx;Tsz&K!^Yu;w?DNh3%&80M2X27}Q4=Mr>p@^$v-kKvtvT;)98qwAw(Z^m< zD+A#OTSI%&)RRP3du~Z4G*-@iI~WxfMt{{BeRzO>f+F>Xo16T4Cq~KR1IM0E%<#@@ zZ_(i*=d*^|_AQwkR(z+U2^2!|Gg67$4OGkJ;8#`PxvKOfvmfZMBQg6V*K?n5(@!U) zh8&fCP#7WB*leA7xe*CxP|=wq)DQ)oJMlQH!b%*AulMIg0r}NnbP{~(a#~5r<2ZFf zGDr@7S~7mwU{Ie0aMO=cX%qPeyf9SLKz2@tYN%0=qC0-bV6%gGap_@ubXWYq4UtNq zjx62-agQ*SR|<$uG))vka$+20EPCJuiPE(UUr5H&Mw{|F|CC+1N0@rx&D6p9h^NJ6 zo~!%6Acf?YEjk`bR>Oc;$IoVTsQP(6<&&lk!1drgMW&_1VJIX%D@yc6&<$17nUAfj zRZWqo+OYmYL)k{Hacv6Zf8s1ITi9|om`SrpZI*JOan0IwRUH-DkA5WKHldo8F|3Xi zpwWb3G4z6fIzNpCtyiS^Vsok;=96ox7_URKv^w<5W9fF=Wb5+oJbj+g@DH3-^3!Df zl$ZZjPvLSeHR##*wuRs5;qHJkl>o?CjefrjxS!COCcrt`Qw5ZNyJkUdS(WrWk?Ff6 zFfqjxL?17WWR430rRq#c=m=l@ibE1Ffos{GA3f+yPO=Obv~@>R&j;Ob48e!w4T1yv zWFI<5aKn%NH}!|E$F2^|WQZ?sW^=BDCYL|1oDPWwo6?7LlpZJN&#>Y;I|j@cQ0H~E znq5`ah}$<;q2*}c7FYA;wm046`Q76O8?GEmy$}0nYybdERoVp^dHk|xpVwNEa?I-8 zbJ1OISV(hz@*=t-V)^??-*^m;pG~p1o01r^>NPiXI3d15Js>hi!LtUBkq&>~pw19W z-{Cq$fi}S2Q&Pi)0x<5=|0a_E=Nj<#6p-;xAo9Ze zlP;grcpd!<<^EkSnn;M}zKB?-(W=@@7d8dS?MaiOM+eLcP!6=VNXV8ggM~-&b$38& z(e?D&3@(&>;ned;in#qGUC(u3jt9rEl5B7`ca_sw5WFO3w_Oc)zL7=<4h3(vo4g`z z>yN$VRk@U(ILCudpHX@6@F#MieRQKX>9XrJkHv_Uk{thdw6r)RPjvMUxc7<9AXlm! znU&kC#~V!?+aJgxNJ6??-PNQ3Y#4klZ*bEr zN-B5~TN}hov>UGu56xs%OeK8%LJ-1WPNBmU==dl1Dm4vvDos5qk2mG)+p^D9eHGb6 znNM$S@V604TqR&Lme9Z#)ETAmP?gQyS&(LlbsgU% z2V@JP>)Cq?zTLXbW$O}GPPpi5O3c=Q>_vh5oa>~c@|%J{&4bSFt7GD$RZlJ%8VP7m zWKJ{*6R|uBLY{55ESpN~nP}(xSr{>&}t}LI2CCwk6JKR85G8Vl``pkWuFH z#Oss%+~LV@#B(J&Jp$ZnZVd7*OL$P;%$7Hu4sv0*bi~7#)^UpoMSM4fxyG@MP;Q~R z2FR)|ou0Ok%P*G;w|E~+N7r+vj9L{f^<*~?H^IQ%m z27@!b>~5)+rlqd4Ih1q~-q~X1TR;sROUUvvU`X6XjzxM+-aI7#+{5clXJ$e9?g1M9 z;*Iu_OM!*CFisVLSgau@Uyf?yp4q33eV?G@jciL6_~j*U6mjsTouNhXTBm8-NYeDe z#Q_!;4>72Q0GpAtYAFWoe3Lk2ph>xr~A#~V}|8e8IN4`W;4`@DdAe890jjX2EF&nsc| zZs!c|yY6P6hc9H_qcc^#_AE=C4yvn&^5#v}nz$Z~bv7zqbZBms3lhs5rl*(&`$hl8 zPn85>cXT-ux{Wp>=ixU0DGsb7^SsK5nRk%b>Ox2VQT|SDRkYnz1{Y^Cs?B{53XN#5 zuG4`e{;77@l&AgN?l~>P+L_aDY9mU8t3ryi+-S^Drpe zG2v)GpXPmsh^PCPaYU(2ER{KBit=`832CUUF<7q?PFY;r5x~Y&_mRtlSh^DsVB2%=2{*-{KUROU){lbc)rrET6^rVBw+ z%XfM*`FT7>8wJ$)5shnWM4#^>Bp1dsm^<49b4%M4OGp3!#5Ui4HEy-(khs0aM>GiH z?&>SK+vGL=3M0<-62ZET#XL0e$qc>Tn2~EXQr6b5v)50GG0qTGD7^pY<7TTF6-AX?rkrRuAYm&3&f3mTn4!VgliPnQmw$@c2p;R zUhtg^ZV;mJ3Uu&M#Q(f^DFDp$!0Q?as6Gx>#^sX z@^{}jTOeXza_xapR(4NP+Hd#I#o2kxZ?4UMkj}*@vSk1Mbfn+m|Aa^X@B7_=Q>?@P zJQzTBdKZPLseiM-^)FERcfDw8O(?o}DE(bVFBiyEUyzWKnTm~%Jun!{OCpW#(b zjDit-pO0~5w!&QsMQjOZPG>U7AY6>pKjMd@cC6}PZb@cxC)S!pZAQ|=aCTfLlnBEN zR+MSyexHeVu7#uZjdrM5{hs*Q*ylFQni+A*}G#*k)KGmHnHSk7VpooOJe{jHEB2y_1}a_*zUTbK^IqFKPk zlB3Ec%**uv1VNt1aeHB|(`t%+dQMNXdJWSWRf3Im`yEzIJF&Ki4GtHwtXKRNzZYhf ziXTLA95=S_m)ed8BW<`yk?q_KInXUwD&6jMertVZau9z}@ch75G`c2gnlx92>=LuV z!C|4wdm)~et+!eYj!Gv=i~NN~N)uRJz_Joit=$Ex-^elc_nC{N^Wcn3=tAC6%SqV* zYP4RTzh6GRf%-CDiA5A5Kf@Ur*dlv>&OuQG6{5fS6 zTyoO|ktp2t0#g*)C^XO!erw+L9zMUzeI=NnN)S5zMc@4A!sWy-%Kk&hwzlhjyiaS( z5qxOxhOz+`mkPqw$C5gpbB<3$UF(7v&ZSonJl-T2(-!#n-yObm7%nW7^av-Sa>___ZzfFk-+}Xa%6a#Y~I4* zvFeEBNGtL@rKDv&sErOl_)IYVl11bj_LM(&pXgwPgHRh4!`SCqvh=N})aY&o6s~72 zx-=y*1dVkfbk>7d$Vn6NId{tyF%)7lc2(cv!V{(Rw-0qlgQ;ht>!l}kq0u9WhGa+k zgidmIQ^^LmS)#~9=_)LcWGS2V&X#jU9(dlTV_`D|ziQ_+lXmyR3PA;YSZ zTpH;HD8E^;=1gd-ucVV*h7l;`S1vDnso}eSbJOqp4{y}naq1hGkwLy@D*WH%)Bh|r z5>ki;O)L<&|1^}Ci#d_7D}}X(fcgU$f?}$}Oi~tiz7K%!nHU??beQ;wEryZs_;+=T zs;^6ZzgnqwgJ6A!^m46ouFP&tYLrlznnDmyq5}4t_XPlQbmht^khj{|w>>QlAZ2N9 z8b_K1&#QQ8{JZK7=pDo7t4TT`^q*teY&0Z9zP#@qfDtL75}uML#+r~McluXjuOl1? ze`C~+;C;UTxqNqF7J@N&I=jH5fhuBR%F(6Th;%VD*Y-aiVy^~Vg_`!#_&LYBM)Prw zP7SgMU2)0cy^BgN4@QT^X z?QecCGDVF4*d^i)(V8X9T0~XKVwFT=Lr=9c#tYu^4?M|_2>63|i3UI|I=+vK(WkzU zW^|5}`gJjxPu{|t85EqFT)3)b8zoQ}39Uz^HQ9Omn!CJq_0}5);N||-yj7ZA4rC=< z(7>N3i$|afrgp+H5!l@{v5riIX&Pzi2bz;l)wa-n(dReC!&UAJ+^bi_3tx_u9BlR{ z6pR?Bdmci5*r}_=|I@TAfHQ-mIZzGR!?iZdg-6zPmQj7KWUgNXpXZxG=h5fAm#Az` zjhjYPBtJ1lM3^}Qg=XaUDtoeC)=Z(E{lWaTf`n`NjDduMqpsMU?e<98|Tk^3_d*IIZc)dwUbqx;|GWdd!gE}^fxn56wB|*!` zyyow~;;l}@iIjlI8igJdM}pL=TeEoiA!PsAJ9#lLciy37xO1U93!IG9+^#Lhs+z5c z7(IGjmI;GBiyx`(T(1FKqqXqS!swdRN*ODgNFxYRo8G-QxBfJ%Q-UE>R-u%h0W!Tg zbqOMRN%KuU(Lgs{rzZPC%`wQ}ggD5^4M%6ud=`2-rJ(IW=`rp&z1nXuTN6yW9nkw}lRIZMjPEd`~5L+P(S;0KD~a z!`dsbx_*UC8sgWW9N)0VR9!*{@O2fmE^R3nEHB^MmR1apVJUo@%=-KFaDE)C792GQ zvS|eMjVdH-qxrG0cJ6}PbI@>=;OSg{bbEU46Q@+Jo&I7%b2&;-^Hs;#SuqOND}f-- zm_ZUfsvJ;Tn+p#GpOf!fL(_(l>(1&*D`_glR7h6^t4_2cV!`CK@!4Z?2Bl|K=AQ_8 zd|000m~E9q?}fvIoaX~MFvPQnQs7-b@yL_+Yi()qujqELLIn z$N&Jpk{FN1ZAVjMXX4F2x%xX!_>wx#YvsFbFYkbKt9!vsPFaP=kr0`dq7JT;kXC+y zAUDI@G33_s@gQJtyX!xw=Awd&2>MT+_8(8yzf979*1eC3O>1b7eDTJED>HnbXZ_6H zy5?O@#JXy>K(x0x=`D0w@hKUC&71A%YwIWIDP19hUyV7Pef}&dr;ifEzTlCDkfWoD zv=hEn9z-dXEXWHLS#eL)&C1Z3MzPb>B8Jo3FNI<+00J2alVnkDH8LdGZ0sUTNj5S; zoiAU;o}5~RHBezS?-M?^$2Q5v_bqMe<#YYDr#yIUl%(sVzr7*_5$Jq+$~%*?z~ zWD8ZVzf0NkRDBAKOv$9~Nwo_iHv}(<<9ugNQAFZ?mjq$pe}jFK{*ZviWa=Jw7cpLEHy2ZjETp3(BKa;CmPI==?Hw)JtGkD+ z^-0@z(@A}ikX!B%?<4gWULnN|Tjwe85N3_Wbzcsq2;NSl_v}|$bjz0sA|nxmSNR>j zB$ZJJbPa51M%(s?YUE0^oa_sNf3swo<=|jnns?rWOe9e6Up6;%wcr!_)41#KV`^29 zmNa^F1_aOyVLktjK41p{T4<_Ezi+ILP#c)|1d6~;v%qdCC%|mv4plUpN}w2KBdDbZ zI3xA5v=>)M>8n4(-LT(g43JbumbLJ!nlESB{x}zl@Xc${Oq2Gxi6$_1ByvFVN!q*m zS8MZ?zL==qM(b9GTgRRKyz#@&Dyo}Y%Nz9@sh(V^cKc{(7{tOXZnR_prU!-eRu=7OPtrmnr5M0(2rS{%ZdO*`?T zd$;(xN)wN4VRD94_BNn5qqsSSA|^-rLjN@i7Bu%6{aJWqx&Vt z78pr;#E45A5q)Iy1u@4kTuT#C8YiW=s+pb*LQG>c(H!6jM1W$e#a?k=LlcF_G!J%* zJ`ymGhTehscHLota%vQRRYdU}WyIF1oVjOE`JBKd(F=9n`cHpXpF9H&!T*zLb>Aij zoa+BCKIs4Vhb~=j>;Eqns?lcQSz}hW&ORVUNAz zb#XD6g3-TU6353B$8H=K>SP=UG@@cg@p0}MH_R^BiX8U`nSJ0buBpzr9ywF0WV=LK zpm^E(M`J|MC)%@tAz4e-jm|2DacFAXQ4@sM{k|f91@7+y>7QCYsMXxE}9?=`XilV3yWM98W8Y;2p^dDi%3Qe&1WZ~ z2KRVfe#}$ccfwkxEx2_aVh#jz(J|mh&a2-x!MUcP+T;%StfuoxuV^M}{{HI)*u6li zQK&BaIBBv8pzj+zJ>#`Qgyxo2qJ8z8;19RY{7>&m0LSUmbi8tQ}ub%^vOIyC<_8faEH%YmFPs@SNh6tz(#4L+>dIO9;PKXe_qKUD+)$o(@t`~2 zHY+et2$Q3Hv4eawaY<}cadX2bs67h(0QTKw)APr^Yyvx*_k(ez>wPLb|B42*wtN=> z2y7QZ(q#Mj?5Vq?5EEsVXrKw!yE6337sIUnNKqpgF@u~&F-JvI$C&Z9hn~5mSxurZ zcbSfm#m`~C_-Ms|+gaSWVR5w~2IH;&))LbZb?ous$jka4vwzNng}wZ?a)wVkz6%y^ zN)O$|{OqV9K!ed(r!k!UpNduJMNd4_j0L^I17Vbx_xO^aBMxoMCxO? z-?B3-%i21l6&X0d23*VAyYrYAO2XlL<>ARD*2-*w#Tl{g=Jj>TFBGLq6Bp1E;r0~G zLRT#YMRWG*U3sh;UZ1Z57dj(KYHD~5TM6V{DxU^*=OpCkJyF1d0{!!%; z0Fcw%jQIG=NmUv6~t0@F6y#jSQ3|8Ul`JhL&A4mP0X~^$Bb%V(`N4f6(+4#C6o;I+- z@0tj#pa1i<%{TdrC8{eCt3#izUSL#WK- z**v9jN4u;FAXkp1JgGO1?1wEq`Q*SH-!XbDCZSGNwd-f^*Zsi@THxhA6h*hhmspTv zO>ESt*L7*WV%3nR-Ik+1%0=lQ&9Ij!kfDAS5CKa( zlcothJbJlrR79Ibk?!z!hp%b#;~bj|OVL|K_hGTk2^i??RnDTGPSbX2&BreRU`AOq z5x1?3R9to3c*@v9k7|NjoOq82uPZNn0MgJdr}!)kZqh(}D|))qZs_|UNow)#pNx};Z$F;t;X^JYT^qZ5LPGw9@OOcbq7S1Sk4 zH@ED`9qeddD&+H5H^DQXiKLUg2=9y>jYwPya2%mn#v~P+jFoOo3OdsazkyYKgchQ! z0gow7e|k_u)mo&Zh2k~d%bG5-bTam3Zn;)6uCz6TAhaFCyRxdiJC6pRAzy1~>T}AO zfxZJS`H7N~nl2n9!Co6m%C#~tSh8+2uP4US5=3YSvT32#i~Qh5ETgZjQ-v%>aP66T zWbJ*B5q>1AAdRv7ai;IlBcSwDXMe_L=cOciO(x8dV-$`| zrTx5lcGoSYwih|TA<``qI+plfjoaHfr;||zcFaQl*!54=Yibr&FK@=gV7nJNKg}Jm z^&1UlBx}u5#rgt}BjK2WcjNBL7ceUl|_PjxwCiY+h_HoRqCUomip+FN>y)_gt9wx4rCsk@E%Wf z6uvG-i2|zE{#57Y8KQe)!Rz0~ArNWJbEjjQDgk@_Ttw&TR9nvazja+K;o6wksasxK z1$4(AEq5FC3{Q`81O@H#IkPV-MsmmOP&1%LC30)k+m%hmKz&6pYjtdhSk;A}BBW3P z1ms#%23{n+z(Dls^L#GxXAf=%TR;Qh>&=m2{$!zCWb}0g$|CWFB>bKkJ z|6?Hg4~O|L>ZNN~;9uLbe_Zh{@A_O#B!vlktnS3APce+Fs&*va#X_fSEwHk1`|h~B z#oHq+VYnuc_Bmc~lJs!`B(jcv>;4^{+r} z9zwwRgC<{RZ*FD8HW?;?6}t7libpIH-6_V!Bc&}U0>`=AYE{@86kR4bW1xt8OUgQj z8S$j<-USXhEr(~#qUHfjO97KVPqIkl{a$XV>WWl*G6|OctHy!H29PEWN4VjitEhNnDL?`r=i@H zZh|^v>M6|137>X{1f|rJnb;*b-^020rO1m{`{O{uG_t;2??8kYySCDFsY}>ThgLOh zaf{J9%n(jnY9nI6{62V`e!#3`(G>_B>P_OV@E%KxCY|Eq6<0x6pczwcu%9W5ULqW! zgSrN@j-PLI@VWkk3p@JGop-49R?7nXxx~II>!?LGPay1l(088MN^wgI9pyheC&tC@ zCmnlLz{vUm>WdaS{I@_ukzKdlMSghZ;`_~HJhykxlQR)MIEZIGrA@EH-OWdbgOAj; zN5g$W!$LIkj4n_pOHb2q?;cd-1r6&`{Q}1t&Y-WEoS8Pn7|mnAOpEUgLP2|~A37}F zkD;u9fKb!j^gL_00S8D)-QOP&S<|&mBTU|stTYXyf^eh&6lGh^tc=nv`2%~+Ap-Xs zlk8)3OIIH6XX56$MdYoO|CR@II!;3oyS{+-k~MaL#I0`|5S{|Yf+Eh|0{TG3cw}w- z!2LU{$lq@XFfR1cx38TDp79j7{S~a^=JXZ26;bb6_t-?P=!2HBszUBX6WGh#t=5jT zD8|zLri@11xNFcS=D#%99S=Vp1E1EK@6OA?v=Dw|Ld_kEJH+&j;i*9D+5&*nmY_sG z`zU_Ek3;1IE~D@_lIxEsaR`t%-!;|B<9`)$RcMw;&{}C|Ai&~l;c;t*vFh>D&K+3$ zcV|M5kG2}37x4gD^=%yXwd$jcT?EwU%PFw;=yB5U0Oj^v+TdU#$!K&M-kb+6MYyA% zL89W>@yANP6SR%f&s3lCVA$pQ)YOeWi-=@1pC6CnFgP?E(PBt?Yt<+A%z6dTH*T7_ zA0YtBBdmZ%_5}$sqlC89fm|)?E&SQ`&+Z~<_JRcDtkPEPKjzQ1w3iI|qdZ(nW65QY z)*gQB?#lpj62xRZyG_h{)+v*YP|`oaa|t+=PaZYjs?@>%M>$>pKbh6^OBDy@t@As= z(MFhI;9f}McKxO__T@7Q19#ji$YX3Gv#|H6G1gjrKbt}k{YaHZbG;aAg;sU;{Mz(vXqeyt>2S}z>UQ1wTBhzVM-$MO zk|X4Z2oR8qmt5=z-E6K?JGjLsy-q#UwyfNP7rXogr0XWba-M)W(q9)z*R+utVXUX; z`s_xEaG>z6h~JL-iy-`%Dlxbps+H~E@O7b;*?-U7noRFQ&0&UWekXSIV3)BcNuWa{ zM#u{V-x7AvAP^cT*u5k=UF3}lhC%h(%~fS@ymsP;V1K{Ueu0FRvCpX*W7LsNb`rsX znjMR%sd$&2yss~<#;QY-d1N}Y1l>0vipzf6*}HVUSW~zGXVf|!JCz51s{(akMMK$u zxhz~xx|FP|_bt+>(%KV3;=pIA)7CyHwOGfeFf^cvz=bCG_QVx$4?qc6I0~L0rCwCB|N5ILIx< zFBtnU%Qo?FUA@|-<-N00wI{TdKzt855ER&OBqy!T<{79vKe5!YRHcoXXujeafVQ}h zUtUo|C`})17xJy^W@ahpJ(_UX{_%*WYd2;cq-d?#1h8%7U9_=C7sG`8Dz?P=Nbv_z zaR#+#uB(AKeu%x?igAd$CivIZkl!$Vw3M6M9fZIac$;y$FWP$%4)h~-#qvo%w^f(wukfrbMc2D$*%T1ipg7{%Eo|EZkQSuS7r z{ZmIx)NN40@`%=F%xx05Q}|p^b}gV_F?`u2yR}wiS_sA-W)-D|P12V5q6sgUBB1%o z3;O@dYz9qw>{Q~!L$`J(RJt^Vfs}n3!n}!HBsKNB%DB|;PGIVE%;(oDqFez~U2MO; z+&A@cj8+e>Qh2>b(}c0cE(qpkR)uJ$P%L-;c7zdGSAnE@U0S*JJH$V3!ucqxw<;k< z`vwlkC-=?2HC8~?=h^^$oOPuW!2I#LAMHoPA5l%qiip`X5=STKAt$un^lp86*e$va zw|+iST{A+Nlf%m3=KU`naS?I*kz>)Nxul|ND`YkN-b7XE=l{AU<`?N0kYt;~A zn=mK~I!NGKS8d1;fFO^8iVXG+3=4pcdxfCL%=}&}sZNN1Q)j9y&|w8nG?ByjF5&DR zdxUl7guJ}0)&Z~C>0uKr{PCyRuMYSzApKC(kpCctMYsod2fXitPFKH-B%P8D)tDtS zs(hy#4i~L$QlWYRe=?Sm6vR!|4D!+6a$EPe?7E$_^H$1X+wUKHKpjggC#Y8ToBMe}2dCe@gt{tK#zrgns;&d~F z`RS}n1|XF(Q-_FXYG$|?wUn5 zi?n56R*3_2N9X7W2c!Y-j(m@(DKs#1MDu!8NbyS1zkX4vqVOX^niRlQGYkN#v<(IK zyETR(WcB7!FgLi?x9Lg=aS~P3;J8NjN~S(YU$#WTeZf{cf~l1Sc)1*|bhf?hBLo3A z%nUvqUuFER4KCy>`)MhP=SSWFH-i&{i!y~Ritaj~R+?2#@gwHfP|4iaE4T?q$41TN zvR2px(epNwpbk8|3f2Jf&mxHIYxY+haRzrKH5E$pY5mTcv&>EwD1kP#Mb4|p5DWPP zFcbXusV?i&xCl@|IfhROhrIE<_%~l%U{Le7J>QXWHHFp1?~qsm5q(qYFD-_@V-g7g zP}xH@eNCFih)Eo}A^g+!H<*|VPV-5)iX{hR@LgQ*NK(CWEUL2L;wASX@(lKgLdnF& z>ZdKW@I9D`pTR<2_uCMxV=HZK^2mB$VVS5t9nX z6Hu&7AAV^FGEYCl*CK*1nYuxnt}^OL$l7tAP)Q_Lk}g87s`yELGJO$MTwX-%ThM%E4idrt#$w;G5hW z&v<-POe&#zpKY$sqp%os*B^7Fz)cla*q`u9O5m^|9)%4e4fkj8=h1)Mp@wb0S)R4! z<Gf`I_Nhyg<0Y01Khq17kVSAV<v1be}eW9u#YWZx$g;hEmp02H|F??!A zBiv8w3nJ>URj>Uy11K5#2vi_5w(f=c;i#ddf@HmO+L0fKR` zjmj--ZGTk7*eEsa$SK5Q6mh6kaL4m;?W(IQ&UM8QdhKY|OzN8&8%r*F(K%UI&_aZY zF|#-qpEa0vdpds38g-g*7)GO8@)D0>GaIVZ&CA{rpioLgblpd9rr|~qls0=B-N|(IyH%r4>GJ#+t9Unn?FDCk=*7JaHdyltztr3pfw9EUZ?69Mg&f%U5fIZ5#$qm z9q3NcIgu9H`T}Pb!N;y@ypS1oa)VL?-5rblDD%+xGvQ5+o0SGjV`at8RmMUfdB$qO znj8FX$YC}V(O?ey1y$Nh?2FQP`^`yK$7rJ4n%mgs?J_VpmFCW6}w*?eLTED483rbi7Rhdlsr-8|%Ph+VNVp_vs77>#iw}c`DOO%r`R7J6Uni)@nGTvL1klwzBO36w{cumcD(k^TrF0kh6eJQ~fz+hmSAs z8O~;CL>`lWh8ouXElEoD*~E+!mxqz`;tin_hg;^J)GUADN9^&vL*YGe(_>7ineKux zNim4~;^9txMD{kC5R(yFZ0O2!i<;%Z=i4LS13Sz&<^mE|=)ai4|HTz5n5|x>zx<0` z{Oc;kjqecUznR8=@=F+{1v&BmN?C5`vwcpTKVYK)#Q&-MH-(S_&4{`AS=m=7C*nj^7mVzPAzlQaX5BDwlW19c8 z_-{%BoV$?6b}e5v zl>z2vfW$3$rfAy~)8sK|# zVGC$y_`CAIiA(Xu#;i%^QWYAi&<;Oxr0;9;1K=Z&0|@{ z_FdkgGJ9kM($;va{y9#nk+i<}X*2n^|Dh|FZ^53zgedoc4@9?i=LRrWaB$U!B9)h` znzRtROr5H}KKS~m6*9ZmbvuFz+Y-J=I3wW)tZ0n0Rm&o}nI}qQ(b=5^H^vr3dNH5L zY^@>X9yom9Uxm`!M@G2)7p(pNyuA{_p`j_1MYNBmLwT!X#*Yny>rj7XRHCk5o_)Z$ zyF)$lRUUEhfb%rIs_fr3j#ACWY_1Rq^0vNLBj{b5nJOCNl(i)G8^s;Cx;ibac_YOt zkEfl^JAOkc>u#TIJ-cH&dt299e{*>Y@_u}K#2@S6m$mUBHcw(}uq3#Iz2C^R8%q)& zi_gAr`l^sr;qdJe-XmT}3ZfG>;JhY#Q#ApLEw)^TQO`mpxvJ#= zX2Hl8oVm1mPjLy6{f9{=RjYf!%bd|R5xuB?pi^+Ufx?*~NTq0x=h?ph1{1ubE_|q* znfnkhm@E=FAXi-_ao9rfxg7$iub5kb?qxf@TAlWki zb111%kjSDNcOi`ckF%;*AVgEJ5MGWEhnklyW+g~ksr-h~tLXyju76k7WJoi?VW*oe zp0(fi7m7ZyHe7Pwyjl0|$xmAYAL)6|Fok;E(GDE~ou@V-_vMjohhUmp!|d!VeDzy; zzxvVOQGu8u5rM2v**r;8pel6kbY}V-i!ssH8p8zE?+KsB+tUcVQC?AxdIUo2I9aK* ziO_DN%cI(v{T|846ihRs!|eTGSHo2b&!j7;Q2GdZTkyhFUT14{6o?H_h~NSzk26J8 z(QU@?q~fXZNoZ5&3fa_xftxN?XR&UlRfeF&^Veub61mH!U&;I_SmXlxaZfvovECLu_`2eg@oS z7mYY1RfC6CP3mlO>h1*b&tlbL%iz2_S~BL{xO2>H>VF7L9gA76k zikB3&Oid!aRb2X0+*SCjmJPNujcog{+Bto$fEet453W9(1Wfg6HSgRF1cw#j+2(@<)^Hg)1PmkJZIx_ z^^VQx-uqGZwg-}zul<}TNvDN&AFLk6gIi`adl_vJe>8Zw`*fy3YgV&2KA0`SOv7Pl z1$NgvT>wiimBi|ioJ)bZ?QlahYV3crCyv{%+69pAg4AXLR{Mzyfb|x7uOzGFCX8r(DKz_vp41D$ z4%o*#{5e{W9l%|nPTAMlNe`Xc@B-(iwp+d`im$;&K+64m0C$~v0bdW>yx^A>V#u{Kd?TT-#)+UIRgyVDAaWo6@$u)5he5~@F4yd`-} znTuGGaERyB$7c>HC+BEAm(T(*sJ&%5Zz(n6+)(aSZ{!2=*fAU*_@t1vsL*41S*v`W z9R<~>SVi5DRT{hL<}w^1D)Gx;ud>O<|X6ytjM z!+r#`VG+-c~kOyDTary%8f_a~(m@Fz5hX5szRy)7MH{!?m$B{b76X0{%qk)H+H_Puj2d@}{dtK-i9=vh7Y89DWccF` z%>bh2tr`r>G~~T(?M0u}4g#FcGuo4s6&WnOCCXKA>EJ#?TB{c-k53Fzof(iYyNq%# zS=rS$m(XZ_PSKiJxUT4eLPEOe(fB@O(;_M2F|>3kMqK*a z;PP*3LS#;-A^1r*bmHBvZCfX1I|JDQDK+JNH5bnmW_OhegBv>Ar4wQFo*e3}tRC~Y zE|NrUGx(ipT*wcWo6;ooVf~2*Gz~|U4fLTZz06`$<@xl*eeY4E(P${QDpN-Eh8HXy@$Dz$ z>BqKzZqXEYkyBe=5J$8#JXV`y9DUH&w4ZpKZ8?|EWs)*L_xG{jLs%BR(d`os|7tY_ zj$%h@u?Rtl5LY~VrdOZc?vT|EoZuP_ySpK&)u^8cQA_==!}2KIf7n8GaUC9ktDXrKkIOT@1;gJGMYZZ4gwF;LPz3o^4sd6Zb@a*q zWGwDFO*q7`){CsEwcu)uz$X(Fj#c-(Jr4Y_zfN%VtWEs;mTy@;!=#@_!O^Pc3T536 zUgp=S*A39QM(~EE{d5gW-(iAW#R8tDVxjv&1zz(p?I)~vaMgXC#^zjGq>^05Bbm^ucsTf+S4o8390D=)TGS0tuIJ)U8nI$KYK zHBU;*pTnevth-TakNkCQmDS_Oq6sZ!v?3x4yF@Fij7WInD)bL$vs5s+7`f;ogKsTt)`ocR+U z^{md3+SLd;n^C>vYB8N1tWNk(RV!r-8Dkoup!@3gR-Rh-mmKj!(xP@oOVE{mGM^$z zMd@{gg)vElH;+Nyh3l)3Rq#nV8Ms^FHjd1LRVs?bZ*{%6ow&bW1%5DS>+*-Sy}G?K zXU8e)k5IttoQ5%bvs=2^|27W1p^K5ep$0$NmaRAubteQpR%^7X`BY`P;{|uGvhm z=iKCd5WrBXCSJqs!~x)s-~E=YTgbFt#_7&H(Ox8ipPL9zP{6J5nha@ktb<(`^FpS!YaR`0auzXlo9|EX%(x?zT`MAokxhMlt1LX=3CX*`|>Nc z-C=viXSdy8?`luqe3P1T)UjQLxEU8n<22$CMXWg}(}&%}Ln1DI!us&CkUe7K6UE-` z8(Ha>!hM%x;E+b)auwoqB9wr*&ScQtneK)&6yh45Njl654yhTU`x;sw5Fud3VYfZ? zv>cLFqnK-HZnaYjfqOZ3EH+MR<5uzr`os$8j!d;KNV`%V&vLR=&KMzJb}%23ET5a@ zWphPT3hqo)b6ixfKz*M-@Yd5Q)A#Pnt&eP6G?fP6vtfdbC!yA?x2Uo=&4D(R{>5h{ zUX04S-J=;754hXG)7m17^MmoSdsFE3THZ13)*`!wP5I1N{V8gFwsG&~Od-#@E4h9h z`tc`%#oNjv%kx3yIqRjKc`jErw`&I=wuq|)bAXdnt@S9N9Se}FZzf~gt z%HKFMlKJcpAJ?Y`N9|)(%yY5ccutQka~b+Ndix>;JHxv9!Sn zS}icYn)jEhls)oBP^*VTZp~xu@m(CT{lInEOXO4HJ*(J#nXmsK z?2K;yaomB)h}%~64z_!6r}xG3snePNxhi^K;AO--mpZm}~TqF0vcnO7DK>GZ6Vvp_!Qsalk z{oz;1wkyJbHK2?VvH@yA?}kz&DPIhYyF5F{{LA5NsZ^`Sjm3mFq0|5yr|rt}7vq1|5VEBVYC>Y^!V#=G%jzzhzQJd!;%*ciaoe@*=m1JAR^8Xb!;_6ds{T$%)}CMay;y=v z@A8u~Tz^h?qnQ8O5xHZpf21X8ZwdGY|3Tfkg#+6m%uwR&+3hK0!s?LSTJ7;-wt@S; z=u!*ZCB6IVK~kjsO)s4*nm+q&AcJSPXl-{Y;b$;dy~<=vO!$O2us3wGW9^G#3-p)f zB-#i>rbfc^!-2_2k9rb`%D0gY$(yZtdG95;CDE1I2ptD}gIj9btdZj2&MB~9eQ2d` zRF@&*&dy@#J@67n_{9g6ajiJPnt5rFrx;7fjI@8wfa$93RC@DX`Pa%~&yXB$R>}7; z*+Cv_dhuo!t^p?>QnKr;jx8CznUf`cO*YJ`v%UU<^aewd!nx3(=ko*ek<2ID%~QDK zd0F$=$gIskYsg~*oP0f{xKfls8*8}(J4Et!y#D+d>LEjb&t=jk0+$>ujw*qLsFJs7h zy-+_!5lA2D&{Wty2cO*)IJ}OWvm;M>(oWk<2ori;vXfw`q@hJI>vnVwy>0$%YCLB% z|7F)N>V&A%{d`l;VRu>|)9$R#k3ASpt%5L`#WIHa26t^k99h&G!7+M>;dGCVCQ_Aa zidldD>c!E30lPY0{SY#U;#2YBKu6c6>Dc z0y*30x$Qf^z1Y!#G(ujY+Gz|}@~1d`hMO;w&$(JT$JCW@_Yai3Jo95zx#`p8Ehp@N zwM%!qw1{4XPiXdh#@t+> za`fd<(b@T|znCiOo%1Tlbtx!Lk+-)C8mPPA6IW;@20Q5M1kor8JBlr5!FJK575mARRC?e|j4)R|)3 zI9J?H@TJ&ei@P|Tes3i^f!20Fw7^h)D(=5Nn9 zCRT!(HNcHf{^17zfIx#Xg933mqBY2~T6@JwY)-WX>y~nzZ3D!sC4$#AbSF%eyQDbO zPg@aLdZg){|1mQ@nTV3}m&D~(T{9cSA_pNVD5g}IlfmQI@Ftj2XYGk-nbP=o^3$td zELizDtp=CsldxX`=O-A}>7;wEL@y950^`w7#Pi!)!(9~nYJ2<`kKc@^A46OuKVU!` z(By2RMiRH(Ysh|ZO`SGB{p@y&;!{X9c4f|Y#>Uo|oa6Ovyk}i|wTw#lCvk?512L26 zC-1uI(p>G9eVbAZGVL(e64Pe$VKb=g1L^o!z`da^Op=c7{^K8X__lAayGj`m4nG!? zV?NC5q&Ng&#*OyO0hGig3vj2{zxrshJ$%|td=AKPSeSFSTEPS~7*KbdwK zM|Qp7b;Y4Y8ynmIdO{5~(MD~&yc9KBjmwT1&F-JiIz8gJ znvxswpygU$6=y`C=YB$XM5w-grbtk-ZRypL>+BfAi*1y6U@naKzdF-scQjaKA!WjxwceQC-4uXM>Mp>_GX> zQU&OzKUPC(a>-eZ>P{;Qu~8J#!d)0tAX?j7TyxhDEMR_EfdFGRCzXRIPMEMORzs(R zEn&TwOonvh{f(ED>POjjxn7cz+Fln}vM4yvzHx#(7LpJ48Gw^qyUqp(9>uiNL3ZTGFKHp zFSuSZcCVP*An&zg@uRLXS~mh)Xey*69T@Giwa>5aI!E|e#Iq=)j5Ln-_&hsB8A4)Z zJOD$@yrOTn&PMcKBa(zw32TDP3w?jo^Jy|nT6d2xlV4h6%U>G7MV6X}wt&CTlW`h+ z%u#aeT1y{}qx3)4O3gI)p$o!cdxl0tupSIVHFh5YL!Me( z8pFwY1e*p7Z6K~JHH5eBWEDE>qF6J^sY?sSTr?p!)?F5xoL=q061Rw>u<*C9A$!G1 zy*>U3wx|4h6*^l3lco5HFYIF^y9092Bd^;?Y{pICsC2|gqIsPweD8!WMe#u!vfL#t z?AbyuEcVA66lhFj}~M6NoYz%u@*X z%uZ-iZ?c7%m^s3Cyk$01x1!Cwo?9D9F$Qg*9a13r`Q)=f8++N%fV92W_GIurKduB$ zzUWR%psJPF*ItH(GmVj9MiQM?FB0>bH20Wu)^Pc0O0Ow9W{W$l000umOD)_goE`wt<;MR^jur)7if2x66h|n~_$2@LfgoUNVhWNqc8co9*hACo)B* zu(4Xv49^Xohm7U`v1)`UnbXEriffAJTE{Wj*Uz5;!pkiIBm!GxzQo%T$9sdO+~Ds8 z=<#^gyXO}OZ6&V3?A{_~_0!1^A_`q_Os1Y)0GDI4w@sVKvO`>7tfx*MQ!+VXZ4rxa zFCK_C5b112jucD6-w|2CghYkDV_TyFi?7SlK53UMm0nF?e|MUd7lZ-B;0A;?uM_7r zFHgedvqE8g2|dCu>otpP6}BdB0UWAUGe34wvvO50O0HA9Gn~>RG$W=?gNg?(mBE__xMKD8tl))Z)+bw+Y3@F|-{%AH%`v-+lp>>zptx1v~T+O0;&vV+>+_A#k z?N_yk*^{U+aNTdrTYpDnoGX9woO!T>C+)mkAY7B|Q`h@}Si;9EiS$o-oo(4_fIK?Q zN?gcdJx#&i6K?{zEE+wL$ujF?Y1O!Sa(m$>U^KwGRUgRPW4i9)_v`5N%X;K)j&jp4dGEzp9&it-vt_T83dD|&i`TUNtyn>_s~k2spf zAy6$p6enZ8(qUCO<(!R(MvzXW8U^TD;lMoCf%!o)Xafb#X2@PhRrsy70B$oN{Ywoq;gtQ%F2Va{6t?+PK)O*|@R?n0HOrE+rk!u1{y@KFQQt z*!zucYMmBN30ZjSNCdd~N8jKjP+^gHDp2x)*xBfH8(}-Q$ZQrr%A9mXT=zPL&Uw@w_JwnIT<2W-ud~6-IHR>`KuuA~Sz^@0P zkhO-#yJp}=3Ftgu;U!6l8@4y5n?|_W-PVzG3laIWE!y#Dvl-@z?!ghK3Z@)1vtR*u z!&>drPGo#G?aKT`U0PZz?6ytO zrT-W)kATOSG@W&)&~W;)qJ*i~zH&q+AWdaNASpnmZS#sX*@2D!raGlY&E&jG%}XeU zD=~ms{B)(Kj*_QJZU1w0A1ud2#gv#oULpHgH*kh!W4mK~{o};F(hggCA zx;fecV|!zQXLbMnbq-!NK{{kGd$&~^OUUtK1W?^z;*Tr+pGS$V9|82M?ihUVa(kJF z6%LwNYWg_}8(vx=aPjTWrfEyB2@I%4#|I4g$CrQRyVUeaJu(0rs%Wf;oa+xP*r8jvFY`zzI~NHq)+^t7m3R&NOvYW3in@4|FF82gU5vxLm7`ur|^dt}dXytgY8DzlKy z@iV?AOC|W^);p!ukPD!ITd0>Qh%T#?-h!-BD`_gGtow{Brk6IBp_KXi*f&;xcf@r1 zMo0DCk(5v0i7J|4M3jU;xQzan-uzc{C`xsgXBBoMb$0U1qO@?d(GT2`(G z176yvy-&3mu&$dC1SE}5?%G4!!(U!8x%N3;zmFBnrE{%%Z%L+dbMdkNh6_Sg&$&x- zhP9WKTL}s@!4Hu>+d-}>9BRwv4 zIhSN>Nl>4JXxrA$(@wnA6bsufw)w~1Q80jk)MVt!_VOeue#NP2Q>}`-wcqP&b~qm! zLH#|r+0`Ae1@-Y`-o-#x$QG9;+hZO}f}Nv-#~Py(VT)g0{p#;e$KQRtDClO{f)=gK z9xiug%C+z8M-oGykr!Rjiu#E3WVLURD16HWPP^Oh%87c+E~UQQUj8=!f~l68l-vfSUK5%vEeH^$PA zy<-F6Pzm!fTs&)1N6pmBG=9BxHc(W1p9BbW9_uKb+egLo(j*3b zyons!bw{fgbe!&8gvfX<f9kKL)%KNs~T=XB&|8ETM!@9FR&E}@| z4`II7axiXeKP_O<<@#A_Z86ZiO?kVWE8vWlbr)@MK&^$o^42?j{;lW-5CRw|e1-Ju z?V9cXR382X$n{P83way;ZO$qnrQLEuL Date: Tue, 14 Apr 2026 15:24:32 -0400 Subject: [PATCH 20/24] Add simple logic to ensure drone must be airborne before other tasks --- .../rviz/3d_waypoint_rviz2_plugin/README.md | 3 +- .../gui/rviz/rviz_tasks_panel/CMakeLists.txt | 2 + .../gui/rviz/rviz_tasks_panel/README.md | 35 ++-- .../include/rviz_tasks_panel/tasks_panel.hpp | 9 + .../gui/rviz/rviz_tasks_panel/package.xml | 1 + .../rviz/rviz_tasks_panel/src/tasks_panel.cpp | 55 ++++-- .../takeoff_landing_planner/README.md | 163 +++++++++--------- .../takeoff_landing_task.hpp | 1 + .../src/takeoff_landing_task.cpp | 5 + 9 files changed, 170 insertions(+), 104 deletions(-) diff --git a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md index 1af109794..57ecd587b 100644 --- a/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md +++ b/common/ros_packages/gui/rviz/3d_waypoint_rviz2_plugin/README.md @@ -133,7 +133,8 @@ Apache 2.0 ## Credits Original ROS 1 version by KoKoLates (the21515@gmail.com). -ROS 2 port and WaypointManager refactor for AirStack. + +ROS 2 port and WaypointManager refactor for AirStack (Andrew Jong ajong@andrew.cmu.edu). ## References diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt index 8de5d6393..e6f81b9cc 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/CMakeLists.txt @@ -22,6 +22,7 @@ find_package(nav_msgs REQUIRED) find_package(diagnostic_msgs REQUIRED) find_package(action_msgs REQUIRED) find_package(rviz_polygon_selection_tool REQUIRED) +find_package(std_msgs REQUIRED) find_package(waypoint_rviz2_plugin REQUIRED) qt5_wrap_cpp(MOC_FILES @@ -47,6 +48,7 @@ ament_target_dependencies(tasks_panel airstack_msgs geometry_msgs nav_msgs + std_msgs diagnostic_msgs action_msgs rviz_polygon_selection_tool diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md index 9ce5dd2df..0b02d82b9 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md @@ -59,20 +59,27 @@ separate waypoint panel needed. saved/restored with the RViz config - **Single-task lock** -- only one action may execute at a time to prevent conflicts +- **Airborne-only tasks** -- Land, Navigate, and all mission + tasks are disabled until the drone is airborne (subscribes to + `is_airborne` from `takeoff_landing_planner`); Takeoff is + always available while idle ## Supported Task Types -| Tab | Action Type | Key Parameters | -|-----|-------------|----------------| -| Takeoff | `TakeoffTask` | `target_altitude_m`, `velocity_m_s` | -| Land | `LandTask` | `velocity_m_s` | -| Navigate | `NavigateTask` | `global_plan` (Path), `goal_tolerance_m` | -| Exploration | `ExplorationTask` | `search_bounds` (Polygon), altitude/speed, `time_limit_sec` | -| Coverage | `CoverageTask` | `coverage_area` (Polygon), `line_spacing_m`, `heading_deg` | -| Object Search | `ObjectSearchTask` | `object_class`, `search_area`, `target_count` | -| Object Counting | `ObjectCountingTask` | `object_class`, `count_area` | -| Semantic Search | `SemanticSearchTask` | `query`, `search_area`, `confidence_threshold` | -| Fixed Trajectory | `FixedTrajectoryTask` | `trajectory_spec`, `loop` | +Tasks marked **airborne-only** are disabled until the drone is +in the air. + +| Tab | Action Type | Key Parameters | Airborne-only | +|-----|-------------|----------------|---------------| +| Takeoff | `TakeoffTask` | `target_altitude_m`, `velocity_m_s` | | +| Land | `LandTask` | `velocity_m_s` | ✓ | +| Navigate | `NavigateTask` | `global_plan` (Path), `goal_tolerance_m` | ✓ | +| Exploration | `ExplorationTask` | `search_bounds` (Polygon), altitude/speed, `time_limit_sec` | ✓ | +| Coverage | `CoverageTask` | `coverage_area` (Polygon), `line_spacing_m`, `heading_deg` | ✓ | +| Object Search | `ObjectSearchTask` | `object_class`, `search_area`, `target_count` | ✓ | +| Object Counting | `ObjectCountingTask` | `object_class`, `count_area` | ✓ | +| Semantic Search | `SemanticSearchTask` | `query`, `search_area`, `confidence_threshold` | ✓ | +| Fixed Trajectory | `FixedTrajectoryTask` | `trajectory_spec`, `loop` | ✓ | ## Widget Type Mapping @@ -93,7 +100,7 @@ separate waypoint panel needed. - `rclcpp` / `rclcpp_action` -- ROS 2 node and action client - `task_msgs` -- action definitions for all 9 task types - `airstack_msgs` -- `FixedTrajectory` message -- `geometry_msgs` / `nav_msgs` -- standard message types +- `geometry_msgs` / `nav_msgs` / `std_msgs` -- standard message types - `diagnostic_msgs` / `action_msgs` -- status introspection - `rviz_polygon_selection_tool` -- polygon selection service - `waypoint_rviz2_plugin` -- shared `WaypointManager` singleton @@ -164,6 +171,10 @@ the **Refresh** button. - **Thread safety**: ROS 2 callbacks use `QMetaObject::invokeMethod` with `Qt::QueuedConnection` to marshal UI updates to the Qt main thread +- **Airborne gate**: subscribes to `{robot}/is_airborne` + (std_msgs/Bool from `takeoff_landing_planner`); per-tab Execute + buttons are enabled only when `task_idle && airborne_ok`, where + `airborne_ok = !requires_airborne || is_airborne_` ## License diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp index a0f914f5f..0c4f93809 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/include/rviz_tasks_panel/tasks_panel.hpp @@ -32,6 +32,7 @@ #include #include #include +#include #include @@ -68,6 +69,7 @@ struct TaskTypeDef std::string display_name; std::string action_topic_suffix; // e.g. "tasks/takeoff" std::vector goal_fields; + bool requires_airborne{false}; // if true, Execute is disabled while drone is on the ground }; // Per-tab runtime state @@ -143,6 +145,11 @@ private Q_SLOTS: // Global task lock: only one task may run at a time int active_task_tab_{-1}; // -1 = no task running, else = tab index of active task + // Airborne state (fed by is_airborne topic from takeoff_landing_planner) + bool is_airborne_{false}; + QString is_airborne_robot_; // robot namespace currently subscribed to + rclcpp::Subscription::SharedPtr is_airborne_sub_; + // Discovery timer QTimer * refresh_timer_{nullptr}; @@ -172,6 +179,8 @@ private Q_SLOTS: void doCancelGoal(int tab_index); void setGoalActive(int tab_index, bool active); + void updateExecuteButtons(); + void renewAirborneSubscription(); void setTabStatus(int tab_index, const QString & icon, const QColor & text_color); void clearTabStatus(int tab_index); QString currentRobot() const; diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml index 76406b6b6..8c0c91c21 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/package.xml @@ -17,6 +17,7 @@ airstack_msgs geometry_msgs nav_msgs + std_msgs diagnostic_msgs action_msgs rviz_polygon_selection_tool diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp index 66fdd8aa5..aed06bc47 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/src/tasks_panel.cpp @@ -27,11 +27,11 @@ std::vector TasksPanel::getTaskDefs() }}, {"Land", "tasks/land", { {"velocity_m_s", "float32", 0.3, 0.0, 10.0}, - }}, + }, true}, {"Navigate", "tasks/navigate", { {"global_plan", "nav_msgs/Path", 0, 0, 0}, {"goal_tolerance_m", "float32", 1.0, 0.0, 100.0}, - }}, + }, true}, {"Exploration", "tasks/exploration", { {"search_bounds", "geometry_msgs/Polygon", 0, 0, 0}, {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, @@ -39,7 +39,7 @@ std::vector TasksPanel::getTaskDefs() {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, - }}, + }, true}, {"Coverage", "tasks/coverage", { {"coverage_area", "geometry_msgs/Polygon", 0, 0, 0}, {"min_altitude_agl", "float32", 3.0, 0.0, 500.0}, @@ -48,7 +48,7 @@ std::vector TasksPanel::getTaskDefs() {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, {"line_spacing_m", "float32", 5.0, 0.1, 1000.0}, {"heading_deg", "float32", 0.0, 0.0, 360.0}, - }}, + }, true}, {"Object Search", "tasks/object_search", { {"object_class", "string", 0, 0, 0}, {"search_area", "geometry_msgs/Polygon", 0, 0, 0}, @@ -58,7 +58,7 @@ std::vector TasksPanel::getTaskDefs() {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, {"target_count", "int32", 1, 0, 10000}, - }}, + }, true}, {"Object Counting", "tasks/object_counting", { {"object_class", "string", 0, 0, 0}, {"count_area", "geometry_msgs/Polygon", 0, 0, 0}, @@ -66,7 +66,7 @@ std::vector TasksPanel::getTaskDefs() {"max_altitude_agl", "float32", 10.0, 0.0, 500.0}, {"min_flight_speed", "float32", 1.0, 0.0, 50.0}, {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, - }}, + }, true}, {"Semantic Search", "tasks/semantic_search", { {"query", "string", 0, 0, 0}, {"search_area", "geometry_msgs/Polygon", 0, 0, 0}, @@ -76,11 +76,11 @@ std::vector TasksPanel::getTaskDefs() {"max_flight_speed", "float32", 3.0, 0.0, 50.0}, {"time_limit_sec", "float32", 120.0, 0.0, 86400.0}, {"confidence_threshold", "float32", 0.5, 0.0, 1.0}, - }}, + }, true}, {"Fixed Trajectory", "tasks/fixed_trajectory", { {"trajectory_spec", "airstack_msgs/FixedTrajectory", 0, 0, 0}, {"loop", "bool", 0, 0, 0}, - }}, + }, true}, }; } @@ -479,6 +479,8 @@ void TasksPanel::onRefreshExecutors() robot_combo_->setCurrentText(current_robot); } } + + renewAirborneSubscription(); } // ─────────────────────────── special widgets ────────────────────────────────── @@ -650,17 +652,47 @@ void TasksPanel::setGoalActive(int tab_index, bool active) state.result_display->clear(); state.status_label->setText("Running..."); state.status_label->setStyleSheet("color: blue;"); - setTabStatus(tab_index, QString::fromUtf8(u8"⏳"), Qt::blue); + setTabStatus(tab_index, QString::fromUtf8(u8"⏳"), Qt::blue); } else { active_task_tab_ = -1; } - // Disable all Execute buttons while any task is running + updateExecuteButtons(); +} + +void TasksPanel::updateExecuteButtons() +{ for (size_t i = 0; i < tab_states_.size(); ++i) { - tab_states_[i].execute_btn->setEnabled(active_task_tab_ == -1); + bool task_idle = (active_task_tab_ == -1); + bool airborne_ok = !task_defs_[i].requires_airborne || is_airborne_; + tab_states_[i].execute_btn->setEnabled(task_idle && airborne_ok); } } +void TasksPanel::renewAirborneSubscription() +{ + QString robot = robot_combo_->currentText(); + if (robot == is_airborne_robot_) {return;} + is_airborne_robot_ = robot; + + is_airborne_sub_.reset(); + is_airborne_ = false; + updateExecuteButtons(); + + if (robot.isEmpty() || !raw_node_) {return;} + + std::string topic = robot.toStdString() + "/takeoff_landing_planner/is_airborne"; + is_airborne_sub_ = raw_node_->create_subscription( + topic, 1, + [this](std_msgs::msg::Bool::SharedPtr msg) { + bool airborne = msg->data; + QMetaObject::invokeMethod(this, [this, airborne]() { + is_airborne_ = airborne; + updateExecuteButtons(); + }, Qt::QueuedConnection); + }); +} + void TasksPanel::setTabStatus(int tab_index, const QString & icon, const QColor & text_color) { tab_widget_->tabBar()->setTabTextColor(tab_index, text_color); @@ -810,6 +842,7 @@ void TasksPanel::onExecuteClicked() int idx = tab_widget_->currentIndex(); if (idx < 0 || idx >= static_cast(tab_states_.size())) {return;} if (active_task_tab_ >= 0) {return;} // only one task at a time + if (task_defs_[idx].requires_airborne && !is_airborne_) {return;} // airborne required switch (idx) { case 0: { // Takeoff diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md b/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md index 3cb5ca33e..5afeb4522 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md @@ -2,116 +2,119 @@ ## Overview -The TakeoffLandingPlanner provides a rich interface for handling takeoff/landing commands, with support for both trajectory-based and ArduPilot command-based modes. It monitors the robot's position, generates appropriate trajectories, and tracks the completion status of takeoff and landing maneuvers. +The TakeoffLandingPlanner provides ROS 2 action servers for takeoff and landing maneuvers. It monitors the robot's state, generates trajectory overrides to reach the target altitude (takeoff) or ground (landing), and tracks completion via position and time thresholds. -## Highlights +## Features -- Two takeoff modes: standard and high altitude -- Configurable takeoff and landing velocities -- Configurable takeoff trajectory direction -- Trajectory-based takeoff and landing with position tracking -- Direct ArduPilot takeoff command support -- Completion monitoring with distance and time thresholds -- State publishing for integration with higher-level systems +- Trajectory-based takeoff to a configurable target altitude and velocity +- Trajectory-based landing with stationary-detection completion +- Configurable takeoff trajectory direction (roll/pitch, absolute or body-relative) +- Precondition checking: rejects goals when state estimate is timed out or a task is already running +- Publishes `is_airborne` for downstream consumers (e.g. the RViz Tasks Panel) ## Topics ### Subscriptions -| Topic | Type | Description | -| ---------------------------------- | ------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------ | -| `trajectory_completion_percentage` | `std_msgs/Float32` | Current completion percentage of trajectory (from [trajectory_controller](../../c_controls/trajectory_controller/src/trajectory_controller.cpp)) | -| `tracking_point` | `airstack_msgs/Odometry` | Current tracking point for trajectory (from [trajectory_controller](../../c_controls/trajectory_controller/src/trajectory_controller.cpp)) | -| `odometry` | `nav_msgs/Odometry` | Robot odometry data | -| `ekf_active` | `std_msgs/Bool` | EKF status flag | -| `high_takeoff` | `std_msgs/Bool` | Flag to trigger high altitude takeoff | +| Topic | Type | Description | +|------------------------------------|-----------------------------------|------------------------------------------------------| +| `odometry` | `nav_msgs/Odometry` | Robot pose and velocity | +| `tracking_point` | `airstack_msgs/Odometry` | Current trajectory tracking point | +| `trajectory_completion_percentage` | `std_msgs/Float32` | Trajectory completion (0–100) from trajectory_controller | +| `is_armed` | `std_msgs/Bool` | Vehicle arm status | +| `has_control` | `std_msgs/Bool` | Offboard control acquired | +| `state_estimate_timed_out` | `std_msgs/Bool` | Whether the state estimate has timed out | +| `extended_state` | `mavros_msgs/ExtendedState` | MAVROS landed state (used to publish `is_airborne`) | ### Publications -| Topic | Type | Description | -| --------------------- | --------------------------------- | -------------------------------------------------------- | -| `trajectory_override` | `airstack_msgs/TrajectoryXYZVYaw` | Generated takeoff/landing trajectory | -| `takeoff_state` | `std_msgs/String` | Current takeoff state ("NONE", "TAKING_OFF", "COMPLETE") | -| `landing_state` | `std_msgs/String` | Current landing state ("NONE", "LANDING", "COMPLETE") | +| Topic | Type | Description | +|---------------------|-----------------------------------|---------------------------------------------------------| +| `trajectory_override` | `airstack_msgs/TrajectoryXYZVYaw` | Takeoff/landing trajectory sent to trajectory_controller | +| `is_airborne` | `std_msgs/Bool` | True when `landed_state == LANDED_STATE_IN_AIR` | -## Services +## Service Clients -| Service | Type | Description | -| ----------------------------- | ------------------------------------- | ----------------------------------------- | -| `set_takeoff_landing_command` | `airstack_msgs/TakeoffLandingCommand` | Sets command mode (NONE, TAKEOFF, LAND) | -| `ardupilot_takeoff` | `std_srvs/Trigger` | Triggers direct ArduPilot takeoff command | +| Service | Type | Description | +|-----------------------|-----------------------------------|----------------------------------------| +| `set_trajectory_mode` | `airstack_msgs/TrajectoryMode` | Switch trajectory controller mode | +| `robot_command` | `airstack_msgs/RobotCommand` | Arm, request offboard control, disarm | -## Parameters +## Action Servers -| Parameter | Type | Default | Description | -| -------------------------------------- | ----- | ------- | ------------------------------------------------------- | -| `takeoff_height` | float | 0.5 | Standard takeoff height in meters | -| `high_takeoff_height` | float | 1.2 | High altitude takeoff height in meters | -| `takeoff_velocity` | float | 0.3 | Velocity during takeoff in m/s | -| `landing_velocity` | float | 0.3 | Velocity during landing in m/s | -| `takeoff_acceptance_distance` | float | 0.1 | Maximum distance to consider takeoff complete in meters | -| `takeoff_acceptance_time` | float | 2.0 | Required time at acceptance distance in seconds | -| `landing_stationary_distance` | float | 0.02 | Maximum movement distance to consider landed in meters | -| `landing_acceptance_time` | float | 5.0 | Required time at stationary distance in seconds | -| `landing_tracking_point_ahead_time` | float | 5.0 | How far ahead the tracking point should be | -| `takeoff_path_roll` | float | 0.0 | Roll angle for takeoff path in degrees | -| `takeoff_path_pitch` | float | 0.0 | Pitch angle for takeoff path in degrees | -| `takeoff_path_relative_to_orientation` | bool | false | Whether to use robot's current orientation for takeoff | +| Action | Type | Description | +|-----------------|---------------------------|------------------------------| +| `~/takeoff_task` | `task_msgs/TakeoffTask` | Execute a takeoff maneuver | +| `~/land_task` | `task_msgs/LandTask` | Execute a landing maneuver | -## Usage +### TakeoffTask -### Basic Usage +**Goal** -To launch the TakeoffLandingPlanner node: +| Field | Type | Description | +|---------------------|---------|--------------------------------| +| `target_altitude_m` | float32 | Target altitude in meters | +| `velocity_m_s` | float32 | Ascent velocity in m/s | -```bash -ros2 run takeoff_landing_planner takeoff_landing_planner -``` +**Feedback** -### Initiating Takeoff +| Field | Type | Description | +|----------------------|---------|--------------------------------| +| `status` | string | Human-readable status message | +| `current_altitude_m` | float32 | Current altitude in meters | +| `target_altitude_m` | float32 | Target altitude in meters | -To command a takeoff: +**Result** -```bash -ros2 service call /set_takeoff_landing_command airstack_msgs/srv/TakeoffLandingCommand "{command: 1}" -``` +| Field | Type | Description | +|-----------|---------|--------------------------| +| `success` | bool | Whether takeoff succeeded | +| `message` | string | Outcome description | -### Initiating Landing +### LandTask -To command a landing: +**Goal** -```bash -ros2 service call /set_takeoff_landing_command airstack_msgs/srv/TakeoffLandingCommand "{command: 2}" -``` +| Field | Type | Description | +|----------------|---------|--------------------------| +| `velocity_m_s` | float32 | Descent velocity in m/s | -### ArduPilot Takeoff +**Feedback** -To use direct ArduPilot takeoff commands: +| Field | Type | Description | +|----------------------|---------|-------------------------------| +| `status` | string | Human-readable status message | +| `current_altitude_m` | float32 | Current altitude in meters | -```bash -ros2 service call /ardupilot_takeoff std_srvs/srv/Trigger "{}" -``` +**Result** -## State Monitoring +| Field | Type | Description | +|-----------|--------|---------------------------| +| `success` | bool | Whether landing succeeded | +| `message` | string | Outcome description | -The node publishes the current state of takeoff and landing operations through the `takeoff_state` and `landing_state` topics. Monitor these topics to track the progress and completion of operations: +## Parameters -```bash -ros2 topic echo /takeoff_state -ros2 topic echo /landing_state -``` +| Parameter | Type | Default | Description | +|----------------------------------------|-------|---------|---------------------------------------------------------------| +| `takeoff_velocity` | float | 1.0 | Default ascent velocity in m/s | +| `landing_velocity` | float | 0.3 | Default descent velocity in m/s | +| `takeoff_acceptance_distance` | float | 0.3 | Distance threshold to consider target altitude reached (m) | +| `takeoff_acceptance_time` | float | 1.0 | Time that must be spent within acceptance distance (s) | +| `landing_stationary_distance` | float | 0.02 | Max movement to consider the drone stationary on landing (m) | +| `landing_acceptance_time` | float | 5.0 | Time the drone must remain stationary to confirm landing (s) | +| `landing_tracking_point_ahead_time` | float | 5.0 | Lookahead time for the landing tracking point | +| `takeoff_path_roll` | float | 0.0 | Roll offset for the takeoff trajectory (degrees) | +| `takeoff_path_pitch` | float | 0.0 | Pitch offset for the takeoff trajectory (degrees) | +| `takeoff_path_relative_to_orientation` | bool | false | Apply roll/pitch relative to the robot's current orientation | ## Dependencies -- airstack_msgs -- nav_msgs -- mavros_msgs -- std_msgs -- std_srvs -- tf2_ros - -## Notes - -- The node uses TF2 to track relative positions between the robot and tracking points -- Landing completion detection relies on both position stability and tracking point metrics -- The default landing target is hardcoded (-10000.0) and should be parameterized in future versions +- `rclcpp` / `rclcpp_action` +- `airstack_msgs` +- `airstack_common` +- `nav_msgs` +- `mavros_msgs` +- `std_msgs` +- `task_msgs` +- `trajectory_library` diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp index 36e282dba..086465228 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -99,6 +99,7 @@ class TakeoffLandingTaskNode : public rclcpp::Node // publishers rclcpp::Publisher::SharedPtr traj_override_pub_; + rclcpp::Publisher::SharedPtr is_airborne_pub_; // service clients rclcpp::Client::SharedPtr traj_mode_client_; diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp index 7de50ace8..675d2b796 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -74,11 +74,16 @@ TakeoffLandingTaskNode::TakeoffLandingTaskNode() "extended_state", 1, [this](mavros_msgs::msg::ExtendedState::SharedPtr msg) { landed_state_ = msg->landed_state; + std_msgs::msg::Bool airborne_msg; + airborne_msg.data = + (msg->landed_state == mavros_msgs::msg::ExtendedState::LANDED_STATE_IN_AIR); + is_airborne_pub_->publish(airborne_msg); }); // publishers traj_override_pub_ = this->create_publisher("trajectory_override", 1); + is_airborne_pub_ = this->create_publisher("is_airborne", 1); // service clients traj_mode_client_ = From aa0404379c4e1e438aabf2800c495e82d88af14b Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Tue, 14 Apr 2026 15:36:51 -0400 Subject: [PATCH 21/24] Fix disarm on land and set is_airborne false --- .../takeoff_landing_planner/README.md | 2 +- .../takeoff_landing_task.hpp | 5 ++++ .../src/takeoff_landing_task.cpp | 25 ++++++++++++++++--- 3 files changed, 27 insertions(+), 5 deletions(-) diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md b/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md index 5afeb4522..d1505bfe2 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/README.md @@ -7,7 +7,7 @@ The TakeoffLandingPlanner provides ROS 2 action servers for takeoff and landing ## Features - Trajectory-based takeoff to a configurable target altitude and velocity -- Trajectory-based landing with stationary-detection completion +- Trajectory-based landing with on-ground detection, followed by automatic disarm - Configurable takeoff trajectory direction (roll/pitch, absolute or body-relative) - Precondition checking: rejects goals when state estimate is timed out or a task is already running - Publishes `is_airborne` for downstream consumers (e.g. the RViz Tasks Panel) diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp index 086465228..7873484ce 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/include/takeoff_landing_planner/takeoff_landing_task.hpp @@ -88,6 +88,11 @@ class TakeoffLandingTaskNode : public rclcpp::Node std::atomic task_active_{false}; std::atomic cancel_requested_{false}; + // set by land_execute on success; cleared by takeoff_execute on start. + // prevents extended_state callback from re-publishing is_airborne=true + // after MAVROS transiently reverts to IN_AIR post-landing. + std::atomic landed_{false}; + // subscribers rclcpp::Subscription::SharedPtr robot_odom_sub_; rclcpp::Subscription::SharedPtr tracking_point_sub_; diff --git a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp index 675d2b796..3e736d05a 100644 --- a/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp +++ b/robot/ros_ws/src/local/planners/takeoff_landing_planner/src/takeoff_landing_task.cpp @@ -74,10 +74,20 @@ TakeoffLandingTaskNode::TakeoffLandingTaskNode() "extended_state", 1, [this](mavros_msgs::msg::ExtendedState::SharedPtr msg) { landed_state_ = msg->landed_state; - std_msgs::msg::Bool airborne_msg; - airborne_msg.data = - (msg->landed_state == mavros_msgs::msg::ExtendedState::LANDED_STATE_IN_AIR); - is_airborne_pub_->publish(airborne_msg); + bool in_air = (msg->landed_state == mavros_msgs::msg::ExtendedState::LANDED_STATE_IN_AIR); + if (!in_air) { + // Definitive non-airborne state from MAVROS — always publish false. + std_msgs::msg::Bool airborne_msg; + airborne_msg.data = false; + is_airborne_pub_->publish(airborne_msg); + } else if (!landed_) { + // IN_AIR and no confirmed landing — publish true. + std_msgs::msg::Bool airborne_msg; + airborne_msg.data = true; + is_airborne_pub_->publish(airborne_msg); + } + // If landed_ is set and MAVROS reports IN_AIR, publish nothing: + // land_execute already published false; MAVROS is transiently wrong. }); // publishers @@ -209,6 +219,8 @@ void TakeoffLandingTaskNode::takeoff_execute(std::shared_ptr auto feedback = std::make_shared(); feedback->target_altitude_m = target_altitude; + landed_ = false; // clear latch — a new takeoff is starting + // wait for odometry rclcpp::Rate wait_rate(10); int wait_count = 0; @@ -461,6 +473,11 @@ void TakeoffLandingTaskNode::land_execute(std::shared_ptr goal_h RCLCPP_INFO(this->get_logger(), "LandTask: landed (mavros landed_state = ON_GROUND) at %.2fm", current_z); set_trajectory_mode(airstack_msgs::srv::TrajectoryMode::Request::ROBOT_POSE); + send_robot_command(airstack_msgs::srv::RobotCommand::Request::DISARM); + landed_ = true; + std_msgs::msg::Bool airborne_msg; + airborne_msg.data = false; + is_airborne_pub_->publish(airborne_msg); result->success = true; result->message = "landing complete"; goal_handle->succeed(result); From 2c878f0413167c5e85e13d215dfc6ca7a9386dbd Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Tue, 14 Apr 2026 15:55:07 -0400 Subject: [PATCH 22/24] Bump version to 0.18.0-alpha.4 --- .env | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.env b/.env index 63a62094c..23c886d92 100644 --- a/.env +++ b/.env @@ -11,7 +11,7 @@ PROJECT_NAME="airstack" # If you've run ./airstack.sh setup, then this will auto-generate from the git commit hash every time a change is made # to a Dockerfile or docker-compose.yaml file. Otherwise this can also be set explicitly to make a release version. -VERSION="0.18.0-alpha.3" +VERSION="0.18.0-alpha.4" # Choose "dev" or "prebuilt". "dev" is for mounted code that must be built live. "prebuilt" is for built ros_ws baked into the image DOCKER_IMAGE_BUILD_MODE="dev" # Where to push and pull images from. Can replace with your docker hub username if using docker hub. From 854423f436933b05f7ea6982b4013bc69aee89b9 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Tue, 14 Apr 2026 16:11:57 -0400 Subject: [PATCH 23/24] Remove rqt --- .../desktop_bringup/launch/gcs.launch.xml | 18 ------------------ .../desktop_bringup/launch/robot.launch.xml | 7 ------- 2 files changed, 25 deletions(-) diff --git a/common/ros_packages/desktop_bringup/launch/gcs.launch.xml b/common/ros_packages/desktop_bringup/launch/gcs.launch.xml index ac3dd2f2a..f0876e990 100644 --- a/common/ros_packages/desktop_bringup/launch/gcs.launch.xml +++ b/common/ros_packages/desktop_bringup/launch/gcs.launch.xml @@ -12,24 +12,6 @@ ?> - - - - - - - - - - - ?> - - - - \ No newline at end of file diff --git a/common/ros_packages/desktop_bringup/launch/robot.launch.xml b/common/ros_packages/desktop_bringup/launch/robot.launch.xml index 53bf44922..2d92337bb 100644 --- a/common/ros_packages/desktop_bringup/launch/robot.launch.xml +++ b/common/ros_packages/desktop_bringup/launch/robot.launch.xml @@ -16,13 +16,6 @@ - - - - - From e0fc0252a7fd032289bbbc359af22d5c87b050c9 Mon Sep 17 00:00:00 2001 From: Andrew Jong Date: Tue, 14 Apr 2026 16:42:20 -0400 Subject: [PATCH 24/24] Add media --- .../gui/rviz/rviz_tasks_panel/README.md | 4 ++++ .../media/rviz_tasks_panel.png | Bin 0 -> 739025 bytes .../media/tasks_panel_navigate.png | Bin 0 -> 94099 bytes .../media/tasks_panel_takeoff.png | Bin 0 -> 77416 bytes 4 files changed, 4 insertions(+) create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/media/rviz_tasks_panel.png create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_navigate.png create mode 100644 common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_takeoff.png diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md index 0b02d82b9..1822cb492 100644 --- a/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md +++ b/common/ros_packages/gui/rviz/rviz_tasks_panel/README.md @@ -5,6 +5,10 @@ action goals. Provides a tabbed GUI where operators can parameterize, execute, and cancel tasks on any discovered robot, with live feedback and result display. +![Screenshot of the RViz Tasks Panel showing multiple tabs and parameter widgets](./media/rviz_tasks_panel.png) +![takeoff](./media/tasks_panel_takeoff.png) +![navigate](./media/tasks_panel_navigate.png) + ## Overview The Tasks Panel replaces CLI-based action goal dispatch with a diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/media/rviz_tasks_panel.png b/common/ros_packages/gui/rviz/rviz_tasks_panel/media/rviz_tasks_panel.png new file mode 100644 index 0000000000000000000000000000000000000000..e87af772d98d13440715cd76a4e623ae8902be93 GIT binary patch literal 739025 zcmb@uWmsIxwl)fZKyY^r?kilL-644(zrHFaCg_nT|U-Y``okl zlYRc(`Z4LE$DB24%oZ%Ld5zP z(MM-9BUdX2drDO+J2MznH#1639?JKQ&XimnTzr%qJc8W3f}8-#&+?R?#8vCqpUh!k zC}E_<->Z72A1--#;;Iq!pF$7qk>9@CZNvGo>;r9+QNj9L^^*br5KUE8^#@aU1v1r? zjAR}nCT<>rxHt62k8ib08Q0OD$2}&bzO3wcomI|}nL{#s%+2{-uJoxLmRsql{%l&2 zv^8*;SbsF>NaRKFKN^i}wE$^U8YrGkPY~zhA2(rPHTB}(C#|log2O-lakDrLy1Ww8 ze_Yl~tzxDy5kc7>3=HTEOibVy7#NhQ+f)zF9l4k5wMdwn z=B+z&qvJJ({Xw7i)rj!s?r#0)C?n^Y01NBAr6ogwRkQvLdGtq>`0zjJf4tD&-Wt{9 zx55v<@K`b>_;2oyLR*CroyuN z#r05$nJD=|k8KKc16~{;8*Rx2v+QF5tEE0QV&Qcbop9M+tdPl{RaUit=PMLwpHnrL^4L7BaXuE^b|6=b>$R`J^y9!SLH}G%#k&w@#Ye5 zWOVA(cy1MV2A$z5xPL4PW%SVt9z`-7F0Sw#5W8IYDx;OoXjmduk(6m61*%sa+JZvU+N_iRLJk8+x!^vtx?&;&GW5}HAZ@6==lhu3a^Zc|c6lu+3DFNYqVAE6v0T27pyaOP2J%9!Z17WD zvhxMq)~|czrDdT@?KBAwIsZmRviS|QOGZ($d(IVz@Ao^c%a-FJaE+^&gZX<#>)e=V z`z)~8nPk@ad#G_U7R_G^IrhD;ukW~>o)shN@V=8Ki!_i)dcW?*Y1ifZ-%DnZ#CLz9 zNKKz5>bz9DIUy8vF+Qe-1c(21rSH?dD_c6azg*my>&(q$JgWr>b+NZN=6l$)({JTU zgzwB-oehR$#2RP4QgrA#*?q!KYp(be_i1D;?k64{T;}qg3HDoU%J>!%&EFr_qiQdf z$k_GMa+H7A95DJ{pX3KR*$D5tq(Je2Jp|WsAt3)Fp5X3^qQ=51fo#ZtM+Ri;%%UsRbBm^pBo<#b;qH3M;CYgjA=cr}fy451b~U9&Wp-?>l9(twZI zwEehT=XDBHA=I3Q>*jF+WO(kdz5kwwc5{y66TS|XYN#_CSHiTv#!KPVQfu>{5Ffpqmz`cE!ecHr z{g=s&5sD3wOl>DlU|?rwKfH?f zGj^em+M6h(_hc)2)o>Bjz2{nOJ;fvuNf2WLT2EcNh{5-Ks0ylNGHy zsRu-Z>+jVit~@*-9rt3B&72&)x47KrWyg(rG~4elG5GA4I?IpJw77wQIuRII|9y1w zkw`O=xq3fl*ofzTp~vDF<|{u;u!1$hMM&uK#o{xS*Cf}Eb z`&g4W{Pxccv+mdZxd(FvAN74B0~FB;HC~fwVmrt_rXE>pbis8y{eV)~eHgKx`ZZPw z2bW1S_yC7a;B@zUwF#zRa>sGUl5NT*u9`81bkg$UE5kv_mTP>>N;jc}SNP|bHW>_LLcbz+ zTX=fy@*U4DQf?-!>knrK>&0fOO{Z;YrR+D+sWI9L>`fF`+5CZZbbKAkXG-SK#qJdx z!5BD7Ndh|irH`xSX05v2!MR%#!OE`Hi0 zY5DeiaVk4bXVvUyA8yU|JqmYQo#9psYubmttU4Gp^7~{hki&M?5wOO7ZKicD_tl)r zgogB%pRv~#lVs`E-u>8fGRTxSt^U|>M=VY2c7sO$SpDs^zsE=CehKWIn0e8nLD&xU zP>E>2fk;|d+l8t?yR@0=!$RoI;Tn_YD~WP)xg~O`RfrcVqaCd6q@N33%PS8Yj$$Y9 zFX`iYq4&U+F~!6W7pb+Gc0%=4R=0AZoUKD|9eUF^Ohf@9bxYG}(W6I-hgL6Wqezdipvq@&#U zSn6KZ)>OVw17e!7SA^DMoJ@Z!EHWchCE`l-Ah(vyQn-{_kjr$xii9eR?DPIwI)fEm zApABF8{yqHuQdMZEeS!*b~R3EzSTe8%EYEVC!{7;liAEQne^BQamjMo=AsV01t@mCNkc>~68y z%yGi-KCUmnQQ${Lgs|*Wt5vpclIY}!6=su(u%C8apLpW`9~eVTj^^vao)(V*iEMg97Fm9MCu`k%%WXm#f^Nn=p;&Us z9BbyCX(fP*7>U2*x?^vN@&Z@ObhwBO0CVEe+j;fW?Y0G#Q4q%*nMM<-HEp3tysU!3 ze)|L3gv7;91t){_7zO7Vie1IBmx*0;`v&z!0opg$itX~D0`zuRgFg%;+3#F zdr)^XX4$h7X}KG+(erBA*NE7s-0U-GQP+wOIRP9(gdG*rg8Lo87d)9n@P%69^xmPLs!U%78}Z+Nw*3!MjFnbODq}!yZ<$aGM$58Q z_|QcuS*3m9>qkXRYyo=8iSU(kHfVypjSbZj@HXjRBoRp6VkK~_CF@=WL)ycZ<$_pO}m=uwNvrD z=roGNXpEfd4(7d4q!YWQgzJBjz5{RW(VU$TK@bc;UD|e>{WosPi3g5&Lxc%&hk&4AN`YN1D9Tt4PhF+rd8Jknxy28Uxs#iBp~HqRv>0(2YeAm;g1 zzk+35=AnT{Bk)aq+NxTtwc6Rnn${2FTaiv8aOX2*k=Tf(N!Z0}x%P*Mq&q6*{<;?1 zLO|&AY~?MFLU-Uiv-_Hy$ZUP1(3!BICWeL1n>p9eow5T|>!YA?_ zsC|))x*bXYm!rmsq;7_+zXRIKTsF>fom=Zk?>zWSETHt@liXvRIL$_Tyz@R$#c1oW zMM7E3!VEhKw>+f?$OQ=?^a%slx9wP&Q2Md#D?ZC>L2g?^+Uk@fEum(5d1Bstr^fw==*cOvS2MWwPU{!LSf6JVn8NORV-F}q3cuky^j%@^5W z4hUCz+Gj=YkivaPlCglCr!nmpM{}9xWMZbWIe6y${5^B>B!E>IouGYH$hP!U^VBI{ zM=A(`SJv}$tv2tOPKNFhcE_=9d3}sr8uroyfiEA_aQjSCuVXQKKG?D$ge6$BMIp?iF_w&Sq@EAZG>n?J99bn;xdyUftI*e=dX zERu?*P70e3ZoL~T7hWzS?^cQ)758jdjda6{AgHmLA6u* z5hw3H8l&a@NMxiBO4XYyD)6=_&x_n~ADu zGg%BneqXEc61bqnrwjZEd@!@^O{16|g?|Pk$bMT>RiDYjGabYKCgrp(oc`J9xAKpI zQALy6M9^HNIW4olcS7(SDu?et=Jx~YcZ7hzX^x$pkKfY1P)Gg_)#T?adu=t@j_wa% z;|$gTi;-?QQ_xH$#vi#Lj*X#rK#HbHkZJ?hRDzv9ahF5Ku^To%!yH6?dS5TmTDR%p ze`CpDCu>2Sa=HNHNUk$_*Nu*vWj$G{8s=U1!13`zqdBAOQEG3I{xC%eQD34P5NF+* z#J-LZE2`#j-VdK1|KY3`SD~O-gzb#=6Sh@EnXA{(ENXgEedQT6Iqh!j6dB+4TCK1; zDPT=4kO2STqv5K(`giN_3L`^S-SjSe{)KHO=!UeKLaN4`zz)Crd}nM4c0xppkF(U> ztduD==MGjntU09t^%#%AiV#V{eaDTaog`@FXjm$;P zUJxUspQOL#fb>;-?qD;&Gfz`JV6?(~Zu*U!jzB6uYnVZI;v@uNEMWLnWYAhP(6?-5 zHTV6KXV8)1**Uc4tn1PYI%#89&1DS?!T|ueYSf>48Vvk9`Onq49EOD5X$Y03;u0ww zj7CQo-(Oc+xt=#tPxLNidbG#Jv#NakDj>{3O0V_M7bwhqKQQu&=DvO9#!Q2zpbpbc zaE3O`gRHrpJ#q?lYm|b(g=%hp*z`_}F9Jh!j-`XQtGu_CQOz%5fHT2Zg3p;?Ac(-7 z4c>lZmlv*5Dd+NCvudcwj2)NPcApow?L?vQVsgPMiO9Mlq}^S44MckRht&TPe+rZPUu_GVy97Ajpy>D0L zZRnHVKRZsR_%5^q9R1ev&P0n^Wz6i;#*}79k{ipyXp2#hqQ3KlX2B_RV^7!(K45`e z1x+Ai!Swo>$NdzbrLgUCp+{W$r(M8lp&-T5;M@4zJw)GTDG_qde74EdCjw&HPU0M` z;X}(_GPbyGBo}VYVN=;|lix@WD$*(hWJW|gpZmZ~&ByM)=|Ffp zy<*7?XUf$rJWW?UMiQ7 zI1o9Y$@huM9Y^?Vn>rfSf^)!tK@49mhdpy+b#7B%Y;-PEO0J_aRXpeu&XI6Ob%Kv) znHx$q9@_`~5+S?RWxTEVvGT8IR1KAmw?&P)1lp~qSMcD0WYWL)D`H%6$jH7YC28bT zllkQnUBz9$__5%u$qt;qKv{ohpUEu=P&S|Sog%DH%a*2xl{|8L*X z6rsg1*$h|L+R^SHz^scKI(H4F;u!B)pZS()hhowlr>rNave4aux*)lV6{0ho9FzS` zBE^s~5~#J3oXU}Qbca|eZhTfQ+kpP5GS$62Q=lt`n%_Ulg>$jzq%pc&kEy^m9#vLp z-@{g-_rqM(D|1zjor<2t3m)I9 z6Tt1s9zdT?G~r?OeIYSIcw5w;j6Yrf=#I-PiHut3wKgy7+B#fIAW)-xyRm!7Z>d=+ zrrY+x#5Ec`d}w(QcRm9zKPwKBk(lDIQ!Osk%*4fD_UUPfZYnYyr|wjva83 zuI=?Vq(ID(XYn7|o5=Uf$vvFKcpQG;61EmYQo%iZ>wYFqr;t97#0@lm8YM9a4_VwR zq4`UBobwnO%4UUGzI>-*)lr&5*sh}{70if@6~`9g8;^TD0g~3IX*%;~OWv>Fywvy| zMY9@FKIyI-C*!d6{?Zo#Md&IPFPX15rR|#_cYM&-xJ_1VdC{t^Up~iIr1FV_TT`IQ zyYR5GeacMRV-zFc+3>hZm}0gy<9kpH`vgnFV9|;Mm-X15=I~O=jJ8b-KI*+ADO7Cv z#{(P2{KcZdak%k_&1I2t6ITMWMuGDd6OXqG*Z`>z zx+D$A*7Z3$i-6AQS&7|A4FJ$=NDd69tr?H6?RScr*hx1W{8&ZBIWwYq>6J=!gUc$R zkCGe{!+AgApF-VVZfLxkB7&%Y8qtJ3%*_u;Yw(P%kl|lWen4P#)^bdL&JbW`i=m%8 zZ=349?4U87;d`n{)0C+zP^mj46jigDDTP;`fIQg=3AAwE&L}>%WYwToCR)8G0kU(P z{jQWY6Xs}gKZDlontmHe6)71B?H6@giQv zIo`||c{cW5TE^7Ww7CzKv)8=}xEPc9R}ovg!G2`6%47q#npLkkzRIM3yi|*uC9&uE z4W@marJ7|3!F#K69fDW$ zu+*o3tb0=m0#cGCsE z@M(606l5Hllq zZvW1BbW6UL6{3Q2>%I0-t{FsFwxZK>x0V!oG893-NIEj$WejV;?)?QxBw}p8EDOm~ zH1zXCh;I8Di*GZY!)tNc6~6E#RQ|EnXST4`W?<@llN~EKaAJDmDm)|o_VI-8kW>ed z^aYb&h(5)n`;*zba6mNs`n?();Y2$}Mn6m8d9qH$(nGu1g@Srn)4S1ol=0oN-cp}^ zrfFSiTrAqD<4UTFj;fYS?jp z)qI4b>lS{yfZI!DBktM6L1NNnX>)V-!3n(g2p65e{0X#k&jF1|Aq9=G&+wghKRmip zs3TEOa8x`FmNxlF-{F5kUf2-s%@j#;R3A~?nol^@Z44WTzwm12L|U#62Yn!($m_xZ z>n;a(zi*Fc(ZNjP{wB}N?=;6kP-E%*S7?VLtK=PhpK7sBKxKf=&Jr9(?TPs8bBQwz zFK{AvMxCOF_ zEJkzHW?}94V*jhTtg>P5uBH31V?tW(XL$!of?!NO;2EK!qV5o6V$JhL6G^Bl!JuCl z5@&Guc6`Y!eMj?T`M{UNF_byVc5~#QcdA6mQyV92aNyGf+sL3DXH)&wbuw0ieRa+C zwHRO@#%9djwP@>!V`I8fq*Svx97k zN}=mC`);G+cgZhWle=E0;EaQ3^XDSNL($uTq$No2^EBsqhNP!?UuSYo(8Y0!Yv_VC z()R3{p)g8(zH!h8!X5W&*L4)%#>4P~lx|WVt=1c{!-7C=Sev;Wj;6*ZjHfUjCw;B% zuWpD6!_K;-j0|W8?z;%E zN0}o?1iWg1u{yF!qF{}iP~d#mRsgY}zbkS6Frcah{;x>iUy>`7sQ z^R>9WQ%tn96Lm;@u5@F+^JJZrJ2-PB>J83>|CcOtd&<*PTof-ETnFLv}9_w|}gQsE|Se^orC<`-{mytp~tbSJ-UzNJKK5UW~0Gnc&6#{K}5xE-u z4`blSNFPpprb7U*^gBtw(RI^>tnn-H8kb9NHUR6U-Ez#GXyc3qQHR$)y#y*zZ@O5t zGpmIaQ#|DT&DaQ-;t`&DJF90;J+sMWIkIbC=ZCJu8~ST|)6OIZ?#g>gx+k)4VF%}J z!v_IgK?zV1NLme_(?#)XhheoS`_z#%#n#bc=7NKnjQ-@ut~lR|^A%Ez>uf{vKop-O zZm(Gtxp|^JeG=GGS_X|FobJf&n=u@x(U&ckTBtUK!y&0=TW~IMhx}jp7L8s?fwX4w zFvz!&m50Y|MWzX7U8?lU$dt|L2FJt0gZ?_vX zJz-PGCF44-%67BLb!P^#hx2g(-;%stSbxoHin1&@{;W7K;cSqid!A2|q9FHxQX|83 z1U*tXg0L*-YJ^woGzW=fyZ;yR4LB#8A9!S;sG2J0Y~Q)LDT$g9oKHQ1T@^Whxe z5;Ljumck)ah;#cQhqUeSF=K8asdTVCD92YkDd>K{iNw=`m5~d?p4XY<3_QKOls_FXTU%Qz z%EZ3VkNEGnpn#+#0#Q-XS=+&Ae)EO}Boq{CCMJ{iC};k@|C#0A3C+JQF+5zTa1p&< z3k&HpGcyS#z`K_PR@h`@@~W!1?k##wc^v;0t|XOcI(P{4_nP?63wG|mMEUQ7U=7Bq z{wwVJ2gUHOtJeP?kgmZOD4ESnxtTiYe?0r2j#Ce#<3fXjfqCygg^d3o!44^4!21tA z|LXjoAhDu<^!Y#MTb<|1?&w0ECPV*Rs7a25*;~AZXC?Fm6LqotxnSt-2>J2!t<2SJ zfULQ>MF#oFUhbZx-%p;3POFocNpz~-cCD(M#_8fFqsgznJT7a9C>(4nY(4tW{ zdX1ZRfzkzB=(cwz%_XKUJ5I_z%!KHC?n?E4-)vgaJph6@J%N?#A-*aXe;r+D6_%&agKMxOK^rowkjw8*YxS9?c-=E z**E-JrRuhsqPWG^gcy8|l|ZNw>5D(}JEMHr{a4A+bQ$=HTj*Z2my9cDtBN#hm#{WQzDym z(fE_9!y^I^ekr)=JvI8-LE5!Sg|Ab1;xDP;{=%vwYpR9s%Ux-1`=^_`{GOFAh}!(W zBo7MPO-Ab?G5#^U|NdTS>c&-96S?S;lG?!^vk)hsAxES_^?^{IbmNO3Rfkgjd*alJ zEEc!!3|jR7b-C&U;FnVnbba9Tk;RXZA0%>)A7PA_^~nyM(sI>Ry>toO%(iNHjUYtRX9=N&#xk4LcB$qmD>#YO7SU%E`5XV zQEV;Fmvt7-e_dlnPeH;0-k0~W{=%wFYD-F=^>`XM#If_bO;E=@tzOk@6{$cilIqAo zJ4GHqwIwGP&sZ8g4%`Xjs8;%A%`4+wSSD?V{cw)Sq_+Yx8&1sE&26~lzPlU7B1w77 zl?KgZ71)bnl+HaiJ#U2!-1k$})2VY<4$9w4-hCd2tHjS9&Ls=etp2ey7RJK-ht|cu zo>hJ}5V5@JQ*PhQ#DVFiM!YQ@WI1l_NO6gI5UQgAhCMKAJU9FS31$E7%$ z(ruD2d^(swVlaAe!2faXv715S(E;ySKeEr*4bxdPwS29i-r{sbI*MeCFw;{rH!S>B zf0If&n)V3u$ieCK_n_Plr=_?uQt4JQtnq{o0$J(LKaen9b{#9Jc>GuKBtXmGx%929 z;@?L_WmQ_catl|8nPg`5|9~);^B?h8d{wMkAM9gkt6CY6Di=(}Oda4U)^v^&gO(lF zZ;wQ;Bn0Zp*=qf%_$-uYuk8_*{eu{Ed!lFKoanUJ%?4!y9+oGGD?<$^SjC$aR;^}F zM$)og-EOGQ3S0quPcWh;o|AaNW$7qsei#%DtywDerQ^y!F<+xxuAhHVw2b}vnKitv z3V3-{xFfVOc20))7Lnj=J8+b0c?&Brtp(zuPN^)ks!Btlu*0$JoSHHuYZ50p|v;gii-)kf}3}; z9MS%ar8sw3Z4DpACKeiqZm0LmOWW>GJcn1zM#UgJCmECb(Vd9U3k$9CW~ z3SU+P{GqN;ONd&@D{0?%tsLs|83WtH=;@u$9BvQT&aV3(c%vgxmH%Y-(thJc58<{s z(gYIGbn7MsH-yV9-HYHyRJY54MO6DqXQbb&VZ&eFW;y;!&xgy_$$nqW(dD;bG!tr; zKoFm##6*#@Q+QI5LQ7#`)ul|=e$_zkuqVhs??E;(&o*%F(E0^n)3PbEGu^ZEal>Q# z%xLR->tw5NZ}`1R$-*#rnczdtrQP)S#jYh+xe4u%s^1p_ls3pr#Wb~i&96U!#HN(p zqoYuBk;xcpNiJ^uL549M&zdz9&u0e_hZ(8v(%L`thpIuTxH!Xk2a>USu2HTlt-`T~ z*N@g9lzFjUtmn8>|98~;AA;%8D`IjSX6jYbqK&$6Z>X33k8l6#(9rUHD*AUf^Ur5f z=|nL4yFaMKX*it<7(`sQ<^H>0mrQ@v;Jh{Te}@Dvf*C1ze*=pDb4)4H|7*Pe4ku@X z;N}-t6u>GsNM;Iq{ZcJbHV^qzezAMD(*;oBAma;olQX@ZhlgZgkp6tLXJVl!+!6nQeAshPhq=iitfxxTFTQ zB{kMW!=jT3_Pj_C#&bKxf~dhRV>%DR#a7>--Vm|z~Sdj^q;;>+yL|=YTvH3 zWQ{-=j*6i52OHL_qqGzM3o~0Z9Si4g>*X63O={U;?O9IV`@rNXP zPDO295%;f6Y0CLBW)cHhsaC1qf`eaSVq<@`N+k@A8B_{e6j31Ax$W3suAhgy9TwoP z>5gGhxOLv)pzcD-dSHVb^x8S;M?_Ki-T|tUD!$S>bjpP)C{wv(je+P#m8#TVBcP>~ z8dD9b4h{Qs^A>A2Q4`AaD<=TpSlR+2%r#b_oNU4AplWA4rNr)b4r>1Bu!)HBudPx9s= zG+N1LTM(RTPrgoqQLJ@GOtpIKIkBwh(ZZTA2IX+fkie3e4^7Rh_h57t-B3Mo*Awt3 zVO#a$TLN0est>5dd|DG9WC}j(FAH5|y;*a3Wv9k;WxoL!TBO?VREEF%O~B`tc$IH?y5A zae&Ek!;b9?ip{YvjA#8ZB*8)K#oNB4^iRRhZp3a0-QB$%_MBxQBsBcMr>H2S#!!Y; zvstgA|G!>BO1qcQkz1a-^VQhcSeU2+Qpr>}2qbpBmM)yv- zrYMmw_i>~fd{JyP77b}7CmoiCvn^sDi?+_tDrNw&U9aOT!*5G~fgf-3nKZeKLX@1X zBGiSV(#zFPSh?Me&EYB2pljjOa=42qQ%HKQ&W7M+_W2&r8jX1+2sjp`{$GpB=< zO5l0tWXwWDuj0$Kj8p18{dt`JWlkO&zRdHW^9>W&!rth!k$dikseUVUz*-9Z)!AIS z65xDtBW#rJ%+?R2n#ri=a!B^EreFh*!cU+-lU0N3`(v*}a-4E3&ZO%+%kN-;$Cnqw zMZNW1lj(9-Ba~QZ2iQF*s5sFi*IdfcZED^Q1Ax5daGR8rGXTa*rSX$z3NS9%ayYbd zho%asB=JgLThO2&CaqTSdNIaNgp15eq}W3_yj&G!3LieCn(2yq5%yocYGA&1U)5nZ z*KQhqwx{2`J2$e3QsRmkMdjR?BL}8B1@1Tt;JO(Kk(`!3W72xTq| z_Nbq(fDyS{3|ObpmxpVku&T&?Xq%a+2+l&Ebp@em@=#M7MtO+e#P=Zwc;&`-?qEwq zQ8kLqZfS?#1)r5QU_Dlt&5nI?{<6zAbBvLG*GdZd$X(smy&T38Q|;KU-?bBD3>*3{ zHhvn#rHJmOeCri2+U>s(gXTw_FA|G-t=XB|VZ17Vt4_*=_Sblpm_ba-Njl42m<6H& zS<+hrxfCx8!U^&o{oHiN(w4J(b6uKN;VouqA(Cc=pY0twf}bbEs!ncY8rz0*{VgoF zDy$x6qEQF@?w92XMA(lGZ!3wev%I1+;^tS;#7jMc!yoHU22w{_Rk{((G0!QAAsA&1 zm8(@Bh^|E6qI+Chd?jt#vfnlEpt6%+3)@O8le`1mPT;`>YB;6zTJ|FV4H z5fGGLY*yOnRFO&uJLmyBZKUsI=kE6DKDp?-y)d6V4iE@LCk6bd-X)W~*+`@1*-JWm z#XqqIQ^Ferd~kO*TZjfXYX|s$M}CP-_d4twOlsx`xlG?s_@2P#N=7SG%6&evgy8ou|o(KPNBE2gU z)6Jh-3@qA5YhmZSG)-cHPKwSvEmux-bF&d`^(0GBc^8vI#V^aL?{_(s1`xQ@?JRSnQL^SelaU1hqF}|hjZuVrxqz( zW|oVMoLRspfxo^Oif0TXXoS@q=DJ9dZ`GN2EK24UR~M8>M<>NEx#yo5pUdv<_k12< zd#Hav6%oXBzc={OAjuxpQVkZprlpO$c5)78Bk9EGjQFX69=XUTCrPux-l`CxixzuB zG1mwUa4LN$7kq82F$<_B!D!`4^A^J>fO$d9q_H>1=hV>yy3uQV!Eva^uAvUoeiFmt z$Up2^DLMm+{46gI#Z&FPLx_nyL$%MYwiZMDkN##C5o9~k;1(9s>iQ%g}mUu{K!9V^mJrb@ZotI^4!)W#|QG2uISJX?ziaI zmF%wfd)Hsi&Y63w9Goa~&;n;LAN`aPd^-UpVI?mUH9t>pH*Lr=e#&L_+Rl|YO#h7x z6;G=FoCl>b7boyIU1L07#_46F67<>Hzoepq>;Ce)Qp)i|X8PP<(n3;+26gr;RDXBm zxPH`Z<+%?|8i_`a$uV6wk4yA7O#?jB5L;>e66u@0qr-@cf!U3*CyEHV2k`?*dtCOW zH0I+|%L{UnXFm)_XKQVO{Zfi92!(eHE7`Q4P@baxJi|&YY<&`6_2_bNDxXjQNrOsG zFoq6aMxRzLeBv)V+nYif`DF<39s(jq^W5s^+H_TWmq96MT(*u5T_MRNZQz?LlG15) zJQ$9|3%@^|ieR<>sCw*z2ej4V^#32ti}48>e!;O5^U7Q}89zKerf`}dyu_T@3K@d@ zS=Xnh*-|l7xD20RUe5j?<1+kMt;#aMjwAb2wi+b(==E5mL39Pi5uPles9+b43Vg#S zpE(e`YA5Hn{+67WC%8^SJ`@1Xxkj95b0HA)I1~qInBx$dfAxxKismyv(SdS56!m+# zZc-^^-3MYIUT14W+q>GYq=c*(Kn6)_ih?OtXJX*?#@li9THLpu2)12ze~@8h=5VJuU%T`3|`I>uEt1`8?AN(sFrCbjEX&{JAfXqwi)cyOA?w~cDVfRTwf5- zvQx!sM8cjNfe2`Sr549SsABV1CH)5H>e#klHwH!@Jj;Y0nO2(7aGsznnKl{`*1R^# zW%dO6I*##{q!0Y{cvF(Lt9`^H5iYw1PB3End~YAbwxf3?HoPy3Gz!_uvTi7ZK5PJW z7B;&oHg4GNC*-_o3mg$UYTm(-`?V98m0}W~yuEI)SD5HS`=wXNt2i<%3+RbF8_Rw5 zxZ<1UUq<{n*O}~2ajpx}G&)h{MaHCN*@5GNj-xWZv$-Bzg=(vpb$5B7T%x47tmTf3 zh}m{(R?J5ZW>yq^2hxAMb(IAOwR`@kA4wa}Ga|F*C+X;6?OeoK;r7Th1t)Vh__w)6 zp=1UzDDB?aVWm+#T{6Y3yh?s+`@Ev!YN?rpaA~aq+CTw|5vDk146=IIQPddh$~|hk zS^chr9YIvw0X=eiIo#<-jZi4;pl1+1s8LEMbre**Sf&&Kmu(Kad7f|rc1UL+A`%kP zTT03=FUQQ{xGfYQ=>pva@@a37k=K7`f5c_iPq&&V;Ix2{UKhCYvR58&Jn5m4&bBopAMtkj}-fYM^Z?DzLi3(hV%xR=BI>TFbl|i2bMySLb@)qjFiwI zEu0Kt9NL6lYk!MAoV(7|7M(0lbkF~3kMMq7fz8OYWnQ&Hi44S4w|g-r$VLQHl=L3F zMs$HxE-{t*e)8hF@HBa(CstiZDm#*TVor>rCN5xx!)^Gr>;}bMn{PGmlAcgrbK77W zF>9(CO>{02%kj-rS>$;Wx30{Zu@yu;o{pMsg1g^UG|gj;{Ae&N=hAx3@9a(g#yX&V zl{Hm^SutN`t7!5khS(7ZJx`q=@BA*lK7PF2Y4i9Lx(zZoH_jqTukJH&7@9d4-qlFM z+|)>PzC=9l&*b%;ZGwH;l2tC>LoCIJ9+ez=oL_x-81t>a#2yaj&sEw`k6a+U{|wnt z8fd*Tc3is-dq{4>hzsdKY=BL!x&Q6B>X<2;+{LryL(<_LZ{W>WpzxUzc8Uq-w>J-S zmo1TChI&xP|6l<;YJ4a!ndboRn=I3zc5+@t=y=SkImTYVdB4iobH0v7a4M%=k=9gJ zM+c1cq<=z6pe)48TM=JBtWnSDY&D2bS&FU z#JY~WKiCn@2HB)*qnTa?m8zK#E2u4l_Q|Zu@!Xu0fL&6#b0)6q_2R9?C=xjNWa#L9 zOziT7my31k9^KT&U|LaBTf^*|jKv?waO$x)-<_@y=i~iiRw{@IlV-Tv?cA7D%j8dL z{JaWV#NJaJ(nj&z?Tm_ygsuS`hEZm*l)=B6I)@uay0rD2MhC+jVtoFh} zKSgKw?YD_Buc6+23p13z?=^=unw$a*gc9=44`roiqC-EitJL4BDrk2nPgfJl>l3|8 z+R4ndb0pKIAqi1t9i5erbP$TC#gZUC;t>qui;X&PBL)FY^Y7$cPd3#=_h-Iv`t5Vq zEBZ-XmnK~-?PgwjUQc;Pdgqfv+m+du0!*V-WNsCohW2k?evaUuc3aW717uMYh11mL zZh&oUYKoy(B$uPZVPiXun4Mi%*f=`+-sbo4ij}bqv@>2ftsVMf!VwCRWfU$M}7IQc=>;(h3p;y4p@{uoRmUqo-`L2M<<$ectgP4BA?bcO> zQb7Kl9H6cJS9DqgQR&XDiJ=Bv*_+MWLb5r5Cb6tf7wd&Vqo02-uS$5rOF#}$ZTUlT zvAS=q9B=yt7a(6>qr3!*VvcTZW-s>nrRWo^Vc>^{ff1c&XFd6=Gha68=BQz176cT- zp_5x(?~SOnor_)T4xyJF`6hdWKAG}_7s1Y(y$HSq)ZZe!oav^CzZMnsx%Fdful{y4 z>V?(vtTJD}JA93|Gf^flgv^)GnW_{ZoH5duvH~q^7QK}<#(wUXDb2E=8*?aL z?WU^Ytyny?zlImfTl-Qix=YekLs(Cdffdy746+(t?wUf6WCn6pjyamckFMoEd~r$< zAt*VUIUCzVyU*m~oj;3;|5^?)???-=yzFNF%N*e-T{*deo+ zA_&=TSHFqQKVa&YZXG)7Ja2xNio1BZXPPMR?sQ|tV12`MYrQ&vhvdEuAo=17* zn6|4=bTs*dU#qqVEr<*?r$V>aad=RO{h_DxrXRP9>Z z=>tsN_t!rid@My!ggyb6L}V!5ds}>#Ycm1_lh1QixW9eh)T);~LTFndSa8bST`dTFO(2c5NAHOHeXmmXHf|>l1?%rro`hHb#yuF4B8t9Y2 zD9-rVrIOS1dMEE(AF?seIg%^eODtC{G_M8BkSwZwLmyg0<#w~o|Iq8uEH1v+ zj^UEc7hk)jWKXFJn#t-ySa+HV_=W;X+?4u;{|wTIV->EH>$NDYLP)B2r=R)b@1ykO zpZVTin+N(u!q-ND0~!`DLsj>vK5l_tY2KJ?^$@|U{P}La2;I!m!!j_Q6YQzN=cDg+(<00t zNY-D$HisQt@nW`tjF9HzW&(gBl}pydN&voQ4ebQ%2zhcR*+9+}>8ABA=0S+sUUNsN9fP~cI77d>_)$mCi7_6+t2_Twq<(JIZ*2;QHa0o1HuZ$u?} zJ`Q7OtGraRK$nai#DOwSUW1ALOm9j}u5g_=)a$D2kbZcZEPpL%|9($o#a!V`0#QR(t6NQ+sCGMpvW1xai@7)91%&*TP6~VPa=j>c z=N0UUj1UtQWPJx>mq>R>BQx^{T7OG%tU2#jo5?rf;39BQrMO43i|=E7z^mu+b@0M! zYum0R(F{OATXL!!{PrD`!}xY&hG?-O`-O&|S|^WWfhrj+!^5d#F5b$m<)VaWo&Buv zSJ58@IE#54DqSWVS1Ik`Y_dT|<=7y+@C5#82s_D&^`K_-o9JSHE2+N0w?Xam91KwP zr+da%K9hqdFJ^hLE9SB7(e>kbDs*u+?9l}%h(=O9b_#ESu=c-$;r+l)2cWp1s&`uQ zID@`HWo)8W!L`cCds!aF-NDT*teF?kz1|{d_r~v)r1YZjGoD8@Qe)BfFZ@Ne z6D1lZ``BortDNqo+}XW)Ws|KQFBVeol8hc(VE?7*^mCFpVKAgGL5 zU$Y%PN<^bJ4yj21rP!6&K!j-W8aeLge99llJ~-)j4Nm%D?#;w-!PU0X=fP@L8{F6x z*XV@$bDTN)r62Zh;u1h4F4s-saVbNTlAlt#E71$6)r<#%IX|bXw_g_g7BItrQ7?3b zjp*sr8xtu>WI^+jjS_+LuF8~i(nl$78}+r)CefZ->X}ks^0)E3N2ltVebPLD&@pp; zH?ad8Y_!a!B@{OFlLOXTkpOk9SDeFb0k;t`F`HAxYDgKW^w1Zt{?bO`D;v%dO}#^$ z5t5V3Bj-Ky^-eTJDiB85I7(!iWMxHgSlY*D=Ehthsjq6gR%sLHNgXKM`C9M-;`H@> zy9Q;`dgma~5ZxQ&+1EK@8$&%E9o(X=!|wMwTYBGgHRz zxZ|r;RuK!_oW4iMJdmc*h>ZM}v($9=QZ1x)HL{SV=g9NyXXIBVE))LK0#$Sp+iNYl z{e$fDwy7jt{=LZxPZsV8YmBfjE_!6p!j+>9>=xD78(+Q$p3CvBMoBG>*?wx%1ZT-yA-w;@FHoE4_puNc$Ax$TUFk#(a4l|CD&%8MR0(s1EZMUPFVQvo)i&F~Um zdCcXKuD>$%o4-`#*orX;(%R#E8hagbVYTwzL*4`b%1NYL1+zOyR3R7I>{Dl-0!#PE`IGdI!bO&^VD@HBG}$FIPwq-@lgb3-SZ z_|kF14ZpOJkCcKAnKz9TznJ!ES$Pv#^8}HdJl~;%n3)i-9X)(|fBok?YIFZ5R0 z;ta_{uPLT_DnJUbPfTfkfTRMZ)O%@kVglz5yzBpv7yk#eX#aNfr`YNssIbJ7;8s!E zcAEw&D!yW_6`cN*|Az`c%x|fB)3@bKw6J*eh9N@)JmXRM#1F>$W%HCX*>#y*rs}N= zT6GB*%wHg3^cha!w^AIY8G{X&d69B>iuVE;si(#7xhCdG%_I6kjja$~l@(m78O)1tq&udx!1wNKR5p4S%!NL{E4AjfyA4WSY zieab-g*C!vkx<`f@i#}+wm=onvek~15jI4Q?90`*b5R8&FFCWNb9q}mn`I1rJfqRR z34=6!VOjrsUDrf5jFW@IIDvHcJ$$baehO7;JX75iR1gLKpW6f~wC*-ihUiSIX%;pa zaMD*%Pys}yNzjf`sg*s0VqjtCy^ZJ9`Pc$O<4O7M0MxGDZN!60c1SR<#*M+&yM3rB zAhn_45M?X4WZizr*oYPGll?u_`c_#baA7$%M|l$QU~MKNet;!I`Ykx9PpZMxSQ~4+ zB0-R*Y-K>{5jlL=9!#-RK1{G)Z5}YC7?h|!+{4$vcRD`<36sy=%{H~_jRbZ1e`0mq zN!BmdIy4>OQG=3BAv1M49FPB`w;zeG{B2Vb7~}~VAhjc-qqtsPSNTV(eh>iw$W(n(Ku!*fPI%6(Ao;`4h16{AtW7cu}j2s%2rg2_SVSeqD^ ztVh%QVY_)sl1@*vR6MRL^~@J=FI zBGFddYzt*=%^JAJ4ycU3Cc4--xO%m6)#jyOwqH#~8prP)a2a1S=mK?|O)XSKXLJ>W zblv=H)~WZUvTNHN{#}fwbE9y}w;ZDbrQV8a?Ih2AS zcG&7fu=q?9*J)@k2L`ymEhAFdOEkvWf*5>G`h5u6@F^m)_Y|j3u2C$W>WwF!^a+qx zu)WBErVye6UU8-c$NpAym$#XZZ|KE1n$A zZY5XVRewnN%TKM{b}rRwEb*ddt}2XwFNLRc9OJ2fbE4p6gVg{w@nY+6TP&OEU76~w z*5nGJ?5#@&$=3n%?i6(#%~Cv9RJj65S&b(Z&^HMFu}o4TpDT~WwiTheQR`H8X1)}D zvW9KFeMf`uN|tW^L0k9PlkZi9fMttcBWLWzV&?5>?*=`F83{cZ&m5#aNMjXF=&1dG z?zI=Wjx|R?L(`WRcs7!0v>{jYFR(l;ip#0;&2~qohG1Wpv)W%2s+KdRzEj6?lr32E zbT1o=tvcc~e(b2TiOE>6Unz8v^DOjxyw@x5KBsA^elbjqx z4Lj_0!SLxUp-5 z=wtR6Eubpd(QDi2AM8<8p`V0Ibab>rdL;+qwuXLmA>{$3?$+G3YXB*}(jOuzqZg&h z#!UeX5CqYUpU~)Z$5#oS>qY^e#x;>hXGdj|7OEcS&CM!|U z$F<5{I;1(fy3(`K@=gXr1RNH67HaM0Tm8HytdPJWOC)5#9+?a`u+f%xw>&@o5<|We zqCb!wk#_p@(~z4uU^|N*x1sGwHgH)ZQe-+4mGCfDgrMQpYUSQspic9kcppVOicp_R zG@20z`?7bkt6ffQ4o!#<9bEZvNP^}qar)v0*boH}giFQ>w@2C#0^!z6I9+s9%=+w- z%5UxapO73jd1W+%++t;>#LlT8rA^;HX^m&Dw1op$#Py?bm}ogAd!x*|Lt?96>{Rbk zmuySepC}}eFy<*F=~i9+MIe%sTvRUIy3%+kS+p_f(Rj00G%Sfv z_-LU>+U!NWv+cmLP}G)HKzgw!Qsw>Us0V1_d_TcZM!}ewl@)>Ao?>&~WzLIFMAU=y z$jSJuUn-<>GSJgYU@`LXC2b9*0*pIQwuiwW)0ftN_L+?qA=PJvXE1)WQj^ka6CR$2 zTIRzvU7xgpqvZHW3|s=7mu^WKcJJVjJ@WNTA#!Eq)rFcs1jh=nSO~+5x-AcvT9!sG zFI#OvjPUm3Y9Jbz&t@W^_2!Zy%{09@KA;wpvoV_m;>1L2LK53=_IP|Gtw(NQ3^%oY zF6gTDy5YUkicb+$lL6oiF2Xj`RX8^n~Lf$ z&u9C&$}W7v3Av~vJ}0qPyK46Y&6nZuqy)bd=xdeFMyI#a8|l-&i)=<)>6;ve0&vW9 zH?@YhPs4EyI#EikG^<^WPNP54mjJV%k=n0qxd4GLa%_KL6?5v?=c~rytvpONY!`{1 z3Y{HA5(GyYQt-#>KJ>b{xOYI=1mi9}OXt1P%rM>~EW3t^G3pCwFDkDNjhGJPJ=R0T z06spy$$z$viAXq4j)tdCmsPuu3Y3u-*xz<7S`7f6VDFbs4{)sx}Kj@``Vsx=yq3>jie=a$G1(&oVu?LVBh~XKU6T4LllyP9m8jGO(!Fz5cL5dLJx>o75 zb)p^3c?pZTPKoM06mq;wkGZ+Glb}JM!qoo^D1peTGq_;q)KYq)DhoJ{()INj<1@|N zoTEN0+O%*6`@z{Sur@q+?7E5?!b5c59$k2-y{l+7h3+bgV#j{4W5tbZDVMn2&k9-@ zM8QB+W^tW{XNt`6Pd#vuDvkz`4L|GfWPBJ>U(u_&Y7%_|C&-Yb8I90_5n5THHv3;+ zJ%r`(Q}uU}29oh5z4=vgDsf3F@XB8#77mTdu4hP~6RJIEIrcll2*alMQ1a7^TXbPv zzYcG*%_o~SHk)p(2=(c;6|}i~=We0B%M23w^Z%kcNsy>QX;`+nu*=3%2Kl6p?rt<> zp4W0XO=@?dfJLXu99@-veP$o6aDPwX@w@y7=zRbBY;ZB?t8-_Ptq+ldWK!AC%6GXl z8*lMsNK5039$CW0uIt<2RD`JtpQRh6%ltj5a4{;U7xg92dBW6QB6u<)dV`zj+P{ajk}238 zynbeL(G1OL?KVykD(!A~3H=e>N~*rGbt?~T0{jh(Y{Nf zy)M+|b3;gk5lO9HF99l%*4{#}Ya*L*Ok_#>MH4SyU-vY%`Beo!k&wD(WU#)V8Hw@$YF#Y&%qlT+C6 zZ|NeE5|%&fLCtz{uB%syw#rYjZ&MD@4Cxw9UzWPyCjGvC2B~)sKeI!$>}k))kZPB@ z2;E#-`tP-*8K|{ev3!#QG))6f_&pu;l=SWWU#Itu#`$u!c|wY}zMrgp8QzKC<@R{2Q#EwQEyv5Nx% zfFxfm5iSdx&E%l%fG@5*u)KFvPl#92Tcq45Lw=zVTl3+*OVJj%5Y*Y7s`wJ_*hX0Hd(#-^Va? zeo?Q$2>)IKbpzRPXZ`6mTIZS&K_r10y;%JYEsdRV-gV^;th&Ct6EgRCzP0OYMFD<$ zrf&m7&-$Zn&SNouqa??0L^(XNulR3QNZ7r(y`6I2v)vO(=;dGxshBaax8HX-BIMAk z!dPs#xptam$Ar#qLF>94k>eV~89ufMe&dtwPIxGs13)p+Z9FS-5Cyj068Dw^0^ z+&AG% zJQ#frZ`Smfn|ES@OpPoRv_pu>mGwt*)J~)Z8L%2{F+csCyTkWkJ|tW7raph7TbTx*GW8p80kvt9)2BwnZfEFDp7HH8RDvF4xN%tTZh%Rois!p&smuqUqXZh5rzc74LJQ1t_EPb| zgP9*R(qJtr9Gq>?z7|BBONZ04*aF>r{&?gkoxD=Hv(YJ&Gb2giP4MkyYeSQNPt!qtgMCmwXMq z!g>82O1957ST>m>;Zd~x;f4)4u34_O1-S3e@l;pSA>ROKHPqLR@?(4THOTFsD8XNa zM+?uZh1bZf_sZsT#R9ybLm;79SVW}CbxR%@lgym|i(!Lk&+icU$E?W00G8tmX8<<5 z49C>eRMnp=UQ^!V4ejnMl3|s9^+)CZ-Ql#teyJe=>8vhag2Tfx9v&XRNpyc-C4p%X zsdx2{V10r&a3Hx@vy(*Y?p4bI~D_cke(|K4RFsONQk&(%MdIsLsvvSvvt6Gn*4m-bp#n^YpD zrGMdZm_169L_b5St(TPS1x$zj-9W{tk+u%?*Bi0{8auF|jJb zT&E5hv4kTrg~)8Nh3EgK_k7^Z8Wi+b+25eR!9zeX}#L&C!)Oa1Se8k?Fn zwzp*>2^e@q|2LD17JQha*r-`$J`kP|^Y?T8yZ@ND_+$yY`=f*C-v;=1p8)++hf=SU zAz+~?@y{IZ--4r=tDBobdfmbK?j#uePXhcu{!d>&vR3DLurNIMUw9<_4#VKAzXkRG z{Sy*~Ik)Wh&u9MkhlE?NhdUp~r3NW&ZSAnj|E&A}yp9;}4h#ZaUd}@1PR+env7a>{ z8GbL3VQ_72(%Et&jE>&kP%)p=Px&A5^$iRFng8YXKCa6RF2Q}V6lTb;e5Irnlz~)~ zMuulXLPC}<43KG9?@Rw( z(n&HQl|ywD?Td$Qb)YU$Q8r|Y3f4I+c5pj0tD#@Pp^ev9tNRf#Jx)ClHE2u7zdgsq z>|9xSC|eT%4Y)6+|3LDrkq?y0W7db{XS^HFl^y^CtfF>t?+@_o(T$gfX3JxCEX!@q zf7xTCaW5{KS@|A6`P%^h?h{Ji_yjE$ASGZweR-lEAK5walQ@OfqCybte0oNA*Nx`_ z0MDI4X-JP+K%PN*$mJwZq@<+0MwU_tR8&-+prPs1+7cs)33>jAQx-=ntD~2XjHA>q zjO*MwI^RgJ^)>onE9>U+r6|E6W_5nATF^?C;;uL85jVA5 zFmm`)q6S9-t(MyJ)J~k?<38vNv0zdIsoah)LtIlJRdRWo-Dpy_%@)t_0{w(%`+($Xo zdC=C`aoP1U)w=t|muJqr^9d#Tdb(Od12+z-+=l`GR}K2#&-z!%=c&Db-o#LY4`FT| zPh&IuQ;X0#Bv5{Cu2Sd~8#*Uvk3m}u{;O~#zh-qXOYXCq7dKdOcj2%zt$#P2j)efW z(n;+Wm$~^-sAgb=y17Bfw9*yPWnp@G-}9Xs0J^MO;f5a)he|mrdNKW%3LYJQcn zM%SOOdY0PiCp=rrCa9d%g{7}u^>i|sO*`8cD^)%jnQ%Nn5wxawjiiHhn<7ZpsvAzu@8|J|C(Jdz>Eg_0rYr2LoVM?g%l`|P0rUbWZ9HcMA7GC}bwrYpTwHV2k5=@{bwI(E0BB~W(E4T%kEm$b zbeU4)dbi7P^4Bu6I-6p#vdB1mq}=4e*NPmK~&UYkC?|Mi^`9-EM+cfC2cX=!QUrPT6-A>YJa zfZ{LKBR&0Qoy~@$Lce(zvS&rIE=>e707?I)@Ah%c67`Dv{o9(;uq7?$eu8){g_)N2 zD^e~QpM*pPDK~+Fj1$r!l~9O~#z(3YtjNy%ZzFy?!80Q?tXes-@;|OOkVy33#Vnru_oa}A z_OZomkn~JNlS)X%@{=ZA+^yNrn6Ufucaq$0^Bd|35TfmH&JA zpX)FsdZZz1MobUQyZ7$_0ItU?~DP5(lVgR_WzdXT4iu;1f}1HRnM1H*50`ig;f zUO#~5)ECu{xEFx`c>aV^DL{kx2jrQlawEy=>NoLUnwv%0G)w#U?eCb1A@^QCAQqW7 zP~=r)w?9kX9(|JhPlsiI9O>D7VTw#CzH#~-V1=7}3yl6FYNl@Z$no=NILGx7c{chV zp9M)jl^FRi#!{(4@;?d4$iO)PNIswPKq3Rp=Q#S-|7KT}n*RQeNSPeo8W?hvrT*+l zPnVs^AP@IEE(2q_gUWP>pP<*i?~?J=#`6TW4E`EQ=F zOOMpO2e)03%lYur&Y!_wr)zP@d}%>2>sMi2h{hO?lPw-VnR0e$gD_A5@xEyb}2j?=l!30KePyPLqda4D= z?6)U5r%&8H`WWiDl)^YS&41z1H{YEmt~#J5$jZJBY6w+68R)DG#pDlR0k6o|6V27NXfprTN#sz+O}wBB(c&@7`uVCydU+ za(>CPce6tCTc?@1F*9pmOD$Yt63>-xcab!1)Q6)@MN}lAF2gWx8QAl3}=8qU$+4@+23;nu4-Bz;@ z8Cwl(Q`u=M7)V{lXPWI&-#dR}$GK$7u-m)}cz$~zjHQe8K^`8|2PXzQZ48Qc^`3jZ zlFeL>R;}JEvX_5O8;@uf3}vssvI5N~U%K%MJgfhYb`n9~|Bi<|F4@pn{mRxHAU>K$ zuAepjr7M2dpT-$o5FL|#K+)H_AE66y}iDSv#b2J_v~cYuCi#`k!itu}1qvXPQvyYGKw9BDob zOW#!T(xxLj^V~c-ZSfAKws$cl?4)yHSFn21?Hq*=2gEmmA;a9E%_N$ai|^VtdSAU- zKU>G;G+5~LK6=)2ypg&T#l)SE2e&ViVWMPn#XHg(;l(FasesN&CQ?;*GGP$hNZ;*U zpDTNd%}DLL_yz@9a`v++&=E+)Gv4?68RANOyXVLewRlO-$p`gLK75=q_$x*v{siLGY}a6_vVGixz--aWXJ3CG5Z zl5AYs&wqBDBcUZ+1iI6U%4jh9y;Vrx6kKfvlH%Xp`>Gil8YFt9P_CVy0Mo7v-CC#! z>u^d#NxzQiw03W7**|UNM9&)Q)~8nP)|y%I1ZDHwLPZr z;u_hu6M9DDy#%u5JgGzmHrjes+1r`k>mKy14bEpI1z2DK4@9MY7qak)iN^`FTDgtC zUcU0{o0cRySwX7iDDAC`#K_iCD`qx-K`Vl}neJWHv~Y(h)6F;&B8`M8TQ19Vv3pD$ z!18DOo90E8_}BlTIfN+h-zUXEE1B+S)8^*lWB)P<7qMsbUfZc)tfnFn#i$}aE>b(= z{XjhjV_`E6Ik`oygVR?G+3dae0PS)J;C z#CS<@vDQ+Z~z#{~)f8ug{WS0T9M3|9*w|As&bl&MO zq=32+p~Fl23Ps8ma{M8$J!v4ghVRzq9+H%(Ys@b5rz;X#Ug}5YB2G8dinxOHnydZx zBxZxzWo&6)it%Mf(cYG0dZ`JuvPL#ia_(Y(2%`vdBIeL zqGbw&gaav#G0Vf;l0bANGL<6oUY1RrFq!TY*FT#CD>k2>9evGC0(w&Jl{0!i30BBp zoXnFFZh1l61uZ8&Viy5V1s;|Fjb*`Bw-dEKuNjt(9H$vY!}ZKUm)~rUV!rv|MuEkI zO=fd}w+J>OyUn8rZoduEB*xlESd7NH_{zMS_(>gMd)75{fLVrItVOg;(B<}3^`^VS z4R%0!*L>CI@0Z5t5&`KD;L-Ic(wWY_Oo$f9y;sFdvHv5&g8ditsPZb_e4jFL*-c1z!&q*;5Z)*0 zk1*xdkoW%l;~SnvdTZxW9_B1~ZUpt^WUAm|+_J>g(`GwJaTB18Aq3OV-8ORfnrChw+WZ?Unnhkyhr-+|7@qPRb$4vX|)0QA{N<@ z0UL_9e2c5)?*~YXT!co~HdGvr?N3Mu4Fgj8I;GSvoJN{~S^ORrZMb? z2VJp2ju`P?oT*u9?Bt8^Ns$V6iR@=A`+Cu@B-D1F9;^*m<3uQ>bgUgy|vF~daK+X zWaMM?x)bPzeCDsCs7Jyoeys@F;|OU{IU$K(W0BJYy-u>@>C)RF1ix204nsU0FFyVBEMK_R>pO)zD~+MM|7sYPa%a%y5I zvwA77(vAPf3|svZDr_{x`s9qrhWCDRz_U@hUKi&h{L>^hs2b*CMmDPgq9uIZkDHUF z^+&-y^PbMjqtgqYUARW3pX)5v(AO%{M{Z}%@dUXcPeR{~*U?5py+^I#)vsCR7*h<` zRK|{@L)rCeQ;f24EVRqZh3rEcfNjRV@7}dEUp|M%Q(4}&jPsq;pp4u59|^CBe2Rt% zhB$AmO8&OFNk631!VirF0MN($5?&pZiw>{Hs{LrQA+ZDfy0Q|lN-A$N0&zDKov~B@ zfG}8Xjg?DQ=eb&m5UFqkb;$SE2O|o4np=p!aU9IYmFC#b2PRJtE4b`zYMj0l)_C*1 z%SXUTBr;a}(taUUrDJmH)Xmgy!fLVd8ll$rVCe9GUlCSi9ZFZu@sOHFA@gbN>Va>s zGHAn0%Vo14%NN|Xo@EnW@uUtUIbOZTWqu?I31E6Re{I8GhjZ9l^X6~dM>s4*9iXkrqo@j#rx^zTZFjhs*%?3JOBDD~d`ZF0q zn6{vOyVI*@(-U;@&cf3a`ztLJ3iDCdb5g#CSEinU!)wVnq_g#kO=V0x3Vv$rK*Ocw z7HdgZEOje6=xj8W_F+V8?n}3%;jjs>u8V5gFO3c#8hSkg zl4(7dyJ%Zk9^qO*i6rZ=ZQh65;I`CV8@&@~i{ANa;@`wT!rjnv?U9{9s(cIaa=yD( z4z%}4ziI{!kEZq1%v5nK8e2X#BD2*P@beMwHgWS_)lv*K*%?~BwU3%d3nQcLvTIIw zGI8?fnN8^dP?ZY5ZMP39y909J6$dv7%8*`2&eQqB% zd8p#QLv-6+A5zLpz6y*1R@fcM=G`!oC}s|)DDZrM==Y^@X%Z5?k~2Tg!pr#eL1v|c zp?T<+F{+wCRr3-(?*vv_KQUh##PV@8cbW|>Tt#BVSeJj%b02?ZD$n z7LSJ%9lgFz`o5AziMV{Iwi|W zF&nDvgYf_l+uWiVjZfnJ?Yl-wvp0V0tVttIVHA5{iN){tV}|MhgVYLj8#RIV!eS5l z9d#M0+9$W@^6nIhd0%nUGNZ>Gjb#&|iNXSqzG89s5Ac_W3XDHi1HA{9H|Ou4dN%U= zO&dT(&e)ukM>{i)1ZcH%>5A|>3&**RPe$5efQ{NII%UU^=BMAAfIPU4OY+`JE&>ii zGPSloET3Bmb_ALH>kzbCXg}B7VFHiLr#s4^m2%bIWn5X9m9-{6c~OVf@820{(QZ8H zf-EEBtr!u#NOVP@iCaNn%W?}dr={QN)AJ&gU+>xVU2rL`W+f-M()lGv)^$Ogd`dO~ zMa?(iQs>ERAE>in1ZQs_#C#II`A{{Al~JL+(%&+C^Vze2f*{k29};gg0HzSc)RRn* zi|(qFHlUk8pL_ixm_eYG} z*%NV3;3F|ih_-gR}87*UVzJ(=41rA2MI zbiB1M_e-f)tk!yxw$;TNKP-L~78Sl-LHkEoVhz5`G<{3t#RyP9|62GPjxb;*8^xd{d`Y`y>s&c2>_kf)^ayr5 zt~#eoLr|`mN2M2dwESW*@56cSf|;)Gz6a;xhyt9gou~yM8|S?s_9LB)UNQ)qEWvnP zc!W~y#*)vAHwZM|TfR`D*F7~`g>lCtBh|ni)l;KYo;`KCu$mU#3)T*oY-zM`my=$I zO)B)c)_`q(B>ZSx<#Y;f>)I6Y+O}bNY7w-@`?*2JqlK~DOrasGotAZ?`Uja^HhIzl z_;TsyK4%K+tk-!NcIRMx-Z#r+#+&BsS!HoawUXgfJRNQ7~L8Pu8}-WT3{(i!qr)f9>yG_7@;b zSVt59R>%G_x^u=|)6hX;rqTT1VH$x5muTe5;$Kk-Pd@Z$F-bh*MwOv?a`$kb0zf=l zqw)xP-kk6=OBO)u&kT{&3x2h6s(QOyfBid)Bt##6rSI;}o*?Jr!%T0cOn$=lEnd_u z-P1Yn0wvvR@#7gd+NW0i2AfBJ?`(hVx;_BG>-@Te`lPEPbpK#*AiBet>q)Ta#L-eU z(UC*~Yl&fzbzf>Z9Q&-@Kx*Z({qub~p~inC7Cw|6wFAgeIEf+K16^ih{@cPbHKVBo zZ{x-#QQBjeuvea5lSg33caiwT?o0a~cmLjlfPqcq!6h^jqhxrQ&YmZI!b7!o0G5FP zq5bhpiHx4?$b%m|;&Ae!*br^DU#666*yvU&V!T|7;L0>A`l9?UjUgGK2z|)}srT*h z_~2I+V8wj>h>mKzC65;c`YjC>qj31 zeK%JvNU2_3J9Ls`*GlAX5GPv?UnkkTpJjxMxn4;S{P31dQRYQQCnUOing^umd|&^= zKK#vhY>Th4nXuDM{)G&Vw915ZY8}37@t%y;$KDK-Ibpsg>Q$}4u%BA`F??z*iacFf zhx8Mlqm9voXuT@v#FD}o$}V^KjVsgM@M{n+9VUs2NMZ~5VSt#*ulQ5PY7Xub4QZ(J z?&C|+H2Pk+{lS$eTMYv})~!udg7Q_Lv#mvlcb>eEP`~2;+6lsf;lgjN!V_ErF#v|Z zsMIj6ZHS4~Q(xk|z4KM?l5>jzIjHdH?Sl3z{McX=?4W!9r#ntn6XPSJ)qI$xV2RYU zLNl8iqnxCvqFh^h7mjxR4Eo_JZe%^81Kv4e2a64bi zOD+(ncm!?uU08$p0KS5HnwzYins1KUGsU}2pl3671csS09bEIDcWws8?mxq&<-PKM zL3;lj+quvc8hSUya2+M#a9dtmxjtyu!vZ`Vhz5NmJEpUPFn`V90rNX)<{bSZ{loE_ zuDayifzeha+=$mx1Do`T&GM1PDd+zCco+~q)=QtrNol_I!?C5Yl)LptBCfnsYHE-N z8{Cwb#gzL|QEqL2wK}clH=i_H%DOT~rg`x((ZT(z!Xg5O z$R4(z;%fS3-aOa5Lb6-MpWT_P565&X2AN%j)=Q8sG~lZvEsp=;G6s%n5tC25kz`t zJw_Xo1!y}l3L@Ta6m`1n{3`dWH&MMZw_RJNC`PEc;Sg=_0REhwbAO=`CI)peVu z=V6;H+*K-9@*KA$k%WYw_;snPm>c7-*TuFRO6TmT~8of2>+Y}8KshMDI>L@#H5d=s#uroSE%-s%MIySMVv1QeZFbrH3OX8 z=x#i?f-%wBl378(E3v{d3F*Y{zTSgX-g}^cd=h62c+X$5X)5nMMcTzls(pMVe)YXV z*vMA_s=f8Di&0EmTCMoJ$7}vfFa4uyi?h4LMOT}^d`2d#Kn#NuutMrfig2C^=Ft1n zwTLYUS@nEoLBAd)8&jOgy${7@v|ifvJgr!|Kwe94U!^2Th2`V3L@Gx8`>!W10w#Rq z6^46PnQ9!m0%AigPLH$;sPu>1i@STA#cWpa<6ISl^Wh;|>P1`J<3pxUgyADT$HHjN zwbj}6k2nmu$VhsI0!vMe`y*I2VJ!3jetdX-l=Z9qOv>Pue5+Xeg;7oCD#|51nsf!o zsz-o&%c7~A(fRX0HZr2Ee_#Z#E4XQ;SiAR`6EI+DwpvPNUp)2Yl6Cz*ael4}cUm%Z z9*;zZG$fsF@IHX!T}Fe-Ztsr~%ty!i9Z{rQQ^W^Z0w@rXRE%Lep4)~OW@o|Wc=5yn z-H6=FKPecF!5gsXqw4&P!0juC!i@7;yXKqL5Kugxa#6gq7(6#aJiEag4=W^W%`#+4 zt(`l-=2}V1DOiu(8BOfZS(lr{FpYTddr#-Gxo~00HmSB%jIn%0RIDV2!4Apj<53lW zPeBc#amN5GI(jI4ywZ^DbcaLnBF+f^{#vN8MRR*pBc&p#VD|ikPvj0?NnwWxn1CgA zGeIvPT|l$ZKy`PwWiKGT(*MRQccHnOOvhFjMsn5nf9QJ4fH;<|YZwcJUP-o1W?EuBxuud)L}) z6<=4C(DTQG0=r4@bU@FOyKj^Jwj8I@XgZD_?zU39-?$*39_sPtM`7 zZQs$uVm3(uqmY+gc$X9nY^&_F#0N%w)Psp!_Z$FzF)lA}?$p$wsuVPTctx=ywR*lc z=2EH>V9;tnFT|eORbX~9(H8kKV3F0`1VCAptsxC#u1)Y9fLKsAvJB9rFu0n3N@#A< zEyIjTuiN^j@AES&Zw(j}ZcDb+w{StLRQ-nKSJ_}_7|W+cr07|}LElDR+z7ny2B){^ zQ8okH_EYWQ3^kDS?ol>t&m28R=q6U4Q$&kTD?c)dgeYI6nQG0`*e^ZAG>+pg)vJ)7 z0C32tn*p7^f_5jEsQ>HIpg`c@p4yQj)JAZoMAtmk98cgr@Hr-?LhH?n5y$Et(N|zP zsO;G4&N^TBGfdD-IB3|@-*|pnIoZgQGfz3B%pJN4-E zB+Wa0NgGmD%zr~hB6iO{L2#v`hdy%$=*kT4G@F2Uzll2YdI_E7zDCa&>cv=mM+9lc zhml>Tq^8%e)Gwb74Bu=r#}b`UxZ;ReZ8dLr(|+xLn2Eo*DvJ{xLH};uQNU69Ks%)6 zx@v7qMX&Rwk^?ti4F@GBEiqpTRB%IgP13TbK|=F(w+~y$LL+K4;2E7(4*mk^8}N5C zy_rWr^OJnAr2gpM2mLpK_XI=pQE&6LNSfH)Ew(rIEPX)dZ5ZnH&C}bILBa)*hKH$w za<PY-jjvL7_HgB0_+X>`Vp$%j@~0i)J?&@0f$hfrV@7JN z!A}85&#W2lYIx2MFL%tDf#GPWt+ij9H-9WxsK=Pt5Ey-SeXUeIV*J(GjKz)<@o`9k zwJHWn*tJ+B&gU7O+B)5`zDH=6jm@D>BN_|JQ&&PansWW#LJ8~SX3Z5tWzoLar2Tk& z?L(dNTgHu~uM_CY%gd?9PcSHb-S+{MnQ&YN4=9+%*_*&ATH9vN&EB&HQQ`dz`K00 z?hFPY`ghrYul77M`<>e$wg8)J35%q`p`ijP zjD|kdmb!K^qW`{^-`fqY_bX2aSj4_ub-j-EtXr3GM>MdIAV?4i6nK6$Ou~1Bh4;{G z9~nIp_|flp@yGh3!5HLUg2ey24CNKwiW{1zr)LEWvq#XM@OQBV37?ERV?DeSZmw5Bk;q*!}||^^x3Yh zuLr`Ek-Eci2M&J-lyi(6`K6ij7Th>KP2BhSrkP&}53&FI;bGgj#t?)*Sik?hy5*!X zj-B`KgTJ;;8p{7m8|X;p#s5H+_328(s`S4Kh=J~Z0Hw&?sh<50RM|#p?qBHFevKaoMKj9OA-=W5^BrFyzP0-|5q*}l&-KuPI zKxdrinf+vFKO(Y$n{^UX7tGm0dQ(Qz`Hf`W; zpCK-Cr|rc-PCH{aHv^706`G7Na&*S0p?clJn{=~<-pMT8)M|zcYCdVxGjkFT-(l2) z8GA-@a;FhT9%3G1Oy#xpIaWgi1%9_rbbf&Tn_K1KndIfaRYv09MxTi#qh1J%N z9y#z;RTa(SjacEm1H(LLndtXt?~#?yb}?t6DRyJ4zuT!*=Z*TEch_^BtAq9#D=MM4 zaCiCgD-H%sD#(x=$uP~D@K$5vLOzR6%rRR3>GZIjjV)D1{UERk&6#Kn{*BSNIDOJc zL;v@Lh*W&9ra}CKo`gh)!wwm;YLCbou!eWH=qwRC;e9B7ur}w3ER>A^Jw^9{R`Um{ zuAXNaeal>tlIvaWks&k!XmI>MB`8y{31Fm38=qo&zOC&Bw;_@|0efnU`p=9>jPP~U z^tREA@Z2!w{7$PO?BGTrw5dCvUT=)0@^0XES1BZweN)Wq81QZEf#{{hN&ZGBhTUcT z@Aj`_et^d4R0Q~Vo?!zsB6q`R-hZPD>^5ivS*bAtps35phzt0PZKuoLAOWjC-i}vs zM9CG5mfcV_w&Ge?2916VNn0)$M_NXT3WlFgduU;|hj&9USZL49qLA|1wbuJ(gN#nV zl%$PsH;|Z=OgK3jl^be1_;@WQA;&y8V?Wh#IBw>~@0P>rEz7>l*!WPyK#?X^G{&)^ zfc}B>HE(l|?-FI&l+_UWuT(ke5fb1gK9mR~rY zOfyWRwiYuB%8(lE$#zQbeoI1^=d1qeXlz!w>LK8k!2ZQhmte5~{*lIPq7kA;&%sq; zzQCK!LYYu^I&f~MjT|#D!Un!ec>*Kh*$6AB#-jp9Lv|;NQ7%N~G9C+A%Ixj?HIBL3 zCg5WGhouE?C^tE&n-hVykZ7~<@g?zmf^sjs+_`kJi61VP%LOoby~9{jkWwRwwhnRh zi373lW9Wb^%j(94_<2_t<-uHF_Y#S+a<#zU)M*wIFiCjZtjn5)v%6azcKYDGn&(5D z%|~8paU{mZHo-Ck>DiGqazC*O2sT$vmCYH+HzruMBM}V2#4p&R>zf(xeGr_vi7BRc zWW$0pJ%7oPK(*i`Uu&C3tq%nGIa7~?wL#@~9<3ycZcSOD&EBWHPaCX9R$Ds_iD2`) zQ5vT5K3$3c;!My+&SIqVW@#qj_g=h(^w<-yoANf2t2km5_T#X$bl|{ropX;<)JD zKh@En@?SbWu6=y&8!)49EAz^{Ev~ISFX7r~SPN5p?vz$5dE2Y`Lk@zv)Dk#1EBUCH z17pC>47}^iBec^&hR06D7yZ4?Q(&aDsD1KX)G3EQlMw|(@j5NH@%jo`Y zxCfCkZ}S#|gyI8Ph>;CJrVrgxsqk?Pt&2H=m(xh!F6R-knnRTq$>$Cmby=-vb+UmD zyoUYS32&YiRJmP!KA>XpbssCaxg;8%B5bcyeBDNOLEekmyOMSTg&a5$c8|sdRfyXg z-luoo6pe~|X}CA|U?ENKwfFkUyfok&>7fg}Hd$1b!LXHZSVDfC-W)E>GFea&10U~x z((3x@?iX9irNa6EC%j8KtWwDkQO&QM=S%WbK8jPio8CYby%91pE0UNZrc64(7G2HC zRM{G3)Vu=3-ZmwFw+EaQ>6L#H829-046w8W4<*TniV7$&4|~)%R#|{W!(Y?8b*|Pv zZG@VxCzG-9*D{g$EMy=^Kb;JHk0IcrVF9|*c68$c*=;}!EIxb*ArCC&b{!uieD(%X zehfWth+Cp0HGjy@(S!;_1L4avjV4-}eE6~%-l?Np8lQPMPnwBB-i)ji*=6W)#lw?D zQ8=tEOgbXk6wLY5zXW3KOP8|-Om*I!oVtG`fYczN`bBR)%t;HdThMo+@$g&^JQuq5 zpnlftLY~NQ^>I&c?GfA{ZrNcEqo;8DN+v|yy#=+0-td1rjht`WxDqz?S*|!Qs{tO< z9A!^_r$cAijb^%}3?W~#6T9FC&1{~(xpEDR$BUry{j4mz#kB6IH9HjEop!-lJe5}E zZg|o*fwN|`*5`Gzj*xPF??mEX=6a!UrZA7C2`{RR;Mi- z9lvICdyoVPX+dZ)e3jzIEYG4BtF2G%W0MwKzm_Fhwnk1J^k~qh-&zUIq-A@nSFP%} zh0EubZ${V&oVoDN*Lp|IRk(WO4TxD5zkbv7bFAdmJ9Rh|nkSvkib}=tiXvgWK(uG1 zhf*q#p_1ja*y(TWf#tpXI5xwQ(2Oit0>NVe>SxhN^3o{y1|lF{^m5e|iWJ^4g>C@`^}imM`zw z5KOy-4($cVPU?CxQ317PDzA4Tr9@3iGfwhnMG8J6{ z8;KQ z^I@EKL_q;Q?tlgux>%?}!|S+5@U35C>)2M?!PT*|v-2#!G=z7J#o^st%=qKemS_q5 z7mse8m4F9wrLh&Von*olHV@>NE5t)V7X0=4W$x^zz`Mk{y#|>1)w|T4F|9~%aNah+ zZVYtGX6ahNd-=hPvS&x}du!B?QiWwuP9&*^_d_GXkFg1&s}vlaa>-YoLa8~z&9YZ{ z!Gn+SIE<5FidYjSb2ArnBa$x(8^cgp+>Moc5(-f@Ur@cYFCB0`u3kw`UH4qycjmz@ zlpbJSviv-+@{SuMs!-~v&mCn}qgBNynWml>#W)bB#fW#XE1SBEzOZ{yBD^NMdn7`@ zo4Cp8Y`~dyq#ad2BK_4qbr^+A-r)1it7+jH*Fwl(<#} zgM(7#CgCFCyrw}Oay+P8%uw!-7vhl`k+SKy-1NcOR$J0rQb7I(tuX#TqV6}XZ7V%2 zv2T1sO@XZgeaGQvL)L1gesC~Pz%D^{pe|{DCT3~9C$7N-mTNc?5QD|lNFt^~TnkI* zCgRNA<3Bd3ol*XqXXV7wK#(ljO2^MeCagW7&^`X+`uh5%dJQrW*RR%HQyGlXWslF~ zs4?Y%_F8zT@J7jrKQ9nGNn z5uTo3zO_5%#U{!9!e*zhdLT_Szl(?Zx8fYyqDWHm~*dL-A8d$@e9x zkZ*U=&3onJ^AEkI;(;+NLM>Pm)@!nfbvk(>bJORyKRI*7E3B6tkYjGbD%bgy4z{wz zoq%B2Y-huy#QW67P_ zT*iqf4s0Bv0sCSN?3XX4G^gJD_Elgm3vVm68J+A>xrh3&R(~84N}Q!`}Ue&6?>t-bV%2_&GNY-jJ*KVQg82g57xaC5d*R#ff z$iE#?v5sIkBdXP^XGo_6KC0<)C7m#xCw&7>k_|t`cC)NmX%+{w(r`(L9Oux$v9osp zx2pZ;o~=_*hTeLM8GPjnT>4L@D{aIWKVdm-GnR23`Z@DsHr1$ARVa@)vY+x!KSx7_%eOe(#|h*F$wU zDDt*~KlRUlV*#GM<)LLMWwyJoG=V1p0`O>xgE;pAG(5Ce?IND`KIX{o9bT9lgI`h6 z4|q~}61cnfTL<|Sal6s4g~uZR+dZs>?%opATBwXy1ila(8PZNayblAfjK55udp{r; z(=>fp=u_1ZEgJP|W0*W;%Vn`lOXlMw8T6_`Y@~Qgd%%0^N*nd;r09Y^aJ^-#*ii7A zjg2ru`|U^in(vZR;ZGG+O_SET5u6DPqh?KEY`Q(r=mDy-^oWy5Z~HcU$cb4@%0O}L)HWB^Jm7AnN-V$JxsZ5iY@bL#-j;6PA`MePa^g8iHy0L4U$zIXg6zGNHt{HjiC2ZsrWyPuJjUO?@nn#tCnt9= zfJIOyT713HkrCbQT=$91VT&d(H+nFQGom914e=!&o*RF#^uz6iy=?2B;Q}Z3-z?^~ zyY8?U$!F5m_gnT7mw>NP3zxB0RmQGo-4^cejlq~L9>1{R#>Vh@VgB_{8pk&5lJ}?E z$1rDgvo?}tChxcLUZDvgRownW1>QJvSDC4|&pn0Z+!C-FA;Ab2`+bf=$N&cCJ7Wis z)~8@MA9op(W0nCP-3L}H`bAg}6Hn5#+@QH-{r_7+`bmr%Z9fn}JTk99i$gl=!|Fp-_4Pb}hYJmv zZ}i=5Uw$XZ4nnWdc*@;QHt^?)uEf+g42wh-H{A}*m``$ma_ z$8mX4u=yO;SL;1a5nvl9;}miyTyAHW;Ub$zO+|IujzZ>ec`)b4&5^6d)99i*2}`W~ zO`&m<_S>x{suus7Gq=%|sg><=_K4xG?yf`SiBwy(|`7CZSz z(fEnIC;x3!1|*373jC~Rk<|Zp#OCj%Z;BQc(YuP=+1Xhn4fy-H&_&6_kM(!D72=lb zJyFiauxglb-ROG-8+8&FI$wg08DX5Fbs=y6{8^`GrkWcHpYT?X3SRspzV-WKP8to_ z0oryRE^S4FcLTyjz=;3Qi~MB^#Wj8`Rdvv=xFjPbDG!%KDKYAv_k-J+p*|0v`I{a5 z`=Io92I@A^f*X5v5z0_&SchYCE#1Cnu`24aW^(-5!=|d;k@g0290PpatB8?_GI`pI zfg5(CQ_mO34G!lz2+t682`a7yVE=@j+hM{4QB{?AKj#cS?sm&esud)|Nh(7bNU--| zx$Fcgai8$wQEytr^2QV0{b{`YzIU)Z>?LXh#V%wTRq1jU!+2VlG!X3I{0<|?`+8F^ zUC)%Na>?L0WpBq??1Tb*GH$H(CowKl`o269+xb+0Btkk|f4h-mqUo&nra6AyT`iO| zOVD{a-}M`UMvyDk_Qwy&_#?6uU3g zU+QCF-A4$^KyDB~A+I=!hGMH9yly0yb#p*G7q{ z%qu-j3Dfa9u-=VGI$L#8YDvcYm@_`EWact&ej`ACB0eMWnr&%*>@Q`=f7Q(5kezNH zM*K`EdC`K-wCyrDse&r?Y2IO)THDiR(*2xPE5+{Y(s`o~uq6P*idOicvQSumr3*fd z*oNtM;1TH^4R#^!#??$dFwUt)DyrL>j$E<|Sh=n!7vUsKldj%(Puwpv`%iP(;^|n3NDjM(~*|4tOdo#{4+(L!#3h={I*~eDT**Q_%g3_VLw2v`}K~$ zTIxVNf(^eq3$tt?6Sv-Bq&1Fb}Y0 zr_%O{qd`a~4c5$yzAu!|Zdm5hG99#Tc{+tsheoGOQ5_sRsy^xJWpYI^pBfWh4=Ei` zR;+yX>(C<*jiGie)XjUHx7RXwfCxSzD_ofzNTQ8`aAqcxGKT|0Pyj*J6Sh#{Tnv_9 z$8XBex2JloRho5_!hM_PgrQ%jO+%+0@cw%1fA7UL{#LI| zpiyku1u${~x4Yl7pc9;w-aS{#uC0Pa^q_OR0`~OQ#h0cQ=|=U0Oh{9{5!`PMwhHnJ z#_3B45iL%~oxk!S611&I{;E~{#2dpvokP^UaIw0(5_Ml8h>NXpHe`dC8GKOy2*p9p zLGxso$xTdN&4(oPJ-l6juT%e}H3lOXuo3oSdYJ!e#w@#MQv?093rAY0`^72f;XT3l z^jyj3@fd)uXw{T{f9|9t`GXu%o5Yv7!Jw}40u0u$wp>3youDlBg;6oe z{MK}qNh%p6dSZ`zlb*%IdW*f{F1^+9s&ksIY&6%2^~DB@)DNQ}!d8~FdJmN7l!*-K zKE=3zt#kku`Be^4k(P&N3KPvLm;dV7<=J+Y6r8e6VaXy%Z<+OzAsDhPB`3^&52A^O zoi#5O_Ex1-8h%8o&jXqsNZwR_1Ox;Iq7JL1WJSbR+O33|>>f-ddU!rRi~t!qFpKZM zD^s!Tv;pwOWjV0VtZu@~_gQnUs8`}V0MCrZ79r9Ia#Umm#(_p2+8CM$`zJjEuDq3Q zf^pINQS9Wl8Ar*zCz01Ex5mO`;E(+NVcE9c;~ag@d6cr9vG$HKdppEx8Tgy!`nN!X zjicd@_EXetHXQ}?`%MeOJuy{Jl!tw3bZ3JR0@xM^I)x`vBsy-k>kjk=6-Hr#J(sp9 zp>kZSN$00^|{Q8QDVsO$YRz84=N!BQ1na6O+ z1YH5Go-0fIWGYy#-6WgZh7G&K7>eHw{LxHbcvKzBu_erOIlLd2dVsdW!A|@hmKmRZ zK3+h+#*i(C#fh7|reoh)pR-J#ZSX`M@sMa`bB5S zes_o^8Y&7Jt#^9KWWCWlF@^Bq!Rawl(?>}A;dB2?L1`}^K*xppOnhyRNZcV-_(-F8 z+2Wj{57G`^F97rW;vtW5CSL}=eX15)3*`rc(FhBWi3$`ldZ^yQaf_j&-MX%Yw0&WO zI7b>w#*{nT;OJC3zNtvGml7Oty}urqEBS@P1)W%PR<+bbi#dPDm?T3h3b z)ffKD`1$Bgxrl5)FVVRCi|10Ec6s>=$HN-I>!WseVFAVa?HHA=UL45%H%opOssiOw z(w+AjzCngeZf9DX;gh9L&vgONJTpt#+v20ir)zVGq|fp(PYed9nQBys zmvH-jt>Vs93HG~EaK=(gw60P#10=T{*rPbLo*5JJzHAdIYmjI-;7ZtB_9FS39Qf)I z9^A@qIO{}8c1o)kQgC)!hi}1Gim4E7Vq~m*g25m{YK};GWI8_y2`!M|>bapkZqmq{ z_g!FZGe+=D`?}`hCI~s-?|EH-|9Q0Vr9?a&O2IauqpS3rXN{adad6buRs11=`Xo{= zmGcZ4C^V;5IGM%Gst`)~OHk|d^k=E6cjKF$U&hxKwO`aBQ%!blL$&6F!s4$Bq%{o% z1QDNKy7ibeXsycqedc@>x9F;}%B4bgYab5wAsBT<#c$AqHmEqaVAyBflp8db%}yQ_ zGwNPX?R8fRd+Fw#%}37H3GS=(_*4@&rzPdE_&S}my6ei084i}Y5IB442N%QaW|8=u z7k1p%HEOF4``kHadNK*-*&Hi<^wn7Vpf002CHzM8;?quz#s)k;3; zX~-(#>t`g+UNA6E1fH?PhPZ~V1!{?SAgQir;{3XH(^3r2C3_X9?>xVeDLO&^xKa3k zDlOQ$K4GRufDRB~wRrzUUsx1W?!{qq1OLjj^Q2zD@{(+waoU-=SP0E{JGPg0?@-~> z)Y1LQB{o_TR!+2}1V5S@(6Z}?-Z#`s7Lo0mDZ)E>7Mav~0NV@*FK`>Z;Cj3O_2M%B z1n2Cz=MzdWr$gh>4siwlO{s=&__g;ciE7jpIp4`t<3*YN&0lnZ|8_WF&=C)BZ}Vx1 z3{GpjC?f8b^}v65F>_coOJ(tzCpJP7>Pvk^dO=P!Uud0@`J6VM2fe`UKQs(obWdW^ zmeACkwcTw5JfJ*y!&vP8Q#KxJVbFtp?*1<@?xPKv;E$vN{p5=ePPSp=vUHPw((C;8 zpI{|f<;(kjv_0$)#IS^mySSmOP@MvZ#{2E@{j!PcA=pE9)~0r!8ygh!KR_c_8GU_y>FA(Tx`jt+#xpah`wRal!K&?-Q&2)H z9^G+9M>6MIj(pWvnj^h;s)z5BTABIa$`7+7W>Az7ieS*7YVs=|=hZfss>=1jYfJxiI zjP(A55!H_PIr1zBN_FM3JgRF&rr@Q|4FOn&Z7GKJH#V)+NnN>h9k^J<#SZ4C>~1B8)B zmsm7>OxChP)MZ~Y+VlkH^V*L`bXVqWOs+T&14%1Uu5@+P3mbX5U~OllJJlN)DE@C{ zqx2;qAs7agbgr!^e6LtL(3^eix4qVLd;`9qn@{F?y7OAI%J;P|SdU$vL@zgRVgXMe z0(<>VV{D|5RlvQwv)>7p)e)20_?k|gbfZgj6>|~GH7j7mH+Qv&;?(IUw5pje-pxhs z@o<0Nmi^{{;vilD%Pc|lw4~MT_cmm^`?T3zXNl7q3v|!ZE2D|?UT!9Fs5&&WP-8$2 zT!o~A2<&b8#3JC2PsQU7^7QPVNnV?fI&+y2MvUFTJnp56cmMElLj@dQbW1zazqB#y zxUiw(-ZG59j#w7_my?fl;kxnm&RrQB8$mce3l+pvvPron;P^yK-mvvraU+{pFC#j! ztWvRE(Hpu?sJo~wPBnA-t)?6fmdP%O5A40+9nzBUGlTxzaHbc88z+AMEDORyxx7%kJB*$1?sTn^k&(JTio4 zyfzv@F!${ytz9t1plogO){)})Tcg17tIn7QzEiQ4I!4GD?M((o*N|uUz45r1IWh~q z`$HtK5g;M6AuP9h%99Bx8(w9xUNH%pOngo34=)uS_HMVe(y9k8AW-M$v?*?DOA5YN zG^DVvd3U*VC282iu?IXy2xHF6fTh>jCNnCf)dyj9KtK7N+bP2-U!Hh&3aI+pQ=ER- z3!_4}(*5$%-d!MYU~DfC^1QC#Vn0-;vpgy9`3aQDFYhvPiFlyKxeOV`DrdRw;MM~M z2N;j^ehsQ#ZN^$qDR8n3cTW>@S(6a*E291(vg`rF>uWu!nH?(XzveY%@(oYk>>ddo zt(1F9nswv(b3`7DQ!+CfGOf>EVd$<$pli0;6ENuNjA+8(`m4Z1AfI&P+YLGcSVs=~*`efbCc(YZo z(p}>*{b3&{LMCBzchwV*oXZPMf!|ZN0!#RY%r5lVT#J+IymCG&KTOvhH*AJLzlu4g z%5O4V?uI}9HF2&unelo6WVXORQ~>TM!heC2S0f*?v78&d(^K#yUghiJE~Mb`4UAZ{ zn%0o1xF9qF#RiuD&bK5Aj(_S^XcD+%gr#lbwTyiUn{I*KW_%!8)>hkKkoe~J%A7xk z7=b7nvlrEG!2O7?#DRC|BmED<11$2ZnqK9Y3nBomtwDdzg3wu^$XL))A!Joj2GEk~ zyh^lVOCSjeYpj63%u(5ybfZ7=)o{9B^K?@v?G8@nXFvULDWes>IALc{YViE~qc_^D zCw1D-W_Al7gSWa8wiM2s(8)l?1@)v6_4{`H1@%!HQ-Trn&oSzRe-8(M_?O}xwE2<| z)C$Se39cCWb3jV=v!W8o+C#Ex0VgNul-2DFK2;QNLfT_!kTGC-t&+6(>M_Ag!f&%} z2uOE*d5oS$mVHCGKiAn3KT+>WT}d^dm?pmS?!$ilDK*^YQz8|VHlQ*D8j$TDK)&|D zQxh}s9p;B;WUu0Wyp>g&`}F;_*1YJI!m{w&yblA|CLVxjijdg*Y2N}mE5*`%#Vz55 zL^gFYpTHv%8zc9}J3o2H_OLgI1>@`hj*Ftn%~CF$zWOT1)h0B;=N7_&c_TMfC#(GB z9yi!pAdDO#h~zXU$SW>Ay?th;?tNvAK|2DBpVE>qilY>Dx{r)U6+Uc%scwe8E1_0}%C|@CsJllj(_kX!2`ih;7dv{t;PL zo_5GG)3H0qTl6>ytPdgyO`lJhFTShrvs7e6_Lpn%DnXyvd+0BMfAtiAlyjfn)z$S9 z7uWTc+fxJjdH3srr*$6Fj#MFtX%>`CCUUb+s9cCskWXfyus=cJJR>014Jh@2_P*ZZ ze@f7xgN|r}oTx7LrW%>8xozjq8%qAn#31JmfibY^C%banEqYkPBGE~%3V0%RG78+c zaDG6vsNScpCWV3tV`O}L1bOdaqIJ0-JHbNkQto{%=I1yy+ejc}lb_aWQWzH$q3hi~dkSMiK$go=&xo;aTOstXv1p(+ zXNl;IUa4WJ!%jAB6Gx_DBZ`khtB02mE_sah&3vD(TaI)ML@g$C;A}J+8OrlVh$i8c zxV)`cRI^lGh29WSi_#Yu(5%VW=lA{EtQ2O5C2I@_>!c}P*(Ml2q>h}EHu=a+-udd3 z^A?A|feUO_iM*EF6oSL`_kjzxR)P$|K(Iqzycb19yUKa*o#eOt(px|uooL|rN-V!=`+5yl9fX{4Nv6B zN!8}ki)f&5pTr^x;!bPJJJ}hgToHe?+FAGdGN`*l_n~4GQV{a$k`HY3ur&^n6PLjPso{`Hr8 zu=Q<&;rdR%7xekr@T;vMvmSxVnhPhi$EDjeK@DdX-o zW{1cZB=vrNZ;eRj_I4l3Z0Ip8!`dOcq#8X^WGu0&!Cx@ym$Q(W%F$GbNw!Ua-sJ7B zsRYyVM=SVQr}(*6J34Eu!h=MqcizmqmY&zizdnS{!ObCad}% zPL|1eU&uC*St&Br(BS^V)&?2c-T9{lB1})JPr)6=I$O!B3LRK|AiReG2w@Y`6vr$n}_l~clWUolMG8l99y$q zw%;_;8+B``gu4dTPR$T4W(|#2v~G+w7MLkM_wT#*c1-PlHc4}oF2~YS=E#g?8_d-PZchGw~g=qPp3Z4FZ%z6 zCe*)%CJJ)p?35IO?Ck8)hYnBJt9m27D74h`b-qqy+boWu8b(3CH&yJeJ8d^#z3ci} z5?oCn1=*Se*=I-|$#iJXm+t(Hg(lUF6 z8ZOaebD927c~7TdOt#X;M2)vGu7R@aChrYsq3>@m4L%Qd=Rb6W%HR?-yem7Q3#_3F zq`vsRS5u0mGN?zMEcQRVo=v$lj@>;mJKkRDbDK`I2yVx>ZZreI&rS|;V1Q<(R)^5S z#ZS|woAH@=Bc)`^d5W{h5*#34g>XS~eTlJx-QK%LZnl(fh+bz~z-JonJq%`T#}zD6 z;C}Lf(@>y%Izvf^*-4Q?NbfO4zl*N|om1ZL%m>Goh(d3-pMrl|6AbNRqNJnyeKX5f z?C0NTES=3cetdyRtXvQa(i0n;T_#rH&ZA4nQPX4$=^=e}#=Fl}^%lR$gGUc1U^=dVbcy@Lk{vLvOH!{oB+5%?x{G{GQDmdyY}|N zas4J>+5T@Vz*9sCud`mI-{ufAMkpqQiZm|TKaIZ)WEq<0?Dm}CtKHJG>h{5& zW;8x5r0xHhcQ&-5Ajfw@Fo2mC+hmMfGb1cLqfwV234doEW6 z{2bg3zsE0U`z%1~hb=8w z5oM`119f?tBd!I#Zp05Uo2WX|5eO+;lagWc8@B4}Dez`Bh6t-&DA+yw9}X-N107x1 z=PEPZ2ZTAlQ#;`H+{BG*uwM3Aazb~w{Ux2k=IbY~_Al<1IIrZ&r(%9GLzL_e8qrJZ zzXS~k?(!Z<7kLvoVzwl+QfNC|S5e)^*|&k`QZtPGDtxaTE76a>PXCm)E_}UyQq-Dk&9FH*3$}88cv1eli+sUTE#u zQKRb3H$Bqv3(S6AvK9qyMj#<8>R*ODlH<4OBwWUDP>v6v2J!}|caj$D)z;Y1alN!y zUx^2ml(A=okqoRFx=`;Ny+XIGO<+;)a;y+_g&t=EeEynH{ufF@w`nqGE~)LhTV#|hq83~5@W4_#m18E^#%8seeO8FHYr z<3>A2gm$I99zjiyOM6&eKfJDxJNlGLy1TkK;moMg>rT0*$>>O(%Erh}%)3&LDa6#@X zmuGbu&5We{0W&R&GCE1{ID{E}Hc}GI4kF)6{f#A~H~1v`>9KJI;mH#+y%EOgmq%YIp(` zlP0sPd4A73E%YPy;MOr35L+#xoGr2V$R^cf`#nFD`%LHC3-qN}_rn=H5VFHCv!1NCAybb z8tecij9pG+w8H)?ScvSe(r3G3AG83)syI1KLKlAILEFB_MxQe=-;UMzWD>a~AtEAl z!@HX?TNizk!$0b-1c&%kM)X5NIi%Z%TbER7GY7Tmnqo*o?>W9G? z*=xfqX{SSKfs%LEjj8X`(Ca4wiKOtd1ZQh6jMxqh2G+WU$*#Rre87kNXwW|JF!jP| zAGlKj>TYWgTRy{FzxGg+)0XM2zQQDt}!;gX|v_$Ea@`Z5>)!1VuR=!g_%xLTtu z{&qK_(U1e-1KUHvQ_0E~WX8AoDl^oYUJDfow+oW!)*2z>c26p?S8rurzU5GiWQ0I(; z0DDmD)?(+dQVgr*857>}-wh|a9<`7KxP>?t5ARjI=wGDrz7a$)VT^i^r}IelL(pnP zfN$AE-_SFSvbXdc-r=7m_t-ZJ)S4zo&-%I8uc2*|-RNg2^2N`|?isE&lN;=-3{>Sa zz8oORdbY?vL-6&jSUyEsNQ3djUAC;~WX1tU@-|zZ){h+Qo0#$}NB5bysK32_taOIv zTwd4nmiA(B1Jws3t6=7JA+at>-TFzWg^w?y<-_u7e5Z4=Nv>R3@(z&mOYqd2@r@R{ z!S~ZYl5*yCS-q7S$j*fK<+svpY1g--{KT2~6m>r8WCbufP1}xUPk!Taj)ra;17_J` z%J;ezTy}5hG2GhhRw)cUV^JFxiFGx3eM)VhYB}hQO2AG&B#$^~2DVH6Cl;SH4WS*ls`QMNrRvyh*0JL8=zy`Dh_TzFot>w8`XXvnD^ zoWToU(E+klG|_q(t=dy$VN6Lm+?erC5~wW6^&xS}x=#aJrB6)I#kT+%hx=RR{G&Og z4Ni@DfJ;DaP%HP#lk2(+ulqrJCV9fEAz&m!!^hRthy^r844~<91KM$9Xy-58_Cxf* zG1P+%!B(62%tZMFOTAjI5g!ssc(?J|mQD&zv6Bm|JZRv03bczvmH3g}bC#F2 z5m#tP^27`1U8s^LfHf5Q11AG}<`H=49FRi4?i`&y(faFCU@g)HI+Wq70D!yu#nOHKm_J`Ah zQ^q$}^da*P$y7LeD*PQN?pSE1L_+;tEcqwj84Mz}Lr_TyN%sPi72m7PN1Jw!t>ITE zd&qY~5OJdu)Ai=x=)Ljw@6|gL+2Dl`Mt!aG4!DP&A>t%;RWIypI#TjItJT`@yh~q~D(={O^4`{{`}u zErS8R{`rp#Va3z_d!=x0i}V*JTek%9D$x~}ync8Wq&?d-hyIygN3yaHzasJZHYDU$ zi(mTOu`zWHTb@X+?XgxLUE;bAYk|{kMOjVDwu2<~woFEFi4_Do6my~&^_^m~S<5qO zAdV%yS6(`uU)7k6USsdqT(ZU+Xd z53Ot_i)`cm0j>FC>#0nO4`ZYX#CP9jIyBh)WKoN^Y}W2v6&7c9g?vU>^3C2GwDpW( z0lzQkxJx{`L{47o6OdJ>NO})#tlaE!+|jjwx;QhPv9g$by?uXxZE4f>^-0=;QK-*c zy3q!52?O`WE2LkPP1UXKS>?4`KSTGheycX38s<`TON*0bFG)D@OvQd@o=4Kjef!M; zsWKrMKDVg0ujp+3jAu!rP~1O^6DR9>3}sAS#^cSHF@v@Z(stkDIgk79W!3la$Y>b+ z?%&lz`KfbIHXAWlS6B2u*HMriNc)_%&xm9CL_NA|Iree^o%HC$!VBSY0E!mv~D@CL34o+1MFM*|gknwxTF~I#>D?6P&=byqHmt%FEsJ510l47%E*Opk!oYpw7~JP7|O>CGb3bt82`tfpwu zaFUb{`B#|1s29+}5Wr2@^12cV96%Rkl5Hjo>CkxL<)ll9klB_=(#o*dr3hCZbY;}{!R2->rwL=%&n zL1qM0+Fcr);#mD--y()!^(fm64-&MmpKVPTiIL6AUk4?!Z$?K>zrDvc;#E(<1h3AH zb)ii=AdREzeL<@4alGD{qt5?a5h7iQ^vZx^Wo=Ckpr>cZN#(8e!ZMlArwaMAlwh1o z?NlLC*w-#>>c;8K7Kt05RukNUVU{J6I%96F=auukUK^ULHM0rPFViil`n-;k!QExM z9o}!9oY@V0H*heIo+1tx>Z*M2)RQm@gS8)6eOe!J(?C2*c?xQ4ty#TL#MD_E!UO$V zcnEP!zSH?`uJv$ysmC|3U`~9Kal4Iq_u zy#Fw#<>_q!{65+v@06GtH}tn^pV!aX-n`z}P5}DG3l0cxq<6L_vTUOgTAI{{sQjpA zQJ9swb>xb0%aYC~WUM}#3-7d#*=S~x-cb4AHOOMa7pqcV%K8&`q6Lu5kLQ;Eu%Rzq z73h3;DX;_OO@Q2Ga%jVYg%vl4a0#jE?qD&mWEABaiw?#|sj4{qCyE5>GRhJ$lp-EN z)IzOiXZd8aiI}r0bLWtlS)alVdAO8NKsiaCU&as(${8HdDWqw{97XndJz>BOwBtE> z>w#plqwK63$G4I}N=%!Sku#FuD#jU^2R0kbQuZxW+gmqr(pX8vW4Q=A_CL)5#jK#6CPU5>}3BY z=N|=gVAeg&ed%$}F8tP~k+=CqPQi&qCC3`Le(s9oX^J#wah^>}6sqv5e+#jJHmRto z^&U1dNPOO}h#W;iI}g@G4D#^MZ(Z=`qLW(>qU*-|+YP!l4x;rvaMJ|tiOFpFKRZbv zl~dVmJbbbJNw^!*I2X~zHe~@lA=rA#avJmWONRM(Ohd3h5~4%`nqIq_1*Z+_opafG zKKWDZ!rPUk&KX|>M>n_jZuUgv&i{|H?|_E$-QFb$k`SVI5?#~~Wz>iudZKp`jOZ=; zAPAyI2}Vt#MH^xC-s>>Ydmkq1=)K%8=hx0T_y1q(-nC|7EHl1&zy0q0ywBeI*?w6^ zD0OO&Bz!eDT>ktmwTyi2pt_Vf^-R7CYp2kCs2A=H@&1K~*ha_@Cylft*I;qykFpoq z0$Aq1g6c1~-t|I$#zs5ZF}D>H^9?XYA=A$9R6YOc`An*KDyg-@;*k{po1K+_{0QpR z$EiBRQYX6GeSB{7;Fj+xqBmD_v%Hq)R1flBr2~C%yQav_5x1IpE)i{pR=oIU$=|X(3;g3jV3~2Hcjf;#-ATt1U?#mvqQ2sEr~GZm2dSKu<$#MuOH#R zUGiR>ntnQ(2z?nUfcF1vw3PDP!CtlA2ptiX*zbG;q}43@8(9R(%3erT29=mvD_Hx!{CBy9-#Q%D zL)nEyH7j)NgYbKN+;i;#6Y1Qv6wOuY?<|KZTNC|~d+%8q>+num?{1zg8lQczfBiiE zoci3=yHt5f)6e2LoTA=4o0yMxwxty1c~o@zi8yNbWDm|`q|=bq)K()^vW<8svcXa( zjlp3A>OYC1Dds0%qA1?%93JuzeB{;p@t%UmV5WP2CU8h^&q+UbbhbOCCC4$e{Y$qh z7aLp1_wV2FGeoFhMGVkcn0GOgTrr?u0t^QEV$C4uT^8%&;U6c|cirY~ zBuGRO)8`LZ57HR5DSsSSbdIEXh!hGpJ(F}*q+KE2AEnBm10~&4aNXsdk82s8x9m2) zqWa;Cida1GHG6DG$QF+#SKYVD+n?L%)Fa3_4nHb$*YL+}+Ly!=nBj0!mo`a#9Gz&!1~7j622I#1hHjr!jCOd& z(>-+5aw;+dE+!nktQR=I#dGQ@HBb68{NkZV5#}9X{H}xqxlgHG_D8J8>OY8&_wV{i zW(1{6L|^mAa$ZM#bK8G0s}f7w?oeeqDEpsq(t$`(QPIC7Zkqb&gX!cu(YSSO-*C(V zP`sFV2U+l`pau{>N^ZP?yhE)3lnQ1CZiYKKcK!p z88$54SLriu_LJQ(O!D(H#NM2R>P8Q~ZJDykk6WP7#8QZ0LUi=PNvQfydzd)0znHwu z1z#kQ0V1mb?DA8m`D&6m*@3Y=#5_+FO4W7-mHciY{Pc>@WMd{3^GL6bf3%gFz|Y)zi=KU!CSPmMBV|DV{m zG56YEFWDo==QlOedO;YRY0fycK-Ojrs?Hu`$q&6>fnbkE>Nl_DPEPjYxKQq5)RSu2 zAb8p402MvQ_mj^82VXY_Tb>Eyo2>J>I5~>#!bYm+OXcZB*%cN}k}JKJA=UhY$b|>^ ziApz5vj%NdHnuuE@W)>+uI;|#LPxjI$(`>8eXntT*k`^a3KEZZ-Q=spNU0^Zr2nK5 z;@rYLHAL^Xd>xCVo=$VpWnR@F;y+q@RCINr5bpT%k;|pgg(hbQ|0@`hee;)V7V_bL z!C5AXh~P%wbCX%rOao$L_kpIQDY&CNQBR3`-rc}YgDDTucv6#b95_fB!N`*SqElW! z@_nB%-w*HU+X9W7$`!{$0L7sMA!#Hg_5>Y04%U2B^d7UM{-!MgB#}Iy1u|#ZIr719p`0V?b7x}Oi~2)UH3iJe}O7o3_;=xrWw*O^$*|uFuU#- zdTbuwRbmdDw%0(3`OD%Y&fJOB@m$n;g-o*e7;Q0__V9~}fFvcG9_bgR|5qoAi!#6= zMlwj!6pnhY#P1XGH|g4%bTbT;#ds5MxrFT=k?HtXq}10&efPT33zCjX(P2GG<(u68 z#j(Dm`uZimOk;FLj(m{}g<3~v-1dtia=MkDuSf%A{HXTF_B4=H-5ckiCPuN=ugQ{- zi?^?Pcr=k#PMus2K7M)Hw+3_$4nF%dIxxuG^#jDqymq@3suNfw?^O7kgwt!{3t*O( zRA12brLIA-gnYRlC|mm&U1hvE<+kelATi7IkX6N+`80G*`M=9zpF4p3xn>gmKL*EC zS)A;4>5G<7T6VLEi-*>KYk0aPeE05N4^k1`-spy4oDFD7c#%tKGc(`imxW)Rf@F;i4zFqvA_ngURc@ z2a?07-@}PLX&y=+;e+|aO{i4r9^rEF)XubRQ!neg@YDJXm?buzuo-T+=c-nxCo?AP zv~9|%HLcHM9Wm!c<^Oe2$1 zx_BukB%=dnz0;61?st;XB2(zqI7)xZ(}z@}n4UDc(qe2TKub7aEm{U~?WpNaP!uxC zl>i>zIxsyDPQOX8;LXQuQrzz`TktAxx1pS-9{N3mI2pEgl?G<1N2{!QNcSk;3);C` z9Y0vQb>cMV&td-I|A)8YoMXF|2r4OYG)tWWCV&0}X5-R&F%ZX+bo`NP&x(2IGOhpr zm^lAV5OKi_G=81t2mUkN`mfddIFsP8_1>^Wjcv@iOf^=$3PDeLwnvK9m!S_1J7Q`n~3Fot5l7O1afsy34 zcdaN?pp~b&w_B0?S*EzC5!OV!zR=af^@Ka^U45xvdhI>8Q?tmhaD3)gV_!*sx>|l= z^EvvPO8Q_?|IM=FA8%jaKf>`^UL%!H-*znJlw+MknRYIyp5oriCn1k)Dhd7}uyXtG z1$t*Oeu8tM8O^wFyJbZ+EleU(^F6a8gj_)*?$lLBR#<8_g8H17Jgqd|_kvRDYRSW> zPoC69;xf%JCj()`DC^SucuWe7{5IEia*<81d5R6$QxcR&t?wNRdQ3MV5!N{XE%I%o z54x^T0{OGVy1XL~B5>T@`HoR+f{AFMzzN9CQnx$!WecP;k<|M1)D!t+@_Un)T~ap+ zbvkTBC5K)YKdboCa8W9L-N~T;p9bk*=B|ct2zESI4@X*~99L@|0XgKwchKze)2$tQ z$@b+R4$C!y5Nll?e;n89+}Hho6~>whGavOYK(Oxh+N zheauL5#`Ff7i2?*OGxC3j5$hKnLF%iK6fxx8=<+nXIOdF8-s6>iwrt`*)onr_9-JH zsxD6)x9epPUdA>kJFoD+oJaT8gMTIQDK{6m>k^|lMNVgX4+jnX$fAy;piq$Puwq{m?r{Cw1gGQwT{&}Uik zsS^zTU~?auX)B^H+Qlx<>(B-+jnl7CI?ir3 z)f)O!O5mzU=yXEF=tGC2biFn|7o*Huhlf?b-m8Swss>@sEhmP_`3?c`(|!AS#MPl2ZPFC?qB)okzoEIvr}{&*cl0A6`N zSAUA`2x1=J;AR@129`{4VUTtk!+Pz@;e(?|r}IpRcWW?t)8AH!zx!Xna@#jCg)C}O8o zu|tnKKE;r(a3wJ>BBd3@_NlAbFIyPz3~J>syfcsaV`P^L>Hhn)j=yRF;Ce-R++(!9 ze-*gL_QfS698}3V;AWAsu~XJ(ZLjo%+Q#jUXVUc;$;UL;LEV22cJakzhU#YT{W5hv zScaoFE#{UFIq4T7a*SLv&V{3wmMrC_1EvrNd~sohH%h4oY&jwcS*&}jqkg9j0Pv0;I3_nP0m!$It59l%le(W97x|FN;n_7 z6`tl0;f>c|${-h7xABU(mOyA=Q~w9ro`L%C=9+YLw$2(y?+A7ORDEG%2b2HryHh8j zZ%s`V^o`TX4cmvt5Dh`(7TT;?|1aq~^7$_ZM)JJ}RGmSgxq>ToTATkjy=1R$b9CHw z_zRm5G_XFFFh^wd*cL@wB%XK^6;FIj%cXOrR?z#bx9Owgq17tVpr!KWo$TDseRLTm z_5Lf8!<3Ou98ybh_q>7Cs^n^>=$RQ&9TiAKzZ*l2xxV(FlAO*z^okNVH4|+{ZC*C{ z$pRDW@8IL-`CW#Ll+1tn{mWbx{Q|B0+=aj3#7qKAuKQkdMrmr!{8gAOwCsb4dS>~~KT+9-0A}#0Z>rG;nDxx=SrJ89fk!F_&1}%Zie2A9QdsgLr z>Vr#SHTttO9iI%V_Ack7S5=&uAB6h!d>)0nyjp_@{!b|bvQ+iHdE~Xb)?$=4?c~+C zk~e##Iq+htKB9$q-IT>ily)UU-%5vEXCm11lao4R-_ zo6!YW?(r}h-=Aj2`KT`NG=rU*r1n#yOyfzCe% zc+GxBHlhhtm+>#y)_qDhItjG3%2e10y`8R<)GpLv=I6itzQN~s=NvN)@_v#C{P+n9 z4FiTO4-S(5(Br1OHUFP?j4UoLE?LNSOdEk%@ki>gu!!EjZWf2WDVb5VU~xc^I5!tZeemF(MNEnOwh z%>m2mDr-Olx-73d%Ek70T~K?err(-U3In0kJl+&Va|Y#bE;pXWJIiI#EuRE)*-MMb zOvAJ8cwQK)Nt##`hG$Js`5d_^w^>1}wkHcEvPefe9acsrhMTyKJ82lavwm&xrCsLe z-jw&POL~Py@F{fZCJpY6Dm(JIOz+tte&wW68!ut8Gcl&LUNfZZ5iuzJ3oxKo%}Vul zcXxr4F-cI%Qx_KjEQOd(3LwMQg{Q90H#0k%ubIbdVq%h=lYVtg)fL?l3x)Q~HTb+x zQsO2k3l0um-rkOmiQ&srOK0KcPW$z156c1!egmHzxDX3UNC583)!cl>Uxm{(WDy~=4= z1DU-Rfs98#dUNUdw%id}%`4!%@Ylxwc%NK5rM&zJ;3BY{JUsXaQdwD9e`}R^cy!qb zFR!kKOxodc5Hx}U?Fge6Qk$BjA3pr*>E#6!Nh+zk2{ z&0F%fS1}R+*oMI@1@j6M)z4lx!I@731207L-ln!tQ=%bzd-R7BcG)@E=2dC*Z^S8- zjj&IWu?!^?mh5ho?{vMe>6xz4&hBfMdk58fx}L#GU_G4_JDR$yk1iCgjmNu^k-0@~ zO>eVvm!(-Kx=jK90qPwK2iFn5Vq)1XqgPdeH$(cqzhU1~fAzP>E{bC5d$vybS<0kc z=k#>whYy|tf`W=KKH@cl;lO7G^hj@o1eui!SoTuTLX=fi zYhFVXTdELMm|o zW>|%ywvzi$9mdc>p|tiD(&W;82l*LHOh7UT1t*cqKsVOg*`Sneiy=*{b><^(ph39e2t~EI0w}lNg4Dm%Mt$C8OAKu;_o321QE0 z70Uz#1wE#UM4>F=)6x)wS*5`N{0d*V1>hhr#l$@7mkg z+-=6u9uLQzf8V;0+VYx(bw$gpLPWG`Db?H&Fckp-HH?1wk|D5kU^p;GAu27+4p=<= z=`;%6-Qwy6LvL>yEKbfmq)GXs^jQaBR{^>fi>>H|nT1qySgYfo1f9sh-+Z-Jh};!1 z&~kX8)$&)@BMO&us*_ZdePU&GRo>lQcx}zPy3Xf52}yWpsDfEHx1eA=0->Uzskw7- zAjW<|L2tb1h&K<*UNQuOaREUdtzv_yq9SgaahNQyYs1Lrxhc5J%oc-ve0-gWHZ#U*-X9LPaeli^*fF}e*NP*oPGwXMTaVl8<+hKHXt>h9`=b*FqhchZhc(qd> zV47)t>Hf?H#TM$6k8(WK(pqcX(O2A(r#GwE+~mdr7G(GMn6Johb$dG?FK-;DrRu|n zlh&6hLFPOPA9>i(?=-_BaOT4+#dxM@DykP!>*{>Wc6fMs2}MOtaDjB>Gc`3rFq{@x z$M9Kk!0R?QKR|$8&35iRc=)ifeF6BGY=B({kIvE^*SxLMOzoG~(D)Yk*WxlURVAki zFI4U}vzeGk1t>lI{FZF?mpr4w-*yZj*wzADp!F?HCo9^Y!oJ6A+&Bs!O;KE1>4C|3 z6XXb(2Iaj*Y)?RZ{AVCV4A^hTm#9 za<#=kx`SZ;8_iWzK&MF+oA;@CyWj5Z43RU@KTYiV%YGpobi)#;;KEAo2V()w@6Me& z9sT|HvIh02Abkjg#pPK=@CGQ*F(5!jD_^5{=M=apSl_bxGD)TS`ul-DE#`;lBrxlF zlecmET5J>CVLsqQ#DcQ)llQMpMk5Pn1@-p5MwV9G|qS6g)=HEc~%IYWPnQ zp-`_u_dFO3Twh<`-QUkDBoqwDio3SDP()O;yXVOTIYOaObeiJg-%{tXwCM1g4yJym ztXoqRbqrQ54ps1-aXA8g(MXtE-H!bDc*$#b;qyc_@Js@bkiNWct)|1&H=eCuB@@Zu z#78_ZzS6DRt+rGvLM5p$CqBp>l_>CZg zXbMW8D{}c5@U+ndj!(^2gcNqRE)uh%H*VgYP6vdk(p_NyRs?cB<<|NPglyTH4prO`#xM=%3U;NYO#wbe2Dcw|=!h~wmq{sm`$5k*+PIT4!K9_T4v ziAX(XD~EsI;Um-mhUY%(c$+rP%=--z7uOHd4By9A@3z^WZf1@`JF`fBiF#3NFcv8$ z8?u#7>y|DwbU-M_6S|a*_m@p-5=y9Myad>Bc`VL*ac`|MT8;Bvn}-%&%4cqp+!f`o z<5JC3&KdWa=Z9N9f$h?szD6xe{M-}m8&~=ARjKliYPN3sUSg6$jhsgSgb3Ci2SSl3 zfPUxw=l#?~9|6%yyC9A5eNIjeIW5Gs$nXh^u14J}g`NIEoe^RwS1q<6E}}-z5nulL z)F}W(w8!aq6e4s)gW&&q;^I=)GceHjWt}F?0Yn2h^+`Kkg2ojTimZ|&7`|mhzac(V zpJBq4ztdP)4FhEefFxBWseAr>Z{zak$Kb7+?VU7!&-E$=!ZO!0P+W21N z;lEf4tL_9=yGX^Z9=^1@9+l`C>XM(l7mOSR3CH-%1&7(Mk0yU+woE0+#236gq&Z4N zT+aJ*jJmLO*>}|cGRoxi2l9qBhMNuXeJoW76Gg|Vyn}561cI+ zqT5#Mjg3K7-XTu4$x!yeD2CN*8cCxIIztI*m38ETMxT9>V0=b*qQg0fcf zv+4Y1Z}-}~D?fX3uI#+k(MS0cS|GnCaV9AQC2wMU*s-lX>W+N8TzvgQE|WswNvl7wIdwW~{E^Iq7vHlV zo_h)(_Hy(zha5NhE}q#HGmLN?eMz+G>@oJDC zWAb!)&L2x3(Xgr2;Jj%#$)?o`hrx->^XpM$1uj zwz|G-1$>#>fsxI_UydzBwZReoZ3FckewP5BvZNOt|##G(Q zXD#=Nsx1E11XHq=!h75(tFoFpvGsCioa;%g6+Uv)6wx;KzU3o4qSd~tuy8=pr0>)8 zy0Nst=`^QkYMNKpwAM4oGuT_dIZUBm{M4sXd*p`_-kv|p{1|gD-$jPDk)FJH&Bd@q z-de(y$wcylozHwXwgUq9$Ckod{Ruy1CMYZmnzV;B-+ww>s_fP9N?$^)*!)=+;Q@5& zy{dVkbLmWBzRJyY!(4&Wd_^knS@obPZBARzrAUG53f@i+*F15>4@pCO!{{l|P2*6R z%*b48R_QW7pU|$U15|LW|E^B_o6c#{NuSuueShDemI&tLy=e`G+X9~`;K4Ts@}y^Q zd=ek~g75b$7*RR(o%@nY=RUF6yeWg8Gp(vEccgDdXm2QTkvPGvFkq9CP|x63kcMhX zazxT$?w`q;i{$~whcx8cXK4>~70Jg39EH{a&<)_ZKM*Ezz){5D$%)PrPh2uupnLnb z<-J(F?FTxF2?Ocb)xGMfFj5<>*q@FvDOyiiZWK#ngy0hph~=%Pm^UC02>c@ttu!tJ zx8k>bgZphR9Sx>HG!521p<5LB;&lCu{7k9f41k6ib=x*Zo;qC((vXw;c!ZmLN0%Im7?SKc_f+ddFBSbTBIeOc;* zUbI~lU$X|BYkA&3h{2=U*hzZNylEvTAS=1TTiSYc=!wsnDp+bh@+tFcb+bN%83A;U zb$V%k_jXB#reM-bk5?YxZRx-U^C!wi>G|RgLYYraBf)Y82`2HjLSl>S-eT)o3rioc znFnBCL~qW_5zOpivod^ot7yI{;2Ls5MjpiVBm4SIbRL~m>v;T&ezoNscRmftZ&Nvx zVli75B<%e+&UkiHRA_Y#ZAiTS=6$%N7p&`v0gs8YS}GpDu3cLeIkJd+BKa%OZ4C|W z(oa0U7POAnFH=brwvN+KvJQMo`{il=YyDgK@81xMwh|NZ-VQ&zNvTC9G9&tt*1LK6 z6>&73%q#upL>z%GFB8iux^;fZ4-Y-DPGN&WS^5!}n6=AQuS~Bw54JVJV{~n`-4N7c z``9Z(r9Mu*X+8#!7Z8z9QHKTPn+55lBaW|J@TD)t4lj1H=2u!jTc<>yKbSuo)J_wc z9_=&gj3hhODC1T34d_i}MC>a~^S@a=Xk&pmBJoYIwTm3*_B zQ@Vz3=UMvH?Qa-bZUkAXSf@QZ+GRK^yN~B`Q+@AJu&KMm;40k*CLQnVv35t3Ozzbm zj|3+gn%ti=GfSk%*DAg1n?|%L)wrj%$bo^10kV?kOpArIQO}ty1gO<5Y#bcSUVmwN z;I{QOl;MCC7Ul_7wu7pKtn``Q;;3;Lfm~i)`Kd$V$E!BvS))|fnU2%wH7iyO`9L2ye?N)DIRfg zDdr7Nk9~isb<1BV!`Fnt?*xN`{;AS4U0+l6Wn1e=WkZepuTMe7nnwSy1{;NIx-cMp z75}R!;;r}MIk(@nB;D@3x>J{-t=Fj)W~JE5{{yx9HIdbLl%&<(*X!Oo8ueBGs~M!B zdP#^8pZ`Us57c?U6y)iWsO#rK%y_a)TWvPU2&ypSse-&E#?U&T>E0uxPkJXa7oh$% z>FDeF_dV)@XcHa_=7n5G{+l4J+3xHL{A1w zT#~)=i~FiqH;IFE=<+2Ymb*KX_y(IUg!wvIWg0A5Qm& zIJ`|CT!LoAhEQ+D{{qW;P>|fux3Tn2hm@*+v&;k!soPobd;VqHGuVCAo8jaRdMUdqaz&&~CXZ@NKO z?C82>8aQh#*S6Pli(mm3)C4z~)#utPYGhBA+VTo#ayi1k{qfk;*?d>|oJoc^iJ2n8 zYl%9N&-vaCN&C0K?@0?dqNGT>UG8{ALEEt_9JkE(ni4_v9F`G|Smfm71o!Tpu1l%z zs+pKRf7Hxwswl@EIU3b#`|%{HiLuEu@dXPc-PA=3n?3jMj z>T}S%-{+3pvTxtwV07gJpoF#a{=K*rMDL*1BRK(Rc1=yNr-YimJ~XKo-0J~e`3|iG z&o?Pc+1lE&16Sz-&OPYaU?=%ZKyaX`t$lAH9ctN^NYNeM#dr;NL?RNT#1H%D1idc5 zetn1$(t`Zko`2@;?R^3mZmX5_`J}UyYqGTQ9&UWzf8=gdw&&l?fJ<9w*G^E1#n_wrgiAu7%FczMEfu5Gm{Q?BgX!O!a&JIzO%Hr{1+ z<~%ht*=N_^S;-cM7`)4u)R1KB7k{na-o4zkDw0aM-=@ykHqz4^o3t0~arx0>{)`9) zT6~VxJAWc21<{JT{nBUCP_+J7EYTiO_G2`2QOB>H@^ro~^>nO4#A#CfijnV-6|^*K zx_E{$X@2;*VdfGp{!@P+APQvn$bQH&!$GRss^jypJv4s_UgNSGad(@$BvpPzCz_ z7m8zE`nZn30{3JX?!PL1eP+(|{Ci0edL3Sp(#?UD;E~o`Ix4a|U1z#dzn@ENMiO?$ zMq)Uwxl-F!hMSU$`USC+)CX(eqP$Ja>}~Fbs&WRAp>W05X3~N>Z}a!oR&0c+rz=@z zXNpU^N>vHXwKpI$5eIr7T1+qT&yB?WR=CCNu_=9bSQ_^lt@Ij&T5pIyut&)>dS4My zovt@_C_K-$5kq3{)r&zF`V#@W#^QX+*6YB&2=TOBIp8nlsq*9!x3u+R6CPD zv3hK@BEU{~Ls6xfkQljHtF9>#PyM`Xsw@XtNc*|HhFb6_r>-tFBm@_8*tRZJSWsZ? z;K2F){8k#Lbs6p{QphvkY7ZpnrrHjlJKXT>i<_=-#JZBYJKXoxfkf+b%To#l^|nRl z?>%;?pNP(j{ws6x3+C%Cp3;0f*!OI9JfUH$viSf!V9SJi26j8f)w1~gyy5mrH|viO>%4&gY0eVh z1z~ZyCv0f>6_LLq(8}R+S=pPEMoulaGV}*pxvo3?n+l`Dd&SlZdc*izukC+*brbPv7r)9PSMbggWhz7O&Bj|hq%Q^Y zeHN-3s^1FQ?7U}Z<9%~j(#%|7_}CuYCreA6*rm&!A4}c)=zH>$)*XJrUTe_Nn?|3_ zj%FQUo=Zk4zoXETaYu&EVO=)hjJ%jRFCG=-$3#iXDtUiplLy3qt7`DjR)5@wh%xmT zSBf)}j^Tk=RVI(2NSWWwO>tYsR`Z0rlchl5V4$w@ee$ZN->0Rl#|Y9IdfJr4z$BSg z;(pTJlQd*7Ew*T@ai}A8oWtxj+%?~mlQq8-S4A&x`zHBb-_-!Tp{6x8QpIeriLPr! z*SN=V&Y9k-;+->Ew-HIY&$p^D+_xb2`a}kHzS@xHe%QmJdnKYfTMpIqum1GbAvxfR zcs)k!{i@zA0luAm+N)>bIC5PGSZ!1Zpn|nH$?h_76{Rw@!+-5{nK?1#jDx2ZqUS3) zI6z*+5W@NDfq3`Rf)J?VL}-D)MD3Bs#Q{vWr%~L$A+Rfc;Y+lyzWcoC8t9rJ*W#*2 z-QQc9dhS;9ul-{uLl5yhx(Y@iAx)?bt@%*)#q_|KWz&MPht6&Qk{6tKsix&7kmT=8%#zceiU$p=`!@ojn_Aj6bUQie3RTBtTRZLpXTAooi z%Euo8J^zmSw>YF{v}VV2`pz9@x!lQ%DP@X_OP|-td+L5w#;lE)D!oIMNifo0eBWYQ$ycai~RbP z0H_Jy3v*m0U^40PReEN!QuzT+T6p2(IZh#3jBCOWVo9B>PdFNKQVFI4YoR)-+T~fQEGBd>ZEI~JQg;NhT#x3TJ@@=D{R1xXZuO4vM z4n%FHa&aOhL@qBciwr8_LP9v_2+GvTtXv$XrlzcIZI3nZ%!=5?Sh;%{UeJ8qObU1W zD-?6|+NOtuglv6hkGiicJT#&uLUANZt(ihIanWsn>++HkTV7m$78KT*E7m*ltM1w4 zfydr9b5k#mhlC7&b{0E`Q4@N&NhoF-m`l|!X_O_FfTp@6R+e*IhFgy&aIfUu<(Cz-X*eN~d8Y-y0q3$Q!XCRj%MZb&%UwQyJ56`z~V>6qpmq zLK5KNx7K%Yb<@#oyPxOD_;y<2k06)0I#1gv z#W-EnNw>aoZR{z}olJ8Xc~)@EcYQL`EM0RN7je?9++dfk)e#v?xnn9V7I63Vua3Iv zqb}973+vE@P7AQD?sLQ=KDekDJV+=Z~)sB5L;MuDe=o&gHp42Sd{*v)ykf zGWUqt=3VJAZ|O^#3jc;_9A1G1@~k=itQnIxNXf#j;;O;nR!p%tcb>!AD-JitW0i91 z6Dk2?Ya9{jX7?N&9UUAVUT$dQ%;<*-CaJJ3hgs!o^+LZSQf3mq9!Mipmmt+2V9n?u zV9J1oS%GJ*m|pd4PTDuN!*@q~dl|Tm&&b#+-&+a5>3ZL57G-ith~C~O-D&+~2nnj^ z_E0*Mf6dGYT7UMapdf9J{uX`^SR(_#XajZD!)#@f7ZE8-)Xl)#S-|y4!alHP)WpqO zFp`AbvbV?cwDvMKrmcVSRJZlZCNbGqdu2sMyi!h@P%*C=@t!HEAb4|wwF$bH`tSQ< zuJ@?NUPk5H)&bnJt*WtY{OSPQc$!F~GxLsBTEFUJp?W#aod-kRYZyP$%(}fBiH;J{ ze3^5}N!?7EqNnK!uBSweJ=eTfgn1(+E93KLpzE2G>&a)Qi&oC^hi_nK19+l)a0QK{ zkqXG=*zE{MKl8WvrVl~Fmlz=ok^{cd!3rF9DuHHGB?8?fqeRjv16$+qPrd-+NB$^$As#3p*_LtsBRZ&)( zW-S4vQs(-Bgh4XMb#CFEbk__?wY%Dr>r$&)$7hPE|{b3=ItpWC`jexqpbA zl4|%-J_~0Fs;_Q?d<_^UCw8_5r+QIYq41WEfF=s?+VvHWI|LOWaH|(ABrNe276PaK z>|BS*;1x^2la7sMU|+apYNSt&S3&i-w{t$yyUru=kG%RgMntb9XN(OOwuFK+{U6;M z2i?UQfL0{OD#q6feUemVA!$sR;NRtj79F<3ADs4?h$!l8tgY>))B9i$<$%=QgpXC; zN=<>iC9XIRQbPRZ%}bU)&JLRK2S@#BEs66M7+?hQsPa>-UDZF?0Wvwx;B!oqf1c5C ztO5h)`j2-W9_mI8w7$`fbV8Z_5W9OG8Kzc>`fWugTj-OYDjcU6^ zGA6^Mof_Hs{+}_Ki_;28XvR5zb~MtD-QTmX#A}VxDzd`Q!MJTJ6ObN zQ93}#)HCF`s4@O{q;;W;_N2W-*JWCB)?x$g)QN^IpHni(yRme2W@ac&W9HkY<}bOl zv1C1V9nT>VUNI8QIp?SSMJ-*|5q*t&q}!+Gf<_W^t^AgR6NwUC5!%Yt zu7i$VaOYWix01Od$$g<{$g(-)%@%!{)x~-5NU_zR=PALq*P=L`CgG(BA9#uq?CjXw z^@X=}uGxWfMqa+^2B??)GbV0algtvM&;(fWfDFzbxYM0oMmy_0`<*ZeGM02~oV`?K z6M+uEO0RCL^(929c=aSCJf{;tyY$~@$*`Y{OKJ^_Yqa12T+ra#Mm(nY9x^R^FkIhM zDGl*ZusPY2ZOt-A%f6Q&&cSNTHzmv}_rMbQnk_@dBtvX7$4art@5u$f-7h==bf)@|kd!wShwswVG! z`X~;5lc?`(tt6YT6@GT+{iZZI$sN~RL)+Cg;#hBg|Fn%~A*cw<~vlOe1ZU1K5q})e+QF&7oTtcuz&K1||UjBq}rJZ%lX?{V$>dEr_=2j*&nNn-i2H&+*FAV^PINHTrI`t~D zZ3*^hR)4>x-D>u#o)jf*8wrMElnD9!KS#N7Mv(V*O|)rreZ;jNoVDtnWS_5pIwF?6 zQuDKSVrt`=po!#K9rsUe4moN{8z|@Bpe?*i^X=Q@XKrp4@VPR$YcV@K%yT(z0872H zY(<2)$8L?_!de?xtAHWuNJVA-L?hvhazR6*yGr6Wo8DIe@e(7Y>YQI(oNmP1Riu9& z|AIwg4Pk`uN@!?wgNlac&E=WfQ!_DWeROuxO3C=m$ef|D>XDfljZeu|$k*G!FHGH4 zH>AgkP+LdX*xTX$I+yCczF9Id`q+^nj8O4w3x(O=5E|iXu z2L95u0q0E@*aILdLBlY?{SOhR9Yk|7_RUCXGC61X^dlv}emf&N10MnVoa^@!GP%iD z6W>%Gef|c64HUk8k|RhQve_<_@Au*Hu3cxOZ@{xP1S2KMMxY~yCR zpsrlOi1O6o_m>SMY5K2Sb%+~P^!q7%5ZQv7Vzzd6Z`McTt$LG{ z{YcFeZKUki5ZaE`xpgbj<4@Jqi9Ub+oKZA9C6;a{tnBKF|NH3)Zg7~bnYEjSkPX`? z)b*pC<+xp76O%UBC1(^{%1n`D{OnBFhdc?^E&f$(gUvE|ur}9kbePfnHgC0NK<=sr?|zhg zLwhZNW4+1@N(;0=3ZE$V4Gi-H`G2Ydmjwjukr5VOpSQYOcL9G&=Zbh{`X-&FqNW{g zA)sh(9?#AX7NF)^>4({FVKB#Ai-JgQp8GFZOL+jYki>?C#98O+E*uan2JF35FES;C zWjI&Jr^GRXS=IO77E|uk)8EnMNF$M3f2r^zXRw7p53vGWX*`?8pBaO3VHrg$;A%|b zbeUow#J)JmhR@BJV0JsQ1$8S{JaYu&0sh`fu7ETB)H0`@gXQD9)wp+o+3*)E&j5!r zYM3$v1%)b$0W8nIyp>9!psn#1NM((iBEkorTK4Hd86`^YJ5c`Xz4Ty#w6ScmsDy2l zl|SYDSAin=nq5cp1FiA0n%YEDA-ZR_8}AAf6xJ{smTr!G!(;W`^>!u@!xT=k`M|ij zv0}g2mHZ+MWB@w6n9fSP6L|FMD5tS8LyvovluC7xE4Dk653~V91y*GS9FF@)M1dAn z;j}Rv?AF52OD6+ZsxK66vM$pPw_qES`Rd6g@CLwvB&7Y5_5p(s7$?ybiH)IQovsI0 zzS}2hS~JsmuyFyR$Sto#oh^o-)Ja1`XgXW(Jx^@D9YTB01y}yj5|$lLmH7L=JuaD? z7tdGnobYd(Ldm6Hj%PjQt1T-4EpVr$F!t>aJwU{l|I-JQmKHv;8kj*Q@l)v7LSL}d zzpGSXlLZ#EhcoPXPDxqmh9;E_7XunP;cLo2`HNqv!!72}K5{Sr_6}(k zbAQIf@6@vKd=^6zC0~PzQ%-(t-pT8GSzM^=JQXuOs6XG^pS0cg@Tlqbz`fo1>%&{~ zden<3SM>g6v;f)-aLP3kfrgLuw@xcktzqh)RJ0N<=;XX4zXhiLK1kFz-XSS!=DCB@ zW5NsSqA+?+qQqwF+e#OC=NT+PG>Jva)D&~)+0*Z7%K5kypL-36iFwGyygi> zzz;I7mq#QVDFVXw799Q!HwpJNI-j4EA>)-FJQ-Kgz_Y~Fe2^f>%4vQiRePkd?x5<7 zJUo1W#QxZ|Oh8D8t7LTqbxCJ8d{C~r5gzuXR1d+PA;(1Qh&zb{sM|v23LI4*J|I^o z_0X+9WfTXk_^Dmg%h5@(6eh^posuk=eB*0TiG=A&m1I&6vuyiW9jJ`L)F8G0jI3S) zD+?6f>xgxY`I296F1MkUV(^z&2cRtA(s8OJGo5u4=KRjLxJ~LkL+ej=cKFAQT<`f` zZkU2Lir^FVUV@Al3wWSYRQ%~gmz2DmT!$zuG0RGoQu@@8^0-88*M?1@zASL8(d0I(pDbUi;7jEROW*8{P-VJ(kKjPuR%ZV= zV=pfMxlO#=`ufyD5j%Nc0S|g$i{k|qKIvzyk|}|tzQLiPCDt*hP``5oMUa~H7I6q66TF(h9l6;*?I(xO@dLkUHT(4Kga$;4z7OBNt;>7%bf|W| z3`y>$;Z@3&;3yE@fa7aQ>VBBByUlDIYm8V99DtG0qHh}29}p-N3!+8190j3~BB_Xn z=mG$pS0%xEr^7}Pdg;J77I$`jh(vh#dNtN0X=vMQuLR;K-1M||xp(hg23?)qD{4^GL>ZQL@czdKYG_31-^85LH>X7J^sua!)EKQ7&F(wStc+X|9S ze|SrMK+v+Bx)62GsR#QMiN4EN@DJJ3YtsGUmdNWm)~ad8ru2=HCWiMVzFW3*UZ_~C z@~SG=S+{X#OvABD3l62z(WF(9Qw7~drU{UwoK;10JTD}nlYpmnFWl$SwMT_Km!!nG z?T|G|7Z0dOUlIv9j$d+wms#zGc8%{0ok{VEo<99N{a1YBVZtDwg5&IIGG?_@PZhep zn&2#^f#|igw0_Pu3@UfJgqbkaM*6~9l!F9f6S#=ApZAt-JXF17JNQl0*X8~~QGB^( zE#kvt#UOzVmY}#LqrjIy%mp|d+GIVn0qIVJO{re}12dJeIamc5cCQ*0kkPX`+7wnN z6xdKq;`1+k&1WesCzdK;S-@w8NNlhJalCjyCiA_fCg-UbK1sJl@$?ko1DdF_TdiNp zMWL)O9+X@1og3lY`2gSofPr0#}PTaQ^qR@Pp*kzHJGiVg#hscE=A?!V|axa}m- z(CyHIWJuA*{X(|g3EO$}>m-Z%i5T2nPQ#CWzPMN=YwNkbIC)T>B8xn3S#}#wiF$i8 zGJAbGP&6>(3i-Ch^~G5#Iao6;>SAJyGN2aH-rzh0>Qta(Ars_Q(m{}TLfRC9eJzN!w?>s3`_ zvWBr-#Xw0nI_f~bQclagk*!sIj`dTr9H_s1eA0Y!H7cJ=#(=2x2FhaNyXQd;{Yh<# zUs-9Lq#Kh5o~Y6=OlJz#KgiC`oB)@^b$2E|MYrWI1j11qs@_@NN5`+!%AkzAfdiSO zY6v@q1c;ffDs%B*ZM^eLWTLf@ng*TQ5lRLtUqxsgtj#R(XMIVrl3Rt;&>?e7G4 zErySt!oVTka|eTL_LVl@-s?3WcKjU>nQx zxOo)Xt~K(EJ2BtG*)FdOp)1qY$hO9xKQCWsWuy(DVyUaZjaYa~ z`^7t`NPwi`Y}aew#rA6B@TTCnLkbJ+_OyZezBU<%gYAJEcA~xX&BD(fadxXi6jft&(B+zA#)1XKlklpu9KuE z{PIw$?8Ip3c;p>{vYy_aY~+1Aw7(E725dA#iqTgF9t`NztcAm|yWmIgIhP*+zP?&9 z?0jlLMMYo-Xe4}WdYlHTSre*VJ2n5-`-*C6avUktF@+|E*;%Qnc}}8(J~6^1;fni} znw>N5mNHjYS3U;cSi=<&U#q#fxYnT~EIM@)@GL}TBcs#cx&WM@$yI%-OTH|qS;%a9 z855L4X_Bf26^Aet7S|LMbR#n-XJ*!6jNIcpx&~Ke!rWcL;v4m2Aob5T9!^UNP)iQx zLpwAA=+k!+bdu#b^UJ6gwAJ-)7_RlbiMX! zxp;Y66NCYon0{ySZbF#8Bj&DF;8@qd2}!&z-AUNf z)cy@`P%y%SogI0a0!bvLev*o93|O(K3Bw&G<0V9nSWEIJ%GwueEaK>JF@c}B3l|Q2 zoE}2U%(LvTLU<$z_xZI}+)kA+x`YPVHT-r>&WR250{I! zJ4c+E^J~cEF`!>jKPP{X;;p>!aXcUG&|cuqmq+=D#{a=2mChAunHyMu5>l=DIzpMF3eNJuu6iM_? z??3$}M~{7yKakwVA9{M+4ZS(l{=x<;LWD7hTUhgZUVi8y%z?AZo1)Wy8CNGmC0QUg z{X+F5W1wKkgFdVE*K2R&P(jM_Qr`cZ68$es8H4f7*>4ANf3D{N%{SXihF4$WdQH4z z$rQg1VeVTh7k#aPfr1#t^*|1>x73bLSK_{av9TV4NrBP>3DQ@7gS|f?09O#yVwV1a zT})RCrKrv%J{(&OreKg>f2Ee{jrF_4xX2F>K5~o_O$*fL6_$gf93~I`nL_-=`Z7TcPYO3UCNCs=2*`Q_BthKnK z9)PJmc<|uInnRZK)5KiJRD7yMu=^P8g z`9phxizZffw7p?ptWR%sUj=xaUEEn`?uXp*5l%hoe4Y5&$5$C${;l`63e2!E24^}U zH-Bh)Lzit07+N@7Y-5{rG z%gMi)?!>oOGydnkTq&pyE1&&O3m|%9F(k0VoG+izcQ$P>43wGh%WYW39om%C#b<%& zqTN+w(9Jb6%aiZuGiEA5`q0MN;SbJ`z!!0S61GAT?_Bsz@kYma2OeV6ntsp}eS74k zMr^uyJjA=-Er)DrA0%MjL|`RadH(G|feLr}N#fAdEPRUY0Z3pZo!<#HJvJ$Y*-VB? zETH69Y%>`3LvZ%~{`K;_g}xb0VV+2UAj43+#oXMZ!)>a;xpzr;CVh4saawOI`ow^s zh!LBVF=SfiW^Ak?uC1$>s-anxoI*-RD6grl`}HyPbj|o`1Wn|u#8()p>X4%E>uyGf z9tkuSZDwR-MbKD0H$LSluW6s^r_j&`!^wuX3*DsHQaqf z@qk=4=K3)CCY`k%B zO^-dm&z%|DK6Ls!_sL2`!N;FG4Esl~G!u^LehRl@+v=il7O!k49J&kqnfqU`J9k(6 zCriWLL%3XFSsCK~mXCgTy@6}+2Mr}j*AcrQ({sC_j3|8CskaE9`9hAs>Xl!BN|FXg zeG&PkN=Xk|T!emS^YfQ4@xgv3FRe1Qdm+WoQx=6w=&oGU12M57ipiu9S$(t4 z_yJ>F$XZOZq>wYTi<^h%Nn}?o8q@wn4an7CO=9AMbP=u{TWP2MHl;&Fh`wg^gezmanFtp$gy$-etD`-ECQ?b6Iibg{K9wRLaxamH77wXC(wb_MW5h77JZ9Cx%UVdD^(@S1YmWe33Wj>ioR^i1ei;{=ligq~P!bf`0c6v;Sg-8) zR4vcTm!Z*u?DG0V$Kej={Qsm5f4k+NVn~pr(lmcHlJq#&oSF0_;~rUPY~%qRZZ$QG zBbz9+Ed+_h)KrNB4h5%>5T2syY1Iw{x}-VO40}~Wobq^~$f0Yvl)yqGre=pW;JkH!87reCP|r8c&8Y9(@J zBNJ{5@a{N=;~{Tb#_r(nb_^#C^)0>1*s=~uSzgF`5@l`$6`8)^=dX+Lvkt~R54FR4 zC2*9c_`hhZX;b*b)D&VpNXHf)A{9xxH{=0)h^AF*Nx}&kLSJdU+F$!Yq(DA>LU()* z_Sp{$Bkd=YKJ3L?W!ZOP3vM*t2Z^czqk`%bkWkq=^VJb$WSF7xRKT3kr<7IG0v_y_ zFE0#wczNsHK?>s4GbcT@01*S!LYa7I?!D%KIaKTr4TqXRh4{V^V5E=*MaFFc#rcu@ zLK8td-ETO;LG458bd71J(Q1?yKLdjkN9a!LU`wn^96vSO($KISW<`8NYi?)iXPRgP z(nnmsb)5qD!YbKcyO?B(UzK2lCyHOaaGu)rSUqwNSU1(+>71F4Fx*eD^0Vpfr{PFB zsR5)Y;3?18q&yG!HkBOesK^z9JY2GqE|OH17Tu5Aoa;H&^C(Y_k0V-fXY9ygK&A{d z{=AVF`eQ(t4~Knp{8rKg`~e6u{E=3#o;)2yavf%IH@%v;6{s11HJB&KZ}rij$=}Xz zV`m`!-M-Y@VV#kyhwIBbQltr1Wm?s99{Z+#z_wIl8?#OG0OjuakJ&HNNck*iSH4YQv?i?4(-Y)>Tsar1T!TK81Jjd z$&JC#N!~C>A98GlzyGGMXZ+QDjS!)${BmWUuDXm}+C65Ihll5anj#5o9wCAd5{Jl9 zmv?k@*!VqC_*{*gCQj+3W}6nuUpJNU2F}q+Gf7-CK=t>UlqNlF@Vyae_j$kPArsTw z?za>H((g5~2~d1W>j6LK1s^+>7U+6SmE5#gH7zNuHv^I0Rn3AyB4>aK9XsS}QghWT z^Zfxh3h9OUD~xe1&kty=^8@eVZ@3{bNOm2?#0x#6Z1}#T+2DFZ1t1Wd+R}Gi_!*@) zR84yV=>NvxyiKVD8Vzw6AFnX#H86jjYh**H*(yq31$QX%73RN%@5R`VaI&-5NLIHAv$pn z8-Pfjo}ZJ-L8?tT1v{9e(^ui%>au^<`0Zt4EkNc5-KP-f_CRZu9Vq6OC~mh7m+k*eXlfBRoyq`(5EUU8sJWX zVegGwC-|m4IFUK=6MRo$m>4pN%>xsBT5%P5Je*nsiOrqLs3As<*%z705$hz0IOaoW z``gn-MgCvQeB?T&SKx9gNQvz%ZIQrvi zH_y2g6wjE5%X7GqGl}nIOV_v#xTP6utVF&KrE3vrD=CRHlOh*G`6FBMI}=%ahEhK^ z-Kt4W8KI?zc|#}K`c7m@{X(w2WL3tw43s}Aa!{-<(*bG_iD}ah>@0$kX7qln(P8*w zq-WEK`h0?SZAn7>2`m=o;kMKX0T1dVQZ5=i-C0p<$Ft#twA=30KA3 z<9h2T#l?MTQq(oTD2PC>hcGXaBS#5Mo z_xGc$=W4M1p|ZFtS-OE5j0uzgbDz%N?zSID-Ad5`E4Qmo`cVt80}is@z^!uSHvhU} zs@_H_dxS&i_+64#kiQI&ifD{l4;k%Ov$)TCSszq0J+p5H*{~M9ZHw-TTeB9QDf@{} zG&$fy8Z!)zcB07>&(VD9jL_Zk|9DnjHEbqVxigUBWfK|l(dE0pLdpE->U_=aV-%NJ zt`<`VeU|=tv(QH_$3HFGP?DZ~I(^JMkJiR#yL%$)%kbwC*@9EwYO!mqV_z+*4kUno z%76$U)>PGhW9`fw2INjOi3^vwF=Tk;WLR(L{Pf~#)+iR(ZRs@6fTKl8hJw%FGA zIW-@>mh(lpdUrS&nCWg3pL5HVrtZesU`lvp;3;_IBj9=|1l)<2$;+yLr3nN7BTXQp zRf%tT0pKK3O7YVI;)KdVudpIC>>6X6tbcW@wP+PnJdXMq_WopxOPoV3*?J1#mnmlP z@bFOFbKhwyll~#fpoaICEaS=a;lwpbCeuTG$I}_;a|TOfSfo}tH&~0jxw|4snDkjw zM`*2#_qoFqNeD{mxFL?cdSyTOPOQap?0GVAaDq0E*tL~Adcb6Vqk z4r~$E-IOd%0x3Ex|46w!RJ_VeOPc6;?i$w{5KM zDr+;{{a6LZY%sO|6gBa0fv9uts%k%fGP@Bt|0&eB115Tf!Wk{{Rni6@E=Tn?_Jvpb z`ooxQkoDHSS-H!1T=qdm>8R^enPAgpy06M7gO$#0{|RIIvY&Y~ z@B?AI-El*R;w7#wR*kcKSz5v(DMFWlZJ?JYq9>Wz5{u1C>@@*eOOc$eM5}?6K*IO| zV(P#7jT8K`($Q{)j z)e3%4Z)-A>IUs9WnKA}{>gy6 zc~G-AdIb>k+g-RJb3}x5Cal1mg|tSZ&)v1>DUP;YVbs9`%Mpt z9Nf`WYj?Nc0rBqFdeyh<->x94>ZC4KW!xYl0grCp3rfSiD>WBjp?Gn?qbq8>u!Z2d ziPCwWTU!S+gN-7+%Tiu>{uVa`+nQThVHpBEHX!AFV5P1%nLv3=6ITmJC4%XuW{~@H z2Y{Wt*Lc=?if(E>BtH-7cK*zHFT$ubG-Mb)#G7wZ5fD2-K zO#(Ej{OlqF^L07hY(*HBiLE*b(Kasfca5hgB=ix09ycf4`yOM^Q!u-iK+G6zp?)#;-$Fsyd`YVb9{@D1*$=V#l%*;$%1&P@517`s}isRba zT0jQ4$PkAke!%#{t#u4d?SH0P*s6)BqG`2bYeR8z%_grlG7|xRw`# zqsGj1Fnrk&a}X&8Z}m|?fX}a@JZ=MH=K{?*kUC4_s96J$)wu(?G@grX-;L{Dp)yYM zgIfMC@Xc=W>XDQw#GF&o0Np`=<1I>o;&y8960lMo_ogi*xz1bXj1B-z0gMGRfbre1 ze89Q2tW|_Vc(J*0Z*6AkO(Fe4wep`IoGKn~1VY-*KMcNBWBRw(y@w*wQogQWf~6hj z8;{vzLu%gHG*c`>me6aaM0WT`k%Vy2#b)9l1!>ghD-oaoI?*~?FW>Sy<9{S_ z6vtTqk1Ti>+7Mi5F`iG7XB;j`5-$LFKs$)|!9}pj%JA9h`JQ{0DLi(3))4%-YP{0= zh{l{2M9(ok3up;|t>*#|67Hn32sNF$dzO?fs*m`hlbTT_m1vaiug<1=@8qIb_6c!b z<7DfXx0OubbzH(k6I%bqMggPBr@&YOKDeCMhmK;+!d7wz9IUF@5?vPcC#Jiju{WxrB!W zP#4!S`~(oHyyy*{Lh+OEuG&qrT*~#~_%LrkGb$g`moR45UtFh2Wt60awCd+8E7y8r zMNK0+l+8evdLV4(NY?(2Kv?tZ7;T_DGwHXcrg^%PkZ|u6g?-1#o5r`MdehJ1JvtfL z_RiQh*_miJcD#i+3~o<^_3;a+OE75O_4x$T)TVenvP~IorAu0%fs7>L2E|@P^m>=& z)xAv_1|v94Tfwv{6lAGLqgJv{8RAc2>Cs(AfTF3=`yw)jBTFmDro5bCp-(^UYVWcY zGEC(BC}`cJ+EcA{`rf7o2!#5ozg4g{)C_Umklm5+tQU8Rt6$-@aa-S-N~Zbr3rP6&sT$ccy^rNIbzMd7l_N?o=H z9^XAX>0~wtg_*rIzmuc~(OL;_v6j4_ph@dmJIYl{63n%%)trRFEGOdyc0EO}M0Rhg zcL;WNc6>G!i!t@AtjZF!+88$97VeKV6I_v_iJ)T4>^G_vP2C z71t0kaN~`w^$}@QrY7_XaPueVdTd=jPqLcx63OgSgMZS4YnL34C0?v&>XD@TvlW$U zZa_;acj3**21~Zc$ubH1J*ZxjHrSDS`CGS66Jzk??c9Or$IX$%CIAz`0U}T9aiT=+Ph3RHNJgmi83NpnI|-Kr(ks7UHz{ zA$fv^@Erp;>|8s1g_aw}K|oAaI8e(Wg;}&1Z^B$ei%)d1&MjGjA{5>cuK`YBlTNJ; zc^-pHlY^gKUq9{fx{SLnuCTLMeejG#KyaE=RWFspKtrGkPYs^Er zoc!d0O>NlQ6b0&mqdsp|_}kyib5?4_17x&HvqoeqAUAQ2C?C@AKUg&uP1%on5(YGi zB}u4HX0L2pu}I=BtSe<1`GS@Tf)Iq2qohp(r~Ddwmh3=yp(dr3ovVe3^-5$}l?MJ` z^&p6lq@;nW&uw{A@`i@%iDfUC4pAXDiuLhz=)9KqkUx}%a`jrC)1IavE31QBw-@N& zS!uj&sEjMFdskFgY*texV4v|H-|_6VpzM7U@Z_hSQlqeBUw^L|W*8o%2j4YL_Dqab zc7Jxc>TGs7TKH`e6>mkrLObSrO9W?8l`oduS5vD4!n#x2s|q7h9j6=xMPgHe0wL|L zpOarIZoAql?vyr(`G+MiTDfnB&I`Y*-E7bU(^HL>s=$i0;S@k|&lqo8X6R6c-az=UIq z*uuX(wLe_76s^@K>88$#RVwe*y;MnE=4-gYpE#VW2n(<I4|X2>RHn4i8Y@v`sok$4 z{@7c4Q1!*EB@fPKhEZU6AlNW|A;TYec6O0<0S^{=G2O}rNNbR1d&PR(P$LROKF(zw zKpaTV7m2_-hD=Y}-5z*)Ln=#47a2}d40b*mX(*l*xBL`$867pBpiA5@+*W%k`#a7j zt8j#F1~R(f<`2o#(xy0_RV$daPVDRR9;~81_285%3rT?COo7gY0iu6Q1|#8rJwwE% zNRE#kHk2gLxVZ7B`&;?VZo;2G(^SccY{@V#U1NMYXbA*5k45)Rle*~l(gOlUxyIU( zwYjQF`o`e0LX)NWwvKmg?ynUVZ)j4@Udt}Sh8+&WvrYl6|6j&4UN2PEj40d^P?U+~ z=su=yXEC@9EMKa+SGS=9RS}9`7d3HteGSd?n0J9cUbMrg(7h?6w6-vf+u{j|xm>VS zDG3JvoeE7336c6b*%d^SRSw(h;!(sF+zd>bPGE#+sTTbCaEKP^BbpuH7=>rT17`Yu_W zZNf|hZfQzB`-2}6*~Zi*BF92l$AZ`?Vz6p-YQ$4RuI zyZcO1m|1!C1>_=ixyC|8TtFS5=L1F{S=~m22`r~Jb2YswLz^;$u<~-YLOmCd>an{M z?NuuDp%3En6Vzc&*?}LHeY-6iJ}_-RnFshE0g?nT zK+%Al{OJs5)MCrHAExz})Yn+a*rrDL&@R=$geUa%kzH_(3zO`y4+1`F^#*a zdKyrZ5#2J+4kMttg-1;4CTcSC=nAc<;|wxyh%<{}h66)s7$GhL2bLd0Ee zHLZsx#pJ&S*L7*CdM}uZm=Mws4=idKLLk*u8t`Hp0}+mc=(q8$IXOA8mi{*I8Ido7 z#oMZRt${T>JB6L&=YvgOXMs+9O;z(7du_G|d=2#;r0qO1%;uE6O1f2=>jJQ*_-QWj zz!&YGl3uU-wRth4U}gOQMf0tt25#Q-KmQ^|GF>#OQr|`um1w~Jah9?w2sF0@3UpjO z)&Qga#Maz|{BvE(c)&Z#hTmWEm_;fz&Z?hnw43Q9WjM*89rB-XQ(g&5+&e;Z5?=VV z*F?HtJjcpZ5?!vRi{*%s z&?6-yjLbV#>`5~@P)!jVPDGd9lXU+=vJ|?Ggy@kt zl=9M1EAGl81D7MZtg-+h!ziaWnR!f3Pu%Dq2p^>8IN|?zJOG$Ky^z!(&HTrYsfQY- zm;q&vB!L%cxH$sOOp~L~I;D&4 zBfd#^ePzJ>WKhkak&|dNFt6;0Hg}e@S6lqnz%SBVyARG4GW6G_1$YbrjLK~PZYch8 zV6)dZ`2fTkFa(xlG9_?Jn1J;Egi8B3VoGk44-HJO)+3_Dr7u;(PV| zU%NO44m2l)6FCoMF#nj4uWZFXO3ZbEQA;hKLK2(5vJxBDeuwLj4+WwK8g-|koa=f3Enc9 zpUx$349?E#Bdy+@kt%595YLuQ<*G85NEk`%78(?Zg>vS)a2(rBczF ziQ|;>iYka}j#N`SqZP!1ntQM=YI2V9vU_(V|8kk$ZIA0!M%MX1TA39X227morE9BP z@w4Xi-(mo>%G%o-fZ2#Z1$=VnUP_!Zy!6coWL`G{QMRlt>R})PNxb;Nr?zXIs$9TQ z5Krkmt6ad8LvVdo*Jbif<9VtUjb;R&X~9PTkXs`ypb)~B8xkLxHX6~b%3H_SkE8=@yy)TIi9)ZI+y7=zT) z|IF8D%(d`ATz#I%=v#vQXVKd&y6^J(hRo{!3O3d{hyhY(*5PmKcRbg9EoGsnmw}XB zR*wBSAn*fBn}tRr@gP{^L!-$nom38$Po7?0kvL+AoiHvM&^yX}Vxmp!6ee(LU^uo< z8F7trNTLx?viRf;kR}Flze`h|}a^M{-B+r-yd;s!dwl=}cynL6O2OCJJ=a)N+IpGw2eX#Sg=x z`~L{+M?|lF{`NLHBDXwx?e}lkqlc~0YoDWA*Z6W9-ct5Z>O6cLE7pUyHoxw$yh)4Ftk7ub`7d^R>V__LUrJyj-19)%XcV4}Ya zv+&&dZW#9Gy9M`E7eZOC%>b+U-ynEfLN73N1xlAJ7*%tZH`YRGgn4IemBI8~pBO8QHl$VRm zybs3na)F^KCtUM4MYOxWQ^_L%wN0vRG~EscUS2MT&uJ#vveQ|#O0kUY-pop|$Eh&( z0yF`&>Aq5)XB22Ye%s_P41j&;RGKIk{k0zCL%UK0S|}}Jt*zVNFH7Gn#9rAt7mDA+ zH~j%&31gH;pMWb-&{3 z1)uLXz{SYq@4moPbULHVx5g65pVEXqNPRv?MlGP4{vo6Rotnz%!nwNvm7#Iam+klW z(mH1W{FN;ZQ|&aIzMghfH@Bow1ShZ?Yin!7WMo)q`3t%u&h7E`N7#g;^kV3fy&tf^ zTkZVM;)A^v-@CCiTaI_ld!7|)*c`c6T6yQ8kT{~EC25cBL-ukq@)Dw zywZ-kbhU&W+SdHLF&P|H{%Hx5;s1PGBG0mg^6J+dpuW}p_D+s`#3YRAc@zf^&wHU) zZiWnt?6$Qu5EM-`)8NpIHouQuy7p?v&yV2MU&cyA_6Nep)Gx#LtrMb!|LB6dqaHqUYM)V&mQ`x?$fBnPz8ra4UIPK%q`AXBc zwDRV;B5@Bv4#NQ76p)^8GBe$8(Kkpk%!E+ij3{_79r%n38Z-g^Cb_sUVn#&6SndS^ zG2oK1qM1?3ca*fDVx^)9{i5yxe)mb&?l4HEpFf%lP2OcrM^6j%wN-)GWF|+!dP6My57mmQ+ zzDU`eY_i!?D73vwnARyB9Db?rBSZUeu-0*$v_)}tLK0# zA3x>uiNYXFQpNswR{r7d+iqF32AVjKFS2R*uo?@nn#ShlKD|Zwu^6s(C8Zxa>1b(X zG{&OVm+I6DwC(b!d3f*xjhQHF0`T*>`@K#`nC#c^EwgCE@1C0CM&Vxx@K?MhUtFN1 zQqz=iNsRr1DvVCoPEC>+oAdDODO`kCvyUZplt4OmQOUVt0${i}6Af&{^t}u1pPvL> zuGcyR5vaN`Ts&=yx&*%O5%C+IKN#5vlHLNe7&J!m*RT778rFw5^zBn^y-^RsL^7gq zQ^TU2gD!tKREI~ab~I)3(Rk zwz!d=l^t|HF5hqP1G+d5;IUlvcKS`p1_3d}AB;>^#27iXPZe5&P zDvO?80X_mr3>SQHR*c9X>|_%(xj|Za)sm#IL(dLOy2B&bf#V>#UK+lWoV?r{n2-K@ z3rhyJLo3RpFVmoar8+e+fk1J#b?M#F)6mEw@?uKAUZ41%h^Hz67aA1aBd=*-VQP zi^|+-TZ+pv(wwLoy2CKTe{t`r)z`)aFuW9_6XZ*61aDEMK*kBGG4jO-sJu{BX#GF` z4h8xfYC`r1OXmlTV1EV`EM`%Nke;4xZO2hKQNlEySvuk59QcZET#lq(HXPOhY>@ ztJcg%e$Us{-H>|Umk57f0vo9HULtq2zI7}83+MZ$#L~+O))#b3SEXnow;9uMp59^5 zq%x?;uE1yD#(e<e&-AsZf zv>=tYPFY@Clro~oSp|pl6ei6X^8VX|vvf>>4@~@5pE2k*u08s|$0x5vdLgdge~Ri1 zm+s(Tw{Rs4NIc7I+I+U;z09Wu$r@^zPF%ynS9oc@=HljT-%uR>`fd_!i2jhjy>Hu; zg2etLXfjijOZuH!`muY=5xcs2`FpMQ`=GQ9jVTgL+oq%zV<53+cYqLO$A>*4c>(oh z)u|4DgpW3a{TR(&R}mPR`|R~=0^*m&0rsaF{1-Nl*>oFv0xnVR6CXbvT%;#z z4RB=ZQ5xJU)MJx3LgB9o+M$D7NRoI zBka17ZIIofP+d%)s2x8m#>*~z6b)nsv1rar4ask03!9kd0Unay_(I8Pv{hB(iTb@M z(~o|nH&4l9fqN?;iuAqI$LhRvM20d^VmuDy4_XA5tWgAb8|-)-a*z1|ZkL24L6Y*x zH$Ekoo9l)5A?WGkKVI6^*=OOYzB-Ur@`x^`(*7zvDox$DVtBq}wEC4!cWL2LyiE2p zjo^BUBv=11K0BM}V>R-fDT2mEufVip@WBhexp+9qcc73^pYJPL}kp8wuoQ}$?0;)@7H%Rfw#V{&d&B5 zQ>Db1!m}A}OTD$z`d$N4%g0@9khL8VF|Bt@O~|(PpPU3vi-zM=-g{|+7rqAr zY#UUSl!>gx8{ahs*H$CqLW)gijzs6(=WjrWOg{lP1GPjwLwKuwI)U$RyxU@ao$((5 zJonHm1^x8t zC;2q(;TOc`?lr({3`{xu4FstMz8yR&ySeQl8oT{Qo0Ym6X5+K%De|OOl|{St9yJb2y%Ji$_4ozaB$f$=fsK46hcB714Mx{5IyHIbNT8qFDrCj*yqZk$9Oekb5R z31POTYK`uW+}hneba9EJ>6R+fp4@JCGFo&o%qmo9tpg^@o}Qa^lO2Zt!7%XffZKT& zdcN|wW?wjFn+RtAHb&X!P0O0h*qYfV}V;Fc(LWB?C00IpN!gRF_k z$?>tO0aPvYhn8r=;k9JtlV`9OU-Qm?-2Xpiu_+jE%Mt{qKVT>XJ6C-2E}v;|ATlJS znwy?ZnG;A&_SP0!`;rt_;&qM+VP474X*`GcH&Hzy3UGrKUAeBga{WaaEiL}< z-+^$94GbJT=Y!Lk_{+Cv{<5D50LBfZ`YawzEXC~*T9rF>t5^YVV%H=;VkQCv?~oT; z?`F~t@O)~!r4#iD46|rs-{@k-^xdg)v}00ac!prTpjhMAx$>_B-ifi)rxYS1j`mxg!rbeZSH2?9c+28x*+kn@hC?uVxg^Cy|z8 zN9neKd-ole0&QryndE_yzcnRz&~iT*j%NV$X^9N&_Jd=@^WSvvZ%r+YG} zNb^zJs!eg(c$!1!sK-7xZZ(B_79?;Ii{t89q!6oF)(Js z61OHEW5hUSeY+;kZOlm@m(BP1)&5X0OZW#}LGJZ_hRZ~&?(WPOwlCZ?jDSbuv2ki> z-KjnOYs$K+DuMSm=e@4yE{~2{`_(lY{w-m*^ZM~)3Da(k-YI;N2WFDKl*Vc9;L<8B zwK~owI&^!gvNO(K(VNyPVS5G-P-bE2*KG3*B6`V~K6~BH&!5O4s6T~KQd}&9O9c<` zVf+dW+MM8fU(QV?=I_4=oX$8ft!A@3Xy|>b2KhJLtVi*Lk3;OA5sid{sK4Ri{1#&v z=hI3?h2H;SUh+yU)_26!;RK~H*yi;K8%kB$pRa8lWild3cwT)xr7_WzHnuYhX0 zZ~LcFIz<{p8tEJz0@59l5`rMP(JkE|N(dvRVF*Y!(lJ0vq;oK&yZ=A$`+45?{c{dS z#NjyGH?Heb7fmj(qfRW^nuQ4C^m0%^mMW(&0d!&C0!?wcE8sY5DtmmI`G*e5guULb z=oaQ_S%P&^(1T%ra-ND?&ROU-Q1k$K-XYIk_O_{E-7@&)q&TKLyx1oPG_P)p5I>$$ z*!S+uQH;YBMvz#U@n`B4)@QSXbnnMPv==Rf=E5~(J_8kU0OJxV(i`aN|MMXit?=P* z77CY1eH_4myB)5`7OYEHP?!vFovf5!NRHmjWUI&Fg(fcbpEt)|#-_?`r&?rLAv%`2 z_prG)1saySkMlM5AI=e1LmeaQGl?*(>35Fr|7L<&gBFx6llZ{_@?L+h zGceoB5bX5reHKX&NW2q20pA@6ohYuTh%4Q}qlGR4v6<(8=H!8V7ojSj(f32iWL9U6 zscyT?av-{;!OtCZEOP?zJi)0aGG$dc2lx9#9sX~!vP*f-@X1XZd{F6)=mw3W2JfZr z?-S&2*H*}wHyPSAcH$xZi1Ir-7po1?YYQm&g4Fp1aw zTJvwD{Oqs^&*Z_X=s^Y?X14{_r>(A#xF76&xG_de`N^8?un>=4BjdKUPlKHk(y!lw zpsVvHa=9;tUN$ocSFeKOQAPTq9{)Yn4}5SJx3E%X^w4kpiI*F-Sd;MBlrupYzL} zJV}o~!&SJcjixUQ!}XbJf;HJ$N#=<|K(piX8H+kYBKDURK%UdQ7wD>`|jcT zVLi>bPi3(Rkw_#vJG+Mi`RtIOoL-;>PJ_ZK{}YT)Bn0+opE%gr-Ig?u`J8uQAF7-+ ztXbgRWd#|3QcJ*8lU)H00YE$DhMYWmPgKnJ&mo4=3>5#0$tg9VTR^wT{^Etle(?zv zRa87-ErW1mF#%ms#XCk_%<%S!%44c1I-NXC+PLRm(YI@s571o~GWDM7BNB@Jmb{zd zeVW#rWch$s?0L%LkAu&FBY|=jf1gwu+r>*_@ouEYNzJ1l-Q9|{4F$wl$HTBpt6AYP zE~?$ot`(xE?_lvfW$q@nF%8vcyx1s6y8$mUvs>r*_f9st`8PeHem>N0IoEzZo=6FO z(5wOvgFc9N#<$LJ^DUoTJ_X`4S9v0k6&UQf#jOkdP>G;VJWPr%Nx-M~+g zXlaQUUj8*epFP)mxl8q{iL-Br6Zt4IftOWcC^^81CZpj)#7CCY&)dkq*ep9#L%c&| z?5j?aGErGseo0|?o=ZUNYAHK%>4Yw-Kg0LvCI2e#4#d|pn0kc3UA0i>c1xt=jj!() zueMz?Q}Cz|jf8g+KD98);r#NwXZ_}egYU=s_E$e;TBYEvyfz<0Z+{Sao=gUoWLk_) z7rvtNhNT_c+GibI)E!4(t*rf3~ftqFd=Y=a#ymf5~+>AYq{98(;lJga@`B z6AHcEA16ENbAXxY^<@1P)yA%UVYA-MPZ#(#=b_<6SIi(c9h7U$1Ce^v$<&5NA28jM zCvW=Tg6$LNOTcL`Rb&4?YFRocUDH#8IO6*1CWmGvJDI3%RKG&`!hLt@}^`o+vkm7W*J^NVhB|2yq_&r=8ZR+@b*bt>@ z-$}@JBCS#GKgg`%mj%n>>S{jL8TgdhdkEyY3#oDZ8yafrVK)kN7hd)EdSk&hQW&8{MOza6BD$^wmS@O6eHFn7j9(YOtP`JBwFG~~aLotB6;8fWR8&M0 ziyPz?Jl^8-7LSYe*6s2AFNjyjcbF4Sv2hB&1*aPPrInIb+MJB&{;+(lq;8V4C?<9vf&V zmWL1oXyd4_BPDpeBz(AtY1y;-Iv1VPl=pCf9Xh?IThTImqq2{`Dx9iP2$Ug$o&zVb z>1RlM(nyK)reahv?$WYW%hLAtcA7{DGp91uY?H4g&UZ}7k0$KZ<{Lnf65~oSI7zRw zb7mzCPs0tJ%KWUf(j-<-g#`tbU%e^?FQ0~P19;`HW+6Y9WAI>#-|Q4Kp=;K54?+pI z{lB=dF)blE_i|78=b+&LlL#@F-kipu10CUj)?{9Wd3;-vfYXGtn$7arlak2kR>uQ2j7)9%jH7d>A48w29Yua3tVi$b!O?-Is4Q80ys zdS+qJw$SeSyBJ+^}kErHg17m7?;Y8e9p< zli29BRA1QAVt?kyjhl7G*H21#1Dc7$CiO%d^Y^27jMypW>_`8Zo z&oB2vm9~yojbYya%vSwKnQ`9y&t@_r@v!gYiLSY+&EoujnwNyk)=oibuWEo{F{pH4 z{;ZO$!W^*Jt0$xKo<`|eGL07>xtu%tKIE)4_|s*Mve=hNM{6w)w@-cRmWg}@S}s1+4_5` zSY=~k?CrWa!i}x~4okL{;Q{T!W1ulxcxJ1rq5@@8tn*sjdX7#AP%}W-PXC*VM(;j3 zQ;#G55X8psDK^DUfqdPHP=9X9kAKC!!5ALg$4wq>yNEbe3yPGB)TgSQ0ngT^#%xFM zKLWQsfYjokq&LS!|6X8V7ePq*NWOG=gbgB=X0`g_!EL=J%A>?CtvrOgrsG!tG~h)= zZ?SXH-4|H;uWytky`=37WM7Fjb<7!@{$b$yb>>JXhPwo6?`x`R>K(og(E%y3i^h^lZ$g!+QOikFdrw6h_KWprUCwDwxr` zf^O8L1U|rkk4dMIDiMXAinMtn;MSgYdJn`Rh)9`9CDNq5m|4O-)IFf)xP0u(3ZlIQ z+JiwN=%0^9}Y+ploU+CnLLTwIrsn zSm^9OxFel!*++B^%^rRE?Z3c9R{piDG5WJeP-X*<-rizx^Q19lM`mS5W^S!5Y3$Gw zSKl)p@7oK>?>u6OlQAfAdKJFt^fy1LE!~3=f%k;|_a+^d)6yL&g;KV!jiJboOe%)U z5Ym?R6WXHv_RKXHcS(f}2+ATT+y`-bQ2^}sYs~=UFO&wysy1O)g&lz17)_uRzf63% zB&>IuS7alzI$G=HGOh`uc5V!D2|UU4U&XapVWPi!w79r*eG#lrM@QoLI=F{u7|3F48o4keQ%)1! zqQ$M|i50f)j93Mp-Z0WJjbv1nTfgjL+`)X;99gVPYUS({_f$qUj(M7K8$K=|IH(2r zXoH1Qw$86)Qr{dfLz3F97fr|iVBLJ%}w5|%{W960A2w=j*CJuj+;;K5Ka;hw!NVMx$Yer zLI4~9LDmzTaCcwB&lX`N7G&%HazZo(f1Ve9U@@Onr?4ySW&wFgpaxwx#SLmF*Q9&` zrevG4%j*~ycV{ep4tY#||7mu7uN_NETf3_$TtIsFRafXDFCV_0L07%3kp-rOaf*p` zO-E!KQ$a%JCn}!u55P!q?2xZ&s354oG;+F9P*4zHW_Z^Hi^LVp{iKVl=M+4KPV|`G zVn%%}$3JabeKNdFF}p*-hbwR)OdP*3H@AvYjFe&TbUPtwD@WJWFXl6IDFMj&5v1wR zLe{tqMKchUAwf45?R5TO+lFYcQh1=-wyw?t(8pLb@SQDjw!|0eyc!$O@ZqA&KLHP- zyI;@pT>mD_pKRJFZDY)T>*wbOO*d{5Zj$ctAd<$u6VUX+w?X+{z8f{!g8Y&p13?PN z!qfvSu-t}p*WapV9ha3m8a00pkBL!x?)jy2VS@^zE@1GZarjn6noj==XJ7vb8!rOzP=Ft59!Brg=)${!z`TH zmengmk6>P5tA52r^W_$WKqT04cjiUs2umA*j1Gd?;S_970tY8ys@XgpcA`~Z5%Xc1 zb=qq)J?atT?zpYffE4~2|0=Gb>`_i~nB|J|6II#Sv8ws7^e7AD#RtrD?-X_q0)~N5 zQB!B6rypV@wPqov;(f_wNWd4b{f?ITiJpreJxXKg@YXm3l><9pTM-4r{rmgz`)O3u zK$Q3edH}i>(@+QTPLIABsU*}7*6@7CA0JI7G^8E(jARb~(;+xV*HIT0)Nw!EWw3T% z4>bIU`#it4*99e-SU7Dc?5M%lsLG&6iU|IVFZZ;8|)J@R!gCM z0wohcy#q0K5>rz*pQl9AH1LUt@LV;Aw44;1QeR$FQTH$}2Vvf_D|rshs?n9Vwk{Z3 zOGjy7hhT+l+bA1FY(oxsnxrulitpbWXY_&yJH_onrgf;TPO(r#g}1#19s1oHPUi zLHGWDzp;EIe@0RBZjsj*1f7LwbQL z2C2_L=^DzlQGb4t6FC;NbasZ47ZZbnD9O1$EjA6j+RSEcK7otdVK$)tS!ha`E;mF! zj1XxJsRBaI7rfWw|H+qL99?JvHvw+q$Ki6OKAWF!&l@^0S5~@0O+BXdB~C^Ju0x8I zE`N)79p5bxQ9rzwY=Ch-U!3m}@0jjO(S2!plOW{(Zi3C?a)$dJOoXJ+0|y#^yzxr- zNgs0ryMT7Z;}%_A5$0?Nv`mtXM7#FI@N+a{H$DuIVS+QS29>sI-QAN+TKkNi7M&zR zP49Q#{Is<-1^YfeNfkZ}u_e8o{QJ!9Vy$}tcJ3!@c+f~iQKE!uSasBRc7W+=)gs=k z(20e}h~31h=aO$fqh~SVo4YM@Y=6XMPCePAt;cN+b!ts?;Qe{#*h%>WngPsdW9TPe z;JK^xp01YP`Obo$lh{t^UhA1(URP7l}C7z0RjKdzPF$vqM8SRsZE2&KBI441RxTngS4c^e)`J@I+r^yC1MZT3BV%LRGwFvD>8ybB zIaZrLu{`aUVR4SY3KF7@9qQ$daHRBYXX(R$%+)X#O zLwwnfryGjAL#~fkaNSBJ^Fe}Fm2JL+#3<0Hm!2&V&fNCScbpedQ8fandYj;AzbpX0 zzpxxQcylGX=waZ9e!LGpcC$8%^zrgfbBw1qDtowBO2`^J$xAK~!R(oXQG|QNJ=Uexn6361*H$LX(bFtpI%QjuL|;7}urlFV|UZOgTBr(-dzm4iJ?t0i1bS%D7*B z*}nnJ@v88^y+=g_FlHH0TLD7>;8@Ay`i5qkw-Q(e-9J4+Gz z*GmJ-?RJ#59pXJ^Jg07mJTxR#`PFz)xM>G39_3M5;~RKWZpO3JujjyO4OLC4xVH3{)fVwDur4YfvZQcI`90p)t}>b7CZkS5c~mfO5|_w9O{ znZ&6-VapG&QB7;|g_&65s9P|H)LH#i+~QnUPQBN04z5F!gZ?M+dS-Cn<-P^kq2`6> z(Rix7#8Zyk=4bHVGaRX7p!As`&A1sLlCP57zWJx^$nT!xkLlHZQa26`t2csnbwn(4DD&op<6Rma$u>}h`#l>$fjE$5wz3}>7I;5=uYU`E@e-rpRcl3w_8u{L?r`7C7RWn8 z5hB-)4#f+(Muj*7dnqp3+r~_xn2RTk1^Of1u&2V8J9xU>1dIYA=GzT^#E zA}Cack+AcLmW+|2r?RwkGOM%?-z1h-YMFpkV9g?HX=yp0(b~6YQu>!DN{IbJ zCA51U`1t_LqFtNhS9RjMR0jUM&bvux0BzmaW$?wQsXpR=Zi^J$@=Vly^XPRI=pFcaY*Vi2GeaQ#lNJ9GKJ>V=DSMsC>N^Dd&KnDUuIRIk{ z0mfTbM+Zqg$3C+>`f6f0o;z9jX-MEPeZkc17=Ux|2?}ms(dqgrP$-$|==e^pa!b$X z?_2Za8bEii&!}m}f%!hT9sdJ%0bew6K8gKjcmojXFCMgDTh>Y7+@J3>UtjIH_ZkTJ z@0&L42-$_TMDPUcs0s>Bfp7MfS!p7GArRSn^9{9cN2#3K&I|(2$}NrnTq@)5Xpjn{ z>b0q3 zk++#y+mmcuoq|6StXBB4gg%X8Ry$c4K$Av0TjMRUAFM6w@QKz~E{_+8rGTvft11II zvavO^VOSu#jGUfRmZ#(Z6gVOu5Dc>+s#vO!3D@H<81bq2RHLP#XB+m$4z$qP@`DmouA)} z2f^QhoRNGU&JOX-Qjc*ylp)+=cktF$3Y*89n!H0Aeq{O*xbYYP0`eqk0mn5xwpq4( z&>hW}))|XR^^v-=GMs^>gRtRDird1O5_H+StnF3@2-q*>zzbNM0Efy2a8lS4qxFex zS;u-ZLsL##9#jHu`J8yg>7*L2OU=U9Sb2L4Sxr9j+fNl@R#Zj0nGf1A(wh<+ zLmu3ntYDyGK2kegu^Qb*cB~z1vv}tO7k&jhU+IXsmWjv3B6W(oN-s(KmCnE~lcb*X z<7zqIoIABka@m;uS14ePUqkR$zFY)y-*^PDoJ&iV4>=GW)Q0+cVRL}-1TXm@YTVX) z$(}qph93Aw5(XZI-d^QA_|)fWMTxW@#X}&FL%{CgI;k#l1c2v9H_H#%%Fo@q9RP8e z@0BXn0ubU`nq@JQSpwL8J$8=^R4XgY_x_P?PM5NfeTSJoKsryT0f=mZ05 zd?0yHG&!vwH#?LvU4h2#bpc-MfMv!j(*hGNJ5d@qs_=p(iH|c&brztP5OZ@41d}3C zM4Eua+|5mLvCarXnylvgV^f<(!naoV`WIr8RGao1fK(a7Jtt-Mxw2sKazr!L=wpHL zSaz*vsxr*x6Isq+T%7T%-r+JKUsOoHc(wqW47RTqA8kn)ERm`gi8US_n2s;Qx_qKX zB&Zw)^KNt1)?1fKN2Fg7zi4eFFrE2?$3AhjWYt*!wV_quYanx9H1U zCN3CC(T;iGJb@5lhTUA2rSd#2Hp1VBp|W@R-`{LyBM@@M6DISB8GRH#3S)FZsI7KBfiMcHeU*^Px1bxW;* z_-?_F?Pkz?IxsX6)9%cBMgWARc@QQYgx-4bLSXq}KIp!s(+zrj=DBOFopXI_fY=gl zm&iuR1p58BB}eyoeg)Q91eQxFSYXHc(6it~$8i@BA^=JR(4;8PwhIB3N$c1K3j>s$ zsO$p-2(x^8`d<+tNdF&8LOE$=3QnVkr>Fa<&@3+qG*k>^bpuJ&bM;Qt6lM_Ozn{Qc zyx@N_N+ac;?kYMmK29`Y|LJd1EI?&teQO3#U=94izuMmEqm+Mi-sW)k(EQE-QghK5 z;HDIV(HHS1`nLnOVym(S5B4*+ER%Tm0Dff>f=Ki(uoZ0XR~L@mB*|f1>*)u?6v)QD zZ&$Pm|1DptYfj3dbn8};i7N51F(4n>kwRcSL(<6g)Q$JLV_{N;F{S)!grIM$EgueJ3V>)V-) zb{MQM2N!ChfGEndD|x&to6gMq&ByuvVm_tL^u#I!v9JNc6y(Y!A(shTu-7t!1`5+Vb0P9hw;LRDf3&d4kxldfX(dT^qegwhso5wvQi443&Sp(9khcC4Wxb_DBH5Olv^X!`dCZ$L}UR zS$T1UvAr>R!GHqIOv!Kd@vlIEnig2t^%g_**nmAcm*r;Ksrmm~^8b?Oog^;-=#}0D!Zi?&)8m|yHxM`r0BX(4Z=kW|}>FQ!Rcljg7(wnUPLO*>u{q8;wZrWMdR*>olyNEROaD%cOeGYVn~F-SPEpj(;PB`g3owWxfyk`rir$ z`tjdeAUgG*O|C)tSFelg`NzOy!1K9vVGhF;D3?BBpU}h>q`PXNfg89NuYd*iuQi6c z#Un$(9l3xAQ_Cy)t9&dl^6`l&V7L9R79iY3EjQ|4^%5nnS4E4$R|AI(1^QQ2te-Xc5i zGr)%WV4Hiit$O-g?~4=o#k`{<^nu&-+oNFgGY|L$sHM5&1&38dbu>&lEIOH(B?1cy zvUSyfmis^G(vshy;4cap-uSro8*pbY2U5mHv2B-}Q z`}qDy6Hc?LNCK^sGR+Z@C$ZYv+LQzFu;%87LRFKJl9G|=Y66m74tZ1H9LdufVDmLV zn6gQ8hMRLUKwTN6%o%7m0x0fYENA~NBftq_4`usD>aFtc+WG&i zSmi0qx($N*&r&s(B-B|_+K+;r5h<%;w13FHYgE7CV#u=LmldQcsIC2BABeoN`SqxE zo!f3#3P?u;tN^ti;uQoPSW;N1;>BG1-mh`n1}nrX0ev_NQIxAnv_ihd>HPS3?g3T> z^&^B~Bzt<1Nk3qD!p_Ad@ww7Lg%lA$j;}r_G?sbb_@F|PsBKH+@&c*b@-2cT(h72` z(~w0i6fy{5=|vxiTLg>Nwzv*Eii$~Ut%Gk2rr9FUsp@GxL@uMdE}JYV&RvQYT3es? z=S%oPT9wTtO`dQGBH!^)fXH#kg-Su?H8ItFELc{2EJ^_N_Y1z=dL>9fE_NpSB;RoX zgq|M%LV7f0J3?hR>i~CrKYYz9zqo2hY<8*>MVB^G%ys|jv~PWiB_)myq+HfAOrA|z z27@a$70sWIi)Xy`{gxI_YVs)3avo*D_sQ)j{B?FpuCQAc5O@}vuyJEK&Sp4Q_wD=l z({x6Vbkv58_(ZA4b#GJInAg>v9SH(QfH++iRS4Crj1L+J6npkR<`gZ55F`g?)5d(t zU(0dA=`=+^1AA!zdo&wmr_XQC5()w16x9(p%Wn zRbF0rd636*Y5;^j8gXx@5mT+*WYPuiO_rRjxG33h%e8MaMJHf@Nv8fdUOs zH-^w|Pc>Rl=AwTmE^P*>qcj62o{Ni1c1!Xrs7wNGO0;zvd~p;XN8j31NlEG0k|_l= z%_c8&{?jF}`RQx}S(<2dUhGB3z=t-!ZKLXsHC?h#zUt6qbOfX8>-UI@+b^8a@Q_iQ zK)AMOs`?^hPJm_>+cQshmxhim|La#WGp=d^VI1H#Yw;WmSe%_L4@biCw3>38vMw*r5J{RNnzdFaRuN$2<6F0OjBxVoS{`)XalTAlXS7;bMbyfOUq=dhdR zSBA6I#rZ$opq$R{pOF!OEo5aGR_xD^2G5d9)_WjaFf&(o1`s9u5lPSvRz#UA)t~fQL0n19MG{c85-Pzsi{( zbq69e(H^ST zxtD6qqy(PZ` ze7tf%OZypsWOIUtfb!VsA8QNJd!R>M%@g*4a+cZShmjwS_69bslsU8G*GJtf+ldsJzK=O!hFHbdB*3A8pdGNMx$z`r!A z>ITDcdBK1cr8mS`*xAhaD9>S|5bpEJD{GmhCCg2X%h|Bvu>wFYk13~Ck zMY~!6M$m*GCgUJL(*uB6gu)5kyF;?e{7P zXuEQltC^(aU`mi)S>B-Gct`NZYCaXE8b>w;kQ=R1qTCAkOJahlSut+# z@!v)Dhl>r;sfaqUXIATJ0Jq{$V3jfRz@J|KAOoqXO}}kvo0HQnB2aQpE)EQEq6%Wq zk&k0V;^9y?y`;KERdRrFUJ6`44Y_L?0W|2#dU~- zEcD5=w5itm??q$^^L@~B<<|1>|2Fk+nf}jutIfINGBo#LmXwrK)6^7CG7+WOI$Zq` z_T!D600t0ylr8`l4K0T?Bg3X`00TKv8FS&*vJOFr|5J;+Si;=KKkoB%x%NLUJRA;G zY5=t$dBp#-sdeSTKcqJrkHvVjR zO07y2f6xj{N;ZUY$gnbmucMCdWLbRp5a<9|9mLvJ%Nm2A&?b>GW54Bd2u6>ODltxZ zWax@L0&%wLzH+j$d9Jlk*qRMO=_G`>#)>)F+fOwE8f{Vxg3ndaQ9tmh)^P+JITq3Y z=J_NTZ#rBYvLsyH{j}=$d_T@a>Aq@>u9sFnw@4JXJ&?gkQSxo#C}NwNjq59C z%A5DDN&9AFd|tU0xbVj>D5(ovyPkolsA!^`H_z>A>Y!jcrouu3g;{Z_EfmkB@a=kT zvmaF8l~g=Oa-S5WI~zhh7QoVq2`8;oufeBq~6Qs)s*8UPG7 zJkG@|z zWnbuBSlGU`WID^(oe_}_@blTjBy5?fakPM0XW}&mT<=mVS4XTJ7j?qTIP9_RJCiRZ zcCkxJPr@_Wlk@HwIvFgd=4BbQMUpfU1|=te%IkxL^O(*B-+a&KeeeF3 zzV+UzsVNN4Leh&K0Igo9s{D_9tMlL6&pZURLHwXK1(3&h8nE6>6-)JgHZ+&j)a2QL zfUw=sqZA7O6%`H+&ZEd55Km8jKEAHMX_(8^DUxmeyCRX7>LwpUAn7$9pFI)QJA}{j zZ2ZJo{sBCR1}Y}%LeV58?Dp2>e;ihCe*Jw`?td-8IgntvKlW45sAJTC+t2K#Ea)!^ z3JOr*ioXE|oY>Y+7t&unXKK(`Jh8?QufWVTei_ylNCsS6GKa!u17V6lOz9dLj*X8q z0Ie(>o**+3cl`SjfUo2l6si~=%=n}tdc+4oE>C$0Aq>h)AP`AG5GjWY!LFJiJXTO4QdxL<`X7TjZxMRbsDq zRO@BggahdD5Xm>leU>Whk@vTR`1n`}3n{aEYu#dT7iT0mk;cNJGIoX(@kgSzp`ir9 z7~|D}=qU3P+%^nPtRFToLihGi76hcWS~U=IBErI3jg#r-xZ343Z|q4nITFAox;*3d z^+eF^%-q~$iu7&Fi9v=wRbszVbcZhLd{Xz8bN6_Jfq^zzybe@_kCkd&nMM7j681@U zAb%B%+1lD?xg1uuHE@eLm$Q5#Eh7v&(^O5>3Op4v6Bbo|Wfw_0i^Hp>tLmgp3>>y7 z5<(yq755YlCu8_xIA->~YLRwn60QYSJVf7YX~CCzfoVb=Rr_xd78|?}1z$%6?psCK z71gF+=!x zg{cDS@0JAAJx3-NDQcH_`1W1+?1)1iZ%x3~ynWQW@V=s-+#8so?IMw28Bhn+G$=F} zvUbaHS(s3n34Tt(NEOc~D%#l|;D>$|kHQO>K}5>5q3eULg`^3+XiottTOWawm3r^h zt)=w;sL}@i)4Lj2cJ7%S_)-8S!@UZI25OhqWKLM)hlc<=3hPp}r7?kxKuvydL23Ob z@eW8`;L476`%xvWe-*Y$nTnA<`P=uRUAS$St!JT*mp!doE3Y*piYB!zCk-nr;>a;v zTXv(-{r@CL|Me#wdIi##Fm-UzK40_ec1Lh?yiv+>R2zs#I@MSj>D_~ zS<#sXaL(H36dPp%Xol#Fqq+wX*@&p;_Le>Jr;tgohFRwN-cM#&>@Om6ltrL{(Wc4R zzixSHcHIPNsx0+S0F;;gg{tw*kjw&!1koHk%E9E|BFVtZLq?q9;_cm?wLe-sLV0wv zCunLj&MV<-prRk)cyS3-m8E}3Y)IBQ#ctYkLd2oyVG3XyQQJ=|2(?@kiIHO zDsrE%H8J{U;HHfgS-aN0N|WG)fpLnMSjv)8Tay6EiJv;YTf$m;dI}t$zX&O?uBcA3 z8G0m`TUIYvfChjgy3zo3FUDTeZERwijb6kg3RYXoq@`Atesbi#dmOsWFk7jbP2X5m zdK;Kb8;@em%GG3ms?;2!2`O>BDg8hs^~;l9kCi z*xyfj0BEIlW02Uq} zA0Jp*30_a%(=RYpQXQ^o6*@zo-atH9D_MWPdmiLGV#6PDJ^vr0%;!==ft7lfWhp@P z4j5AXN>!_UGfJA9zZ@UCKjAU|a|N0g?-Jzf#7`&RI0q=*tYPk!xXhr5F=_u(orL=d zSMHhALF{FgB7Xn#dcQgMn;ge}bwbZ$c-0)-y-Jy-6>U zs{KUeWUU_E|ES%({z8+_%t+ZuKdT%j5l{UZhd~HlwJ+A$@t*$egLlNo7!q!fom7r! zRUFba;*Rjo3bI8hI!7vT7x(5W4MCE1el2jNXiaa?TpoHOt`nytV{810ochVh7)7eq zQ+p49s<=8vTi~b6@{4hG5uXwt3bklT{ZdnM{uHRrEB@}oGi2(obRfo{9i1WrjRkb5 z;<yPQI%xLdr|BbOARhuREuyM6url8d^n zmeRVNY|4UV!3vPfJJ~Fd-gYNpF1UP}Fqbq*SvX;mW3CcL<42F$PnfU2Dy_snL` z=p{Gs9?tJ|bGVf|M$zR6{d2Th7%Y2h%LgcQpI$V=3`E;ukY=&8G()0jg>59rYGK`~ z0>CBX5)weU+eg7WtuR$UB9l9Ya(tyhriSng0^&q!5C2A(0FVQxR+T}g({g)2m>lB_ z%e)<}3fsnO}MgGe&nNqH%9oji7G)Q!{+oZ6@!(XPs8<^e{fb z;eP+Qp!)++EHd_L!RuiC=m3c-!gAfTQw|7(j?kXePq|+GBrzD{vHQ`=R`@0uZ!b}* zKXaeznf7aV=1khhU*ND7f@0(LcjVG-U&9WyJ1Zse$w%u<7bOPiv!8xVvAREIs`PJc zO-#J|LAU>cZS@PdEIlpz>)s)+u3g23<1YX0IqR6~dcv!ivZ1E;+Ndqrdv-2m!F7fe zTgyCg6M!0gt zd_9!08_x(>uSOE{Ndx8{I1fOI4uwbYWVk04%6ojLLsaM zRn8tLAks+ghS!TUaZ}z?3<<$am(E9mRvEKqVpXo&}m~^mIcs#oiXB4 z6r^I#Q2R(lU3k+O%SHcN-k62nUKh1~;?=f_oIVD;B>3EIc5*9@__Z53PsB6D%%NcP zXdpQi7*_)C`<@d@yn+5Ui7-0q=-*hO5GI}8D{fAXX9n8Ik}f9HLZxILN@lOZLO&r} z&lf&~e-a!+Uupk<#^6WW#=s_oC2GG=h*EFU$@b{^v*$E;>HyF4TK_5PK#0QI+7NDe zNVO3cHrZJ$+LL2+UOnJZSy)X8s%0t3?`U#gm&0F-@!?~Swjsi)lD-kcHM!* zZtAVZ&NX_J?gz>)Y%?_UR}I*dNBZQR%x8(&p0sI7iD(~(hRf#vp7J?5JAt)XcN%dC#-@V`A$3UDMNNiYNQk@_nq zG5A5Lm#Va2* zN`O9~MJS#56u@tcESrJX|K&?&zl(i>jaD{G(2?=ne<_8wno|eNh3vrVcigRq-D%Bu z6Q|EUc`6CXg&l9kV3Tlt%Ac zc-GjuP&6D2-pjEV=#Iv_xU5!s{I!p#6XVSJ?~phfY0ES-|9~CPzP(5VAaD=F6Ud4@~|NEsyR1| zu)~r0pbCGYW5b90!B~1eXM1&ScBJ@p`*Ic8AkJj~WZh4(r$=<|7$+)jFUHfLdWI> zXHCGT0<)ux4D$q4qF-lpzjS{9y2I<68?f-$rj((hYq@?;g1OfC@IryiJlZTyjn;gI zzChCa_;VVn$migYv;d zNMI*TJ{TPbz*&v!%BFX6fC!6admgigKfkIa?MRz|YXETPIGyIRAF{frxhynB*VMQJ zfEDd_AK{bFK`cM0`4wiTrm`*q^=6e})41*SfIUcfyI`UMx4~a?cKUCkg@`!-oM4j> zgK24LC)(*39X=l<^MZLOgocO~x3{Cv%^RnY^}@~?W-R03C1u42P~#LTj|FUQCW3g(Tf-U}8gzgC>X}TG z7}-}(8;7cmw;x09^^CTSix;G8c8ifS%ok13nR&h%9xq-JW&}eV5{D7Gi_Hu-6?)Rv zP1C=Z0)uJA>k+bw4mqLH$_UJmv`?RE9Q4oIxi5S?JmL{`#C0fuEO+tB8m~$5Frgg} zjao!VsMgn`ytXKi0s31S2n`|l8hB{w2ltzpns5aq<=F=>eU{9D%ah8st{#?GS~}wlZ`0H0e>@fG6^|+58b%1c`oAbTt59!U0O!*-Iv0m@hn*9c_H2kk}>L!rPI_7nc zz!UcZU5@~QE=!Qd((bHF?)UGXmX_##&l7q}c|q<9nmw=2#76wHJz8c5g@&x(@>3#r z5g=ZuhVunIF=4CMf%B}C;ci&Qnc`(I?ue5PjNqk;J`k`O3`J#?5< zq%XS&YkW@Lwg(?glS9Iwj@X=C9b6pF%Qbb*ruqYWg?F}0($~A;6^}KKbELgL zj_rlV2i0er%y!S*c!DR<F16oA&BH>zTkuhd7j+ zi3=aj24WX3LzR30m7*|L`D}AT>0iC?=m6;NmCOIN+ZM=~<9Ba8MqgD?txYhjsr}fh zO-H5@YHA1L3MTSIDamy!=%X2~uAMczk zi7~(=q$dEG!5fnRI0gIwXfJg#TAw5GwY@~-zfWoJ8q}8MS%*~_&bIdDOZ6G`^v#2=ZDJ7#IsM|O9du|dy zd8j4eO_E2~)b2jIxKwxoaGoay3}I9F%ozrH8*ulwx3H2+p&T4h>p z^1T8!>v3{AFG}Io+1;jm3i3ubaj#6;wGo{!(K{0YVGE&BU`D@4MR1ue@n?M3uDY2n z1COMbHTTp$9bw|JWu5-{Q)k`WtDO880ETGdIv0AC<8y@eJerm^N!j56f3&%s9nn`N zX3a1=XA}B*eP6!%(nvX!oF=ov_KGhXMFAuIElCE_uzVYwzQah`IZ&=a-t&nTzpHKb zrDVQcXb)Pbk4;&Lu0Ncpjl0DI)1xOV-XzV0tn_t(L{XHcNXQQG?wIb}`YHzp$y(`7 z-`I|uQ^2|gZ9Ys*JY6HDgi?K<-8`~M*YNZ^DbqFNOmCtZ;w_4nuSUig8yGm#Ous0v z^HA4#NS}JVbXQQW9ar3)E-NFn`X0EYc_Nknt6Xe5^{oRn-mMY_JsKG`YV(C4pkD5S z%xU&PZ~a&s-)^o5Q#ayU0xtK`(uzk^IPqwk78Yl$>uac-qnTe+uW2Z_jW@bwP7rGNfkEr2K=QbnHEyfZwl?hv+h zsHVQdt7`SrC@)EvzMT2;+i%CQ3es}YjVW)HsJk2q~p)1y4EkYKVHvdy5V zL_JMX&v0OJOl&<{k$hfmhdf-q`26Rm!smaQ{W%5$nloGANRSIR|F=PgO@Cw5f|9P_ zg?yYdgu=MERu^HQFk*_*4l0FTc?TI7kZ9C$B%|Y}!l1Xh+yd94!X*GHsiIzjJvz(A z5E$6*gT=!3HVn*CdwF{DB#W=n~LNCG@4b9{4Wh;{f3 zb0WGsql4)^&6AS(-hHBKPZrD)s@Mf#KEQ&JNf+(*JMvMGBJVca&rIod!pbgZ^gSo$;I(0CLFCHEM`^xHHnYa>uII-F>rmr zWx(yXI*+|g74Y3#!1zZqnqxC8*@X|3mT+*j^oaOQ-DKr9tI0Zc_;>RK8fEj34b~0J z4fC({74sPVxpV~h*o1h5cyUZ{A7Y~zJqK%G}DgyI(y$K(B+j zHl$z(%_%cStYq8v=4WlYk8cLr6(d|!$FX2l%GLxx`V=7M(z0cH-msk-0v8!~PV}(e zM$*Hbs~>$0qDY6=&_U}C5i=H;MBpVbrJ9Tg>c>E z6YFNbC+<^eVkvg#W1QmxOSJ%{Gez4{-!8nmpu6^fwjQjocyO zt~V)!DO-O!KK)v3h;c`Hc$zu(#xK8nNq1>sSR<>j{HR#I!6_0H~fxOOEm zzh(s-c!MImmr4G>x;_ez56Iw0(QhPdZQ-!9v)4yaKk%wl#apWXlzc5HD8LSvsP|-J zxK}(=i>Ad>Rxvg<&ftiM^NIA$%2j%iN>mXnU2tvWSNa(vjaXbv^o5u7?@H>J-rcVO zjgBmDN(m(R>#Ip%*NmiSi+9eq374eg+@(JPE6~%TGKE@~rQ8$=Ekfr-AKRH&Qw_AR z+eW}yNxcAix=Rt{^>aMwJlDb4BrnG5ZKd3~3&IXs+pk)IecJEFNc`xVgzlc2#SQa~ zBXN*9VfQs0B3})EW=AmBO+p$ejX$mNZmAF9YEJNb-Pfw6Zq)e7@gf^ z@uX4Px1U!CiR7~C(8_k`h*K^ie;4GyLIWm6CK6MYVoQE>QyXIbiP9%2w;UdWcN4KK zz|UV?xkj|FXNGXX>jY#eBFTcKAgOOM8qtYK)E{rE#OcGBz4Uf#@Kp6F1h9WU^6v^u z{&43d9XP+Usm=!V86o{mg|%k)Wt^B{_N|6Em59;DPP|jDbEb~pZ}mNUw6tQ7@iwq$ z-q{oL;=4Ot_~N6@2W`J2*VosdMF;iJZn7%0w1iF-cQ~*$((_8V`Keciy6?Teh7)7g z`vv$3$&> z>*MZVe3U{1-0ZcBemx+UDp*Z7clw<7Bgk*Xi#dPq%>6 zl2>XDEWP2jn;54ArA5(P?~cv5ZAIf3E{6+9$>IDYwB$6~h3Ii|(f46X+i5^?xFixE z8nb^=8FqgkEvxl`O`qhoTS@8R6I!VN$nRyDvCWn4v+NBd9vZ-(v5xK+#ZyI^Wk%v7 z?PGuT%$k6=kyP&OZBm0Fp{Av|EM?02eXc<6(tBavWTUk4E4d-JOJQ>CqZ>mRNwDwx zh^@&9vw;KW%B(C|R94G>?_N(HLVeb4w)%N=4`h$UWsM0q1}x%Di|+9#s3Y6+Ts?2Hn5^>Pc6TZBIvDeT}|Fw}$O)+x=%)zmPNw6A+44dF69@6d2^s5!T zlHar>-BCgD$80onOe62K%v`+|=TEMpl59l^RU7S9jgT`tAaywJ9(C%_Bi8^rAX!<% z(lVaE)6>THkv<&nCx#Lk-oJ~Di<7lG)lie>&BIWnw%~y{#g%%0E0%$AHQ81{#9Ktn zG25V|r4XYdHLz=thxp`>I0B8MaZ#0h#@O$b5^4v@>$a6Y$c`q zk`=M<3WxnlDf#i$KTgb`q6RGp{-y>=eymPBPP9J7OW%3{v7~dVH}u?2jRsS~6vwb5t55`Ne5vB%<=YHftd^ zICpPvZ&FCx@F_|x^ZTJFmkxFT3kYQ<`41J?RC8wiQYU;Mvb$8YYriIwGF5nt2YVLF ztgysH==74Yc?@B#nQHh5>_ee-W>b_fXA}a80wS;k;df|K)zL?7U}pU-p{T@}bWlcN zr!al>5WSQtSB$!%gZV~rhk=Z%H%F;j1_UPZ*IwJ4;O}iAST!T*B*$rv;K*NHRQU21 z4Kyf4%;1v(IqzZ~QcN4xYH;S`1M(ha>&XD^5}v)o__)CDH0dpA5;C&WB`o+1iJ~Jz z&7B&&DiFPgc#*xs?(R!HA4RwXjuAh{{nuX=*s)d!U=%tIBHKs-r8<5|pvwgV`yy5% zFgVbO=wN3J4eo{p-G`GpCEH%tEuoOL%!xCbYApe1rM~ICcfPgS_2Sgj29YXmw1Y!? zL9`SH|D7dgX;2>X{r}c+zs{TZ4ll-^#jjhY^VuC+*+n~P?4NwptYu1qxhB^Jfcuho z4i%Mo3_kC-Ee!j{oAmnf#e`Z58}b`~G=lp%{@F^;d6e!}Asi=4%5(P_)t;ng0dMKZ z^Vt3@CS%}h{IhJ3dWX}#v+e{XdwA^=sm3|q=SddD%(l0Uinf5M`0@Y;dQeR;;{#Q% zf8G}V&D8Zy_%F{rEsaT$`0wY|e}9g2Aa*hR`>TEZbg5SV$u+(w=d0oV)w)v64~$Nh ze?ZG)U359Cro?75U*0~ysBMwipYU1D)At(zM-jNDZuwEnOORYJi#&<>Eu!ho^RGeK zIFJd~1HhV^9G1}J35T{zq%czFpLyHyd;^JP6yFJ$bo%l&alXT!B0#A^f|Qf&W6(?Lpxl2Uo|=)EKSMQDH5#RKl|upd5QvgHI5c?{q^nJ=RG zK`0R2+JiaI`?Or&ztb=>h2VW{yw^u~0+WgKIjbgvnt@2*r3Qggmr??6o)ER+PVkS5 ze%f)DsTs1oZxSY+`@Dqkq!{$*LTD7F|L);z&m6{FU9-+;esia>;qst50wH$7mU%G~ z(2)Jpi;&7Itkk3*zKcG&ra7wD5&vd6$|$8O?D0Zu?J*H~MZoIAN&NJ|m6x<}x7-ZD zE_JTN-blDg3uFZlIK9u*BOzEv6-ov8Rrs{4Lhhrwm5 zoyA1tB!B6>dL92CkCz`>zNNTOj!Sac^Luj(=I}`scYWjC8#Q-d+$sw9{g*&kc&?m@ zVnxXQ`F~sOm#GG`aAMANwWD7@4x{1pM_c^=g}AOfV0%m+z3D#|+YIE*(w5Pb_|60ikx1y60u%|_y-uR1f@-+P&j1=TBx-j-%MU*}v#VTu% zODnlq|0yn0PAMx(2KP_tqJW;!eFkff{LD80OW_svYjBdD%9rJM7oy7(Hs6PyHN+J` zax63g#*Ha)EbyzokjL$JZ~kys_pgB_389jm8`arhm+mqar$zsX-a#BM#@@(W6D=$cI*G;~yFT8a@ErxWM1eSvx-oL@Ot6*IguUVh?dA!Mv?R^( z2~D&btm`m81SQYi>K~C~s|Iup)kH7}o+o+wb zIE?S_%uMR+QpDi#x4kqjUjx0qR|SECqods8^e91HA_xuI=m@M0tHSk%Dr9GQ>srw` z^zGrxo}AE`lR($UDB}afh!g&{!%vf+UfMi}6X_p0OL1|&m_dLKY&n(F?IaqPNRp}2 z?yO!~JYz}Lpj(BCfK8bRcFiwkY9CE+>(GXkbgsxjVwcSHrkgozL*`QdIO!uG8dnTO z&*zAUaaFBCj}S<`b8deWt`Ox1Nlgq5Z45<`4C!3qbCi}Xs;l=sj>&5j7G3?Q;(3#_ zR}+JF<4ZjXI8b6UBaezXD~ zqz99h?qO*Z7Z2UOzII(&URKy|*FLESt5LOfV%O<6a5v3Xtp8-?%!pX$Cww&K#y8PWFM z?kRTg?czf)OY6_W{sF`C&mRglsQmdKNr?ll*p#w0{-RlgB)OdKm_F>};xo1t{|MPf z-<;?Y9I*2Y^58CXI@v}ea(R3AT6Li_;P=S-_E=B8UL4=@GU>r?VM#1BcjvP3g`vfF zHBUYxfIFVqD=BmqN6uOGa=a~a_l`oLP*3k3%uMXYAWqQHKlhXmgKaQ><8{pypBmu8 z(fPCkYd)|hHGO-2Mf8#$G-l`yADk@|9#Is%6-lW0?NkBTX=L3x{3V}NF5e9~gpkR+ z0HvJZ`5K$K{es(|MLAwOcQXeXW#aws7SIn z94V4H@@djGXH`>9UkKcM?upY=#I}Ll*_mT!hM=o@-AWq~>f;YmtRNCkw zTXJWRyP{uMo(BdlgflT(-D7Bv7xT~H+32?D-8=M6iYw;*vw#3e7i&XI-d*!o&tnwy z29nJ5d{XIzvuOG|k-(zPF{E7EMRkj(=4Vn7LJASDb9|s%D|_Q_$w~V!_TmtWIxDB7 z1bxMJ5-(K{l|cyaT3A%*a{=)|K$0vYIGwfU2M1H!EMe#%IRN#6nW5vy-$6Vomhsz3 zJklFK!cQ0PnU?9xY-nh}4*y{%04bqt{Wh9pJ?-_lAUG#wRC`&>#57KIu-B^y)Gp4pc^P)f(p9G?|>oWuvo z(_)vr$J+nt11YEs{kvjIe`Rc1oaK)yQz2}-P+vHM)a%^uxW8~6-Fb@EJPenM79wVA z2%-5vpw)@OY?v-b9Y`mooopUhKtFT=+S#&5Ub zarYRC{ey>(AD@*)PDoJ_ao$*}De*S!wiF(t-tV2(t^RmF)Y^KwvOFhgYR~)&gd53@ z5t1@9)g}0OJIfG z^DD0@)o1~VqSTdaM!?%E{O@Qb{P*rQHf4GDv!ayMHp1oMKG`-F!r@-!F&`VgclPn4 zvJLW-L1|x(^#JXg7&>ser15si7NMksN`3q&VY0KixliLqsWmfLLjxN%1ZPP-ssyd$ z|3Emyl0+B2KL?&!UK~Roq|Lt6r$V#!#oll$jk47jU|l=zxW}&uYaN|2$tcz*YKq29 z7k<<7HC!;9iCkGc?{^`4ZL`b_SNTMdC_R1F#L(_BRALOh1-IQ_%#iZli4_v2L;u92 zo;>@aI5a74wNgiHnR2~s^O|dXh+*f8#{Y1i`f1F| z3Pf^;QU`##E=yim)$7N}Djyzyign9kT@LajIX+#4JWKO7A5sZIc>KDP$%0e4x*%m8 zmL}Qy**Gt~;evPWvEmlr;40cK$4nl{n_^WytMJzk&8pL^wPj%N3@%~%`ST2t^JH5M z#!$`C@pC?tH)VM-xQTehadj@lWRBV!pRGi>X5&Vp+UYs+xdc#bwFdYNGdx{iEK=_~ z{!8^>cRq|Fy(+ppv;~bBV)=(5?k8>h2^(J?bROQ;WV4fC-khY^%h;aWPI97fxvLlc zIfFZ0)Xr7~sZ==m($>qob*W2GH(57Wt>@y%5o3tIKFX+7O}XhHP2uOd5@VHlwEUAU zO6>yP{%JVMmT&j7fk+Ly5~o}OX40xFj%I~$W`OTC>GliBJ#=#aU;J^{)vI4vEO``; zolcMHIn^Eug@Q(Xh-QE{Oy@dV%!3WHQTCMXir_wQ65oc-;icBPY9Q0UEO0q7S-&T7 z-8}4nAeaAk!+u}cU9i;bVsBcF&@C3KQGuGC$Sh)n<$Lt<_MO*)Cy(X1f|B2>R~9MU zeQ;4h6d>=Jd}bFFIea0Usj(#{pot ziXf{}1$+iVfy6$yG~pMcQ}LR>&lwWxD6w>;m}<((qNb+QAt517XISRSg=Cbt-aKF8 z-8|wyqyiAI+}F{qjPR2{t4F>+-@~s1qftNN+%(S4O%)0B%S*py+ILD8IctgHYt{SBwWNrpWp(aXvA{1Aq9b8UpDBSy6#CXQTra3h(K;Qp?i|o8p=P>1bU$ev6G2rqw%xOzO zykTf!cAD1ZwvSX$bnkWFaY-20^HM}0MPLi`TH{62WZ=j8O*rR`u~PV4g@)NP>=svv zvg~|utcq`01LQ4J;v)?&;ERZ7o)erbh=+$iRaYCgcSbjDi7LLYH-ugAnK+Oj%KLM= z3*Y`(dPo>!p}yB=RuLH2_Jr(C@Sa@DgP>^H);UeJ^IHsU~r2jZX*XAELlm8m>fuo#K_Q6W3>BJ~cO zIr>R@wKr;%=dYV`NU=QJN`23^4PgKeh$qo}GAk3Nh0O1IdTD$3NEdM>cUhbD-1Zgc z{!^rVnp`8yQ_okgtwVc7|3@4eynMLcRG)E>pyybmFA-l#FpRIr)(Tqb&@ZX*(4>E3 zJ@Se^n|imSx1zVMm8m@OovXKShI-)PgLaueer18_|I?iPmp*!9z%ew4G~7#v6?)vJ zWP?+*m5CfTD@zfqMrsH}2bKEOkfS4U{S*r*pG!W09G{pY6%4b6v|WA{$8(Q|=tj9QohxPn50Nb5q90nHTK#8(JlOHgDb%THC?gCRNRGhN7|G&0n|#sv*S51r@3(fe;`^(PCuiX3imP3P zae-_?iSPO;MiCFba=wSR8Z3)BRQ8%7!=(Qi3SlE|(GR~_K&AUVX(;lR2_w11wX}bQ zi#eFn3ls|g2PEsiSb~jEXKTyJQu-%U)T#I{hE_*c*ET4B%b{I)ig;NxZtYZ|(_c5p zaHfbNqkcJ^XgfOk{@!XX_C4@9<%Rreor$Quy{FM ztnuOtEG?MNl}>Jvu9sWmSK*d6Yt`x81Qy;u>nbZ-`Y57!sFm?YO|1Vfqx9_)OK`ME zcwB&Q5;V=6!)}wK&5$ol;K|3Buyu!tF;~==Wq-JUZe84T6|>dZW?}xBqVjbbp^|X? z6#X|hy^JoF8K~$tjSSXjFSv)DP^cQk$%nN4xU5A5aeeBn6<=pTm0ZtZmXYP%T*UW2 znZF@($rJ?JY*+&>Xr;&*d0=03sm2}g>?Wcoxhu^ZdWAd(xExht> z95MB-867YLf()@P<=$t`O7DA)vY~(KVx7e~_X-WP>8>HZib6Q%>w4-~yMtcWg)k1~qDJq0QUxRb zK8yi@nWZbO-750*5`NiaJXofK#a+I>BKi?HefYIq=d|OWKOX0t$~xJnwA@M~r6I(X z|L{-$%fi>jVr$LM%!mU#>Goxcl<>$PDkun%Jp~sXNmfaT7AKq+u5ia6_W3nMZ7KGH zxLr$VF(v+V6>5I<_KA6;N|lFuJhk*G?;epp1?=<}!4w*YTY-?jJ8xB`#Ca{)C>A`l zae3YsRgLatNUHC6uz>tPd*NPy*H0;pMJuZk>iLczaV~OJqnI85r1c3%fO0CU>`PQPMG4p6)HMkg zPfve&zVczrd(sP$Nk#vHC8=P#cqkHO>7#V;mZmc9J^0q%cN5o*)!v&PM?DB6mYeHq zfSfZX$)AC&9hiD#^0p2C?ZuO#j0>d8=sO#+8=+JI8leh($VIvEmMWsfuw!&AFwud$ zftV<4ZkBK{$38Aq`IXsWu()dn#0Y0Ke#bhqgNY)jr7blG&-@~Ox&g;A?Wb0qchr0n z?V!}-i@#c|dO&%zl>5F&P8;$V%)9pG1au43BA&7#^$&c+dgtyp2i2(TrBYX((#Xi% zJavX1gtQJ-rfU&cp8n6Ucm)NQ2h2kfmD+RXXZ-Dl`w0LIfkS3RI58{G{_t{`bQehe z`o2rn%S$9J-L%X1KeiefrH!xl2V$E5D^ZymPrl5ezm3mPS#qf4dt|apb6ji&XHcwBjqQ@lO+z?`BLg z1^Acjx?Q)lF8OOLr^RM;ZuYaYvJ~y@$pIS54uTxP9fnax$-@(~w@2nFNUqCT5?efo zUc9Uu?EsV~VA72yTSv$#MCRPp0dEk-!W1v2Y66@W=U^|BE;oG5&4l8QQqM~4oDvE( zm7-^_4-5?Hck71s+C?4u*^`5S-&(!9{>A?yZR|-+w%jg*Yr`&RA_WgENL)N?-eJ*uVYn@{6)69GCHredQLNZ ztx<@#2p)eX6U^1UA>t0N-1sV~yW>Q{3E3{Ie${kUW<09#W6;(8$CuL;9BPUp!!W|! z{1wC6YgCG@=Z(sy^N@<43K90D{|;r%c+llJP+JgUDO54pHadiBZxLugIEIHD(Qvs| zVd3oa)ZgZKjPA^oDkZJ=t1i+PST4H8OT-2R&V7OFx`f|u5X;0$31r^EFiR> znHX;NEdW}dabO!ABFLemn;vEl&Z!{3H~M?iawXS1xQ8( z+)o@43c~%r5$1mX4hPH@Lz9zG?!4bl?(sa@eaQ#xq6zXVbl3htEEx*E!kqwxuHwQz zVP9%mvC=Hjxutn;Iv8E_=a29o!@9Jasdz_f91>ih$JVJRRiJs$;Tv?@@{xU#Eqq>6Z{-qUzWPWBgbNKVqoK4K>K_C>` z&vWxu!P$5tup}T z7MaH5*H)ihp5^ILewjI%!?})yB00xEHPc*1Y2{k6-8~AFG|?sj^)l)((coNPAFo%0SyNX z?%$J_?0;8VS7&8olLsX8(|Z+4OvM>U8vt5?(BljRPRq+`bhh=^xa}SXrZaG&CEz^Q z)0rK%xO6E%K&HWS>*Jm%v>|TK=9<^3V}r?mzju@R%xk7noVPRem$=8Dk_U_3-#XH-81#qTl(7O;Z6qtm$Hk@;|qvK;zSU0%lzXBb@ zv5BC2#6G@vOC{iXD?C|iw~8FXzX`BhWjecVosI4c3>tlFVTLz>dcPr5VY3$Gm5-m*Hyq;9eB)8)xl@otK*+I!nVrZVgpt@Q39?q2WN_I2XUi-5|=BHw`%M6YCtZK_xma= zOw0Z5rH$i+*PdwSQ>&!6Kc4edT}jz%sIn_jYH6-7ZYp0x5^WOH<>BIYic8u^`&=Vwx~XY$iwM$0=QCFl1=h{tMom zaHjnb^x9gSdQhU0yTf+;OZ)kD!0=zwrH9kefuLpC=2gM*aOwkf=uNnXejX&#h%OAa zcXa4N;&A03PJquh0U_EioJW5=XX$)nI)@`R7z@qnYql-}YHQ1W)qM-Jg$5Mu?rtu( z#woK z97Sfxn`4Ll)DDXE$03H^DV`VpW_?i<8|gilVNGo3cQG7yadjmJS_Aq4TJno*ENtw% z0q-1j8?5oANr4-ZLP7vMZb?|$(vrHL9gt-jBc$PD&q>^WeDk-;P~^0?{6AA6N<)1; zZ|EH0YfzJ1>hwR|+uJw}$#HKe7{-$FJ6WI%R#Hf>@i-YBpu3CI<@`>gKAq{ayr>`( z=+d*O(ERujm&bbd1nH8E+ucT^{{iUCYEW!woz)QmjUqlMM@2H4c+R$dvE8`$v3W=( zds6x%&YyyURG{L@N=Bp7<^s(0`0Dr&(?|&<-M8Y|zq16QYt7lyb%KP1C$1>VG7Cum-tA!X2x4k30ORh^E#cwqc|3xT$uBCQ{a7GLC24*hwJ z=^!QYS7pu?0sAly4jfpx+AIT7j@$M))uRQE_k59ZkLHYsP}irfYXA!eY|25Gh)I+f z=%kaHrGU9gUDIKfRQrcdMx0Fod12jl28y+)%jr_p_Jq=>_GJuF0|WBm<~EeWKOW$U zE$`v?arnxmX_{2*s)&|pnGk)^nW4Bb=7UdP+w9Rq)mD%-*nZVsD>{rWAgUxJI@{t= zQA=N*G}_Hd_ms;i6g0RqDBb%OD*BpNE!WPZpX6A%Q55fi#l_+OqZ9JdYLOnkq9?Ld z`%WR%^_7*V9-* zK~p4K59GCwqm6bjAqB@4YFDrq19%)TMA{J$CZFh(&GS0@1{2wW(2*J%!1jdYUlcf+ ztm@oEVebA9>GJpd7wfSgJJx)QZjkN76t>qN@Q}o9$BfL_9*Y94_`_tuXd!$-tH^u< z_jDOaOHTPXy6(JF%wZL7uF81=v#0kIK#Drm5kW}dp9a5gFm!DK?rfKH-IO!FSbU2~ zt~=k@6NoN4%J6QjMPff2y7D{3`!eb-;BuD&|?MQiCnK4p5Npi@sC2{6^Ko#nf zciq=gQo#OL{}tqMi}>q+ush)X#rNO7sauXNW>}`z$IkXAN$zZa;g@!)nnH3UQa?fJ z02d|-3Qr2@q+5PpD^Wcq+{m|Ab}o!XJpofZDBQ-kF1~>Mb=S$FZI-^7!^GMdoO~8cn>W>R54a5o@KAo3F%SWuvd!Wi!YxLa;sUN5`#1nS@4Hi%oI z=tY6a|AAI^_V;PYnu?D!`?kZQ9AKY8Ejo)8+F80*R#t%V`}p)=I3ykY0)=T$_E58}K>s^;Cyhp8}kWdiQuUZU?5vVYrXN0FM45krnayGbl51Un2K=|wqpRm?r}qL>%547LV=oK~QmcCyzlKlqm7b83OyQ>pg0eEJ z4L|$VVLpDlem!l_@x0Bs-|t*R#1Js8w1JcNG1JsMuL@-%W1Yn^g=1wTp&{%6Cbf2$ zfx9qMH`9&+#7EgcT^j`d_WYlp#xEC3YU{#&xf*gVH37oQ@tiNg4cw; z22(LX%a#ohjGIyK4BJwd0Oh44^%fkarQ2AsP*(*4)8~U{lI< zGKg#R7Xb#2pSjkl5h&^cgkwuvUoPf|Dr&@r+2=C5Y6{+5(W3`+sUl!;l zgwpP@+fNVsKJ1V-^e&Q5ZS_a;Jzw-TP?-Cl&t72!r1}udX#z%qvPhi?ZVj3{H{M=1 zbDDhDQ{ssMZ)=m8=YL4y?XUJH_nWtYCHFeu)_pW}G;hY^BNCv%-J;|H$U7w|DI~x? z*R$Qg+Qw$F#f5f1%cs(-ceSj=Zp+gDMupb1Eq^zm=Dd5~We~n|t6J4h>cr#EyEkDU z%BGVmg3(IQ7gW*u=({ZM%rj6CYeUts^8QF7S<8R0bRTIz!F3d%ErqG)uBZ7cr`{}M z6(Ip&`@fi*oBwsnGoOI1xk9zB{*h@K^_cjletw<+@VR3&)jpYJgeR9G@lv!QfYQ^_ z#^SLW&sL%H{2cTkl*2Wp%pmw3MLIWW<+oFey^+hWamK?%+)ZJ(5ojDPx(q4%Fo%XK zbuCPQ-d*TTq&$mOpK7HAdM?I!B)k=FwETu0<10As3jc1a8*fev)Gh9<$>3!BRUhM3 z1|B)#i()B;Ckxzhx{;-@uQu|k%0V*xOVrHXJ1G-oU2V*j`eT7#1tgm}-R+YPM({s; zHeO;juD?_>62mW@d6D>gxSFI-R(%hRz8};PtF}X4aU)GhT@!iYvqd4ODM8dgMq8Z6 zKbJ3Zw!$?cj)mzYw!=YNgq`UNwPK&nEA>a@HFjg+Em=Isir@TDb_Kp+n9zlh*mCP; z&M!IA#4;Z?rL1aDH0B3+Cu~cf+Vhg!lyy3QufB?~WCr4HHFN{+7c0>#Rit065&nY6 zY>+eFn{IG^SD&jQ|BGO{Ff2PRwUOs|?ZjUtkgF(^2GzffA2_+S6PNB+p z?Py{f`9c&G7k>a>#OztS5x5RlnFGXI0Vu+~SQfmLY>{UZ24S``1yAS84Iw{96K8y2 zO(>OtH*dLd&ib6^L`-7KfIXc=%JhAd)bRNDOvYZu_ZVP{f|KVwr=x>;lS>|4)?uDU zp_Uq?E-BfcUsOcv_J%sxcy^R)DJSj=vAQZvjy#VwrJw>Ym-&tvmKx_^)XAur7mN zMX@J2v;$fzSngDWQI8F1RuS8o5;1U2@2h7HRQx)N(J&4v%u} zT(4^Qa295^B@LeXAxtnX`&?XVFkRSe?oMgrx9Z&KErUBtnR&F}u)M3#b+KMJn(lbT z#y>C5E}HMr#Mi#))Fg+5sTq`}XfS$X6QfV~MZo14&^1#cL0}n0thq-Ylm0dy z`+DsAzrP&y4rAch_=>f?=+?XhP*?8Q34gv7VQRW>aJJ}|(W%yX->Brf>tl^uH*SA? z*KSim_EToPu$h9G_{c73zSc}@v}809TwkQpZo(YtsaVIWns?i`vef2<8+*TG#EE2n zW+l}S;qGzg|DFxXUT#Gw54_p%M3YP{26-~7Mb$KYlr9f0S-3ytuvnH5j}QbM5QQUj zKKNr0UO2Pg1*hnC8#yqR!2AZALIf%u9@&OQN2y6MY28HLc`lCKj3ci9m#M(@qYc!Z zq#@4~$V}J7*sFhf9X_p#D4+=R_X%7!4kNn_4oUEC6dvZ2ULPLJY!$g)j2X@H`|W}h zFgc#p+OgBYS9Ez0YA^hBQYW-j4?W&(fEsWhuJ{kR(1Jc8Hp9w(vA^0I->&Y(+#VoI zyI(EfSiJFKB)3u989h6RaPAFuxajUJDkWJ%Y-Z|o#bwD%4GSaZez`P~dc9Fzd%MuQ z*7xV>Y~B(!c&J5jI5eB+xSCvXUlDzDWj0;wAgtb|ty{c2m-NLK{P`r@n#?x(7BgDq z6{y*1NtMR&(+VowU6&k9!}ZMd_PATHa(%aJi)m3ed1CW0lg(@_)+K(Y>A||YahK|( zNU;`RgNxy2Oh3_*EnSr*cPFA`aT21WwqC^I=K@G9Ta#lb==PgbC9LXq;mMn?RnPP; zJ_)FPP4#?q@H&WYLBGPbd5Xm!d$c0{`u2ja+Z0m5`-Yv>b|&gP?w@-;GWV9E2ZVoF zJ2j!B%gs7HhesnY_ya_v{GShwd&D%9MbFQ^z^#pXg-xN&lfAnl-PTc}IrQ6YsZ3GN z$Br8nPm}mLlmzqHD%9K=ah%$dc|C(QC6}J}n8J!C1mjfF;LBo-!KElte0z;yiDVocC@R+v6OaE0YvwZ}i3C7f=$#bvdI(?&8=*6muB_hP*%tCHkuW`W(=4o@ z3P6lZ0-9gmnex;RYKSIp34|%xYzCQPe4V=<)!c0C9nW^T5o^90>KkmT@9NS!SB@A$>*(0Y5#DkDj(93*1x86mVeXh)vMyx+Ukmm?K{6(prSeE#zRo9A$ zz$mJK&9#q^@LrWq7sS^VeknJpT3C) z;+WQ<5Bna_Y}UBjou|VKoDN-VS!DZ}pcT#t*c?qRmad(%N8`=rBx_eVLx7bIU^fQv zDk7FXv&uExyr&TsSSrz+HQNa^cN^~$QZY2#A8J>B{UfiaDEhRSfV&|3s{sZ!6V6&& zdodcS3tCvI{Z^OfY49`bsLNlls0aMQ~6v9(LT4x#R5Tl12yD9Tv=(^mY0RM-yn5lP%QaOj+AWXJR|w9B;D){v5o_+*X`enM|;2SoNG{((vq8M2Q+uzFoPT)vruA}dRJ*6;a~ zNnM5itOtx3M*pi*KHr#c_-=^WW#=sLCfpQ(c2s4)xz1v)K8RB(viFf-(m(jlo;3Kb zOdv&Y?`~)9lAFb#k)>m))8+5I59sO9*`IIZCfMbsHx8}2#ks*_2dL7oBxZ>DL64E( znqj0GI$}O+ybMVG@KkKu2iqITMzUggtO9_ww7iTcb!kLP9Cpfc&sgod)S%1+B{T|9 zW)^Eddy`iq7HD@ndIK~`)gqsOQ{7U0T%O6cqI(^?^Y8cj<*kY((A92y9X4HsPNM4%U;vG;)fH48xvkDk*Keq-AK4p(=|Z zart-alTIc|UT;)aG0U_X0T z=nq^NrGHz65sH_oR`a_vMFe0D2W>ja0A_)3n4d_#(2L^KU2&CZV>K*wf=E zy1T`FLDBZxWm>Bv&+0I|2qIjhQ_bODfDC00zPNxCIOjsqpX<i{_+^4C0t6DL!CV0$91a2ER2ce&6yx zbGVRf20(UyT#6Ys?>Btb%TYP6k>)9Z0N(PW?ete9IR$iR;_>9| zJTCscZ+7m`y%Q2ao?SG#oGx+$$#UIx|AATI!|<{-2DRwtpY!{@GiO())3}W`M4}>$ z8lb-8jP=o602R;FZ|{=$#`TL5pnqVDQ33e%vUI@~+I5=z&N=2Nytm)5aGFs{wS}k^hfF~@qr8d%B~|~w?}NH!z$;h|4h1hYnP#QfaJ_I7}Fa8MhmvB+n%-ISlY$cZ&k$?tEYQyL6HS5f}q3g(8dU!zMvPd+57?@R}QpmYms z5ZwSe1!Bj?Mtk@y(TNNizO7bd?M2*VQ#24{FG?AI?Nf0 zk>7th5bN&S=2zD)IQLeQp~0qieBiegbE1e(S84p^%O2VNd0UanVf(1x+d3_*&iKjO z%YuIx`iqN<&|GCPe%G`5tF^>ujc(%p!M5MdQB5SI?rJRJYX-3Br4o>K`CVE^L)A}0 zdocVY(jx1%sF4`9aOrj}K|ykQl|kmKvB4r!rWQy_x@UaAa@b$mxJ%?_`B?_Gm^zZ4bZhQ;PZ52g4B^@q4M@K91J9fnRF-&vrnbh zwao8MHPf|ZhhHsB+S6hHD@MbB+_MkU##yaHO;om8L7Af$e}XoeEq^sg2e`aNuYHqF z!^j>cX6AS}y!8J9-S?|k*%;uR=~9c$k@VfFQE9_mV4V#x>jFG?SC22Lgzb}##P;T$ z%cd+zR9SviH#Mb>jHrKCIP{b}dB@kPWP*JEJYDL`x%{E0)VD+4mhH~hZ62wtzG;ev zR`ebQJ_lp{5~+50JWa8M%#QmGO;W)VK1QF$e=m54;eRDCBtg_olT!(@FFBR zKYf~E+8@5MHU6j+ISJZ{x-DnT`TmR3IV4sscal?7#C@2%hP<+|R2wD2(Fws!e>YoHkJ+1-7x;#4m>xae@Y=^|83@v@cI<+1h%DfSxn zQq?8iCDL)}UuAK>1qfVaDf`6)Y&z;0PcAK$r*S0xRJU%tsuqqZ+rZEU5 zEy6F+HE?zT;bCK&>M1TPdP^Fy=ddx>@SgSi@)-YbC-1|dBL3@*>(_EqMgX}F7}P0? zaQwk(j(9%y>eV*^*X`G6aJz55kjWD8WrlIBJ-fe)_o-0d%xj%G(l3lXuiHu01JwAe zewno`M$^`@?GeC|Ld8!kN-<#FcENXzc;<$#BcA;b)hQDLgSQ}%0qq}lM@gd&(j$0r zW?PXb6KRr&mqQ|uvH%Tjt@nJ-N8XKXn+g|s0fZyx{dW=Du(o_En8S%_WpgtFz#Mnp z`vPT_S{Hjt+`BN@=ah2S8nct0NQ24$EzRk9{PEGViq8U72|TMeSDp#GSMRgjqX_A~ zJNui8a*>7V16WWmz|{cSlW>zKXg~iAZcD}aH|v&Mv_Dpl-+?J216#yc>WbX}d4oEYi}H#TDAuc%0BGX?Oj+HCn&R+-PBj$( zL^?Piy+0v6h!f;M_>6x_w?z(MVO5_y14vWl>Xnrsabm@No>Cubx)uFw19c{k6Q$^TLv?@~Xn!#`IWXuju5``GzP@Bkw&9Q8w_p8zm9 z03fS|K7Cke$b{uZPv6U7;vuFez*1FLjug70pyN7dF2CP%bWpD*&CEMg0_OXMq0GU> zWzlw9wDM^!O`Ndb6%jCzHpS&wIjEW9R6(YhLar#mNK6I1@E3~g8QF3lJjj`i+4*N< z-JKw474>`5ssHjO?|f<9EH#0+-G)F^#YSG{-*iL%re%AG8LN2HmJq~#cd>3bv%Tk= zboJhDXABeev}Vc+kDw3s`q6X}8R-&kw&zu_mI~$%@)7#R}x~Ooj3bO1pZIJMMc16Zyb}$B`qyojKy&ZkN34dsjr{s2lEts zYW^a<{aFj0I(%8u-hMkLEv@+VmXF$XK!IHZ&KbVmnk2y)`}H(kG{67254cF{yV{ol8%7pXyE#_^*PRQ4)K2%xy7!j-B9oiD^J3J3}b zb-(2{?D%rkIK1)Qme$gy3g9#7&G-&4($Hiz(+&&@xz+v5^d<}EcK}bDi;P>n?RG-7 zgaVs@=0Z*H>tY^Z)4&K0&%dFiL}tabpcnMJ7Ehb$w8*U(7BlixdFmXOl!3iIIHlmj zpV;y0_X7V4w9??xFY3B!@|PwurL6L&iIm&-TFhmYj4EtY}RX6U~9O72pm@N z*l(u14T@fKxXQY8d|5q1SbS|DGm7Q(%J(L(d}bHEWwN+C#Q{IP^iF}~B}Yt$3=F&i z_LpB^|JDIC32vCuDYA66wIh00`ECLN=UmB2w*Wm6vIWH?;0PhY!oWNKM)!E4$l+lP z8BnOX&IPV#zY$CCKF?({N^^j}TbCfO?8xo`pm275LtPL2-K zDmIMo4iiY1GyS9>hp1;h^9;L z@Y35GWOwkhgmqT+1zvog=tpsi7Q}_8`gL>M?_(%@X&zSV&FJF@;n@f>+mC)|z+L{~ zfaeY#h2)`+)J$%+gj$nrqV7btB_s#{US)LPk&}v61uQa3NsDLShrL}c$cjR{O z5E%Js$g)qJVsUEYZ<&|iw{UYMQ%k9=-&Cq>0b9gCysT`}Yz6@GfEGoB>Z-@`eu^JmxcGwa4sUm=m^ zG{Lla3QV;B&{9kc-Ow7wz4el9&WvI5ZtA+pP>wL=Qb*EOIZtJo%OF zI5>^=_r6NbtUljUz^m=_VZ8E|OO8jBWJC6A5wyzdO*PlH5Qa#4^9B*MU=lz);=<=i zPI?FU=gY zha-|6A=IUa{MO0D_S-_=+h_A%*Y-(ZX}rLEVc#OH zhkJl=X>Xo^zaGRI_GGs^mU>tSK;mMHih5!a6GL`u@y@cC(0z-xbzvNJsk^sKouHR5 zeLxNlOti!jE;VE`D)$Cs;N}7YLZAzm130QDJ2RQzzIh@JVU=Gc&H?<640o+?Bc;_r z0zl&}n3jeU5}rQr4?DF0wrn1NDqLMP)P1R$Drj4u@bPjXtVc!p9>r(! zI=}_*Dxat4kRUTrT%?>667LQ@*@o0tf4K)Xl>5R0MR>n6m|SCx8uO=29f)T%ZMlGbKe5vUnN|*- ztt)OWj=VW0eqjgP-ePN7Q4J-j)_X=nJx*r%W_ORHO++FwNOo^lKC0gzMmE>J4D>t8 zDe>}tT!+{0pv>?~Vqvvag=f7ivF(>w%~wqImSEg{$zW37e^7K0y)v}_I(Nr@pmRsD zhpM^WK1`;?0q8TzU+~Yjfi6nKV?>%RI>=lGtbM{I{2LI2;KJz}m>X6{@;85^DEybZ zC(D@i8oN>@h5WGw%nb?^HZ2z+<{b0OE){nKfG0c3M{Bm+LTYMihKtbcgzKl1q3176-Ed?+b8@u(L}g| zmXp`TLkpeM(?+?Z7n+VbA)~3`XWYf&wY)N?6#-AQW|^|Hml{7f_C41%cQ7>NOnAmR*DOr z+?_6EAb5Wc7$wtoiY!v3;k3lo^|z-!4zk9QZDU;)bT*YMveVPnPJ7bKo|Qd6FG;kZ zildIXS~E+SL1vd?LZvAa5)NpQO@ERQBIx&jW=``veiSicZU5{yxdXwuV8KDYjaEG= zf%R)v{}g?*2vf|VG7}*30BsUybr1FJvXYYLPw;_tc3Mo^70<17#4d&{#y=GtP4d0K z($dm*fRLfSwIFL+MDTw#I{ez@A)1X*4!{;6;{TJd!gmaBfVfLaahlvwINl%Tw&)`E zUZKlD)(2qpiT@8rj?>|nr9P39^TJme?CTpdo&Y2SCjnhLj@n7}#aD^dNc1N8#lP>B z_Tv&bXY*Vb`CQ(qOsi=`eG8L+?$z~Dt)BjSBqwwGAmJ|mwvo&t&?i@$m9UbFy=u}! zch*dSZA7H=C5kLE)%GKRjUywYR0lUv1J>wLCLRHL|H_>*=warP2BneAenit!*6j*I z)y@-_K1IJ9`oXUH{HYBSOZ7KZZ3 zk88fm!uDdM6oX&)v5NGc82_)``l%(P#gIYXuM{`dIzhCUMVR^hnvG~o&GiJYuQH5* z5 zmydwJnn)Wl0-(T-q0!ixcI+cj7cgMv|1Dyt>y>XBFZ3K9JBq?dD{>edu~V=A!RP1=a9MdPvtRdRWQ1K;?%Sjr(z?$ z#0I!bynO>{IdcvQa?YO)zPO|mtTbI<`R|=MJkOlGmV+tzX?7Zm3JaG3@hZCD0q;wA z+d3w=^@||Xo(?dWNv10H_7`NdTUDl1nsgS67x}c#gIb4pp{K#&`C7WV3MM8}NF>Nc ziPckWa~}FWhvl|5ju0=jUKD8~T?4(G&smSd@oK~3;o!&tV7{ZHBf{z|gkv!TH|X`Z zZ{OH>c-&kAT!J2<(z4d>8XCC7U__Q10Mn5D^JgZ9C4~$g<~K-M#K}yFpWn7l{c3oW z8k!SAW|?{4*$+AF7d#O+-)82-sU2Jz-LSrY+T4Jx3of?htuL6drbts?6ZM5?y%8%W;k3`yQ z5@i|Dq;8#7+%~8hCJW1Tva99KpP~t$5ZgE`^sTZq;XQrzmwXpFVd+NCqnUz_zoj5s zTvNPRi@C)}<3HwHS5@@v&zE^Y>|jg0$8x|@5r&vSfE*Hue5S8ox2U_RYvQT;OR^;p zbkuMZs(*r!FD6zK`80_oXv;J^)dw%X(1OYT%DY3b&xBcB2yu$oo{#NQ43(eQxA^&U ziwEQS+Kn`lWwxa$Jtc+jRE|f##+6$b{)h%}Wn#;Bc^|a(X2#|ky0z@H2@Cp101cl{*mu#@b|Nl-@mJ|MAL1bp4K(%Rfg|<=DyeTWLjhQ^fq+QiV**-;W5c~#AY|RiK$EqF7{)=}` z2B+io!5JI7OboEd&4JaPXG_mTJ-mn?T)!e}rBO%|T!hd3@E*I9mq0vwU%pE7ZXZtk zsqOZ3d7kN$ZdyRxv__||7?Poxy#F1& zc6Zz1*ST6Q`F2(3a6b5ZYURBgsgzD;6e42P+8Y!<|bLqMOZ%#hWhiZPPwoc1U z8qee@wszHkM%bvRaD;Y9tJ^H>pw*pt%svU8crj$-uPH?VJ zfKVq|#wW?rUlgwM6RQ5=r&s;wliu?a@|L?%bP|AlyHm+r;bM%0*)Ai`9Nxea)%XA! zQZ78tovtz{9q%xHJ^C?~9jU8bqx!CGh%xW*cFPB!J1MuL@M#W^_L^$XN~${ z3>804PMjthg{FE|s=*6gmGbbH@8y%>u(AxJV9O4;&@jF|Bo1C?BeAHYQRn)6hBKFZ zt8m)h)lnEd9ma<{toXlN07$`yLe76ZrB=nhsU`7pe?dMzEy-S0QJ4irC@`cf#wmqR zya~oxSH-g=SYvg$z_}!dObPDtMl{w;QmJD~&4@hX*4`iH;wsIc#p!Oav$dVAcMfvS z%_G+rG28>WAf7*mKUsO=@Y_GRKTT^{INdY&)vH&@(mo2)0uk!NaxPCww#3oBdL`;o zI+wq^XkgDm4JHDapz`4y_r9cdKxqMi5B%ULmZbjjNJ#t$UBql3hf%G}0NM95nsOpo zSbkpV)z24?*#DvxSJ%YN7T$dR$+;ML5Am$HCzZ??gK1Nt=Hl< zbeoK;yd92{9arWtyuZsAMH)}++UkjrOr_}j>v%%;fzAWEr;4dq-du@6#sfK7o|82? zb^_D9e0%Vb$gQ^6H~rfbl(<9W{s#_xV<-@!KIn@qOyqgNXB=1PvoR|zex1chg<-y< z$vc?L(~@n6;~3WZ=B$1Y92kSckPk)<)GyGFpw#QcvWvrsPEUWRrVVupSfL&0S4e3K zm%Vr`NowJ_&e)Vn`Ix)>g?QY8ca2M`=Y2r*+EgRtajScjUE;+QCWD3D46*r1mSAy` zkrta8^v@I0jC{=$9TXI71SZW8uL+OjTYma#e&Q&2LR+yzt|2cpC7`4RV-1y%pqxiV zOUqerlwv4g+54*JQ-vxri(!?0BaOE0m80MWX1+lOi7r|}Okr_W667)vB&&{9ZZfQH zw=P4Zs%59!A&8Ej3|0siW6iMW@>0&84vSaG^cU@*RVB{?>^KJ`$=yvjj*ctv$s`gbJ1I(7#fV3?U&T z#em+A$5w6(1Iq;+60fkswS6JpZvaQz`PLH}E- zNH1*+CYIkSJUq|*>%*O2@Nse3#t`T&@H}Y}nb^J)@+WxjN0U%!xXqdjWxx`>JcHtV;e6j3a7@#0A>a|;K--I zt*kDa*6bmc0}@+a;@`Wa*@YAJjsz89X+N>9V{Iy)+e%sNRHCx&`RnHgzpT;oEzan@ zNB%NtBFt;(zs~$Ne7qF+Mnp?%ZR5en|U?3vt~hYE!s9$>iP8Fa+tkh&4% z5agraHR1Z4R#=aJgB=_xlco^}yC>$U{=L*F`Rd?}q>vwar;#uOIR)zZ6B*T%B~H&$6J2YU;yoHxA4jn1egn>d5vPu8i%&gp@x_~%s92D;GU(7E z3Ik(MT^&5sy$iz+$6Bj*WbH$m=P|pEe0VM&2hO}(Yn5OxU@Z0S#R}jJrd#eyPUXYM z#gJ6i;uGayX)Rsjg+B2mAOuMMQ%Pb4JS}P_rwSakTJ}nLAKncN$bI=zGPywOQfyLY zaMMJqsQ)NYkYed%TQFbzuy4sfzWDn)6cH>{Z1acx*!H+$wj*nrIPQS*q@Pg*G5F5% ztfCHB6%@%gfwx|HuyF(-?n$`4+U(pe@3>CqFYBJpwC>c)5D^kun&Z~&?;|UpG4>`C zE$ua)czhN~PD!EmFF9Sok@z=NwlMi?C$Y*2UYT|VCF(5D7`%ielr^?wge<}(pf29l zOxc2eOnHL+C)QRK$dxhAA8C-gRgQl@_>s=Ju4FR?S&6;gtBx&h%^EX-$*KG;;?eywseCL$hz5b9tLH5 z@~g4&8*nUn81hW!*PuTR@2-}WeW)?7G^TCP!77Q|bU&d!s7yGp00KD3IJ!M+U0?xH zDk{Tk?<26JBId^+U`0r2@`V%tKb|TAt=OQRA^%b>(3A}&Iy3_K!w@hLd-4jXMDG(G zg7Ff59dmuI@wN-g_D&EGQ@spmNiR&DZ!!#~6j* zkBenfh`=f1|F(@eGwR=QABVAwZ{H}|iShH6{W{{6B{ z){vf%pi5REtuDITTH=S8Bhdj_(Ce1?!|crO1nd8~*RSt`vQS+X=F1p6wRNs%N`2!yKd`6hwSw`gkfelg4B;3bWI7{Fv5-aOoJ>VtC^NI$ z+D&Sd)`B^0S^fQoL9y~OcGtbFGoQ+MOBPzl*{aQNOo~yhC0Ct1D@V457+9iE$1Mr7Ag%`Uio9b41P8% zT==Zi=D&7o-KYBjq1|UMIS{n%{^YMvX{iIw zp?gVI8E9p34d}Je4lAunj3=ArEes=Dh&2lWg&P@*s3~93W_DXY)A}RdY}P-L(D)~E z-i@`dpO`Fef93%jFsX`hs_+!)1c|E$=^n&_2+QDLY4xBOv+4rR=66Vp7iC3Z?xq4@ z00PL;Yuy8xZl>E9)f2(dZNa0W4i1wKCm$jOwGFjHJXCIHijgc!8>xbqWJg5K3rKi@ zKLVhM4+13AcR*(-U}nYuh{P{P2#oYK3j+-a;DZgM%#p-4Ad)@ZlzlrrPsSA^ zKh^+|4p|9hjgtG^>Wx}FLa)2k%h&wz>ae>7ZGtTH>-eF%xrUY&1W>a+;V{%nQjfw_ zW{JmkRRU^2kGIf04cQdY1<-Dn{u}O?4V-GRci!mSD`8zd$%$$LuDh!Kg2k&yVQTC( zMv2g*6C`*yzTcAAJcqy~%;Wqnp21m4MwSyN^ZNVsPFW*;>p8{wjL){8i~_&Tr!6IG zoi@VXX}tV@+w&u7>sy&uF{-j#GXnChGD?ec9FLx4?4Zy~avpWq?*>C+lDq&TEDIYO zB|CvG+uf$RFHSu}tS+Y4GoKII@9Ty83q`nI#J(E;Ho>BnLdd&)m@ZzXv2x*^Her4r zFrlrd!gH9jvXHId?iny)zCT+S6N#_9j+qx~0pKr%B_%`k2kxLZGhAxH6O1z`HS1wn zI2RWc=U}@(%f66qO|(@+0nDq|NrimW#&nsRw8jd14lo&sv%}fhc_d1|pUbY5|G{ig z7VtG>?dt*U!YaOvV@{%J5Nqa}r;sbzukf8VA+#VY88Dj`hI3-VhadCKTY%Jj#Fxc$^ z^lbnG(E(Y`FGqpE`%qYmr8+1o5*>NftM9r_IOShxX?c65A=s zUGc9GeszHZQ=)Qpm)0vs`3oFh!@qAek~#!X8P8GKc)vg4E7b#G!f|I{q9N7d2{f;ZLnZ+jfE#HG>_Q3fmrn-yGA5x1c^V%vH;# zPLOqzPpoH>K%2FxC=BXKhlAXn360TNW`YlGUxN@lHoP0B`G?u93sHnlLsI-M+d-d@%}A#db_|;s`@$eqc(rhIiElS?P&yz$pP-T6l*x2)Ae#>tnt(|(uV!iKA z3ocixKdoakmt5_6TlrlsYMWkB*3SFBI$K=ZcvZ7%%AIlRyGMWTVCsD~IHa9A^P~Ut zox`=%CapVOG`*()kJQOKmirKo(1*%mySUuya77D{z-LKTwR#Ok1N^@Mk<+m7@COUt zs;YRCCg@>obp0$r#0jL6#B9BG4~<|nb#RoJ>tp6etN*$w>3F;);W*Wb3mOtKI(WC% zqFDSy-1GlHGoal%8~H&V^Ro3T1fp0aVY*2mH%HgI=H7ISnXHCMnzwOQ?C#u5tXdFg zf{}JaR`Y7akzzE5CT|1lN9ge&&8+TW&?OoOg@QZ^sanNVvsl_i!zq_d8JTy+m}u^T z4s6a~PwYm`po@JDk#mf=58lG!)T2n6e>^3A1e~AW%(1!8V1o6Qn}I~e`}l?FZV7a^Evoos?xvZ6!7~7S&7jNN z%@U+2V;B6v($+>ntt=2=*DMDrT8&2@if=yM7c*U=mdFC;nQUsN@i|0!$@S6=Fh^`< zJW9RgX>H*CFsbh;^ktoq7&G!x-%Qx|`*gRCIrF_ORlcvNw<%p~!7?E|v)NR}*>^0w zm4eJaNc~pVB2GCEupm9GhIU63Z*4gaQPyr5nz6IvzjOxk;h2(?$W zV6~mgM?;(BJj9x(r$mCnQOvPQYqG+P{y_PhENdFwhVlF;k_it zLtJrm3H(|ekvffxF9u+8nvo;b4L>A9;emLkwpty4TMmIWP-E*gT>^#fMUX}JN;MQb z)Y6beXGjrwoQ#P6+tfxFSMNan2XkUvrA?R2g4K9w!?J4-}mL`nNA;G2bm2W7x$ba+4k{yyi=q?7mVpB)Y|F|64Rw zrlcX2A5Vr78r@_KEQ4*9F`dMx9f{Lm-D3>$K&Ti zYaE+&MXnJ%X8XFA{s@UT;<7(pJtL-~qUxK&f=VoG-Bez`(a?xKqihx5)ceS|tgQuP zrkg)nGRv$X*=WcU2dw#v(KL_TKws@FVkhk4Tvm+AtTMk?WI+? ztzdx>nx>_E-0e9X2>!Ude}zTw1OkzI=~jLUOt%0@L4NZ{;@Lcc&vPBYe^LD?_kv@B z#8$wn7U-#y)zry($M-(@j=rCuc_l=^OO;VCh#qEW&%sKiiSiCXLjmxD<{@Ae_F(8h=YU8>=Y+@ z|FU&+VB6M$cbH>|@e>|UPDDI+3hs(lo*ETYcO7&n?gd<@;blNq{Fv=X@P6&s5eWwo z<_EaV2#!Mmye&YsoqURYyS%WF&s4(YmL)dB7O^7LKM1FEGJHYSf5jB8j#NKQ9eQ1G zCjsMvgKceb%ulycsAse?f)XVVZ1$uK+e~9m4uUxl_uFlEHYbQFXzd z8@efQliD@^1wr>fEIW#6i&#ZknenQ7NEbw`lIsQ}=pEAK_ULA^^uMM7m;~}H3IDy4 zkm++yM0Q^x(Fcq+oi0vXe(jiUo^nANJX*-R*0QD^F&BOc)4?r`B~=Iu?@wi#L@$L( z4N{VbCoq(-Z$>P(c4zXGv7+VH-hZ1c@JVXxf!A+u>0R!{?wbz^zn$|(aO>Wke2Kc= zmDy7MIqrQBORHb;lQOaFQ||#)zW2Xq$=jVOP^AkW&9je|7mmgokLnGSD4h_egnIPu zv@-K|(tH2v6T@vCO!apoO(pdBx{o2bY47+S+6zK{f%C|-N<-8j}UexIaqTW$t^1yIs!^m z?>qo^zcw{R!qTEhaDtMDg+#J?PHt?CBd9y#HEw|o$0-oAr-r2YrS2E)sXX~Z%V37jWbzzpV#tHb$|)xy?tBN%G!;ziVq$3_f-o=T~g$IBHN zyBK0oK@}7flwo0s+O8`?bPdnF1DmJpT^+6@v6M5MUI48bV4A{2)MQZe067i`#88UL z-g&QLt7=8N(eTtb9L|-NmnYUO7^3DXG;aFd)q&%$(*1LQfqi46_^5M+R=#Q;044xe zV&D`RYL}S~iRU(+oS4{V57fUSj0F$UmXX@Y-bNJdNL#r!t0R9opeqcH@0c$1PBCaF zw+n$sEWj2Yw6xwx(w|rRGNPJ)D(C&%h7;>I?TAH&YTb&fo322@6O|0m75|!w4v)MX zQrC4#2*pfhPs^`0Qxa8kXaZ(WCJ3Ma=yEolj#j@_w|H(G=X3A?kLG08VLEwTZ53?o z)wX5=!b8pgJkV5|xqT}@IVzbbW6$$xpxfpgRBy))&erOZKoY63en$<|=1f8DQEXf1JF`3b_U~xLyZNX8OqXWkvYdXXc}MR9 zblai%G;z>|F!$dL%nNiqE2BhvB9zc_!DYpz#mpPB<-My=c6C*Hb9)&{h?OdK;*+_0 zE#jMi?K*at6FhWrBQWK2!!*6%f`M?9js<0UgdOTh_YW}8_NVOAzP*O=j2&IFx*zA~ zu)mOI1<<)Y8JC3!5*H1}n9kNC(P+ONrB|5mYGp2*H!=@7rg?)$rS8OKBv&%M(%?UK z4vz5V;hs2dgmfc6Wh6sIe7y;x9ceow1X>4p94`eS#c>9td8y@yK9J!map$Pt&ohsi zDyzF__v6D+{)$KaeClPZ&s%E_Ov@U5a6|kyDKZ*t#k;#MHhc3cF7%MJ(Az;tk6oVR zmnNBS=#@u%7dWeneylp0b~0z$=GiQnN{@MR-|Klk^Fun(gfE5?f2Ciy>`Q!!{--b| zm3tnCS5k85;D9&gSN$VX!^FGi24gn5Hu~?J{re-=pE-3Kvx{dKb+7wH^6OJ?Bn1@% zl6<(M+ya+wqB0aN}G#^4mcRuCOLgeXIdkK%> zVGfcva=4i!UoWm3gnoE&JxqkK-=B|&nqA-W6Q>%Eu7_J;9Mo-!9OzpAh;FsE!T|%5 z{>1V+6(}!2&5wVe9xYM7GvAJy2If0&-+ta8nDIuAV~w#03oxN7m!BdEwAyCJo|=u- z)TjX}(QDr0_*c$(asW~NBY+TB*NtZX`V}{+Aro#>%|n1QR%({UaAw*Gq?EAy{0%}) z0p2l<7i7*~L2Ik1kv0oOw`o_S`h%~kYv$Sh)%u(Y{K>hswYqj%$nZCYMu?N4o_HP0 z-FDeF;W5Sy#@uw_4~3RE5&Xf=VPY@tS4{kQp1;E04FK?z$%gKvFtutp+>lu63pYTT zspB!p>e;(lare00{k~^uZ)q@n=yp#Or6szdW@Ms4(B7`Ow@81bCq*KK$1yYQe3T%? zYZUIqU`dq^sJt9^H_mF3xj+CFvLb^fsM>T=b&Z;}xj7mm!4e<3Z5J&)HT6LI+e3F+ zrA{V!;vC0bYTvsl+MZzYE^@x@0rC2yT2J8k&MC@|r8|rhq(y-JNFMLB=H&@h`F34) za5id31RJ+`GwlD}hZXLle;V2xPIdH%{^LSjS!_1Nb*EP{41AXaj8#lK zp9OSnE{{&c=XO>Er0j;$)3}4D#4PJBr>2F|=c*6_zy`{WKzdNjLe}=yR=;yesQh!W z{Y=~2EZn@%MwkcN{FUnTSQH)70K#}HZKn3>=TN}JeC`O-=^c-ZW8d*(mu%{~D}Y`J z3BPvt^YdFEtps9cFkk|JmPkYu-Nj)%Go^A81e6&u6m7c{s-%!VITj{Qe{A4T4*H;7 zU$T~a%}S7Te=BjPpD>X*O8S1j3e>Dt)6wqW>A4cUow`QA1Cnbad)IwSx6PA_iAcN8 z>7yV#QLF$@o18cVQr0#isof!1d{=Cz=-@T}>wH5rAJ4>Kld|07f4KlAL@?OcL|iDp z&tYETnL;uPnPk;w2qPfWmVC~1D!qrb(=X#6yUzr64c}q^WvMnDA+fGR~okZgUPbkRccCO67;dpFYQQ!6!>RLPl*_&s6gcD?ssQnob z;M)^bD&WiW^c?M3*?4-0u2XiuBrO#cu#ot(wRM4W#;~ptcHFz_+}K!)7@-gmRSRY= zm1S?L-Pxg`?Eu%=836Dm&{G58o56lM@M&s+rZWnXiZ37}CU6YC6OcsH(~a!ypfvG-){wO?uZ>Qf77D<%k51L6&~a(o@9*~SD=iey z%DsA{=mr6?p;A~+*-O9m?6MaTVkx6OJ84o*G_o-X9t3E82dV-7DsfBP^w)Ryyr>H; z(c3A*6y=XE+YgR!cKvE0Q!82?W;SHYcZwH(e;r@U!5>$R+zB$+`u<$JUwO)H)*N(1 z2~;-87oZRTmk#WZxJ)tht&?D4&(Ff{EXRzU1`bHb{j zPH`pKhOv`0uFw5WiTe#V{j4W@q6m27uIa8@)0QwK%?};*G6q<^ko2P~XxTS3RaN_V z*xNevI(2V(v+W+Ez=3^vk;EtE9YK_pZNFA?jXhp*$Y#ZMGUeRxBbr3X-fzp#IK9q< zzG3PN$w1X#FW07xn_fMRK4-!EK|kCp?Su6b-TyiDQ=e}n^d~fBCKUmS45s}Dq+Z0D zUzS{+ss~W@&m-@p``bN$%SJqP)V=%gfA>N~E#1TMfi62Cmf= zOMf9$_lV4+zfyi1r99rD&q7%nt~*L|0}1N?-E2K^vtlrn^dQZ=FeZA#uH?$IJR-xL zm-=Y6CwTH$V5(=R|K$raui!)p1%2;!2~o(jCfuK9O%BZBM3akNhiq~qe}u)xjjw6E zt6qwtSC3Q9f8_phKJJa=!G8LQRu^9Zecvbv&r6urNVf>|;BPA8!b?L6_s)x^eE-`( zvew0FH_;TXzjhdDR(*4*k<83rst>#L>ST6ml`C~dbFIFtc5y=0Ud00sndgJ3{$CZl zCXX|~Q&hkYKlbQ@?@^*28;#ab?^C)9XyPW2dfc+VAUkwR+}V%2({6Um3RYc(j{u=> zV51p0)~d`?0L5%Oy8SP{97$H!XATKw;>Eo|0x>L|gaAgSU;VGepv(~5TfA9^v5ghO zLMyy0i$ z$egzi;CoY1Q@db`!}$JSPIS2@WIy3Zl;)95*)3xhZvR4uvo8IcHv*e}VVhll%J;KrQ8}bVc-?^x^F1;WMzR!W~95TN)BeHa>aLiP6RH zfy0!WS-6({kH3+}Sn=b&P5qlE2lXJM*=}U?=j6!huqARZY5KNO8UIMHdV-hhw(;qZ zKhAO-j;5YoCc5pH&1{%ZOtx|Z_z(0QP$d_cWrQ4EcLieiTKZF)@EYy~dEY&xSpXXt z`lkBkjfE9aLxbep@M{SwB~h>MeKP=^;fV>Stt|-j*~W%#Rk#v36alUi@VTie*oN^{ z`66SqvniLSSpg7F**T8;M?Sd32wliDyBf&coNU7?KeC;g$nE;@a9kQQcVt24M2cbm z?BdU#A2tHRP~anJSQ`oK5a^9b|=R9c$3R*lxg-Q1{rWBhUhEw${OJqnDtOOjg13ji1i+_1C13 z7^w}tu%OMMHiRn~_cd>F!24rMsm|y1To(-s5xc{rG;EFXCEr z)|qqmfA3%I6i)#l10=uHiWlG-lV<95T2^l2D{~&*`Yc~G>vYxB68u_RC>r=phE#cY z8-6>Pv0rIT!Ioj(iQt^Z@4(Iimd27&E7l{;2HU2SCa0(YuupTBZ%NrYPs3t4sSy=; z1r_|>w-5=^GQ+qS2^`Y)>1e7N@4#~KpG^P($ho8cR9OYpwtxmwqfCRXiw^Mf02^aU z&A{btUh;{5&?1=&4g`1wxvsP>>CA|a}fAgjCXRz%D>bS^Yer-$130b zweLFN^XS(KM}-RMILCw9N%x#m;d6a(4fWmE-E-(qUBM=CrVwm<2pggQXfV{r?Rnq+ z^ziVu)ajP>fm5be_G$X8@hs>e@8j`SR^eOFJ{?mPqbH+==TiXRb!o6>8jtT)hfAD| zs_BK_*`7c5nrZJP)kDV|Mdv>8PZF2KU=n?$$Z<=deP_f?C~U`r~AQZGu*=3Yey^b#C&gI$Kf60 zdgCvNIY!!gBLqT^W)ptlT9}c^Cy2=CbEXy5v&F8}Q)axqD z)3#^j*~KdKuN2Ala)@{~lr05WT0u%jVPgGbknab5LBT2 z*4H0sF@IH1P*`P7Lc#nw3R`+x#yP%nsPU~9(3}l~NDoulaWoB<5Z4b6S zW~ClOH~iS1bn+r9Hs_h{cN&bRJqKmn(mbQC%}#bO%X{QzB)6D<60{_~Y`!QL=raBl z6jaR?5gpPKSwu3wWgCk+DDzl&V-S!7w>h0aw&jGq1 z=>%variqwK4%gk3!s={!Xoy>&#WATaex&L*g3_(B&pkqhdt& zU$~|Vkw))uniKSvjfqnAf99Q&$#A1?$qy9yWI8Gx(6`w%FjPKQj&6Wju+XKeE)+pX zWWm8$ZIy*c%J6x-M?+tCR7L|o){@`UQf5@(40i@>kB3C?#M!1ELGO-!8i_qBjv z1g-EBA7}JuR1_X}(k{-r5M#f;tL`W9VLwWdtXM&m#mvGEi`?Xg*^H_bI^>$H&18g*W;6(U`4j7+aE z1N7W8GaP>mS!BR+d+xy1j&pZlr5E_y=^d&QKa;+Q%Em2v0pzAtErqD9FXl2lMu}Z^ z?z_z@)Uvh2ABc?6gitifiDd(LXnKtXOipB~tN}(*wyQAx6bn^u$QRfs9gn(^#CN&} zfxSRnX$&SB2ErudFN(C^#t`ig%-;qN+!k4I!sbEx_byCNqlX$kuQ`4`4p**m3R2hO zz;v#ep#{3W-BJF}_}{iF$BdsV^L&uX%uXILlbyi*qsR_R`k8yhPnpIuyFBvk7lwN6 zmr2h@6)E&5^2)4F;1AOt1)jCo1iXp%Q17eCop1BA9mXGGm*%T&V5xKKZRy32Ludw@ z(PBfXSe+yY`jF+a2Dc68Yn=#};8nDI)7n7*dWuEb`*$6KJ4vS8Xhesx)qs-A>&oP` z=}z4AJKsRPDn+5L^M_G!W^0$w6|0963bPBrag@J~rzd>pFL9HK6hf9iySlKk)fBY^ zn&%Akhw>5O1L)5ORYO;L4&DNt#ViapCR+lu zv*Uw?pioWJxTX`F6;PW=oUlZj9RD<@Dnb zrtj+4uhO5+b~_y;`+YvDS35@;ziOgVN6tR#_L5|3jsl;PmWF@7>hxzH?#1b8Su#wn zpb1i3<5*n`SObHd{dM^1g$#W$7x@&{nfJMv{YSULaFT!e=!C?@1CMZn)V=I^I>3d# z69C%Eh7pm}D1+ZA`F5vC7IQe#myi1s{+Qh88%Ni&eMR+r`>UZ~tV zx5+*KLE#!}_I?W7W}YwIsh_3JgB?z*d2$j#Nce8Hd^BJ1(EPkO#)z*J}F> z#Q4O-_wTSV0TOFfrL~M=gPpR!pNAWj=cWruI!>6h%EA~9KW!P=Sdxnfjht6+h&kgF z&-dkJevm>g+;2Guae<ZTp>8oYes=O!0X_T2EYvc2*I8TMQ>T%ybG*L@`IvMF5Yj z5s%m3z)9H+`3oLQljGV*=WhgsW`r$xvJd^x%~pd*-R72-W1Z|5uFLPFQnIo%u! zN9@9ZtD9_@FEMmMzSYSvXv#U`>CeskNTba&o;h~H>(MrN2y;M!lm3@}o)fU_r;7(R zA~fv^a^gEi-Z?H^W;uwV7hq2NT334a=Q@f}8TdiTz6|*bDE?|LD0U=B0y;dAoan@> zY_)CE$C_c3$4B>?Yyy_K8Q|z4+RIpG%IFhsWttZjwl$CgNV15Ct@$Q4OBB~oA3JmN zZD8=n6LxWYsy=F`*QIKb%;UM@7R5bR-KZTKV@UZ7^{LduS4~$heQMf)1~#2?`AK#z z1`mdJU~2F}PFF^O?;_dZB=-fV?ZDUa_gKV8e(r}>GGh$A1ptZJ#hG$#$!DlO*h|%= z#I0{_zOnyM1CG@9(P{T@l(ZS&Y0rwEP`^X?d!jlVNX%Y0t^1;&=f(G`_ZGO1s41gp zOk|;yc|Af3eCN~3bOa3-R+CxObJ8h}Uz{+F($e0+le(=_-QPs)9Y_3@Jt-(UAeEk9 zs!zv`6CW{_&5iv$6FxzY!}73<&irOIe))$@aC3{8a6$ZM924JC&<^s%vW^Vql6lkm zm*-1zwgChCmM=y8&M2@YQy0JPn079*o`Y=MuX1cU21@V&h|%;%n| z;%pV3WAC!-ZbpmHFTdGsAGz>q(4#@o<@jd#`x8RS=Q#bAxoY>9cYc>J$s7-YRGHX( zAX`0-|A6FoenN=4yja!;A#r#R9h-P;g#FOIiLIsB*7Nxzo!`deVKC6UOgzz3d+Lt; z0laRHU32%UU*KBi&ej7liv+S`R4l`a(v}8B_P8z=39TB>>jieB0!Pzg(>*N+U5aH@ zQ2LGdn#iOZoCg2(hW)fiu#LO^J>WMFbeQw5t-`1Odd4AbTjrEjiv!rd`~Hd|z;-T| zy!T2;)mRZr7q(ve021jq`PTuL4f@a+PY%ozLfr(Q$-vBFZehU@+EUvRsh-wHD@JaI zmeQ>wVhE!PWdV|asr~hM{FvQ*-L*O(Q>w469pN{X6afmy?nf#V0LmZiuJSi}=)90o zS1Ju`T~fJK1J#U2Akip9tXpL}A4#ImkfnRW-t*|x@q4tj(JAmf;&N7SJWrdUAA_Y`FA~t^SfZZ{_NJ*U8v>e- zD}EsY`n7Z+K&-J#>_KDb^NBETB7_io5*p8#RL-Ssq@O}AFg(zxQ2RO`O_fSi=(2Gj zl3m`&fC4`fKp^u0+!to@9ay>llN5rf@;9EDDg^{fm3~ovy+3G3!JnD3D^z}z9kLtm z%?4wQ@1=isBU(mbB5K^_HDo3xH0O*rWpwTkG53!^u z-K#*vqMTe=$pGf_=DU!mjFqqUpeeC3YmGU`T%9o&BbhqqhcJ9@^dX~cpiH`yqG_|n zlRcW;kuwt)nF2^G)c)~u?g}vYU=|=fldcR-P$L- z{{6PCY1u2*ciTI(2vvsm^f1bmaVGUw62WIV3bRqhLZ2x@dXH^5)757rDx%t{wipBQ zEz3}YC1u<8O_f#w6Es}!D+BWnO7Fus81zjHKX794xZh5TZ^$0W3>k5qKYVZ+3-FmAxpYGrzeotOl`*2bu zTDNUdkh1Qw+rx#JLgvVB@R`w+Bn#G9lkcy9-{M~7yNyxY#+XzbuRoXcJX7-nNcO^! z_TGmUW{n4a(Hp)j%-rP;HE-PxNLMz3lgi(3KSE-BJh1u$x*=L_4qWrPxq6O#zc|(w zL>C#!T)jz?8CFo_dPYNJ!$NXv21x%HQe@w9vs78^TyATONMo$}3yT`5J7EO;zTZ+*sC4C0-n~E|8Ui7ILxM7QaU?Vbv-fP1C1lLv#T}?E`znvAmNhd z9Veh-aEql0r?mU~g)9aooRTwFHlz30fF09?X3=rUfa4$l=WqV30TOhV9-f?wqeH-i z^CM|HMxCPsR=@U57px8jbE>@!#wm%O0b}XBrW=-+CwGx8IQdpMh_OI6C3V4Aj#oLQ zw{P)AI8qWz9tlFY2N6oc0ua-f%`jIN{uBww(8O0@4I*52YwI%gr80uCvQ^SABS5%I zS8Sh0L`>I{k;uIC5h1SS=H^6P5zj1aaiz|r277-NhD7fJGWkS0jsjWH-+ z*j+##a1sM)_ON0OpwBLyjDVlqT}~~!PbR($MUqiJvz;kL$O1H5n-(SyIL#-Mg)DOA zCV~M|AGF1v`TcHc+ekax=sb(`GIu*{D9O*tazH?VpAadGOv{Yz3<6bh->@w-_(>ZqJ2ON_x`#Y$_VXNpODF)d3{z1>=-hhY5rgO)XyF8o1>Vq*H*dwz=7z(`GRlpACyyZkpPcw31m4;BX_u@)#9? z#lAJ(>G|YzzMcS&$uv=&i|*LcTsK@{1PrzG`t2iCwuKHUymvptuTpXMSfDw$R}ji9 zacN=y;f<<*d%=Od!qYB(gT2Y7aB=76vuF_IzsXv=-)uHc>O=$(Wb6duCYr4*?c8>G z@eAMTu=`E@2wOXxDb*2HXsHLxZi@PA>)eL302J9Sq0uYbeji1j;fg%x^`DgSi0?|3 z#)yh&z#^+H9!?E9lz?&TY0b+YUH3^NaplFVPsbB3NxY-0oXLaNh_w1=+UvtxQOl#x z!;7GIH`f`l=uP8bEy)%12ZcE?SLvt?wl!D5aqklWy^gaFdNjHt>6JQTnBS1ADVZau z1ntT6UH73O1t76ir%z{2KhYU@H;?%4h2Q|Sy~gv_tlia}5DqF9n(^yHlKpw+dQ|K} ze|7flQ`zFj?1uq2S;h*3k>>z>r@N_R#*ATyFHIP_a7r`?-nY=1Y3KYEZ5Q$%y)W=H z=ZSN_^-1Y?FU)wpu=P)s#euaQ@vKOzWkaBx>@rwn54#d zT$5<+)=j|8IeG7_DXVS}Uci3g;NW`bjTEk=w3ID;A?x*;3fLaPZb{X0Jt>nS=p)eK zR^=ZTWn(t?(*tZzib0AYc{%N5cfPH#Dri{;47*1em64HXlqV0$mq6z8&L1oVcAnK? z7C?GQ2rT(Qci4{k5-Gg|z&X!FwP}?A-TAA!dXjZ_5*A9?5AnjJT|PcKt|ob<65=;f z5JnshZ(8xyak~WNms{Xv*<rrmV@S5W{@iKCPo3u%TuJ2lTm-wfk-TXtE;UlAA} z1OuXMAbBC;nK`g&S^)N+2on!DgCkG555fDl!q(uQ_q6zwS4eq-S1cc+OgKNc_USI( zbd^BdY6RB=fbf7A;7xdZdI|whG{eXA?B*~mMA{`&`@=+rYYjCeHg+*PuBVLN6 zY&EXe1!oVJ^#tZP@UzLg-s^{n3Uo+asgcp%n>P_|p-1t+3*nM|u5_L};pKR?j0r5mS zAdq7f+T};OCga-?`00^=1O9*(%nh-Rmg474ZvGW~nj>6)5`OugyCVC-Q&ram*xOVi zq*ghn>@5&$g>ZK2Wm`8q=kk1y2-w-TTrHZ=$&hMFtvpQm4_dz*Tz3^i=AU}lFni1w z5gc9tMv4FA#tp>yCyKZ1^vvN-WB}**(f-4_q`5MScUnw z4DH&QiQ)S7|Fi(#b$e_4ZEMTaNQ@B#R~F?S*CDz9eGW8x6658LOQ3k{^(xzw>f>Cs z6U&CLDzwH$DlN;m*9UB@NzKc#|7 zNkeC_m``q5f19;&0;?)T3^an+|50Gu*J0Hzc>zF{Y%1GWTw_= zIOzSNf`TAXbbjamu|CeWK-X>2~vKz4D{A6{}s44w+dt7@Y`(KKTu3NuO zD8V+<+xDoVi>O-dMjbjxB240`dOhE>Q$$G=u%#uoBol(kqXOhf{>oWI)NWEo!LL z(9mlpAgYEMpj~+Yb~1}6ve_%z3PWimN3m!<(#!EgXf`$0>KqALi~BZ3qyyq*4>P&V z*;+<}FB!o86ArJ1j2oJL9VO50B!G_-kb)*wcs*PTLpou@JB>aO&j~#6cgbAmtC9TS zm$0rlte`1%P_$Cy+EK&kh8=O@>417b#-u0};0jq3W_q0*M#qE|+M;+>mMl|H3LvJ= z-CEv*A1ax{nH=*1LT~|=ZyY1KNLa{%mDCjUw{et;>-R9S0d)f)XB6}Ass^5Jd|?Ym z!7|Igev_>tv6n7&q475$=^>7yJ63!6mhEvJN{rEO`T4RRRfeEjzE5F9TpH^Vms_oF z)_4%5%1#3)w>@}dwmc(c4-f12Fda3baaVtp=E#&Mwif_+6;xJoVbNKEu#*9>-N?w1 zp?opX=Ql+_Yyn1uZ*zJlI~9VUZjp>Y;W9*2^cR)uS6hYGkKKsv)mGY2?mTNTnh|pU znR6+rhLki6iNxb`aR2tAnmfWw{n$!A@Qh!osI zjlFAccGF73H~CBkIgj-U`9%ixtokM^pfo^11fEudt26v3@p$3o-9h z1lvE-IkoxIP4w)Rzrd1>vTH;^B#+zY1mKo!?>9!5Z`>m;9O~3emhF2TMlv@UxE6rk z;thYXWA!%xSomCL!8fLKnnT761Ak1Y28WCI>g2)~MnI`hDi7ITAObWlP0x>}~-ht-NTV1g*B0 zN1evD%&A3PbgERG>tZk6#BvqF--*gBF|Oe4e|&BO#R~OF3BjAmZrRNE4qs&tzmVW~Hy@W-ApwPUfH7H* zjH%r6cYxXPa(a4SSA{oDCW{MkZHaKF8rkh6T7eTGLIwv#58FfEz!1kkh1WV--r&~y zECLm2c}GWwL9{V#f-#U4(}%`*c;gI;`t%+6Jphwtp%__=ALFIVY0XoYA0f2`2Rx+O z>GZ0)VwylKzRaBDT1aZe>Khj)&`v`*etLNEeH;fv9|{b+LYo`^gt@J-sqFN(pS(c& zTjZOq6Mz+8&^|T|SUPc9B@7m4pzwq(3XX;>tzm_*B5t`sFc4+o!J1V~DK86}e!eFZ zg;D*^f4dbu_rFD6i6IO)f?Brss4EQ?W4?S$2_JYxBJpG=$PViFmm{rNdkwj9H=AMtemN=Rz?D<>6xtn$0dz zLGr`J74%i5P4J^=CVL}nn4 zZ1qUGLbwnTcMC8;YT*BIY-ZuQ{^!{Ihl?geJ#ztFw#1hw-gWhNcybZjba|zC(IL`R zOF!sg!#RPn0gr$HL~XzYPW%kY{lebW)?ErOZ4~CF|7H7hho`s6T&IG z@@T9$j+k3b2t1?zlNFZea1_?RwW#lSB;+E`oN6wL3;G>)~oOfp3naN)#iKEcrcdRQ3?v-+*Y_i1l!i)h( z+P&$6`j}UNQZTJ6pJDlp`)ba z9q)IE2qTk>#~kGR5FRAVfRy&k((prEM*#1KA^<|Khu{?8r&_zIK#ABBft0ouxr_}~ z8xR}hjnnDr=@CFeNk5lhi%qGik6c>S;Hb~)(g|brQv*zz24YwD%|J}1e6$437oUWU z(~zM}m2M^b61VwU7@W=SsJ8HN{zpe_4?3uuZ**e;9gZ9KgWr`IeuEV+@X(B(wN%IH z+u2ptZ>7lG8aqUc~LpyRT4ffPBKiX4looMa}S@7Y-Kc!=J4628wOUAi}ce z3Gzd0XN&g##l*Z4CIZU!UoVLEaa`L#P7-V92=Av&bJe$6*C&yu7@1d{ci4{jFTD~9%idB&=ZoH zC^+Q%<*_z-5==au-yN%$!~T%T1f_QlKc*=@!`qZM=o?x*oV?ubOCcj8vjAjH74D1E zK@Fg(!dYof9`UasC0;joF^QVc(ig+H9CW+LpUZlA1?<&PEPl9q2E2eKnFx3J0a+S_ zRlw+i7Sfvx(D3t%RjuCVM4_VJPK$~;^|TGn9!+rtOX{@CK8ddbb-++f>dUn>7Q=!3bZFf*@q!_;Rr+ia{XU;!)8XyN~?T^VDn12~4 zC%NpaSiyaH5OV2$`1B#n#2b}9-cC?VHBNpcUso{QQc<|azL9Thac{?c$Yv;}xjUpQ ztR`7SP&SuQTyV9;gl!M<-Ave~L^Q2P*yV)H1>F%Q*;(gl+BT3R^6>!^q8wX*SH)mu*OUDbTW($SV=Uflth{F zjJNtwC2o+L{D28n#zs&dPwQ1SLqR7i;VKQs)nu+c?kH9FgqAsF{PFz_QYV_DpH$&v zplYLBgEt+OVCCJ&|D-(_9BdbQc&+G6Ew7VRwP(6+vTQwyKmBi{3}2U^e0DY=JI&%a zm+6OWK+zn10tSxvMRdA;mL_kiFPvE5(TbO#pgxpnYvqn;&#ZHTz2YhKhNgvCPI9LI zgmv(ew*+4nR|UQtr3^*!-t5r%07lZ+U)#+j)#n4a_h%6uTVB1x4@2o;lFN^@g2{pf z=TwA@)=vUV=clvYsEsR5snj+uEZTaJ$~xHIMC6a@}BS2*~QYP zJ&ewQt!fuqt5YZ>k!MbtSstM}ble-eW(%1wYXQgD2QDr@#wbkZ%L{Httf|tz#3**^ zJb*077B%(s)o*ws0;QJoeJOfP%N5%ll7PGiK;cBleW!KPGpH*Zc(Y6@zT!QSxpKOo zJ5o+^*yKhXehzvDQY+r`U9o{bTjRe;Z7>%gkL=&}ph{jH zx>GHxuRO_a8t+s=Suu|RU2XEkB0Bdi5Q_%Lre0fx^nSy~tgM>JePe9$p76G@VE{-p zSdjR?#3V!V8Q?Ty;2FQ`A2G8<3N~k&NNRqu4>iI08%~T-Kz?DZ{4Ybk-5EHf z{i~J@O?I~Ao^nLQH(%{81KsC&Q2N4J4;?+kD73{wMB%XrFa%?`=5(5sTyCBH_4_opdu zO}~FkpV+U7RzqfS!OrDDh1wh#)`f_u#<#sKPRd==@828BWeU*Pfhj8E=%^P?!PaN7 zmJ?8m?jIeEf?iz?lb)cP?nLoZoe4>F=M^h-Bb01xh{x0HDlU(UDDFgYWmS%DKypJT zKqzAPa9)zYPw#<9Bl#QNa+cE9Cg8HxW;p`@s>v-V*2MfhbBX@IsXH(qvi>$#?l@*g z1Yo8A{Aswrqx~_WZ2OTMeK)nP@cc;QY%6y6`g>xC$5`P8FG7v+phmJ5-=cWl{KMth z!|t5VAAW_lvBWNA0yNFel&r>}N*~XUb;R%2)tfUYeB6^`wgfx<9mG%NhRqgU={_hl zrU$==28mPruu4sV3|ypN4KiKmn~?~KKZ<8AHN+w{=0h0w3N<|a-`d_dAQGkyyBgkI z;{tBf3DBkfEv}o7Q5PvBZ*d$U@Vk2VHr{Si;v?@s$EFVoj2puZg8f&Owgw{EzE6fMi=hS z0VL)1(*x=e0Bmvu%>ZxaSO`@n7%Ac5vd-t|1Zw#>oBSN@SBUHIggrLQ6Vo&@+%H5t z;ne{e_HfDoUr0y6D1rpmMCpb-xMq-gaiEaI&`7*rZNw5wzmVke{wEV=Tl1d~9#y<@ zAkCP4v9NAo4=4Ud8)mj%7hheZCk5QdYmOjPA^`u0$BqOF5N(cRGMDDJ;2+a*=(D5bU zj~eA0IGw*4OY(xDwblr?VVDpN3MwiXhoPnRygEN$PFi|i1~wU!YWXS_{0`AZrDfj2 z9^T6*Dd|auift=np-W=ZB^|XAoPM%tNAq?h{yjH1$bPGgTTugp1{bgM&OjMVJ}mgd zzGTgoK0TKygY#MriofLw88;7*MJl9iKwf@3=2iz7%IWr%Ek=ozKqGCk?)LVM*OEZw zb;(|<0TT8DJNcIs`F%jXFBL~^VY{(P9{Kr0*u+fT%A}Oc9L2()-tjSu5#(obQ8qHr z6f(OJg3*D9uHJ6JV!N;Dr3*n^7rP4es0IDQ*KzV0m(8&X@f{@-2#^F+` zZ|ei#mH(vDSbr%j&8^b@1?ibJu<+vY6+X_~A|G(>&WtLwk~9m)so#`l^|v)Y1okv3 zCF^CAY#37YsROS)xBOHsP@t%>LFcV~LgNl2Hl9GcZ?}X_%*;UYMR39!Q04eiB$rJg zOrW=%Da|}~xre9sbr*Z*037%3PBNnVdY%E9m7?@W&9_M7WC-M(R?flhQig@ajv>Y|cKD|9`m>t4 z@l&>cXm&QppA;!HloUi({UHyVI{$<8zKF)+@sn}dgOB9+_Q;^_Skw1zo-MmZA9?J)PnIJlAvNBd?{i;0 zj1Zb#jJJ&Cd%rM&FU|=q?t7%Y9Tdez6EnVN4P@eWsiCiQOZC#-zZOPrbVa?T?X^FB zqGTC)dxenGRqwK1CaFBAkJ-7h!8EoVZStcw>OvMwh#>Rd*txjaSXpC#ECYazc7rVi z9tvd+moM-%-!3~T2wa3Hv<7IIkzu8r6VR^j!k4zy=LeL;^5wd5FZ#rV$a-RI0q^~E z&nJgY^AhR;7z1uU^L3IEtlLDa9BO!@+eF(?R=scR4}lOck*R?}C)TsE#usXAGC@JX zV!Rxy4l|AqJlWxjSJQsj8JCI-jB=_^VuU=00qPH>2=~oK-;x3nN|L1r4bXcBgBK}F z3@ITFprRU(iSto(zbIM`sQXnw!0r52C zCM>$iBZEORO!SC(nz{wrTC$`1ffHhc-km&JTC5+A6c+1KXh{~JEz}VnAlczdn)5ew zvnoO6tnOWp}#Ua6<=s z`?2G}P{Pq~iN6fcpmXtR)uA%ikS6#Ic6U=}WDo=U&=epLb(f;xl;+>zG|a`cBkyj= znIL739}hpW1)3}$+QT$IS14Qr{8W-OLV5l^yjJqT9^N$Fm%36hl}})*K#q!vsy{Bj zQ70JXju)Cu{%_ul=6qnYgo*iNsZAbVreRyMNL+J?9YoQBN3~B{<_nIZ$&%4u81L=p z$k8apmQ&PQA5;9O6Zhboy4+l25?d?PFAk%{@HbCFJPFUs**rHXGX0aPCmO3Tn_sNE zbH_`OV&mWn2*XLE0&(+M@M;9*gC~=HDNpD>uG~gp0r86B2}v4%*VfLO&@R$rB|ihx z4&Ge*DO=LY;$)qTUMKqm z{Cz|BbYR@cAqFH>FNcCk^Dk^V?2A>s+SASs4mJ)>R6w({B}R_F36DX>ayz5_{&c(k zj4YnE_U21Y5=RO0LP~dj%D|r|7FOS-3Ou(2y1Rwoovdd9UOU%Bl|;dT6qNv^^~CI* zgDl5YxVekrI8lqA-lE4 z0EIxRzqz$<(DG@oI7n~Tw1R@9uqfx-ZcgC#BX`baci4@1W9|Eu7`7(cEED<;XY^{{ z(+=-M{G@67wL_8`>Xbzcg{%(3{+s1!=;hVGi%j@s#-{D}XuQW;>|6~%|Dr<5<-5GB z10>xK3=NUtp;UW4K>*l{dn=qRo$%wqZmN}rlZ=eN5R|``7Pf@Q^c;@U@hb>m?u7n6JxmxnOJG@6iMak9ktF1hVx z*dY=N(+-%pP$TU^@*M}5F~`0F-cV}VRes+maHgvjkG`$x6fgd4qP1NIz9j#Y{g z(l4!rq!OE-%z=#tC?f9yMJxg-)D-*BwkP2h({rmFyx+%SmVov8x^4N?-u)T%9(T4G z#1N5@L4J66kmAK&;oRn%<_4A%U*Fvk7Kf%l`Imqqk_8($myf@w?G%{TQa4Gom4y27 zQk zBGzR2CY1sHlo#NnSjFl47dI73V&JS_Un1&VKUsA$jgQ>$d}96Z+^NILZc#VxJQL-d zEro}k_EXfek~wKWSSapLAmEz%p-F3a$hUei$kL>lQ7|j1dn4ZLi(AC(to%2?Zvt#q z&9Aj%{dnkFGKXlNX{2)AZy5A<$xf8HM&%&Y?f4r_Yp!@c)P zOG-?ENSi@3Ff#&GMkl*VgvjH}^Pi~b=OWStKMP95B=a6sB^@{_VC`NkXR^0%g<7e) zJN(zyd4rM@TwL5I4uN`uM|`y4h&Oozk`mFewerK*cYU?WH^y{ z#*;A7P$WYc^L>U07EY%N-x8#iKb5x}LTx zMd_-G0iZ;jz1{C2r@0z=Q0aq>(YP1zwKrvrH#3k5VQ?STn6#?nf%qC34wjo5$TyeH zx!G9>Ao<3f#sY3 zg+Nf9zx6a{nFvt{1Oj2T(<4XzK%bYN&t2@CHx)F{gCr5BZ$5mR4lJ~mQIehBjPH58 zIf_L{0we|_8B6jhzaQXo$dk}7Y1?Bgzdb%ZBPR!<6j761wMtafmXoVabSG?) zzwp<~gyB+S!Fnfb`wJ*)LpR+~CCNl030sEY|EC2Q6(8xM*0FpGbHpitdUC_@VS)hx z-z_h~>OK8L>JkBQad{tt4akEbZPrmd^~ErGA#Y5F7znzC8M`|>HC|7g5U|S zZUbawP<@)bFXDemv`-y&a9ug(pu3_9cxr)s^nXy+_00`Fv2n56fTieVo!*FFdVnsW zyc5|TQ`AH(g^WtJ6q5&PACS}xPgqlun!pEDU(!{AT51MVk`Kck-g0sbsHio{*e0EX z1Nn=n4fXYu=;r{|9(TvVl{{r5Kg}IISDYSvpr=yVtNz!Ro#4i~^6cQ?<9CdLF~6C% zVOU?~JBJeul zh)Kd52MX9H?TON(0l9A|5_@Xxw%o-2!$#X`-$tY{>9CO~HjE$ItwHkL_ctaS2$wuK zSutIl4ct{}TbGxi@f@_TZAmbmHy)X%JPC6}D#Y?me0F+9lZHA)!viPpb~ty(6~3l? zT$=2jgJ`9IbgHZ(Zf|Zb=8d92M#1;$PU{7%1+%$&RDb3NPkNGv=79**7@YKFZ!Tq9}lVL2b~N!B;4E{#K1r&Vz!~R7Oz)6m+9LAXGae%8 zY%RQ7gu1%CDFE3ej(_L5B8rdz)^u)F=vL=u&F~}~xqzCT_gpu++x#Y2SQo4g3A`?P zakk=h<>rc8(VQ=%#E^hJ9I}y0YHGkDIIFtyZNOewAan z>zfTRw4pE6*eg7=xkuHWffoG3Uq7eDZ^E1?*A91Cv*!UEEU(^grf62lUG0NWf!vS#E8sTg zA5UkRUE)@o*7FnN@4orBmFwJ{DK*+eQFxrU1RxKf3mpNO_anr-^R<_9wy*XqNwUZw z2R+xO1e*&e95uJ_<9(AWI)*a7M&H08SvZ)#_3p?Wg4sVRRW0LVfm=RK9z*JeiWfrF z`1-0bkP+XTgtqdMAxDpua_<|wG7K#lSovo-C^q)JzNMi&X$nfNR&j`%n(NUqQ6S|H z{=nkLP(n#cz0^fNfPJk@%+Douz{~jv%#tXdaH26Wl62Gb4A}9-V5|%#VOg==imXJ# z)jq$MYB!$b{++aB?@u9)3cMw;mM}b_hCH93fYka$>?3}r4`pO!m(jwEGpp~*W_F#S zVeyl(ePuN?3S%-7SG?nvFpl=$Zj<|i^|i#c^aQHPwc`}i%zsS?-N?7n<2Vt8VE;BA zoXitX17mQ&QOk1MY@u?+{;U(?hWR^Kqbg2AS~_y zAWiMzk~?fSV!t~7bX;>~n~t1sAD&Jc1fxH?us~11BpwaW;%0nJ_hpARMUs@@vr5+E z`tu09r@)j=1M$3Mi`7N7WMKX%ts=MwE1FWFf{11yBd#*qk{t}zxXa$3t70S>A!wd0bSX%cji>C%0Dbn9T_0D?^u6tPq(M} zr=ww0_%gax`ehy_nfm}&Iml5`Ux_R>7`pBV?#cpMdBe)&V-A;aU|zdF^T~2()6<-R z+De#{U6;Zm{$&rARZ?=eT=A89B_kl*o0?#Ggu%n{oC<6{JTe0dj316T>FKrav>r~A zHe{ux9l2H3)z@o!k30Fpl=n&24{?r?^m*Sy=V?Znbv6J^Q5&Wf+t~V2zyA1v2LB(a z;1D0)?%UC&5QZntr_mQDy?t;xhwjr4xz9Jwkw3!>`R0(-Q zKU_zEEH{+k8dfs}21raCUBd*4}%yUB@y(JEpic^z*_uBKpb&E<0~<;=wHk z1qb`VY6)vLeVdb+6dHQV6N9Mx9wa#4c5A+$HV^^ zwk~A&3Pt0`^%z5ort!K~kbtxTi8{{aC1^9$da39jm%|P4uJy%PF%}QTs4f?sZ}51C zLE!yp8kDyaj@RXdAsE8KYWo7uKqO|byZ4mkHaqBV78`k3FEZSwK%Y5deh}(#aF$dv z7w*{Zx=&rlSlW<)^Hru2_+yIeQ#Wk;dnSe%efdY|MzNng)6LDrQXDMMxd-(d@xfrl z=ueC)94v)=+YsPYM&rM>H>`Ti>y9z+8TP9f5G7(CR2P;vMDPcSDB+nF!!%>R=Kf1m$sH!*Go0JY| zK|+*nm2Ls)?ruSl4(aahE@?P~ba%IOcXxyI`}lwF{doPb$B{Y1xX<3}S?gB|EkDFy zty$G5N^%Yk#Z-a1yuM~#B^1g?@9K|^s=QP|LM*~7j+-K?SP2XE(-sV?gar9Y)7Rjk zcK>il*ESRNMPH%t_WH`ciT3p#txYf|rmK>QFP3$fCXviLbh1?%Wfn-6ORUCLV*i&4 z@vva8xTnI9qFH9*s3Bz9*9{u}$T`8zD^_h!ZwLtV^vDumVx3Dx0w}$4>bs@)`{_O- z714gwxgp9WiMzeModhYZa4ZgjjM&x#=v;80%r#zvh6>XKv;e`vX&oJcIZxkILz_pB zy|}n*-luDnpcnYZNXf{^T&NFEMM#VY&Dj>6`Axd3)!}jD^3z#QL^i7F>SpFNCQVlP z5%q7w$#f<)CaFrQ-1T9>q{YQQO6f5YBMw<+Y!ga@;Ff@xcW>qsrls#Di}1LuCy>M@ zi7~FNx>tkU66w_s_C-0&5D}FGzBjU}O>e*ra&*XDv~-|w(Ch+hC!k02%F9(ziWSXY zXC^{(vlq%(@{>ef77QqZ#pJ$LW0_;Jbr$ezdGT}%rBbEn?fx!SqN3c+&d!@2A96nN z$(Vg_WR8p2NYO^COm|aP=LBQNXVy~I6)WcZl9^jBCslf#CNG^YG8npd1WW)o0Z6+Hr)-J3GUJ zYzhGF>Pi@@sH9nDm6ti>GGbD+e`YH7$d0_fe*=Cg@vWOa45@~KGX>E1& z@Lns^?mLhAyjm+5xk3JF>jiULQrmy<+`z3_K5G!)(p0bgj(V*@9i#*O0PDDk=3#%> z4is&WI2o(gOp`=;;j|IV(j;6CmFMyVf~E-xzsYNI1Knwct9%c(3Pi`OUzqaaxr`{E zB;zAj6~4}BxT3k^QxjSIbUY4;E%eYSSHhQT*?^3#i!t4?Kie+`)4`vD;Slb|IMLD| zZo_y#k&Z!_)W_jGPv^LZt_U)J7J$dq`+R)=W4=CF|6l+bYdO`as>QFzxG~~8(u&L4 z=_7k(5YsVB#al_0gdmkkvLV+lxJ0Pt4&Kvz~S;jjF$P7`*!QjGvt4l z;pqYcOb;canisO;lzr=slZ-~fC zjR>h!|Lf^V8aat4G>fdgub~s0RXS3$lj5KD_=#@evhu6xk))BE3|ZK?0F-!|)YtzF&C5OZ}#XdAY$3!QK6SCQ7Det|+94R+Mt{T_CdHzyS*k7qh!F1VX#> z4Wmdil(?T_ji6$;x$u()4I6+0frTelE(eT`ilJ_%R(Yn|qRLX$bSD^qBm{b7gC;Kp z;=ka%ZxYh2dButGPewiVWgeGV<-Dp`gjY+Zt}+RC%Mf11a^Wi9icA{bD9wzyNQ4&= zi#5oXRNs^SloNb}Lry`^7@LA$omB=QO$kGAyUV4HZA)&q0SwykLfWKO zi42hV#-#nn1;OuJtZFsuuVji@+y6fJ;9bM;(`IMuspMase6~WM9RN0RVy?Vty05x zI-?5GgZ3xt6ywX2CIVx$kXswh;S_R4HAIkD6`~>KRkpFQv6XRIDWi|WCG`R8>gHx* zb{3-T`?fP?3Mpes`OV~=hXwoB&g`0&7WXuV#Pq+U5u3ckh9O7RK|{JO&e9PgW-P3i4nooG?7qXA=O%5TZYrmZWy;E&lUYU zgp-mGXVN?CWLpz*%3RaE_g$gYhdFMP@E(s4v>taG9?$lcgHY=#*6#}D*|xEd_!|;4 zTEFBUv-yi*2Gl)S%PWph=H>=eb+3LpJgo{z(zAdz5do6in zH_PhQS>X-0_~OROo>Addel*@^sQMIE;K=O_`8Efs>j@MkAR){zHzpoieL-ox8!4E- zoS@=ph9Z!8I{GtIcbV>qcb*p-VWffiN~baWlvl~%VJzbHGj%5KE1BnYV2OC1msSF;SE^_~9asSL zwTaqZr*NUjD_F>dm|KjBf~Bb~cAW&e=f`R*!}i%!DH?=F?`Z8kUMK~I0RW-g=F7RZ z0pVz-5&ENz5P6%jg8;h+jw)(cLV9@LYo!=1-IwAHO0`x`8lk<$Za2c_0A2>6i%TF? z8?6}LoS8tXIM^8)?Hw-L0surndXU(MFFHCIhaJC_iPlP}^E-tA^iumUnv3_Qm7alt z0w6=U5hXhv=w{d!L8}uDG$HDOS~@sATWo%4kU6_AHX`^?HA6xxbq2%-)FIFdS&_tH zGxPK7^Mn&-WBs+RU&P17iTlyZK6#HHwTn+`EGhN0KM@|kx}Ou2+n2-jJ)fBYGa{AL zKds(%)CwI3&2wvUaY}<7QLO7IgcyRzZH;v#$VhiKP=-f`%dh`^W_4B8($Z34yWfK6 z=*yhu(4ax3OOY~~8E<7}60wp&9zErbhI0DnWFT>o8n&UIk@fU!Gcji2Ui(w@>aH#I zgxkTb=Q4}{dp<##y@X8n`kBlO)4i}EX)1e0&t&L8WCR0XX$Mao#jn`&-ZyC+-4vq& z5$X9>q=wWf#)U?>FtP&Fn~GigOwVHhM()2|$U8B&+FT{-AnqFUK~qy<>T~;E6qc9? zlP9`EN6nx(OzDC(&Z3?vHIhN#D{w|%8_eXZZ0nthq_YM8m)XJ*$_hEmttOs zT>BIn%h&9Ye{_Ra8>N|(0XFq|sr4^@~0Yx-hHD3G_DEV>I*RZfG?~VCu z+?9F9t6vegC&czm&)5cOp`dTgX=bcH%8qnOv{~%c zJk+1$b4C2Ur*3Df-_h~#P;5Eo=N9$zEo)4*%D6U0FKrFV=v?N!m}t6NpOB}fYJC#- za9uW^(y}K+v4vH7>&feBdXKexqB)BHYH02-*Zgj?hjbx+m$_W4g5A~qc3WF&C0f{O z#9(JO(_m!!L1QK+xDL3|MMT6uACxtnYyk76JJlsi2$S173ca=q*(~pywPHKI-o`qY zAgZtWwb8;pPCSA<(R!v%SDyM)+4d^R(EQEE;u#I=!iNE(jSV{s(@PUrdIL5n4FFgR zR%814a;IFT_6c!Z!sEK;&Cy~@_}KH0_e_fI?4y}O`|!M4mqXK!wQmk?7JXeKsXt6D zb~^Jrr;8d05+;sr&qRv!!!GFR_64^sc2L@K-l1GJr8gH8RFf+RdR0m!D}^{ zL{Xipcc?RkF+Ui(+Kvgn%XnIp76yvl)6bbg}u`I=uoDQ8ZvItMdN2-4Mr@GvETb3Gqo8P*qpJnCSHD4gUSX-985$w zxA}??Oy{63cxPVkmSO_tGU7TR>+2P;YbF+1l*@u+`hCWCqfoJQ_k!B>+R>67!rm#T z#}egVGdSUR6zk%O#`5VJTZDR#TAI*-I_2+xa6=aQNE)}{h>Z9Ro3*QoytfdxKN|rt z)pWu%N>u)+w5lpqhn}?-+FBWXe$(htulU<5XKe_`-M0m(4OVbitMII{dCVd7t;we* zn~%^9X|_?N>MgYQ3){bRUfR{Q>6w_u2-p((ia@oIqwbC%wo>opYCIlTb>9*)wK=wS z{Wei^25e7Zin3#cyoY^2e*lswPpQo10Zta{Z;u5zJG7H2K8Y7 z#)5U$-{0Tf(eYn-`o#PWit|lW^sOJGaFL{iI!0 zxsklY7uNPXUvrw9vZLZlKn2aj&RTj6Ps;#kiTwQ8@SV7uT#++GFl2sd^)qcxKp$?Z>$?m?s^KOG&z%t^0S>js^JPAffjxUiFdhxCyUl`o}4 zIDvT66-Cq`R{%tvZfST_o;j0nTM;(q=USQcHw#emIsFq`$nah(B`|6ahL3%-d)~d- ztzlS3MeQSgq2#6$(EgsZy3&+p+-48EgoTsvHHnaLy)=PsfIVt*6Hzf7JG!mgOnLm{Ot*XSC zzbfZd`Ej>xr&~Rrlo5W;%<|Ge$jS)^;NeaD&5;(k`+Q&d}d;6xH0sPM+g5j1TcyBn!c+V0ztZC@z3i9&i z`x8ddn=843thv0-az0Rgfj96=57pI_9DkJsZ+!=U*sZSvRFW5RD|8=>Sj*1;?tRk! zfHlsAdhwCH5*`8-*bHT1Mk0W0LE>2Fy^1Qvu zq0aYd{bDnL!Ly&wffUyC_0BtEOUsCw5)+XS(z`z#jysoAbt`4|x(x?kF3gMSNkI03 zP=0r%oHbXOLy*PeNKNF&a-)B7@xce4B0FtnuqCXQMjJD+gqHH?orC`81~hF+72L0v zh6Ba5x;i?70D2ASjGjHD3v1IYY7dM>&Oov*oPquz_+Wp^+kU~>RgB)mW{y3;{B_;TfWAztmYrtRRmH7N(QB=9vN?XDTTesa6k#bb(B zqZuh}^AS9Z+&gZ_^_F8Bv-i~IC!?tNtJeu{%{!;zU+g^ihMlCzdadiU>cR;S@>OL zuimw)f-*udOBOi2lvJjkeph3zd&Oe0a1}?2o-_k}LzbtFrsAFpn~QU5{&4RSzSbz^ z_M05&8%e>%cw?FP^n3epoTALS7cBZ(0xQv5tWSlMYmQiH>g~ihKVC;6#s*#Pq?A5h6yase zrLtTIW`Q(IATI?P@FR|^n_=;9-m zruX>_UG`u!92LL1x>^nx0UnJx_K2Sc0$m7+-1U{53fdoFSlSt^SA zkgvo7i6L(f+)y0i?V+^53?Sar^7!Zm`$#9)WWLBb}uJ*;zL(4uo&S#`+yT zQm;eTy2|cm=z|vyb80l5JLzLy1hCi{VHX7u%nFmUoLKWMW9DJk@AhO&(_&CLuqXyi zoCK;KXt@>V`I~~>%NmP8rRE0O9(=09Nt`m%L%Ha89?&@nxq2SV64TL1$I7j!SPA#(sD7#&@2;T;vtUZJ_ADXYj&K({Z zp}-l;EBan)gJv6KbKQ8WXOD5{QHS~K=AFmY#`Owua!tZ{FH;Es|j(Vj^}sAI#4>UEFW32GIYb=5y(mpxEpF zeX!rpLF&Vr;{e5~t-C&)%b=OcJDrUnUBp8*{{??yVZ6vba2QQ;{XU1W8gS^JVc++u zGcxD>^&#Ii=o<`jF=lW)JY*nAZJV54%|AONI3!b(_dwE=3iE53sGlYH>rXQHfbs7_ z7DI!UlK5*A@K;lE`bqZlf`f-2aFD?s3&g;#vIkiKi#&=vdpw+re@}Z|mH<%(oWc!h zQe?0)FPOReM@FQ}G!;eQxa&ueGT?fN7a-S3Wvmr##;h!pPgJ%QzVSfH3lYViiu$Gd zCJP)+low!Q<_9bq=1Tw1{_v$_WllUYKY!l(QHMC!_{W)hpKl((*{ExqJZV%S*B~nf zbtAPZ+!h396D0AcBK}q$4%OZJgPa9tBB|2ECIuxypd5T|K0vz*gNYuve|#*xAbsHT zq4B!V+Pm4Zqs^Z=jF@0xEtb?(j7~rR!RrFWuQClu^USj%)DS$h(;u-xr$Bsg+{0;;CHF+)Nq#BRZdoCNAzqL@? z&I^8bv?iNd6i%6Wzxs(UIdw=(o`uxe7&mrd(b>f*D7=MNLnUA3I>^BQIXAf3{vCJI zT}0pJz%CoVO7xfY!n(SjOAo&G>LSGsYToRfv=b1*jQ*T5OWLQWoUtEfr1@;6Dq~`e zX0|#O8q+q#rRiUO{``qW8U64FP1~P^JxZZ(VX7D%H}?v5rHjCC8#fo{+Ur4$tHX7_ z(#*m%i5EThvv!>fvS%YywCa#pLnL6i!9oP!q0TtKj7A6N3UlHf7|OXsaL20AqXXx- zJ@gp0|BMzz+IMJeJf$RZ2}iK9)U|H@Ao2(#4#9vwu$*4kBGUk^1SuKQ|XZ*Nu5TUn-r}GRayp=4Ll)J)F9@8V*yV z*log-rnVn_{P)CjZxPLeGPR1ix;Blk0>NUHUWe1+1R!F4NwAUXiJjKGH|Y(?+!ONJ z>k|X>ncg`lkC&j+NkK8EyKL$1x>R`E`);Hubx$Zq{(uzFzR81-Od~5GWPOH@?+$GM ztUpLyjiF^EpD^yyP*F*!&b>5%-&ct=d!jiNtRX4SQczZQn20GWFCW7f`2I7>)L5TZ z$fA5SWn>c zI@64V0@<+LQim0ak)Qk*jxM6&H=*9s85Oup34s+WpKH(>@R$*(jU6b-N)y0wG%QRT zf`ltk?)rxoU)@^)--Erh51kKA!3%}CF6VWW&}WS;qHO!(K6EJAMAqELTV>^GaTF^i z%tR#N{m;8Phso5+EObE=g9o$wcOqVTI%I?P3qpeuaU&z#;ic*#9+t&cmQXlr<|83I zezxbPO)K=|=?CNR4Ub2HbjB>@Hzl^b7nk+1gPM&uSqpvC!pW&@tUN3yuBfQYpQwZ_ zWY8r~pA9DluR`8@(#F{8P}d$t6G)?WV43W)m5)TiF`N$kTXuMTPo0%Sqj;boAhFD~ zRa=rJ$o^aAxJ#1PjC6djkfMwGL4aWb>H;VVn%Dt0CeHP0h4*{wWqw&5@f7i*W>KS~~Jo9<3ab}7z+Rb3z zbzFif1@BbTq=~Xf)9U_2ZClEf*3T{#3%!+4b`Vn&Jr1M$iVF%r=1W>7#^f(bJY@g9(^J_K!2+)48AI0HeT7d7)7^00 zKVYo)XL53UcI!ygrH3&PVQ&l}hJ6QhByYaPzLVf@kHtmJQ4E}QnL4b3((i`;@E5k; zh-lqjFir-PRAD5;+i(1T0&#`+MdXLkvh95{m2erEifbzwAaaFgE&|1!s*MhF(>bw$ z*r=Pz@1#dW1mYU;63vK;W6EWSvm-&xXC}BZdMVm5Fu~Y|&#i`tilU7{(uf2Y1y;%;?F&N(4m><8$n{aFKfzBl zPl0E+-V+3|uO56gC{3Dqw>$fXd8me@u7Vb{9Y%GGqK2DpV4?GTvvVxfkYu`xJ%db( zkCrVd;Chu*WMrN(N9e?WCG@+&G_B`Kq_)v#4Pk1Wiy!eNGlmYQ){w4h5_YFTaDvdO z(BHz}AR0?duPiDhPZW`8BNqSCPcVt+e*-f*GVuODNrVgMJ2Y7yR&R zx~0o#RQjOeQ0P(acZ0LZ#d75A>97jFpZwu(2nF`(3Fs2AiIGyQIMV_=(}ok;+yjE{ zGXqu6M(#3=*VrL<0~_L}!ai1#MsHX7=Kjs)|H|!uQvnbJgFi_1=|5NQY7uxH14UG_ zu#+G`!Cl7ZUzV%U*r{b+LF_%!_j>r0YxR~}-8D6S@J(xhdl9Y#V-NgyTt_%zk5GZ+ z_;0d4^U{N67A*_ML2Y{j;j8(Nw6W^%lfgaru?U{~NhWk&3MxWC04B?ujiJ9ky|QxR zyiAgoI99~V>qkp<`Ar<@1+5*$*SG&hBOfylk(lEB8_WTCCB50db$W{c7Xu zY(J__2v)|bd*RMTPlB>#mlBdJ{ECr?MB6nEK7PR*YBIIW{>WA7(TcEsoV4^ajBgS@s}T z3fp_*!b2ikR%cHgiWDSy(iK`$mns5@CC^X|IxHY2Zl^w);dW)8IpWMj!;N2Ru?UqX zwnYpYl89C)6B2EiHzF-||0k%^AGD|5U}bGVUqe)H=!nZdFmPmx_9*f1v1`JXDl*4L zx;d}{<@8ae#~geEzjR7Fq8liN6-2QB)4+Z?BA1*a4WHjzk5+pkK~dNXHAq(WTMOMD}{o1@LJ_k zSc0F&4u|itPk%ILLe(WC;0+G)giwSx55_+n4bax@yf-O+QJ4=~{gRz7y zzbvqNB28Sq!zr&5sy3s%#Nf<4wB+z#u6*URR$Zjkx`<8RWXh(lGbyWR1XYLO2rg0p z=sivTudnXz?iSXJTk!uI-}vKY55d0Dr{51gcQo`fch<;pl)C%f30$=^be$d!dC=F; zIS{#F!%azR;CL3A7K+I9XBr$|GRvxap*1BNEc6!xo)s zwiSx&m5ZS|2hk5nrco2Z{zE8H-{2K?c6X_8t0wZOUxCAU&4TIRNJwv~rJJdpBE$R3 zucZ%HMz*p_=9NP|=*5z|I&r1Hw_USWL4+XMzWts_aZLV+gF4z+Btv?dBoL4?bmze; z`Xm=8HF{iLT*N-~LL^e4K7i~yEYpMsW_bmh2k%&-?(LsUgM-ZR@v*Vyvr0gPV2rG& zalMW!Q3Xo(lO@H!0{jgF{WlQ(8Gp56au^xmaqXsps&|)2pMh?sSu!*hYOvcy2MR|+ zP(#_fr~fe1Apv7CukD_iQzK1iu;(c}N%RAzK&!6u`zBTs7~5n4Sx0w7QvZr{+T&uQ{%PT>F@4tGGNfTIr6h zR0y4Y`ZH*xoA5Px^Fha(h1h|oKx2y(;(SNKbStmQj_U>5Yn0+);rq=exO#2t z4tOow0g4r}x@gq~+sqc{`{CKU!`AxTZgeDYbtl~BaCWw+Zk9o#mGbH`ST<}r^7b~E^o898+O$^7cGvQ9&KFM!diJE zr7~r{A53SKPx6PVme5j1H%)!sK=j_$7w?${6_)QE=T3Z0r7Do}& z?!lpQUXV#!19qrEyIDVj7 zAz_w6%pFp8J;J`>}zj7Q9J#!MrEa85;?tOw<=Si9GHWNNSuW<+}EsKu9z5d49L zzsc`y&KSMEF<1Fa4fH6%j}3J+mH6!9650%jy!z6i(J;s)MsxdaQP9Qv>(*ghO6ZAB zocRT;0worbi>vFv*jPbZ+iKNuK}sm9f=_D-!JcN+0<;!P{#BKu2p^13aF2m_JbE41 z6x)*RIP~o#bVvV~15m5=-t?Pksx<5suirJasuiu@LD!eqR&e`G`_niaRHXj=WfX^= z^zkkFKaJl~C?zw+o}i;8CjOfFaR}eH(H~ibg-&m!_C=B>81c1(BuVfmg`}LHLR^Dq zTc~%lJxHq+oh1`RAk)paS66b1isp~LNUU&f6nYX37}!}8=zh`D%e4$ksqA!gYU%MK zlOiIUJK8lCH&~!mqSvZt2ji@`$oq24#Mqu!>3FC*i0a^K@aiPTK; zOpVNVAwKvUt}}o?p*Y@e9P8Q+Pr-iu@vkKe*~0Zdpwh;=YM)TW?i|_HS-ID@!Wjf&ZtVn2 z!q^7$EU$4Qe@+eP?#-iLVUrQ16L z1^C6U?`o2NvR|Y(CjPyY)SMgF?qHdHjwU765n&$h%}LDc6{+KuRJ03QYJB3{JXp29 zTW2*2ZhIQ~Qda2Vm$`IHs6E~S7FyQX-04pn6?thMIXqvDl%J(@XByj;crEkUu&^&# zGrEc@BQ+4*rpa~WO_Ca4WAIDWrks-U_4zQZN?+yHro$XL_8PN~*m`>3{>|&=<|a<7dCCaBeUEls z9lD1yB+fv`pVpXbjRBemNq`zJ^!ur316rNSl=*^iN8Be9Hqidi(1+dE`c@D1;H<%1 zvYNoRJNeU0Yi%871ruf@aw=dz;Qvy`(X!54s11 z6RP|_L5q!cKI2DFjOBxI8-Iw!NUofdt(vr?aC(|gL>)47C11-Hj)piC7*2nWPsJDE z;RY=da^i1%OA8C>3iMkTr4+YSzw=FFV+u3;k4LZ0=BmFNsm@wo4hQ7kNB)om<*Wks zQgDo9f^N>xnB~ZXfACPI9S-=zm31g-Jsr;!ZEPw|pQy{)Hu^xoCpMDJ{5+~G;1Cwx1L3+|#(JBAwQ1{u1w1 z8(%Q#?66PIcZK)}v_|SbqM@1dGVxg;OMh70n zsG(v~x^{5J)?@+_y;QRfkSK@F{2^M8)XF|2KXx6OKdv*aSa}hxq1jGCEgiHj49=3e z`<*h;=3cH>{XOGscm%`v5r0v<$%(ViQlwiNFCBKt!)Ef^=NkPomt%~#s;DD%Z%5;* zQaPSy0`Eq|YmS<4wa_{35b)dVnF>^zsi7@}cpN&u$Y{CK-abCN-Jq9mMw*Ze{6zK` z7-Ab9L$a_bk#k&1PTq?&_KJ+jANrxp-0SIkM$ByVXu?Xj$IPz3binxZ=L^ zJ#qy1K2n7H#;Tjc4l{UJJ1WNBjx5WrbQhRcibG|jtH*;@lk^B&@XqJ-16iC8RR(Vs zLOT+5407|}zkdD7kN|^8Py5dGmb1ECN7~Mv7lH5Z8h5%akf?eiUI!Tee<;GPYfzYy z-T=I#m!sUPdlYeh^R%t3n1DtnBYyfwpc*7R&2U<1W{MJZ&#}f2c&>(R19)B}3ZAyC z*g~Y{jyPLsu7)}F%8%Y`Y7kACGExprE&Yw}CE3oz$;nw={n?yu ztd4oUSM$L2&Ki$r2|w&P(W6cP7m#iL<_Fhax>VEzn!Z z7P}kdy;?0>|4Mc;%3kqaWm@Q!7Wd_EnVAZHS=zhEQuqR1R?Bc7C;n zF}?@N>ERZic+21ECxm6i#W&4V)4SQVwY70S!`@7@d!Bp1EkQXhTCg*={xx{wC;2aJ zBKEXJM?f&5y|FUMV-%L>p{2#NZQJ_WlS@6tiX#dN5#!6bhT?llUZuMj4mdd zd7Zv-hbPG6qt}mrV8%Vst;wC;s?jL*_g)7Cwu|z~8Jm|~whIR6dWOI3CQ|&Fm9Dz$ zq7PvU@e$3AxS<%!-SN`wwsH|McFpm)buWII%g-1YZtJX$0XJ)Vp`IN~qpOhbH|m^M@5o6(_A@iiA*mo2OK>cE@~UmwOGkkDFU&j71OlOu7~L`{Ncwp{Q#&9iRoy z|L>&LoBt?5L`b04%7au(fn|er-d*;B5lkkPGAq`XYK6u9cdeSPfkLO=XIHj9c`lBL zRn32P@INhiR6QzvHx(5iQB?YAexjv9Bs>b}1y)569k%4aXRQPrhrYfMSg#(*RfsZf5@ zC$=gODNg=$Kwxd9~8Pww+ds_d*i zTuj<*nfYr8t0_u*A}Z~Y1y6>`$~A1%8#R>E&+>f3l2rBZA8vCs85~&|4o-H~YRrpt zD$=C4x0e)EdWoBUgorRW(mLhWmO0+_<3;6@r6^0QG^jy4I3gs2`ISWn7`g#fovW6V zkMi}C{K|z!ERPPe*&+o!nMkgXxReUxMYdl-Y$)-W5qzrG{C&K6O#E5%oWQ}<)+?*L z9Ln(kU8kW^N<~e5CfA8UWQA9>Po05Zq8UMEt+%O%nG5&SnbLK3Fcj@H>@2wIH?!8_ zt93Krb9)WRBzGXgOd{RgiA}{?f>s#QUa=dt8X5-DfDfe#=mo1eamz`Rc4HVCPC$~t z)C0GeqO!6yaG!V!v=`#Vrr5`AJ${KdXdWD*`^RyfoLG(pPC7Plc=K5PZXM83=#zxf z0{wFaM!|Fn6vOY)V&XSzG1JRz@rhOc#XabsAo{=UlT;JBhu8B9kq05d7p*Yg4%HAO zCcW#sKa~#LdaxQ5Rze^{^?2ziOJt17MH5pCO2$Uu(rj>=P23qQrfky1&QX)v1S!({ofH^x;s!9LvYqI5b%mgqPV@)Pdyv{e+ ziE6xKoYY8L7(doLDag)_0Xk6U;vQOje!V|A49gbWeojg^Q zSf>BdKKmcs>jl#w@fyrG4Bs!{fQ-cwsM1jBji4lk~X5d@&~>Ph$Nt z8zC6+yohJ{{5MxVbfV2OK>9X)*mMZ?@i=$j(fZkr$4(GG@fc>Q?E7Eh!09Jarr8-R zT!|mS(2XvM)esmcQ#tQie+7o{i#SMpykM z2Vp;4Hs@$5mb!Q~R4(Bm^Lx*kWC{OY4mPW|-U3kqGD$}hgco>kg{Ko+#kQL_&NE>V zzrCg}A@>}Ymuk7tz`E~+Y0Ch!vcJEt4-7M{?|84HeuE?j zIci~X@!*P$1R3dKg?MDeLBsc*)%l~NGF;r;$?WCP0Ri*kNg!{M_$yOr8rjDNVu;3+ z<5bFxhu!;3txJBWnVns`*)&cXy;MY&+wky9;Qrva=$EBB-f5HWz~D-YqzDc~Fc|R`)d9l%S-n(*&*-u#pvT1D z#ak{PHL&Zue5aya1*GS|dbt`@s6C-2&BmstdBE;at#u<~$=~K`GuRU8eY-1~fdQ6i z1(5S3o>f`2@6gU&NL8+{KHXJ>SKxSLR#|Ke{H@{w@M0v?F8&zXEg&%})3%=^{Hw+3 zla9I1R70TBH3Kg4$N5C^F>n(=Tci#XuM=NaGV@!L!Hm0+HQ2nuR8;GBXT)5}yRKOP z(M`6X+#CGdXUCZmPBmIR0F;RVxa=h<^Iycbd-Ke zAnEgN{mYJ0==5Cu@@AUe3orxc7h2v!-v~?JF4_GYe3z%mpkipK9Lq&z%V0}dNt==A zUc{FO&`;oHffEqwDv8tB8e8<&mcDRMa6|8n#1DhkiWU=;kk+LmRQ_!A{P^MMrbbnF z+dNDoIo~aS#fuI=(4jr1fJalZnJg0VL*-U?Ked5~JeBRR$;#Ma{9g5VfXz|qqP+E} zX%WjM+kP|mofuNnU&B3}y8^O3yPwo}60Lwq>6|d(!4%LEV26-`QkcDYbYCy>oSko` zFvCZ+H;8ayB?zTEtra$W6>4ESJL$bO{qM{c0PMT%nfU8N4c>U96Mv3k?Bu`78wGkM z5fO@LF>jM7!z;pynb#YY5RrgjP`OjEYcf+(H1HUgh`fNxeQI`$xlH6r5s2kM{SEi6 z?_T1bCJ$7WZmbFNzzT*F5$O^4(qu2m=m6+?%*zjrP_5X<7P&e++~2e`G~+IT+f#kR z$!GwNbS)F{Q+tuI{;kN6oe45pHy=V4BLA)jtJd(>U~v2MEVEQW28>Spzhtaxl>D&W z_OPFxyT8AuW?+!4ErS=jU%{&9n<4NyG`(8CRo^u{l+0kF&dXH#|bW$skec zq8UTMu1lS(v&|xpe>7l@HjJSV71XuG*Wcm)ek?Pjc{|(QUiKO|87D|j`DlAgmOyF) zR0dhyb=`7rT7%sit%iSfsCyp1u17o!%ToMLxG>Cyje+@$9KQqMp;glep*0E)rsYzo zsVmHe#Z{@+m>hXvn))RoJ{+0(t6#ru)rm;nF+V6dw(TliLOa!oWQW(Drgy(sdZu&C z8_A}M%3ps7sI$s?=vYKNdVr_>7T-Ln&Lzq$vBHPak5)VJFhOVkye*+}I&4_JDC4Br zDEnh|xZT=EU>eJ;?Or5X=jU-hVsHt4YN~kD(f9Bz+^dggy#lqpKba$SIbuTK;}q#(0WRMachs%g`5l$=D=m@z}?|_ruH}lF5@3w(egDkKSMS zaig^!^o5De?NDubjBE;WRUW zzBh{z;?+vjl{hS3+lPX^;0lmm%d4wPY;JDGfv=Foz_=V>eaR_nm{%wrp(S-#rq{et z8mvF`(QLGi(Fjd?X>NYBah-%vKu}viZUEMQlAy0QKe)Wo-7qo3zfPiC4jdz9eZ(33 z=kUQWl=7A!00@mme~lVV5NAz}oz?3Xx~$^&k&mB2y0&W&^R`Z?ade= zSOs^5*v};)b4x(C2$RFZ`F3o1r;S3Ffs;TZsIW&GZ7i1(cO?YCC~FL{U8Z*{P$w#@ zwhSr>cKNIWc1#O}#lKT9yQ~RRhT5K4twpY|!>}BkO!~Srwsw)G$_rN2SbTvu9FQ zuq4pk+A9CRY14kPt?~XIIDJgb&2zx|EF|UPhY4X^*|LFys0lO|tmD7ly8rr5Ma9(W ztXOEq*j@2?#>stajR27;mMS8mCTp12M1kmx4gw6ru=+q{pIPW|fW zfaY0P`1bbwD|qY4YUrUD zCtdTA!RFIZS&h_`8S-74nbyB0G7M2%FU&65e@X|?H&QsOyg@GBt5>gjmxrVn0!vRE zEWzm7zDL6D?OWO&2e`{AkYzTMFhb)Ply65G{&oNKbhlwQ!=Xe3p{)9TKP zI&eaDa!5;;Klmspamy)^Ne_EEJBtizFqev4y(42Jmit4K2K8n6F7j&*h(c<(*>xnQ z1E4a_;B^g?rlw}Eww08b{A~DiRru&qs7E(9_8Wz3WZRCvyEc@}I7V*tLlkxGnMmyhQs$ez}VreUZ(1VKG9FK-cL$f^3& z$LPlwrLA-rstWL0W(GSh>LEQ-~Kit$jJ4qJzdGoeYn$c(L1`ONGt#2T0OfbGcL5>2l$ z_k8!{^h86=cdO7jw$vUm8-Pf9f%ff1mvbc1BhzAxJ(l&96Sl**$_}9cLk{zi%|#@-49aFgU`CZHbHyJXv*X=NhH_yiIyIl{Df2S+$GGd{qr#ht?hwbJGBWBM>^+h(?sqid@~qFOm#_^ zN}D~i>yVxQ>x&p`Pl4{}k=?Da0@T-x)_`f%$Mls_2Gm=jnXP#o(p%PVX?9-8FdDxz z22_{3E-KC%1BjEPXYG&mTbi9~XPa?`Xf z7m&Ez-I%#7viMSqJ;q33HC|BIw8b-c*v0&px}4#Wocn%P-flc_|KTZfU+S&oW=`Tf zl>_ALaWC^X-BtHjX{k1keCmo2_hZ)v!8C0U<~Rq`Y%rTW!r>RvR(5wWcJP%DlD3;GE1`yiroDb9Or|u3bi2> zCcSM(so4sr^?V;qo!k6=_+Gm8fd>VZWm_&e)x~k;&e&bgse6`00Qhg2OhV@Xz)_#Q z0Mh*bs5;B2Dx>Y|lOiA?Au1`-2#5%W4k_u*Lw6oZx)Bs4mG18D4(SGI4k_K;`EKvM z{}1mM#*lG%Jhh*_*IIM_ramfd(A}iln&w)E`!)Y6U~lh(JqN_9;02%4`tm`#WC|13 zY%7u~m9&-SSW&-rJz{XW{Pqg~N$PI!M0>sbj@S@=K7u6=umY|RU7lhy$ngv>@~_qDSMo7zoOWl?tsDwb#d@S` zUV+I*5XpZ)Z!h(d`eTC_$ka;>8>@>x8GKMTcf(RaG&)Xda@>s}aDh$~kJm&>CWIx# zVW=jw|E3fnE|@GM$|mO`pCpq}laa1kHHk%^!tgGzSD+&>=n1PegMr#iUd4ySUZz2B zoiu%P>(VEKGB5vcL40NJVofx$w_^tgu3ybGElz5jYJx17ejN_C3O5Kj7LjnMdM z$D#{XfC@A=UI$%X+SHL|K_rH@>t(cyR))us zYhOp-;=0|F9~0zLH=#M<^~DnGc+M)zRlCAxtJN>6QvvV@)M9`qevP!J%yal9T!UsY z{s^=7Hv*1VdBPD<&%;pG_0nnpVJz$H-_i=AlmQiSub5KiI5~4`dgI2!k(S2XhQ9$Z zDQ!BBH_se~J)?)WzF)7{*sMk+P&^w*?cdB)TNoK>ao{&SJV)j@L!r-G{2K0c%y7Xc zvd{k6T*J>;%{!)0wItV(BKG8)C+AMC_un7k8%Sl-=0s(e=(+OHkAerZu#M0q?;xJT zAiLiI;_}{NY#sH~6D)TGMB2{&*4DzM3q6jINxRNzam1S6?3X8}i96PhT>p$;f(i-> ziqc2GH0m~YA3RRl4xsOd5d7Z#@cR09d>iTpkJpeOKnWjQ%`7;0cubMd`!Gwx<1hGB zstuJ=l%TV~hmf#XYSN-wv#>R{7(TV5)Hnxkb}H8-w=oRZtiC-e`cr~0fzdr9^W1D!mJ4wVI&$V>QcbVjFbKtr(LYtCi5_=lDn}~|q zN1VdtpkD96l^XF>Yv3~?Ohx(LeAcUNe|~OT!st0OPt>pL$@kYD*eQ?C3g02r>QwZS z34CwQcmki=qx=c|>}2!~^?O?i(KK5e-*@`Qrtss*;#-7T#7~)wy*w5e$FZ^F&5+zfP2C# z(`Y&_BCJzyS&gWZH#7o{0{Gq4<96fOMfKw42;twXCAl6K_3t_+!(g-6Fc0A>3WyPC6=XqEINi#W=B1O`?!dQtxGuK3 zz14hjik*FDDE^CW)rv+I+P~vqlVh0{c!wWGTf2^$pu313ZR)VKI<1s&D~)Hni}C!2 zs-nyM^N`{E%$wX)S%D|?yMNwEdbfN)uS2wYU@A>Hddt1Kns>A6AkBAoem0WKFEV#I z^7p(E^3(Bdgmb0VloS^g!YH?&vSAYAeZQ+b7$503%fWZ|{;^>N1N(l@G~QvqI{z^E z@Sn=%b9lB??1yQ|fR8@vb++ldrh9@P8$)f6(J~s|te{9}RIg5vUkfqlp;&MGn8_yc z=)mnT%2}aGZ1l!Vo8r;^2kL!2sArJfCO-*-L8AaluDiU9pcWt%e5-u)#TwNyovHeT zot5#e;(1&m8RMTY`F1vyIeTtZqKk7oCn?Oyp`j)P=a=3BE1z{NEK&C$%jj|EGz)h_^12Q@3>>k};Y8<}_$YPR zQ&}nG3mcW&<-dBKrGdsYq|SIU735a?F*GObHcza7G+`h?GU;J>5uEJ<Q!kBIEQZw^Y+sU`uIS&p*SCL*rnq{VPei?{T(MDKbbFfG8 zWb<&_5i35+ZpqapIwu*kva!-*wIK zfRIcYjWI__UcN1cDHPE8U)f-5-ZSM4vym?M$y&?gzF;*$TDi1@yd!7Scr~&=GXu)b zQt+Gsl%m{_alBhyJ)YUh456r4dNQvtQPg;ylVcw~s7nJYzms;|#C1K_E^7?WNFkYP z;huHYBqeTaC7c+tVksvVOO^%rL=Eh(vnI7ZV|!7-MPZ@I`(%E!1iIYZ;o+l;4E=jWRUwDO19YTZQCNgY7@@np*(f5PQJt+^?X)g-wBa>|QKhf>|V_kZZV#S~ig{9-;xB?auD>^%G0r z4NlF8*vtldS#|Ze)^zk-+&|d-__*PnfnQ)lgN8_^LPBEVyAgKSIq;;a>V$b~FTB&e ztf3qUdF7b@`mRmobYsXF<(=b(52vY%Co}z~Pgb!t)vrjC>0M{fgc2FSTlFAQ7O$zH zM!pnagnw@C4AdfruHUHfe+LkP zI?~}k9;p@NQsYRhteX}IKrEOe5AKmyKV2Td%a_udX%m0x&X4@=u}S|MH9o7=8dh>6 zl=njSDL&U>tjAWP!&cM9OPxkjB4K=%bz$!ozh3;<)3Io|_eWESXV|1NkGcohg|yOZ z^EMy$F&&;>ju_dVZ_bq8h3~oTdeD62Z$HT4Ot(v2TXt`iQZRxv@>lxQrtH)ZQ#^61 z{fW@NN<*bGz7lH1clp*zojqc2fmOiZK$~3d5x&grw9x4HTZEZVJE4i$D@66u!w!Y*&mljKQ#dqN6PmuTUaj{|P zn%#9dSF;%_zjMShCC&A=dZKH*>X&at@JRY2;`Z2qJ`4kG`~G=?3%aA6N0_`>polKH zup{3W9ebSn$6CMUufcS<>TF#jaW|6BrckvqBghRMb-Aop2ku;Dkd%4yPKepVzOLcNK{ut#LHEfgjS%jWN|Lkt@g)WKF+fE7*m{D&qvPUB zznLVQl}DGk_)j7fY;dwhuNh;X)>_Wc`btHC^&2{VL0?}`g<+4A+KtB;{lbF#cfK+21YT+A%TU z6`H9umJ=fAED#7wwZhA+^USh1{N3>qUDf?MA)}SY0ZEY^lBY<51O;Jzwbzk}j!2(A z&T5tU{aJIGFnoKHHXa7mu276leyxM+6Iq~~RY2g1$hd#Annf`+Hnu`Mk9Yt4v_4&5 z31c45CT};-y4RARh>2pdwyb!=2b`sooQ;fo*1n!TZNAkpbEy1KTQIP%-naRhXFyuX zR*IAjv2iekkM_N-RPw+wY{+6djCewyJv9I;0-+X6AUx;d+igX8lh4g3!xAY|o-(ep zUndwg)KhP$IXgoDYp~h4>DCSC5WzxlIZ)Ui`@xe-_YjZMGlh#to5j(K8xT*ckP8{{5XD$?;uru+t9er_3 zr5isL7z}4aH2^OU^v3~0`Q#K+vA*<0YHBnJvW=OIT;+#=FEhm@uouFAIpq%3hYKXk zD+tX0XvK-1{$+K6v7It9Y%k8oT(~1ra{Cg%PBrpkFR-g85DxspR+uFShL zpWy33J*)ZE>x5qvPnDHJ(!nQS;h8X#s5xX@c$jypF@)@bl)Tq1t=cnQ?O#)fsRzDW z`KcO0axjOsVT_657wjWRT;fQ5tfz){3?s&knj&PmT>DuuIXtPNJXlzX?@}ciCMh?8 zWzqQhgeY{HR$bWLsYk4)vP!WxSS<4$)TGiTPXUK&*vwRv@$uR?ESKYnmm2;s>D zZ&z1WixpHfPp>2yFV?N(XKSXWpIfo$+Did1q%!hvCz-!!H`2CmCi+%YarV$|zSeMK zWsnJ+a=i{!RAJY#)D?bE8)7r;mWIRO7qcDEX@krAe+IYL;JUo`XX7cYkwKTRCL2UZ z>5etRbtDbz%&d?fZcryKaex0W1SoIHT`Wq_75^2}Pl}Y!5l;g?@9oogk5TE~V}&LQ zTUFfteHu+JqT~AVCb$TJ% zV$m<~GeSEriqEiq=M^EH$Tj$s&q~c!&vzqn{1MSrLTaZLp^c^TR^|EYV-i*hfO1lw~y)P*)q?X%9Dmk@1vAk9CCl{&1;!>?^`z6o=+A%bg{f-b7m$z zKPS1F9l>K_@$R{a4w5!9@E%NdCjbWxfMR=_CgV?-^y?0}bO0ZBg-|3ior!R!LQ(t3 z&@le)aBSkMF^kO;D58<<&NBizVA;hZ-Z)3gWfL-#9U49AEELN;x$(#pk8DxjogS$+$7I6_hE{> z$^O>LN~9{KMI=*~fdX&)6jaO?s7N+K_WTeCB>UZ)9I`);|EC3*JjL2e9Ty-tS60cM zSkTdKPJrxSXBxJnc+E@?ucB2S*m!(-VFmksUTo_^y%xUs*qHEA%lVD*X7lelS2Sb^ zYSm*%O;AHPZ>ocX131n9?t@QY>e0h5kTQdKk;=}HLg9!kDk`h9HP(#4GSacvaE}zD zIvR<8wvkgo`yKy`ChAvWf>ZXy@LtO*LBmDPvPX)O65)6#NI$sh(3!vsRQ$BPek(!fglmeNoOT6hB-b%n%3~8<3=FL8j&e<1o~kQ zWUUH!9|^t>@2ThD1?fC!fQv8;QX0mV`SI%tG7O#ppy6H_i9H{;p^1e9gYKNaWJ)X% z(f-L`B1AwY`Y{<{OeE#*4vA0yWi0Q?tOf4*mU?o-dbvH>XtC&UrSsvU{s_4YLL*>T zkmuOuk|ly!gRWC80NC9!nT({|%R0ZoN8?7?j$&nlm&I}SKSXM40V*1J2;e~c4J`?daOio^% zLu6zQi|Xlf1|~!0JNDPD*NmDq1h}_@q0(BMF}~t0eNb-?;-J4`d%*M+ z_w~?LdA9#d(_!VosiFFwYvjH_LnI&gz56?Aw)N{@q7SYD%MsySv-i{by#D2P<=dEX3yiz`3aL z7B;ou=`7X^5I8PGU|9W<@@L?mZ{eh7>qZ*XMWkPRm`aJ+Nl8h;I?qCchK430E2vh^ z30`7Yxg!2SsZvpc1dq$|u;K115?+B7n`9x5z_WrS$FjfmiJ5XQ>PTAXW4(X@GU;a_ zDEGc={s1<-0-5nXFT>HRvOXPn#(lb;_`!5z<+@|3qhJM?WaNK*;q%>Yfs zRe&OR^Ex!Ajp>+c;n)tTq)55e52<$T!dN{gE6cy4;zV#?di`O`$INM;^Sle&36DWE zQ#>4)9dE&-9s)zZ@H~}3o3}?A+tU+yA?lPyakAM*Nr3f9aQhV-p&z@rxW+z9 z@WrlR09!=i^lqeu*V*ez9XnVgu=Ex!d_+O#-66SOzu(%UNYTs_ISwoeGEMyBe{nU%- zvd0eAyD+&r>x*h@A=ysUbBS&WQI(a0UyvYroYHTmw#Tx)FM$Z9SyNUP8+_}SPF+-b z@f}?e>y*_8h82}_$$pydOlX3XPM|Y7E{@2(=uv(%Qp`-cY`ihZ4bYe42+a5aO(3WP zAj1*0bbwu2oD4tN&FDyaEojfZ@6Rq@Q^LPnXOV6zGuATFu0z-yUk1XDBnz$x1T~QA zXiWwz0u9o;&s{r5{`~~jK2gyJl@o66Uks04Z=@nYu^$+_*7odklMP>PDLlYF6nr2ARnJ2ob!2gC3 zweHU)2{H4PcNO`BXpg{-gnuv{&%SzvaN_gJjCA>=bZbU4w-R4}Lz{aszbI+wOFVau zv70OVo9~#-*CC!gJHF5@x2wXYsnh2f#Vn(WmjV~o^01$f6}?uhIl5v z-Z~`n>lNwt+LVe~Ln^rO&WroS$eevtPCizC!Cb?8DS@pyBfDE#qTex~5w&DbShO`;d)YmyI> z%62Eg44#iLXfxpl(jYs++F~TMD=gv=YLua!X@Vb>b`@DLoGkd>ru*k2G3Q9Syq`}Q zM=w%V>DYrKvfV0DU={7{@1I-kuT7AbmotV1C!tpFsX8L7Pc)Om$ z#{%}|t)!dV+yF|%8z(C?Ux`n4e@opYm^0#sOS{|K&!W7q3h>WE{3%nO)%U9Aq|2Li z5*~wFhk$K1ckaLdqoPxX*RrI_`OuE_7g9nl2r6x^o3iadDMJdJ9HPQ2@B_O1EF*te zRZcGan4543ROp|-GT!?@RUJXolQR6OzT`ZYWanB(%N^L_K*+Gv`h~qfF*1Ccu5Y`_ zP%RvTCkX3|3Hn;;GK=QTLyMhK_qf837c3vQ=m=+jLvvUp^IiQv8G7C~M3KI(E6m7$ zQwXd7%`9sx&r6nD_FhbFnry@|-$64(2|Q#Xm`dkSHfp-ySz}(R9WkWPscGWvrKlAL z%UoGP˞L*jSF>b`PAoV&kg`T{RvvKW-t2p3N*tSzEV7n`m@={RdT-Z=bn5znCk zkPyVlTt`3PY;{1duTf(hx7*Aprxqzcey{>&bwQP7IQ>?})Ot3V3iXJT`q1`&J9WC}fw(N8nhUf$!(Y|k z<)D@{3Vi}7`lO^JK`YrwcY2odKwg;Rwx3OO^r~X(Y33CTvKGzx)`neSPxxfM3Yp#E zbALr07_7vQN%p+g6-0N0SSXwh#ye1*pYI}Z@&Drib8&NX^LAJisusUaUo=_~?7YRZ zWecsScc5?GqSQ=v`!Vz8``GQx?(M$BrLUBPD1?H<;A}#(p~gyoFjqikcD^1_wRLZXvLdmv^d9^;*X2Ba@o&s?trzdEl0b-ecL56>tk0*feck8+j~JAT&@ z>A0ly_uIkSVzhZ=@9mIk?tI+rQ;q1dtEwi{(MK=^H;l9kYLFLylfHT6cQDb$m_g#T zdB2NfWY4G99F#F0rrmogXcdPHU}vrt;`@;pR6)njadw;Gu{(q2$9ij9kfmjK6Ow^D zx2wa3{@p`frmK^(BA!!<82InX6+0Li8KtZbcKBz|oK-#&!hb@B6>V~ID5Js6 zU`LB-lS5&lAKdSD!)5t)v_@6%9gy)h2f4s-|5pVE6Vo{?@oC?Xhifq`@%8s`8M(*N z8&#KPbjsQH#VGumm_0K7#mVO64vNCgfWF1~S?eok@Ptf|8Pib+wE9$APG{*oW3lkI ze;V=mARIuq?kSh^nHyc12)d;8K0Yt-%w^Uhiu#n2kPD7RpsNZBLRqC=HrEn-i~wH7 zHH~#UrB3IsS0ZGHHt~5jeXct@Cdd7Zg=0EY2yDSh)yyp5bZX&u3&d6X@qMyVd4)8R4;GXCtz>q8o(3+(PrTg>60uh=(|g|B z+}sj25=J_=y|q>5(Q>F9KCK1hNe*X~XRS2H$@wEk?P|HJ8_}k(D-!f+79XF3|_IsW*u^W7ks_)kkv8`gAy54m?!?qQ+_Er@%d=p4(Iis$*1cF`VyiD>yW z4WK{3*9RR*0TLz3DFhIQK6j&vu%6P%OqYSCqN1dj7!yM&5z_a=1t5T)F>R<*F)u5t zv$j2kSdeBKd00{;gOuw_czlx`QFzaH;Na%Eu;;1p%r6-WP5uz0>7|+)yLqf>VYHPnrNx*Zd2c(tg~)Sf@39jdSq{WV0dbaYGu8S`HeCKq6#^- zvqPTeJTq;ou&x!OeRu-Bsxn~?H{?SKiG2##q1vL4lcpH97+1Gb@Qqbov(~CeDV1)j zR(skF0q6IJ7TwrGOUDu+3$mw9%|C7#?OK3|_54|_&#jj72%nxnZNN%Q>N%=BlqVU4 zz1CQnXVusDxm1oE*eG7lznwOW6;C2=9uzI)J@L#W?^WbCS$U0e;V?{J6gFEk{=>Y) zeg?(6ij0g8a{XBA)PD5|VZ(}i?VCf&X7DWnVPqVyD+XwSDMe&!h7(OP)f#S8sj39< zM!NH|%USQAd0N*J&kFYM_sJ({^DXn%?!)ac9bp3(IbHxV%x1S_Uj6OMhTrr#!=}P! zyFdD5cUm@ygcQ7qplSW%<~$s6({W!JtgPW}uN^#=GLXewY1nh2?=W1PY61EmON5KR zHft7UxP(C9La(d;4Y1D7dFC_c_Y7L{IqkdTqg|A~u?s)kgfkd`W6H#Isoa3!huZzH z=GQQX#u}%Fa_c%0hfOk3IXO8DjB!3Oi#k%ag?c@UfZ~n5p`pwI3tr$n5(6YD$3f|h znuBuZfwu@N005KeCNeQOB)NdIJz*FtC3s9TP4Rgt6?YmtIRT9FGt;AhiWfEd}e^6}G#f&8Co`z7Of^@q|Nyk6+WFM@8#8hlQ|?}PX{wBjq{&a#b* zZr8uRGM@b6L0p^6n>?Vy_Z4mD@UJve&O6!FO6STCPESmSm@%wKzhR)TnZj7gH^y)s|Bp+D(bGo8m`Rb z_G1Yu-BQ&WR+LjOzB?~0GJ#ATyYQk~`YzJcn~7tS>PZEdHZeqSolEd?61K&t)hQOs zi0fmPC1JuwQ)6-Ur1bSehKI8Xf?{RXF>h};8?yt(ekm>{aU?$yyr^hOYjdj9LYq0k z*v)^_8W8`P3JI;IlQj}TFZO!o*C~p*KE`%ijQs2gl2uR*p!*RPlqt@hRO+ld`STG1 z#{GYAe{KU#bnr1mLBP0&~uwY@Os>;Sp zpRG2;utv@PL0hY4cxB%5qcL&N3V0AvZ{J#+ z2BOD@h(onkaw*}TUde5~-4R2x)NxvQX_voKAzAnPemeL-3UOhC(d{24-Ph#z9JLUespkD_-QF)Zw=1M z9o=v&i!w!?2^IWE;i0z&L0viZ+u!OZ)py$*RsR}~&okgqZGHm7rF8k;+Jx+vyU9Gx zSr1bcet*6^Y()O$$Q`K{vhng2`A=Do0K5_*(~O+L%pk2`(ors?x{p=q^xttDc*lxXhOZ+`~()i{ttheH&(L7%jAn(E||Z(4-*%8dR@VR zM=CT{*F}ntD8DUjQcK<;zMw0Nz>2;^R8=)sXVZ`9{SdvJgakShlSCJrfCIF~(y5>) zpXLbr`9OUqn~4UKP1ldu5K9IorpyX^643d{FV)R;3;|ilEiU2+wJ5^E=-h`~3(sxe z@(V7tfq~A$A^YRK{R9|FsF&vj z*CDq$=GkQR7axw=1hMu8dklp$nF-9+^0`*{;@~1c|Z?k%H!@0yaA5d;qzxkL8PePF5 zpt7?t;C|I42$j8j;$?~N>L*{We2a3s88OFdZz1lnh^d9RJ*p~ismi}e zVrDiV^NQuEN&@ID4Jpp8rA%PKE0A`JI7+`FjIHfHUzTd_!4Qi&Z96hFf;cruTB>?R zO#hUh!_Xwf8RZsJ{fqk90cjC5c?^40#}@V%m^FtKRM`0)AM=3vbfV_VMrI;+%2kM( z*+_|ifzoXFN({z+erx4d$2|g}HZ6r$7dA0G^sss)m{d-V@?6~tdL1=--K5qDK_yQC z0w*70=E*6S{ibZft=qQw{9xf9I`2S{Z|s{WbF%>pcV4xAP;Qo$dZCX(KF|nd+J2DG zSX?Y4wLQc!A-wN(xla+;{SKhKyvDQ+@Wi&P>jEi2Ye zdDgT}X29R?(2pXk+|!#y^E0=>E#r_K3R5V3tGrRxc8m#$o*8%CC9R=$N;HSoSQD`QodL8t?oj92_IpS<7%^3tI;!JZ@YJ= zx^*FtM>oXmH$I3ucPG!7x31Z37Apexisg>(Sv*4LQWx4%k|f?WtkA%2Hz*m}(Gw2U z+b3>KPWF#k91i=%x;^%gzIolUrR?=)7f^=pRmj;+O9^bel#-}1de-DgY)W=2eBynL za7b2r0Bh=3hq5*!ow`)< zkcjpGOCU{na#0Ckltq#mEm^n{;FbCbNb57z!uKXtC8Y-HXz=uR+9+(o`#09xKc$$% zI8-0yA=z!jcYjeSDiyDk<}ljZt4d(1{ik(7OvceH&0k2{agLjj3gDF zIYyljT~9OArQ|2;oS9+=nV-B&+Qy6Nr=GYqM8X$@%2Qyt(kAl0#YCX7bU4Ja^InbDXGY^V%~q8^MX7 zi6U2lDhZ6n#IiF^Q?-L%geM~e@$m2<)zjoxZ?`#G#L)$5{8I`jtAyexzmaPW_g`xw zCW&7DDcU@Y)#o$EA3T;Im71{?{db9xiD`B4w-EO1d|UgsCkQF2-XFit)gB8};^by# zb`Z@|ZN_s|hNYyW2ols5MXjxAaqDH||4K@rHER@^Oc;Y@&JQhuYAK}*#QdDx!4*2Z z1Q(PY2Z9|7$7j|zHWXAeAzP?8^G~d?TVW0 zr`iu~^-3;fw^T`_Z(8r!P##hO1;WjZV~e#cY7_FyQjO8lA?rOq`9(a}4N!ZM^3))s zJz4x^iSZijWzG0UF-m0GE+ZvmKc)7lQOaS>@MQSayy6*Mi6OHtqFd z(f9=?IMYUH0_-fT8ai;|On$LUY#P-FiGD*Lym zHJSb+*i+)a#Ye-ljU+eX`Td%^ET%yLaS;;H368dBh$e!GD%NGX+Pi|kH38jtZ>F5j zHdyWt5b&kv=88kHM&ztjPk&o9eJx|b!keln9O`SC$mdW>TaRjgNv`vN=Z=9{pIQ4| zEkj{xN7KT(per-1Ax6Tw0!cwi>Yqi-7aI2i{)Mn(&8cYOyoq6@Yt`;zZx%n#o<#8D zYnlAkKp7(zoG2mPW0_>`rBI6ka1tO$B;cMp{<~V2F&iz1Y(5ZV;l<*=3-kO9OcmW(z-R zk^~u9VM~RhF<1Oq!qDR4;+7F)3u~`5rq-Gq@NVV1OA3@xXE7$uT1V`*lj{(k z6m`pfW4cE$&*0F|f0d-Nm~^xI$?8TfS^_1 zAleGM^B{I5GiV8pw2*rmp6ots5?( zsSX#ShoK_EhQRcAolZ|NGBB-;$u1nIQmJ+1N$72*iu+`IWd^e;+L+R*baY!`>SQeX zDv8m>u+ajjDtpj1Fd-tk-0t5v2kgAqnx=D9|G*Q9mzJ){?NSXe9brn6Oqq*z3I5t zelLNxzR8}rmN{i;b+dKYFg7InFrJa~>O|||>;_1bCrepRLukAnE|QaeVMe4~Ur>`Y zof&W}JleT|%`K`?)?lcDF&~}Qd&w!5W;tf2PdJuj$h6ig$T-~F_pA7vchzGTi^En> zVf{_0xBYD0<54r$smsdUEwHgWpUto!nAagX3~1OW(tu7_}8A-43S= zpRYsgZXt53N9fla7Ip{!hXnlpSK3=^g&nj{uO)UBx%?|s4OdO%65r}Di5Iugw1N=0 zR3r5Pqogkog=9UZ#$%4+V$cJZ)R5v$LwhW+vq+ss_*l=>8j&pDSy}PvOfwOlD=I9U zR0bpcng}`Gdh@-)-XQd1qnNa4eTw!KCob^{Qq@Nlipm14UpS#gJR+@SG1}HT6V+|0 z_A`U=j#1Ik<4a36M*0kwefb=@2@_6h?@?=vq(lS~EiF>l;9o3$%^|V{s}jO?z}|#% z6EU3>h@4$!jCO=rvudrl#Di)zOK;V8ew`0AYN~o|s<^5-_E4YaE)*LEU^x;_tf;(_ zgY^s~D3zM8fCc$eXwn2#^V5;#bO8;Q9Ijx7nJJhYQvM{N&@S)U?M_bA&MmpmU4pM+ zCBfm_fZn|HgRfyUChSSsA3Y2*95zvwYqBFxMg+uX zodTb^MS9~>%yvC$KKZwk)r@fc8Zu;1*Hs>5)6jrhKy{)z_k1YyYxmVerO)y~FA=l_ z+N482pG_7v=aW*HSkUHe#B*220Iv#sZcfo#_*UVdd^eIPVkCGa0h)5WN?Yc*`@&Gl zpk7Y(9>qQIH*Eijz8wQWEqL@|Zm?HgxW8Y(B$FgLcZWAzZ0VkKI=vb z<=Tk^k^fx8SjupxiMSJ9?bq3qG_Yi?n!7?$qLU~>#&Rl@%R%bG7+4L?k7CB_bx~u* zq*OUPv`HXt_kHU2T}?lmHT(+*cv#U?dSW|A^uhnC32ImNDiy zTjEX4t~fY+4DXj8D>*xA z^@t)YY#AD)`YUEIy^zFuKYn+cC2)GtyeUs2xuLH3nB8wwqW4~RF2OcnFN^1t2Nj!Yv1T;f zWjs{Bv@G`Igtk zGFJX!uh?F+5uN=-ow2VJnRxX!*9!&9YIbr%<<&?&(?Wug9-~9lfwVdZ9z>Sy5duZ=jAB(L^4u(cy7hqNG!WVy*ieB1Ybsnh zO_a|18dV_4$AAUH757;cb%_GasH*!P1b4$X39-sJkH(&icYAM-CQaXPGw-XdCws0j z$racWog2+wR2Nt@tykZ)xA5~%jCVveyXV7T8`(;-sLKcFeO`I1o2c^+7>L#Cvs4K_ z-9ug@EAC)_GfV{{N-T`T)_XzZ{56amqGemfmGYnMxG<-s!E~j zc;5NEn)94{q^o)u-O8@eoQj|p)LV%KUCQ)0O|wZ)itCJHO{vf3YY zrwOWHDb#9dUyeq871b~)4LzS)nU4Y-5Y@ErTaomGR1a~4iRLsvTy$=!rcpY`BV1L; z9d;t+J9qc?-n*3*&e4*dbMoL?_gz>gE&Q^QLY*u6v?%yfAE#Qb;e3{qhf!Xh$o2@+ zG9I3i?}_BDJ`i3JBb&M>2-cX854V9~cOgTHnRu-nP1%dM5h)GrfiL5I#d05_woo{( zQStOS#{Vl-33*bAXN+@2LmCnv}?v*+|=;kmQfa z1^lc01jTaYV7LkJ7kWiwlym1u^l{W+(KRM~A*fko0;7l2A|EF0Xfl?vu<e=h@#UfkLwjZgYj@*DRlxm+)8;13AFwx*@icNN zfCw-;0t^&M<#dBmiiD>NhMOE-W#ny_jr9D^2MRTkP@Qfjj$*&Na?vVlSdP~Y!jKI_ z_#F<7jNPOCrVh53Ioi*~wMwtj(U`Ii+B2hVmF(k zCYoA=z^dKWH&E_CERYT(0yA*y{V(DmTaEjEjs%3LXw!5BtO3L02NODDYh~J@BIGwfk z0hr+ryfSKhLreV70lIDH^rAl^Vtw;cel@ovnHQ(F9hi`Ebt;LEc838ywx=QDuBY8N zarI{&8=krTOU$j&_`zrw$gpXG%9Ee5eTl6RuLz%Clw8w;xnw_A zDSy{yA)61B<_rL5CG7UAr|nPrXvgR02S-QcG3+tFcL0?{C`g*{TSNe`Ca%4*4o(nr zwDeoYloFpjsaNY?OA=^okZgHy(_XlIkDuTdrF?#JauOoM#5Mm8*HP%-DY3}y=w{c_ z>UM1+hUiw2R33AXiT}5z3gc5^=|cWlQpQ53HWJDx{a1(a_sjOT@d-O)M7P z_L>6!6lb(XoQ=y#woFxCFeA`~7hBNFtA({_T}^uc;|9rrQAtC)FyB1(g}Uh^b{#ar zO~L2PVQrPE-HF6k-<){iQp*|Cvq%JyV-OO&lI5jNVsk1t8V zYI0T_yr#=M!a`e1_I2*htym2}6Nj1*qS3N597O=uB?*0vJtU~h4$}o%^gm`35Epbb?0LM@Kd)MWlc?n|6GSK1 z*Smsh;SU^ck%dI}eW9E!9-rHi(@>#-r3nc}W!8L2lB0F>v|2#3LrRy2F58Kt&YE7J zeg`^#F#)ZjJ;{r6BG}Y*W}Hsuox-y<9Fe+PTO~RMjMP^JR|Ggk%|W8{-s7B!-qjK2 zY7fC)!LUt_GiE1V`{$x7XhAdw+@9P^sdw)!ZFpmnCTQ`i9`_?jz8I6WdY{mFdESl0 zeE}D=*AJ05Aj0voAk!stWMhQs4i2O~_kr@`=sF@U-3?e;?S4zDc$M@J3avXH<38cV zw)sYMrPp(dZR@_3{+)9*ge|1y791;+BjxymHa1?Y9J{<;dlC^DDGY-#YiMWyl{>KZ z2zh%8#Ok=^J9G%!oMhI2KOTxjdm2#jGFeS>QpiF5E{O3OP8b}&^{&KD&p?k+?*3%% zZtGI6%)*dSH~>H1vz_+(#JTkES^n(ZZGri_x^iETep~eUIX?dv47G<9H7!@=kRb?@ z-p1R_kgvXvdftDdAOmUtZFs=Xc*5Nmx*NV}Iy|z_?#EVNR3}i8p z_72M^44{}*Vls*rBO_YWH*?YNu&KD?*Ut+wjo*mG`DyA|2NWP%^hwG%86FUg{#;6m zg*-u-QC*lH1Y3iawzAP|3^UN^y;LP$7xFVJkSXnZJ+&WMw6l?euuUWq3GtJZl2Rh3 z5u%st<7i&SPV3wEiMNPz!zLg$wGWA^h>3+{H&4)xII37P1-epf{?unu8Wm37l$B=< z;Vq)J?<;$OOJ|!8^K%cVz5~-omYVakvyi-om>>+Qt>0!R?0R(1Hv-g_j0{BI%%-Oc z60UW6YS`F}yr1bHV4hOxaqz45%acQZwpVl$z?4RKoG_r=xT)MY(u6e(4Bg%!<#9{ zd)aYyj6YLpDko_?@TF-Ffta*Vl}mcJ(l7D9I5FRRs~~oD2)V$UD~WTZ)Q^8Ek=KXLuJ*q6sQRm8QdqPKGd??)LS*z-}J2oGt22GHHkgJPf&ns04lY$Kw;>~AuvXdTb5&3 zM@L6j{;NH!rK%ryswYw8Kl+Xp*@JxojDE~vu#@UF$v3?v|A9?w0P_)W7)7Id{JoUbuaf1#6Bu##^JorHiUC zbw?Mtw}CaB_Z_&f3}35g-laT3H@al=ap7>r3}B=q9&Bg={x)9Tr3kB73L1yuVg9O8 zxt)?S`K1B`G=q|jY`jOE${U^tga1f9#>f)SH?SVz(|-i^n!EpUAD+PofqD8jxMuJ! zy}@Q)oZ=P&#)*-=fziSlR^F?;*PeogCp5azEqwWkJt;gX>AN#d+@5iyeLiU)G&yU`AF~DM_pa7w-EUYZC{>!fO zU}m&)DCg`^^omOutCW)dP=0`KrL8BX@1iJzY+W>&bC7anj}|k{o=RQIlru{!4__y*O)*Ky9O5h?h$<05ih3X!vD4o9!B*=>$o=Fj)8%Xo8b{yvH~#hL}eOY2r8LH2;KK(Eye z5-d>GB?t7ypsXwfhZyVbA69SEYY%Bo#~aUG5$J2<<0@DR+x`%cy7OLEhtJJsUe(JP z87rT$^??cM)AUgosx1y~zp6uy2GgoXr`D}xgbs^8(KIi&J zaQgF_J+R9P_=Cc^YOhr;&jTqEXOgbL(|p^`Xh-0F*d9=lrWFJ2vX+n2hf{@U(Q6gz z0us}rN`rlGk}yaa1K9QGQZ;L}E!z2AeySEg^vx941I}{5wF=F!@7nVc+?VkgY zDxPnq%bwP+%83-?elwUE)S^~A@}Qu#_;(owyH%^aKL;+(G)H zFPn~^JMss^^I7YZo6TLHZ#_cX7ac+W6^PHQKqLIWM-Q*V!St|PMQvGZLXFFzMt~i9 zX-DwSi-O0^=(kD?T5%oT8z5g;(|A|vM4>^Dy&hqvTnRz8&T2SMP&+24yxdkietQRv zP49*~4r0>RAf?0~+NqS9{+&twSk(1UO@tAvRG&FJF=1-S8)>GdWPB8t?Joq-{;8<3 zg}%wkf_;?_t(?Fmm@&)EUuZOd!^PxZhqjWP-D|ttpsLNor0@>24VJV8AOcput7gU? zVI4JXyE0lDG$X8xW>JZB zRQ;t4f~7i|tJAzBkjgY8KH-d|H|mF#N4MeELdnn?j>{K(lwy?IR+l1K5UXC3HL8Iy7%Q zgRlXqtpAKa5mbc2VQi10?J)hyPQ75EuBfdwU_%NhH|+#;{#}6XKc=*;?NjuXy5)hd ztF+L0KA`jwWOnYM?=nw9$Zl}s1x$U{x3>`eVJomz#ecWJ2Uh0jPz?Pyw=fU{2fhe1 zFuB<3^EsPD_x0U1(zKTal_P#)G`Yw)E_)x>zjKkX&foKE-2-+7A2hDC@AtDaqdgU` zW2Tp58t<~OMaSc1{8hqM@%wKszdzMv9U(k^9^qM;>b=2y%zJtEQCoPG&!NskAkT|{ z{l5?AGQ^xze}cV*24YJQ9xinJw$hC(I*gHK4OT{zvV3FDM(Oj64@`+2CD7eF94Q9! zF3iNrT73m;$zHgvU!K?HRSvkI;HRJ)J^1K5JAZ8ZdE;YrfKk+5xpM!z;Qp66$F~eq zt;AUWqpKhnRQDZf>39Q2P5SNlD9C}?ge)FanWGbz5)t*9WJ!A>BX_`B$^ZhY6C?ct z$VVMdW7Kq3N0_Opd8i|zZ-kVUNozC#vgW|KIZX;v{t4L0mH4^i{-LNGO(`jFD>lD8 z5g;)IL`D7^*-9c;1t6?p5b6z^^eWZ#G;KXK0@3FHweN7!EZB{R~~=c*m<~`B=7{2DO`6@?|u6xvpBE&hI5knscn$ z!%jN-hKyWC`iSUrtnEz0zfr6YbUWq8wXB$+t?TRS-@&jAUeO_b9i}%a+rz9%L|QP@ z$||Wah2c1;5aE(jyC7h`gSfGHUShw6nt%DtI|`XTTc@%DgBQWXx?sfY!iwEHA4&ry zAgb(A)7v}kY*Y92V^# zZ&1@BL5o>G{D~Q;f~1b}J7iu`-ENfXdf)T7tUXb2k)$bH0rHvuKfx$lumJzncl4u= z$!g;w^J61ieQ1mpylAFQdXn-0VGBnq-idvHrL@a-QeF(~OP zr2U(R5_KR9+A!cjzZIjWTY!cby8`Sl3K5})@5|&0w_6#b#eU!3GlAVi3EWE8vy&quFTOC5rJl8 z9PK|Op~_B-G)=WYXv?Tvqt8wx(_ox!&=ObP$ftFoZ8Xg($=^f9l*cv%13yY2uc!DT zdCXIfNSy0v4Iov#;QASbr6`PosJw&nYh<{iiRMQnZW zV$2xXLKRlU>u0E|@q5PAw6xW*YDB)jL%lHSD@g`Vm8Smf3B|K_GrE%&*Lnzm7SFcD zb+FmV`RecZ_+7aV?WKIO@+gp>)K8weWL^m%zf7Jh3Sv8{EV;l|lgMvF{8U|u8NZUX zGg-d;aS&bzf^N4EKjxj z^6b{A(y@mQ#sN8Vd>MeIrQdbXmZunI$hA4+=(%KXuq#G+3A1EW|0uS{D$+}11o-*N z>3!0=Op!&`X<&zxpiK>|mNPZ#>d#EAKve^jYCzfk)Kng2kuv_Z^~n+Z8eoL#{>}kN zK(;c%|C3qS+(or<_4MYrSXlfF2!MV=`bEQsYWz@a9B4$=h0}j~e0ShBDL&mJywC)J zK5D9p|D-}pQr1tU^pzQ|SjARI77noBx8}zx4Zh#6;M@v*Z+-g2YtXq%_EhNU?=bg1 zqZRV-_0AV%)P0!hdxxp!Q}Go$?frv>nTUp;MS zwyQw>J_1`+6`Ru9KnO5@_HOr1hZ$SY$SW>bn7lFUZ%ZiSlsBV+tLSZ)YC@e0qm=uZ zos2+wy%z;1jdUqct0E)OfrynNph@{poQ$sT2aZtD$u2ZB(@K)jajOQlopIW&2m=96 zZz8@=F@Vr(ywNEghv9P|iA?oG?bVtCUjR$Zo2T4#^~jv!D~WqEV>94@Njzn# zOCy2;lq_%IXXHUDBnmx5+)pEbKIM^U;+}AZ7@g-qri!r=d#s)5CZ<6={LPkA@l7;k zL>vb*z0zRIz)`WRgfI&OJ%+;Q9fXbDK#XP4KpGv!@+^+QP z-f-bU>k{5zP0pWNl&F=zNyYf+2{Sy;aOPrhq zpXS~qN=ETIp)kX3$8FZH(AF*@v^?%}jDqLTVh9^DNo`PH^ zbQ+m>dg}*}ha5`e%FJ&l`Jq+w3>&m-RW%DLEA$0MhGv+OnzHO|R?0Z=PPz~Ad1rUy zfqr%`UXI2FpoH`0*pinY_V)44SDbsemQTji+?rh&S<4T#ocoL<>KYp-XX`_zrdSR3 z9{@ z88sNc`SjfYi&=hqyMi|pZxBv4&At<8+=_{7SiP}DyaGr~Q5#=3Are!=FYEBtJ0wWf z)63=(GPxftX8PdP{3!+zuq#D2ryJd!CeFCSsiWb~=cfVhRt&vRC%LKKF;|ku9{ixQ z6oBuqU+EVzHFM(lT=C+qI^EpfesQ%bH)Ue3KUrG^bmZ(x&XeQZpjp#|QozWcnkrLl zE=AQ09BpCajdvA-*UsW+-~=+#m$4ir?-vhvtQQYLdm&#WN;Iw-!&7?Q+Fd(ALdTc2 z2_2ztFH)SB&k>E)+_^-%glBSHqi}YCpEo$UxrJ%4a~l1AetEC-`CG$p@$Vk|BK$Fi zhF>0-KQqccLbho=otRmgHdRRVbOxUcW}<^2P`vVs$*N0QHu?0>eIE@ih|(HORagp= zdx<)?Iy+{&B;>R%Ec8As239(*rpGO8HREZ^>o-Ls33)_^ti52q3NX^2G!8cM#k~q) zGn$Pgv*cC&`O;@h2gJUn*ouAmw!Y?&Qy;^)YD%nSCpYq@UjTCb1))BYCW2_sfCPvy zKzFH?47&pGr@+2kF=Q9+lRCD8e-=uxyj{Ak@~272mZ1o(cJ^F>DNAXnY=GV?3jl<^ zmGI>-#zDk8#lc2m3_?QdSl1gkb+zBed&dLSHRC>(1D62>jAcN5AN9g=G!Q=HsPZj5 zx3y(KSG8N=qenqA!4gPd)bj((6lU5t5s+a?+6t>n@vT@PBXin{Q3OEb<^pz0E)Uu} zxnNEInQ8?)(SHFL`oioN=YNqQ)iozKC^<;npQ)*-^Sh>jR}@&iiZnHKkVN7_>s#1B z*^NDeX&;2L@O8vntyGC*mW#e>Oc6Y=gI{u`zqWCU;`;A9NdGswPw~;P0~%qiilfDewHM3CoD~<@7xb zA%b4{#5!6?2Jdn1O;E_x^HOKXEcNN8i!fv5fHF9nDP9>+X!K+Xc*8U&YL9xV;CaB- zyL@A>XX4RPR8*AJ7-lY_9A}(NZ24_xv}w(?=cK3TpHubhVkJkt<1A@!&)j`GZK5F7 z0!bq&%P$f6dnNXgjw<2Vep;kF`2AfN(CtD2Iuow%%zx5Y^L#2~_v-y(y0GVBo!??F zEbj`Pj+2`r=Cr+Jb#&wiH!M8bebFWxbBldF118F>T$V<(=4)r4-W!H2_;W?9w(6+b zR_e7ux38* zWBTWurfMF=I*+Ersiz$Qug7 zMtX+uYQS=x@!M$x2Ut!JB-#c97!^NKk#vpGrO*5=>o|%Z2DmF^n?b{PRI22!kdko= z7bw0`UCr~Pq!#h`L@JHQ<>h4t5%x-JP&%+;WkDKRhqw8ELvMo1Eh|6nwXHDoIYXfu8oj*6;ktm?1pIJpLl`Jm(D zOCSM7=lev8!g=zZ-Ko@bityoVBc9dh@$&DQa_V9v_(vf$R^z3x|fIA^(Id0iX0zd#DI zd3vTyzm9k>r02{`wtVe+C^$J5QR>&T^_{yl3xYY2?!+u5&=$d`NGJh}Iz`}P(FQ>e z!3QXCl+)yoEEexR)(&==fUzyUhh<=vxlY)=pHx`iNN?T_b!i*D@@r0ceE8I8z>|?w zkvf)g!c}_%aS|JfFFGAT5Xti+mG&-=LN_1^#!u_4IpM_n`WP?{(g-& z`%hLplrux8?yUq!8xiRd8UK^rOTK9yZBuE22JM%JF%Sb)Bh{8m%7~=^NimR1mwlV5 z`8=hY~i{Twj&yPdL?L*g6KrW&J_mv_PSl%Pf0d$xVA%h9i$V+b4n zT_(jow-{Q`PGD^Ie0(ru6WAIT850yKILt+-nzHVMHNFx3#edgMSI!fpj9*uCdE=!& zbC8swP>@bvvyhu?cs8u8AD zVShE=f?rK1N#aej5dpI*oK3N9bI>ZcWUdO-`Vk1YHEmKxz^jDihu^Oq%PKPQ|F*z$ zU-VKQ-@hJbczUSMJ`4!O*|H9PjuZIt<2?+tIOYdhm|rkVO<}Dsy2~J)q{J5W(uSqE zh6c^I0Pa~JY`d|g(N07B-3OHqD#CE0{&30B0x2mBY@I?>=1zNiYkclu4ZQ377cnC% zJo|0?na+(@&FhWDF%=bx%f-T2`3>xBx8-?*GbPrCGc5}pH7JV&3hz>jm>liuAeZIQ z+*!@5DUl=ArmdJKY|>Av0h9PQkjVqjjD!S*@r|pmdvEun4GOQAz-|f)0xN-!@2{R= z69{2NY>Md23e;*F%iqpLb81$VaWACcvNtsJpHYu6mo|vqQjLE};%&l7S#Xs>;Btlx zLEE{xjPdL{Oo$*{bkSi9khUyW^`#9B=>C9EI5q9LLCuHCDyeN; z_))>>?cYs^k4JY7BDR#KpX{OH^DoBSA{v}&7uG%0XG1x^{9ZWeb|3;W8=kVp6JJMl zZ(Y6j@vNTl*Cb~oM?as`xmFR)A41rX9G3lDJ)y6`5eaD2mK}0dnChI&ld^+yver@xf% z6e1wGm2{RfTHgrb_4`ds!wZy07hDnARiPZNhn(@lH6`CR8lw&TyYTpTdK#HF52~i5 zLkS0T0M1VfVNHoFv=p;~#Erpcslv2or~9q|@Na zaFE|2!3Q>^*JFy9fc!Iv)7~CKVun(m?*6zIt)T*3zhnwmHBCQ^nx2bby}P?xYc(q? zm5n~hv?~Z}tr#O|BtH|St-a{cuCMbYPFZi2eP~Fs7Jw(jwpElujo4v0Xh{q+pc;OK z$>FmV#GWiSE(X`vZOGKVFVNSP+>SlEe8{m&R18RVYBg!(suj*!1jgL^eR(0SvKTr=tOeCdI<18sHv-q%gGH_87CHvAIphJLYqvSN|k2kfb_Nm zXF^@Fy|QyA7wU#$6W~^`4|RqxtQ7Mfqn153ezG?RJX4IlE@HKH<_C486QUdVAox8^ z>LTlXc)}p=`!QhET(Jdysjdl7S@#YySF+#ew+BZpC!O}Qy?nvV!rt7&yEQ&o)?#JB zfi!mhMO%Mmxno`wH{avN)%D@K)8iwX&oyUxZjIVhBI_$!VP8S9-w*VTqSmnjVLN#H ziwXIp(Nm#9+rS?A^`wif8E*z1FnC&_MX31>h1@A^jPF1B3o+;ojAgP*j&cVQowf!| zTeHFwB%NV4{Zl7=y++Vq-!sd)I@>!7qgZ(;ANJf>)!P~CNbeN%B|+G4^+z1FUmw~U zKHKP1(vhZ38|AWxV0G%VC%Oc#@)A2dGU=`J1d#Z7`tR~(Lz<2}&oj?zlsHk#9#Qag zJ+PR|7bU&({Ffx=9mX@(O;hncl@B*Pe3xrFsb{>77Fqkj)_k<9!$Y^8KiP;vGZ}!z zp%!1juwB#MDR#s&F!?fs$;tKbt&{9xB8xe1EEjGC#>eZGC*7emElco@++0DrhEtXj znoDLs!=2Q5Z)B61%!}tZo7W2gb06EiS+_~|+nSfTfc={1A>PDLUMvJc2UukjX8!&Q zgIU28vA7Ie6|Z0f*>CE2(&YP0FH|_EgIaq7dDz0*fyxG3*VTNT>7;Gfm^LCGMVUlf zdoty$O%#eB6sGB1yIw;Sq1o!&>lzEtW(GL;8rfo&|WA; zdQ$?+q!0J<cy?)uY?AzWM#gOGfrBBZxLUf4YFSq%eu9Z^Eoh*B{4q6S z#=`3)_789QMI~Hv-4JU|ON*t6sVUIW%K|%P{}@hOih^?7v|VFrkqw88^GZv@j*o40 znUajrt({tT`egI@Y~J@uRV==savdsKW>nUU*pLf0bMu>8$c=0r9=L?yR@ z^7du?4u32=iIzG{Td6k8^3Eb6{ittqee|(te*uG!O>=`qy__f5%;ibP6-|xkb*p6x z>8Ffc((z}6e!a_`8n`bu*fUctW3HIW*c4>B`CH4R>P8g*@1MlFNCTfNBAhF*#HuP0F+KK7k))^oO65xY*6(yd%d zSd^Zc3eT3H9vF6Mpy4<2~8i`4+Q12%k67(_{*-i|Gds{iwgb1-`2R4*lSN58@qvJ6t=<%nm!?vgu2 zrJx6{v5vu>lvLJ8`{~iW#bSbdxX+0F9%+9qf>1A(kWhS1#_N_;7?aU{LaE17IRA_7 z-#-c@4ru}>lKk_Xe>yAHxUBN9pP~!1kgL|K*$Cp+dOIum6P@S4Nf-tlUsCfOE`L9P zx5hnB?USmN=5y1XH*m@bz2WA8Ec~(3wLfIIB)t?@iI-y>Y7VyTS;pq8l6@KD4o9KJ z2VRd_=}!Hsiuw>T-!CHN`8^z{4rxA!e#Q4J%=|ZMX89F+?$jiM2Il+&A)Of#OAx<{ zC?I~tdBdY-d2LUNI^(Z%NPGX#(QU!YUSM+P7R;LOj&6U!-9(ca>~EPzRwlhldpVBj z;X@d^INbAlE>gqA^)Vv`qGs?Wbel)NmHyM11>nhBc0mbp&loDk&~Q9Lad+~OU{%OT zjrC8B+nv65Q+H262mBb@@(Q|i?zK|e2ZGM{gV56rhLrIxcC3wFPn4D3evb(>} z28LXJu+UbOdA7Iy4Bgll#{6z1pIF2Bqce;JmTKZId-l5}6ihF4YqMe2DJFu6n!`Hd zIz7#m?H|W5pv#9YBoCS9WLty@)kIe}n%=?D$y)(!b@t;3Zw_HOp4$xB3tHS-2`@s5 z>Vt%YB0Z3QP6E(^l^2+O0t$=`3u17gAS);_#*IMX>Oed^hpBM-Zb(%WWM!BE{5=^` z3Sj7f>QMzRy_<}WPMlnb-+ksPgv6_LAx9hMse%vt%<{{`F%L2TKN^roTA!Y(W0w?7 zAWe_0nCnT7@(Sl#xWogyY*A(qLY*JAS7!B;?|r~Uwear8N8;e%D8tJ?hs&;Z+zg5<_l`l*P_VSvFaZ->`2+ip{-IKN68wli$jg)~$!edA2HZ{x#se(qrh~VPI8Dtl0#`@;gS^J9 z6$@UmU1w+Hfn`}I4bu=Rn5hwAp&SOjE1gp*md*@^OjX#jG8hHT-#8rq7%@Yc*mzT5 zt~=k&VH&G;X(;AF;oNa-d5u-nrYEpxe<7Y@RZaX53bC@Hnp`7QXynJV6y9wiceD}p zI>5n_L8AXb{@A98g^OSX#`l4{LB0q*s{q6{}&12$4ol22qBiL}A6U z&@kgpw+mS;n?h%fU_HY3-}b>M#h&NNYX)wVvuCf#OA@Wk4_630yeQ<~Ute+;j&`pW zE_*+%vBNZJ==UybH=7hd<$XD9qt$_u)prBJ$!s`*A(||di~qQZKt#7 zAuH4J5qrzoVsCp$bATPGkSTj-a@~*F&U8h>Zw>3NH1+oS;@ig5QyxdUw>nPHX_0q~KqIN*^te6IOL+d+@6T5LMt|sH~ zANPaGybpX}+!+k_wjZwwy_t5;msC992kT!FyujXsJVkPN4$DXKUT5on$@cPLVawXT z`9-ci@NuqiWX*`oxAlzOUfpq-Ij=i&ITdAUtjz1m94o1wbgXYwD>?fkE)%%{)k4IM z3NPb}_YPsAx~dGC8m77&UGXcLcEAL%;-(L(^Z%uhad<4Zzt)W5LXxo3Q2ki$+{)D z^_3svTAKR~y8^u>pu{0|UQ_8e<1DXSTHqo~Tj)pcDs(IVs-uJFJQG`)k|F=02zPlq zu=@F%7q!+8(epu&pf1VtYHSIeAc;<&ELPa9m*Gx#kW@@uT+i*vvdy@?<9ex!-So1( zr0Szpy%Z^hRduNKP-Z6S+ag0?K-_D*w*|VSxe7fj_i_d!*ehD$*?#Msg&D{cdRhLH zg6oY(e|WLUas&Ku_25b3v>PZ?p<-MfS-HMN+-K_*2zFu@ub`}V{+Y6{b33RUov_eb z|9w13iUvD8FuH8yLclxq;=#verAY*5j+L#m&;FzzUTi`McuyAuO0)+bZLandMp8Mb z$2e4N(P{h&DIL-AWU+~Q$y(!!g-4}JE4sTaO4NQvjWSgwTi6ZXM2PDRLBvxHS}T&@ zug+6a=BJX^Xxe~o03E;b*RS#CON#WIo}CXqp7I$WDPXJM!9u+2;I>92Bdvghh3_M0 zMce6kTXl6pz>GQs^nA~BDA}ZvkBzIw-K2|saJ`KYVWgkZHLbgo6h&qIzMIfuNzwQy z0!jGk|Fi(ZK7J4rCOnO6x6O)^JPMmC8OwTI$jY=&Bi%cPm_x=-;C(0EHKSkrQ*OT_ z_#IahR-Q%>*x_~arXo7c(O2935u^tTi-hagB1T3~k;72nzj5H5%5%l6>BHk^Tk2r_ zF`akp(&y^`b#|thZ*%7M$wKIEO2di;Czs9GuONz4OlH{pzGtHInbP+;*WltG-;Ile zstnTUM`dU7)fns&=6edi1y>TTj3%yq7Y&E==6S~>Wt$W@!zHvLX{vux z<8HOI@S+Kw!#lrEeTx1HCBGHWNF$d>A}kk=g9=Z}z!3gN0BDcGg)N3S5A)3&U_`C$ z?F#|x=F(CNe%s_km8^;^1b$J`DUCvuD5gwX`m=;i(%6XRjjm2p!*1r3xlzuzGM? z+-=d3ceK!7vu`WkNtcjTPTJmJsM_+6o#r1-j!EE^3MUzJ|V+n+Qdm32V6rj?R)>Ke%SpJGH7%3*ES!j5cyLoKKh;umn_!0a(GJu zXzp+r_fT?1=ud%cw9xHq#2V7W$2{tQj$eqYBY3Hnt+#xp>kL|~@;un0VpCWUD zS>rW2pL_2*3G?1Tz?L|w>P#~~w`)8mg%z_*G+4t6R+27>{d>vdP;)6;{FM6((qTV= zW7X`O^zG3Dg#9Vy^usc?{hN&07MwX9HPBye`hM-EZj1k|SdPb>`6d48{<#&aJJ5?2 z+3En=-pUd@x~63n0D=)`Vy>)0HR_&7SH1Q7gg6>HljXJXx6KoUhK|k*s2#v-!+{qG zWEON@rV4#9ETp{H%2?}|`E_E}m=;SBx#ei6X->UcT%3M>P^kMfVSrl5sv#RbczAdL zC=99rWJ)i(#}1-I-xa0N$ieZ&X|9Z?x-LdjME)Zsunoj)>N{yfZ$X)oKk;&-eOUWW z!JJ?&ko^HHsEX3qFC!-Ud^!w7gveDTf((9PXHQmJKd(@nV!bP(8GuI(EWF;r>YRl+ z3kM1lSX-MXk!#Ik)ybx2=SaF)u(b;#IZQ!2YkXghn<;(@W-WL8@;e17(LXUas~b~O z(-gr@OXwefSOY)~qtdoDH^0;$LGg9v=Y0;jXk0NR#BkNQKY2TCp9Q(T3|E9;=#(}WX1?l!_LI8l+g8>`TPxe?P)pZ_6uAzGtcq-5G)~RH zJ9@RpNDcrxU1$z#0*d@_coW$v@AST$k|G?UJJnnTPag;X859n!tH4TF{A|jk6hxa^ zWQ$@Ru*FSE0+^Q1Vi2X(ZG)2Hx$?)jHA@G%;MXyW@Ng%kUSijz`i=kcqUP)M@`1LyK*v+WZ%1De z{(_+5&iS+3ss<}f^(aYlbpdWBF%jC@faG+e!Iw7uRf~q0p;Ka6J6q72GtUIgt(*Ei zl9Kn;Zrf(`^T ze$@32!)s<(j0l5Rb*TrkiWu0cL+{(xh$Hz<;aFK&7aGd{xDiSaFw8hDvmir~L)B1j zKY(d_{wj)qCTCKKw)*oir&yUu_Pu$ke20+vi?L0CE1AIX8rK@Gi2m%hdQi-iG>LO zu0uKAm1|OFQxMFs!Yo)OQ1-_YD9fQB69LdNz!T_P>B854|3fa9*jCWWZGYXOiBd5Y zm@)%Vt?T)fo4&*ydMuO%0L!GAtU+Z2Y}_5q1P0k5Nq2Pqd z+m-Nj%3LjK{mJeEx!}8^+4#R!^P)gAdhzH!Fl&y}r2=Ca3Pr)F#i)`+@Rj~U8GfiZ z!wFx0N$J4!^mMLw7JUEX)KBls5C4FW(@#Lta=gSLuDjrx2y6Rg1ob@bufVv4fvAf- zz^SNfMY)@xcb#M3zM^&II7HRy;GvE>w?oq5PE4vah66^&9&{2{l7J2tkUdYWt(oz0 zvQULX&1bJCdEc@RG{_BQcdxqK?5J{hqOM{8TYq84;O~s98sZCqG8xA_?kN^Uc@}@>`PrWW-;W^vHkSx;VU~{Nuw~wjW$Rgu3)@@ zOa3u7O$X?I+~QP0JwI|#f4W@$3G_2IwMSZK)l;S0RuYUl=zOIV@-?FC0dCsmW&^7tAJey!lgUObdisIbv?FJR_Cgg0;W@b5A*^vBm*CB1RpRjdxUA*NrGh6aAOq3g6Vrd0~4v!jvIA)f# zZmsxyPJ|g>pyrsklThYyWBMl!?|#BZC3O3v-k*X4`!gu+f^S@V#HTKahh<}#X1kx##h6b za%x>YUTYt&^9}_>VT$E?X6bdkw`QtohtT%*^{!>>?U|B?CqEE+$pU-%=V8ObyNE)! z)W;n2OLJIH3iUSB!!atksP}%YOi!1$ELhc%G8S?ObSa`})}`KRmbV*Sfbw4A_nR|j zvO*<>7vgB1&3;cj@0=R6fgTh(%%@!i6+i{`f@!l&8ka|x z>aA^{Q&`KITn=KJ8jw?fy1}kzJ=!e~Q~_zxWpZ2E$G48i=jB0CN|-U%QaBf}mKA8KS0~60kI`t8N7z3d%Z+CQv3+JOZgC< zB@}o-fHo&fFHbtAMLWKSk}LXk^5Ow=Rd`WRRH2~xYUx8HR8grdEF*0)R07tVIN8AZJ# z;+3hm9+{`RL*@d@%)c@aV@}pnAN7=GK%yJ{V+Gp@AWQoySV_UxD!5F#_ofZ|au zTAlsepA_ys7zseHRA0|=+ngad9X36(^^0Udk-Nb)A!2WRJ$aC?oY65m2FsCd85cbS znt?Hvz*RGjk~E&~ak`>5wMNhX(5Ql>5sku;DiuYspH`?Vs-PJS1kbYDVA)r^;-1}( zxGA3Q1h!&w0zTbq=7z^7p&#Nd?(GkNc_x|G@|dUR{SJ9Q(sneLr!Xl;*D{6%GIgUc z0Ee#R zw!sSa0uMZPE41KLXOT4oO+Ce+ULK{UU+{q7_*#rp zxU?YevQ`U|N9#uqVP#{B1J?AR7Buo<#M`RPA@uKmU*yJ$z~KXMpd~84uatyop+hj+ z%+!=6_CSqk(5H%7*3i|3@gK&~i*00^zu8g`V^jgVZK=-{a?Y2JA=Go%Z^Z@3l|S24 zDwbEPDk}>+JF@{}d*qla!C!U0NP+{oTt`9z`o2EOw}Q3I(mio?793n2JW!B{*=K3S zG&8HNogCXQ_XHZeEX59mI*U+#Zv6$8o(T3T9lb#+wd zXqmS@LGlvmsD56b4Xv~sRR2p1oyPgK`<7V?g*FlHG4EBy3TQ5he09TM{Ks$GWL!#3~ zU!+qMK;G@#u1o;ah(X(r&d;&7z_Xt zWX$B`HtjQX@_lok{|f@$Qp#D5AT*`9nU~Sk>ezz6$9uG3e-l9OpqmLw|NX)a13uXC zgh}lzC+3RjpQ$c89GE#ayq*uMcwA`f~H07+Os&3BItZ?g7+9B{{+}#2dE{$R1Y) z=Mh9uG;0^|yIFcAdQ4(rmx2b@lU6j?dB4BW8=_6b?pLkxU|<4AxG5+U((B1gK@qrT z)_HJ*mw&xf0B^yQaH^&-1mP#eAdMQ(gxHlgKqr2apwG@(1N+BRn{g^e4T!nBH=bA{ z|Dn-Y9Vk=H}S zw`fgeo7(hDR4$AD=VNc@d<(7g!`F0La$JV7TP zjOAI&Q)b<`)KUp#%%h;#CX^;7vVZW%)yN|FskDf`tNZ?r-fjFuv__{92T>uBL|IPT zfScHCrifJvit6VnY}7#Ddgn6c52|5{bjjab)WVFDNx)gEHuneJ5F{j@S=q9|njjaO z%6uWpDpG0+vCLQ=m2Ji->!mh%H!@Q)zI_434bKwFodH#U3>7v6>2+89GYCw<{raj6 zC{~oerWxui+&hME050qkHZmqEylv}nsB?`I+1CKpkA#IdMf&A}S z{Qr-sw+xE23)Z!94-g>1Ed&{y5F7>z9^4&5aCi4W0>NDdcXxLS?(RCcyYoHo-rqTO zeo#dL1v88F^jh70-FMq{lJ{7S-eK`0;D% z=c_FpYNK}>!0mi~xh@cd4p2q*p53vtvSJ6WC@Co|R2d-ykEMNmGcb1YxMmzo;yA*l z|Dz;U`tXQ~dc)+STFqrDK#uU50gc*+t3BeSF}jI-8ff=`WMeV#|1o?=yRwbL}JBT zTM-+R;zl1Cb)_!U(9q!iWDYjQ=gGMkH1_A%kShbzPJ7X(t;a<~8~FHleP6zQRDOqq zr=acF8Q9?_tfQ&=ax?L;$U5=q8_m(}g9#o#L*cK0%X{%seKgf4^OlNuc|==9JQvUV zPlb?=Z{C?kjU~iFCyIyW652%BCkoTJ>fIo&cQ0)=sI5*|Kjr;ZxU9SpFKGfA7++nz zb+J$3UE4jHtO6s_6xa~Ihpwk)e*|nND5O5+PRERA2R2%GsJM3{JI0Xkq&>{bOR2K4b(Ibh%FL88m_#d22PwhRl81|>hHtrX8aP1cEjkB|u zvM(nG2QS>$KlN#MyTmXf6&1)EX*oGZ6kJ&OUpUa{O1i8)mXB@sb^aQ51P9v%Ut zv~*lbokx-Ob8s!hE-dS6?pnxRT7RrVhT_aA8|V|-XQYT@PJISa$pc7n?z#f$jk z?~xE}qj{g{KOQwQa+w51DZqH}u^GsK*a_N7G6U7y&|DhBAd3yk7CR|5HvK==Gaucwa zCNc5xVip!aArfo!*Xt4kQ_zS_u>Icd zU-OOcYfzyta>c5T0N3k-*xK?8oco8c3W2Ct=JsHj$O_88;I($APggc2rk&7FvuXWF z-jOC3Os+6}v#7sZy%$7FxcMas;Iu){&YT8Fl%Vg~%)P7b` z=VD4Y{GJ;~fNCZcFOby(nArAzRXMSC zZA11J2+>`Isb>kIB7@V3%7I%gd!?GzItza>H_j+-iY`inPlKBT_7g4!($>aLKHC*q zi`4fG90i*{Iq+v$;N&>BxVLjtNxtbie_#MSP z>*Rr}WJJnENA#vhHq(~4-ztz-Pe&I1S{RT{0T0{S>vZw>;C06T*hhE)rM>f@+_$gW zD!F?i357l!0}{DMP8MUscXax{Y9NY#2BkX=W(%NnhT{tuC|^VfM-`?%I}q{W%vVr zVpL+HJP<#CB)Y7A@W$VstNZgt!c1aTZs78~_J930z;S2ry#z@YOU9y@E8UmlCzOi} zDHEGG{Jry$iU?&EHv`g+HD8)xmbH;-)2IETg~4E`yxnxX;9gnVnaP8ZsbbM}GzozL z1;>Z9{<$$wYivO~$8XyTUO)X64~~KnG6}geIk4s<-kl&kKG==tDgWl;HZPVt3(8p! zw!5LxSvA;7JGpDmMeyJkVkWE+`Q|F`k4xlh5S1u>^D!o8|;@h@Q4c z#rgL&^>*B9`5Lm*+0;bA;&pfJv^{uvF?1;RyauW?W%|{lpu^Sb*UoI0*R`?^!@3uH z#%`#hUTQ55E$k%dcDJ5Yo_tG`Cwv4vT!_EHHl^Rv9jmDzj^13XbCpJPTZq>cz`nZk z{ge$z7e6_9%(l0m7(G9(Qt)Q9@_~JXQ}FS7bP)+Z>)c<2`98F7D0*hFG-qsEt$wE( zMg|RcoTxs!1ss1+8g;tU%&wIYPN9-&(+BlM?;Uca1Jj zO5Db%eN2|1w|%SF=y&RBr)HObi_NUd)t%#xjxjGK`w3n|JeD#yskmPsH4YDoecu9F z$1~Jcb#nD?a_=_fj^>^AahZqYMi2?(aH~Dm(f&;t4lNhYB41psVfNBmzP*^n0-IY~ zn}IoT_+utw2rPQp9*o6J@&Omq;0>yzCimC^kDyuIXhaDK!O@lW@{(U+i}rR{vK14P zp|u4Oc~}G-s9SXm_{l}iy8DqZ!kW(P_q60xH$<~Q>ktJ2&i+8~1co@oVCdTg$p2l- zo)F>G<%5@#lM^?b)&8hw&6tCWe=W;l?p%*(f|hKL@m(e3f5^_wRoC?eD2?v_VF6(O>tpGM0jJTtwmxC!NwR7BCh(#7 zVl$a7#;8?GXGoZ+>q7XO+=qK!V71$}!Wx@LsMdKcaFL!O8AL@QHZ}XjXbU|_J_?eJl8|wKMU-xqC;a|vK zHiJAtnh%Jxg-r_-v!r#~Y70@breSMtJ*HBXJGX`wHrIl<` z9RyJ%dxqeORDljtpiRhapyr_U@c4ND-f&L4&)<^=<6LX;PDVTC_@XJXvBOrbrT-9X zH9r{Y(xkLBQf(^|RBjm`4eJk6tkaxqEVD{$5eRXFA>ROL$iJhTLtau|!V;X_*nU4R z9XQjK8iZ1mUdYazcl`%ft&Y6Q8H%P~Hr7lT-9jiLq>8515VuCdf5F7(L2F@s%^n%( zzZ0u0sp95(ed`Z1q7vQ*E!X0aAoR<%@EjssPhK6GOREcF{moEkF&chiwW*9Swe`DI zS-2xIdnHK8#`^p4oLp$6bHJ7Ddv_e1T~s+PCJJqJc^?OyuBWdk#SwlN^dO1#X0+Yc zkA9kZf;rW$)is`Y2gC`=>9=r%<}VREr6Cu~laq4N(xFh53^hOcwwWRm<=;f++5k*r znEB5)HWi|L0Pbs=C=bk~Q??XLlD#v>Z=Qz#nC3t}JTw#5F0s5SmS28jkO&l4Bt* zvkROXZf7<|t>sBiy`KcTc-A)s)lV?83H;*6`7d$P&!oS5ICl+=-;|TAtKl_1T*P@f3 z$C!hffgS@$=q9r=`a7%zzRuTFIF$-8AM;;}8&%ctzipK{Y8i{w@dmTLsVys#+|q~s zF$SgbCjna08jB!T)j!=&{z4Q;{-8*91FsbV|1%(twSes7|5FFz|2_Ig>}%ZgUBH_f zw&7J(hyCQc$XyvUf#*Qq#qzZv4q>Hz?QsakCKI!XFlZUZ=RA?Qxqc^@@X|8W(n07`R>^3PiEb?isDaL|;N{wc8@66ftVlHPr zi-x_svss&azq5mFdlSF$;155ifE$^FPU097`AeE|sFud-j?xz_{s3=jDyzr-JMP13 z9~+%FSGhstH+Tufhd=?Hi=~q1A8O1eEcydn%ws!U^0r1cB$k|=!Rup&kB$Y^yJf?K z6}js_lwfQ&In~ze@P0p=lc&EvGt;c3I@!rs?EF6$b->2`$KXXL<3v6+tT6`{SHFM? zqNhQ^+*T~ctUnJo{Bgmpm2IS63peUnk-w(e^uGn?D0rtXMq0>3Z|bj4ZF?ykCGIZ$ zm;kJs8n7Jp&!X3G)Eq_DPZOvMMl?wsoFKDTX5(U~XnDwM$`v>;Fc7~4H4jk3)$DM0 zHQ{AAGz&5~l83cqQ3pIgeoYt*2=|wJ=9&>_qM4!+%3gqmYKTktO|n5?cGA=*izuB! z!SLe%snWwV>}53}7!ULZt*YS1X*0Q!o{Z$qkb(;MDR0&%k5Sps79u(=7aadJ3<{CE z>+K8A%WW>L7yj?cLI%1_8%zX`?ScrnyWie!ZG#UND}`W(ncA@Cp3x8SD8#SSxTUuJ z&wvbGh~OVnFe7M9h~4XT=KRDn#qiA%K&=mw>F)DYW)%;MB=uWRFhiP$WPvM0#j|YO zPp8oBW)?0GGY?PD2aY^hY=lb<)dfqCW(>dbe6VOJ!S+ojGXuEr z;b7mjb45H1GWPxJhlk57qsEBPJF8DE*0`&noC{Og+4V+KT6S^#n8})yxrEhXOk2Rn z%W8G5cdD~=lg-5kW>XJHD3n=Kj_J9Yzslc$RbhZ~zBd7{51Inu2&`H4NMk1<>>9*Q zD;5|c7qEb?=Q8a>1ba3j^jA%}hkp4p%XdB~y=yy5q{&l+iZHGmS~Y0W#ls~^P(Xx`R<`ve+X7~zS)Z&7mJTB`Gpyau(;kIV zfCT4ogs{UgCnTzKZ+&Jse5ziB3bp(fE&y}SN`9sCn4!eWQ9p0By>_h(0H*~UdI9o6 zxIr!_=1z2~%US{c=>F#Q$?oLIyHTg;=TCekushQ4jH)DZeJ^gKRiU3;3}oK%{tu>h zopiE7f&SyRCa1?7I&CkM5zfB$l+RoYn0Dv_gGKHI=ie08KE;Rr)i=H(-;D)N3@~)G zCNZ47U>#}c;K^zZ-1+))sgvsPLtdm*K4PyuAa%4n)1SW16FuYA%!9ZtM%oJ4X%Ih^ zojL4b`E;J8Yxksw(eI|c@twXv*}_6(76}aR1jm1@D`yzYumI(`C6NAi@&1aa+T-R| zT52Iq*rsIvWthjOr-P%T9;icf%GM_i)pzE9)%AUoB)L;K2Wpkj=;(jlCe#pEd_B*PeTf}a4~xGi8Wvb6Ig0JQ#0h`+*~*spiA6E}^X>^Kxsl}(fGLTI|;gl6lz zG7dr(bG3XtwsqKi1?vc{3IDFrKU(!V#$s>K0ZRs(TibN0YKUarH(p7NrFo#T{PqiL zdcJMz=V`#B5Lq@dWxEyQg7?Q1L3C`qZ_lWvz$F@y$oOCGab9SMIOjjcdu<|SJ*jS6 zBa_Bmk%9n2NkfAmkiC>257B5M31|O38^f^Ukm|c^u1o+3DJms-3gR1}_BdKZWtAag z2fjqeo{wYjt&@==flQI#uF1ap8N<{903+F)K=zn;D3y(G@ zXXmY}2aH5(PBnM(?(+s{-R`eh4M5Xn)G2FdXgDGU=q7WK2||1s?y~N`YkpjSzXxz` zlkxQ3q+t=wMKi!mr{?67>1Q=4Smp0zhz9hFSOyxmD7Pdp>N&v4_Ktd2aP`-g1QKG) z@|;n&%OkQf1sb{hK>T4WHcSZjb!5bwvQC58RZN#JrDk_~d?aY?e*IqA;bM;*(_0s> zpU4S#IdVC#ZB@t z@G_b`JyFh+p#Ac!rt+@;?R#6!98=(0`(}pe9@g7&j{4@bbEP>cNyXObE=Z{&$Fk*d zkD5L6b-hP${g(GTj|3E%na229;b2wF#RGrUTQ8wL!c^4rqpB^q>w0jqEDU(fH5=h` ztx?KK=*Zt_*S_NKK>#nP-d%_!B^bxX!NKd&UA{~{%`O&q4{fsk@-j3j6*8YH3h>SS zt2=RfqJAkUAys|OJmO8Qz-NF7brO=&%wsJul$eKy=PTEf5qh0kUYM#oX%?p()a4)^ zSl%kE_?r-L__t4hITc^bBg;(2zxsSRUWcp(LxzfuSNb9zT;Ydui$W%}`gh;(pQW68 z#^N`m!+E99-sMvvX2X<~O8PRk%PzMR-Hj>AoAc87N;ALOaFJZtT{q4(!=}uO$bE1_ zHmrYTrn~ghMzn!1Tru5WU$yo_udfI~BQ>*rQF@NW`lrvm!ze;Nv4HpDny)f{o2OvU zTCxPw4jZ_6ywHU6X1J;{Ya1BJOOPfI4E5hMNE4*S2d2ABAQLBip(V+zs`BTLbis9X z+TCJFCx7zPFwTDbP?&Sqe z_WXNxlM#f>qN2&En{Xv(=jmYo@uBSo#mfG|5=gqye5vMS6;;d7Vvzf{jJa7^qmv~L z`~EXv^%pJ{F7c21U@72_5UC{(f=}L8<^xss`KU(7x)WDn;ocN|h?2L}oB7|?v$ZX<0UZbwzREs$ zQxrb^ZTp|uqkNrr;amYAI6k}yuWknl5cSrU1TI$7L3@@adEQBnJo&-3Qa&6k`0ef3ed({kY_$V$Mr8bG~!( z_2_?UFP`&guS#?i&#z5o3Xj~=G9cGXV`Oz<^B(~mvR-nzMCWa|OhsNc$8^VYkD;gn zZv&|p*4ku)(+_a&1FTjla47qrpLCJ!j>!LDAEL8kM??X}4bHAIg?8wpOdAXXJ$*Kk zpv*=Ej5F5JmfI*U6AYg0^BJ^%30UVth+1h=SJzP2>oozNMPN`gIP0b^oIIhAG<{SI`AAjD6rH@xz`Be`L>3laz+D>W-Pi?a@-6w1%b zLj*Do7Z;b~u0&EU+%{lr;#zN+wRPCp>F!h$a!~{^tx*sqYY7lrY#R8G7iNXU4dFiPDl7|xA}cP z8TN~;Hp-H=5YoyoBL!EgT$Ao+zL}%tTXF(NNemBdl}9$d775tO05XGfRJ9H?6*k4b zD#>IMmHlaTgEP_Dj^SiP_|&WoI5SODc=)JCdoNA-Rg^5NKR@A;CzERN4q;rGV;yv@ z_6b_g&Xzttc_hq}Ki#3J=qyp71<`#4<@_FcK<{e#8(gl$c^wgGZQI?C)tyAV?;>k* zwd)JBbe`;BKgSHA&R_vVcmI?&otb9CvjlSF0;+m)Hs1oQ2ky< zVL`bK5kPcQ)!v!Fe%16~O}V@;L(KGNFL$u;Zhm{M85|kOt*e`L2&;}e{UT1u$0P2p zUDy7XCrdu{W8f;Yc031#>h3!I7> zTJdTbyL)@FF)^1x{w@w$v){JGePHJ;yd5%jp-}e!MCyPDzrWE`{y+Mqc<(Yg0KcQ$ zAul&NAwk$fnEHv#kq2x3TT;XN&C2bV`AYMfggr>w6a0va?|YWW-%%du|CPlk^5Nb1 zDxW{{+ZmVF1kuj3lLmseX0H*oZx2tJ@cs1K-Tgen z3(3<4Ruy@gJvdPhFZnMV-MRxl}q!&{O986T{*kw-uU*8n~-#I)`dF7 zOW$-MD_;zoy188aU`~rdEB}5eEfKw(%6Dumn@F26HKnvg%BnoT!bEA^ujYc$nbc(@ zoSWxwEg(js^Q`YZ^S}7(umgPqnda-^bklL{sY|n$BLhSZKY=N75AV$9do4 zmuZJA&CNr227qx3sB@${Gd3#m&_(-UTr65(Gk@`Z#L&ic$o3Y84DS$hC20poMfddq zHS{EX{qgqceE+XD-%^Mcg)vL}(RzgGC)bl6BI`Tn9eyI}V}+x$Bo|)qSyH zn~^@$E`aRBO;qcxe~3(t6ttd5w%Qi#;zL4cw3`_1sXseCpd{F*-IC5JV;@Kf(|X>< zL%(si86ZYLy>$|mK+fI6h%azL#5r6+ik9!x$MRX&Nbe73VzpGlv(t96L*;XQH?g$z zFZedCatoBiu@g~_T7$?N>^t8m=dJB`Xk=(G(N#wAXmXt!=Dkqq$W&?-pw9fqhRQO| zW$0dtFkEHs+jOqY{vTe7!E$GY=1`-kg<M_URa$ zF&sGtz`g0-3oJ8HZPuc(5#O)-sZ;J~X}&ZkE=nt7h=u8oB}~C?&=)moM#G)QcBYLi z@SEN2*)ym~p_S$OrZWMb(ss-4{(Dh54fpX{VPJk~+;yYi(Fv!}(Ia00 z0@&+g^`*hJ-eDD*#_8!_3IRc~v8(&dD36`48WFRrW3 zlNWa-=|=|uTR?|LK~K-{UQa^SLMUDnMs^X*&Z_mPaNJzI3E1ZdaImsMJ(6M7GfD*@ zV>}&<-#u}O>YttB;|v@AZ)bS)_sz|uO1`zVPC}vt@RtI*3|5A{v?}AGeP$gcYPOoy zbOqKf+tRc$n04IntgR>UJ4*l2HR!uwu%j(;A21d`mypKzhTYqEipQ5`bg08&4CQ!- zAG{_n+W%uS%4LRly}|k`Br-ecrn&lcIz6RfsY63mtr!1}61J7+xGd)&1dVjBNS2x5 zF!;E$2ME~3)B*-WQm#Cja$SGLjdSIPhs5D0n~o5E%>jh(G1&OC(buH{?4U$IaA@5m zGvrO5&QY#evxH}6S_h_L8*=vGPhWVkR$7uywIk_2@fMJ0sxTGuLBKQL4as=@6&#yb zc~cGgdGq*iz5UUFo#tY?<1I4E6jyKwNl{Ynh zes&Y?lV?I@_Y=*VkE!j7Y^2>`*l?rgB%cmDb!SXT#P)CUjKQ2U!Qs|wR@oBu=~JXf z!QEZu_CW@~j-(}$OnP$6_aaAZ&*9>iD!-3-5l2k{i&k_R|JAuKf%g)z7Zp53P^cKb zL$|2!b~Kh8^!HQe;qSM>=C;U<~H}(MFwX-&?kfV1qNpeO+&K^;RFc2Ike&@q};<7BA=xP;D+P?&!#PeTCI2 z|N2ZyNu(X{>#?V~LrTVZ(-y1PgiVni=hQT_BeK0**Q@?n%BKAi-->68nJhUC6Mm>n zxrpcVC(YZbn$H8^Ji^bIIEwWW@I;L7Fipwxt=?%WO|>i6-aYrd$v83A`F*pGiS{2p z?_I11=!IkBM(&mUy2l6FGkr0e#-Mk$75N|x@d%Bz2U>f#y}T8>{!gbZcD|v3#BPVp z%bGk7Z;i%3zBtl`S{CxgDVR0TWap?@VXj3`4`wO1?>TG>4$*(-iOh+4J=Q3U zs}@^C++Ro%@etx-w3C{$NV3P@A*#(!w0>fXVna5i)jwH>tqx^M3=&e{7f)APeh3BQ z!ep#~2{rH>#r%>@K6;h$bcM%B|p)=6z0LBFZ*W7hklR z&lAFG(;kKCgm0Q%1UJ^ONG|@i9gUHx6BbS8jn=pYyg)Z<25%==WR9`QX?p0z7YaLMmq5m7qa1t;gfE`H7sg{@z>2uUah%t?L4wNul(WMgi;5AMt zj}%alzH^LYKT1LT_pb^kLE&GaQ{3~L104N7xN!@&})b!z4o z#X=n#W)m$~_NyqxN$5(|Bo=Q&*DaS}CfDIeKH^ZF4U8>M7#O?0st z-p#kF01f;?+8>dpZ8*4Sw@72R_wA{v0^OyJ91$)4DYpXs(`FW4)mrGjugI65ToWaz z!-Jrn`G*$J>2=g^j^EmDwN5RsvGNbv^kDRANKUD8F9;kiKG&EJ)GDPo8_z%1r zryp;g;wkrcPq0$W*P7VIRL4TMQ{EGd(m^VTB{6~<#WB%vqZ;gSuJM$kxc-# z9)-~gfe8nutHNbZ#H_|8WqVr~WU89-EH?HFHs_~rSVt@~j8PTSV|e)}!%;jzzu;rwAhb>GKH{tpWfrzr`_^MXHV$O{tD z9x^+~UdJ>WrmI!hm`7a2qoX$dNQ9$?6BCujJ!aQ>7iTqC4S-8~v2q11(`lz9nX`L0 z0UA>Wnyz<}&3oP%@?R-1!dl8ev$VzaE|lixa34ryT8nfX?wPg7<2%9TX&wgcX5M&5 z40Lq8Hu4Qv3FSPd&%?my6%XN z&nWBq5AytdXY0kg#ZQ(2*eW8EUzoLDu;;Oy}DCzDAE-TR6k$e-A>+2 zIo7`Jo{_lcL*@j1Bd!E*c!peUH)`@^9`=cd=hxrR>zUf3Q#O4a=X+8KNVUT)Kf{1- zo-ZwZjk>Vb4ctBadSdzT-X=rgZEzl5y2Yg7LP*Ssv-_dpE{lP^2*fAw9-pM!_}`L6 zl)$OqLfI3m7l*m;YUD3&-|Z=+`)wV^ao;gKU%WYA1`%5h+7k9@)+JQ%KVToBSuI?) z_v+&7_R0Rmk5NyMcwL#+;Njw_#ukvKGhDUhigkWVTk+mbUh%0V*0-Qk9iFRxmB(^) zw!dCmL<0jf*ujQn!wXj3y2VerqNpa*vb_sh+i+gt-Vf?J_I)=Q3^@u3Zqd8~tM9|E zYv|{2OM%lM5&v%>!%whR(-P!JzG zrjqY9vfII>{CVWFmo!I&Ku+h6(g^n{winjM0Z@E_>89qOnDjf1S~QVZxW7Up%nnLo zfnR1a8O`0*M&P$RzZobZd>QdWn-rqw$W&jFpn@J8Du;kiYIHRR8Bs*Wl+p-LX1#a) z>A5x392AGs|J`Z4Vuvntp~T!>W)b27hN@+iIzoMfC7qKc3^CZu;mE)17iUap&- zXPj@kBw4WGmSKX$)1FIQc}a+Zy8U44ANmnHVK>f|qY|(d*%3N_R-&%mf7G^uZg`;P zr*-k5=PSg;3%!PY`1-lU%vIh{MpUr%j)6cP@sdIc)(&>}x(t3X4~c0*yt%P_KIr?3 zS`j}}5l>l&4Ph)B)*t4-KU(^D!W5GS+!HI>{J=@#;73fQTRJ*yY`HQIX!{6Ee< z(yjhOGgEBl{tvK{m9@rpncv1Nr7nVpICW_hMcO%#LWS%`2gg|q#$UJLzNt|sZ}YmM zmK!{9Y>@hGsUCjdmg!1IZ2O&Q2EyP(>s+3h?UHp+`sFs}XmM%Ae<^U-OjBMd-Nhi! z;&k?or>CwJHm?9QpR5LB#B5g^0B=Cxl{~SG%F`rNfBCd?XdQ4Fw6yHznY9&l4$$5s zDagq+S@!r|J4+KTs9z*mn(*b~fkq^kXetAVn`1bd9dTzSJHit+Ur&GkUclI$h(T%s zqz`T*;TUh%DsMntktsFn+DX!73K8y{rhSHyyEWb^lC{kX%@@omTQ?LOmmKv)`M$M5 zzMy;Vo#<~o|AwI5xYJSLqOW&5)lB!h986gfaR zZS%O%OyC)YH9XJJgAudT0Ztg{%9*V`8DO$0nqxw!Gg)CN4aJe+*PwCJ( zi7L5C*?GoXP+3JuiSmb9M5j@B@guyveqA}IU$xm_hE?eG9O21=|Aecod#)MdO^7of z1v98w1S?>tkR(kzGRb3Qs%mM8i}g7RyVJ%Em4`ApGOVRM~bnfpH_-Ao0N#s}m(E8lUwl??O za(#HE(T!6dH-p64u!8W%1QsFreP_Ep<{K2Nwc&pHxtyNuex>WFV&~9z?)>Ow{OW?x z?)sp@;ez@Iw0g@0)-9d`0rC+$?rAAKJErwU2Qtl&sG9@r#!FgDw~I1Eu%{SvBKZ7s zzfEhhb4~lW-RTdo{bJAvclx&oDxqoIhD)=}h6OjdkDQP4-EPl&LkR!}_OtQzGO?r5 zFe6BLF?H))wo#&J2VsUiRLa!}@#R5B@;B-@#!qi%*o#X=&l>7CfR`L}zkP=M^xBu8m}MXLbO_ z{x~`YPW)iJXcu3mC99Ymd++XUvO=E6Cd;WUG69AC!KapcqRe~S>utM3!iJtT*gt!A z7n_{SVJ_#8Efb6aA`p=HaZoYWsI^(1KhqA_R`I7t8$8$5j%f_x=FNib*)$Q%bNky| z`Qrn{=9SVwDB$9@IF++!P**OyJy zVC6$aEzqodi6HK*Vh&w*_bwW@QW`f06OQt$sBP8N-prEHzg6F8`F#!!v466)!g~-= z@R6G^z#y4=fiIf`mOI%$Ooay7Cl#N27hX6QOEd%?p*T}1ck5|Y6$ZCweLh5E4z9PZ zg!XU9|B7iEGNL+>(1(kXyNUbhP#v436c@ZKAa0~h>fFOqn#A*gKjb^8a@z%&zyWce z_*|K*9%+iozbzEkH0ETV%b9U_4;DrDIX$e20vlz+rKP8n<>Z3 z`0(^J7?d=-ylk0FT$O${Jo#@H4f|bphfL@?YN<<{@?$#&LXLbm?-1ch#Z+T{0bc-i z&7z}dsi;oWN{uQ0f#!$SG%vlK;Fo?1^G}>|=us(uI#g5_lM&LUz9Dlmao7gn(JtV0 z@)2n6CCS+JF=k}xAqiOo!@v~C7&QFTwY%xb>c`SSL1zi`swnIdRcH}~)_s=j5WV;O zM|9uS6s3ihEt8f53!co=bLl{)cck$B5n|zt2w6oqMZ39c)I!L_{?$02ARDEJp*h{t zaKwY+P9I%N!M$-qg8dqSG%RdJ{-iU}W(${_Ueulzfc6a6sK#eXzrBshzph%=vKE@v zU@$_uOHVsi;nG5yI%;wlOjERTp5*jigSQ~CeLPwNGT953_RWyeh5m5Xij{$&>oDW@ z^uYb1zhzVVqd6WPO`gxyc~!bujE!RktQ)-1562@0ns{^xf&0rN+=PGo^V3 z_L%iw^ewGkah2QhVCyJa&{~sS0=jF;HBvWx}Vbhbx@q&d13JqLo@Zxf1Y(+aW zdTMly-x=%fWDS3NWG2^d2rqH9-T7Db#BB|=v9Wy>z+Z$7cH1pZUP*pKV0pgR8B(%t z%y>pnCfDh@9pz#_IbSX1eIi&Fyd~Jnhw-=ZxvEO$cU8q5*Q-yq%=Zq@-n+frhHkpD zKi01dJdR|TD@Hgr@vWU^d@;eJQajCwjER7zWofc zd&@s#YUkV&;XSk5zQZqaQmHD1DT^#OzO5Mlxy-k2;PQ#JKG2q#`)~7E?fJ}y%cEqU zh*e)C8NGWvPyJU6zIptMLErosbNr!83@3I7WH|2X)U;n8EZg<_6Z~yp7WW3tFC2_Kd_21%)?L z@WBxB24K2a1@OpFtfICo8SJx$nTSHI=%Sgf&%8diKL$APINSD+cYt8D2`NMt#IoeIJtFkUYc$sCRPy%HQ$e! zy}!Kf9-wPHs`W?6K*u?;JH#@)N`tUd;r^zQf>}DAu8!^Dh=io&icG_K2mczH4v zj?+iUYh~c+T)XkJ!KO@I#x2bYrpSs8#%H~Qjzvim@xzLSD>O<9=&8inc5|>V5(>CD z4uM#Y(C+(#6hQFf5&Y=>?Xob9g-&Ya7dmZ^c}x(PA2Nmy=*98#0t#j(J4{J zmXUQmuIH6yV6@`;3X(8C5j7~ zaNNtuNN2{OeA(OE(?+rgJz1`Xo+QD3t-HLoB7V0I>jW(Or&bMpef%nxu6t9HuWpJf zNHefs^HOC-uhn_Wq0nhya^1%HCa(;nW@ckZV}r4Z|IbTH=yNOHDimmA$@XYo-X;gt z>_86`zxuHWtahDOE`M=Tw8L^j5H_iS$ys|1T^8OUVJMp(x%d>%U5pFW z^z~EO?Lp8)u5(HVf_iaH_79Kq8l@s|4$z#gx>nR%gU4DScl4~iHbh(jxG;ioy|nQ0 z*{;oojIH$L_ThhvSQodk8Tl(60tk&|``c-IE*l!oG*{>+jd#z#(8s)zozL2a-W^0b zc7?6mpPu?&K|{ZxT%Y&$sXp%>r?t8$BZj2&k~Lqev~xNkBWJ_fs4p(KP5&rgc@uoT z!D?_2kItA|Z6SnIK^DzD?>8mJw);3bHnG;VWW_R%I|eUuK1DEA2~PS zzZ*BNe2q`f>MySxs|iT=bA5XS?HLv*e6>50^qGA8@oo8nwjf_g&7u8^?T=#;|g1EkEej zd&}B*Mf_T`Q;XP5G#c0FR7Q1Y}4MaSrtr6cHWAhKpHtMt$4 z((p;0oe^G%kdx_Ud1^EJFPV&!V$8s_x39H@4c?O^b2K>}KjP;1_X|N1QdIvF6=(JB zPjR!v{My^W!x8w3Q-SZ2G-bcKmU(b!)Qoc_MDQT81dZ9t3qcPtO; zX!nMbB<99E5F1*~ZKN@1NHzHUL0T1(t=~d6$B&U}>+cU9$e?H3Dq%VgJa0x>YkP1W zNU>8pT0w2YStxVIh1mNNgsHFAp+>ZUgsiuj307biWhhub6VOu+!Qj5pAv~+#M?|yl zxqKmECNXDjE$2t8dD^%3@ZTI$XGDz8g<&sjNhf5IkDOU)f*BU3uHx@lA3v|;D;?7i zHW4_P-mW#_NTPQB4Cv%Jpo~Qg-r||y1JnHE1+AtW$UW&2TK}J=rJztC5ik*6|CEDG zOt834v9WuC59ye?ycV_u5pK{03&BM2Q}qT9>9%DzwYWcJSvH*CHHT;Itv~2}hC$vS z{uMehv3(*B51RxEQ8=*;yop5f?Qp`%m8xe+MplhMIVm{x3kV(X_~L{3+tVNvH{Y^R zq)B|!fD598^RT2q`B@&uAs%-=@kxM{4CbuSBU#D%dtfjdEceVK#BZQV?z?})N%t#A zBeOj%ruPM>Ob$k!eW6Blxk>BSpQY@+=t>e;Nj3k4yz?AeYzHUq)*EvF<7AaE4y0{` zy%8Kg@iv2xNxy4$GG!>RDfsyMs~?2c!0ZMIO70%ZnMk(}FFyI-LG>fD(!-j}L<_EU z^TXNE@5ijnU_=!2<$bQbL@`SzVX)aERzhFZ)W$N4i-{sl5h~^_rB*W3p27feNS%$ap7OUY;%&|XeApxpN_xJZtf&s$n59h?#d2`M=&2nJPbMx{* z-6KEJs#fB%`c*M%HyPWYVzDF!wadzc1p5s?!3vi8Unk@a1hk+B(MoB+aFy%3J6W{O zLbZZu`|!LDt$ul7e>=l2=B;&GxiL6J1qar%=(XgO($<|*ak!| z$KP0~Od)ut%*Hi|_NVb&7dOOXS^S6uv2Zp(>ut8=emAzooG^Ii`9a64U-bF7rj8p< zx7F#%Sm*9Y0As=As!n}4!Kqgg-#EjoAG{4!>to-d z&WTS{Gc7ZXa&uKfI&H@*_388UG6^|Glwv!?dEF~2<8_>W>ca7QEwXasEV0J)YE*^h z8|W{LZpC_^Gnc?X$Kfh>@toaDTjY6}V}6v7-?;C_Nv-~OiFB!H;h+}ug|?vskd0me~ox$_7*j?TTH32+z9@w54wFzf7znAYTM zH~$jYTx|%C#KKBrqL5N3(7@pe4SX7ZPz%I{fqs#t+c^nBjLf1i&Y>;wNEq9%rF~H? z^O{B27sCk#HWO~RCxms)&oTBNU+p*vmo3?qfm-~Ip4^mc1PslK-9skaIvj+AG(=|? z9k$4S&HD$sNqwK30t%-9t(hWim2>)_&>{(BsKVNgyqjl45h;?eeNQo?wMYf&o4(H_6c?Hlz;aqqij?4n1KlOL+jgMkEE7*wqATHs3!mX_| z@v}hto%SeiZ#7p-3AsN+&!NOxgNE5!g42Yri_)B21RrQiEhh8me>dK+PuTQMZu*lF z&E9^~ldtdlqXzj`aQ^r)&}Oa!Wd(EXOI+rt?}h>l@4KW#Hk72Gw_U!nw)~d}_ih`Q zA;Mu^s3_MK~-FL0HMc!Yf6T&R)Ts{;DrICc1eV`@vWBpwZ!O!KV~^2*oC`c9Mll1Dqh50 z|M9GDJ%JKTgpWns(&f7G=B6tO!8jLDSR8VGhA5XfWEB z^qBDDAi4x^nb0+K!og87{!V>xwuhCQaFa)&EyA*)SyI6GnL*)s@B)}rLo0N z9fb4=m1;4=(RLN);=B?te}{OvBnR+nUYXFMgKb`1TvTt88E59_Hpo})rX^0=+ZXKs zEDGh=?A-b-+Pq2o$NNWRC9e1rpRQ7#(Vx@>P;Y=-5fD)2a*rJ+Vn?7MbepnY$m<>& zHA@O{!WQ7@&r?rH$P_1?reP`8DADP4GQ+luIk?Z!R5VYj>l4>qXWwv}Oq4c`>&R7j z8UHN+3hM#Z!?K0c^mJ(#7Y<+um*g2GK~!HqDLc*4D0UcVI#Z)M1t$f{YnLlKge0vr za`&q;ML(61cTv#P9PAeCGS3tnV?&Q6sE`Aa+a=(4#$38y&r?Rj3Q>r*u$S_wClTIU zXpox+fKkU6`~iXLoiGb~)>Pls%2x-Jilw~@5`P0A5%{8yUTT;Uf>^ULlb3|*hKTXZHi~Dk1w|P`U<*Cgw zfqp4Edhex6?FnJ*1qNSDg!#UZ<#gukvL@2?AFBlJkv}yyzcP(S=T5&DQG6_#Q?xv? zd|=maBQT=mjPwk&x3`mwTkbQF(lKCDa8&@AQi)svtTxT->EkP&qlc+%)`)YJJGt?| zjGBb>)l8)VPz)dMP^s!edi{TL1KT}8o`4^jp1C{zYDg}nBOjiGPZr#$GyUexBraE%`rgha7b zBd_2wA6TUhgOu{m5K%YbcF~;2%deE3AM4BUD`19b*{I(9L+&zT+iEj#5allF@sn^f zARb`i;}(rSZ_?10rk?erqj^G4wTLI}<}S$Eag~cUEiM0QJXxMwEWyd}c)psaUNpm8 zR%%>AJa;qD6A#BQx@+6;?Xula(y=I8OwAvjm3;IvU{8ip7g<>iVQOSIUC8#sz5zZ; zx91Q#5LcROD<39GYQ%S&USbSubRK+-gis%%`O>g@Z|7?1u^lv&rZ2PK`IK+h>|W&D z_TdhC14~In7*N!25Mn@dH7G4#uT)%~!PXeOKz6mQsP+mG2d(X`#6#%h+2*3z9|l6$ zNa0`j8i_xh{&7CygS=4f*_I957Yl(j;ir4n?&Y7z$T_R0NW`Z#xpS3}K_j``MyBMG zZIc6Sl0dQ0=igmT7|2WG=$4h1)~ufQaP`mze)YC4_DY5}B#Fj*k}Hu*9uqY)!@IwC zO5(0C;~K+*a*N;&8WB+5bCNPNxfe+li)THNmuD@=x)Jo5*Q@8Q2&|)~F;M{K5Q;Mi z`Z}tjyQMup#eNBh4#3ltENB2y)QHztdAs=8(%XOwdK1XT8J16u6&dy16 z7p_obLVUj9z1a8~i4g-ic((M&VJI(T2lv56#J>eUi(G#w0K!@_2mf|2<3mVBYAF^*j_xmyp|^yoE@(s49%wd{MbFBB^C)-m0Fshm?VT0%~WH*Z)TbC``;;~ zPQIJuXV2b{u*1q)SytHN1G64tKblDdRljg|Y~+08G%3Nl#P>|Dx-j6DU}mY45#N$p zh5h>2&KDrpDupfLMgd-~S_7$+8DkXURn=|zFZcGS|C_54x%Tzk^lkJSG~99Q@38QL z@MMur@}Q|G%5JR?mmXR;k?RNPt&@;{;ZRNNWa|zn%Vdl~Vqa-HMclN|Y%P3nzGa!y z{ht<~FauoBX_S$R%G%T?mTrhI$7-Eu`p(9{K=+~&db$&5rT1ANN)=6WUwr7 z37Wv*NMx_Ky?MForcED0O0ADTFJ$gQ)%p^0OEuFh&)RkeeX<70_8JNS{wr_mLB<^VTfY=`~@)05*u~)@uwCdhN-<9^p z4NX-`2~kdRD*`QnUCbF z;Fwkno9uG*jjLiwJ48$jE}p>3GqI5>q@Rr-=kZ0YnED`Vx3vt9Bv&NRdi`nOB- zV$*i5TJf@rz&{;%N^BJ^8qccbI+Ntm^g_iUTvGkmcDZNmeCV+OY9{Eqf`Wf>r#SAJ zTM?Xkf z(`Wk>sR=geOA~3@SM@Tv>y-vrhxA0)aj-Bad?z|Kf>@d=WzPvI)4Fy~{K!ZOTDz2h zWfHLp?uuYs;O4n@=X2#HmOcmqGT)^Ug$$ghOI1Q!k1uymyU`HU-tRAuEo6XnU_0&( z;uJtx{I<27o_+C^a!W}L*ad^1mUm1{#y@}YMr8v zST_RO^n_HXJS|EfY}eZxcxzkRa+{0%`2L^YC;uqKx!zCKn*NiwLd;Vto4f@L%oufzendF02+sxfi<=R?wgIpBl&QOVNE%rDB?a>EJG%0#L zWG3+N*nV%bea&EP^e8D?rL{aehxz1;@CX`myA4uTo|%9R40`cd2h&jgmM2(%Z|?86 z8>0mk#I_YfBrblUzu^Ra#y$^uKjq&fZt9SP0uDB6GQOvGkMURZbhY}yrKc%8Mr*Ss za^49xiVPCmb`KBC`BVV@R)Dl0OloL%`0I(7F-wsZ*@F>^*!RhnUzitw^}zUMbp9-N zr6JHi$nL1&tO;}Sw~cyv|InYmHWJh@kK(KuM{++*Fa@$}?(#nX+ixBqUSGNL_PAP_ z0m;}a$EIwnQnR?|Ya}S=w!mk)&w+mAvaSc(U~;k;Rl6mPqsN~hSDZE4 z@rQXOXwFxFWHZnNxpht!g1p&VUNRn?R| z4i!~O0aRM(68LCaE2aTQ9-}5J2aj)QsYa6Mu0KcyP#pi){p?B0jTn5R8laHcw7~uu zw?yTX%z^&@cAVRW==AdcbpN z7*z%MO6uulAK#Goi6WQVK`J}MLY!`YucNm&{>#I+m8%g_Ue=*YPfv4rxxasQ|J>Ux z8p>BHO`R8|Xpf6f9{o^WQZisIKL8+}oFl>(B<1Ai3$VPfr*O<5FN{QVgpW8`!3`zH z;;9#5wNZZojVDbCwhJX>-F|R}L3}@&3gz~{&C_SC6 zZwf|@6PY}wS8tJu9PQ%Qb~hk zL)p$LHx-G8cF}5rBl`dtvFu0j*18h2Ik;t4HqU*m6dF&4?SVZ1*K{Skod*z#O~`3- zux{He-_c!9kFh#4L`F%qnLq~G0G8}ek1zAGQ1UJIdP1Pl*&-2!G7Fr1EGnKt$pZF` zb&sH_^4@`7L%s{^U#|(i9Aqskfy--9dXV41n$&w}*(ebL2XyNy4V5G_SLaVym6Bsq z=1dimo^*Irn`J8|)6z7>!~!purJV3pSUEaO6?&7MFF?I{G6eE`k(*6TslhP={}qjim8ImU%8FYKjIqo3MU6jMND zYS~!4#^s@Xtnf@?Wpn1CX!;*-nq%MWg?MIFQG5#@h-nB90Py1Q=qLdGfqbmPBFQ71 zWJX{f1UE7J-`RTVPfK+r0Bnch6kvf6#!+`(p+Iyy264BW47p%>=%3597kD z?Qr7(ef7_E;LXm9lWnnQ!-bntU2zPvqHV9@r@k+#)~Q5_3w$D8WBkt&DENr!yA3(* zIaOu~hMud{A)bdDXK{WS^KdpKI61MlJ>S(hGI%?2bYSKcmy{%CUpsw6#N*umU(ZTu z+6dg5W8-O`#PaI`aC`y&4b#9sDj_zpb;0?J-2B?oDPWccTt&*(iZvj^84y_qy_MLC zy0Wsgv2hX^lgIrvgU ze1@ZEg>#&;d0r~4cEQb^*p`1|e8$f&KV213FwvzED>VdF;8WDm0%)xA5}BHJgi%sL z=(%}#B;;L0M7G6f>c|u%mU_o}v)3BHuytWqvxC>{hv|?y4$MQcxYeM#{%?GspTxD0`t9W~{M(gbRm zyh6PE2Rx&{9SK6jBNzTMMP^fleSho*Cu!?T8d%Z&g9gL0$%FRsmx;ohJ*j{3_)K{L zNPx8B1?~O9y7Ox{IY_01dOEE*DTYZ8J{xO5@?Y$SxR8gNGB(BrpyPyGN;V_BWso8L zC$tou9N3J~NTV-D%bas{b*c9|x1|@>Vq_0C`ug2h{3&o_yn zh=_=k;99{iKl34J%p$9>X0m6mD@xJ52`EMP2ER4%r~4)TIK(&m?_j*>RZ9hWB)TMW^Sh%-gygWn4IR1xdm6IJ4md`}m z@FaJCeEbE~Pt74f)C>s`+<4UwkwMcgtgcZhJ@Ty z?%#a>uvr;&{(N6864Wgq>>D~dCIEbkxRjLtuBb3+(RjG#b)U}wL}cWYFu+>k@3B)@ zEjpv3CSu(;@}Ff>fS>cTfu&0Jfcrv5Zg(rCa?O+yN1i&4l4wIc>uow8Kryp5)y-G+ zcP8(Xlv^3hAnf@)VhLHPM3C2`F195~^FrGj9uOd`9i9pc-{H0BKbbIEpF1@x!OY}u zWn=_dO}wWZfYXC(Y4977UY#Je6p}&8(DtkIa<9Z|{jcB(=ZLu05h!r)KC~EJC9dYJ zl`9Gt0Tcv&?2olZiX6`zkp4t^DCT-Q*q~UB^KVl?aDcRac111`!*y6(@(jC%iN}LK{{<`SluOXb4r*U+8yC*O z;&ln9JH97Or73pXcEwv)ToToX{4nL}VtAw6B zUgs24G5pt0*n0{Dd`p#otUfw*Z+cT5KNcQ!4+@gH+CzaV?a3EX+3hpnEX{~;bhBHb zYlChbgX+Q~FmZn5$u$x_3VFa`QA~bcovG6FEFWsb&NqTuE?g8dGfKvT?UAT2A(j|9 z;ScY&@%9G$@#9BQ|LPxWz8R1hUzGjMgX*0Icc*h3-_fLb&})DufuWNo%bZEWwXD2L zzavZZPXpg{UVjZ){^aV4IvG$tfOj@-xoI@7j$ezFX22x#@BO0_lK`ti^Q{RDtVz!k zTggaaNg{cRlOj_f@x+<6o1#@Xy1+MGo750|_<$h9M~~=Z#gM1r6$4bMMfj0{zg4)u zvbab9*N)_|O_7cL!EcBVVLW^?gXDfHC67E<)99)N)Vw>FbXT221dRPk&yQ@T9_yJG%XvH5H3s9C@;#D;%}ow7 zrj#3QL$0J>P*?MVOXe_CX89FZ3fQn-?D#AwCqVPLr9$#lyVdc3&9>$-zfLzr3r_=k zLwhi623;u!hxp@8F$=?Tl04mRSxNJ1C1BF``f#pjX+o<6fj7|FokE~N>lMY`Nr7M# zxSY9k2Qm`_36u$nh4M5*vHefX)y?7ZBs@hnxpgoB)8dkNKgpNotEC^R)76=n?(@Q` zMWFqCKS9xJv|#OetgR(~{P7D|GZb{w?ex9gR;ACG38Mvn^4c{eijN&r7^nE(@Fkx+ zH*3!;tSEN`jhB)ySDzPMVdgx(;Q~6E-6~VT)*#v8wj`vAu5C}EgAKb(LZB3&Y&}S` zXx@vH{uR6y0dC!@-_*@W;cRL0*AePAT(~=l?kgDSa^lg)uSjr6aCTZ6`m|hd>s35T z9m$D=@8G+-FZd5NT@=YdW7H!N4UyR3)_x!goAO*=BX2d*whfDKIrU+91ugj$P`FO_ zvx}S}2kohQ|C>Dm#;J`~t70lDSht5$FgwWBb^`^4BTcEtt%`{`u}LLOr>Av<2k{p;&)Tr@1Rhk2aIyMdil+=~ zq%uB5e3=$I!g(T8O3XxVcq^X2zrJ$T_3(iEX%bD^)8m>4ZdVSwM}n+# z+2{L$X?nB6p_|zdyQ3%PHx3$grdLo{@I*f z#gCU)1$e^j3uon-)xL-<-PVwGM?_>mT7}=$L^Fk>bR=0-FGx1?zIGC-T~ZE8yz4a; z6BMh4E|1;d1&BlDa0vxPk$@2c5Fo#7*4CB)d*0AQ`Q)VJOA&2^{TFEk*lcM@NzmPk z6_>d5%92Vkqn3K2cz$8IT#k}D-zw5bL5r1q00^bkTUNE7QSu4rn;yPotv*~7*QU%Tbpd|IIA@O#qv<8o)r^*XPr_I^_I`|gf>a?;Jy z$~&)zEI)gj>7UU5cQ1itgslH=7EGXSsWyhKP%(?w)(EAYo|>IGvlvT% zb&w)kNDRs+6V!i#1oru3wSMJQjSUp%`4`l&9Pz16T}Oene|(?49Zh8`L+m*kpRyI_ z3yE^xLC%j+{ORvdjkZ~zI6e|^0b%3ttt2BNmi~p09sYnmmp3OMFNEL-SmH6Fc*d$L zrgn}Cjc(-AI-=JUm5r_T-M-`+=Ap=-)n!d&h32fiNA09~j(EIh*&zywus;~58b}2} zw%-x*NO+y18cH7T$xjS;c!qwX>y~Ba2V1h+SU)b@nSaJ4hrV(q+E@5N@q^S5GH!O5 zsw}sa*8_YD->~=|Rvf<#4<9MUbn0(?Yj7B?8txW5`||JyL}tF)0wc>*luvO`>kp(m z*X}Hp-h>3Xl{k|+OEGLitG0i$$N9bdB13;e65@j9W$+3_?ew5w~qn1Esab{ zr}Km5ajxlaBvHwatz{GUR=m529qDm{mo*K{f`1?ZQX+9q*LnySlGKP?r4jFV`L4YB z%k|M3z@{ucGbFAnlQ-9KZJl_PzY)(Yx%Lj+I@cq8_1yS;r6Io%-lcxF*zeK?>3xCCfa_?~uE(+BJ=e7rI3Y zVkH-+mnOlh69WYWXuriQ@={ZzSr}F8akcBNi>0gpLL%Itc3O+8H6-rbZly7{xpEvV zqkD%g(BY+Ol5`^wrRtIV`{kr=6io(B|EEQsVoAe{sb0bU$S$AIrgtnvF6ss5Z?bwS ztGvxi6ycm2VI*TPF$G^3Mm)xhorM&)6B4QFF2f+-nx0cl$K69QVbtj#0)>La%xMgVdWTH^EDcnc5rR%00iF+amy^BA2- zs`>G`@zc8KN!8~b(Qpc~d?yiK6sB-&{sf-_x!xVLzjI2( z%Aq+5kwAPqSBp(}<)l6dj=Qs^;Ki4dUc)ZYk!UJ4f{fc@1>>}~8z?53zSm5l~}eY#^S42{;D|^S>D{-KkFv!?x_XF zf**8s$62Lu&P?Im7{)P|;)l2EyBbIiYI3o*+-te#GJqEK^Rwc0+>LxQ>H~X;3)A>G z{&F+Cewtzib2Zm;tlR1S`lG$RD_PJOs>tX4k=Mx($;ziI@w4OB=8SVAoFOmFq3ew# zdd(f*jh(KWPVkgrs_+Hni{T>yhcaFbA%jT5NB&(%M$M}(u~%MVLW`RHW%ieYQ9Mc1 zqy2_Uy|MEykB}F7l#>0T>wnq&gO5`TWM~XiIy$2$L>x6+{bgsDXSqvu*e)Lj-jyj- z+8zWJ-m#aPPfp$q*OWg>=D1FSVO-DBO%zSzun{2E#Ig=ojyd9<_k@T!*O6WSz3p>( z{<=CO{5&6$Kp=>+ChjsNN1^u#x7th-|HgPXt}^~4Mm2T*3P%&C^L9MT?Cm4O$Kcu6 z9aHmDn?j!a2LH3|4zK|NPw`*7lW>tK$sIi6s*M)Y<7%LhwtITzYIG5JC79DtVzNW) zSrYHELPLF|E-Q0x>kp^;?x5?t&b7v2CP6qbGM9GFS__ zx@|ySuDTQSqr-X>ht4=@9r^<-%38p`tvYxgfu#nCt;Xh(KdK;0SS3m-z5w3!$bmFLm|$;sUs?2-E3S}RoXi)&Xbme$s zw}4>Z$MS<+w?rG_@a}cB#S;C^%}sG>Dfr)phQyqlucf7>{JRrdhT;K-lP3!% zK?4OcgIsg7vxMzi-yYcT%S(P1&Un!!(LJa{>~i8UCEIk|i`n{VYL7GFlNsknntLU7 zvg0u(xo#vRC2e0vq=fY@tcvk@v1uB!{&Bea?{_OX!f_Z1+S9L)3S}5 z`tM)#Q0f1xL6N%MRrf;9MlS^%i0ley~Op(nFgF>d@^ zonA(JuxQ{0O!>Nfe54N}SYHFt0ac2s-kh91!np?5Xswo0G)-$})92%8_Fe)|kEXE~cSUBbQ(r?PFYESBrKe7sF>wmJ8P@fa|IV1OFwv9w7|a^w1F_0DZxug#F> z?TFjenn#<;@BX6`i8n8{JDpF`ca?)(+%l{S%Q?!`_t26(7=uL~m{$ z(nIBI?Vw@KdLYag97e6NjUpzH*@VDqx$=@4bk!s@F3`9U?0X@(F;)Bwnc}|F{dd++CbjUneeVDUGYGtV*VFWIvMU%EZqS zy_vf%$4#kT-~M#$SU4$b?jTM~N(vI?kt%T9ka#=|!|GjQaEW4ucc;2nDP38awn1m{ z!YY8w8<!IytB(!g#Q`sE8nX z2;)KPhi;LkUIjS9rv>KGVNjLsq>fk9b?=|kRG#)&8=X72$|pN4tnL{jLyHcFwGeNf4U5{p^0pFGWV+73 zcHXR8R=zHm(CU!jAB5i2yfb|6l$tcn^4p{wcDX`le_lY-KlK$Dp^{ilx)XbxPSH}r z+ulv-ZM|987|i4d)Xl@>C~#Eb5HWnDF*2 zc4f$VzuvC7kGNZ>v}96L(bggo6WH)~e|@y%=TK`uNbPM8sI^v5%wTlZ&97|$}#>g^AeB>v58Z<6KV~?1-0p7E- z0X#gS(+peERQU~UoRy$49##+?;Sr&cSX2}bgB8_YGIpFfgajD{Pa^peqqpUq^TRHs zj#w5Sm_(833TB#nFzZm!;TC}dY}Y14A@$SXo&Kqn~$@*Vu#*3ekKLN`%yBnI}Z@Mo%$GztguKDYfg`Ft*B- zM7kHiWW+&W&uqan!T_ZdEm|cijtm9Mj?xLb3J^^JT){%;hUXOt0S&eP^;h$uXkt|9 zvob=*bQv`^s_r94?f@JLL#jF0?qWzHN;-XYI72G1hLeB_II^f(XL)(~7Vp=_A&FG?RZ6I{ zdS9Yr^;Yd4Nf{i!+<+G#O$V$sDbiMs%&mg3lKoiJLdnnh!NfO$|II=j!f{m7T=;bY zQu2Y=(LCXO&3Z!b_g~F*8jr{l-`6TC3}BYg^;dGQ9;HvaTz6VXZQwr-ehM!f8WbZn z@=-Mp{MLaPN$zn>xpeg_rJ7*@LG0KGvkOnpoC~N=(!@!c@Y7f?q_S!O%Q>oUQ_U0B>d@H+f`d1d z@^*}eVqYhaa%CV!K+Il1&yvBz5R^Vyosz59U$l)EpPU-7(lO-N`1qk-YA|7R0|mRR z82T^*J6|U7oD#5fC6J7^@1j;AF;^y@D{mIbFa^Dlobg_Prk-CYQxue?a-3tVNIQ=J zDlDXdi5(b)s-z$7v5N;8t~9cSDcF?0r`{M&U_X;?$4fb*?VLG)vxAy9-AYwWb=UR* zZa%&&czAfb7O!^Wbfga^&KHznN|>VY8TG(8ks$`(v(#Q65FmJXqBc?!%H?YfSKHvt z88<4rN}X<(=5uw2d-ZMZ)2MFJK1yh)(4SI z0jl1|uTpYYgGz)ZWTq9L)u;<}qgfcbolSaA5!9OC7tZIc%D3c$?mIwHm#fPFdwzo? z4|0z4+Gt0+IS6RWEP#70&P+5NrjqV-rODz^n(j5OgX$7bQ_(wquTC5# zp#bV}L?|3c7^iF2sE6}v?ZvKKA~p3QKXfZAbc&b7$Z!QKs!-whhTL_e${)#n4LIB^ zCJ)9WC5=#!uAeZv@|=#DqYA&*QE;XD9PSTzV&vk+mo2JQ>`Kys&lPKV)H7wVm8D%= z(2r#__p^^i+tEo-tz7Rp8Xx)3+!4wPP8(RiK3Ki*6z0jz>@(pL7CgSqa1S;dz|p15 zP|g>r78Ng)O~DTqr5%?Q0|y<=Dgx>%evzhiEA_lg9q70~wDB$6wNoa}JN+!HQjMt5 zb{DEHFSl&pK)thR)I~GKtl}zJ;Q8kjWV0vBx#UHHomN883SA9CxegrX8ldym>FI`ovF5RSG@=bK| znA`HdLtfHShhVY8$Wv`jn3xG_ULq= z|Lv^50_Axa9FlrFe%f5w?vLxONJYIx+$+m17c$JfY|BXmd>{&4#$B?dMivhZuP)%R z+ZxmmQyYg_Z_o>u1Bo< zi*Gk>UMJ*P36)UVlCgZB_1w!}84{aG5fL-}h}f*%v(>IIuW?Wb1^=#)Sncjy3B39Y z_3O63+{XUoMh5$`p(r6+R~FNkcUSKiqs^HeH$HugaTUp&v=ej32iC^NRgS2o#4HqL zIbPIKbte-mX%O(6^y?OdZ}n!JvNG8#UE=&tTN#{-{A|(@3 zYzvUsI2_6$6Z1+42??!r075W+!MF`8xY%oMU|p@%XN?MsOzba+E07F|raR5_XHBNP zuY_YLH7)IIVDQOs25`D%gD;+Ra7iscEi4az7=@UoL_pqzgw0U zZ-uZJD_JOZ4R8;Hj+K_0kA0)R_jNJ%QlXin?WSA+O0=2vb)pEvdUX8+sf%vP)|?|g zpI=~?^@Kz7JGK=kO|XpMoSAZc4nghXrdA07>cGD%wQJVT49{}S(X|~fLmu2t(~+5j zU@8T3*2Fm-?`FN(Evc>!eZIBm^EIjSjl!oqB$Dn`bf#YwR~1B7Sc3PXPw4>N6v2Ih zoxMS6O=MeJoxZKn=GGbi3<$Fii!&%)?x(l{b00sfq_lwM+ zWVlav0!X!%9Ts1D5|(*mweT(NpU%PVh-Tih%Y9gr^q@vUUQpW?_{%O_Hfps~q5VU! z+F1iwFz}}%j2I@iJI&9UYFRbTHpps}ZUI<7CK428h5*&>MHq;Xtsol&{nhzP2!%{8 z88=0ks2;gBYY#|5l1z#SPSMmz?}Tg~K(9cn+nxZ_;?k2u&u)2;Ft~OJ@yU2)7t*!mHGcuErF*A1B92 zlZ=X6x6H@a@0{TQAU7iJcns?7*@k5`p`>dQl_&77PR*RwqWR>?I|RJb`n zdBlX@zD7)O23L-A?Nn$R47*PUOW3hXR&KLinx{qP3DN?i9O+@o`b0}f z%KwqG5UZ^D+ZDBb@yn7uoh+(hwpG{1tEkW-;oq(}{JrGw{Hp4!r$109@ls|!nzi{^ zGc#z?VEE5=c~FQ{Ehczl$0)ozjAv;Ut1=~K z?>Rm4r!#kAb>@r{ty5)qf$lN4oYYV5^bZS~&s%Z0-O^Xvn@ z_+J&yVNz>oyTl>sI~iYJ_=FC40gGSWiAam&YtidhvoBF9yRHE-7$!0$lv=9D8Zz*{ zX>-tlDOa+>z^9vg)3I+nbMjq*o(QsXj6#dNB*}8SWNM`RqUEo>Q!S?p1D@|S>uYX< zc=@sO=|Ym-6TUlstNC&M)=JBCs#g}m-iwDVVNrdE-fWBtH4<`rQ3~C;%L{)crk(HU-OJ-hroH+UlhPov; zllXNbehraIS88ZVTsJ1gjLXnIG)`q%-UOCs4#JODii2D=H!}DCBH+`v2s6Xemi{{K%iNXvqnq;Aanp0xON@wF!k8T?fK&?h{sxEfYJ z&~#W5nK6w{Aj$ibNZ?x7O3DiJ%hl8SNA-^cEVN{$k^yaeySVryGbmqjCxh}5wA`wQ z{_T^IVuZ9<33<2Fng?KUdCZU=SdG}HkNDLgHi_dm|C6w;E=dsR{Y#e=7bBuLtDj3y z@~Huw%vzgG;xoW)-4hLAxOj1}+mbpU9?v!GkZ#(DoN;*#0l}h^7vCBqQ3E3Wd}hv_ zEtlGZTmQ|8(k808p+wTrqU|2)X^d{vmO#)Oj&KthhYxaH%V0u0@i6@;Xh@)kT?=b3 zTlz;2YG=rL zN=ZRCCqWR&IhsnREI->*32clC=b!>8wcy;DhWsTlw&6+2Vcb)%dhFrll@;`+vW!?O zL+p$2hE1tcbzW~mWbvng7!kjSyg4_8N=65`BE*t>PdQcWS@Ux)k*5)EQ-h>LmrjXHtH^ zK&f%ksmn>1)Xt>n5&EL(>#*;YYHO8#Cs{#}@AW+s${q@@r0XM18Tg7&D>>jaKE8A zoM#l&AbPU0|7wB}rh+|pW>SyjuMXfz;j-1wHk+1{o%Jr0L^48~io9{MgmR?N8zSJy z8kwKRPxs9KFJzhS5(OdQ;JI9}Q=m&VGVv`~u=wVNruTUS!llsak8) zz_9j=EPgqcH#r4G?nU(eeU{V`8`)n)*BQzmkIx;c?gba_s{P(!OEzp~J2|xw<;F;vxTMab#qgcyC}Lbl&4Z$DJ`Oo>kcX2?sXJBF`RoDc+3*7M@#)q~H?&E}WOuwDsTEK=a4VX_=#>bhgWF!qFS~ zR(oFO>hW?FNMRg+4hkaxCo!PG%7_X6peIB@Cy&-bm?*wvv4qWi3&DUQxzc7_I+?Tx;+_ z!WWVgYZ`)_Gs`nRQrAQH5$V+5?L{ay!#SE6Ml@Tr)Zg;jlEHkw{>EeEo1gF%5Xstk zJH}+FEHsfvfRUe9R?Ct%HV^f+N!f_9vsa`2v$9cRV^{~wHPa`=l$9~GnyjJzR#ws< zZvckCHt2ZIiloBd>660~Y0^_NG8i#=%zv7rMm{l$1tN|kMhUZSeNQsOERPX4*F?i8 zotG=&$>iN&-T+fl)O=?LH}GqC$JS{qEyKA^oM*NCz5hnZ67OY)2*N#noK~pENTO`G zx5V--gk%Z}$X6BPBZvRRN?->UD-ofLW=9o*3%1Uw-N3x-hg*R9hp@D|bo1~3qvgs~z!!5YG2bVx_CrEI2cXxO90KwheCAd2T51OD4cX!|W?bh;xDyZTI_uVsRrn{$` z$c2ZWpU8!(wkfCZ7L3SI&+;>KJf9M3DKDHx5|6B>`i^##A4>NAerSR7=t@PeI}#Ap zvU49A0iE=@$hYn@lMy+2{m+cL@kJ`~D>s`c+B-Mwg6Vi6jQoS!~Tp9MC#mTMCWIGpr?PvZwiswn4Q1;4ue9{j0SLHzqj z8?nWUrYYgT3LhfwBE0Lyl9q_Fw>p_&y79}GpVE>C+)O#0M#b>gCn*yrE0DM!+L0~u zDi0HiPMpX`NxQ`_W70Q&(&ph$ae54VrA#+ciCO2!hlZo+lNYZJm;3Wjr|?t^5HJTxi~eKKK13&`f@ z=bc9Nj>Vm$mvz|De_n}NO4nyCI;G_k-{8kgXfwX4L*kd*!G?&)h)6V`{P_(|kbG|f zIY$ng)l^jQbfH=?Szw*ZK#$R;9yxLY;mZ_!e0ooaQ^&e!!Afh1w~-iQ2dULmksyXHAo^2oSBx0^6#WDh>O~CDsoU~ zLzxU7_f0q5|FZMTux~Ulbt95KNKa&hHIP9DkKVB5bZsCLhQe?B{w=lWJta-@WQEnF z(utB0^jw^10PONy;u`qUp+tm0!QE>?5(auNSXBq+@k^-6aUDzvAvoBh4B9_@oP8W> z1@O|yMDt{(&9pq(ow)J>v|Fn99ttw@wsU)7p>s1>j{Pc4TTz{{R`;q;D&JRV=jJIr z8>`Xu2X`KRf;x05Eqg*G&>@|*xpl@kakJqJ4UW2ek}~>QMYQ~bh_CR6sDrU_BrwcS zZ`|m>nBqtAtG(D2wJ5afdO7haOD|vj{fnofqEacmL%78X_h(dJXVq!ga!T_!g+yp^ zF{bc17Plp-qX<9f?8kyl%ceJ3$qd)@TnX|Pu3n9+jI4Cw50|!MXBMutJEYpDDYvh( z_Iu|S{BpxSxh7`Th;$cktYv-=t832@^X(T<6OP{T4MkJGN3by;Kf6?Dsf)J|n|HpC ze^a2_PH5bo<;#Xq$uvamL z>EUq1O6S}OxJ{(xjT;cDLr+lV zJzU#M{N=`GZVV>8`+MxghESh)Yrv0Yd~x09f|&NRDvztOhmY*4Yj>B6?vMP}V+*Y` zSlQG4s1L$2|9N`)U!N_#w&l+sdx7~l5y%-;V zicbCZxPP^{I?EhuHP90F|5U2Qy0*?L7y2VT5tsCMKsKBpuJ1+M4r4e`S?Kf|D+1NN zh#^@*UJB;imZdV@;x+%;!q__&N-r)ly_=1zeN$R{z`hQT~}F z8NH?^ti(xFg3Or1KUqLbqCBtidu)bgx%3WNaBMaq&Fc!@@K;i5!Z)LJXKP(|vb^IC zA{5fKe#MTEgl-q4s^=YD=zd?3Hc|ll`DA>qV6oG_>E?7#vykZl%P(<|{ z4UP2inR_voR{tg#X!^G3%NBA(@~nY~=$6JkwO_?xG)ebUGA4nX>H&V|vk?g*TP?M( zOU=%v7bxCy^WWX}6Y}g-nrWLYSPCotiM&K5oo@O^9x2ktG2)&_i?{9K{@`wD_~)LX zW@JPThyg}+uBg^m6Qz%tsCd3_J93xT)D(5Uh3@@Htw$^TvQ0sgYGsyO0e@Gcy*M_q&QYo96WxmosX5u#`^G+-q zJBAYi5;F^`r&vthYj|ZVs#*+1%O+X&H+AQvB-C2#6#R5~GizRCi|0?6(-P#I zwKfco-uc(r-^Gh2x&9kFg8#jitJ*aep){=NF>AW@DnVipfv zEv^(`x_(GtQtZGIybipU)^v-yc5OHRD%>{5(f7fey>X|a{dy5v0W!7SEiANC)xe%h zB!`&PCJoCbaD;#955`jt9PAB|_>DPuC4cCLoIUKg>!I5u4f-=u_RGuNvjMH*Go-z8 z>{G#U_bl>b%iwohTi^K0b<$pFY|@aD4;Hq74%nK%jp8iI&km{MI~g@g^)GZm(h3nh%RhKL-R#i&c$H}Ka`WB`FF#ISd6?>Op4}xV)KjP+ z{e4>C?H-p%G!tPARSMaR1gPRAQwkOD^>(gL~Bue;IGJ~9k_HNyv5L@h3T*c zkd`)U>ft19hn@}x+1kRwk5Tq|utzG1Wtm24LfYo;W|fE%V7qQ=VWETZg{gLDWu>Ej z(5zbC+u5qUFazSX_y#WuJw*nwQ;+Y-3p!oRCmGnKogUz{n3_KV%5N?=yClQXOsFf2Q688Xu1E&R+M z8wQr0R}#z>&um2%)Yar^gL&r zw70#g`?gQ~d%Y8Knt>U(NHn|vGLZ%;Ro9-sESdkM?Kzfw?YZL>^a#&VkjHH}Kfbtu zb9$RW{&jP}w7iqVCwVE zWJU~5HH4A0@;jrYV^ApKltf;WmYyZb4XK;U=*;C%!>>%&QQltw!dT_xkU=v-AN(gv zHS_wyrFxz2PFrEPpYzS6sPC4R<`smd!jTCvl<%Jo@_G$3(E~^7UjnOTf5lllM}-vi z8~)tb$V~^))Nlr~F@6?I<~*r3|4O0;7(N7h*F;OEw5l+&3mII(6651X{gaZ{F4gY! zxcE1S#KEx@F|ysV=sk~xu~Vp_@+%zx%E`d3{2Lg_t?{>bkS15D-ev>|nsqY=MfLTp zL{V9mXcMvlv8h&K*WTiA{hkGYR5dygg=82}WoX5r=FYaHNSBNwr9akU>o+_2jzO@k z=Ya2Pt_KcEFK4z%Q_l9&;+Q{m1UA|Gjf9pKkN*c2XBN|O7rCe%=6$TEdCBZ1Xh9m( z)K`ucpP>WQ9z!u7k~B-}gI{dMp!=Y6C-L^G{kSlAc^e@5Ku)V$u$gckqSyw{Mui$k zFdbrcAU?w-2+uRFln3H}fluyHIGiv>#ybyifM7G4hWoWMiwAK`z!s;dw-;DIb9k6j zA|CpWY}@!NZs7P0SsjXVW#PnzH&S&wx;AMYf*?01DG;!LdBJKkTMS0HOIp zm%DpkdF+q>Y`3sV$RG5I(GOUr)zA)~02l~V_VjpCmvW`ijZP$42j_?WjaFmT;= z0tsW<54LdPP|G{tFXpS47`dr8Y%GZ-)p<>#0NA}WKR<9y7x(OpX1ik(jXG?$X`6Z2 zhmG>Ug3^q@PRHFH1&E(AqS2_}li^oh6}6Mh0a=Zn@Q7CjxH0hIR3Sx z_V(D$8e{rR`;8=Lx=6s~Ta$@S^tZrJB4%34AF_E@{idXCuKGkoR*Ugj$*DZvpVn@c z>8z^DF+NfA_R~on^X~tn33T(up!~W>CQuQM^37;x;Ap#XBAP52W|~uTxmf>Tw-_{P zWi=!9SV6^n+kbHTa=pv!dA&4tKu8k2Kfl%Cb@^oX&>spdM(C;6Ca6{&a>|332i+;X zP=+P;>m`2!NexjLj6^)}T+gE6P}Y{y_b4ceHs>5G5=(E^5u)EX(gN}GAUm1>3&%h( zkwmhgBi2gFRqomoR`rB~p@=L~KLC)5L>52P1qG7!Zsz?wlqvBpIrz?sgQ-E) z)TN)s5D%~g{J9VlurC+-jmg!y_MF|-z9ow^3gz}8rPYwIYRrG(u}`dOW-oZQrxO_Rz+9d&hi8=Dxj1LP}RM*BR^X9oII zKfSt*$;s;SNM!~p{dqAhC!!-_p~B?aZt1)6R)wz0ni{0Mh_{=W{%UTA!*$Zg7wGbb z2Vm$l?$D?72GSZ5KTTxGL*%x#B!1}khTz&)iX@5r(p1(bs|XOHhG^vycEHb%)f$QL zD{j{{{cCaMPGTIOfWx3*&^Y_=WK*9U(u5K^+iSOUHJyZ~|2>2ft43>rV%Ya@v2ns} zFn|a!OGqMXfx=VL(kuv~fsD@pIBEjN80>*L0#M_MlALxaH`(!BTn-x^!VgqWEts1q z47i|g1&VkQ(o~bU3_ne&m{k@Y_Ull&82Y}~M?xC{R zVA7ziM-g`6CVG7H2Mn`x|Ja!q(DCTz?~PfSHI;c1VPm)B6WwY$pM(4qn#!LRvT$hWupqwFyDC*R9w=EqlDa8A}>(t7Kf z>~JbB*2E87)6m1a?8vw8`sS>7rq0g6Kp+HfC)^Q{)?^O}$7-5XxgG|xtrRs1ECYnS zioWM)+5+MIi9*OG0w*pbeee(0zfZKPwb8JDUj;AY2cu*1bzo#c<(dfp#L@rSwLu}O zZVP*mhN;F{@+!sq5sZaBUw{&5ry0xQql{RHH#nNQoCS6rf(w<>3H0%%Xw>$+M7!2K zX-+@9Tve+w#me|s_rOH35w-zn5J>IH>;+ff#?9Q{F)NuB>uyTw`ff2C^*+6G!iQPX z8i+OD&^0=<9i5;`h$pl4M8x9yVg}9?3O>WiKybgWbgOdbDbo)#E;?jvD_dvs~wi&Fs3jX9;=xEO@0*AB&nB}M|NQpcct1p*cERh~Uihvb^ zl~k%jt=wgaWudO@yhia$Kmb?(VuQI{mAf|>{9U~q(pXBQvjH>MCrf`*#O@C;V|` z6KM)D|E~z@TB$<;DLe&A9?1_KII40g8J2CiZ4^6~eQiG<;p2Mj=I`TohZ{FtKUUld9I@ zsx|+XN4d+*QpD4H_J?-21UWXx?-M2lhIn2NO>7kw7KWvF>l7<7?YoZk;jK35DyrO_ zArsXKeO8Y+&RBPh|Od$lZAk_xpShNrST+4DLWMN-+kysG3#s*yk zfss*hRR&vZ%Qx){RDZ|33V%E`3`ZY!dW1IWyAfK1wr&XT6OjG9XWV&_n_+bO&)9`Y z(aPhKib=W8tIVpA6&r)64uqf4J{ieOl(v-yQI}+t-G;t@cu=!w0txYW)EJJPXDxNZ z$VO2@&v0;XfYV>ukdhn`8plq(VX-V_;&K+P#TOn|S_z#I0<#iWVgh_L4oJ4>IR+IZ z`=nGl82pHch#mhBKAfNEx5Ne2EBo7qF^8X*S67o*H8`v?%t4GbY$n85KY8n@2qZ8> zB&@p2#aa3#+-2F%`r7K4W&#cYk|viempO>2xLm@WndfJi601O2U{X7 zFoyH>mT1Pk)Ws`1&3quGS()_?vuV^=7nYArJwCQEs~Q3`sNIG@vgCSWO0xPA`-UW?+qJONDg)I1YD)u+17TE$R(T4e5ov@FDw(1oI$VOQ`2&7bLeCwi7Qh zQ*|72#4gxRTqX)J1P!s|h!aSO3aRf1A1L*$HWugNwJ1Ho#BthVAjWp`9#lVdfU~wk zwHbDIz0RtG`j3$8kzi6BDh#<_Roh#K{LT9NMWpYR7e;2@rvU!ZD`aP7z6$z@IahON z8}hGK3ugQWD8J5BgA;ElPO96?$BYo`JQ$fDbt-bCmx-(bAOK62(fbMTaGjWxl4bOPTmb5(J?g#To!d!%qlO;-L9z%V? zU6IS30UtXQ!~jBwB@pa`h*DC|pw5H3=cZ7F*R!v9A2P*s#N6KrO%X=mT^0UHd8d8U z`1!c&hS|{CI=Z5QPA0czY>Sh_s@<4Q0FD)@^=MHCV7AQ6u=VtEoZ63mPpCufPu?zD zW`LGqA*(Yo3+;`At>bA<&p*4>rY-*;jOo-HTCyPI#b1ceCD6?lI|jdC*&<7MhDBVy zaLmz}J6!&vsY|eU&%_YK*s$^Z3_CI+!2xtYHSQybG+M|UI9OO0e(O*2fkd1K&TqVBtvV)-0*Aj`}o6=Cy1-rTccJN+h0VrVncI=)I5ja?l|@V z&wDE@j3rmQfC_wXu8QF(a~!J#e5bD{-e8l~uTPYw|H8Y7ULrvq-~4r3(XdojNrJdw zfrL>9|ALmuWwEl97BoR`@kQW(i`_6U#ol?&5_n`I7qM~9{yuy*nOQ}pHX@o0fj_*> zGLP!!$SezW7sY;}*F&3sMPdu)eN6ez#dw8$a(|Cm1}%YsjXH_P@}0a#jwP216Xup~ zI3+!ZqG^2Xrea2H=Jal0ih$YVrsHxh2BU=~N;w#RN-#1xl`i+do4@E2PW5M-OEj+v z^uQXQHX?;o(5oHeI_xy8bEC!K;bB?H4k-Dk?QHU~Z?$2z|MLQbN>TkjG2~yzB}uS? zLGbBK!E@uGm&XP}pBB4*c>=Pgf>(bAlB9mrwtgqBb6pSu#Hlr{Tv5jyg0SQ=78AQeL^}d4 zH|lGjQvPEr>$}eP2`t#LlqJkQo<#TPH&`Q9Khq5!b8AJ%Kz2m=_D~$nhOSgRHzTjR0 z*w6WwWU?&-a~DeUH%`}c9+Fe^0t!e6@t=UUi80GzmFPHSv^N+ z_w3etw0`xhw1B;aEw*X?`+`~ZgP1ljnV?8A#{_0|>HlI|nbr)HV0dPRBUoKk(ClHM z6Cs^@k9&E2Jx^z}*Fq*@hphfLpTEOHPVn!$Y;)J-)?o0C&Odyl)vxYE(dt!cdnaL6 zMQGAtYRgrUY4nRiXJJ9>$Mx9((8_ZQGkbbEVSlZcw+{tNUce!|ah^VLeO$E>OG%E^ z$mTw{(=JB@<&2^6ub*%jh6;m0lD+=WsaONY)MKMMZ7ZTW^h>KKk@_~TRtFmjrmGADJi5)94FD{tLrY-UKNAeF5ysd6O@?xGl)&Oussq(zIgV19hWSGZX`tWw~Qsq07+shZ z$*=EBnBn!(CSk^)jZoU9j}SEaDVaCF0FuNTn+mEjbHxq*yjOt0G6~8a*AAPaDs95J zjmFQ>6IYc5rghi5(*~(JsTz(4{COGZr0yslkDwB)D8QdL6-HM2mTOMiXgV4yti~ya zCQ6H0peYx3Pr_m-&aC~75+-o8Q%sg~wuX8yO@=gAL+1e;?*Y{-RJ zXcc5}ZC2x&o&?B1i12^J#%e<ot zB)@uR)6ya+h7y>#k+RQw6wOAbC?=Kzl;}Y0>nG4H+ygBb}GcJ<3$+ z>nlRCo4_P(A9ZF@E?0mEO@d}_$G;YGLE2)?+!R)W2xA8$9 zv@Iv0;f5LW|DWUBfOoI?`jzP%zV^!jB+S{yV)?Mdz*V~0u`&47RtJmWXzb*al!U~@ zYY8qo;G$3bzcY^4trVDr!3sS>)F)O(*4!^zr8~T9CT+sB1CwAJ+q~eDZd#I+-IjZE z12ZPpq||Ed7wnx~p_P8MM=Ja;2yEQAIe;`tnMgB?zlVcqBuof zuXt-UXv?$-FR5Ao7U;y-Mljf!Vx?n8(WO}mnbBm;>W$|i%jJ}EUJTc$xs!^an+|fW zf-G2yJM%3|?z`UVg#9qN-9X$2Vf7alih@FxHOa1=Um&&E$ed=99Osh|*=J5HNJDS6 z({n!jblu1&W&5^0#AY5Q@4yd%IwoYkuz1`M?p(#?cNQ4dX^h#rE=L20DoP(O^5uSI z-rYbfoVe~*=_r{1>2#ZbcP?f?Q9qy5#I4g9ZR9&MIP4B-9btXdq0G`5E>4lu2QtrS zClO0p=Jb=?`0iWy0Di41manVC0%>_GX$Fzm!TQBRqF}#yhL*}&?0RfsdKv|QC}gtrn#lOs z!5ILxuW7BQ4D6Eqmr*#f^n0}e);L3JxgikCyVgAllvo|t-NlKP-{Xz$*4@px+3F#Z zT%l@CCRFvJucL#zhi0aBT9V74&6rSm#S2(wg^hJEGc#}X1^ETKov4wp;MILgR?d(p z*|XIEbTPOFuVqJU%~UP(h!H$i84Yb5)-@+8*a7$~w6?`L<^`={fw2@sOfZBsj<%}S zW%!Si|J}(joaUycv;Y1X{qBy`)DRapdn9nUCrX4~+rW$cI7h7XZ_O|Xc;Oc3WS8l2 z`cicD9i=TJY|&Wja|Ks?VxUfNv(JOQd@etJTnIfat>Joy+wSgeS3eWbjJM_%<5mOK znczEbIi@_I{je&_DHQ_DNZ+!KR3YuH4KdR_KuI0Ka`N()yuBGIsVewr?@AW?5k=VN z7S4wZ=yBG@IwfYjL@2NaG8F$`+6FjvE*0*Q^;SDFY(Y3a=-)}ll{BYrYv3ZgwR z5Caxs7%6jJrKQX-$GpYMQ24K(SJdPX6*ST95QcUqX(L{WUog>d*YX$C(GxkKzQVGx zar>T)7SagbQSp~T$U>aMU6gGXzzycbo*G0!5=@K(L59DzKwr-@#&z&^=+ZXf-krvh z+B0Kk2I}G1Oy?KZR(7GL*#+@7kz*0<>80&JM>@8ly40>p8Fl!y{^B0Jgt(q;_AL7T&Rm5dwiUjN1LPUz>8-u1=rfp(y>5; z|8>6<=*7xks{ z`{Ot5xK;;@P`0$z8uK!eRrqQRpCz{IBJ z=9$qc^DdX{&yA9XoGJa2a-OG+F3K~2TrJQSLDh^Z4y!O{`c}BOf}DI`J6nMXQSErB zv@}j1kB@#xsg_%&HwPry0>8X~5B`e+FDsfL-P!!?pb!)nAi9AuRy&)^RfP*AJ9kre z+-6%^G<*2NZd7d9pW_GB@R14OrY=eZq-_P(`AT;R2I9I8usn!C*+^&J_A8RAO4T}0 zl34OV$5erRu|1TP@{)DgeO|V79tN>y=aAfE?bfM8T3G)s|S}sHs zJCM1beyAz(=={GHp#CDII)sA@p>Nw0cURR}sUHC`m?q=j%g*Jg^`D*wX~fB>=w+)Z z#!w3^&tG$9atmGudVLEEs(=6OsfsO09ehE2q8=w6-*OBMqGIr8&xq>&+7a-ZQs}Nw zHg-wJV6$&JXO)RBm5hLdjbP8Zcv4f}HJA&<_AAo3Wr`JWUP1L@;s*PBd+eN?)=`7m znl0)JcGa^w)sA_}-P`V|!LjNhQqF)MFPcn^Y|)(d^3{j|z0~i9FZ!d+p2UPk1vmI; zFmYN10Ihq;+dN=~VjN!xYxLoLSYR;pm(Z?z57gQ|=xZ}*-P0m-?Mq)0m(@zL-#a7w ztBY5zkLl}lZbZ-I)TUqZ@`_*azQ&y6O6Sw@+k>O{p6q|~Hd7fDI8|8SW|IBUw+CiE zq@V1(`g@{{NPmkEXmG2derJ^`7`n!LBWnCRtv#*Vf&2?~!sxqQ9Ft_(S z=pl%GUluk%x)*$(hLwXLfTzZ=v%THPaj(!H9>;)od$wf(O(8GZ?@XQEo%6~k<1xFsf~(WPkN;!@+%8bYj@-nF2@hHPo_Rs~A@Vx=tS zYtux|UtDGx-Wx~iY|}hagkJ$^GYS_qt$D)z1f-1J6+t5cdC#)9&~>=>OQ6#I#V#ZA zNten%iFPO=c;O=U`C)cRJ=TRFiz%<4DJVYg3X#rL0s;V+79etGJ;n;Qb#BCkR0-~k z%MI6oKBz|ufZUnsljS@0#Y&|e@+bZWdGTInX?Uj4+Gm=8#&@s^hs?&+>=zJGDua{i zR*T3DJKKVks{+C)sn?h80Iw861KWVY5Cr#Y;?1j4>gx1*v9+==)EpA@|sMphjz}so7em10pL{b}~jf@kkI_KT=Rk_7PIS ze*#(!Ar;RczVog zp7_Y+{ec0||7P%5dX?b4WDw&oDC`DNOY1-biuJ`nm~*#=4VkRSxkX&7puyEq_$ z(HrLnNd!NXQhtv;c?T~yRIcCn2_rgSoXLmU_nX91n@#u-AJ!x2`ZezrJNf(b!;GYn zJM7Xp(IJX`#1v`74qWnt6yORrV^xGJ+m1?zg&R>0Nz9g~ z0c3uuqzY(WOJ*?1reP+OVo-*L0zaW4X&Lp?s)G}M*!y$~%ACl#zLuyt7A>{JW8Wrq zrVmp*eMw132pUWf0jNInb#t?!W^{SvHBB9zH0U+4DdK${LivL|1=76+)F~R0zo*5e zWl7fKMpNlcpw^>+^~vao)~k)px9~b$%`m@1Jiffmku@*Uox)0>Ff8aO0E2f>$3@S} z*whp<9}Woc#P;^~e%!|G#mjZy9YY6lDF*XgoSiirjA6922smGHXm>A6XXHuMEI5^u z1KF2kFZ5fGQ=RuKF%k=^rL@SOU~GWiBJ;+lTOatBt*juCdu^6$cVQSRim{Tv_nnny z^?<0D=P)AiMH>?E`KQ)-&IMtJBn1s=7XJ84;eV8#o-;mQPR1W3{TFmad|xM0yC4I8;bELRZfNxE zu_?Ddo0}HDL%f^c;Q&f1yJ~1ho4C8rm9RRotw=TwF)%&1icqYx5`y0|;<>9ZCJsv# zba@u)mPMJ@iHi88oa2OIZ`{oomH(v;?F*;>r=_uT!qP6VY9MZ^9*7zd#jph~g_YhRh>p-bIH~C%RMt0AJcHE?^VH(BQ-Zt!d{ML;K2XQY$z4>K%4-O~?J=w} zBy_=(efH|#ERBm(;pP8R>aksx!2KBBu1^KP-yZ`A(2%L^cTsM%dPqA_v9V$U$51Sp69pbuLsL&orTl5^vpWpnI=H0&r+b(;Ui#zXI8@yf19EUvZN z2^qMPK-R>}`MdDd69aZN%a_J=*io#Ne#4dJ#q)pdQuzx z?z^}gi0`@j%KPw4reU%Awqxdb8j*N^C;rW4`v6q{-mb#2XZ+561(oFk*}T*!XWCom zJp3!NWRxPB;N8*K!RmS7yHne~P<}C@poipcXN3qkEY6S7QD%P{RjK{;kNoFX5R?yi zAP+I%nx_4NdO;)TPogy^<0rIg=DRiii1q5OJ573mCkBsgdHJF6qx7% zrFS$NVtl%jHs(5C4d7Zhtq6?Ju5NDH+sri5NCfOBKn2l{5TGWb!@@Y1i6^#MJi7tl zE1S~N@~rgyl^vy6HnkP`D`8FJ)jOi#h1B_I)tWj3>k6P&JkyUOwl;gN7bM>|h_z2H zE_2PUu9|3_QXhuoGzdGW-x+i`q@|=lX(Ccp1gTsF`(O3NT7M}5WF3Hyb@=*z^-rv9 z?_d3~*BzVmjz#ErQ{@xcniBkuCTxYS`Zs~ARb1|uLz34;vQghmR-b;ya$V=ppngfz z9tlTXAD%gHPozc(B!kj<&th47#(Z~jOjoo=KJeW$B58NR?hbfk%j?=WC!D6=9jxjleYs7jM%D1Y6DjA zuimLeZwGCcH`{MU>Mmn&(vbvTph#XFQXs|H7!&5JG<8R7Wc1#ddt}Xr1n?UOL%{XLa|da1#G4?t8QR9gc-Vbu zfw5&0D3rA%v$VwDxd^N%JQ!l!>Sc8|jj8m^%|E}CS{zzA6uosPifr$Ug3m9+m@azu z%%kIoM*h@&Law+oKy92)T;f%Wjlsmu4jrL}{EL$v@=th|Zxi12Oo!Vsz!XW>5h~l= z?Dp1Y0|r7USt|Q)_=AXi4eu@45=)AHHf^6m4^>;q*;@q~DOUrM1g}xZ$i-d|XWKQ& z-Ni*aq;u*a6aiTv9IhbfOrd|}LowH)8Y#CM)0R@PN4L9Ls~1!SBVjZSRROEdOt^x& zh#P`T@VQm7Tl-P(iy(S*pL5IxMEl~FIH$SKnAAf;%D&0*9%)jFpebG=&O?P#UeY~y zm3%krgA4W!@j*iwH|wcG=GU|1ztdf>_kpp#-=QP?(Q`3hIF!v9p}M8P8mxF!T+7&k zby|1fUEE|0_B2OiRs4`EvKb8^6>ap&C`S#{_o@d#k0r;G%vkQe9(h3=aw?c(yxU9`Vo|MZ+t z<=+>-wMelnkQ^H_U#Gi)_2xAGnm(5sCeyDGL1yzJ}Bwx&mi;! z$?p}g`wK|7@@D};$`o7dl!+ao{(jIWPjv>!KZ7rsY3rh7F`GMdJLTXW2K|JheS3B> z9;Y`c^GX5<`~D(0PB~E49Ih5XIX+QtrT+=PmC`O{2a0tyVtKdhqYsIr3#oskTt>ih zSm`9B!}ils^o!pWNk@J@+3Q@`D7ztkav`i-#ofQLCq5EKG30BP&KMw#+DZI_Zjl-$ zyV_Zs9jOpMYDJdn$HK~rF+mH|9jyu_vx_%atI&|jN()$$aO7sgBP4A8WWNyolLIlA z?l;hdX@Vt+5*=t50*l4^Vz<9C%+Or!M-Z0OyHXUg>^T-?+(c#G_Em6U*e5UP0hr91 zuEt}oL5=+{W!}7Fp4uQmM&gsVsFi2fv6-2JzM!|#2{}mn8)c|9(W2KgOgY_y_OLR4 z52y(m1Mo>!-FEv#p2h0fRB_Y#3?HX|UgO1E3aS43_tMssGrNrJhT81fgO8#9xft%= zFL@Q+LR%{nJu};zq}!4QW|q8dQ>U-6C(|DS93NL4wY{f|OLh9vQ7YMVeVEIsj*Bw5 zPMbSI2PzDopH?lV_jo@%xbIgzk}wIjQzTn{I^FYW>S1g@k_t|haLqVBBy75vy?<5E z)tU79xC0C;?{ICIGYa-bv)aM&xL2>KEDelJc|M$aLm#=o0>(8E#I^9i)#E#ie7oM5 zBxIl`$}izA)pxe3Bh@D-N&0pu*}fgkU>v+g;{Rv_R7!Z*km9m3c0NABcX{Zwp0_gx z6@7hqz|aoQo{*IE0Nfw4Kna7vyAfB}g-nez^7JBP(FQlQ1e*r&(mD+-1OW*y+pjK&(!{9uo*#kh zxAFG~pRJ=!VOj&nd8ZDT2;7h_#ry%^hHAts{~Ir{!%?grphBNA?E~WuLPgw|EHY}D z9IxsI!7JkL2EhTLaSdycE?MOjBHV9P(ZjmFuY<|EC5(YJO+*tN5i(b@&qjaRkwg-- z$eq8Q(tB*v{e9&I0gG~~77s}&`;^p&eeS!sSZ4A=pA4edkUrrWn`UDpuvX{ z<5uHc&e~LE?xZb&;?&;KMinefxvlK%8rJmW{LkY@jhHsxt7;ss(i`Xc#r^AQR388$ zV)%|2rcH`t4)KjI76RA~OGg4y!*8#X-V~kOZ@b?3^7EBCC-F&toCd4Gt}lwwv{X28 zKXr6;W^rHCu=M>&%je>q&e&P)bD?PL;;y4*YE?o1d*dGX5c+;6{O+d&Dh&rba89Ta zmX`IXhr&r*>C;lqLr{;0fVrcU^n*muBlfaY^L{e4zI$SPiz2KgK7L@0aZ;Y;Ri1a| zPxova%Jgg$&D*HTWu#-x*7M0$rGxO*Yqv;%&>GL?2GH2P)LO!6wTpp~!Q)S7&2J>! zZw$Jsj=|OK^3N;U5O`NGxcV*-*34nqPtT*B<^Npx4j5501WB3=sjfU*dC!%h`JbP? zi--t!!r&$YH6^xKs$N)nsL}xkK{D{@#e)tk<*^#kuc<=j;dchiu=^49arAbX(eSxDg(U+k8a6Gaw%Jb>fqjn4&IJoQ41q9S)cil ztuk5b!0^Jdl#`J$+-Mg2Uw@if4my^1xeD~Zx;Ln>|D)Ib>(}75OY|-GqKg3gT$!dJ zBPA$(aoH-;Hh@8QUo7LO7d?&VD%<$Zt)sd+8<4h!M?}a$c}Vry>AOTcErl=o-dLjW z96>52tUOZZzPvd1sJvj)=dFykE+K`B@5JkWJL5X>+`r=+>$$L%-}Dxc%zLD@mqRnj zJP_;-U9EiYZ>eLlP=<00!S`-?&%SuSMCE_0TPGrPX?PFW+rBK*UX@u*cX0tWrcMlX_AE*jYk7T>| zRd==Do>>p;HHW(1m%i>%|KDaAAaefRw&amAq4B8RuDon+bq5T`mxol5s=5FNf%mq{ z!F9%6bzoE1-8N~!PEAd1t2YeJz6S7q$kF+p5pSh-QT z^qb!tKBl-iAxV=Z`^x&gKZe6l zZ2Lt}dgr9>pUo@TY=t8mc2=z#IGnZZm^p)G?^~UBA3>M}uFlfqzwg~ye;s}zK-#27 zn3d{QLJSin67}TadczPa9U+1olmSX~z4+$L?ooaT5IpKMTYtB z9}(fO$fP>z-~5b;0VrElgT?r437AIdHww(#N2Ku-fr|D+tb5I%$*$)zVS zC`2Zv1KH03+>fXh?*eP-!IB}{SAtkR{R#*wXZ9vzvuna$s|xLn7lP==FVLs1x7R0* zaGzzfjlc*yBCJzRJD6iPCIcs6nre_ne%Z{1I$A4EJul zKG%{#xBOkF#1H3!^aRMc+d0@ZEJ|RDmDZi{@6A)B6|=B_19H?%EeD<~<_)#(f+CDXay8VY z{Fa~F8S66~4x|l5HMLOL{xZ@B+4ec?2*qazPCX{w&R0P6cGor} z*f=C$-y7JEbCiR|1D>D$y2KVKyxXR=qoN#Q^`5#U5%-xDWMGa8L~X~@$tVzNgXan| zt4IBd8!9eo#0vL*DURo$>d_!W2>elF#i)vdfRf2vMY=0NtV{vYs;^B!yZX8r*G4-UmSDdwC5wKpY9$hs|fUo$an_X}4;!9ESL7pW9ipHTJ~B$QVT07Gd6X(j)?Bvzf9d@5_PH-Sb|9b?- zI4@mJI~hnAYJrymh~<*mpQ-6{=84C`$G0Zb(MqQ-kuj-l5~<;GDzLd?gRp%T zryXF|cy(M=$HvDeqpps_piyhOH=bhD%6TQZ4F;3_r;o6I0w1ylElySI zq=v_$y(bXSr?F57v8RB=xFYUJN(DTi?z|eZIc&KRW5xu$6C0w?#CeijiMR(G^(jx( zcat~;hOXWsc#d^v#xclsc(~_g9vc^JHTMlyT#~yb;}YBbsY|rKzzACwCJokLVpXq< zW$N-Jtw;P_CB}*n0i>6Vy_+++0zR~ijKw|rp75*l^Mj9%+;?|(rlxqF>1nFUQq;1_ zhQgs#L;bQ!>Jq-+x1g+`^~A+XtUyvIU(>CsG!@+4_RnCR&E>}+vgUr0cW|350`38d+JN~#U?JWUlj;9)$GxjFIg zU#YoLfsXD%u7qdicoO{JYfXJ809Nhp?!vpP|3$D)8uWVc*$p#-=e&}ss)`7}fAPz&8dLooWJWaUrd?N4=ldnZl@oZQC6Au^V`&$`EhYr7=ak5Anjvdt!+RmU@) zNh>iFlip+yhls9`RUW2H;78+hN@G$%Z4y&Qib^Zyid`zU+p5@HF!qsCD!mB$@b`-` z$E?0bN|HZ}vMH3ZUBZK=(Sz&-@f#X2BKn5C zNy#xTYtF$M5py9i7~2q^wTHSgL=am)dsHh{CvisvRin8}(rngc_B9vYLN5u@4Jar%W=x=2I|OZ3??4N$p}2B0!`8qvPf4_LK9} zre&b&uzzl^J*6BT4&P}3U*cliPe$|)=k88jg0K1Ba2}kGe{Y_gWE40l-|K&h7c^&~ zQRGGPB%tKyXVig!9sEwC^{0X8jE@Vv`&}WZBk7xlJ3@~%Gh&xK5}(z zkt+;^OFhaC9%^2DtS;5qEdc$f5wM=QB?nKD69?m5vS#_{COQj6xCYI{}0fuoUc{W>9N1Rk|*An+-PM#?xSM?<-47va(|lxySKfTKT=Mm&%Y+h0|h& zhLuGolsdm`G)cfRTC-VbuXWuqXEbucsCEh4TSWmQ#iZ*Tq|fALbsLPyMcFCW=$7At?Au$w0<{m$la&F6?u z&<*kM9?Mde`7TN@6sG^=JWH;d7ebLBm*~;%_f{Zy_v?_ogbpyCi}O_t7u7Cf!T$Ukz419E=6hA)Q#UpM~BCG1bv`UCT~y*tk808s_?$FrF;OQ z6P;7Q*22ih$g7)Y_NLFO!bR66&|X5+_onr`lo$}GjZA7KHT6O->b7&Iv>zF1MiK`J zS)pmjgZvY~Kkyq3MZ3WjQMMuu0i&#p-+TqUF!Nx-R#2S%gW#jbE;rlZnZuKlgQv2j ztW`lDfqqUZ`sHId6fP!-igHq6L1m)*>@{$5o7X{Tc#RMCS~q3W(FC^PyQ{g*2prQv zP+l3iwvM3o(HkLbuVnBCh^Nv7J5{#SaAv0ty{K{?srT6dRs&= z%YA5$dFH}qI>!}XXtTF>`UsiW$jH76L z@MT+n{E@@tn!b%NQUx#okBOG}E+8`%tTMzWn5$pPw$RN*IRcBDd=eAdhR=eG9Ces% zski?vA~#^MQ6;FRzX!IcHCoS~mqSmN{u>VpDk9|WOe>jH17}j7PU%sp6dA{JZlc!X z$pTJ7R#qi$A5rqzP|qbYkt70yEk$T+SZt4_1&aq|xpxJ~Ahi`_o&;M>e(RV5aBw4N$#NxqAKe4U;MJEa5A4l#1aZx!Tw1lG#09BXx= zVAb{A^vWuhiYpE#^~EmFf$t~XdJneSs3DCm4#CUId8;4y1Q0c!?^Zm@lmWlqbuAiw z&v0ugJUne^DYUnGr=W@(hyn{<^GYEiM~x3*w6Gy~?kEtuS0nnAv=Lp$k`Gs36+k2u z=1^Vk4?RW&(+@8-&|e#aR|FbR9M)i}AwZDuyIaeMW%SFVNx^zc6dqX|S*W+Keqs~Q z3wMu*o87;hv@rr%uUEbjwJ$-$*Poz3H_=L?pwKMX)oJ09kZ^Nk$P2jJ{X+wN`!%Sq zpr)rLLHQti*Uuk#;&tjipg!1MEq(M=n)U0Wulvz85^>I-Ox&gMsCxD zh&nxzy?B9cq4$U43eCin+&!?k?Y}~cgeGgJ8|)|9B?ZU~T9>LjvH-)vK5$8}5@$JX zGr-AMvg5SILKx$;8c-Irw9x+IMAUb8bK`+s*!WOh^bHWjqWOCcsOXQ;|*UFN0OG2MFKylIkPwvZjY^t%v#zW;1Wa$s<| z+31V?YqfFc(M%OsxNNu;wK(>4fhsgY($$typ5$mNulrA^HEwK@&cx}G;{(CvP&D)_)4iZuCbB!m+5>jA3Le{VJq>?9M}gLWe;PwIz)~i{Za` z^dB^2WP#9#*#89;;S&(l=~OvBHa73@MN<%g5+tTV5lOxy=9IPAe&3xfUeGXtAyrmU z!N>B!l-3n*iNf11EnZyw^=rJ0di`c(ax$-I|C<_jmV-;1_S|eQJNKHD_>bZrx(!C` zMUD7a$F!~&82Ss}YFRbnW6*q%EL(g+>9}WoMOt$J3mz52F0+*?t%|C6sWJ7c+FDDm z_X2Q&`$kU8EgYL#M-T`tXG#(vG|ejpoY+;&M@xAz!Ja?yvY;d=K@b!WjVJJ*O0S+g zQ2lXmVdc8TyyGyZ)#r4?9E^eOvA>A;_L5Dj^sQDVgrHOoY$V}$Oc+x9dj(WjB~?&Yc5x3= zvHu%Z5t#m#0_btA`C@ zTpx@`8;I))w4X*;#!WHEwGZh)0DX$np<-9%7#qB!1(<$jp4vZqWIS*)$BI4#X;oH` z;8b^34qOd}ENKN456Oc8@`mxSATylp>9H%kk?tXyhoo`mmJa*kGo+IxyigcIF<6rh zeA4tAgqmUA5z|tV5)`>%*!nu=FT0)u4q~r$O7t#_{~or6M$Ebp$N4|Yq&EB`XWNkJ zT3rgG%!EBxAi$D*ePMp3-1R)Akx{KBmyn>GitlvMh{>+P4BsNbNHe+ya%S?7JUWFzAGh* zUw?{|XUY0wb_RLUG+;0|Yy)1)1Abf^E3I)CdOL$s;urA-8X;>2&YPfM;SF6I zy(DTa*9r=4%SpG6gtSqI?KC7}#g9p52{l=AY1Nyg zRRezSgPUW7Znu5CZPcwTE}F6+UtOa~6REj?cQ^Y0>dj0%X}Sfapce};t5DTV@B^4m z*k;=}Yvl1nZ4?Jz*wNo1i?ngxY|v}pmB^agH174_M~;6*BP)A=gj0GkH@qF*?;Ie0 zZkRJB0R~1#auXe_E6!2v7hz%QzhYxe|K5M^*vK!mQ?DSXCmKpRi5WCksIsqUh>MJr z;p1B&e_<@8nlYD0OoGF?i=wz-!-S$79DaHC69*4IJ3GUhskbJbt?74T((aA6Z~BpB z<>uxlg+{M8jVjhB?^OhCjSCKGbq*=xN&xL2nlS69p`wD2+nh7hdI18j1Z6LZki4m@ zs6?(3J?WeGdmSF)u<-C$4tvQKaX)Yn9w9>o=#2C*phvhy*(HBa1%OR^(diw`pKyuE zta?pmtsFnr>0Byx6ZNA!MA3)H@%o(99rAocJAkwYn(C;r>vmoYug|)&X>mm~HwRn0 zVn9P3Ik`8D#^cNCdRGpo9`?uI*ItL&Iz99SKWXTwn>=VOs>(_4^bs+zZBQPliT4bN zc|=yPD2@kic`sWxug^N}DRvh1_#B^?Jf9*7o(^Uy_fij4Yqta@4M?MpWlf&%ah%^` ziZCzhjJ2;k{hr5(#udTPC$~DgK8ZiGH}~Iw_WX5@Hp`o9$^R3c2~r^3@Sy9XBtdb5 z9LyFY++YvqQ?=?vsJi)Ex|5Srv44;-kS1TL-}a!^cvwF-!M#a{wFYzbv>U6cqa$Nw zb$rJG;DveO;mxo1WUkFXfQ{?vVx7~z3{&$Kgq#c{y3_MHhlAj-+4}PM82j$=#@OPA zi3TGRdKlfCTSgP-PI^a3Yp)u*oKRSd?XJ|0*kt)+(6!sc8Az$lS_t|EqwgEHcavLu zn+a`lSzx2w-I>K}9n=9Q1F8QR?keg_sjhaE%1&8{H?uCEvsR}qwiQ*ku)@&qSX>6H z+)hwZpRTSH|Lu6$jV}_HT@kO<7YlWZ9qaW0CP`>yL_}zWIg1j{Rq%FaO;%xHKkV1$ z@}i>9@-mV^Kx${P{Kp&&5b|vJfBK%OD*j5J__0{6&kqS&ZE>c?(RZ1VwsY2Vd}lub z9?E~~Dpp!usFwX%c2X?*Cm`!4tGs+!bnDAE*o~vm!hX?jg50hPTYsfi=@!p#pQRKP zhxQRf@aiJ}Vy@EZJHSn)e{c7Ey~-0OlvUV)Eh{tL6iHelLX>1JI^Vy22JsEKI5;;r zky}-G^ogDGL{a(xP9QjY3_qZJ3Y)6(7Ih7ZX{wqDI?x|EpPvUTH96Bf$4~SfJX<8r zAa7a$(LXXYkYR~G;&n>91X%fPCdW*)^0|-^!>Y$j{CXy+_552(ukh7ffi?Y@N@D2E z_B=sAkE0y}n*q_lZ;Bo?M9)5!+}2=aH4js^3}FkJP+T~)SwZsm0-J1y9GwhQqjxpE z3^3)EmsV9^!;#7t{q#b;BMKk&+P^8pckh0pY5vnwdHq&0MAm%C&mi?QL<{@aVx;~040wuDxz18tqP=F0BGvJ;l3!HFA=dxG0pXB6;$!#-IJCx;W+HJWQlw zxQp8SxwJ2!Fzlbj^&4I_+cRQm)~=~ZNiYMQ_+*~C4U4*bhBTZUl?Vh9Na{^AHT* z;-gbLWe)V;8!6V;tL8Ag>*B;zN-d11p;oH~EEP@59`p{ zc}(2Pf{IN@N-!!FLme*0s>BEYS?97}gAD>5=D~6zO!lh`qeNvSv=OM$05i4v2Z!JKZ?-*;TZow3w1x2Ajl7Z7l8% z#csRA$mbZEoR`D&T>O}YQ?8=^=)tuREW1^;vm?Te3QbADP)0?HJXepB#X80QJdOUf zaH8479q(rW)7Tp&($^0K_brRkTuvOum6pm$6=p<^sjv#C2YK8Mc8OH$PfsD5B$xNV zxK%LG)r%r@vpi#v%NjT%|8_BTp2uj!ev5a*s$P=}uGa5a_3y8ExAW5nTG0HTaMc>M zf>6KZ($WHcXP?~5u7U^B%x{*~i;`(L*3!zwd zMyA8@3Ufcf?ib8?%NQnLr&xfM9LI9;*3XbHr5~Lpb9T}TNh8!TuA+^-HHLU_({aX# z_3~=7wnj}R`YOkPv0oiEF={+#3@i#=mzJ2xfTXz~2>SDLyRblcYhO~|R$+8^PTByh z3wOo_p~u&E;0I>m;4tI)M`h1^+#Onf0qUlQ6Ph|98rIZxuv$lJ4kJK@D=aE<-0JQ; ze!P*YmjWMBvQyV_sA^r`_=e9e1n*_<{_mj|uL*Y2b6uB|76So$B1#K5KGH(cE8ZqT)ZbV5JN?Nxcl9M$i4tR(wV3h`2=}E}KT8>mXV#@o9+UwC( z>qB#nhn=;%n4a4W?f(y=Lo(z=W)kK1QlsS0Tg+`hi74*PT8P=_y$&*_T~Vpc)^*js zdM#cDZ$^d?ArR61d-bt>DNY@PkqK16%gJu{xUzre6_F3@2bZQC;{Sf=a(hAo0ShKu z+}Pc3zsG6|;jUM|u3?`LR_txS(X`q})Fypd!fmmM1QMiwoMu)N zyrFYB=DpHGp6S0Eicw4svZ>eR&Jf4?*{%6<;?e-V*!lziEYhuGU&T2CamiSrwd?yS zM~T|wXtITA6Y6(NyK+jP782Ip0dzfmjK(>g(pEAs-bl9DKsvQ`85AvvK)1ZL#llHL zO3ET0!h*1BZa4|_o#!jH{>;c(Rd*eo(%gZoQ#T$7X<6AEKZiZ9vFz)w`VNkG&wa() zQWY21jyTQ-^DqNAW2Z6n)v8r%YkG?{h9nPcj_A@j?gaerP=*c32994ZzO5jzN3!UR+D%E5hSWxurpt5J=7&<1ZS2CdOsNb zUFNxLzr_Sb{a_$yn<$!@O6moMeejz78c#ok$>pnWv-^~KHi z8Q%Pa0WsJa__wOYAUBe4JATG$StafEjJc<*ZP^)htkn#etZyWLs#yM_0t5YQV3g$x zZ~^6>4WrX*wj?B|3=Zk1$x*GW=pZ|reK9Yr$cP6chT0lTB*H=5Cb5us2&@OL&AUVh zZs4=z>3P(TM%P#EUZujx61}h!`XO6W2G9Qf zQkvl;zkC~sM$awD*6im2>2t$hdz7$sljDzs(n$-3DV+|%QMcn)ssh4anF0S`!hM62 zDLGqSBcFa~WQk*b(A;$FnNUDkExR8eAjp+tyIgGoNP#~Fi|M3)DV}d2<#>1<9ENiT z+Qgtq^Zf}9^Zc8px}u~(%B0g-E^oo+Df!FBk0=F4M5nY^#l2y0ZM`Cc_9Pf01j}9Vw!x@`C%@r=H_`(8 zWC6)tI%;N|-qT}JhylX+|!EH))PQ5Z~N$NFA%fKKJdwFt?JuVB3!456o2 zFPA1PKa^ODK^{Po@YlEySwdkPsy*Kor0UFxb$?Nlca2N&ubUN)9&_}MMqg0Wb~1@L z(6vqtg+q1gthi@q28r4*y4s?BoH~Z6I@z7BGV)Yo*T4zZ=oLd*`fD1#Q&CsW{KE#z zGzh%qXoT% z;1dmX3Y$YA12CiAg_p(^- zAbuiOFP`Rs`)gGo!xny}*^wMzA7rq0 zZ6v2)&=GYlj(J*a{>V|I>1IsY3HV=yFoUp{;a>d4LVYKpvm&0anm15vco5`iuB{A5cNsQhwP+_pa_3L9`A^_WCvx+ z4B#m-wxL|U@$;DZ=2EvZCKU#(dZPw4fl;Y;dtzGqBkZpBtRatdjMrm9>bUpd_!k&_ z=qieR&R=qBj~^o0t$^7R{E`o}h@dX5&=*PcKA|1mKs7Ey`nP(I{zRSU1n=`eJ-RP+ z&3RQK+Jnw>!+^=C=>RF$GWG?Oy84*}w!+v&%`)|HNOnvJ7_h16>mVkZ`^~BnX-RB` z*ZJ=Kpmff+OWF=W{O6?x!QJc9o{<1}4Ep(jYkzkJnbp9Bt%@`#60q6MqX>w$)+jp1 zO&wW|y}dykjF%OaN(GpjY;WLB^1{@^f_|MrTCL~vSI^9(Sbr(m2D7l<7X!XBj4v`O zsv-^ zqV|Khi%DFg<6WvQjvNS1Sd_mlfK+Ut4-NyD+6Mc&4dx&L?svl`D-&{A`Za)}J?6r_ z>$eabbhZ_vDdrx{qP~_ECdRNbd`cu{XF>|%jO5J7DYj_47PwSy`$QL8L#IX81D%}) z{m|^(a&|^Jo;kiWiDi$b6E|1EtI_=lqLqyeCsZeTQB&3Sg~R{upzl#9KtwU;{J9)r zZzPNuTRv)1KpOyz1MT@S;3A4yxBx*!9=h@MJXq=7z5(0m&hqc}h2f3VvQ#&Fk?Ra1 zUwMzA%uvQm{2x-=8i2(FKpAR1f29IjK_WxI$OsVS^WYXq>;F4hDg)q6u}wPxtJ1T@ z@|piZxdt^j0ldx!Ai!zWge{v-Ym6V178|3h)$YTES3<;oVD2(4s^Z2)`-7SMJpA8g z@?`$sgE-&TJ`cwMxmmXE<>;DZwT2y%sv$R`O-!t4sa zMkHyx4*Eq-K%@P<#e$A&Copa zQz$N#zBgKer#w)oRxyeAYS^+?QOBO9nRV8wFO-1n&+tFXt-)Wv${yXlt^v6rrJi!o|8W80 zGZUp8mFY}P4K|3AkY)jB*v@-<@Kb~NF_fft4HnwS6hvoT{|rr|MTi8}d~P%n^w-?? zWd%}+7ZH1t?oRn-qQ^)#C2{ntv9MdyJBsdU4Czq)pGZ$65bMDAA6{O*U=U|NWWr`M zu`&g^UTtNf*oz-m7axSUDD-%pC8C9@R_-XR|E!igx*t!RY4KM?95T23)h&dCL;JXw zK=g^k@}T&=#DG19IAJpd7XT=^qe;+Xv9xjTG!yC^13BjlaHJSgQ=P z0N7dAX6%R=+x+t|u=^4|*Rwr9Tfzo=j6=IjPbxaUpqjLi2{6OzUgad^F~DXFmPVzZ zK)8s{;}D`4&y0r>Y%_i?`7sz8hS(ha(5FP*ek9HXf2cltcheB}g^pM)Pft@AiBN6B&1+@r2*Uez{@xyp2_AgH_X$7iR{Gqt zI;A=G!4Hr%jOi3IY2|?xYV}A0bNAJ=55OuBF`M*~nRUWVq$30yu}tNxlLHp-Nl8h$F5o{q zYsBr?pX)SsuR#im+?#-{Rup zwp%Pauyik7%~%0!>ZV!ssD&wM@4YJtiT1bjXr`4Ny28CXeSvLDuU#t>P#c;HBO&cc z9DsL;r56|WA2+F8|53>S>c^TYT+=h&<-ajWM&e3m997M&p^R5Oxfgkg z;(b+RU0F|!oif0avP9_`QA5vhK%x$6?V{^5@aGn3QBR3hFW0OS&>bR2JO0}H(Y(^F zTiGpCr^oAJ=CT>|!j)M4cy-0nwc3@;Rsz zU+4(*Tt8>I<{H0+N!`W|l)V&Hof4oE!Dhp$Z#ARl(Xl!?2huW5T0bPr!y@kPz6}nx z*Sj`bo?MG)gKH%~gH=&LtEl$ch=U1(%)0M>?+HJ+IAYS8m$xNskk7g$as&(I><5PrrNL_dY3s~Z zyoNVA2UWZSb;^8ucIIxv{;JB4DIZTP5r@{1 zfqNiAH{TNl+YrOIf3Dk2JAKQEDpw(xHxll6-}=+jP3C(~pL}`*^{TwzdRK3JRSVYf zOik|WF?Ishg{V==u-cAeJvGgwh|ui&#K*zi7ejV#-pbvVuS=%>6eIK6Rx1OO*mX}t z^UV6o9SW?8d^4=&6JA7pDRo$S0~sn8u8cnF%T>Hb=e&3I3}X9t#HO-^4i85`rc@g* zfu5hv$VZU1z0ezltK+3`tpM0;mD+M}K-JB2^$mH4Cz;7+c7Oj>&(1D;`-_Xplax;l zwY~BbUx>HB@ay|q9jo=Z8=W1O(3RKldDC@8Q7`0~L~u-9Wa0v1cu3n69{BUfsgQcE zY2kIggou{RyMdNge<0**K9g=Wh}`_1&|yYI3-GtEkkbCr3xO0^^DWd_;ON|)9E_Wi zQAbTtR1`coI5^VYX2yV9EFGqwPlF4kdBBwo^AK8S131r)01rwydIzVnc_%Vj;m0>C z9u@B(V6U#k8ArP&Dp3$X?zs+-QX}iC>q4gT@r*b}mCu*DJiiWioSX5K^JXjf2$293 z$1oo6kT&L!6L<1Q)}qEp6b4|vV+AK{h}o3-Y8t(QQy4rqdn?bdt5N_>c%M`uX|k?@ zMy6quNvK0ZOFM8(7=;f~i{iopkoj+MZuSteTzkwR>cT2H4nqY&tEsC@0WgUey>~Il zMpdw~7vtvbD8rB{u1Jxw{6_Pr^#0gsT%}t{T;7yw)<_bZ3t)`NATV7O#~GZW%Q% zCaymu8r1@sS%lkbW)w)dhpkvlM;3dXq#ay)`}^;zqA{~h+!sJN^WAL^`@aX6fQoqR z;qqBngXns=+L=A5yUQh*#w_2sq~f<0LflMT@Gevab`mLNJuW-+7nGjaF*07)1A%At z+9M2>X%zqWSkgy1u>W{Y)JcF0-_EH0RLO)(TW=2$g$fOwT>vRQV(Lw0Q~@s9GYS zR~3pleB`Rbj((G9eZDdloV7^$BBk9?tJVybFmp(7+$V-D8<{t=klVrhZI=hz?yN+o z-_p%3X1f}wEkR%GZQ>z3^B!72#zQ zI?dt<8y!x2fJR)ri5|+? z>O`zeyPCO)TA25>!I&$ep4{I+MZFo;j*x42=U>1P7A;X!siTdu`CJ?^6t38H_tl&G z|Apee34B1J1Y?VeXr2|FCla$20V^HfMzci=T+&N#zn=gf?M2dsVe7B|#N_q^^5tz6 z|Ahc$j5X<7>5_M!a7sXd@_u=PW)ki`T>OAmFcHRYFNtHmFePD&DuhajX{ikAmH;B2kw2JMQ2OKd_Y%3i(6I2Nn8 z5(UjdUpzpnU{nuQH1QDO2IQFyo8XCE_jb4m4T9etDb z66HAZZ?I-IEfsiJ1m%kcKnp&xh?D#`OAY8frDSF2_T>t>#WWajAYOxfzgkdjQI*>u znoR^vqC#0pAsCMoK??$#uzd1?qjM0^2H2k;i1x*K2g#}Qt!=z8Mgv&A_1{x_Wl;m0 z%zofGl?_Ccmpzhefn>KbYOwaLg%OSiR!Eon;qK0{!JhjueRK1Mz<;xX1BvRCi0t6} zWrMK6#^0B~3J=2VA-ku)r0G(EIi$WLrm4X!Wju7ht5(+vKcW0ffXv~wW1(?wLbUk2 zHh}7s9@b^lEF$Y+YTE0e%HXeN$a-LntRBBUn2(=Z`C;iL9TOeIgz+xn6o3zXTRZYu9aT zPH~AFA!mX$RYD;K>lXzv&n#UEZDnK-uw`ZB^oWwHG2*M+e4Z_dFM`vrR4a`ouX}9Z zHjNdfXS!o_wlwPlGIiE(w6s|c(&n7yLJ&Lfj(Mo7R;?KeOH0!_J2#G9Vefr;QJUdz zTq}3~(v#%duDgAl_A?5zh+?hx*!_4(G-#xvh0YyJ2U z}|Ybr2ZKmVG<(d*fsJ{El@R^M;yQ{A~F=fS=;<3Nz&QNXr05#U3#- zLXiQMgVQt=;K4_a(wq&248X3wuWr~(dQ#HT@W3k% zCz8GzVD2$rU;OF1wfPpi{RGt4^O%Mg+RNhp9aV1NN|{?fZXkZI-~`1O-RJt|6_ zZb|Bhj*&6?^zpptM{i$j3Ue$z=vQG!UT&t=qd3D?)B8qEAv9uZk?#zeNy_nc@9*z` z{D0S}1&LPEwg$5|F^8a6+r7$(T#$SCv2A;MJB`0wdMp~7<0luF2BVCkLyI>;CtZK| z0dt5M^kZXSFa%~UCz^gIzEd&GYg-dEOkcyEqa3*Y{`4bwmOGZz0p}ksSz2BATi6J97~oB*LdXjUjvnaU zRZPp$<`T@u(kN>eKImsYCDnM2(C!?Hu`JPcC+d>~$xXTK3Qv z@yNC$npS2lNJxbJx5^TcjIY;J+#D(=>9@&(d&YwXKeBUZR?e^c85i9E_^dvaAHV6+1TW~+kK@-Q@z_6t8aEO~$5*=H>D~>h-)c4| zTxU;x9=Y8HM_XB3=xUR7p{=DQo(A*IoC8GeP*bYJWU-x6(bQo*>38!I?Szvk6G8^SLSb!{{}CAAcaL4u z5>stLAX9w0=$UJbma2&YShte3!Z~Er%Yjw0_26J>{qnz?5yfpH{GG#r-e4*(;MlLN z_FARRvRX7?5AJ1=!xrU3*UXPD6exiy042b)kl`CD$+6vKnVU}H;ON2L9-DwI_u8^@ z?3_;XYxWn?j9I@_K!66wR}~J^^6YJH9?E$;LfbaKdtD$eJSHdqMG`&~$?cG-YrL`h ze7l{(GZ22e1-IWScu%je@-XA_UwI)ZeA^?eUb)BO63pmT?EFyO__s7!D;ztZ=^JkN zdBc@r_JsGg+oklFO3!n5l3J^9vF$B8wR62_}Jn;LA~rY2F|s?tBXN(*YK8rIQ4{)YWErUdeXls;0I&ytjYAU2}3OW_^5Y1 zIYH>Vs}U(DwBqMUhG^IsL+;=kijMK*{oBm$Jm-17=ke(WW&N88GQHcH{7@_X^h2ua z&4cEFbK0}B9;n~$Z$r{is^??%$=Ni%Da z_}+a1Y;cVkbCQz*GiQ2}=|9aoFNcdGFl$Nq0(U{AI$NPSEfT%JKB`y5-`QDpo*SXp zuEyYqLSs7l=xXor6*(G&w6KxN$8S}YJvJ2;rIsu$9eR;I>1BqqFBEqL>Y2HivJy0H+g1LM=8&n zcIQKZ3gV{+!kQz0Wd-+{-L)@1s!oBkJ0&Z@W|L_+R8LsBu|C;=ptP8>)tn?8 zra}BIv;srxxw7?J%ipa5bS^))?67lhsAn*itx&;SoSH+~KOA=YOVcyHwtZfoIg2YT zF=U@zCR7OOXak9|;;w-#4|0&N$0X>N`3fj=2;5==e8>R$I?(=-C(A<~?DFOSc1n0Z zWp&zxdEop0-5mmIovk3ln}sE0s@@ep+r%apVTh%rR_Nwsj+<5#b}M=jPA3A62Rpi0 zB1#yuj#}*MIoH~?R7Ho(qtG1$t^^pFOn2sj&d;%ZwzUz(4TFLmvrldP#jHtIBdRA% zo2w(%wk_NLC{@+_7Bf0(!|_>q25#_iPa{8*u(m6-zKw=i*I>I8FFZ=z2fw9FO-}aM zll1;LWycgyv2m#HHsm-otm>?(%rZX`Cz^d2)z4IHn9I=E9O|_~hN4ynq*Z;a_>TQ0 z33rX$Yn|MGND6%ob#=p61t+(*jOI_Pn>udZKeoe3BFmXL-+_7&P!qjrxX`WWJ0`us zI%!Ap7QEW-aFtrkC**36eEfjwam229dqa7;{9z<`up8^x)8gIoc*O4GbOg^Ncxgen zk0G$|WW#j!gm;+ZAMhIc@msO@_X!sNeFl89=kmiAUA5m0ZeOtYQ+a3i<)&}Ol)B}% zT_WMf2%Sc!C;985fA;bGznRD9#b@E%9cBm6f{l&VO$soJ*Sy!P`P`F~eNM3ZoFe_Z zeR6#pL$vXD4}R6oqWPA@^c2fAsv_Xwd{}o-?0-14sUu(aM!hgR=2Le;P*}r1Uc(&Y zFbx7E3?`*bKz3nxAFFBW)Zy;moOj#ldLYp1KOb2jTvDUL_2q{(Fv?)X0YPtm?_Sn6 zHhnssEiLI$OtW9Ku>h!oJsYW89wkM@<%?o|X6BKt*|!!MS1EH$TTHvcvWx;9h60r$ zKCJjUW>+^S2ElAYMty9kj56dnN&MKd1p}Uj7;BIKcgiz{?E&XIAP)Lh!FHo^JZT3f%tNtB-^jYct1$D=Q3Pa0Hq*eDAB=3Dl4{)(9Ip8M1?)CQvS*xNZ%;=zXziL;+5fSU-05 zCh}9^R#EIDf7R0}(ofxvJ%6&lVrdVv9rIWgiJ9chikLV>30vpX z1$)jeMAChWP7R%|bF`FNqR6d$cqlfx7i`$F;haUyEta|To-Oe_hBn|1bwM?Ij(;S2 zV!T!eq$^9~-$}zs8L$xnjS_pM&vXnp3iXPr)v}b{qPzR_Q3SsVj~q?o z;}@$HPgIWoa|3kBs6M7inK^p-y7~2f%$T+ zTbQ344rICm#ViQIXnKExv=w5(soWMe@QrxYFaz@obMNToCr@UmmK*3i)FysA*!|^a z!%lFiEfU~(%YJp%FfYgxm5M4bT5h&~Fi`Yg!yx{jeIhUs$7g2p3r?K7%`Gepth;Xt z3Z7qW_qhNj09{k#<7V5vp}=gAGyh;cDm*@8C!dB>ovU+dmaCfB@w&XGDm>(m=Z zvS!lawMu|uYvxi&3n$F*U9#okf~jwG0plDWeh&vZ#Jym3LO(iMfXiR#lpzH##=0)( zb>65&^|%y6oo8SsrV)rbg4DK&AA zkoSX3Rv`}ks5~+{2&&(HKRA(`6;AT`^RYRPCyD|Gd2Nq164tQ9qB$Wi-Z5is)rbw8 zZ?Id9k>S)jkXINbY2Q9P5Qof$l!cKMT4zIzxZN#QtPhfrGJf`|x9jQZ?+?EYrfj8JIk5e50%v zmBr_kR8=HjA&C|Os+DGg*1st+Xly0-ZFd7}gGQEy-bqL{kVtZiBQ$V-h? zn{&p0jD$iQc#$RpCEH5L|3}n0hgJH;?LKqDWMi^xvN27zC)>8&WZSm6vpLzeYvN>{ z=l8znTxb7X*RFPJJ!^gM&wbziM-!4W56H%}H41mi2Xb%Ke({@J$zJl^ajE3$hn{+1rZnt%Q)j(F$ zuZm!)iKN_Id$>uTvP%hK%MhB7Mp!9+(DRIjGmE2q5v5GbQLGYh{@mR;%lm;Mu-X$+ z@MHdU>z<648Oh<9v|B847bU4*mnJ0OGFnkVx<^4hv96iOR`nDWVSv0g>R|aq%bPis zQn^oWO-v5I=6W?fbZLn5i5$%QDs#L)aRzb^(cBl-x9ovE$H3~ei#?KJ=-T{OwGml{ z`=WhJ8`lnHq8a3NRaZ*=cGJIg>BJk?&c4{5chqTHi@sg?UOoXKy9*TV)*HEsNk-ic z6J!(y_ef$l-GS+8?^M_f#zS6{X{Y5J_BZ<}Pk~lDM!fBIL5{fyYG@SVjpn%8l8=y0 z6oyQ2%!rH?Zfd_h@`DcKEuN zSibHlsT0^E=40!5$5+<0)80iPc%GG);s8_|KY#Y^ts{_!dU|rwYt7;G`Thu5XE9F+ zyh>7Up1sp1O*?h%!fbX27Pp7PTXcUD?7PcK78RMq?bnAS|34N$OQWyqR-0aIzQX{_ z_9NcNdi%J@^3X7%=q_XX=lW$VPF>Cr?z7Qds}jwW{QQJK3>{;6KllbfME>WWF*N+I zxi%p#4i$D|FGBh!AhHU)u38zMm0(RFSyelJ;tG)!JNgI^18KX89af?UyCHa0Y-pG0 zb|SjJ)Hrl%W^bZ*MchkyIMjlP% z@BwiMojKf>1Z(n$pr2`nFZ0`ffrkUZ!40>#?oO-jMl7w=NWa5_l}#Jvc<;mC zWl}BLHmzmZFZ(GvLA^A$!=4|9A*{z*fWv}%M}}%R{2>ananS(NP+|y2P4Q|Qa!TbI z%Jy{;^HGtzG~y0|&gj8ltqNorXd{Id%MZtuIfPJ=ymajRU!upbH3w{;X|#B-(M-Y# zQsstu_M)6?l2KLm;vJazZojPzl~H^xVp)B)w&Yi+V++UsWJ+TE64z zU9BXHhZji#EyItk#??ATD_J(WzY_?M4#rdjsOIO<&2Cn|K^)#ICytN;_PN!UjYSw_ znp(Z4OG`rh;7`vzV^|c#-d2?(D045jBY_15%BFE3GvMK|?|63GR2-yGd$2a~ zQQ8FL<>6`HDDAxC2RxrQ#IpJ=BHi6#H{R!AR#rzhbkeB?G}`;Ri9+_~AcO+NkDB+P zmG-1;UA>uK?E&d3^f@ClGqC${^c+QfPvGlW2C-z3C6|IawdCVF;LnxBlEL2 z|MOlC;r4m8iG+0c4A(da$a9F}@I zq?glD_dkqLeud2IGL&*#yn8-21DldE>dw*873ak6E41Ivy|{p|M?`pikB;<^AA6nA zzK%-f``zcq{KV@zge}3E$Z7lI^YBfr(x+fs75|$bIlo8T$W-_`OaM`@4N z?{ADD5ADu>iyj+X57HSQ_R#%0MuIKdx>Hqlwq$h5b*h=p$Shp(Qo^gp9_=^BQQO*s zK8JSp*QH2-0g1;yE^|IDUWm?3H!-n(5&C-OYD!NkS3aAsyQK-bM9wYWN;C58$5w5& zr2A!Jk6@B1{R`0IQpv-0(TlhBFp8NSw$ccy3PV&-i%h zZp-YfA~F#l7yq=(vxCc(*)j{tQU)F^!uR?#DhJ-*Cl^gdas^;7j|lIA*#cP~*4y3L08Wj?fM&Ze z4A3HbN=sv5)JWn~^Rh@$xEPgy$w+n4`giCB;KIRGtC@>dZ5AG}7a}VRpra6HFC;v_ z{fF2}#TomOf_14^M^d&i&(49xMUyvM?y3T5GsCbHW7*p@5HZVKPTlO-yvMuvhl7Ww zrLHav;AWKZ2=Q%`vNlLr)=o4m-k+bLix#!}+(me7x)LFFVB#`hFW=)TZg`8DdBNI4 z0vn6YR^ZZ;?N8_X=3y~mysFvjNCqEg-<3bNdtlL~AS#Iy@PB}eHo$8<)3}H{w}5Mh zAKl$$;6EaG+p8GtJac4Y&7g52;t-~f-?)Obxi7x@%-j2@Ss@}rC&In#asm>JsSv$t zseduFFXp^XRv*kXoUye!wChf{`*?ZXxAw?s$CbfxT-;YYC%|JaR4@+{_vdG85zu0z zf#uPZn$4MDF6Lxj3VBP}I&gjy3%Y)lCh3+9qC` zxA`pgh*z?VBN8lw>j?+RoPpsn7v2?0qwA$V4^FlCg)BbDrW9&Dq(V@8v}8U$vU=xj z2I+wd3Y+mfp_h$8Lk7i}Ld+r1cct8o>R=ImSsJ7RwzW``O9U$uCDIO~!Wc5t4?RT7 zloi-z3g4T$)M7EJpQSp}01fv?9pb7K4D_2D9z%U`Zlx`&B%aND zO;UAkdUPzq!v`7mDI%o9sETk&MA#`F!cL5*O7a}A!2oSgw?~->D9)m!6mYV-enmka z@gnB=XR)eD6?{q@2^#W%YZIJE{%2F+$`(L90#jYqyh8I=?e>d7YUSC@i>`8(Fg*s$ zVPd(E@r4x?x`#zH?Se;Mnc;d>#^961^jba%}x<#-)tq>*uEPlTqGH^?2_sWQ+QUuf*P% z>e!-t`f<)v!x!EEDOX(7=?{dI`+cl4BQk1B$p+*;AoUzPFug|<5nt|3)~X4=TD=|D zzP29pX=%{T*%mT6&2QMny@ZPSI!UfMxA`uk`V80xcZ>;W`Z`fy_k41<@V%NGVVTW5 ztXQUex{}KG+~TOKJ#*jqx!sm$J~+;cXFh{Gf~=okVbi9#GCh7`{eE~0d9`ax9X{u* z+YcQtK|`YAeoIuX^4^De=zf*0*ke@qN^|L1`h%(a>6_3>oEFe0&}5W}VOv=Sr*VQP zkHE>w#x~d=f(Q_;`#|_|T9ZW6n6RdNR2=&;{Sj7VUnhK#DYjy=4%_{f_-FoP6Qx?h zX@dbVr-4pgSXKaKj0?*C?Gtn9fr66q$X{ZsuaaZAlY!4B#-k_#$~+-IEt(!zaF`gy^)KGIJYR99%Lgr4pv99sLoIl{ zgJbd?C|Tmu)Fw7qkK%~8dG{j}fFwzvW_ZGs)#+%0dvP)x(5###m`00B0PCAEV6&ZugnfulNr{=~Hia`LS1s#CT^8i!%{)89TZAh$f6=Jy0tgxa*PpNX_Mba* zVzwz^YPI^U2f{md+uZDA6wT~g-jJg9bDY>DqSB^-=1xSnXh-e6(L^p z0-8Hgr@vd2oU7tT2%&Zw`}%}=czH|gUKW<7D1bnFejd_3L9y&>S&A@WKRGvO7J4m>t+a^i4Ccv_^o;TJxy=(`3a(` zv>Xh7{>e-;7eG?{0%Xb%fPuXD zOj#OkeZFnntJ87LS@meXqjnEe5{19kJ2SJ+-KR=b#vbC~oT$HlP=t03(5TaDExPna z#vtvS%>7<00=#Pf<@G@1DOm=9d7lOpqA3TTOm#lLeg4gM^Tt1XAK6X_tq^Dikey=I#~8k8f<0vIuL<|m_~e{FEcjRJ zczoe~gxiKJS{L1bDJbgQ?7V6tJTTQm5Rz(&Ms%vE$0ft9<36qD+2F)>?_`q9s#4{` z`eXJpPMX~KirYpiu*7Fkla9>`<)KpDqc4mwGqk9!(S9=ZuDSZZH zJvP1lPVV+QEdqf)?j1D}b6y9pwg6C(jgwPRmvLhOmEN8~3JSe=U2d!A?cM5BFBl!7 zd|K;s@7T}ACVHf~OrIi_Pt}Php~sJbQCvw#C-NZI$MW6G*tp%6d{L{pnVl%Nwy)Dq z@s`DR)_Ct{B78z3DO2oXSAU!Nq~LO^K1eGuk^P?7T)R4<=rw7PM@Ty>(;DvRU7CW3 zxcde6b6Ajpfxpa0r29(pl{4LNbYkLmCHLMQmo*ceuST!@9_8|}R=lVsq3I5=lmv}o z6yiHmByZX-H@)8ncNZn(dimVv#>a;b&EQ8)cIWp(jRzw??e2Z_nVFBpCE0=gi;5~ z)$eGu8P%@i49``d_5_QU1@irGcqz792sG?+u}Q# z%oO)*zs`U9&+oXh5;lM8{EGoUS`27&>Ule4!d!QLSgg01Mh&4mN~}f*;6CBIW_f*? zPxsm*_$~vZpVS?r8#Pv*R;XWA_`AzRE+S=;f>jA@qlEyE)UPjmLMFzzvnS_|kJ>HP zG#PJuZo5r#(}-as}eR-0m&3tjKEooI*Yc- z)W(Da{7%ZG#(=Hs<8i}Du(jcr{V(gk?T6FD;fYra#)=MhOhN1ARaN8w*08r{D74yz z)Q@ay5K>$sKi+ro@1z8#TW1==;c|xckMfwTY=uJX&$=lJO|UeV$w`8k*hl{j(enFR zEcS9v`{aa#z)f2>9Tn~^f<@CwT1o(FSU%D4vwYy>QN5~1W#R~*t@jLynalWD-d6GK z_2mqgn2sMd;NzzAHUm7?DUO9Bdbz_f-xu;=G9=jfUhJ7+xE=b@ZHSw(z{0hv!$dtNd$KGS zNct3Tefdq~eW6z>TXps?_GfmT%icS&an<_KS7d6*BYto!tBI+cHW&o<1yCc*Je7Gn zG8*>T$DTj3A^dl1U8_REOqe;4b*_X)@cv*YD{%BAEeuLz@ce!*YLEw87xN;aMT+pf z^z^Veca%|dWg>K!LPR~Ntt@QPv8(;s#}TOruAOAHfG|w0Hb_`xuKCTh(L*YRe`flZ z>{gAMkLHx6;bbnX8T*W&fa(IUgn)QJ@Ze0syNIiK9;~^?T9<;^+!Y1Aga^Ct>0#mF z#m&t_c6CMH-`B=jD{f(aE zv13O4*y~-9Ze@+cBjvT8(~VuvC9GFR>FXWgtN^h1<21nNE}fY0&C!O@@@{@e5x5kk zMUxNWhsCn%<2!mn*s+}2>ieuaC6#hZGUL1VIDWa^*k*lux5lD)N6yK~5mr_%v`q3L zxjlp{J-TLBjgOIf9~mA-!^a>0jYJH!QKPBXO|V45yu&ba0+=8}=L}?nX?%vHUg-Sn zw3VHnG9xs^QM)0->SMNEP((Ge!XUy`@6G5%S1#@f#VtlhckI3SI*g2OXQef3SZ44txmz9jIF! zHI>iwD(5vxe8xsZ#w@P;V6T>o1=|Eb|1A>HEi$Qr7d>?x`+xcR;GF&dCD3BM3X}@| z9#5aN=1^8r>IXt1R_Y8OVS>Oz2X;MuU+zw|eeM?{F1Xt(R+Vh>oQDYJqWtIO#=CVE z9(lpZPMuN|6JWAo0hfR&xO60%!X2%>X8Cq~Z2g`I1{FROENDq3C5OwVe?vd`=#P!F zNvd)RyToS8d(<>zDfuECSN+meo~1L^xM?YK`cM3Pmn)78H0=5!W+Jm`(iYWNRouD!(Dy9bhm`^&$?*E*4KO~_Tz&C!|&}&mEkm>W8Hnq}{h%HZ366e!eZ|4Un`7@*w4nb@82^R4piY)< z8Nq)-5p_51>n_|T^S8Czdp4+M`!i4`7ED=S9$;|pDV?K42i z^MU0ejPpsjZ71vqajIB*?q7rGYPN-Izp5)OEaeRUy0s-lciJw6n#_WSxAho>M%aw- zxrgCz(cFUcHPL{z+U3iyyz}0JM|~T#tP^jat;jlDm@8zbtuym2da$kX;>6`--^=py ztGe~Bno5MZBdf}RHH5~g&>%nbkB1h*OpbmE;{Nu3d}Lz9YjA$eovvhzLZ7>%~m7&$R%SW&o>QGpuqY+BG`u$yZ9?83vGPfd5dv zs$!#SlDPb5dIYC_N@{JdW%G9~^Lb3JTQmAj!XPO|tD&Jrm*^DC*IbTju%JGF;DEGv zII*k&h0ajHX;1z@OuHjtLx1Q05r~UuH=`#eR${vxn)H$sI63zbvunOWrRk1Xjn%hGQg77&_Z!) zEyrIkLl5d3TL}w_dZtTDv@~vVLBY)aMW36?AFp%X+wf_GhlbT?zD6AiTGY?#NGgDW z+%c{*z)lWgrOr*PfGdt}xiVU>=fa}To|2g4K*p8UVa^g4EjNmbDZFQMxzoqzjL*^; zt-{3}{4EKpGggAw0E;2y9j?*oNMkXA0fy5Nmo}&{8~q5ug$kmacN~oHua!iil}n~ zTV()TXt={Zvy0bOet-HGvky4kca|^1a;?qfqbzX6jg(A}hh;67q}1)oPwT0?YeHmy zeIW|=7GBS}zNGS1ZHX=V8Jvsfj34aJ>QwUuFj@Y~uDd0@Kjz#-uE+jy{>r@1xV)Dz zD2&js7VdUgQr$Mf|4YCfsvv>n@XH^>3et~p<5JMYcq> zqFfElPp&f`1HJb5K`Z8uKrtzV;zl6Vqq3nPq^P7MAuUZ*T)e~f!io@4uP!~|jsWqL z+|AOmf=)?&n)=tZ^DR7#dlpnH(qsP$Di@|9u`t)P+l5;$`kMp0)fyc4;f&@kz8d}+ z#y8gFZ*^KAA>%AFW6Nc5(qSzt!n|r*Equ{TeyjT<>ym@P5{&`M-g2M6FR}13?uLFo z_slbSAD((7pe`+Y9?V_gYL`2rz=KtYzspYnJ4vZrvOYe_2=wjn6(4NRZENg1I6u^b2+poDAAPwcA=Q)@u+SKUue7~x^N8h&5d_f-A!rR4j z|7n7m#D^ecFwRacel_#ZZE}k_R1Sl0@ocllv~g7JM`MpoYerV=6tA{3l`3*tS0bKN zq102bp0$N+^%1D9NjMw`Uh54YU)q720tfBj3QQ-8;~Gy8Qwv3~*5nt&!9FB3H0eNm z0)0wMUM-@;<|aoi7p^}(tWCu`tS12sFV>d!5`7Btrm)s^)i3$fW}&H{nt446!Xsdn zYT3Jv_y3j;$1|Ij{vy68LlAehr9dlNIXJ)%47dUwX_x4hJ9aG1tcL|QOgXFk*3;os z;1DvBk44S&r8R^d69Lk81k~^UzjqViJ{z!DzFWAqwzh+#qxO_v)oK7{)N2FUgb@Pr zQ~#TWji)f|H_gi_hpdC)TotqzWYqtnViBZU>)Nm={z%mMGNk~sk=0`Kx9TsMS0DUA zIvERB^}^N4!1cr-W3P>sGFoIR2AUmMmMfl{pNM=7KwA*+3~Nxqwk&>SFAbXw5)aF9 zLu*V3X6Fave8ktco)OVeMKTH*Pfsn*=)qfZpk?o!Jauj`7=ZDl@>Rf#9+v$7n*_|p z9aL1HgEFKGEE!yNV-{C=nYwXdkH1EpttIM)Mp()-M`rZXllvE#AjazixHcV~782t+ zvL_T^U)b`a&gZb`+JjbhFyu}Pf7iEsfN2k*6;RV{95a5I0Ql;4tm5TvQV8VJQ(R|P zP3P>DWxP$ej{w`P;WjsVwbg1_NhJlF0c8=<Yfd!XJt?j zi(K0Eqy{yRh)(#mpgU!|aK&Y8RM@fr`mynr%q<~XQQ|%x+0v4;ohoi|;pS^qr}OP? z`Z(!!rgS8F1$htE`Ii4LY)Q+C64PzJ{8}tSV|{%|#>675O4`NT%da2Ar|1ROa`AnZ znOFYFwh}euo^eU$_?S!Z>g?=hX-i}?Sm&-*jhwAOdqCwA_$M#&1_|u>Yt$6LJ1|*1QfxxPNuVxsl!VMq@m4eY@Syn|pc-r;Pxs{qelf%e z1O|4v5Luo_TSiWtTD_T zS#Y9JF|T6IA1LZCrf6|4Lpu|FYAeZ~y>KprhCm|yY`bmkex9}aqnSCm<8u;9H&-Y* zAyHTT_1hu`gOBxFvHF*Y{oAm){!b>%=B36ja#F|S^Gla`rPIPv3Gq;k0q#EtTZ*ih zIX-h(wDfaf19}xT{W-gKI4BsjC`G4HkdUA+n5mLEXVfZ${6Rvy9Cq(PU_3xj&%?z! z;t67kdnLCPHNgHoI6Q1v?|gzF5ZICd8L-vwuceWT z83GR4*D~mx36f-+OU}q@^XI?Z2-nkJNNskV_K$ zH=g)rGzD>FoQ_jZU?@Kc2Q7V^h`xCxxHHVP$-Z88$*~hQYPdW14UO{X7vDE2FJ9aT zIZ_%%v;lJ_aoR@~wyrFXbc0?7diip2TQDG^%6hE{UT7AWJpjLpK{-v5|N3cZ?&XUX z9&W)sY(-98@`kKzR#*ltC;LsoPiAZ)k=>G`YSS(w*&kn5pXN&_+l`E#(l=|k&j!|A zXNq(=Yww?+VhW?c(Bf{S`^jKz+xHib&UK?y#S+=yoxd`CP^@wV8R34e7h_b7>$YXY(kFYl?ib7{D$oEQ2idLFi}mMEF!v&K0# zkxM@`?X9dfXj(4* zk*O3nk8NIPPUsaBbVnwT!?GuT&cZ~Lw-q=0KyX2ZF22OT-7k|eeX>nUXs}0XhNMkD z5gZ;LT=nJhXtwk&Z#fAPnFkhLx%)+P_EtNPIZwIziAjTVj%U_g%W~D>!AzjO`bgcv z(lGGLc)x4%JVY@IVQ@Kzq{)k)3|`BRncf zXitXT+qgt>N5nKIU)oq&I(yNfj$J}-u8jA7mnWN2w02vnG6Y^Cdv!oCC4t(})I+(#;aq^rQB*aq5(3`%AT z<;N~PrR8eFAs|K@G$WrN;6E!j_Q<(;ifc!#lQ1&o6cnU0KAJUuK*obIf*f$?t+o{c zw}5v(`TMu1x%ubgHqBPnQs62IvBY$EcTKSI??}DDLRAy#$HzbTMID1QxN8gD|CI=Il@u`&OqY zYGn+?8%fdoX8*yy>iz@?MQ2W=?4YQhlyO?xQi>VyL5)mcy+{OI&DOQnl#atnSn{#r zcVFWmYzwPl%LSH(cFNGBX332w^NOfh2^8^`$UPu8z<}n9dJXz2?KZ~*FZ|&D86?cB z0L~G7`dPAeCE2~$;jAp}R7_9meWiP6Dw~ zRXx3h7$pn)-bEOsWhPmfgpKuC)X%ygBcvj1kqM}iQzR9yS7GK-55{?j=q_KBCaulu zbhsFg`4X=@@osz62xG;(=Gq_+9`D`hoN?H#pxMHl@g}YcNpR5T2P(qUEz(yuo8TlF zjiPIxUo=?FjksHW@L4o7%EvzR0^Nvm-Fi3Wj*TJK1G;NjCJOHmn8^$ZCopH)EJgKd zVlT+^UQZM-ULo(z%a%vx@(|?NMJp}Rz+!F;q**t*Nyx&(O2$OR=RX5gW-wVqb0tGC zTB5HF?6att=|Brf76fE`gpYF(cI?Qwj5gf$jI;b)QO!+Vq78`xnkFGLNYoSWvJMcx z-?}O3$(ymC8W#-glCZE?{K*^99~P?6&t6b#gl4)hV<^x=ao_zOp|yItc| z9hg*rpS{{8!mgcO9Uh#JZeVKIRLg}wcth$7Z1`$NFpk1VEAv)&o?vs!&l4ttj2$q< znYVhkQjRuFQ2$d{%UUr@VU0;@179+=`CRp!|osax#MIRx(z1Ya3x zX|t`)=es*NY}Y`Sj6_g1@XdLg{JY{7pMW3>0L2})Gl649z}4D&T=A2-GUZ~ADw@eY zr{y#Xp1YpUi*d+KM|d7TwQ#ob#ZT$~P8TvEY}T5>Co?(aH3e+e*#4^^_Cvs=vHG8( zz-m=mZb*M|Q(gbd!XcvlzhdScEH#Zk8B)EnNp~YYWjo*OW(()S59H@%WyfY2lWZ+_ zh+-86*`<8Nd>m{75Uj$7rGh zEA`iCcdsD*f~{9;8~X&F=HxpcUyr0`HX#RewwBQso4#UgLWpmNU<#sVnaaR!PSZK`P4^6}YX4`B(-k*^wX{NCm(@d!rX0bfz6!&Kb$z2ikwO(QGIP6>l zYzlsh8sabS)q?t(llm^zP)I!*3!Rs55th-Sh!A~MUq;VKEncr5 zi^)D};m!vmezS;S4FB5y+H8alIfEkYTeX%W=%0zf!JawU-d^zx8EygHC35EG(n}L_@v{!(X&w4R*(ld1=Tkt(RDkX@~AZyh2M+VEitp!=f*oht2#(QSiR+h zX!vKrVbo!Ab1;?95Ho9T{!U*S#zT7KTb1zt!p``h?lt5&+3nQf$-tn9SL@sSPC~PB zY4Ro)a?;ekt(sK$aC+L|q2{qG5X`(@B}_epInq7{^{>jy+m_y<^t%fAmq;U$l?(73 z{VoOnwzm^(*9Ha(HmAE8(Jiz&=$L8AKo|+SbOA|jm=<0zfAbck)>Dudd3m%jA1x@M zi9zJKbf`Anh1=eTZfC`Fr@4ZtwbOzZ!0by^_=znw?Pi%buhNPeV7Ee-q*$@Xj#w}F zj0445eud(Eh;ofZdm;r@bAW8+DeQN6NZ08*MeW2V18`B8w zPxYLi27}CYdhFS+N7e`Xyi(rRxCX#VC9rpTxY|KkevgA)z9<#6Aj1B*v&iXmji>vi zph)KRv`91l>~SAbb?TiSNh$Cf_VGP=z2=jm*48d$!^Hbvcj@!RA;ln=5$~0u@G~R< z4my6g>9ZZm^{fpm%Xhg+Cv~TLyCr3xiGBqcqR6R^^lg4m$U_=HyL{pF{nPyU$d?%t z9oN0{?c-{U>S?zCs*l97Gvv|Ng&!pNu2<24RFrFv%*l64?v|Aj00KGi(SB)_jpwl2 znn+>L!of#>c>2|7>Tp_|YRK&E>N*B&K}%*jb0}5Wyl!*6H%1DT35kjCzxVnP&fRBJ zAZ@=Dk;Pg<`H(O^>(ppcqBg%>e@V{FV5?xkP{^!3k>cN6fGGb}{wV|&u-FCU7_PRG zFv+_RHrwFPU*nih77V^CEU5JV+;b1Rso&h(Y~Q#zv77wxx6OA}p`*_d*3+xK{A!W! zsFK)%)F<8rvtM=;>n$AXxT7HX-_v&bgC}jDFL!2d@L}maE^fEYx{SEH3>l$~+(ir$ z2S0FB#fix_B;4&=E?!RmcYlRUd-lk)?KzTS+ zrh0ndHo2XDp!B$Zd6AU%Qf9FV2aia4YFze$Nbw67!}zC!P$iLuW9Z`}nX=fq>6{f& z?}2sUvhE*6wLsFqgafRU99Mx;Q@ZMV%r7pBGxpA@hWJGOnbhY3b!x(UhO+wjOZ;&+ z?4!?Eh`b>Z@_xG+3R$T|HI`)iVwNLP7Usl{P^d!oc1rO~y_1>aSy*P=?9dP`<%_U6 z>!eBk@!ovBKFXrZy?V^dIki443saWR(DS%>c#b+9w=T9z-}ti@y*F{dPtLYTVt#sh z!bC?SwFj~Tz`&Piu|^Z)@)m41yWb5~nChB{(KL97Tj`_{|76ITlXP z`s)o;TpHEQ5K)RE_+;h`2r9N))^DiRHV{n$|GW*-*>o|2SFR^Ql8(jVvTd`z zfWR?w&V48KVXa?q5BOz0YM|GM$h@|e>ygrN>(X~mddgP#FK=#d(a9vjD)-)XV%t-6 z7H;T}>(d>ETeI)MI#t}+H^(}BkdvuzG%)(Kx;7UN>@(LquTO===C+>-@b6Sa#P*y} zxvsJPx|f050SA8ox8Dq~PU9o8^q0=F75nfVnStO5p_Ri7eq~T*yzD+Mo&L^ zY>JrBp4pP_gDdwZi0-0`6T(Vb%dO7uz}Os!W?UMwkfUYT|4MyV61twRgamwUk}@*4 z_L}qOkCAH}7_TUhw&-}ZM*${O^@lHHRbAi0`%0quoS%pIl<)YOnRG-GtcHNq7{&+A zNq1hWH+tx@d^=SsSa33W)%JHoQ0dK)qDN5KCTW=KZY8z#j+ld|62YUu2*SS6ZkLM6 zH+>Sjb9md&^?N+8@5o_l&2AD1^skbFa@ciiC_MF-hxhUTeJlhs>Q|F*v=F_L$KA2q zXo^AxuHSxNcJcWQEI;p8sh9h{v3*0~o1mf7)!)k9-f`2DJDh1$|FI#H} zu;LIAl{7a~5{f3kV3 zHrTb2$t{w@ZZr)h)pQVgx(UCek{IzsS=p!JHbW>h{FOpb>cFWZDC}nhPfl>u-}Sg0 zsr|r#F*1-jOw|TX)wsPc4!Y^> zgooAhjF2coSS80YCZlU@I$A~F3q?zKRB@NgA zS9`2VudGAj2FNS^5gi0liKLsG>Y`XRc|5Zlev5GVG2=a8=&(8M z1qg5K9W^hI9jCY^G@Hn3mB~#_Y@VK;&ba_EP=ys0saUt4k41(M{N*n3hm+^fSm4fD zi$mE)m;NY(4(vhzEkoUZcN1#=0GJDXEV$W3nju^LsdX!##o4B>drl-KE!P@Q(@kX- zgR%S5f@Ly*=0_M;@9$ndiV#* z=&1T@w@|%M07!wWDtuiy$}x*}lzPSd7hLr~MwtR(BqpYovx7!rdxwoK>7e>HAb4s= zE=f!(IedSs$6p_K|$czHK;*qC0?=EbD4WUgAV#v^PbnyCdF6tQe%75@Ii3O1craHK8@PF_%`>|8Ke%B+mIJ&ozJF4i`n{9e<^duI{ zZu9GjtB?gT55PtFPE;3T&pe!a>V8=AA<1X;ZTRU7=Rf*N#DHhn$UDj1jC-4WhHhxs z^V#TZ0|Jgg2jqKO}7U-lAvkOKqyrV#iim$+y-W;iO9j>jzo5aP8;M z1|Kf%NI7Pm(y<;vk9whhBR6B0^kyo0Lt#z39OJ`g_JFfeSeWr91FL+5F z{f398h^sd?O&40?u`B_2(yU22(4QU%Xx@XPZEIT)EV%ZU+nu#;2eNK=tHD!p)l_sP zp?BtVuWoiF`GQWj!R}LIahD#K$+SiTC=#UxX!gaJElQA+8RAR>dlEO=9#y#sS>y<} z-zX_JM=ZFmIoKf)q3UevZ=uyGdS%PiSU!wtcMEilXnsB`exb~ja&3=qk%I-pOwmYl zYCFI81T0hu1N=&@)Jb{7ts_6YiTxQbE9Y98B_a#ca`ZEmCjXb*JcTeGUx&GvveYyH z*3M*juHw)T1vxo6aDdNyCHMW6j%s#s!TH79DK&Aq8?<%#oKBg#kX~(soupIB@7s6| zR+POH^EJ6&7HF;xZa7a~=fHs$XQnw=?EHGmCSoXyPwD`3w`>JDp0vgxCOqIrT91lW z>eW)sjpqVE@C8E+vX5IHd7>?69m+#@7-wT0{S6WY=_~Uit$duv)%?yy$!Uy^{gHB# zD2fs*8ti|15enk;J*U#vlNOrNWM@w)=Ix*4b=3TOln;pC-V%cA?;B8n`DA7W{9c^q zd#9N7GyFsbuCR7i0CHqdOUjQT@i)|Y@pEl^{9f-V3e4U6*i=T?#4Bo>YL={Seb(k> zCKi@8`pGhP#}e*3n!k(+sn$gnL&5Wq>rB2Q;u-A{TX( zJ>Bfda$=}B#s_p2i+Yl~BX@USkO?bhH^)Yo-J$jwUG3C3#vmc9Hg4;usg>Ewg~fos z{@;~)okyocw5I~~CQIg-WTw!@^5CdDh|eYnzq$M7K)HMflE?_t?>3s?t{s~LqUTbHW;LArs44f$tei*kPps+jPVX;Oum88d zp3cyNy|UVOuAVhCuJ^=QJK>Q9t!M5GX$xGk`c7Y;E%r6L)1jCLd%CkniYFhP4tkao z+RhoVYCKc=q9nwk(vy5{Lf>w?tu!+BK72TCFYmML7tfs^U1qVlV>5O2rmwo=`s+v3 zSg!7Cm6~sk;CpQlL6h7;_uE@jQ+i1T=HAhCJuhe`^6$x+*g}V7sSdLl^B%{ApGLk1 z3sL9CKmTXf>3`Xv2GnFsHFFH9-iy6RCh(>{#_p_zUO^%8$^({YNy)MHz@NFCob2}E z>}N<=7Mn5MB&^LXL-ik%`9G@0Cl1&%Rk7s**IR%GYW$Sv&}f8>6*O{_SZKsWMO!mc>`%i8f_d%2@#;w~@IrQ* z;Jfc(>0lXBj#ND-3s>-ow_A6|bovic(bfjP90X^P?p>ud|$c1**`+g zc$k@;gRxR3HX)5U7?eP60qnn;hwhJHIvvS75}H|#hW+)r=nRWGQ$YgU^RiQgy)7-Su$V4rpvD{|<|~uM z7R3Kh4o!Yq*(zQNijbO`8hIqfGxiiE=E|`6G+g6MFLP-?dCTRCsP<7G1-gR6Yb?KM zH`%PK>8wH9?0+q*%mDN+f~UyH$Psh4v$+-}J*jQPJ9`W|IxPupZSCH~KbCb`)PNFW z^Z5AKMsh8*d3a!B6<|@M1i_Oez(m#7@|*xC5Bz0=E#g!TOmu#Em#Y-ur(xWp33D-6 zR@?ivnC2dM`A|s6Fvu-7z$Tbk22H=5y*rhjS7UA*47LnCT@K>LX#iA5+ixD|(6)nL z`clEv#Fw=NRn>8ERH8*o@90sKqnbsXHC^~AZ=x$lj;b`RGg7Lb99cav2`9o*%E&+7 zGn-6wA;q^T`n(Y!n`4z{|9)%?)+1HPDmVr(3xLh{K!uW#euqWYg>|AFc!T$HLt7{1 z`j@SI%Nrr3T;6e}1!Ox6up;jf~Inj|W}ge7P>cKFDtp1k$hO*4GQq zAE^{S2Dx4kaiG!vmA42!+~2pgC{hy)4f+R(FBS`)q?r|J6)> zKB*4jlF%y)I^0vKSyS;_XI!oz136fc8o+rxi1Sa$TOykQV_QJp2|4(u*iCpJrH({? zsf>6Ba{|*kM)BSa_R>}r;5QQ0Gm{Cb2eh02y^A5Xff&;daHs|#g9aH|1Gl@car9!{ z6I90+z(KPSxy)CU*;O^~hvTTJC`xbZO;8QlOM6tqpfbpnXcO-;Y9XniCdrAplgI0^%L|v^9(|K)=hMKk; z&ZDp5n2KVdMm z-5LzoW~8z#%5ib?2_@!x`HBUL13+);cGdea#UoBQ)eQjJ64=t1J>D7x>k)_8>W^dS z-9uef*N@QlKN2x;W&5gl7F(3)_Kkp4$}UXoZI;$ft5XP1!q3y+%n<)Ja!L8LgfiOV z3l=TfI@TeIMiE7cVg-V zi5Nnqzeeu#2~&MIS5q7*{QaWOb4&rh9)9%f!)f2f-JZu>2D%YL?tigg82Fn=V%V>& zJNACjyl%jZoU*ZBzj9b+Iu3)X4?+_By<#V_5e_EeoVqF|;*2OtaqD~N8g}*1`tw?| z^_uYh5x(w&^290>&J9ZInV<|O-T$?yE{nPuXD(kZO!je2XY8YcTH~32uds?pA7AS# zL^l+1gKql&@br%1aW&A|aO|XQ*cgqSw6WFLHXBcDJ56KTX>3evH8z@wZCic!bG~!F z|NGBe*WPRHwQeoL#yHmB-2b-$mYl;{ry!p@;1ffng)UJCKdT62cm4WhZqhLPDbt&` zUjxw;E5JzXhMS|xVBO&L|Fi(UAL*Qr2v5R~jxqf4(S@j4?B0s@-o-f)Fe7oJzV2Ll zph*l;$&F!GdyN)CM4`bW&4t|BpHH8pS2zzZ%5kliWun}1O%Fu6Ex-92nN4G~hxS=1 zROYv|z>!fVKImjEzyz+{u1M}CE~z|Th00*LEIqnm-5}_=o`-Jv{o#{MCYLjGe^mUDyC~=TrTo;^5wL9S+YwZ*?*b{&@Y;020r&1;bTq zSbu zB8AR7{Y7Pgv}HmUB*Ou>tyV1Iq{$5s#^kJdNTzlZ?+ogFOog_4(R@O zIw~t)sc2yW$mNis3QwcIDuS=~3I?xUC^J`dMQMesP%+PvoiKL&CtVWfEV9dwBU5Py zTY}V3cK^#snIe4lOSD&fL5~E3fS{gXn$6V0l}MVIR^Hq+d~4!V{f z1G{Rndf%CF`g(l*8r?tNJH=+4t>$^n`Dt1$R)Vt=}yrs4GIiND>B z!!R2;d}*~0zWLT+>E8dcY6r<+zJPU;dhSD((57dO#Q-ZzkJEuu&R70nqWwpYAHbyu z$68vb*6nn8tIb=qA|W9`tKLi+i5``qa;jNSHUOd~CXt8H_PA4oknfoK-~Y3zk)broL;N?QBr zx(hPaGtWYev{$uPBoD&Q1GH-}&U}q_`Q%#^(AKcftC8I32~88XER2_~d~^!7?8%G9ke^V)BWg)e2#VP03x(!M37w71bPGiTvUvF;$+n-#{W~ z;jQbnO!u4-aixc%QwTEn=X=1Gal73CZJn=SfJvU6iC15&>QQ+yIQDR>9QV|5rz)(> zNdt?x=fxO<9})J&wRN{nON`e%6NMCGI}ye7&pH2x8f(Uagz1u1xj1DO425kDWUj^{ zGQqIYTIV6hJVWj51wg6|mD(OnR(Kl#XFwkRy*5;RL&%MZ?u+~?a|(l2u>3s5j6 zTRQ-SRC{|jx&I!y*J0v-bzHO3npG)>Ws^yb6d^;^k)Y2Uwd$6iSEKoQ`zbJ;`?Ut(zN8yV?LW0Ax|#L_V9{_x!?L0& zBpwihhF7+p{`Gi{8T)+_A9*+gkdCZ7Fl!cT3@^AU!KT9)ll*g$SW;TX#3j$)pt%g= z)N2*2*H;$le-nrjr_*=m9XN2a5=4s_a-$;fqt46AD{{{mmP&Q}IXGk1uvf}V2y#`u zSp;jy18mv)X5k`m{6N0UkeOEOXwWnWHUJ@RYZc*M5FN9PjEoH0kvj3<67x7M`zxV` zNP|qV&2kQX-+D2A{zORZb37{zpG{m-u#Itqwk3=TWkVNQ{$BNQFJ!M92y}W;DD{)D zbXT)%_EBI&wwg=RO;9XZ7^ex}SDIsKMN#+W!(K(A4wbHdI_^on?D|gkw7Z18i<)Xi zkP%jDMHt%Q!a7177yC{)d9!uO{z-&>6doM7xwyzh+tShb0{h1sCCw)=Yz30PyoPZ9 z{Sfl~$(C@_%nL9T2;guNVPIl~no_AbMt8z0X>Rn!_3&CF`x3YSw4;vDq+!U0=OO{Jh)dRli5f)?=l^?R?1#e$P;pNkZR11%vzd*Ws>ir zjtcKXy-4Qg&-xjytuJ=7{oE)Iu-%B4AskI$<%hftMEoATwOKG!YDXx*YHI&E^5uIc zw2nY{Pu2;c2A0Uz%MTiamO=9onZXb+G{PONs$p#g(s;y0KdF1$c`!4QK33&^)mil$ zOl69H`K8A^iUgkUJDg9;odK&wMY8}eQl#Czp4+WHxrw@biVU~db_#XiF*NtBVlBzt zdk&zHk;{+1ein)s0AVal$gXb4W(a&y(9g}({%*@j1AB&ZODS}0u(1xuCW>CBs~gd{ zXS7G1lDZ);8kC%JZ~i@s%cC)UT31G>ijn^rJ$6r^(TTi!lO;6uYnYxxW;bHWmo>Ib~Cg^xd9;R9ZwJ4NB~e*ga6U^XIsdw(zI#4=mR z!o+MD2xIRBJD6FKs?kE5CZ%rAVP8bSApl}oyHCpnua4R`z>L7*s8ADAQDFz{ z(rs$=7!YP-s->_-PPLNPRB-)?R}D{pbNDRSD&caUtXw zZOk1YO|Kl7o z)1*;P3?HF(wv)$mbH*Lc`1l{+NH4ucoKOEj28(!f|Gp{nS>2c?SVE>w-1R5cs+Q`W zHiQbeow8OIDzvUo^>X~3IqZwpko+VmmNr zE?1x%S$^I0nLtj+JTQ2hmX_e)CPK*h_W|3S=V@OXprxo!n4fp;l&KaNZ>(5=g4(c|?ZeELupv2Pkcau5NGtrKF;=Lip9# zSfy@)ZgQ%os2FPpikwwx_Apkcl%4_x*Qu&bznU;eMP2>OwRH!0{OR;yao22-gR6l+ z@y~=|sXVeAb zHf^%Q^G91-S)e_)+^a6Xhn zVfZvnBZI42!{3$12fn+aU0kIMzYy$(OA>k=>MTvUr_r-BUzAZlZmT+^oIy$Lx;@F3 zUe17==#LNTaZ?osS(VE%W6|WuS!(p8v&5^#a|4l?5V>EVRe4H`$tIU5+JFM8vBO)47EGu+# zXHnrg6_vcd8>lA}VmJy1$^?L8`31>!}-bxi=IhG;ihBFoE1xB28I(C4*bp^$l(UAnIc8QTt^ zYf3MGbPJ^E#K$LmW6afo?S|gPV&adHQK17zaayGlGjebPDpVtQe-koGc9n~D zj5tcfv`P#eMtYJMxfi6rXm>79$h<;6!=wMh(VI`8oJj{kI+iHl(RBsGYC12TeB6`W zdzeK1A_doh+GsG2C^j!tm;a-M8O`v9@BRs({_G9U#D1y@ta_DO!E=_9S3LP zmQYxg5V5B)OoRS1c6Lp%I9D5XQ1=m0lM$DDJv!m@F6vNKq%Af*u2!M_xp z+s?r7pYK{rk3ZJj`{@)V58+BLJt;}f-d<5^NW^ca?)9ZpON?x|WEqS*GTf_){{BDT z_$=F%h8Qh4ynBaLo#Ve>L&6at_^~L3Kzw9)YpxR7=>8OQX~N8Fae86l$jd+f5m3}( z4{lf3?G)AcXTI(ln{-{Hxw7bw|Lc5b?B`k^xy~A^mH4gV^bXqrwk1K%b!*L)PUpGl zU3xrf657mK<*TL6>3MSR9ul)a>NX~>%JewD3f^6F#ECT7mLB`%-s!~1lp`gEHllq* zDGnVq_c*EV^HP`n4Kjh9;i?q)C&UO47 zjKUW&M8nd=HHFTJbFO4O2j1s8@9a`sSR4=3O!hnWquy4 z5yA0O7>E~(Opufvg`~v5K7J5_5$U%81RN8>93c(R|~;*`oC`7sJ1pXqy;7Jasg9ARjl(+ z+NmmnXRH7W{yCMV2#J@WuhfLPfR+>>JSkIkQHzYNp9P#97L+*|{;RM%q9LCLu{b_( zSviF;aOwVuv3G7#H`14UZS*_`OKuyD+4qPozLCxYP`5)p;Oa|J*3M+K*v2S zwPv+KfFW{U#eAs*2dN)6$ZIboX>a18R4V1BqaETGbHEGQo3wbB*%0l?ue3yN8;h?nF=Krvqxo z?)gFxN5pXKa;ge?pr3n6GgGQ2kYj-Ihc36H!?OV@;2?KDH#2?yuJHv5&5a(`xxlAs ztr6K|Zgn$tRb(;~u#m*H;c9Z&H8J1(MvxbK1d5u1l4oPoY%L=!ExX+lcM zWTo~XfK+BSHfmlt$e3IakE@Fh(*D>;$;h~g#N|Je zyp3r}S|sa?@6$yO{G+?pJM`ForU6!J_V_+??X^(; z6)?$U?J8l*K~$c8CEpG!Pi_FHaYS0a2Hdo$uTG^G@{z^P#!>ZV0Zd!vN($_`CC(|! z_pr_~PwO+L;t%)N858A@wA;HoV@{g5l$7tliXj=hc;Z$^(AaA{>o|RUS>g@|+J$C} zq4JuVevB5XN<5vY6qOWa_;h2lXvjAeW;7zyfsG)GD(*hR?OIOV(1V6pxbsywJxx*Y ziN@?@qke~MN2onn5n2^199UTIC_-WL!cBqS|LD=$n6}pP3+i^_k~(BEOsbxja@vJ% zx&6#U-pA?z$Nmb23a8DTL#or()6$U8o$xRH%zS0*QoGOqqAn1Xq^ADO_4@fRym5@& zHF@b7YWe+RmP^TraVSS{LcB*xF)5|M%IN#M(~7M*eI>pb5TuSThO9Mo%@3(nFDx}x z?D0rNT%`^I^_Zo$4w7Di*LwPju>|zA_b!M3^O>14)J0JR?IO_SpZSpGiUDUxVjV=` zde1*6A1Q~C?pStXZ&ze_^!QLC$w`lg=%$+DKico<$`V94q&c{B|ElWDpwBinExJs9 zZ4fy(*qeg?VF-FjxaFs+67f+$={Y+3hM4297EW4?7;=HB!j)u1Mh9T^_Tq?hy!9?c zsJ560B**j#hx;nmbW>A3Oy&yqCGSY5E*f z1XwxYcKX+sG|MGc!gZ3YZX}PJr1Xym!15z2Tj1j8%j9mcHNua{r~-)j&fTe3E}eSdK+2(Y8}?r%>c;13ZMN56lG zn5UZ6c^rxSWc`HSoC%No)+4tTqkI*{`E-ymdxiYCM@yZv0rOTxT_v(&;Q53iM~#IL z92gb`G}WHTuLsc9Asn^J=$NvCDx}XbzqpsBqtpTwn8?AsJ>D0cs4ZLYt)@z3iFbg6 zH^YdbirIPlra)X%QGl|>82GS&^cANCsOOf7KpHrf)Rnre*cank3>)i9KQAv{YSpNd z)q+O5yoB~iI$w9S6_%#?&54=G%z1052f?eA0se!jN&ZM@-3%T_%b$^ae68x_!1w|n zY8IRpJ(Y2q&ue55-J)f zi;7LFG`a!Qomq#VFxpJ)eTf@Ri*dxML*6R@V97=UD!PCYz+` z#f_WGk2X9vbLn3TXLv4rHW1WwaDvob%(37C2UUk@q~)v}ecFs^&?j&;veZWM$Tvo@29S09dB*vl5)QD#NK5nn`sMtz z_oR)&Jt|L+iwUO`UFFHE596=Z5DZrpR-u4?Ww$LYZ>_=>pTMjU009DIS#lQ_aV4nb z_E?o^$-;e%xs%$Plfoi)In>nDycnTKfP3h(JLOE7%#g?8!a|$rBv7U8*s6!MIxkqK zrM0}+SJw36LBTSmD4V~4j@A3sP*|A~i()1!*{H{mamY9ijE)dYfknKvc-ARJV(C9n zuL!u!plKPiWMqEDKR?6%+W5q1m=_M9A(lsFFaCKjBEob3d8&By+D%}BdI8}`fgyr_ zgDYuKvX|igAz}F5@j9mISpB}pi@9UI@0LIpM27D6wf$DFu1Ylr)nJ&bJG{_u_kGSH z>tNqbm_<~NPBM51%4;J}WFdzqB%>%w(9Pk&&Rz+tVUw|;SBKD z@WE3ZQ|f`6q#@<>>5e+`%;=m|hEg{cPiYbtgJ#9qAnv9m_b}lD#EtnGNL& zUy=tmhU*w-bPLEkS+x-gj+-hw`+VxHS7&%(FeVgb$axP9Q^?40$b)ESjRd{K>b_oe z&lIWx+azC=+3UrdeSjcgl&R9~A1E|e_^<`c+2P#gbDW*3M1?M0K7Z|Ig0VVW(&u3wMQGTb#kR z-oDY>uEI0XYE4lBU{{*7;?`_wO{Q6sh6uJ*9T74CT``Emy9a;U*iD<<+!K7px?dP7 z!xckvi(Ve&9qEdA`#nns9NyRGc6^WLkasp*RHWgZMMK7$Hk7N|-uxOU5g0S01i_HJ z1{al%OPTV&(R~iUMQTF@E7gS9q||_aXIPBW7BZtsTCc z955gk&K&y5Q(hzD;iHWtrTpT`9faXb4E79!qPa->EB49tL_hf9ot2;v@(^f!cy{La z?>)#~vZ$oS^j0az9TxWO@NOqQLMA8sS{ORVp{r2Oo^_PR9vH%qA}XrqNdi#DAK$PERO+PyY4XreWaW$>jUSspe=6 z_m68ef3~E~=R1*2GvA|ww-6V0G1)hl>wIr1$G;U;^NNbHp`1u8@mgZvOu&22tac6Qu1B_9~#|B$(l_Yo41 zI%pxXT^0&aRf^~13!jTJ)txzhnha9Q;hqky>I%0HYtW+Z99-!oZ7y;Wtqbg0^R0Zd zWO*pjyp{@$Tw1R_m>A;TCrz9Z4UUY7@#{Jw`Ofhr8FduVv(+nZtH>-x^Rra+SEW*1 zOBAhtv=^P=NL}y;F%wML81^{Z24x6OPyp8^^|X?Df3l4iz6__+I`RnG8OU^E*xM32 zW_K?!ak+a7D)x+sqM0$=29*Qt7VTO-JU9pH#Zx6*GTYbf{1x&&CdY0Yu_OgH=NyDj zhaBG8CoO;6tt%72z< zv*kd931|};n^{MZ#CiDINRNksgeJh&%@R2;q9#7LBMo(q1zFI^O}-RwVS z^T=~$;Qr7zUF!c)u6n(urxE44rnuY`(Pw6?e$cJHo?rw>u}f4REB2z{h?vW}XL{WC zoYsKy%ko^!gG5ZfktAj9U%C9n<_J~A@PP5`_gcQAAX=4G?|n;Zeh=xgh5cR_pInks zS0NwVv?LMz;}lU*@7Dzga?F}KnAmyfy=)7EzHp&Bw;eQ4_gR~zb|Savs@e5HI<29* zsKb^d^r>(Fnfd#0f%TdZ#FC}-?i|b{Y+!L1kXf`^seFC?D9-tJ(?Ob)W^gaOR?wLN63HH}r%OS3dV8v2hxJ;Ie?xtC>O3-M!hwy?E@w zf>o2_<3lXbD$?L@sR-W#8-FQ`DggnFL48k{Xq*eSPv<78-#!+xG*j^SAnkB%(!#uY z^0XxXF6Aeuy%>>9HYb7!cjO-9qgc&F(AkRWj@(GK`Z@%erWPBD8k$Lfwn9hzm> zCDYy4yAt}?ZE>;~;0(8~N2o&#HL0A|g-NuQHzP9FM#k(~9#IQaQ0)8z+lJ@(nh*wO z*B<(H*Jgwly`PrdygZjfV;KbzlbTEt!%omQE{DNAgJ2e+HzsZOizTHMq6?pIVCRdn zcD-LBOtBgvxv&d3WM-a%xy&Ttb_d`$g>fo^Yj*V{g@xJqtsrAIoq6=uXga?WVoN@( zK=H-}Cho+nmcu?Pxn3(q5`SY+!8!1I;-o^|MdYa3IIUt~$%L@Y#et@gRUt#KMxO;9)8|3`?+)j?nL<&U1jyFOz`eBH`Ksp-m@-HRa$JY|hOj29*AZ_TXO!c}fLx zV#Eyj+!LNa@|EtxXVQ+{ zv{l;>=*TIFKB^d0sQenZvKvjJ!&*t7FQVos(>f8tb%<1RXKBsc`?Rio^_1_P1YjIKBSjY2Agv_IEzUR1q=rWnnx+C>av_k>+3cgA@d21Hsf9H&=aR zmK%q;Bywv8t=I*$m+H#N$-(`UYZO5EMQgY^l|4!)7IdhxEv?)e;EY}2Bf!9%tXso) zuxb{#MrymmXM?ESTovB+1$|i(4sO1P04q&7?N9nJu9Id#OP=dokl=bHiP?PGkh;Zw zJMmmGeCa=S5FX0~!BE+(^Wcw$)>b8-#5uY@Sa#yA2%gTSq;CU`v-L->rFy{?YI)D; z=GL6xo4W)Pmwsm9P(f))V>?VLXXnLiHg52uYrU}|;Q@(m6dRr2Y$r%1 z@tI45J0SV?3-hYh_tvDK2;iO2t`*jkQYlmW)hC`0rGY7oCGAqKGE=;+V6DPe7qsHj zS~g-#Vd(3qYE5s?$#sL&Yl>F@g!DP~&MoPmgpbNswYL+dj_tXrM!FGh1zBwI{v0ef zEUM%2b_<1M{~-*B`kp_3h6+w3`LGCf&z00^Zgx%q-bVSmH5%%~aQ!=sdHh6F4(pl@3 zAvRp&$64M)3e$Jbp$`e1Ore0a0E(Y@q3e+YjXK~f^!7opApGgX^vw|fTX~=g-&k*u zKMBVPy7#)E$SVe7ajHkxmsx+XlHf@?=#XDocdylfw{FA<6iS`HPr}OE!Le-Y?|~#S zamV&CqD!x6H;x2$+%*S$L3FYUs%v_lj1N6*Tbx~3h$t+^H+6*H`?^g#j-_u@e$Ut2 zhC3@Bm(TbkuCLN9VbsF-WL5EQeTMDxIi(cht)y^9tnc9C{dJ=a4Zq#&t@45&(Y_fv zjsz3;=@;&%^wXN=UL_97EVR~CMUUKFB)ngu(D@z4IZDKZNgm~+_cEj%W*6u>S6}PPA@LG*d!DdrA@KBhkjo6%_Pa{z)kCV+2gFxkD@{zXWJi2 za&0pP4_$i?&->kXlZj11f7V+wcuqlG9xtgX1efLq9sMktHA=&`B)l@q$SLUHP+&ff z5nO~N=?ShbBPNMipi*LpO)V+;upbWDX=V5}ExWDf4s<&+Ussws;C-expt(iwJ0ayM zwX*Kxzjy5@H$en1uHD+C&UQaZAM*)7`$x+MhsiZ^eztl-9Kn~B{#-w2+8T6}J;g?> z#L}64%8v+X=3wK$7T9(L3AT@ss$tU#sBNRqmP-avsrNx9|N-NZol;opUrKV4&r;aZN z0_YC!yxbvyP~wJn2&#FHO7@|s9TEh|_%Z;aHV1V4HF#r4OS?B24J)w@3m~16{7&l6 zsHsa&OOw*k$=D_g8T=oJj3W83E&x)lUeOmro9r@>Xzy@q zbfmSOA3%mwdVGT4`C@nOdrUV^?{WB~bK1`gw;8n~SNZ<-8UUhBPSdiky{zf7TZaG% z_YbTJuKYApYy}@~zq?Z06c4=wF2anNuE>7={agY2dVK?gmGk1e3YD4s*%H0HAm^fH zvN8>IyYp--;CYrj#1h8Algt=rlm$r@X|dRuTARZ-qOtR`%Ei*hC(AZG?cTWw`uLNQ zLeWR3e8Ee(+{L$gyhTA$>8{ui2}f0P^rCkj_LePF_I!Xt>Ti5NC5yVgs?dGZdS8tT zHgEr>j*6nC>>bbyCfeMuflkgC-}WKt{FYnzx>3qr)=$>S9FsX!w!0|gKXRdAzmtZq zop=sP%$VVvSzCte*ci>KZ@F3bADVskuMN{DiAogY}Sh|F{o(9JAo%qlYgukx{hG5u-p}Y<93UaWpkQTBnoGBEk5#@gy;ZWU> z(RBKRe#TCdvC_;B)tq50z;V{VM#z{{vXEdt7UoH#dbf9y6HQ$tzZ$ptgEDUS+&-br zUC~23lPPoe5!#Nn+sf4FCOwjQm4A3pVMA2M$`pp#NCb z_^1kk^w;G-la~FQW_epT%+~i0fikG&*xb|bjuUAI_;f7TQnENS@`IMD={|%0)^l`Y zGDQyO?$DOYPaGT>_^dQIf}Qx7EFpB=>C0SnG(DwA42O+wEBC%~kQ|MA3j>&+@fM)y zTvK@+vLH|dtjmROwC@YBs0uopcxP9@!q`zJLFG7z0|5l^WfPXO>~(+P7VXDy^LdQ1 zZz`#hay<}2#SorBSo)Tt%HP5AFDewD5J*(B_k@8k*V{*mbN zmqhoUZWi;YY6re1&Tm9&jT^AN7F+*~-5~CuJ5N?=Q&kN5@f`gvH=Ae)v(jDOolc=I zXQ-_dp;No2bEKyTJ4=yuE}4)H&%&1#7}3+nBa_dPvrJ_=0*u!5cHPpf*3o7 zZ(3It@?GJz;vCW^t(8u_AxTSMVq zV;hbcsi{*Pp2JWSJ=r-q`Hy#@L^;U2)wpy$m>6kzF^MS#xkcQ!G(a&@3LsortikjD z3V>vazX$nQx;}Rjl2|0qPw&E${`qYk5-0q4NQ^Raaz%}euVQ;dPNO$3Y)6r9@A~x$k6Yimm?nsNWFS~*bTek19K!|ea;n+J zv#B~%6JytDeq73-UwTmGfH7;xP^fzAx9f|C)moSI0~ok6=rU7ni*!;k)hDM+0y%x| zFj8=Jfh$JaL54+S@c=HK<@|ssMJXM$QUpI76LbHw8Hav;Ulu^iot>Q>%L~YRd#h^t z6OqZuY!`SVo(uv4YsAjQ0|P!SZxp1F`B76^w~>vkhRVuETQb-Th$NS1GPoFM$2Dh` zFN1i8xUxtp27EtFCD#2KKb5b)In~yM-Vv}wTI)7UJ!qh(8TEwxH6rKn3sCoTZAAWE za6@Ry%&8hCEi*H>c;qBBd0)bxt>#1Lygo48v8^(;jVK+1*IVbVyC08h{{=GreI=%u zwL+%UIukYGK;&dCZ|vq-uD#bX1$3cTTNyaYVcPVeZHpBW7kK=9G=F=PuZn8Tf(jy! zE>FRtO!~n!c{JOxe(GA+CpB!FnOAj+YNGn_+x`MY~ho}0m zqnI+^@aKfco`oZy0Lpu3=XQCl?mp+wD}JFFHmKO`z@kOx`TkvlM| zF5i_#h6KZzi5}d`ion9KWBUok2bb=##H{-yVR|6hhnF zE_|~@c^5D11oCSJ+XH8VF(b;(C&fE9H?}<>i#GIHpy0Fs5I#TiW1}I`^Ljp<+%!&uQnJQG4)AMfZY!P~(JpW;iaX zOMh8A_b>nOnv&gA)&uiknru$UeDC;N?t}m$cz%X_ZtRj*Mdy~!>}5}eLt(A#2ue~* zHJQn|HZ3YBNa*PB@$#x9Zw0RD{=zLnG&K%^1(w1L{zi#JwALU{MCq9k3ibs)D5;cX z>DuUe32$A&fH_r`ZJ5!2rMZUMOtZlOyZl6tvL_Q$!GAqrsch+FO-Z@dW61&M4?Z)I zJBPoic7)%RdlxNpPE7xn11$0T@lWyfH%z2j6uj$%{aA|Z_Bfkdmr7<<=M1tq&Tj+s znb9}8I)4}DVBr+ykTh{+CI2WXbMJi3N}Cd{O&2QtL&}dA-Ek5pCJ_$HnTS2{s8$~X zkBXa+lyqx&!HJlYXQw>#tynHyRIFb__-~h`ogD>mF>Y&HNjp90uL5%50r?<>cSA!4 zBJTK>h2fYV#H!eNu4Eyc2p5YtXYaO;^s)<9&6-KN7@x>}q?7->2N3&yxcn|p&fxEc zH@Us}n_`pJ%*aMBm#;Y^=Pk{IHS%S1kp*Q%+%GwgDsw>vF|)x#c#ed!)L$F~jV z!#7&@l88%w^|8Y-cn@XMoq>`y-SHcpP0?;8@v~UfoB1W@rk)~5QYj5#-3IPo{9iq= zASVdicQwQvj#tYQdZHf;1^vE0@V}6#d-FOJr#jE#e7JmEv)Hb%vRJcObv)_s0Q)f@ zB4W~}`C~K-J|k&P$cuyuPpu$6^>(t{?4?+*+}Ll8oqb@PD$Evf>vlopdf&eA@iU4m zDjRm_N4;Q{m0$Iq|<^O&T|jR>MzBxn z;Q5DfWBL9e&(W@(ZGPPtMk#GZw#bhbZ{gom{dwQ1xSyQf{LY2qdX#Taxxc6?Mj&vy zxn5Rq!4)x0|0-}^5Db*fI?ZOOsW@C-M=tn$wBP-M#`K&o(w3Ds zJ7_!~w30`q55E|L;rF(WG$*gxQo!i&cAVtGoVGBq4+`f0*N1_TL}N-+ugv#@o+W3? zHLmooGAp-lWBquqBD!ifx;XBLAiu0C7QHaNL(SS~YGv)UQe^lw3$ECbXdVKmG-xcR zgyNl(l%P_f_WBxB_;g+)1h<)hWg*wr46q6t?1K~}YU`Yv(3n6Z`ylmmpKIU^Vj8@) zZnZyN9Bq={5wLJ6f~5kqX(5^@_pnpQMk7rp+3N-|X&jjrL>TXJDQ;40^GOI16cGyW z8&_p@VQ)r6e;}>Sd|tko2*KpHQZ-~};kw?Xd6_l7H!V3msDSCmVIBpaHybIGGkRuP+3qY@LNhHdQ5U?SGuNI!c%= zeHl9l-T2R*(wIZ*A4O2m&nT@BYokB&udN8Spb}A!JEtUM7yi(`hJFSil;3Mn1Gc}E z2*@{Pr(h5i`kD6pttV3mVSV0|jq)(h`3V!V8Y$wL5%Zzh0@cIpVmi83Ee55hh%?pv z>7%eqQlgEK#q{|V&J7*&>Tv-2>Bh#?g_7iK8bEqzKOK8zO7*K6{gr zOG)BTq$#DyYvnq@GWmVzc<4};O@2pdN*_5a#+u_TNB5pz>w{LTgm__ZT$DmdVMWE5 z@3{&LH3}Sf1P6&41^k(mZW*@}!>G?SOyz*t^QG&V3e%m(o(@|33HBcX0s^4NGO@Ij za@_pz+CDMT+pR?5=1Vv0hm7NPbAVKm1gvDstX36MO%8BjwZuA`T{fk+L{sCu2=wFB?`ShJ3Cto@!dH6RQ1Z!|K!Yp>Yf`i$Fc=w zpAc-rNVHgV;c`UKPZ~$p$%zSnlIoDP-|-MJW2shYxa(?5T9Myqf&s5in8tS^RSb5& zjLxNPMnL}Q($AabIgeXEvfTB_+YO)2#hdvg3A4k# zwjKc46{Tgo1WT*E4}O>WQD3|F*9(X8NnVN#onKO^=@a+3Tt3|V?Zk6l>O$4hzri0q zdAR9IE^+*Ox2M+aN0%=035zM+d1|lZ;O#^1`mOJ=fZ%tbD&Hr)$4i2otnA3z11h_Y zT?*#0l~Kume4su-7uQB|#FKNg zg($8^T~gQGhczC`LOo*$e~c|9&=z}gB?gzum%%rAz$r>jX@t$N-u z$_UwQ|0{p_t8WnwM~owB?tC=zloh|nQ@dc5uBXZ~YLojg`&)kZ5$jiLg=pk2NyNUA0!w53sZxwXSj78Y+hVo`{Cg$$c6 zR$JG6-K`kOD3DfJWl%LjOk5uMtriFz5tayJa9?8TzYjj7I{F^0J(tUpw zMAJ|z_N8LY@WoSrC9#Nk7}xOUpb}ae_VUe#G|&7Oj$#%&3ezHj?CJfhb+h1%`!1`2 zySC{g-9ybEaxS4WKKq|Z{!a@4m;O=59~F(DhX*crL-?t+fKV?btms|H_-kds3a>sK z1P-smpQC64>8PMVeqqu-aIeD=vF=BM)ycdEGi6D1dv9{OS`q$&nZ*y|IdE(s$jit2 zm}A;0_Q13cDhe%l@n&(Pd@Xx3W1@Z*c6`*v%z--xHidD0SWrMPPrWH^H7`@}NPK+Xj!UXY zrA+*hd1x~HdQjI;!92c^7|r&E>cV#$)l!AP_C}qr=RXp zY?2FizV~nBUUNJcVp5Z3Z;J}$eRlW{?$+J%pWQW+8Akp+z-)f{e@uNfUS zoZ?obxVwi^w75fYw-Vf4io3hJyF+MkcMI+g#XX#S|Cuv$E|SUQ;+^+muf5lP)+163 z{FNi8Y=;pnuw=G^KHf&b$OGzVX>>MrhK69&jt)JobEUN6{4Qw;ol=_}9@s@;xOJbn z6x4Nc{~Dzzx`#ru$RE9RVHle4C@LRjw$&5vRPDJ`n@=sL33@xoZX*2P3UtbChebgX zTdqvW&hx3n(ygSjHPEO#SG-jsSHsJnvh6gP6rrS*WjLICt^s$ zx6JkT<7M~wW!QARL5qu<46OsG(r93dq5U;L;|Gjgz}l*q@|Q64jV=>tJiYl?%0xsi z2yOv(23{imKC<>y_laK(Obe~Eu6Kx_Q7d`H{dwi~+XmSYF6mmt6o2ab`Zc#hyN7q< z_9r4a8un3VYpki5ZW^`UCxHjGtXuy?^=E~QoSamZ>gcf%A^>PeJc%GlXc!&sdkoNN z#$PvIG(A0CyG@rRO43Ab@MwBkY59eEULYytrbqtd({L1Jq$ zoH-M8N9h3&Va4@^v|G#>1edIkwnulz*zS@M>-pf0192z)e~+s_Jte89)^op{3+?#HXlW*igw%3hQ7 z?z1Zl6ya#Q$>fMISzKA-jKmT#AVwnNHL&8_@p@oaK+75-<<0uL+X^(^JaQZPm!q$s zJ*Y@V#M?I7{fgf6&=1G+>s*45L2oUVs`K$};?i;LJD~U`P{+*9b$WJQ{x~9%Uqp}$ zP0D@-A+qhbrkjhOLbW;Q<$!swk^JH?sIrmvnlZyzp|gS@YvC+>2w8k ziziUz0VAu?3ZF`@Z`NMdV%g%~x@(ulB8jSMJ zmBy-2Ip1ztFJuXg*FV{{Fk;{jis}Yk`-8h|Ha-7+Y;hx4pURZwGR^#HNj&m-m$CTw z;fkjG+HyxG#g*}NEdQXb-nSJjM*8tN|6O9DvOM!sYd#yaUtTB~nfY6g@N-n1FZ#Ow zxL0@*=I`iM+L29DnM$hH_Ypfs9ZQwdR-{!DP%`B)3&lFo;(WIIdG^8Xl}BJ2R2T-f zSHxgiiasafJf?k^-%bNlD^Q<`jBicHlarQ()toxPJ@@M<&k5nH!#6Vk4)tZb!iKhW zG_BvBO#G7AY*Q^G;&WQgQSTqghIB}mOVV*nvP!*F<=0|-l2EV0DeDpW`c9+F zkR?wC-xX1%Yh~=EW_pNr5S9b^UMia7Uf}84A<~lv{NLEBTa6+XgZ%mJPnfDI&`Bvh z9bHj<{hwW-ihjE|d+XF7^I2{uIyNl2PiVuS)$5y2%bl%~SDU7oUH6uQW%HLm)?l_O z(G%&N#EJ@_D5BbWO#UA%zVo(OLm@2de$Z)mNa32 z@(WSX!JjX^{9e>Vc)EtlYL{LTSG<3z4XNa@S1i#E6e&`V*gS~X4WEW_5fM=W9-hFo z*8&CS526)iWz_8KSdqn4mZb4?^I$5%Lg*Pr21@-e(a9k@;C4aNfYdQ$|9XrSslPw3 zj)K>M8-s~2gtgYr@XpL?7c+jkZ&g#xK6zhb!{hj841w-gHY2D{Y79_vQuBk$MbRa zjWWiF?Z@`IQ^SB@|o#LKhr36?(QZt^AGAmwc32^P%j zxb}3|l36US4PGpO?MuGzLY_Sr-(Y=J+(}2?!Gcgz zkmx$xlo)TjWO%1G9@`O|9&KB!zaZyVM|!s2x67C1I_`p+>G0ytG11x4ye*Hh z*UlIF+cd_PXM!cy`Ah|BbwWdg z1BwZ5eeq}B+i0$6a{1S5P@vCElVb=*Y%^8pO$m3-@6|+M5~Xi}IcW;F0J2N6mNXsZ zb&1fN0S+bmYt|a{#ZX`u^`KVYr%g8VKPprS)YDi5^0-^K$yp8^Q%p0&nP}2QAl4)Z zhCVrJhBup}b=_ZF0CidL|BKZW6_1~1aWlV$Y!jBb7Oy{?oLH|bSoa!*D%>t6)jXaehz1`;qX1M@4TTFW`s8r+IIJrh5$=j3Y%iP>nSR=bqX) zhfvDZT+m!z&{SQi`Aw#*4Y37)CLc{%#&gh1^G99AL$)5xM*QD62Qhok1Pr+_nl>O9 z4j?g<$+lpiDEZgdAzurl*^4#r

ZC)4lx&@>k0pY=@5fdaKe!P9X4K=9d5J5#F>u zyg+(oq&31n^#6;Avs>28&!H(izo#XxR78+AeN}+x!Z8_rZvA$hg`Ao4O!KEF?I1*| zZzETrI(q~DygPg-g@00uek>Ujg^B}}u0y?QhEShxYV<^SD5Eiw*WwC~@%>n!6l8d){eVgH zPh2-B&h$^a4Coc`c_Qs97owH~q5!*Kq{D~Buta7}$5|T3~V{qt}y}wAG?iM0mqK%t~C;)wQ_W^*JI@t8BA*1_q^P zZG8_I<>`}P4665$sqlGwZpJxLqJ-loVVlYw%Yq)FSmg}0eTJCX4b=36l|(eK2$y*rBE-hqymJ zEa~r$aZ2R9Zr4BYT?!P0W8S4awCOaM(gy|YpqYmD?aQmsT_x97^?Ch*x}D_B?RUe)D_ddD~;Z0R!*NH@RJ3be^U zuL(OV7PTTAnY3;KC7Ol`g} z2wtW|Z!drvtp1#zbw7TLV)$Z<7#V}7!zgqthBEY1f$t=At?t?g_+Eg1n1HD=A=z`# z^V>tHip(g_Kz?Ke<0kc8<{;>1N!4{-gN1IUupq4QvNM2o4Dv@uUen2^#*NBhyyJ){ z#mpK;*eQjX=4$Yqgg`h`+vt9LJKlf)O{eX;c4h7E$}LbT1nhRx|KK;cag)3MR47q2 zx^T?_@DWPS^>rt*I(g{Y$fImFMi|2ZO!!>GlY^>?#YfMl^zAnaY8l_nius_sF+~g=*H=fx^C|5u4TeXsl z@9k3y&%a{y%5U(V3qty(r+Azl;-iW6bcs9o@-C6V0;Bc!BxA1)SS1RZy`oFNDpIeN z9@?fGEy-7w1QG*P@KKrbi=D4OI8_2@s3dUDO+Z& z1m*{5=|DXz*kM-#14JN{a(z}hjvXiuX{nQij%~6%)5JDMir`u_G$?QPBC#x=q5W^Q zFy_bO${2g&pMCN3m$NQXnwt2CL9m50Wgk(Ib9{E~>KDnK@kf2*pCys$raIAsDAJP| zr%GyTd1-p(92~H~ReV!U+#G2W4WDkruDV*S<5OB(Qx9((%kf1=1KF2tIn6@IP!8oo zsd4|4@?+-}w!aNe1-Vmg53gMbjewOGYuBaaV?Q;-WPDsd-uYvQ70`xp;h%-ndqqY~0*?$c z)Ypr6ewQ45`+`%C?DzaT#E%J$^=E8+v!P4Vq*RG6{i_W+Ks^vBPP znwqHu2CYtq=&dH&)OqQE-$cB`^#4jst18?`XVH)nIF*?S)Zd_w)>TIO#f3%_fHE1tcdN9ty&wFCk^d!&9v;Rzp6dCTuZu7$M2BEiBJ4Kv zyt-R^G1LSSYt|lsj|FbaRi$Gz0~#~j1So3Rme6F%XFt(TyUlJK2O|4tW_&ieZX?dt zh;&{4Q}-~|lZ<_&|IVqQ+a8Yl?jCwN=JV3o&fOIY^0q^WCGh>@6`Mmd*o(5><#QNx ztA9hYIibwC9n|^LeS7rAUEqqMLf}0#A{bAk?Zul#_@0-q>$4QX+ z%{-Eu2|8RAzmA5}dU~sI`@Q@|TiX{pRHQrwj<_No$3gklI%-}lzIdH?H{{s&6Zrcm zmI4k;J)Ua>-sJ4wOLV?(*%RuQqJ;3DVJJOb9K)oM{iRjfnvsZ0LpelT4kyo#?qn_o9xPjN$}@kK?Q&`OP}$bDwx+H$ zGC~Q~Dh7U{Go4-E%k}g_Ni>jg4O67XLe_b$cG)d<0v$OH;+2PmGSvqJr`w!w`I}&J zVk}?^eK1pZRyG2V48f$Zyes?-aYE-m-Ohj7qM+F_R8&fpmp8)w{6c!OhCV%CXFa3k zeN4tmP<_mQR2JIy5>PLA=bYM>%Q6P-*Xl^8qrclaHiLF>?BUtCH@?}e^4`MnBhZ8i z{y~#a^U*$!5g41aG-(5+$7H_`S-#`Ve}S`BW)Kz*iV!08^x=-K=5Yn;lk$9||Kpe} zBoo`6<+*@;6`pcPpXo)*dFw|dvm8?FK)HM%du^hjFI7ipSxj0*?at54%zS{UT((4p zNhH39)*|6Gv4`e1LQw#{cMPnX?e!Lb5W1y}c)#X#iMkBi4Td#WW^`>P`@d73XDU5J z&O>@d{l*IdZasw!ysy%S3gWRZ1Xa%a3LU%~-JEwkHkge_%vUe_btxzPJB?biNGg8P z_Ea+2h(Jm8mX$9F6)|&0_T<#R@L*ZnbsL7KV*S2K+M%O`8(5I_uF+If5a+#;hz_(L z2%ze@@X1?+FKW?BogBDCQsZ)LUS&e2Ha9+iP@Kh&x zsmXU!l5H4_)gYWxQ~xop4ila1^J(09YL*)Ao9p8$fcN|FGqA}r_CKc=wbMwpbJvIr z7E12sjN4Gs)&P^K%CoAY4@MdCWsVX68>ydDzAm;`=<5@6x5y1%-)c@;In3kbGV_2i8CGpG8H zhc;(|2J_INl1rRHArmA~nrj`fRe*yj7C;R# z#m2$$;Vlv+-QcZ$s)YZ0iGiGezVDKMAKDcY5a26u0Nt>a|0BpfKjapL?Z~XF#HXdm z>h~}eIMd-I*8C1Jr`-#~ar!Qg=3J~eRHR`t%sun6^34-Ls8CW$WEV09=^cI}uX_u` zMm;eSX@{cEXzibwM@pC)ILwlg1+uG90}ci?bU)`K2G>YtAae3CP(>Zdh$56>iUpmc zw}0>y0fi>xgNFVBKvS%WX=0)`E%5^S9j~Yt^_zbM-@CF@!l#I;&Cj0&dOU5gJRaat z=av>iPtL5=-d}Mxx@)3sJGq#AUO5;_Ed$D#IR1U{}iYh|J(V}WS{?hZ4Y_sC_GW(E4SV3SrC50wPFgy7R~Xdl!df*xwadx@IpP3 zp!Wziw&~hoo`P@_E`kL3i&QOGzb^_EdLDnV6^O~UpI_lNpt5r}w+9NOuwEyjV5lka z=)Jt2UNy1lPw34g@XMAxA3EW`!>QkN;ExMoTMVy3z)+OOL~yE9nIycJXDdd2ETNs& zfC1_3o<&=HtUxvCTo`VoES@T1Djc$eVXYg$lr&4sXch)08Y8d9+A&f{~xekYfFj;5Z=4HcExk{%FRIOCd&YN4eg-1PFJBRNoo32;e_M*33 zFqYnyCAM!@G!jIuPFim2-~ZAkK_KGYsQba^FAY_iC#xl@+mnoh@a@dE8d{;D z{klnUBTcBx{Jcs3M<;X?7HbfHs~}uN4TUm6s%zvlEZHedt#j`e{WozaET{JwnYM*P z$?vg}3a>tS1E%rI#|u8oulQdA@8p~Q<*NAXR-zvhi9-j0Ao%1Y)*=2UaD??B2t0ZCv^Aj3iC~Tv<=8sE&Ct;Nga~1yd6JKrwi=t^m zWBJiRN`{)2u)pW(6E2)W==&k{3P#7fcJro8x{L%AHV^$Wy+%=Y zvd1yJ@lD5~1*&TKXzMvPBki$ze1r`ab7Z)6=^EBs7##x`DmJ6N#AQ>gvZHF1bZ&Yj zX@CFWhHaMqX~;M+53c4b)7VYFqqR(k*p%{|B(NQJCS1l z*nB*VRXS0EwxH@mP*yn9j2IgyZ-o3a;czpK=%sC_Dob8oklNlnPhjhxWYu5sBYDS^SToXkdo#dV1Um4hFnITA@>-5|OsBp-w@}riJkaJrL{z2A z(Dwg^Rw!S4vzEc5i!Y@d$q=Lpa)N6GIFr}r+~>}xLzus~AM z7hC>UcHYTu(!NGwcS~(_x*Tr4|HlQ$;G?=ZXnTAzFfd+nNOcewBeu!)ixysqOiwR> zJ4C<8Y>k`pZOg@|nYt!`;N9l30HZ58l^Oph75nNS49)Wq^MDfb73+Tu&M}pP z`?IA&T58|?STH?%w#p6cO3p&a>$y~a8@@%+`ZoS{1o*+1si>;1gZ>%#KA9;9-_6s7 zPW#0OfSw~dK(D{=T}}!3>|tP_KDDOI+G1DxsfqQ5e~fDEq4U2>mH*~{5)z@EQBaf@ zpl}I#7x`p-o9((2PTTR$%uKewx3^=z3=M4*DZ0wrNTB)hy__P2#Ysgi=*vf~YK@28 z&YAgyl{*+k@OvS5s3_Xd$w`h8s^d8lBmS~8zK75Va(CFQv$7xlgerUrt5uy1%B|V|^sI^+oUJU{^U8Hj z9JWlf<0TCB@-J;vT3Q|F&t-%bgE*RYLYGWLfb1*nhbE1LN0+=x&EK6n;@7|l35a#t znk}=d!J)&kfVzMy6=~(ny?kB0XPL1%!na=I?t>^aKssm~D9eY4zn>6D=QW}qrg**;f5 z!j(wQIU^<>e=A?+LPuDBA`4}+ZpWyXUlyJd`?*M8)YKEDZU9{&CvhMe5(%foj1Liy#Fg~~ zsgAh#ic+*B6isnBp(EWWsHQ7w39og|Q z>{kD?CzOTppIXO2dBn>hBW%!m;JxwTBETWp1@dl_z?Jy2=W7M#lFtm8_t&m(sWZc#Kj+2Z@zXJc!7vxX=-;>xr6emItm=6)XK`Fbx@d#Rc3D!N>Yp3Y2`WE zC!gNph2|0yohGx!ZsbseFa5yOoKrXaQ#Vc>n)zLaW{YS^eBbZ}J`);o|g zGf$KpMpdz9o`ahcp@HpV3|=WM!1WC05U2=qRd9``Ih3`^V5pJYdN=>!^LSu-QxCKE z`FHZ2vDhv#zn_G)eoKdKhq9MNEbw0juO{9HKt8v`ulLEYDwGRZ@AbL=#&k3q-ZwHm z9?t!YDt=)h?AvIkJ`{;TDT#}{l2ndaR^JknjIeQ-^_E@*8Fs}pUfcF@n(%wB17c6gA(M_50Gx}yRKuk`0~Qon|GgoJUuUJoIa}BYFw|v z2KsShgLccr1W{`|lzY{B)J6zq5OHXg`!Q zqOCaMeiLiuceK7YH`T4lyz{A&r_sw?I0-Tr6m>$L)e;yha>IL}n>zS-fT7|v!pmPl zoP==-(CpI_MO`!=_Bk{=vb?k%2{3CsJ@HzuAc-%}ZLdEW`)dM8v?fj#LLFBc~J8Qi8x z$?+N4(Ir-L=%|?IM~0U6x>y^Km z1;BN86l2?W-h*4y1J#W=7pBZRQIE#aQDr2ZE0%8==;)+>I5R8{#hw711=lS#`FR!= zWGx0tD*{6eF9vt@-rjWiaI`%ycPdm-$TDId)ww}H(*$UxDMOlRK_Mr z3JNQem{-ZORs(=Roh)|26%D(l7U=9G6Zz-vgx#G0nfpDbCNdD8Lp_)aQ))7`^j-K0 zcKD4(-ll}qJY|W5CYf!hqd@`Ajx)AiMdpNtVT@-E(2+3SB=XmaG$mI4gUZo28rHg~ z<$ulAo6%8A@uvE7Q84kEd81W6|IjgyDLynlP>sNZ{oQ7x{Gq-W(z&oqTY;4I$B$uX z@T@xwMM{u%D+{Z`$rCc_n#EbOFc4XJ(0@Ceu)gLAD_#wLaJpFi0|XBF9zrrp-xJr7 zOoHa>GSgB0byjDr>?^(`haNbv zXT-WrMBnDXt_4@bc14;c>s>u8{d}hM6a*h3XS-ov5N&*7?2+4j%+At&i#T4sBzT!dn`qIa;_ul9gP_)FRKYC$JtZYCvaOoB@WB>*1snj285oNTv7pi z1oIHh-|G=%6|GT_gPD zADsJ0M~U_yH{nBA=2&v2KN$QgF1#h+U#^=Jj z%2cP_dEUpjlAj5e3%u1Z_M9^ZW2~jGN6HaXBAHjDf@vogA?5U3@>F<%Nv~qFle#jS z7wgUo^Y+`ju~Tj%0dU!Pvmis^r@h1)qvrF~R;Q~0bRIf*1c8YnZ2Om1zZZM4QuNj> z%;C_eZwU7by7R3s@C~!mavK2E0I91=E8-K623_ zR05SI1ErRfk@24)p@Wt-in-nSLawORA~sL2CBOBG9=wCT7SmcD>vMYr3GyhcR}hyo zWY*L}3vvSfSgm#QvzyE*`FJT*!oqfs8H^_iJ~em4JPlH!+4FX|zbxGRJ^nC2x(YKZ zX7pEE*x5O0ZYfp%W&`St4Vo-(r*^>^K=ArlssnE;rr*n1>Xe9z-w!=e_YMvmAMG=5 zqv=ckC1RyG>@HFe*UU~u+n>g*^k^HHJJ}o?gRsNZV~x0h1T&~!p_ayQ&k zBBZt3ALPH69q5=tlh|Nf2o+Ub25*IVW}6DquCG7epQRVIyF7P`&1siolI3?<25u{{(1xfSWwu2e9QyL0wZaCY zQ0#);RTtWGzW^TUAE$6k2yfkNP50APgBix;hxF$)NPmxJpQA2Kh9EMgcEudIMbDi@$Tpul9|@{<;G*a)5x4kjKUCX0=E4fsKOq0@$#{Q~4j^iJpSEkI^{L| zxVwX<6MR>Ba9F=ZcuI=-u@ZF~y!M({JaE;Gp^$NBd6~}EHnivg{@#hPkAG|e++GRF zHS6nBb8#6kYL$O_N^ya9j|u7N<)~3ynL6p1dAZFdZjh7R0(D7w9`0;e*)jd&3+p%n zdrq$|+z%fQSUiAWH>xXNYAPx!UprOTrt-x0yWJ0TV9-0n;JIc&4t5Jqx>l14`kezk zF7s@8H{~ukrj${hgdd=k?M89@8VWa;i81LfBUEx}Tdl!ltac z($C|WYP3_xpO2iAuM{XW+rBH(=R8kj$v@ZEqu!IWZ||{|p#SL~kG`*p z6??qqe_LcG%KtJe@$~mwNT`#g4Pz$mcW_flg(WHqwKKvrs&C#r zLjWe;ukd&rpPp5)H;3xeIF+aoI?Q7K(g>PGVm2wXg+MZ3*~NaP4GdX&F{fK#5KcR7GsnuJ$3sD&W{^6o-jtXp_HX&RVTnTYnv_ z2z2wOz*;LNs>80YfJ&bjKGW}guDd>QrxiuPRS;KKm!)H2+5U}RLP}sZ^^HyFG}!Wld7l1-;EAW+<=VokrA zQp2pB>e)vz!4jwj1AO+WfU*BnqzTiOy@3M5o88e0G+PZp>w;9&JxC76FU^8#|3PR zNAOO1_azV%0^E_N)_X{87o@bjEYNLpedFq9p`Nv;mo#2I-dOPTiNw9~nHf8OWLb>5 zK)E(8z^~lG!Z2%a2n}&q_Ogn(lYWYLTZoG>-#yFy!BI*CTY@#iH9qNA4KdQ%(2U!I}qHH#6ZPMg; zxf|~oR;wq<#IY*AAdy@X<)hr^WzO9X(Ts)1M9*gMz{B?s8eK8NB%umPI^3R?069Eq z`;~qMgU(Ma-1)Na7pq&Ya!V!!K5cxovY32MwznCZB+Ecty?>85*lqpUvI?z3=X1vS zMY)+JuW5CzreC7pF}TKh4nFY*c)jw4js%B}XZ87e1cfRj)2Y|FcFYagRyb$PaYb)$ z8a)&8Oz!a30AGO(2c&w*zn^@J{R$5% z7P(|}5&_*|)R^*RNG?qiQ!FCW7dvHCRH7>@#fbrdVP{?Y&dxO-O7d?`vfScxTWR(E z{ zF}5+rpQfQa%2g$T!N=};xVi1(00kIIKz#)V&);g80%&HSq-2O9vOirq@ws8Qel+oU zg)Wv6Q30kB=P*K;_=~%cw|{5u@b*U$5cap-$4AFN>2i#9tYl)5%6GpO$ykUz;z*PfxS z_{uAR)RVW&Z=05*GiC8m`z-A@^q~DP@Tr8;r}QWPYl|#@9nQ7Ly&w^=;y|5Pn`AhC z4F-rr?i~m4`4?2>`Tk<{I$ug6OskYPr_Mn2BO4CL_GaX8ck-+~jae4Zg8j`%e^=G) zyM_6*QiBQNgmpY_?#Y6KrO2-8W|38uuxAoLPX1a=IlgJa8nmTUAdtW7rA{N$dB)L+#FkuN?S7-!A4F6U%2%8OkKQ?}o{?d`4uQUz zojl;6$?Ap=4)M`=Vf>K>gI64OJk3~w{vLY?EDQln&k2K&w=1kH>w*?*{OVY^-cT}# zN`~APW?7*d2^*wzc9z5SQb2Ob;836i1+5`F*_#&9sM{K5k?mWVKut zOLBe`8`t63lID#s(FZ?VcZnN@SzGi&n*a_@&fUqd1`1JL`%?UmN(hF<2DDJrf#0|5 zd&PHvmQ;Gi0_;T|L$@ichQ^_Stu5(ltDP!h8{ugxJB{mkXFLvV{gb`ahobBu;3;nm zvR3X81C>T(L_~R+mb8Ndd+yVCX;CZ2H*u@HmH(AWEn)9@020|2^uzYHIv7p7(&k|D zmxoNhJzeZ7T2OiV37QfYyCK0mHtFR(w$1 zpae1*Z92J@I*WKe17ekfteB$%6Qck(&@9M@spB^t!TKi3hK!n$lNP_iA{teswuQ!{ zIXlxmsfU@(9LdEH9j&V;x5P}Gz?dP+r|I?EGr(YfxPzES@}BNLMW(mCXmJ!V7MNDG zh@P(Kg(dO4H+_Afcg|ZyT;;1ii}DG`>=}>PixucjBj%TtS=Hf(`dcv$ViuDtT415K zSxU_XXZdnd%*^`>H#{l5ss5|cQj;u6gGIGM)K>9ww&V2Uo+;gW;Gho1bmnA`0@7+^JqSid8@<< zGeeT(x7X_QcAxIeS)*x6QW^kS-J<^QVY5=?K1qzVU9-1#;V`_MbcF@R6woLh6=2F^ zz+{)$cZF3q)%WrbXzdQ4ysE{%d-AqUvFeb4w)gN5&Oz_$Ap`PEJnAl9k|vOMLf4ei4mB2lWMP zvn5`8M9e4cMh2LIrx;Cy_etyL`%TE|5X>o^YWGXr_h%9|IfVH z?v?{tI73b`pu#qfe|`{>jJ6lg&tD7>W^%y+W1??@Ow0l*>E+xx*Uwxp4e zO?3yT!^vlDg+EPHEQ4ewojsGXmu~{!ah~>mwPjRYSR8p?3!ZtjrzS~V7D=Dw%AFq^ zEz!_>n&7Mife!n>=kD%z?Q{8FpcSFEvU9Y>{q<{$h^qP)LIxq!13}vf zn5(+(o9&6X1K?xV{{)oCmc5ro@XMD}fg*OU4IHa>WjY`n;xonRQ9=;9?}>4alMA0& zYCkO(a}b%4Tg_G z%vwTjO}2P`4#>PH6a!)oFj-OD$Za~#*nU;U*M z8TPlTx|)gv9hyHPsQsWocpb8RM*{?HIXt~ocL;twb%2gtyP&n_SUW#jNt zQT5H%*oi6VrAHk)C@9nvKE;!kg6HPs6&2mQCs+*h$H2|e&Teippq>Dqw?TGTUA;}w znA0o*9G{8gI6}o9w?= zVT_|xh3nD%Gfx@_YF6dBI)d~%6&6_ssk0E5bae-ZhZ}EirTEBXjM{b`{}OIc%5+DM z+*;)R7MgUi(;^IAzjwRX9Y-KH8tGsP2^rMuW2ba&qPQd*9E4t6VmL^AgjckA6LLGL zAZ=M$x*Z(?D;;;*5fLcXoZA173lK3fQdYDxj;~#R{VT?;AI5wj**YuA)dj8<`Eg3- z&3qf@z$CZhS=V(1 zH@MHp^>RZ(S-HN!Cd>Cm2SBsa9neyH(82 zHnerdvj?)xJnc65u-Al}a?`lp?3VcOVxLme(x#@QBq~GSW9|XQEN9I1j(AAiFIF4? zaBUtYB8S3YMMaRjR}7w z&JyzL8dp?SW`{yjwArgfL_5kQnfGT#IO7g(jgg+*lNgw>)=A9lG|x*gmF(=5Iwfa= z;<`8LSpZ4GT3R+A5KNeXswm4xJ`N7!=VzcsWa?AB^=A3_$@G+>zJBm0mbNfxO?|Z) z0KNg9j|yRGzVPzCs0F|w2>9G)z^)mx>>VHiBW`x-SfL}t9DYL{m}58%5Fd-xQRaqVhAp zF8Jy!435GZE%;Xnn0A++FjE0MKH4lUqA0H z-9qcWr4?&(>Tsa*l7^d#3cU*f<@0d%8eeNT292vDTr*)Yk_+}a*VSwfad_sVoqONr zM1-Pz3QkH7I+f)X9zg;^HsLlXKOe^-4R%jVCyqeC2_Lm`}kD7~FiZ+Kh%yO@>ECqQ8H?ISx76*VWiA zF+X$a$)ou4e<*v)sH(!QZItdt8l(kj=`I1u4G5c-ZV)yd(xo)gozjgU-QC?A>F#bg z%lCQS?;GdeIlp8KWQ%LfIqx~In0MR#FR`RiYv-kxi3wEYOB+NN3jV5Bx`jjl&!Uyl z)g>M6Pg?pz6m>%X%{i>L7>z0|v;tdl`_}f5$VS$7NZbF1T>?r=ZJf_2a9fgg04=CP zpnVAVm%2xRgpi`aRpw|(f%++HWLwtcsb8=n877Jk9ims(XUXv1q0iHtA_Kjt&67BD#%$NLusi2T!7 zmMQb2Q6P6i(Vtt~ld-}db|pC(ENvO#<@b(808ICU0dKmD(0s>&I(pi94DaGX!{N#O z`>Bl{e`_E_aBKHj^hJovy}Gb4?QKuBaCdH((_mPSdv~9U!$P^uurrI5+xg=lif*8v z{<;`715O+yL1RAx@$70kZTAU;gt0*=IvpJvr=u?TJ=A8fLtKo4;uyGHY$S!Uy;20U z#>Ehm0%m=15}zZgx_U)RCMpp7R{CSGtkOPNt(`!43o#b=EOI`zyhBzsd?5+X!1HH$ zYO0x2g@pMowmbaamUI(4KR)r$=8Oq{_{aCGtlG=vN)uY>|AXxs6jp2+?vd zqho&0cskMMSN)iI^CR-DNi72s!TVp8D+67nnYougGZd3WZQ{>2pT*Hgh7&$!HVYH^zpCVy{4?m=!qXZW5&k4Q~&h4;!qHa-TTep7RWer7!J|Y z*c7ZDC$+*`E#}+Xd?KP$jr5BUvf?&p z2IN-=JL|G9M$Vhhga%zTr#^wf%!CaBcjARrQ#CbOkJZuVBLzxFPeYoFy6vJ6d-OL0 zg@5do$yE>D*x{#%ulaCkdfnm0`1|BZ@yxt?;D8U2`dYK>rqg~0Nk`d}4~f$OZYT>5 z4p!G>&#$}AzWTuqLCWw5el-;br(Ik&mNuoL>+1gdL#aszfg}D11x)=r5|h0nMv+hI zxk*U|p#XOP$NSDjmFv$b5vk+m55{kpp#yMA(|h~-p&viiR5;Njj=hJL88Cx#eZh?% zLUj%f$r=ty>L(nYh>@dNcKrKYvi=%p`5(QeUqa8;o=ufo{A-K(#_pFFw2+K4X!U3~ z#?hLbHoJ1ZhdkNtrAh#p`bQw<-35`;hp^J)U|}A#KZ3F=Ol67>I%Tyh1OYaVxnrb+ zkeOqo^2+=F@Msv~2L)mHRYMIL=}pA~Usof0o_^R|rSe?MZ>o2adQHKP`B^NC0$WvR z7QPx9cGTOXWn8UI+fza%B@Xk&*%eYb2gkmMZ}urR2^LWEi5&4t36b69Dh*Gg%~BK; zp7)#PXBrL@TI?pj&8`b5zB0){d%=GOdd$4~dcKng#%1mP_vvoGZYw9ytAgnhDoun* zH;3G~vxCJxuB!m3>drhN$(XNa3M?}4GJ?8E0IM~#!yK-GZOymJ4byThIV3N0S2lEF zI+E%V4I5b`{w)GgCwKr=VEgQvfp2YPm3gVHGIwu_WS=sK2B)~?SvW?84mbJ%;68TBJ3wuuxR^NCq->7IQ*V7x+@|1D!1!Gkb0#xZP8i7=zK) z);{Nnw=8!T$XbE%v|D52voQl&;jP{7kt7{h*CVJEnVI#hPmMnlUv`Q%tBl`R^wG|z z{Nc1oSk|9;i^WKAK$4r9o8yH_#m_ii?co9~rNdf>&+sj?xs9|rs~r^|!+%nIp`8@| zb`$#a`iL6V4iQ*a5bdcc!GVv~hP5O4m9!22CE~3meV^lJ23-;XVbmPwso`)G2g`?? zYLkfCC`l#W>bd8LK0nzH``RW~e_tG;o~&Zdq|>xqHV@@&T9ZVwJc1lFA!OoAjeI^C z0Ca&T3^LhR7qYrvv0SX1 zzZk;ymA!1eo$@+u_5Y@uEiOtw{h(biJOP9#&|r@*$!a31(}yWvH~p-DBc7U%9dTEo zuEsrJ(3mU3uEZ@d*6Tr1VT;vdag{U7s2YjXUDY$`sk@6`WF`9dWXi*>FK9+QdC1Zk7I~q%je;oeh zlvX%o`g4>VFi2!B!eDlmx25crTw82||K}9Zb1GUPci>}!N`iaq;Nak_1mCD1l;8B3 zoGu`wr#^Z`{7X&$K!e?N%x|={?h2n$r-5Uep9W_mSO-(xWhHB}TzA+zg2^7&1qo701g)X!h?RJAx4n~vt5l?6b^-}V5}Hq4HBE;5*A1jF4SN4)C1Duixp^!vK`zr|7p1Pi92F8K-TU zn-^zh%??i9Z6UQeaeXq!at<{Gho?9t$%o!MkX8$>W~Z#wNzWxojxG^qiKWlcsJR}_ zS+UmavixAge8U)%q95m%ra7zUE24YaniLYwZgjC|S6jRwSELmF;VYEzqsh*y%8%Lu z>r}Ust@OjndOQ9a|NN|m2>zpYCNalXzag{3EaM7f5d)4 zW|v{7{(Vc*q-z{BRFVBevy%3%JZY2i8$+DEUeAJoPyd2C6G>8gifofidzF;}>~RmQ zC*?|4gIQMWuW;MhzDMGh%}op$9*Z|=8B-c64?A2|Ha?+~bGWka3-(GbS%|7{=9d@G zw`sSyfwe)DGFVyS==m{(4sSka9S0LtP(LK@Od%Ev3!lY16WuGXG`*H%z~WK%mzJ^ zIwHp}smm+FVY7095$0PBnJ{yNtC51FojL>Af=ls1pAEQ~Y~La{?D4?g9NXOstD z6Nk=|d&igjSdT@;5O7fE${Yu+(*tGpP$a2MjCN0$(xK!*iJiT|$cLgkqHdwLxCF9Z z1=kIQGY2i*9!6M#6*#kV08m}cQno;dW{=kBvUt1vy#Htuwt%=Wmai{kIdi=pI&tL- zV`}dex*p{S6Y^)I6?w{ayIoC>TU;UBYk~ySgh?Ud+2hpHkb&2jx#;f(+8w~iyrdDb zw6wL2|2G>R&KwC>mGq)>$46*^sS~P81Oyt-2PB^FS-R;J%GBylwXd%IMLOt=`M?1m zH-^zdtLAq3@aXcmCqakJrph{p^nnpd-P_2%+ zxiJC8YNmBV%k8rrWcSOB3UhEc0ZMFy`|L`yL0Hy26=jSAoThfhc&NCz7?ztkXJ9g0 z^AQ?Ap@~R@o-?Z9yYay`KM!>Ik726hlg88n2}e(#AD=MVQm-h<>MEWfpTt*Rw`UM8 zB~{6UiGcxJGX`iV%31mw0U!l{T=;#;s=t!d{qx!WgYm`vz23)XWl`48KHQJ{j+rHW z;mx`pY5ud~#g*cF2mdn|oy2>ezP7m7UGcp*3omBVPdN0%c~0oc=oVPB`XuukUaj!p z-JjR(iF#kTQ}jn-GC328dr3~s)}I@Zr`cZJXrB%4gvVPqzeTXMg@&xI%IGiAnfN{s zBA>h8m~m})BSAk)zdh*neTr{|L9Do(zm}8 zeRpr8yft zN0G7n%J87-Wj%@qHX*jwz)puqmHTF`-}jeqOq1t-emf)L_B}wpIu+@(qF&CO|)SctL+1L`zAuk+sDFKyeKl!cp>zS}hhFH>&-84d_|_-mmI znTF2~*XLO)T4LcvQ}#ZWX$8LRXImSI z^s}8;b0{)TT%3UX95Gm(MI8y<|DN~@A8#K34IYh;WnL?R>TNW)i9_uXN+MK(8_A#? zL~U12py9W)CaggI{|a0jKjs6J}Vrq9mvM$Z%r(ky@kM&3Wx5@BT{SVH@ z_b<1#vFtGhPZmsspm*DznqOMuJ3C?NaRWg{1P*b3kC%8Pb!#?uuIhS>KU`eUphkC= z9`y}qg(q!Z;t^QCGhyW*B9@=K20@AWN_&+b^~uMN`g-s9N#@O&2?z*&n=6T=7T}@< zTiOVjYKLp0X7>-03sDelI;lteERt^VMGcl5%0> zJXNdB+$1vbacjMfm!-qoaKTV(-18EqzssR*K=Y}s&)gCft`8u1@~~HB)&Q52Us|fR zD9A%bOR@>qV^j}}IbZV>@n@5Y2*Kwq52QVhv>mq%$%Ds&c>T5-;j`DEUJGqi1pui7 z&`e_DJk+qcu$7=Jof=f%2{cS+Dae$G0r&!@2T8k#4-bUso;S+0)9f zYv#G5Nd}`7M#`RV*#$^H+XY{1sNdo}@pWR?tt zsh0v+KXLyNGXyB0_=DYDjq$je{KP7j%#R3#%Gh|q28(0On1hEWCSq#t)H%K{8Qu`z zFBbh2kuk5MgSX~taz_m%+wigHZx9FpaGu7hx`bwpigXvXL-l}QfV&(V8Hs3)8?aqH z{=hF%8TUcv`Wn+gtEl`q=4zCeuYZl;4Ne-E3VUaAJ~vtwTuq%~8DR?ZrY5}wVQ+3l zs3$a&r}k)7N#Zg0`?D=A776 z{v%r<1E6SqCYF)YpRa0ye?Y_R)=5tD}|WG6ZwTgGV=}tl14T zodo%f_Nl>D-H+RLCO=3OC2b{Df+}a9tN}X5A!#0|UEpFzq&Dl?Y0C}iw}aY5(}>B3 z>s=Tev|wACb0)Eg7_ua(#d#W9?wQrqLX0puge>jI@U%;vIb!Y358B#`fUb*Kw~&LV zF9s9t!QT^vXo*tLFH2d;L`LfP4MStC2uv0VBPfPfHv=d+d3lHS_KL0!Dfr1~Hyiwf z+)4@xoQl0Yxh$mfSjgTMFiFH0XN*`64h&>BH>UxKG4$6aur)0u$zgJsozY4o{Do9a zyHR%00(Y{VpXkUM_VjRmn0Vht&N)&Q6&B9+Z_DD|>M&%1xHc_Pl*NmjbqmdH2{=vWJEFK`}fV0ALey;R;#1J zhvTXYbwwd15vL~Vwg&{#nyOps1+^6$gwyftYR5oxa5}dDl9Af1@Wj zyJ}2>Jl;*rC-W_ng0wkK-tpFk5`o~R*zFPx6%}#DH(~bK!$DUo;>!B|)Rk+A(>hE{ zgm8?_JN_aQn=X1+u>vw0hnhT4b61QS7`e04vK<5jbxceWG2{URx?pIRg$z-eR9z7{ z?c~kD?DaXjho4>&wYL~3n;MYfuPT&^&6SVK?{_m6PQ*}h$RKk6GH4$RfT_2= zFI7*LXRquxbZO<9Ge(3xSXpW5vXk7+@-^~OR^+8aJ?R@5lVJI&n|oBG@6GxjK|FmuOfC0qwz;1EC4is9ymnj%0=#lOmE3!tIW!w38% zd2boy-mwg9m%*WDeyc7kRRk#hWS6ThoG|Rfsh>aGkQhGCU~j0_#u)=ouDvPv7TeH9?Yu0 zeN7yZU9s|wx&1>l$Xfe%LFUz!GZHd#ez)Y>Sn&|bUw^JMZN#EngZ7PZj?lk{9*9t# z!?s~Cb6R#@dgimLkB&LPe#9|;WAh<-a{iU&hB%!D{Sh|bJU-E;5)hGnY7$ zEwm;NsTJ-c$i`t)en-R85NLWM0I9LK=-E2L#AUOOS>Fd8*pGm6l7tSGfueduwAr7$ zQ0nZIj?vn`@hk&vqPxr&3<_O4CNAqBE*;M58{ z23*3vhU#>PG176#&st{!-hF*DVWdJx6q$zzQsHGhMz;0ygVVq`I~6(B^pdBF+^?i0 zelXwepOU)xGJY^Ws&HgPM6#XUoePHAehj0voJI>(x-b&oS_b~T%cUb6`e0NSxBO}B z!t87cWYirN+LUIun+x@ovSAL~VewR0+JUk2Yz$seZz|cR9aR5v3&`wDz^z@9B_?2# z|KW*;jESYQ%=@YE!_Lw7=mVP6KeifDlr!0ELYcEIG|;u|(@PQPdmmH${jGp|VrH_Z zP0kL;3*h3pyC~No$&-_+X1gxACNU0n!vW)E>8C-u#x+#pG1wUXZrT0s&k|YOc$n*@ zNNz`=Zv%;LIlzVq$%Q2)^#8!YdP=8S^9nLDCknIFJ>sXP)j@p)^GkJL-T~q(|J0)6 z$-BKeQEl>r>Mt+%;^D|6a{OogTT?hYU<9FJMr`TW2kaj}*`Fwt=|tDa7PtPznS1qT zS@h?d?;QM%Mr<}Fo$T)GZ}2$Z28KB>v9Ls}n*Mx_1VJd_50Q30W2%KVNGnapHwNwR zHraVaM87^+IMFCbvwC_gvLs=mE%p|@BYPuAK!YgFYDk%vigAZs04oC+T9^GhnHjeb z?jU3z52S%s1Ly$W(aZCYV1?F5P{WEcOjA!X$rC(D_;LC({pLx>s8YgKC+V~hU#eqg zW*(j{Xm`jw%0-kY&(i@E8@ZE=|AHr^G0B7j?gK~<58OKzrW2%KY;RwQw@c1&mTs`1 zl&G5=dK>GiP^to56%{+~l2A1EI6IVmVaHy0)(NH;fZJQ4() z8!8baPGe|cfL3KQl;Q2=N?QUH?xX(B;Ly*>V!Y8f-Fa4ayb4`Eh5;7U_~LmJ2)rx( zCQoj)Lq@SlZrP=7h>3Boj(UGt*yCMEx^d@U`Z4&6pdam4==#g9;BfFOU;y3h+2mWz<>K!6DJ2HboK~E8JUsyrAOVJVifZrm%7Zq*4 zf4}0zClM3d$=BgLoe>VmI+kR4mxvNF$QU*q-M92BzAWI`0?o9a*RB{q9AwC2g=%Ck zdr1`^*lV?s=BoFa#KOjDsI&ZPZ)e9s8!c2LZg4|a+ZSY5Vq;}Bfk4C`>XZit`R`rO zODpXm1U6~14-Q20%|P8wZ3Hg>fC1g+Qas9DYP2jkFD<`}-Pf<#1oAs1Ze6(E=lLH$ z*w^201z>PnJh~BTxtOw>3zps57{aO}MlXGM6)BhQunl#*-suF}+gC190&Vnyhac|g zw}rF3*{$v;1;&-t>qP~*$+5c}2 zIHY7Gn~mW^ppO~SHeksW7wj^Ii+5vyx_2D=y z)f+Te$1k%%=}~c%Yf3l3@CKoaRR(0hU%q6>i_2AsA=R6h5Sl$)#9IGhExy6rUo1CD z80(XKaHw&@z7$mEq}r3(tsg>B3q1 zI?>iJoE`DCa|9*pY8)q7_#%PB-%u2!&qu5-DcL1g)cU;8(&?L<2uLkfs|7&+!sz9W zk86|$WrX(%++UOJ5rJ97(rKutaC5MY<5zS5z`)Gv1$ll=2%v9LT3 z?f^BsACkbPDH5uO%a{|>CO?UZJBU6>N~oVa!H{f3G(?L9(1ujm`wdlKv$KW9EX*q9 zs}Ya5$f=Vsqm02?LU!E?jnl8vs=D5*y8N=HDU@or^Q-9_#Bz;0UNVnA7pcPCi*<;4 zbTB9>)(+uKm-gNX#&GU|S*Y7K!}=|R)m*;*PLR(l$e3y0E}U~l*l2ktCqY@}N;rm)^K9CQ!Wy*<@IZT*sp;4(1 zek1)uq|y!g1;0a|e27UhF#{LGN|XladfefFw7@YPK?NsNikO@{{-o&L79ruq2HM^{ z<}f2I4($dQ{N=U7C*73)T>yE}5EdccXH;0yemO*pJw9U|T%0%zt(vwrBMnpGf$y*@ z5piT%vQjB?1W7fJN8V4W1$Mu_k7!g@SU@0tfUBkBso`A{30d=Qsk2fU0Hy;HqHO~R zM^xO(LIbdd`4sket>@JD^;_l=w;E7S2IOJcA^-Zq*zA8p?EPfkn=EhMO(9o~*%eGR zHOo{P7KHcr!M`#ZW7}4m_e+Y`yZR}!PGbRYAU#2gAtKr@89*`J3S;M!&6`)oyBP~x z*J)e$2M{K-t-m*+^wArG!blGO&@KB9Gj&CVV2)*ECpgVn8j{qrL?#Ejq@OFApFbu1f z|M?R&Imu{ZVlqWdUEjY(&#TUZfH@r{3G@8yZ3~z@Yi}aG7X>~iciQQK2#N@oqUtFtyD;{Mt6LmmGpZ)L zYPjaW2*}P~u3j~_WYf~dI4e_h@%Oe^S}FkTvYl~C|Uv^m%pbN(@jNe0IN033>M{u3mHaBJ`I zt-0h+aS~%=W8V~wR$yymNv?@CP20jVF0O^QVW+S$4gOGdK_6Qj92r&e#Q+*96~ z#td|Z>#iddHF1FjbDmXBDmm)*)0FfE(R&A4Cz?FnT=%SsA=b(Lok(3Am7PaT*oJ-Z zM7+HGHWfjg0J+Bt!X!REIdn>bOh_Q`a<_I;S?F|q8Kwe;uMo?#Zyp)qnmG(J{_c@W zd(QLyW2x^a`5lB|O*U9i07tb}#KwkkeiW(eZm?d%y+b z(lgQ#o^{Z<;dd-daKw2)4c}mfeqPH+LNfZ|hX@%J*&g%~;r33?BeM>_8uGm|8mVBL z+#y-T-wvDsl0F&LvD>Ld2O?3`*nrC2ZmXYXa$m0);oWuCbzh$h2?Yh%5fj0pDu!~G zV-YCFY*tHG8f||CR4L8Ssv4V8DN<6N=*VwoD#5n-=XLlkLTiH%km8nU0Ul)fw$d#a zsc|e+-$Z4lp`|!XC6Pq61TbSEPBE_`g6sjn0#4+t1Kt+eFgfki{Qt+BrQ3x>ioe`G z{vvdeziUs?(-mwwlPSGe!2a3A?rmJVC!oo0jJOta7ebc|Et%01{rkP(X7VO+Sm17I ztIVKK55k~S@`!bns`8)qs2Bli*L;kh$QPk5`PJMTQ19)phPk5Ek!&MkO)1=jl=%e$ z+weBYHnZ*6fP!^Nk;lZ#bLF5>(vbw9YuZF(YoSoRx57>Y9P@HYeeX(07~jL=$QLN& zYE#n4s|2g%CT&6lH3uDWOGAd$~ z!^f+!_PsvvgrT38fQYX8P$io-(7)sQJW+2YG=1ZB@oLUE0wD78j_O1h}ll*-7N zz?QdD{wjNq?-y{P_#jyD1&VN_F}gT&;a0YNaCeyj6m7uYT$L7aDYU&uL+F+vvU>}J zCUVEp<-rC>z&KD(x-465;r-9)^aOQ(i`<*8E=iz|aCTNtG0DZX<9ckS@Y?ou;2p0^qv>g3DR1?uHJ7&Hy z7WK=5zhp^8prOdB2AjG5j(lILJVHw`oZ%IocM)80OV<#HRzsT7ygjM-a=bmJtxXhW z+7nPA)vOxg zz{3Kt)aEAkiyz5*bc+QmlrujmMl*+tY3k;xGIX>M^^LU?nZ zId060%aoy^ot}HZ;nI+CM^UNwg!<0z35mHvcQ{~>O~&;pWj%eE(Iz5&!*6*O<7v}e z<7-6vllKAK=c&&-Gx9|4<`{a_U0?FIK}01_i2D7W3E~#NkmVCnWR|AY-330awPnY#0yQfAQ2F zF6onRm!nU|>lECXu{SV0ZQJBynrTR3g~#C>1FyyNvogR$e8AJ7cQ!`|Qf~u%f_f;RTbIL-Hh={;!usAFOn|wZuq&Pa|1Vie@yu# z#Ikt3?&1Wz+!`aMyq?Dl095(k=G+CkpL#(`cFgI!)Qi|yg z+uC5_qug+`JZw?K1w5*NzhNv%d5IM%&>>He(~mwteiuL`+nHAAdzU`gMU}!;;@2G$ z;l*O=C6{lTN~5QG=M0T>jvOX^1ajvNj;+j4+`Bd#ElH^L>hdch>*#lrAgl9oAT2_RZfjZEJf^5v%fd(XX?QKmIz4ifD=rmqaeY^khDu z=$>c~E*Z2WMc^+Bcr9D-U(9#+Xo)YyM$Y_wltZKaklWt;J?f`I@!y63fift@8t+|Z zd(A`YkM(F${PqU_^5_}WFV$&dMA5M?(PG)g{dKk5D^g=Q{UnwOg?FW5c}$x|H@*jU zf(8d6T?ubiF9Z_XP3VgwrZ3kE1fnbT<958J;4-HEi!RRM=1WWWa`RTe7qm;K+7^u- zRlBY-)_YS>>Ztc+ew7$aB&hxIr1Z_&{Wp63oV zbML$0F}&G0z!kfmm>d^J>!Jq5cHVh|pbq;d<+|Ej$s5Y5ideL^13f! zE#>OUJ89{xPbF?5!U@1GUFsTG!TNujJ@=Q#idFk`ZXTO9>3G%Y?{ZH~0PiY&R45!| z`0oU^;`!%gUbHj=i^p`IrN*{>*UT+8Ha1@(=XmA%y8IqOh#IP5n3D}q+X1Lj_)|!j z>}Tff8P@CurntRO)XcvZx_>nBO(Dc4ch;o`gFIPzzDJ6~ zux89*{fc&3X|xQxe%wh1m=tq>hy-|tAI+4dd*k~K4FIPjAMBKS4h@sK*grj0J0LbE zYTPGEoVlfjSFA4m#PehvgjsGV2UGyj7SUAzr^4v30#u|9Kfs7|bPq7MYZYmp>V1xB zt-G*16-J?Bm_k1eR)qwUgX|8#Iv zdYZc{GSYUrCfF@1Dpd@!HGb531&@*G%@tnxEOenU|5H0g^zswer$59dU z>NVwZVdd6p?0G3I*(7}j2C{sS0wR3b6HVkH@Z$xI7yQ0oMz`M>F@Q=qc#uZ4cKGwP zCv^h1+LT~tO7Cr-o?k?Y(He8CvN;!-|DP0xGhM>-E4vH>gh(ft=0>e>(awovdCeWz1E>n{JwQ5*3Fv>Ruh9 zz}+PQfH-o1>kIBsO2jAIQhOo=EHVhU9O13iDevO+qi`J+3hYGyq#OHW zARlu4j4ohYmp`SVgU+byVM`l?Ms>ThBDkfI*YpozKxdlYl`J9Dz-6=q{4!^f)g94B zOyYDlc2BffX8c%tA#4F@J8=ut>llq!Mek6)gPA{9l2rOKjm>zvmJ`a3gQh&B?6u6HfrMMIJ|Q@Agr=9WAmm^O|2(i6Y)y>8_TQKp~TKt1voUP08eH~X%Z(d zuZ)7i@2?{I+i%b=;ZcfV#v`s#cBK;1HeA_sYtms`yS|zq`w39dl}1ZFA3nw)s*pUM zErm>b#$uul!WE4?K&CTESW@=xfzuPa6NQf&7IpOdH)9%2780Ot0FMTu%pER!waIVs zu3bCvVrvH z<-m*7*9V^DJB_uTO{j zJi?+AHVXg6l$Sb{*hx+dIdlA}1Sj-E59DsNg1e0*b7CxrP#C-$1hDunw=K%j8yY*0 zFl*F0Stk!YHBgaBHsN=f*%q~;SMS70`i;QjUSIHA{mej*XB(gm)3&FZbtxG}9arJZ zHf%n_M9O|C0*5L%tSN4#!NZWYN~wNobgWn&4Gj(uU={d`g2QqA@f|tc(xuZe?7tie}5pwW+gu?7oVfoEa~< zkcm1H=rnbDmsE|~fxEU-n`tT#y#E;EEy8`+ee9Gm6IWJU0-(OY4vVP_{Of;DgG-!I zRRqYU88uzqPr$~M+mkQyw1~$Wyk;;Qp$`z+QqQ1o#+)l%M+fJE25^1Xp5&l|^X2bq zs6>J(nBjI4F>&!0F>w7MjSkG*?~caJ486M=mc#MfHX?*vYQ(|;5ThD9wcV| z?fGJ6zLI{qM@w#_*FXLpNHy2E_sfzjqW6k}$*1Ux&v(=8ySrG)nz!DG{WAj%hxTEm{_^SabSK@uHPokj z6TbD&e*uU=1ZYRAjh}Tx7jgLqgR1az2Yuc>^=71f)~Q`GjEh60J8SsBGOBvh00~Kb zC|-u2L`lYs6e~bmZ=Cxx>0v?zXWe1x)di75J%c_bhlvKIlYeL7SgOG0;|z!u5m}LQ zX@xUy73GiIb)NoCIq+UpWYAR&-!CmJ62dN?teeC!OO*hF~g&?OjSEIzM!7Oy%+ord}_J9!$r1Z0l3*1x2Ry{5)-&dft$L>XpTbFBA17Qn~k*~uyB$x zIqHr2ekRITE^cIp-|~Izahdtfj@IYT^4z3KI_jBUM11_%NK6unGEE!d!bDBs?Y8FFq8h z>UbyZJ@ijxZH`faXOsCF?=c+|kfVoYnf%(4{;|EqQDX!T>@4heFsLrH+g^N4>KkG; zpgUdnH6QL4H2msF_Q=+jFsLM!b2F+StCW)cI!!bY>x3OiS#EJKAJWeywX3u{<*}co z<$ZjGbTISrwJR};+wq3|uh3=%5=ZY$=W5MqE2YJS!D~-RX=HUClE4o}C4>g6W&7Pm zY|Lt}OF86v|JRmekQPz|d@0=9}>~zJ$O1$p>F=ZmA~B z6N4OI`9R%4@y+G0p%1vA3S|f|qs~!}C{fzc8Op(`j9PeQ7xiQEZ|4JH4)3r-`);Nr z^WGW7>2tJ?C|EKMZY~UPjYmRK($@6n6UhL22e!awZYC~?CbE3B@4>wbWotlaz;S#g8#b@0li~y;}*;NcQdVlH;*p?e=Z1XK2y_+WyMEz zM}Rs4oT+%b)VaS$m=XLc@S8hFIQHEONa;?!bmtrp%!|#j_`~TiYQ{pmtnm0Mq7Wft z7&gh;Zc=-tN25Ud>rH$O6>UQC3=W6%mD}ya2gmobWSUwsLDq35J$-$k7aID=c*OUF z(V68Fsl)Hb+CsZmzae|@&36xrZA{QohnVP^Sr6;lnP*Pb)NL(IcXaMC= zmX7oEr#~{*QM6F-k1VrWBL-T?&6Gkj%nvCVfGxD*dxcd#F$BJ!RTq-phg3pZ>F*B< zka)#qdQ!lqG5QljVAy;rYV+r_BE_~_9zvgFd==!heb9PFDoEogw=VPaY}!0l2eak? zPFp`qZbADK!-w;;0~{*+vMQZv8A}F|d6~SAAsEPr?KZ=#Ih`@tD#-FI_aF+JU1N zV3H=kCtO|H9etcp)6wCr91Gpx>9$j1fVT~dyJVx%FcG0*mz)@N4|meH4WlpV$8d}- z)~=e1V0JXyrYWA6P8KgHa`5}GD7 zZ0hF9bq<#*8`OI--EeUnq@}2W=wpKEVhCcPtCZ(@@8VLvSqNCz#e2M{#-<6JdW@%V zx$SuEcv#HFO~gv<-tg;?3X<@e<6x#OyIV|_hTyEpw3$MVaggS3_&dtqo|D2)JxV&7 zPf2=i2R#)l^GKqCUN13Dnvs|&<8ob4_08D&fU5YA zM#~L6{nz40dtjyj1?H3HdWrd)XsvqSLdExNY^rc=@kyG=ncro0TU2GcP-Yg7e&Ay4`yOazBeqJXBmnEjeLq!Po;o zw!SG9N76y^6|`*C9d&hBncV&0qBG~go|%_Iq0o-BKmMWANl-vQd&s4S<*gqo{=19g zdgg?H)ULr9#}EsaHFdstLzaK2DL@ z$M8Bc9vgT`6qPdT6}$mNiO9~hSa>oCQ=c_I?T)1UTv;Y1{B3k1V(Z~6P_C;(#gi5P ztZdq2&-Tt~55`hkW|qCuu)C%_s0L&@KJPQyL1e#{)|@2nDhls-W2*9GGehvVx5s7( z_3HlVR2Ep(oRG9KkjPq$G4fWzTpFD$NzuGZZFl1Nh^Or7ak+NxG^mFhX|yGF>M)At zeNJ58D#bt&CLiZ@1?^s7nTz+Q+4D~|H{pNnKO^<&kBPGDb#++e2{phvmwScG@Ac^HVjy_fpKZeaa}8JX`~rH|QyLr5ifg^vIXudY*=9r6O` zOa5025P~G$#zm}!JZ74J5ud=G=WhH(9(D?E0Xv_?APT~;}a~TvGH$U`uBC`bPR0 zHRN5U5<=z`p`6P<=GuIqW{GM%Hr-KWO@BQQm7*vO-nzDZUQgfap~g585cXJ4Pfknw z#Q26rL?mzCywp}(`w|+jj>tnFpL3gxdMl;dT3Q{r2-dkMIc?oGs+m*r715&drXZDw4D!Yxk#VQ#mM zg^#@a>M%yr3}F;Tkd}d^u)>E^K1;^2>te&}``^uzxvyi2c567LCw3*Ba+5N^@|04I za`l~TlpFan!S|JD)?;pa&t6nwzKoHPm;hA77|57A%G&xEKm8$Y|BorJImrJb!`H(c zKFAKgMIEM4&BobIFc;O4Ad#6+$^LSc(22RzfbEE>kReHLTwENPPiW8RQqlLN%+ax( zYD1i=lZu_%k&+DFqk#cLc2?F5aH$3p;>bwf7qVzw25IeGW4a_hhjvCMMMAdP8{?=i z_gHpqwHF@#E4rd3u15f9#6A6hZ7 zTRbpV_6V99v_0fMp(g@?wne{2So~Bpg3MUWM1*qT&viaQMN1o4TkC8#W@wj9#hi5u zhlVGv^63-u>}*=R#8>gkQDcs`ZhU0b8kank)j#(W5=O|l-aV->#nyhXQb6jP;!%~k zXV;Dq|K)zg5owJwQDmE4cCBhVCP?B|YO>?9*ukpH3(S&v7-%(~nf!<=>XPak3!|f> zfP1!QMnIJ;dOFg6apKovvXz3nX9jx;M|OnMq`ZJ)$~O5ZT^}7WM#wPokbZQ=)-Xs8 zObyPL4DK1m?GjNflp_h23sYVFz8_nzB1}E-w@6EyiguV~%p>y52I^bWS5h@kj+}~M z97eWePDr`vnbvlYeob|o;gBIq=U7dfPt489P~kujlcZxQ1_tGq*$DeHVK#rP2MM_W+N?rfwhNWKajVQukN#9G*^jVLPdvg$7@vg8j$ zE(Gq^5J}KA-5NlKdU;T15iPWC!`r>JI!_mvc{((Re?#yyCQ*ipm~Li8NmBtmWBE_D z`KHXpm;ghKQyRNLbK`$P=ocv@9HDN1d&lSxnxA~Tb}9QZ2|5vvHVC!m!i)grGpdTj zsTV3^kr;oVzc33XC!#agT(`h=_x6R83(v*{*?I=YNm1%Ybu-{jo)&0zgJyc zpcS8l%1|XS7XDpYDzVL@`P^34;if?kFBp!5=z$0q=Jj=XPD)QN-G+~zR$w&ANB`6E zl}1M8#YGs$QH}Miy!dE=+b^%atY+AdSOt-y}nd99p9Ar6Ft(R-D{fAEM zOnL2PQ)6RFK!DK&#Tyqt-IpAAm?EFnLbRUwmQF1!SgK+cabp>B){h#o15|>%*uU~~ z;+hgL$%o8L0q}373!z1Awdsz(gJ=JG(cleR9>#S^TwR$ z4P*nSh`sK;ZZ0N6>7wr#98=kaE|<_5dVy7p??BM#g9D|Z4yvk5c0l39 zEi(zYU z25mkp7wlSXUd2DR;d(M_K_4)avm(N^vnN$#QezBex zAqI%EA)x%_4=jcWh!{#d;5+$$==#d2xWcAM+$}f(0tAA)TaXZ3gF6J*!99cl0tp&y zaCaxT3?5ttcXtTx!T08SzdgHqc9(yg;S4kP_U)&;x~jTMuYH$~AA$4(NXDOw#bjR- zbXnjJM{J9@I(!j+cPE985yIP80PINZPnVYKhJ{*l+w~Np+jW@%4sSjb z(}eVE8%rywye7vm#tu+v$x99Vc-I+4E)bKN$~?owIGwB_y;DL5K^`FI0T+(0v<=mN z?NdDJZ&vhhReC4iDN*41X4!A9 z8FxC~e`!W8x{3pm!eOkgLF-Ub3`P+r!=39UVd3k1d`l!?Rg{gLUBXFWp=1A$OUAYw z3(?(VmVJ)e*sMi)I^oK$9E;vvc-*5eLp#hO6@WC71sblp=AO#uiI9*w4PR{r;iGY zYwd}Ch+tb#F%s7N#6)F}-%QMoy7`n6MZ-aQmnY-WV$sPrMb-g2r@MqM9b7(wrcu~4Z$CUb?D@%^`$k1Utke?=Urp`v z=U3$X#(n!$r;q193r=A)^vFQcI`hB@jk21)%&8!8!p|V@M0HuixM? zN?ej90`l@^{bBlutGEm}Gaj{hf`70LfkB$Q%aqfQS?%U`-sRM!keO+WmaVO5Y`ViC zO^8~6v+A^PFdr}PWA+L#h6lg4=G^xgAX3Crql(9}=45$y^p@#$_BJ0H=MQ3|qg-6>`&VOb=s~91lcSb`amCgJ z6XpIT3H`g)&J#8&=gXbpIb4}%;;ihBSf0UGo^*B_7CKGX|4P@IxdlT3Ag!eRGLF0Ka2mTjm%<4)L-=r z1*r7pof4&c$<8QC4HaP(293-if#o;72d}dy$*?@TB=iL!x?u2Ida`JCP$z$_`GJ5! zD?16}Jpv<35f&`R_Q%PeT|PXzY+JS3LB~1lnaZ*>lAVOlI)f5b%U$IXQ>HkH(s4&Z zR=gmDbQC9;zrTrv@V7zM5(;$BS{`eAD~iGs`2# zaF4D%?n5{fuTCNwwwsl{zb$ebIcb6<>ENxU4qRBzab^;r;q70h*npQ@jkmdtkFIN> z%r`hMFF=S643l>^I4Td#D*Q6OpH^N_W5c7rOrH)m1j4V}#AJsIkb$Wl5ToJuyWBVG zlSQQoR_eTyx&|%`{_d>SsGU+ZGgUE0W`mm&;6KXRC{k-4VNC$!kI!>@TA*;emDr(@ zv{da<1++i?%6#*sj!OefNW*znYZMC&AtAAyi2F~31LJt~Qbz0ub%Ad4w=ljwHbdeH%3pINKw#K02%q~i0V|XX z3uP>$!%ZtVK!E~8ZX;-&gJV=flLZm)IVekCG9rO@WWtJE83uEHp(A&gQdlB^;$>-Z(o}yT5LI)O=lEaN#3PxjeRViv7`=@}kBEZAhZCNQ zU2zymA~cnR@t7kNoN_JQFrt85>WWg!^XzF<)fyD|QGQ2)x|77@%SrQ;R{mI^zYhF@ z5KmB(#G6Qxk`=jkkb17BJD61woh6-g#2{vqbQaGOidXqcS6u++#2oxaalz|JHs;rF zPz>J&3Is;OAL)6)4b}(ey=e?NK0>P8P=V8Dn41)};PG;7iXF{>d@@IPIPt34b*)SO zkb`${K=xUn*VNpX)OpH|(*AF%>VZ|ZWoJboGs<51US?24-m3VJGkOBH8gRbXWdF9A z4EFVe6D@N+^t3{1=^3KI^5qYa%E7Cz=Tpy^u5-O$?Li;dA)Kxw&;TGunV;-iOHMk> zepYW65$p>PS0n;!hRa{~0l@B3hCNG6(_)B< zIA0M6vd}P3F|n#E<)&BZ>~)CIr*x(*rR%ZTGZSE3{cjcH60UrP;+;qDf&22yJ1-UG zA0E8zUwkSDNXk_b4LeAzJ;gdn8dYf$tp{%Utv~(!tJMCm)@*TGQNCf!JsU)|;5*rN z!=aQ`7g;tZK2-hc^z_5Dm^WboN5)|2o(k=ZHj9X^bC=v#fj?|wO%0LWvav&gpT=j{Nrxx1Kd1;uXa!4@lmvI?b-pooL9X4>{p@w5xu=AQ;NkAxQ}?l$pI*StFvL7b zjJ~RiU+oZ!p4NK8EL15i`+iRXX|}bhybP6e3U}lKwK|^mCJ#-ul`t@)#U4vh%ib z>y-CR3o-a=PWEE>)zpEUQyo#Bo|3*#N^N&{t})zoXI~d#2j9ZkCApqd%tztnM#l-ZhFosqhNx zQBujDU=~6p=!4+23OEI01WDid6;}Epe4$#*%z5PIR#zc`%w{ts_?RP~z!J&xd({^5KJy{pSX+@T*o{-o6E0`D*st*4 zdGbMQz2RSq$+dZYyc!CyQF%~Q z^AaQYzy+ivM4cCuWno?KbHQgpPnxkpqY-D|u+jt|IY1@?;#TxLQHeGMxfV{o8VUPG ztLy2B1MHnvpa4ZmaQ;Z=Dcb32WyU2XAz`SX70N0}kqIyt1(o9_w64w()aLr2WUO|p&?cHI}FSA;NT;Yc`KQQj9Igov1G&9waB z5`rvE4r!aKr|`6i0AuesbpdG>73+J^UJrWC`;g3syvD!c_@o1*^jCLK{n9(^7r6D4 znqeW!k>-5Rn-3Sc6mUymgZyOEB#~s20*;WpOn&QsW#Wt_Ck=q$ra|FtjHZ!~f|joE zEe-pfdC}?AdtEp8H&q{lGb}3{UbhAH6M#IB2_?6MPPAZk9OyvCj7k^0oj1a?`0Z%L z1?+c?OA`3T(eWs1rv$R#vj(LjXzeIbX#g$fzq&h6g2fWivI$`LYek@}3Wn?-DWvge zapDP%rK}{kf{TZSS>zNHaw{q-)|$RGlZj{vP4(p?muPiK;Jvr5*=-t0mv-$`M^?92 zjAc)*5wF7eA%GNTS&0mCv+8A1dbe&x7!gy7pQ|FFP!?_X!FczA~CWN~D!QDghODo2r67LJwoVKC-joYd7#wLM3ssICq#{^M0!)n*!J|gG@*k~ql zkRM+l=_rGbn-D^tJg1hn5X#@QG=Ory4G2#nS9>5@UwKnUTlL zQDXp##_D)tGZzm4+O~Gtj!=mtULTM}4?AJ9Rh|LhOcFs!U7@u#j9g7qtuxKN!j) zXyD@u`O`&0JHh+?k=lbv+7Klm`G1vDpyw!f`U*FL|?xJ@ZlI zIxwKLRRB&>_FfssZ6}K1)q2!e(dIpNAzL|$GJz@@h~{gOdTCKlR3nGH#5HFskzsvX z(%RJf3hd?PV{WEu@-BHW!_J3M3P_{`wSYN89;;Cu5GP9?Dc)Lh2QuY(0){PS0`&g? zByKX@oN%PX4Ar3dB;ii$vm?TMTg!)JdRfdRW6KUyYSPxmAF8?6HEcl}hlZZ(t89^;grkVPS~qd~Ca!Sti|%9AA}xgTK&cxM1Fn zzEAno_2w*hTinmts4Jf9HVO(wg){*JK6yRr#oMwQ^X|Y+d{N*L%vE1D> zOO&)Mm;}bUo|vGxV825CMN4CNHi2yUYCKEGGU1tYr99xo4%Tr%CZ-34WCSY+9o0aa zPX8bdV0=6bP!$PKf~NY8|%yP@vsZ|};_tMb~M zidLUXA;X6O+453HhU$Gd81(5YNUXGzJ974V)UXitH~CtYkHw*t~P`c81%3Tsfx2rliiDz<-n#u%48Ho1Yankzn4_y^F<*~0jLCg?by-5fvO4>G(>WaXPo=!1ywuWl7g1%Po$f zB0W->m#jA-Jssauqr7Ax_v&-=D?tqtleyu~vgBnWo=0+NMbp!gp<6{EP)%q(uoV#y zOh-4aePwx+FbMVg9^+XF;9UHw+GZCBnfQl)|DNxB?yM-Z!UUXk6xs@WEc{^JA*0PpNs6^ip&hHo-*Y4K#!JIb6C#ty+e> z;uA=~w)gy~($;>q+)6_BZJy2%osX+1A`0?ADnw#w7ZklwRLB0u49V}?2LGox_m#)j z`19B4PKqiJ!X|9A4mvu+O1P!HOd`D$L|Y34Xm*F4om|GU8>)#QOZ;(~AGHAOyd(aU z+`FjR!FpcY1*N`l{LI7Tho?)L+sQGP4IIFPM*H4NrK0E7A@7vpJ{fF$7`RfS!wtt= zn+%tlmNp23X}5TOFaax&$LkK)+b7)ccrF3RfD9KAAr?<0(7s^*eTI$>iQxeI<${4J zf&s`{#s{BEI(5&JS{OPxcCNbS9t&!53Z-QHglgVu9{x!9C+dVU4ugOyrxOZi2 zPc62*V^fop3A;*E@!n#ECV8E!>66-qf|c2wT1xs7gUUcXK&bKcSq&jj;_pKsbM~T& z(xRxXx%z>H4Ih2A%sYB|ZjhnSzX@h9@RqW+2m4}NwpG6+dfdj60Pwjr4!21!0Vu#E za%7C#AL&4jO`%D1Mm_VhAclHeByb|D0TH1Bt2--*lQw!6A~>0R-zO9^ z%{@U?h@UQxD6Cc|yFFfvy2u}_#*LekiB_I^aR-t(dhK3f(o~>fYD#?jZttk7~p&D^ZW9kHJc?HjGUKA*GIUhD8b(QLmFuHXS#AHj`_ z*`4U0>!^r(!4ps!^j*s4*WTwWP`F%hFx?-Cr>8%Yxv2`Ky*zExtgg7T(rz98{S$A8 zf((bE#(Su;`o&osgP_#sF4bJ`ch{IQlI&07 z*XBm#w=YKaS~S+=Y0tOt=V116t)JlKer>aDM^&?*zA6*m<#WIqjQp_aV8yFhq%pWa z;ApJ6!!OqS*0Spvkd8$C{QEShbGDTjfpp*d5}jDQ6-)$ZmaU$9Dfk~g$OH&yE!@$>^`(zKQHgdL`_O2MyU@sH z0N*Cyl1c^kE8Y9UwbR)~Hm>fOu~67`mD@SIwew8VnD?0tWeV}S|Hr^dMImM}_6?k!ot@?h8nGje4V5;Oi9FY7Z|vG*I*RPK zyobjKqCrfW_k2!><5je&aU$wW1MQpcA@3^JE$mOJ{E;LsT%Q)K4&iD*hP$6{Nfu2#6EtK%QZJyyX6;}xx~ z-F(Z%YlJgSul;r~3LRxJU)$ukIks{yR`a0tT=)JF^;(RkoSB;oxtv^G1y)HZ3+gZ{ z80jHjkF3j|Lv4%q+%i@$yLZ(nwXO-_3`sXu4cHaWlWB1rt{!4$GSBF*%7WU{!?*3YR0O2snwBKVGa@Gmf#Ln~-1R^jG%i++bDgV7D+olYuI$)vjx*@*Mlc`An+R8*v=c&dj3G zjqzn~>XbH|_u%|tacjptm;A@u&tl2md}XQ>(h6|uIIW>9*311S#w$I&Bzp*mj86-_ z6b9o{Od2-8MSp&L^pgnW{RmlIAu+*R7?`hNe_9k_I7Ykhi;$Ei<)WN=3hEMNVG z{L`POWtX|0OyThRvWBmV5@JZfxm%$1+>V6X^4i+k6yFQ<4f80m9SoJWV~f?7-1vCh zx>PS}7vVh<&UOY9J)UGYJL2!6mv1O#sb&w&&tL5ty^$~!tKCiSK0^YV;ba>3m?TzN zFi2JZ*|{~3dBuy|7Fc+H-*PruHYFfw87!m^SKQkA_EC*H5oEfk?4Vc4&wZcg@yLnj zXcpTDka!T^>akJc7`dT%~7wlUb8zD45f70 z`KTRBF)^%{l{ObfeZJT(;S~`0PTAFJh*?KIqW`1kI5is;wk#nL3m`nM*3;3+Q#H#| zBmc5YB)|E6FiSFAskD!!R+^=D#>UmJ1ackD6gOp&F@Uqc$i{|<1}!R9<3$zb(H&w^ z!#>$dwOJaNQHI)X5aAVnXI$x2*IufA`(6$o9U}qVR$2oD%5=5ngu?t)awHlp4Qb^u zp#_;uDar*EbdCd9FRTZCw+-a7>3xM)MCyx?yB|nwRcr&Olyg}th~P{uZ}7!beSQWr zt75!3U_Ee#W+pAR8`pii{z4MEGJD3iH`)?DJsLKh=r7$}2%p~}HhFZWp8p+o<%4kh zE6qTb@7RMQ&OAj27T#TNe=ynGb|P&F4HgoTy*^|4NG1M$p3Y#A9}_d8`@|GXh^o*Q z9-){E<74SeAS%`m`CZCi2vo2XU;ln`cdz>%h_1DUt*(K39q6tJ4!o}!@U$cX;J2ds z$wqV3?%L8!?zF*%jxEwrCQd5x#uGdjL4Uqgel?b2Qg#G<9dS4I9m|DyOgwT!IWupN+$a7^qzP;3$BFxasOTNDTRn zkg{!wTD(#N0UZan*q5v#{Eon6OB%i0Iqc6rS!Cng{+Y)q`ACV0P)gK<2|H&e)~Hlpu_=ckFO zGl}gCiY99i$yvN87JP)DuJ|J~UTW_R?4UVwZfkfRr!OJ)pfAadI(*|qRAaDE{YiE^ znvb~dR;w?85){ExD91rl`1o@36J0nh^9}8(H@F~+7p}%ogF}ZfhJZ2p58DVX7CTng zuLWpB8s^lOxW3umnLQ#{5MsSs0RK3wTCM0&ZLy1Hppre%q?ue0ihOwEj)>pL2#(IOI5ix1)lvNa6P2aK?Wv4MaD^SJ5Ay_u%>Eu7}=g=LGSvHu<-ZxxtkpRQD zPsU`vRar9Ui;%RqqQ&!wU5s5VTdf@6GzP|F`7IN6mZ;NHh~%C|T^32`A??{_pC+7Z zYTa}@+Qa|BFZv?B(unlw-Rd&O1FjmtA1)?qCSjA{tHpov(JDHL_gt)g%fmTn^SE4R zu7z$19~ZtUzmzyO(5x}9H#-E2B(}5imvq$u`vhLjYwo-OO;yfl3%p#r4JkD1FvQF@ ztXrXV+Y{l&v{iq5vh(Yp;7{}?8*Ybd?bv^}dyW7AN+oNz)*0GaRt#Hfy#$NVIvg7h01A?oXK+L=E1H_6?N|J)9S+AcHu4^I7B*TC9T)rz;D3nT`_}kk}qtui86MZ`&%e|$6?7yCU4%4CgdtuedhKwUvhhY3PN!y01Bam=3YG3jP>@v96 zacDKw!M>Y|TX@m^pvv{mntFx&WFzLi$?w+CqS%&swdPEfa5A)S4La48H1Q=1Ekx#f ze#>8OR*qWl_{3fo7}d8t&t^Fko99(DLc?jDY~BRpLgRW>Gkey>I!@u6(8ONC?*5>R(s9CVeMnkuJE zIX#T6BrPKI#APo94RkCrj9KwKV#LSWughSWoXW`!@`;KP?Qo&(Cn6;M%8t)T`z+4q z5pyUYZiyffI~$^#i0uA{+q#~TVFywX1Tx-HE=LFUvmhbBmzK^lAscnQ!9%-Auhc{c z-0T4AT%|PrV89Zou7~^M=}%ThH7hcOCzMFf$5uu!^aaB>;noD8p_O~X#)!}Gf1@i9kXPK~2sD~t zV6(XP=XPjW)lU1t?d7Haq-~X9_uPtKtx2^oivd7SkHEhX3QR$S?Pk3|6Pao+_DjD6 z1+*_q>^sDZ|8PI)JzbAD78y*}l=*4~x2SV5@Y`u($O1FA?!1d7g4CF&p=HHQUe& zbF?CutXh_)#AUpBL+H&H7oL@(CA$#`pwZw>Ll1aHoO{m`-OO+#X}706%kGn<9MbRH z=}i7zK@?07UAz(Atm@h)RirWf3oO2JOOt_!dvH1N&0l5nuVihq$f@W}8^~lcajln4 z6*>9(Z-TSlScZw{h~rp#cUuuw-bsN$lUHw`p_>i8!?KFv1?P}VArBbzXYFfDk&Zie zFKA9geEYPqb%g6O`mO)9)bho?XLQRgoNomzhmuz$(+kh;5&Qr$P*|v9x0C^a)qeXu zKHXSGa@~0aK$zzpMpIXDER~g&6&AVTv;;UCaW@`n$&(4BT@mB;Het#ES1~em%Jv)= z^y^u`z(1&q8UnF5a*8tnY6a1KK!KtXP=~8=)Y4osl14m@ccv;UE332ue+*{{TC8Sq z#Pa>yuaKfkHYseAA`~>}4K8u&XU8jsXvuQUbm{>#1RxjuTlra1Qlh|bb{ymjl$Wd!pLr8Gc4<;d@UN>v$TJB+P!!8T3ui0bd zP^q0jWg8sA=cI>ZMqI`z$-0l9_>bxg4A54pNP(g*>3@pUkvyp^(IAtIeJ#xcZ$$_)sNS z{^tQZZtaAaU#@dYL4y&lO=csp4i9Fvgw~v7KD7u?+l(&FN>nS(S;&AnnzBTt)^ZiheFIk3&ZOE$V{GW8YsH zx!XcK3yd@`kZdMeN*6-T(i_ZmCR__b99tR5ne*FVCCrqmfb(v%IEb2EmzkeO-z7O) zY|QZD44AJ?J@>`W9V>U=_Q;>DPo=b;Vf8)QAumnd>;!$M+9(ea+&}W5c2#Xj+WS+v zeG#wF+#vSRu1n0&{RQ(#hgIOe#47l=dxZfeFb?)~nO?_c3rii&otW5i-iI&wZX9q7 zk0UO81WQyiQ8jZ2>8iwd$SVjpoVooMmKK(XB7OXtMot9j^6LdAiO;Xe^fn!hsDD)5^Jo`ESE&g2Q zi0I%TUC0UxU}>|k#!w9<%U2ynu`0Bk=1v9ChCuUV?rIGJYJFRUpqZ2`yd|KX+m&= zZI&DyfIvKt2GFL*$GjZF=x)yjO;=@c!=hWws`3~mP8`G_Bd2v+yvtfo&k zB9C-MhV4QDpI{y|)pBfG+k>{D>C(7ZgY3UmBa=BGL*l$01*uMeHS-2JgGEibp|`SGe6Cof4j={XfW31>Iuwlc5WgzF<^tMe}B zNqW<_kff-;uM)X%st?+w7A|KN$}<8`4klhYc|81il1jdpZ|w5jy3Kd)XPx5e|1yP- zr&m^YJvx{w`u-xWtzt?p08+cqZjF4_W%4@kSOu1hkckQ^hZ7|0iI{dwm&8X|AJZ3v zH)2RD0ZKFgJnf}Go9=%%jD6Hp)v@`lKrvas3hO6wh6wWE)`ctRFi>J5+96w#*btws zQnynaNR2>Z{6+;H{xV;HdVNH(1S9no+LMW5F8KB9M@!41v%Ef0%@$VCDABy%ez_~m zcFWbkZlN^yT2^%511dHEGsx#kXv@?KlZ4t4aze3O?|D7yOGaVkaY$Hq{p7B4ezUW@~x#V^hN?s063j$k5t=?OPL zxCrkw(KYOrUfq`6b0zSBR5JGKnrmvhPNh?{Ug-e3NC{G_Pcxa22ao;tYh7aA*+Uyj z;-SDbsH?B{;ctvuoLEh3&N!W*W`p)4DD^u7VBe5pXt-zHUd+nncxgGzk#>PhYUad$ z(et0iy`sY9%Nu>iei+wvbB)1Qy_xhWSQ#)X{EY))?q^yQ%12(UyIcVo0`R+fM_Rby zK|d!@G|$cwPtAAl$OT&0)>4Wq@}#+0*(Xk2OZGL}@vqhQ6RnYJnS3{$OXne%(z~rt zsl>g%!_<25_nB{yvL3^O{W$7oL^P&C|4yJyei>?o`2us%1MP7i)%ud$D%sub1`Y1psXJl8as0pW^7mLtPL`JFby z%wIaXUT#w(vPbI}Zoeixlce!0515pPhlhS24j%eOb5+AbvRsbKyqEq;ZqtH&UW-?N zQ-J&dfHlkH%=b~UYxCs5^+%p738M9gPCn=_XtKYChU$mFSVd<)Jr9G*fEVhiO2aHj!^hU1DW*U#Vb|H zUMJqrO+Rf`cxqbHiDRMT8)*(&up$)XgWM?T#MzJb9E*+;q**J4cs9g=SZvN;Z8F;8-ryST^kf*ux$>thCh6Eyp1@94ysdP!gmgIx+92 zzv`J;TvU*ek(p=GD;U`gB0EEY-E-K(q!G_s;g;)M_A`i&NB&E55OPn;u|6yUv^*Wa zj2P&CW$o`UsLvif-UPTV@nq)q1g$=Z+AiI52?Y-R`58-)tbsOCIbyg`C-B70Ut+lfDLB_%VWrGx=P5C71XL)TZ4cVDgadWMSv4Cya2!jz$(N?+b9k^!o;M(plWCIX@uDc zIP#+7ra+1cm=Cb!CG7|MH=eEkyG>Rr1kFIWaZSIc3!pdp}Fz5?lrlwSJ&cb_Ifq~njWq7ULsZ*5>2aV=B!VZRQ!W&wh5$v6ubS|uZX_yXG zDt@2B&-X0wLWroB%I0SmP%$l)cu&hXeqhx^DbQ%s9FP1o5Xw~16d2gZ`3{dA7vrhl zXaZ+{w*WC?7F%fs5yUW_U?7mo!x{EJxd5C*_8Fde`k4CtH6IxVSO}PxUFfNHue;-T z{|=#{7V^tJ%}QY*y=r>JTYqaW4fbid8i{_JUum9^L1k{mMX7-Hz>?2I{k;{@QcxOY zV+BOa3!t%8EW;^#ZeC!>i~{zfKz{@bx-p?Vvf;qu53mMEA++=xtj;_+IhhoNSxZWP z0!**xoULHZ>1eo_xxn&6+AkwU&rFL&3ubDy9`{EG6}n4#72;sgaEdhVhT!ZI3*Fqz zR4@A{HUyYH?#jsaa50gSIm`efFeXaJGWoO4$v1O@PmXMteUTf%T;}jTJDiqX8WUiF zs#%oxqC2xb>~ZM`C7wpZt*+Vx939$P6&e_ZOUTkuu-=a6>#@nri6KCBV7qgP0Br;& z8vw*9PI^beYSKO}_imlv|K8n}-Sh+Z5C+)Cc3d|}6Vm*Nsdl==fq}DVvN3N6eFSa# zvKt+^rbt({jt22848M3pgqzHIF*F87Pf+T$Rnj{(lTbreaT(3gpZ6(;()(zj4n+&; zb55oGL)c2YuW6RBSr=u(lbWYm0!v&yoa00owu*(l%#QJYc>rn_Yn8xQFa?=ucKBr< zBRj|Nw^Vp*5DinC1(YwS`Z96uopzfulG|3H73$g5kTM$((x37a{2bNG7J2L9MH3Zd;TM=r&3kEm4wA^!v z1nY&Bi6@vv6DK8EO4Y0A*IX7ritW?@BbVBR1yN!w{bvJcXPS=bjwGsbQBDrLgl~IY zjR@5;ToAKcQPgmm>xj1N9&s_D>!HG465}<%RsFx!TR!kj=+b^*d_|I9fUNoe*Kj$= z*HdBGJ4IwehGs}J@DV>hmrcY!4*n7RsOa|;ME$i9Hei;Y2A@aEPYi^+I_Jzy_fsOryi99tkQ&K}C&-HBaPxWYeWqIEYghv-Bl%C2L z$*|tu%7^kKGs+5^{*}vAl-~_3l$qm_MTi3@cLq*uy7EMW0%dEPvQL+9OWkdNN_cRP zsji_x_g_-ZY_!U@u4@8v-5jpu|3h`vinN@4Y83=f&c}ZaA}bA)Vf)V%NVa*xU*co9 z8@!%YFwk#ou))o$!xcHYT4VIW^?xQS(*PKpJoAuMbfqi#owQ@^-QT!_=&ZA9*?NYc zrPxmw(+Y;w;IBblrcECiix(0+Cm9&l6G_H@&hJxjndM(xYt>oT*Rcw65R}@Tko6K_ z%Ch8f=PWiYgVG27Xz=PZ>XyISe5f_}JFNs7_FB|qX$>m;MsClUOuCw^-A2C{aU$ zPs&jq9xPM7yp*=pK{V)CI(8vf@RTXna z7vMy?O_;zf9Ia%-p>F7z<<=4=xyImsr>57LW^guQr>D`l^?w*G0NwSI>9)x)z#xgX z3SMBpnT8xVxBh zQ|bXGO4>YC?M^nf_1u=L{DzOfi4ei9Hmsa=#hy8lZC(W~0jftpIhOYytBRqG&%b6F z1lYYn8|5}G2Lhd~^SoiR3@OgpO6#onKk{AEBR9u8bhio#D^e`32LCMIE-JGD{xhMW zC`)*mltOpW>x7;f*vht)T|r$RUz3yn{k!!up{~G@M?cG=6T}RDPwQP)Qo_`#cdR8O zk>@AV7?WUJvzs|_Jupz;XD`b~BvGKP@?b%-dSBfVq<0)|pu?#(o-!e%r?21lPnyUQ zVUH3%$QsN9s2y!iepkkgY`$nIt}$qVfv1?PmoKk9^8gz=U)$-AR`_&TO^#W{KWh$k zJ1rLIdV|C13wTl=0D>O?(YiiT&i?Nv zE1!4+p1=H~N*w)!YM=GX`<*ZG$)1fTT?+Zx{Ji|wAD~L(bz;n_e`Vj-qlh&NQ11WR zY-O8hy>M;73A9@2K&u~$N&2zl?)r7&>;FJX|CF;WcLEMd*_nk{zkq-kFoZD z@b#8Kbw%5<@W$QU36_l$AZ*+%I0SchcV`2^-62SjkPzJ66Wk>b+%32}yp?nAef9o) zUlqTof?77`?9tt$hXcgSWB_5p?rj601b}uN-zzP5=adtb26J_gX;WjL{c2zZ-djuX zPC=*O+=mRX?~u7-D!h-|}PMO&#wH!TE} zA5J3&=SQ$1hQT6+Eg``j!Yw57X_HyPm4KTCu)BzQTr((lDr+ND_uOj_kFOaFF_NEc zAo;sry%W^co@HiZhk;Ced$FnwhBO7#qPG7)T&~BR_kN>ck(GNhWPc(CYR$6UHNH+PF~Y6?RFQuC@WPoJ(I3)*+Fng(|&=PXfwhV~+hO zG-B;9cuG7k9fM!2X#qAQH5DIV|BCqD0nI(h>FI_}tU( zg2oSxCKVm-A!qnQ_8oC4eIS8wdk5p6OZ?&ytL)wl&FP1``pi$g{}N4oqkNNKHfJQW z!BM07nj`i~V@`@n_2!T)iiwdYML=u@f^yP_-CC1Ygj*O7!6OU9M`4P`UbQ`;GlId@ z72C>$XAESETx9a+EHljAtcwBcyl!eU^3pHmvBkD;O)Df{KueAR|8HgYpPnu_-q7XN ze=9ac+y97Q_UV~+T=xl;2s7ajqxo3B*Jz?OwX35pWUK;?nDboSvGY|aP?H~fe?5#V z!bR^zQQ>8KLh#Ckg5=StM*{1M!tc|Gt?=){W_qh8PcK6QE$*l0Abv=D?^uTZ034cD zosbJ1SKz(Y$?F)p>y~Hj!vQnj>%4MpduPhs_M4-i=b5LqKEK-Qo+9x51f{;#8GTiG zX|bgr<=fR44hR)r>fNN~YWqETWxzJA=I_Q7ZFkV#N}vdYN<&mo^#8NPClWzdfp@vsY;1mVTE$9$$9ABW4Hd=6k47VBUSTVMi2 zStJE80&QOpq4&l}WvMtkG8t33=r?s|rM>?-@`S?6fRC!G zr$-A&30XPY69?M9JEBS1*#p%kVR97J0GU4YCHB6GCP;cmysfQ`gp+QKt9cClR}x0s z5bTF?(f5Y@AyH4yf5>~<2mh^=-W_qV3fj!vrxptNwEGze8h~Rj*KL?iX~Ep(OXPdC zsA@>s4GMBbNC7}RPmrfvck9?%76nC)`n=nyEW1s#J}~_Y0nTbN4>&}wpJqB`^?+75 zz>f{!3r~ypK@T~6Fstg@6V@+q=H}*S;{vuI&Wh0stK#L-e>BwpHpLgpf*jXDu8)+? zdY-@K#{JxwGSK~@JGbNt;_ThWAM+l&cy9PS|F47Ju8;lBy@xz{lizz|R50+NCu#X| z^LdoAC9lnjVvypHf#Yy4$obJF%Rg|YfV^QFw$pzH_M)xR_yi{6;z=ywV)PX2jo;;K zv+tageWxX(GF4Zqo6Jl6)86VjR?5tQt#;pqqRmmA73MV-rPPL0cJp?eSIaS!TQ~hF zKGcfUYCL%_Gk2{!Vxm)GQ#szasvW!ROLJmT<^J}Z)635x5|zu*gQEZowE5>-F}7t$ z=*@6n`F>t^pw!yufr~nCN+CyON+Ihv?E3H0w<#L@pZhdXZy0HXsDsc0p1uDU4#}lT zr~Dq9*MEA_7pLge(FkSp&s}^1!g1jY<kqMGsMFvtJBf~j?9%iEFVWw|_-+J50A*tC2ZI2XHF z3Csu>DL1}-LuyiQp5^s189_PPMIZo2!J-BVmtlnZR5a`U>?d#JmFt7@piM?9+ab;ehVxd^9sdv!Ak@~NI$D`T-JR4xnQug?CaNbEU$sYX~q zxjR9b-JsS5=ZQD5KE8xTZ0)HVE|d2Qibn!v@ghNwkid%rkJv97KPlFPeoYO50L6(n z`W>2O-OXB-z6NK6Lzhpco>I2B%Odnt4_)<2$T74`aB5tF2rfaKj zVd2VjoL^+8=`m-tu}$l29`3XE_8;6Amr1qNu2y^pEq)@I$ejZTpYyMrFR7PWly_qa zH;f8>5XVakss9P8VTY1QdcES-Zldm~Tb@Nm<4SUhetAJh1jg|sW@btP_=En0Pzi?P zyK(+JrZIru^IBJ=e2r;$yRygX+mb(m4>18pOv+kg6SD{CqiXo9>{Pd?%127|a5U{8 zRxE&%DO^Sv9cr(xb1Z>hirvJuP*ZP%F60t9=CeY~2o$9q^_~kP!GGMc-ImfmK705#Enz6;Fd~}NbnNRq`vI7c_wTP=B-A!`56wH? zyGleOI(VxtGXIx)`kgXhb?`l=?UvHz5e@@(u&CQ`E?`&V2`b z)Oh?cyXw1XkGa+(<>uhQP>$u@iE{hGDerz*Y<#7Pd`$fsG|q*gte4aB-gip${Uw0y z6p*KZxK8-;;55%3o`CGBye@v$hSD_D{ZaH)pw)kT$*GIJft5CEEJn5xpp@((K~*A3 zbn9bi-HNiKXv|8sj@!HBHx&O*5TYs_2m+y(%P{E3vQkDlpX(#YS-K$-7QRrGem(H( zu5crmSoX&78a3+w)(ASUSJ8u{1=$DYaUtHOf;-$caS081LYhxa>i<{kM0Njvgvv=~ ztHj4T1apiD)BH#i8Lp*)wO^ZiL&OZkv&~Wcs%(z2NkhkIzAo@R2jue?uG1tIBRZU;iDG6 zFx;M~!Jsa6@PP|?LVjL=3o04rmtW3VfW6`{Xvd4~TluIt&kX?zh|C;bZl4`#E#PttjM6SWxA5me=e3*l=|z{w?&g zs-9AU6}-PRf4UZwzI!8rO3KU(E?Bf1C(=s8)1Y-ZwM!jC+jb8qDEWb0*gRh3MGts4 zuDnvYaMHN%TJf63=$s@w3cq&MIiXZ#77`us@KSo>NpsvVjX*Fmzc1SkytylCyU#l$ zfEAQgQYrvi!4wtaD(% zUTgw?7V>N4YQ}Jf>T#}Uysi&MVR7wj!oECh3bW|CQ`lfp4jCpW?S$=BTFH%zwnCPF zzVYkqZ_$`=lm09O1P9iZk$C9}ylT5ZW@tK`Cu_2>P6czblod7_l%2kv8Ogl6$a~hQ z-$v~3gIlq?zYHd5_j$41J$=ObMt*@~#d-&E8=fJVyeEMu3Wi*}&7ZGtECG9^>avIf zyl=V$1A6+Owm#S!MOBxtBbTRcEAzr9rWZMjUOht+#_(RCZ zL*i`wwee_BE=onmK`MEkUL0spn^|1^>&^91WS+*rs^e2Jki6JSHc^^ecf|k5>(ToW zLq2K@dt;Uq2(rpBZ$v#hm{5K@uac%@>?=As!dYPHFciYn;Ce`2B7`X!Ze!kH@t)F! zDt{V90oaG%&jW`y!4d7rdHo4@>0-T~V@vSLi-?~S<)2xP@6RGyh$G1sBhtwj#AMa) z;9;XBs2SW*%o*Q&$gZb%So`o{renzc+l+g*XY%d5gXN-9gi^*qa^nn(;*w2D6W!R? z52Uq9pGA@1h{E<8$Hu+$&ZuEUvtL=G+Kt>ASsCxx%V9nXcrmH*=vu2YJjhGPV^?lg zJYD2&E-qyP=HQ$O5mh4|XdCR6o1Vje8||M#(++#_ABWwn89e5OTYGqlhdGL~Kz~eq&nY#?bSf^di=^D;mCJ7VS<h{`~y> zZEHxLC9!zQdvR>+2UjitfRll=+RVkzme0%|_2M^pC=hHNdtO)WsG84_9+R?yP(aiH zro_R+zATYMuzyjG?y8K;mWELMfAw5{H@Xm8PS#Ek=<=ip4A|ozWhRyKnvwtGxhbw+ z*Nhjm${8M0)k&<;r>d@*TF9Z27&_g*dPmUtyo9xWl3g}+J>azYUD0Vk#83!spEr2p zjGX1OQMk=u;q8La=B?j=GYJU%PXDpsy7>~#s8@M@HBMPyEqrQD>&)`TRNppvTC1vWIvRV}s$W&G0)!yE^dA%bM@`>JxO-y*qb_Vvm+M!@H(yp)^OjA#ITws| zcw`yCQpTCJwXR=hY)sbBEn$`-b#*a!`?*NtI4S%m^YKrGzYe&KeP+%twOwtVs;?&> zz0S@?I;H8xNtU5g3t3!jt&{81>1!=2N6!YeH@bZ?;_D32Fbt z{Kdx-4VYrz6v!3*`?trkXWJF#*7eI8OL|E_b@2|h+7JA6R(Tpq<@}Bg#rfh-$Z(;Yv+ zGfcd1!wyFNBO{PU*JR8QSy-4@?^>X1oj|Gl;I&*Cy12+cf0#+B?E0m&^m9t~+O}0g zgU9rGXc1v>Y3@hLO z!uZ~m7Rb{7%8ls=N)+;CchrBt5j1?nXz#pcZZ=*g@ekPgetviZE@c{4ZE7SOdz}kc z=5==VlX=4djMC`5UJ!7({rJd{PgrESVR4sT^+No*_7`$~eH%dddM(F{ST}=H5rp)z z@hH-7rIn$W3J$QQf3cWLxoe8JHRWiJ^go!wH+3_OWcMN4 z4C)}eo7a50_$)3;(akLKOfLMGE3$cQNRU)2@BFxuuwK~|hT(Sqx0Qt_=*IGC=F~`L z09gg!D4MME;>%q^0)y(&0rY;@>p$uFrrT+u*#?QB0|iBcwfT$77emh@4nE+v8f^=N zAKt$swl|VWoU(j%NY%}$S{X6qh9$^Z*cuU9_*_74twE6|5?n|eB*o5g%l*sE-)j0z z)3Qd=ff{hAAX65Jqp3P;#bZ4zM%TxO4_}J!5L-!-r8}@KrxK1NK-QI(&G;VHB4v4* ze>(E7M92HT4Q|x;L91-W?TZ!z2nv!Pv}kQ^4f!Ffw~7!)cU>g9vSmrWwS%a@iMi!v zx*bEC?*@+YVbMnt6#{t2ge*UCew7;tju>8eN^y^j*&#{i(Q7ui!VT87rjqaxMoqSQ z%oi4IA=4zuvO!e8XlXC)e7kDdKpOvFFF>)i7af07bhI2mM9QOjoBU>jSZL~))eN&h zvK%#iE$rf!iQp zyI?ty2B|tbVVSmE=A4t87)4 z?^O-i*$R`c2h(($=e)pn$*_Va2@NSfHf3%4%Rm@Y|0tuXileR}<>yECvFl&>G6^t5 z;0NG#%D(uQx4IYqL?ds6&boR<%I!IF@*)w*sF!9ZXsBq0V5ibW} zjM+jhot%7;wSy3yLzNY<~dAPYhX|seYFwkNEd2K}OqAKv-W~q9@qQW%f z@F-^-oSd6~JK}Pe+udRCHrh*wVmuN|DL(2vvh!VOw{l1I^xy;c`YC~g(Z%LB8>ORn zJ4NEbA#BP9ElAvyqz}UMW@H9olqo&ME^CLOmb+3@7dh6eE340xK;DrPMhv7~w;TPz zxlzZ_vG0N8&sb)3IOYCwc;iC=q$bDkV>U4TSE`ETEAm@0N((z3 zYB8O7TRKg*%Rm$7Vje=fw%CU;ROFOUZ#h-tOlDzIfM^g^2D?F?Mclc>lj|2-o>>)JmB7 zD@)1Tjerq|YBhqTeI#Tt*w6g>&9QjKm?ch>Su1 z!@ALI7!RS&?=UsSf61r$1F5#l`_uV_dqNaTU_xb;@LT266$8^kTpMdHZvLo!B}1BL-;wy)wXx_G3Z z=uC5sb9KB(}pNRgjO@^MVpXqzy8kJoG;=3X4DC@fUFBQlRX zDt{;Rma1xGE^9}6L>|KNecVmSl&>RR$C2gMijsySHxj@zeN42@BP>lp&CVoq!uPz8 z>M@ok;OLEwk5>w*m+D9`%ZdTAOOtNjIXLzhV;2<_@jB=03}@htigM(2lR52=GC|lu zW)&#~JdpKK@_(y^bNdqZ@{2HXr#p#urMR7_=j{aztA=5(>*}hn23gsJ0|Sv)r|R*qRmN*+a`t zJ#um33XDzKrO$UjistmqwT95O&f-&lmn<hv3#3~}o+~NN;R8mE1-}=|u0-a=6pHnj z*Y^CjvhEfJ62@m8?c32oz|sjz)hphqw=V&xb2|5L9T3SPi~W6G8Vjr%;1SWgcfCHJ zq73x`dh68x>}>zCqxooG!-4z@;wU!N;g44ZCSZJV;74!C#3W)EMBZbhgqdnCt_B<> z!y_Y?n3(X(6r8pL3STcX=6w3)c~#gUNdSIGBl97~QUIFXvd~Zdv}GLrl(Jm=12sDc{zHyrAq~>^NVbmy7oF+9 z`NqJ6)QH$$-Drm+I16+|SB^JYk%>5puBm69CUfDftU8bOvOnzN>SEbwiat_yE6MWKc#2S-|x6y_87JrpEfyQ^}mC z0Fh3{OOge=Y?nV#{ONvvNc{C?XSJ<09&IfY=JB}%skB=75Vzsm2gmu?xUJSA862T^ zkwoeA=iV9wd45Wy(j=O(L%Ca!8LT}1-LWuX}sE(N59T|k3B|?>EH8R8p9epfjDM>*xRT>T%-j{*B0f}1eO|?5$ zOz-X?V&kJ69qvX<~Vt0AT_`t zw?(edJN$K zuV;o#D@i3?(>K2n8A+N3GD*qI&5T#Cz(B@f){hP!DrN2Hn5@Y#d*a8}ZIGp+nqN%# z3-8%SoLK;Xisa|sp=#33Soc}zyy^S?Yy?arigC?iw^vuxxKSW%xLa&KpIsB4y>dgV zTd&+`Pd5z2&_8un8L2|Q;+ZMfwFGgVt>NF{4(&^bQf;oIXxo~dHxK-QLFfqamlOcz z%E^acz}H#h4Df)wIVcCr>dLB(#e|}xqg{@kVvYYI*wm`a@jAM#Y)y+tGQG1aO>1;_p=c>r4a5e+|zP)=Ei0LM= zUUFzE*b7Fg_Fmw`*U&7?Zze7+HDyT?fB5t6XswOtJdVueKsj*JqqNgskz@)|e!SE~ zntl9A+y2%%E@M}oF~V~(W6-HUUY3=l|GvDlEE)J+j3HJFKz zl~vLT-s{Y@+7;G(q2pW9Av$#zRYSz$y)Gqwb$ERHUl|Pzw{b2`kXZUHu~NT=rbx1j z0RS@qc+%$+j=)oViwi*_foi|iS|2U=YLCRx5x9+ka`EZrsGH01hL-(SPH2b?kExD| zjEr4EM~9CyOLfCST<3ABf;P`uC7M!8Lqk6W401gFELSUzm{6Z~~P z*>};bH1DgT6&Lzv@JO)b@6z8Y8U!mV2I9lz)2`DAj>BQVXFdH5XuLCiePP(Byl___ zl+o%Yv3|3Nq99Pox!0+>tBG#?;VA(twICpeyLr5I@L5Y`>6$$-2MraAf`h5bMTRhY}7C>zLSnnF{%o8XA|4EG5}LIdme1>X%|!<^}4s z+vPc8(_wXZF!o9%YAw}AtoYvh{7#UNkN`>;!p&~kUqzDO zvcuSN+=3)o6hbzAx&}#b_sK3QFY_V2t>He5o?&Vex2qe%U5j=U6P_)+eH56{Ivs5# zfrbJQw`pVGi0=b**o=RX_!{SnAlb)!`l!7Zne9TblE8hWsji;tW;TlSRt!pY#85~z zmQ#Mjn{z%c@wkJB1FUl>SKH&zy)GNRGh$3L48rkKp5E^{rPM%nW@Z_yJyjEn7wd&% z8A>~GZZL9=4ju>_HLSTE!UMMyX`YV0vyh+(K$5+8%r-0ClC7v0uAU8O?YUJJ61k%| zMJ^4Ot0@gs0f228{eNDdP5p7>lFG$qOyuu*TELNvY5(yz%WS#t!zq*$^o?EKbp6aE z)-b>$kgw&(Gw)53hP5wYWPlf0dMD)XI*l3e!|h@9mJAZd^X_By-)yJg-nV=?4~JOQ zrgl7Gf`Fp@1W{FUCeYz5}xlpI-{qQqAcmD3;J;BcV_5L%>SU`%r-f#m@#)5K)EX2%eyeqGuv99h)Ah9M3F{$e!!rseanfhXAOycg0eBWPl&xqj_tPj|Syze0G^$ zv$(nlsaOb&7){0KB17+oL?V03fh+~fC>3MZ9~wIJ;<@}Wur~%P=3O${)%ldaf4}FO zCrPq{Udy9+uB!`F5$)`w=8$M5RrX4sk3q>a=lQsBn&XI^%@FK|!r>eI=q5U6h8>o) zjUicy)b|%M{JG(U3W6 zFb9TweQO*S=ytf=9cw=CC!^?Sv^vzZZ+oyU_n+|NXth9_J+I*s%`SyqV5w!w-{d~} z1_s;O|2o;rlh~S3rgelzitPwbFLM(2JG}eV1&4r~Ixc=*O7`w{e1cl@{g{beoI7mC z+7o!u5JB$sMXN+l?`WNL4w~(IxA({Acb73XQPIs0k$hjr;A@M4Z0Eb&`63UaH#Dc6 z7->WNsVnuAN!6kF0g8MzAjiLVyp)}PnR3X9yZxFRrNm4M{+S*usM$e~j*Dby0P%=| z@7hHMhFMnH`1UbdZ=Hi?M37;I)|h3T_(;e!y_5Emv`Dit0=yKQ+SMCZWo3xx=_-9g z4)cgu?aJEQ#HClg8eA;)7M14qe5Ivb__@L*hM#~6MkfoW<4JC?GHSG1sj>J}Z)VrzAZR|vqnSAx@7*|NYcTkU zHMs7L7}RNP%5{l{d5^n7cFDY3h;!rokK|0(m*OsiCG5oVgSM zpdJJ|aM!&HM6a%JXqrsl7t%pM%EmUHq+sjp}q8FI9V>Rv;u|$`^YNQH+s!i8K)9&sQkF&ap9YD{Yf9$ zo{8hJ*!!MDUUA-|*|+y+RLz*eEMp2iapb)&b@hdPd7{%?_Q@=QIK2&r5YvVfDyYxCO|Eq5Mv=&5BflXOHm-=2f49L#ix=;q#+ zMvvT{^ijq9ypyu+b~(|!sO2tM2_@qMf>wXNBY~zia+m1cjZ_{r#v%RbL9^!?!N`1a zFzym8@fe4`=iW+-A;oZj+gt|a)Q_Q*)4M4p*9HQG<3Iw{NEvPccjl(My_7^q_jb(~ zk!<4j9)9FBp7PuG%x~W$ZCR!!G%A$niT;)q9Qm}ULqtPyRzJ-TjS`l$1kA_Ako0BA zw&^LevVV#UHqhr_^QNXg*?=jvDLa+KeLE~WA6VkcGgq4}9qFsBlWpJZi8wl33ml=G z%(+!N;xK@#kbu|qtHE8K!a)5cdI&-EbP8C8Q3&!)vJe(P5_$ZnwwE*Fs!j`!40wOO zbx>CAg=kjiXDAud$OAmzqUEfY^!?DHeB?jceQZpzQT}r)4zv3Kp*J3e!L*rxS%0iP zpSQsMfB7SrrXLlTxXy6v$gYnwn|<0YJv2FsH>k7cEW4D4+<<^%%~*?U{18TD>J&t^ z+TvC9!oCY?3YnpokmqfE;PF4*sJK^OJH~> z5B1dzmYL=z4!M7RpYXaSS0;0u?oG`EZT+R8`|)3i9)wfz6|ByvXq}**?4hNp+yXYW zdolg1UWkhC6$<&w{OhmtE}o6;A?%Qtwdky%SAyB{+_4|rrB#<=-=M(W`h5fk`?j&* z#%#OxH%3VaYxE-TMkW0p%DIvLZl!}NjUO!f1{zLDe`62UAXX}J;c(WR9!we)3G!$6Z;n3l5_#we5KoJ3B z4c9q%UR>hhk^?A-bjcw~MH4K=V4tqQW4zHT1@v*HxZVxHvf9kE9{L%s8bwZyDEp}} zOgktrb7k;0jobLnZ=sy%h;h}9=-DnY)GCw!qa))h>}5+k19ABIeX{FGc+#@#G&5qOB>D(r~_nN_gYk-kNOiEI(=ePC_}!9=LM zPT46nX(+de0emSWQbtBpP1BLmron!uHN2}vJ1aZ%qCR=BA&%4H$6HqDzIBolx??w&sBDi8ZZ!% zK5{UUSQz}sdvKu0KA$d+GjJ zVu0hC8dmkAz}*XC_;Qh*oA#h+q3usYaQQmvXju zNgei-b?PJJ5#)uG*yec*L79u8Tw(UTt$1JuiZf3p?wqDvgJ_r_d)q-Xi(5g@O9z-kPxn_s4|u=vyL{f_7A z%6R4=s4c0Hy&*zpyMTOTxegD@8H@W53DBQ}i)CXlHV9_|ahp&Qgm$nu`1}z%qD8tY z#M=D$1D_@d_m}BA06G>F;6+LoiDT&=9uobngb`|4(2{Ifn`%iC0cIstTaFQ^jfCos z;kBNEyy%A{Mg80Z2?)|sKt}v|u@cI(e-s362VYxoR(QUvgiihWOOfxr@qz%F5Uiv3 zN~A%B&wrdgG5lfBbbXEHaGQX>o{VT=6QPy#$QfmYaB_Wfli$=N<8?CCvXm4FbhgwK zU(zaZ8TL512ZA#9^0K_4epi2zC%$f9HhL;~Z-5#D9vka06Marb+y&n{%)l`oZ_D%> zZ7(vIp@B+E3)|Z4rkA-!CgN=E4(-PriabU(jR|7@%O7?@j%yPT=%EGCVibjV~^Ju@zh|YF|VKv5fFK^*bw7b=8|9?tm z%hbbVu9V+`Q+iF^+bwT7MYyJJxjU(B)#SqeemK1+cD`A@q!DR7y}BU)rCg-s z>IFRaet7<#3q0Om&zc@f-Q$ctBP@8S9W3z9zhiim9q%dIPLxh8ONLtCfH#R8~8(g*|CF>i-GB^gIYmPtw{*+efR+sh*P&{iEcPmA9?l+OdW z2~vxKSD2ADvMSuOMGj0B*#;l}jG>-b5%UxH-To2S?5b$6Tdz`3P z$J5~5$k7N;;OQH4GV=wG)w?Aal4&A&ZQn|*?#TxJP)8j}r^i7j6yrM{Wxr6Fb2LhB zu|h~$h#FW*8%H(=4zYh~B_ND{CAY`3{;-r`Nlp9grg{EXUWi(by$g^4NxjRDS z^Kx4E0Z)UcaeHYgpBiT82g4t;qHL4_XKb*#)o7^6Py6#pPukET;NoSCYEdbKu zV$q8#9RA>2Zs&e6fPO%e8iJDOe9iR(_-F9~6-Ni}Tq9vPC-=a`7Klr@O1KL6lQlOJ zeHSpq<(KKXK6z2g-oMO6PWM$s^BPdAvaN<=QJnT3lSG zA8^w6(5+Hc?o04>3lEA4y8{Rb=*p^lo)k;pA__huWGRvH@W9~AQZP)d{dx)aM-*J7 zP4h5~jC(bFuY@LpGr*pgNX>3NfoZ+1VHEz;q`rZozivX{Pp@W( zVS9J(I)-32`5<3fzf1NJfM2Kq`QwWjj=9p30IWApWciP1<%5KB0b23CrO&0(X>$*} z;!lJrBo^aoH=*nfFtRNGF%ySH%n+9WG#kL8B7pP_T(5uW)_y!)A3EvKk~XpxYsVm4 zO}M$?v0r(>z10Rr()q?3bH3dgAzQ8sX+Y)%Z>?)PDNpTcsj3cPq;A8U*xU-UT7QUH zPO;$sful0Xs$fa~Hb0+4!7}X&ayugvx6O^r}fC( z0}E6J^TeX4vwG46p{zxn^|Z`L?;Qebw8?2{l@ye6Y^?WxeHBtbOU)hWCUfCSNutW~ z1J*K3P6x#ASoA;Nc%g?O@QttYfJ*f15Dy%dI9PSV?VWCIniYlMns5dhS?;|EgOkCW z0GZ$ZU`vLBihbV=so56Nxe7ezZ$Do@w0>O_k`;6p2uUMA28%YnShBRb386+=Wci}X zNeSV@W9zrz7KCUe1zs3lQL>6%O?wrVZ>_mpCHZm8y~o@MkxuPrk>xN@V}aU4{gHgC zG#iYC3!71*aVwuNiBc0q$vM~OngBy>xRjeZIuH&%c3<_Xe#P<>l>*H$F{`Zqbm(MJ zZ!&?qdH$GgGy0^wqe_M3@j{KY-D7=#1nkYLM*|t zhY2uc_X$ToO|lW^0@UNMQVQS%Cvs1(F3Kt@%tBal`^^Y~Sq^IRK@4dasT-B%@L~Hq zR@^d+QxyX)Z{cguC+O-9osSW@w}0y1qSI(W4~T?PH@t zs3M=9LY?~$Apcjl>YbcKVLbWjDKFguvm$w0%+uxEOkAV=&xtqP!_yHevznieyvI(f zqO!{mirrvmjg)ywkP(DfzyOyz&*@h+9*Mb2;PE6^vpPW_re`%+KfAM z$J4*s6*RfL{7Wb=FBZhXMLo>Q0vsvFy&;ADpLy zq^E~QO3FE}i@LEjBL7JyL~Gw8L$~`laL`3P zr@pzz6N#T`S|&%ulqFjWTq@b0`#!no5i%*g{s3q4I8lD~Jo#nOv}!Aos1{EW^r)ID z{4gPV+(L9b5r9opeh*^W6O1ZCdO?z*WRdn)CEgmq-2C-=B6fGEoNxaopQRPQ*h1vz z;6|t{QH7LZEk3=2JXFT8AB>8vUxT{=+l`W@>AWC-qbwM{g>?G!g^J!%;|uUBy1c<@H%DW7 zfoCgxENmmfR9*@;gU_jIzVV}q0{J9E2}5HTnd-Ibbk@=$Dm3>vGFkq?@E-ylmx+)2 z&C)2Xzm6&MOiD;3E;TugjEN)_i{*|JXsXD28sS2Ev{?|PR5`faX-cZ~itwhwn~UJFxaIflql)5QBM9&WJUfln9I8m21Q zZE1Or!z;(I{4JMR@G*gqJ@U6>p!mL1 zL&uf9@@>R+_rLKn{qaP9EYpoNev`X3pY740F<7j=rB$khGz zglp$R9Uj#$2J#gUJU%{K$$*NV0F%g*$uBapEK^1|C-G|!FWPGrNNdmo(x}0u>g>v^ znZoN$g3D8jpUd63O=fzDwE0dOhgo3HuNYKzaUBVqcn6Z;T4O%BA_Q=|H=j5HyBVEc zto4@K9e`rjCAz*vC8;lIPvbTa~w^BhsSh^wQ2p2(d*x~ru&OD8BHDVBkPk0mtcn2hbJBH13c=j)%WgTS<}~u8hh;etw!?DvwALb=W@OxtT}T z%;1F-Zm`!@?YE#_z%qJ+gce_luyC)Tj#F&j^*|wrjT!N_XPM^4nxC>P<#Xd}J-zK% zrJHaD3c^vE&mKx!RA#pHJq88_;8js_bc`m%FkBp(IHvq*=eQWwAj!*@{Q+&p<`T}> z4x6R)nHtsaN% zqi@--Mjx&tkJl2c4JbGtZ%q8D5#9@UwsJG(r>5sSulna$JIOF*{aO@xT{uh)xc`g` z%tq-0=B9x_K=Xc2nwH_vmG9fC^Bp^;{iwHjqCf<`gBBUjviUtokT3=gT98fRG=&u_ zUVxJL+5b{mT@bRPp+nU?yAnl0vDF1|n7cK+~{IhRL-Mh#V-aMBE4`7sPF z?{vj`WyU5S7&|lwU9z?@;W{SW4d}K(a^y-`CFgESU-B;3Z936KN59%z?b6=alQus! z*Ew{5t*OL$d#){2wP9V44*L2t#1e}CY#&~Z)4f0(1DjTFm-*`qmT)#^pf!A@-_4i8 zH*WtpwDvLO$U^ceKvI%&5f#@{>Xu4A5a``XzX=PyC6YO-Ou|7ouk#kh?b(_^{ghC& za$|E#{I;9ghl+hO0DcIIw@w;FjgR`lM;SxAO6a@Wq>bSBd9LA!n2xYOWyMW9z|ype zMH*nUSXqCsQ-RZVp69bmB6F{81LRu^|J-DL`n0@@G1`Ys03RUdv>;pjTErK}! z<62mgpi7Glb{JUK7X`7!H*jw!u-YAacyv86=jtOG3cEHw44{RHBZrAw+X=8B;F}-I zzeVb(#acoE^Kwikz#)AW3ZuXJ1%Mo~1P$r@e4f>B!7$|x4r6I7JM?8Y=ZGraEhxBC z5k}GxKWmra<2Iu{^?27O5Hu&Qe7U}k0V(imz?f2<@slt^^0U!Z661?XOVw2-9UqUN z<}BylRLwJ&hG;>9EH*ay2}Jfkh!T*>&533=2@>epaT7WdK&Ce&Wv(rnEuVu`+P7*- z8yhhJ*P5y>XQwz57}dy6MOVgxbFMRv7Qcm$$=wC|+aG6;w{Zw2hFl?;|hev^Z!V>asnn1-pYZa+mV4+EhtPaI&IyUpjKQ9y^ z`fvFOkSR5Ow`@PXvk?(N-S4;iQJGp0TqHwP-2=Z$=FJ;t>%>?DAQ7_s|#xKx%8)?$lz#m5VIu1dcxTsZ*9c> zdrCrfn%p%np+ z#;iKeA2w&_*~J;Sq5(EWZQZf$cniTU>aTLqI|khMf$;Wr@^oj$g7HK||A(!&jEX93 z+rNkIZWtN_q(fi`0ck-}kPhi?7}5b0q*J<)Qo5S~q&uX$k?xTAZ}0ngp7nls{Wwct z!QR(-o$))4lY1h{3R${|+AQnQ#wxOHsUj2P?YL1j7$%){_+9p;va$L$1oW+icL&RpsMOQ7((Igy(!C`QF@Ht&Mjy`8+4jM9S!>rbWg4 zhQ+z}RXA#k>Y$?91QZC~>(0D#av|a<@pTfLO)Ah8 zq$7}%5n`|yc&~J8MkE@FIGBT!+$R(v%@&7PI% zS8F$3YR`t(gfh|(uKlZ~Q6H?wLE2Ysp_rH?H?iQOa4Rj(VmFTC$6z;-01gcaIVU{c z!DtQx*$qny&C|uGi^Wya;Z=r^kR~48qbP&!0c^I}<<1TB#n4NFx5op&WD6@QR0pL9 z*g1;7oXG%{Mg0Mk z<|{I)x4{sXHIr`){Y~f2&g0VkIJ!NfYxB-kj*=*35D~TR1ZQyp7s=V^?PR$Q=yj2Q zu@{c|m@jOgQky|NPAIkkeJx7J*%GC70CfpAU^k9#`>@UZiJs}-fc}5s$^Rc7xx_7U zv701LEpcT%5C~{-q8Y`~Hd*kXOf+Vr<|33}ssBPWZ#t?@EJrJw;r&_pfTpRq!ua#V zga8n5E-*!M-D>sNfq14SBv$$tu8qp7u)E7VXX!~d?AEc4lcu}9i!xW3$q&FbG;WC~ zJm-UFz^>DI5ZyNZ)Bv<8P}Lj)&cp)li=x^BR-QrYvaiUYrRU@9`M-QS)*YYjn= z8eZBxY}LL5{~nd*hDrUrZrYbFlNna$r{kuDN!>r|W^|Oo1zink{t7CUC~<>PjRWo~ z-T*WAt?ArR#U?eOvy88;5*z@m_3{;+-x%r~jGqRcZoQ_A2mM)L%rr7U#gond9q+#k z7QjT#KyVtx0gJ7<7OxZCX9>VSa>?&vB!%B98cp}#`mDq~s+sGf#kjWxDMqwWa#es; zhcKaUOyFa?E&TH zmwY-ltha;1VPa~|m~8W3miFQcs_Cd_?h`nTnL-<;$QS zKlV;elFvuHi!3$~Znk%1;6d>DO%5v3+Lr`>P=olw`>-Ob4+ytpF(mk`YD1qGs7*76 zDa3anq9Wk|lqw5#50qb>07@^3)LDNaFV;Wd&@x22vM zO@DT^+vQax9V53S4d+A86y%+%V<%->9U}Se9;uo+NuX+TOG_i%+;al~*lwkgInckt zNg18DyPg60Jy&Jcas*x;#D!a-yqO0?lQLz#j46={Gijj6S#i7@fh1@tpC0?d6$g+39oyh*tx^ z)I7&~k32RcBqU+zDV<~EddSkrk00TZbTEk9&Q^QL;XiqR(j|@^u-sv|ashbEF5BNe zVD=9KAL|<-ID!_}VIM$arMfi)*r-)jV_a;jFWvMArw0OIrNJJ2qrZ6NriG@jHWrRF zY2e6@aJ^sP-=Zehm}?WF--!`2PmOLoT^|%}h?jHmX-YHpF^HL)Ig0f|g^Mb~mC;^R zm`K5OZPbd&d4Z|KTxTh1B*Lxeo78>3Koo?{07d}&h&I-{p;pgnpfc&?`o4|Ap@2*L zpE-Ri!me7Brk7MIm#uk5SW9_iTY9uz9j><&5kn_yz6(HR7Odc&@4;6xOpITaR|4R`0fNDTfe^+45bJozy^zr^`@A$a)_7;lkiiM20x3?!r zhu<&d1mY1E{u;s6j6Q4psqNCB54T~Xxg{pgOpb)+Hngd+Skebm)8Hkpcmvgmj~{wZ zGDq(P)!;bq{^~aCrHHI?(j=mzcI84lBT~vM#z^bN@oPK3yR`6gLT5%k5$GAFEn~c) z-snh!+0o8k!PEyH@?U#avq-A#^M^h=58#RiYRMN>od7W4*BZk4?G>A=@Uv?o2BQz%2EG-LqS>l;7G86H^pAz$n z>nLxYS;A|J<=Kp&+-f=+*IPMo2P*1)mB)cn*TzKkVo@thO8q#<2NI8oXw>E413Bj) zcw0UI1OlWMn<3A^SWnQE?+23o8Ymn@h9!I1ppti0n@R@(W<_pHtW(x;uBhvBBH~E}MxUqr(f# zl0g)cQQ0jaFgM>7slHF#YIL_D3=U>v8(ncXXdyucdBM~B0jUXG|J{f|3A};A`XwT? zW~%7FSq|L6cF67j14v#E89(vORCJ&&FN^nE)+Epgfmi_?UKlJVC53<(2oez$bvfTs z^t;Tbebv4P#Wa2%rMf-J=^VpiXx!u2%Xsvf#@Z!fi6rr){Iu1`N9 zH9llcc;QtaeKDE~%M|dip zVafZqdKelEqI9ULWLWBJq4TESlU0n}sbr~B&JQ)Ub?{?Xi}*~WgreOqyIEQAvO#D5 zwkTM(N=fIDRAGsrSS+lCuw5BTATtJuwcbzz^@Ry8nK#C%wW$>BIoQdlKuXv3GEX&` zQz@@jAbe&2!icWGgf$r#NO4L3{!+Apg{5eGtK)>HP2vr7$!vk%gZ#V^?!*; zzV*9^qkvO3NJs9hpOOM#jha6ZK|I3E5V-3q60|(OUG4($``@Gh6MJD_)94t=@OK)W zCmsiT!6SOT&IlT;?g{+xQs&H1{Tqnr+0rGOU8&J@V!c$5My(OS_ArW}lAdUcc|BY&HK z+XS#(&1~KpIMghgGBGyJ9_JfdX!N{KL_6I9$e?rC*K2}x+mJQSgR+K=UMeSdNR3=ZRHg%R36?RsVUPaNV0TuHKLQEDT2U~?YXVAH|E z2R{yDAfkUhd%F3(ZaD4RepVVD1fn|Kc`Js{P#S&)Lll&TkjQ%pnr#M)3#XyHDd^E5 z<%Wkn5rDywYvtUWogrT@62ICbIsOQDVP)l^M&yO1Ush#r0L~s0VvnTulhp4iCVnAo;SW^RF3I-J1s7!3~ zNoD%`#0~J=-T0j{zM_yK-%^85mxfA#=apDMN=~?ciE@fCqT_m5Eyl{D{!vAH-VNTq zne4f0I--tBT!4aVk*HT-fmXP=&%^qsErDWsPb*A~(Mx9qB%)gRyIeF&xe-Trs@JSf zga946FiEt<`n{q}}hf?SSG%1cOpwXre6RvP55P2=}`+nSD({ekmr7 zjOQ}ja#wP#Orpsv*B43!8qw`cf3$rrLaYX~%AiLjo^F?jluQ>Pkww-GQbG>yn1Cy( z(Emjib^u-mMbkBi9ycPLK>I{bKRwTdIz2D{7Jhtk=bI_a!fDS0Yr4#;)|)JjJ@tyg z2WTE1g|0Wb=jj9k>>=%Z#t=>0+E&DD8}jaMZoHhI0rXkM6&s=*4t@NF6qi=j=)@>h z<`c?GF3a{Dcn9BDwI=*eS=;|kyNIpEbt*{FCvjv&aT^F>4MnhYW&b$=hTy_MBWNKL zsp|NgF(#Y7yQYWhhPS3H%Umc*D=q{99fF@%kcuk21%lm8L~QMdZhrx&xGFNN>b2i~ z_RV^nCV}5+ng$r!geCf0__fw@1nnVZU(c-IT6+U2J&Ysk)2Y@{y%`t>_~fa9G|+Nr z+MTw&)`s>;pfu-x<4fbNIPWkQ2*wfJfMaH^jj^NpVZwqv`D5$z4~^Q6g{Tjjn6{)J zHbto{^XhFRC_haFtN%!SYYLWVbbGCV*BUOG4jY;o?#W2XhnBjDygu8vxP=Nt$v?T0 zKiApehswQ|8Dwbm)53WTSanswaNzH#yUWW$&)Pb!*RR@Lh-KdBw7GJ%x7K6xBk_R$ zKKnmouRgwu9|j3&$vWcE9XrVTgq%J!ILfrvD%`vR0Hn0oWLP?lf;3HJ7!)5I(Sra> zSBlI8x3OZp9VGmgB=;|CTgQ`Mf(NPeE^sOINnc8_J_Z{1N;Mna2pDa1$Rc9;Kz4{Y ztP>gIG=+q+9KP?i&FlE?a}@u0`7e1*{_rXsqp~3`0A?j5KVR-{&Xts$EUiv_xY9P{ zR{4%wz5zxG`3}fd2zE%NcNIi`4SK3qZw{lKdXJB_L}^2Oj<{Hn$hXw>CfRsc4|qaA z!KuT=iG;E$9fxa{r4~&M1e7xW%K{Wn9NPf;rtirqHHc81jNMYE!MX_!`FZE`)NVSu z!dhl-)=9@`v1?)N35%V>tvzkWov5j*B#efc|MrwEwv_?d0Tv7_8H6IZS!F5HZRrCU zM6D`aVEuTqZb-WbL7%S}Ia&Pwc$QiuVimY$ zys{GnvWJ4eRal$gx%1_a34Renf{lh+b#*{~e_WX?n%i z3$5P#ARZ}4Gcz-CDk`L$JUY;!SYq03Am4tBVw!f2Nq~h5?q`=D_Qpa1wPoZ^KeGex z!VpA`QwHXM?B)y4g>oeo8!I}WXTBv|Pmyrm(vMtCfu(QBGF^=91Rr}av^Ij?_5 ztR9PfR>eWY3os|ORVg?d()G2Tx5AI%B9rj8(E;rS%|h2_R$4J)%q?a~XYGD%Hmp8nyQyJ)us#|eB;$F&`I=5%R#Vdm>1+=6}6A#To__j19= zv8(SX@l7*RI8JghUE4GHQ>_K7Zf-OL^setydz zL2$E*`gKVwOj_T*4e-*xhQtGbzcpHhKS=4x2r#$-_)t3t#E1@OV1QLV6+}v%;JA6b z-15RdLi@950xJZDOx94(5XEFYorx)g$3Mv*w;;&blztDYNiq1s|J0sv{Lj0mZP_+ZrAEbdvp zUI@bwc4G9GRB`?OY|KqF=2EM{K{|Hyv#qV|s|*9cgDxG1`n-KXm9pLjFacI&6z9*{ zd41|z_eE}{C8-fmG5WIFjAg+|2;#AUqD-Kr9Apxn!@=5B93}QQj#NC_@#NXlEfFVe z+`(@ntj`savJD)gg+2393#4GHl~t}c@_lhjG;H@n1jvO|wv65qrnTj|LlhAyKjk2U zT)b8@a(tscj|$HjT4K4Zq7Wa124J9*`CD$~QGuN_Vs~LrMx|G;B8uVL+X6K}TO?0& zmtPq$4fOA$@7fse5=JM=r|2l;3r`B*LJA=BhTVkrH3ZjFd00*2ez}_ z*#L^L9m*-?32S!^ssZs{4*7-~`v$k)9P*N@%TXaAVYMcUI9giKZj*1-6Kk>%bhcUb zRqoa6_kezz3SC?=DApMA$KMFyMb>sax5(aOmU8O0u$4;P`$|viJ!Ak9UH6r51Mdfz zFMsm!^;I+O7zaFI+`eb0?{BA!Sb8k({R7#m6NO;uL{U*u>(eEgYQ!ig2q-8!uU;a6 zih8TnYHUZN=c*8U8XxnAP6r03W(Shij>q1cioDOD9AXe>i7>pOk)B+6v_&pu+;3$5dYMw?w!rQRxx@ro_|WWXnkSfRB-Vm zr>w}tYyBqHsk2ckvd#1eB&ayg*Ys>!SvM<69j!o7O0=`n6@p0Fp|h|9m1I^e)l8tp zM={{@aP7~pRtTDZ&+@wUhPWDqU@72$&`&Hkr^1nT<}nwq#b_T$K+B}U=AoAIr>FH& z8E^puZx8CH02hSntC!bLtw`?{qc?xQA}AH0^fk_U3C;+~Xg7nN{Lzz%z&h)e zIFg&VMD+W(On89xPgDOHKF3zG9cI6BD1>N+{89)p_e>$#jv zJAuQY@PZ24?UHbbzLE|hB7OjsJ~ZEPQGxch8hkw%f&zd?|HZ8TjSMm>bp}P#t~MV# z>5eOYbOEETe?C;lLfIA|^@V>OTzqt8Kay@cK)wlFc%Q$DOX7`B()8lT%8|}l?r`;E z#?2GN2v)-!jS{PvLUVyOHRQuf^>N&=-S1Hg20E@=7^bOVqs(!|@bhi<%1@sXF0V{? z$CDFp*AcMKLtfXSO)>QWGo8uFFf^V!5cZ#Kh3DZC1x1YphuZXf)=*x40jbpl` zZ^W{lM5u1z` z@V@Um0NJu%ZRfoC%g`w(*%4(4IR~MIVO3D=Z=>&>Nc@MgV=Ui*5V$x^A-AF4fz>>~xwoK9nL;Kg5frZ%bm=g!bKE}|=J<)=l!SARl(Pmqv zFH3aY3wmR}gqu|yb}xJ=re&k3#Vg*U6$^{RBz~W0qC5KZuCo>+>7Bf;J5Dq`779NR z{bx`P-RI^MME8-{z)^3U)IF~@xvf{!_d5rnRoqO;Y2icFtoA&~QOY?8t~k^!yJrf(&=0TZog{o=$1 zPWI`Fu>Ge0pwZp5;2*&Efo1?lMmivdWHb*?3W$a1;xa6=hE*FH|0ZMrtEUR$s7a|k zNT3o{5=g1En;lg|OGF+XN`3$e%wVTm_L| z485c{Wp;KD^3c&U2+b}vw289MwV&!a;@Q{Zk=Crh6={L0hy2`RYib0KF6^s?$Kho)C>(=!IvI~Z-V)#^ZJEjqNDSQiqQV~ zWybcsOls=J@?=y?|dhH{FMc5tz~JQ+{xhE;cMCk zI2HHT7!>g3TTj>TpT?rBi`AKZ0OfN34(Kn|~!L79F_l)|c>21)feS<}YP5#f#?%M$tOdlSRx zBK4~Mc}7FVH+mf_=2G(6lTcE2UjW$|lZ0%fPe}W7?9X#ZIfEXF%szYj*kd=iF3+LW6#_ z3~{C+DH*No{d75msJDvrgqY6O_Qaw0T6DQ4l|oUDB%N4*y1H@Gm08Il_K#*O5xQ}0k``5F7XVix8lfwBDXx__6 z_{E~UNogvYz_W)Y$8YXu6{2`r_XDluTd78JiI|?V?sHew`)|Y4z_9IcEmppx8dyt@ z7%VF*do01e5St)4`MCEzvccY@GB1xXOa{=U4o)m_tnLqClYig##3MwIp+L~PTw%)t zm&8ThYdJY2JnvFW;n@GkOt5@>(PA8kQOumFvYBdCuPkCsaKzV-i5a_E7nFU;^b?uE zpS2bc3bArVeH_a&)EL~ILjlIgVZSp35{d&}v74qTyr;`lQTnoYc@Jb(@MW4`Q<*Aw zl+#EN=3Ndjmk!%Nv8)reWmuewsZgrLn*re>4J2|(%IeH~{WBP_aM zBS%2;tATrhaM6^HcB~U%8#I6qNsGDoDsV2B9u;rs7f0bGNq# zhx6eq2UCELsAMfU?C#TSP%xV{^F?^RiCU-<>4YOjMirhtloR`4YpOe+F_Y*tZlb4M zdu({c3CEj~EVoHR@8AMU*G+sJx&lN(zwS@dvo>!ZR8=W<`kT>u!5g1eWIl9Zoj7YxLtQNm9)eYvE|Q0m$J=UU zN>$$;*EIxs%N1$%u1e}Um*RG~j@SNEF`0vCn)7ledJ;1t`LSxgcMiE%fDOjVK0~sB zO5FZeHpx#P$l5PX*`}E-*EWB4-*@O!c8B!HSNf0PKV7T{xtJIsT(`}K(i5-ckzjCe zf)@`nkc;c$mq*>dglMc{j^Y>Q%(sq_T30*A{`kj3aU78E(BFV$n0WS3 z`KClht3bi9i~t84$XA)XHzGX!lNAEcHR4gi}*IAouukF!k+Xg-W?U7by5UlMA4f0nAE3_#1Ny5hN;;G(W1M z8%hHT`h5RmEcy~~BG|Ryh;l70E*_?SAwuossxw?;yblf>z)w}46=V>He|~LEfPixj z%BwYr`whK#sc8GboI{bqz3ps=v*_^$nnaakFyGtHwz-{vVc&m5=(xh6s0hkF9leth zc}x4luvTEy3#@1L#sy@eV~R!=9?K${Hf~Ix(gJ0T5;1-^_k@9XY~uJ1RqnO$7OLEe zxoeDVK!KOkPO}1xRhK_kcBy90NRJ{*gji<(V;Wi<%dG(1GIy#@D$Udq>dw39sm}a#M0jvl4HdbBvb*$9t&hU#(kG0BjP?c$q%3u{DqY z(}N*pvW$x+PE@QYmeA#_=?waZO%7nL9etSD@NX-FLZ1oz>V6WRII>E=vumJ#Pf}Xm ztLnrCFXZey>#Apj8nH>1azsWX@K;(>!X$}}@B2|w&Ta|pU&nSaE|SPt$y8R!AmGEd zozjCFs1M*u@;;~Oj8iW2g|%GCI~K&hK6~Q;+X;JGX0$i4 zoG|j?u9mDRUh@nO29U^;j-}Ah?059~!qnf+&}Yh7rAj=S+r?%E?=hEJ3u(AdM34Ug zydGKMVv&rrAtbT`>672wqhT)I3NuiKjH!M!FGS)vaGQJQ6nnCwD=`W-;&C9dC_LvY z-*;_3L{#rURc+o(xSF|t&DI_Y4>>MbKA=D5OPyF+zvBXxMUa_EtKtbF7|;s|!E+Y* zTmc~k(kAo$I=i9cRD?!^r6g8N`*b+!7brroCB#RoOG7`NT==5W@K+}*o^Y5)Yn$_Z zxXjz}+1XH_qEKK80u)-82=xg8uY&t^K86E}p1}jz0722@>WYN)IM;l|OwU_ajl^P; zD(}Q#v!FJ)ACt2dcCfA~o>d z{-#{vbxvvAUKo@G-M|nK6vS-02Dr^8gU}GMpiVksS%PD^ZPHs;4O=-ubGg@`qA44o z#ZF8HJKgjkp-B~As2GNGNX zsQyBzUDPOEI71!2QR4e#4iSzA1G?wjnv3G`_UT^pOo>u|n@gWKUxYSK5FI&oUPp)V z9}(R;+q&%sm&N1-yD->ot-s=!689472wV!LYHZu{lbAn~5j6Fx-S)R_iR6p6-8d^F zb6UjPt8GAoRJ?!O%YU)6EUNFo?hAlr)gNnyY1`V7=gyh3iDZtd zE^Bo7xQW6r0U^V7&y(~ndgFmo8PHKE&*oL6sUhJw%k5o3`Z-- z{(UmLy}F==uB|C1avDdnIK2!F#7h;@=&SPbBFnP*(<@$qlka!+1$uk0af?FZznu=i zInmUj|^FLQCw3jWSF7CXb`n$X30tmUvIGj!QVw1~hYwvn&@ z>;CslmBDW|^z;;=RR4!=in}RSUr0_K-P3QH3Kb?C*a5H<2Elx4jgL2B|A^v%hLK6S zR!&I=n!tb@5G1ZDG4-O2jgTzUYIXX6di z$(1saqzoJQ>)d1g*pFIS+hm<9C5a6lBwDCyA%l3IY-uCk4_emz^S;7eX!ZzqLku7E zEMnYjbY5owF5G|SL?zB;%MhgwRX2VbhTT${Rs^^k;0?bk(AsI1brz)b^$^CxpoDaw zh*vyy&3rNzECyrMF7C&o<4?7h1pE{Mdhvdq(i!y$vK#@eAQHEsPq404Uhwr~5MBGC zc{{MD$IvMy9?N0eDJA4za+4AGL3HF^gMFnkmO2jd6HSW#Q5z1o85?6;W}neNBSZK1vQVJ2`uP`s{CvjtZ{W?m2h41_xBmy_xL$s~ zC3yNf;<__C!phm@<Da?$X9?49`|-lLz~xBQ>3j4>R(4y+ zNi7;ri=*Jv)$@BZi~fV}es?1J|2zgOp0nG$Vk-W;ym*%Q`*~|C!$8H61>wyb1#~tP zjhtG9X;K*_Zd*IqvivgYvZse=uReXNQvQHG712KpDs7ScqdnS3b1r&EvOjAz^lTkU zByDoG3DM~h-W)?>x3*%p4p(XSG1=4GZswCc=51znX^og5f4ygFW*7cuw5{x3oT`t5 zgo@~hhj7%hVpD(b#7;OUeSX)vYze6dZQ_tZF2eu95lW5dS1@G*KyKw#kM*yw5Wn}s zc&Vs9MP)1rsKw%-C{bZV$SY~q_9lCpW$V(1~_l6R!xzsgoS=q*P zmz2nJNFJ8BdK|898$3I5sWW&@$6<~{wx1IsZ)nZ3I6mID(KLQpHb+qZB^8#;UZJbp zz&kt>lWz9)2dDq2Srr2|E-rd-7lM^!B2{eUSD3@mnJ~>u_VgX%u_5L`+`)t+W!dMY zQegC1R{eP-H45I(@)K}|~w=iL+!z^r1^xYr2kA~Jt(&OVN596Cn+1Sq1@j*foYmu{P*9@lA`ACr*4fV>rx=k-mOUr&2mf5q2 znJH&+1#|T6GpSCfKzmbw?g40cvHbk&{;MQ1At4Gn;y~1~3`J+BE9I>oi`b;u(Ck*b zpE*+X<8&rC$^GS=^Gi8)1DksNm~$>}qZW|j-?Ks{&d#8;LX5B@59-^%8ktVD%lior zYTy$mj6LN3TEuf`@1>jlCM0?Ns})It6%`~YCw0n=t2-_{dZ5dH)J7Tpi5=3gmNT1T zWd6BJ*3S{NBu>N=px%D~Nk+g8N3{=cF^o_XDO9lT<0v#n6XE7v9>mIF zM*6B(v*QYwaS(1?qCh)h=A~qXiZtdXMIrK0Ch6HJjs7=5QI-pa9##%UJX1P(62Q$3@9hbd{;%$qZVn4Mc(L`{3%kUi(@U1REo}5$6&I&Ol$TGvX_x)ukr5zh_K5h#QD#>$ zV@jq8xejN+md@~w*u7o39HG*Hgzog??F#RI(N zkP(o9+SYrSmkPo`e434AwZ?}FeC1G>r5906GQp@=SOC7wEd7EF{#t|0m~DpRI){2R z@GJpe9?h~{gr{_K^9)D950A|n-eLQ)mrK~8-Q?ut_$!3?{bDLfYjk4^dQ#@VDtmZ) z6d2Dr_V-!F4h6ChxsT)d{nAJmPA{h#6B3xIYzx@jfDv)znZaQqv{LsfcsXxE3^4Xa zL*(Fn$|^`Fj9IV@IyW~C1v#l@t)>{socn!X3a`t|1i`59?rxK>1s#FsvnSF&wI30U z0qsbF4rso2AQ9`=*7gp63c@tO2{^MRNnHjbiiM0S>N}_;DAdJ)V&G{2CSO9 z%FkdIE@=p}0U%x2s%1Ha3@LK)=da()(zKM5qJt$ZZ%XNeapT3jjS?QBr|Nxpm) zeto^!m0^(?oxpth0#FE)=UNNk<*Mxk-C$xmYZB7;U=2IAnIbe$i^6=55oo++JYN8N zl}cq+D?N`EzQ{1F|G5J6*8oes9-A6JIh=$Jk9vZmo;s1q(=_&@(v-eVtafzyHS|qI zD!2xZvK084!eH%jI!21z&UaR08%f3z_Vd+=1xs&&Iq1-V*KIEPQ2&2ffFaEtkCj2r zP_oKj=Zz}sWCW+*43!xO)=c~#2_qvTq0QIc2+PBIIp?HDf^(~@+)U-h4N~yON5g54 z&J>oDnjJ;1pEn>BEsmxLz<|<=*mVh3~}i31589WkRsm4 z+FUfg;1tUWlwS^8gwASH0=a5on&jckhrL80)j>7pAf2sd6VJy@jFu{UqCWy-%13J6 zU)#AVopan6I%ZM0y~9I{6v={@mJGgYu$i9bEV@*~&>m+5HQ6;pPzT)1&5{2>&NF4I z(C~dNei9mimzr68Yf}7kk@DjFJ?`ucup|ypwy?*!vr0`k2Gon@a*`&gwTSGBgABBB z=KB8qaL?1@$kh3JAn>EJ!5usgaIhNNjxg8iwAVx>ke@bu=I2@2*sAdTyBF#m((QB{ zX3GudYHf%@hZ7Sm>!FB_`t_|Jgo~vGodAoWe^)L_#o-niB|eH2#l&5&S99NhQ=F(+>XCS76NaBDnU)TVGp&Mo9(Gj-Jl-be5(hpKLL zuw2e)#or8~D(7Oi^rF&t1{(o`i|Y~5`zZJ4NLKSw#-*~m6cHq*&dw%sjkt(UAV5Uy z9HcAI^d#eg8Bhpd7&D&6R{?7@<( z100yV0#E}G%fM@%s8**q4~!zmM?K}#C-QcO#<|9=qzhKBv9`AQRbsMx|DJsl#oMT= zLiF3e7&?p7c;_j{uOkvI-hy{>|A>FiWf)GaAI{5fIjTIe*c1uVf1z`<7A7^!9>zdA z;_^VrTrkg?1zWU|`0Jf}tcl#pkaXNCWEYt}4Kj%OJyaNv?FHNyA{@pmw;`dZ1H3X2 zoOm&dU?$HaFQ{a&*aFewHXD&Wk_iS*b;y#=2xB#BhF`kY&Qhk3)6@HO49Q_6f9``o zu~;U|m%<94kc5PU$N+*o5VTl&ZjOO_J_l|X)C^(F$`qZV!T=+Wc7NdOlw$F&4&O%u zBQI^UVSzc=*rbFrB9fA%-)tft!=>P>-d0D)_9RHc*;WE+p$`v!`{mHobL5BBP48Oc zk;EbnoxZ)iUaFU-9^4-3MZm5Iply+r<(PY#lT02k+S1>o^byE8K(KK;@ip*0pPTx5 z8q1jHxVASc1&#TB-d6pU-3!Rb6qeZDjV=fWM+fM6RLi~=tWPl=5BE0{&(3W1_KjF%kEeaN`&PRQ+!P_#o3x_BLD9jg zZ9$x>F?3Gbve2DJ=C6`{$E$~(q1mbk7e7uB7OZPg}yCk@9D`c+=~dyl52^N1ZGu_MKC#T@rrVAMFQj@as>AU*9eZwjz?5PzN^- zo5v~b4#}VPkj3}66{9|1&maz;QS1z7Awh?pao51GAd9QpN3>1W3DDl|>FFc)X0$ZX zI6;>dZ6o+bFhopF9Y$3aRvT^i^wgjbnbGa$wF=9C(ErPObQNSGG>oc|ETMIa>j?Yi zKK*PzdVcB}_ynifFNMQU9~)C34sm9rnoP*Qr)wPtP1pP5lHh?%GNntX2=$Ioxe4zV zgcxkQ(-_KqlG1uW$A50-u&RY_ zDT2{Rg!feCZkQGx6_cRzxh)_ol$O14=}2j~jNO&BXMKyj2SfPF&bO+P9$<=0s&HyaR?3isE4Ri;%1($I!47|?m_)oL*s`6xcvdD)PK}wpVK-Fo|M*+@a?POkH zy{^yhMh2Dba$HA&aPDjlov6AXhSKjm5H_lDrm8W|1{Sr~65^-u%fbX=x4)s)Otfl6 zoWWmS_o2XYr44W2eF8TmA`-QU-)1usjq`VKxkf_Z256U9Izz@yOTWnjTigVAEMvtx8PdLIL$KS;(;$B6N`{FUre zQs!px*80FL1B8(T7FBd#9eHWB)EPOug9#hAOSB3JrscVr5MP7(7wfvlW?2Hl{p^L` ztWDsJDkJCS`@-n3fvf1zn)U#Uk5xJ*aH*Pmz$)&phIn3*nu6l2Rwe3A7;;lORzg%) zPa|u#`F5{48qgik&-%i}4P>8s$Mo_Jh7J~#Ru(6`0UsvdM$bL{Mzl6`xF8d7EZf@N zD7C9=WW>9@ruY#*M`dd#S=WDG4B`6tT`8SngEyg?Jkyf4zJ91VUsx#3eKyuP@@*Z{ zC8FXaz8wdtTV@d}e)#JE%_$MUttG$af;eFe_#U;}xdfv>DvUS0SElSj`h3;Sx$m&0 zNBsrTSWq1KkwzlD5f5iHY;5MI)6Uq1yaA8)M$poF8DKnU<2Ihcf;Ts^pTQ&T z7)t@3l%9W|ji*id`ul3dChOO-c2eosU&2DWlG<8qpnOz5|6Y-s zH`A(lb#BG1Hsb!Cx!uhxeHSS}8qBNA0 zBJ5ifq4DwYgq-`hj{kbAFh%$X_g3LpCYA$7AlWB>%Jrc9y+40?yP%xy;?MMnwa?hT zKM8M(?qW7I3~WDTtULN`WJjCGH{&-vU%4)2EC#Et`Xg76Zhvg_0y}lwX)HA{g`N0U zP)Ph4?Ya`G=#t`3s&gEu@k=7$xdmVWx zUF=z>ADvd(GWfmTXbopekbb3iIey)kVy;@mBOS{T`dPH{0Z?$*#09RSH0RN6?RHA3 zZ53rh4EWcTCaxoI?dwnYw2w!0Axc9oH}VIkGnb&JD=(JQy*PqPW%JzXX5t3J27IB> zp`gN;cbP37RHPrJ4%oydQlnx%RU=&a>bsm|4OCg|TACSo^S-`&(la>v#TJ`;2wrlh z9ydZe`|7(GwnBf{_!l*iWGAg%PEpZDgTJS91f8+z4t{X8IF^S{17u9^fq?Vr)ARJ0 zd0lDkPj2=PgezBd3qTxHQllv=flkj3G~vDRM|k4g06iZY87(cDPbV9scdZ+^du9>V z6Py&Zb5NssH-z)MffIpC)0U)fGWB!OCY?#!aoAsDe7&XFaLcQz zHjKOd`NcaLW0v*}_+5s>BD3=OGKxWNp)dGn6=y*75oXPh8@>Z2TkD++*(ewbir&vqyv3F8bhcvyXU5O1Jln(KR!cAxePx9{&I@h{C3UM`*Q4~ zQ#LLqJKj&y&p9#C8#;VwPED=YTJxLGx+W~uBb)BsTJ(UMEa8>5Q)DC2nV3~@NvD32 zW$wW#$VkbKwWAR`c^A}y0@|BvYaw%+9qaMUU%ox*Hf-GNaI3u4)Y4hl@P};Ol6Of=zvnLzhZ85Ek)}Po%rJPTK6-%<8ZfDGRgYZ zsFXWhq=(&GwQPR0WRk+upP`GV)_q_D&pX7@A=UhrzZ^!#5@=qird*r7?zJ6I^ak-P z$!fX~&JUz?-nRlYtDgAO_pV~M^{pk0+5Sh!0S4-yg^a;+vhTZ_WC#r>$jgnhBD&6) zvYy=V>K#QtyY>7$>;COFUUk9q`h1RVG{hAkw;@U91(g+_h^<^dk~S&RDi(hyKGB(r zPS!^|{hLoT*C>EhWOUHojzJgT0(Kgt=suzG!!dSv9oqE+7<0*WXGwT%vf$B3^0{KP zw+q|-(b2uwXbdeD$(~)G6=m4!dbJ^OG=9V3idwu=Yn7i&?`YW^Rr)U=I zuE05GFL2}qUX>w%tkYi9S`7W+brRKk5;O3-rHxAq<#t73pawC4X@CVshF1YW3dkK%I#&%tnP<#r4~|@Z5qA z@w;~il|EOL?(Vf%zPJ0m1H*gAG66d*FSz@p^m<2L@ZU%n4Zb%vDi1F0gs|Y6GZ-um z%h0hlx638d&djoQTrpR;Y)Zb!Z{N!J$E-CpB>zlc zp}%{P0Cc;)ltBLU1&)@q3Omk2#wR)&GysQVwOy(6fZAf~>UV8tH)7jB+!*8?Igk^t z0K!e!uUx~hKL=Em9tT9qW|r~arjpP2#o(j<<1wOH>Zt~gdv2;=YuUkJ|JdP)^xe_! zMItNb`tR8K2UMrrM-Iaq)y}j`cSsM02Fu~41(TE2HWF6bZ;}-q4K{~&ipgecfqc;8 zNv|o6Q%CKUhbq~8*PLP&tf_|f(O1{?&*A^0>#U=q?7y`?Gc-t-q<{!0-JMcO2qK-* z-7Uh9(jn3f3MxZ43@~&zGQ`l`C8eP6&GVe|Tkl!x92ft&)(qVDH}>AwXJ1s zs+^0K8ttXdkJUd{DGWj8*vofIQn!sIlPme9cJi|1|hI&5kVV4`4##JbxLR6jC3D$pe z=XB@~cN8}uSNTyqF1={~ zA)U&)n*QT!ME%&SrMqq_iOV&R zRC~HVKmA}&3m121MG(-rB`FXR+U0Swicx4w>wP;_~A;}g_&P(DK{3b*=>@pvm%QC;2 z{CrL(BO#KWl@)_RMJA4PGeAQn_ElV_oo7#UfRy9SvrU>y_s7C33@dG|-;Grv1l3_y zJDK%HO~iS}N1Y{?2fah@uFT)5;UBe_qk%-tvfN;Bge*y#gsnxDK3=x;l@8&dWdjC~ z(`49__TddPp7HBQYf!xE-U}rcZ8-IUNWZk(f z%Um$K35c(R4{Z-V*hp+$_l?bcah%WL#WP&`p9ZFnWwy|n3WLQoPuK@|lOA@DkB`R& zV}V`v2TDWhX_7o%ExmIA{*17$riZk&iMS0Jn=k%cEKq-nG$Qot3`K;mgtA>nrxK_0 zI@t9WrC0$;7K>9%R4np!jl-u%FAEm6sbVSCm=F{A@RJ&kR~4+RSwCS0?balc<;BHb z59!o!v7%75T;7l*QSt;Km^G9D-wvQAOhsgDF@G4p+heX5XorA&D`5}DbalaINM~fZ zwv5fs5~2cwb+7i4jYlI@Sa^fXIyuuqJ=ES%VxrnO%5P6>x0;Q2qM zafeI4>4yQY^BZ?e^w)33;yUa+V=ggznumHRfD&Pgf$4faRrr(UFZ%6%@b3cCyBBY~ zt)C;kQ17o6r~Yg`$D&;Oc|mPLjY%Iw>pS-DApYyyxz2!%qXVT^zd?aCYI5AU3B7vg zHl;PZ69Jg*Vq#&8bZiD1kqV4v=4PPf_n*-c=u`@WRIzq{Q;P`)6VtJ^Hqz3Z|2n;1 zrFT5eK=AiXVUwq=Wrj0CA*d~iO$Kz(oM?Jl1$cn>CxKf2?_rV2aUNlMS#(e}(^vK% zP-i;HC|(*LL3})RrhZHw;!!zyw9#U(*jk4N zSYHV@ediT{=Nir5MI2ihXE&U-02MST4aPk8n27C_7~%5nw4gIc+wWQS#()>$?k-xd zGYd$-=}CmiwJNEOy393IlcN?KjKWJR`5EVWi3nLx?kcY^uYPc-x-hAg7y)G4_*CAp z+n1`;G%}18Ft}s~8a8g)mjW>EH)*|RPOp=a!O3=Tpa8$EojGfXg%!ru!*z%wh@?g$ z4$0;ZD_nS%8JFUvRtAX3ij4!wNWT$g$j-q6GFH!VGS`qJW@%g2Y2f*n^rR|l#-4rN8q4?cj%>lheB0A}JUBJ8$;Ubr?GIK%vMm9nMZ$Up63 zcz;^eDf#?apoJV8F+zyK1hHFymTDd@(nOqYT?(V6->&5E|C(-3GyN?XK=26d* z0<$$+ZN|OlceY0dy?;k1G%GnC0bQD(DYhPOf04aC+jLX4W#lkS|3Lfs^x#qa+Mh1c zNYgjr@0N`s^^WZVcB@QOjYqo_8r>8gw!e2HYQG*4G3XU|!_EHOf`Uh(OIFEHmt;FJ zF58ksi9{^ls)&OdZ!_G3s8cliNX?v#cteeOV!i?`Gs4%AK(4qb{Y|8KV)3f-{LSBz zrzfz0U8dW@0&2y7hs<UaGl;G^H8dK6|B$My zl=XGG-cPZO)EQpl$wVtnw4z#D-X%Xxq1<_KXr6>nERscF+LWZPnnQ-YU)Bh1z8ddj z;!4-zZn~`~zDl$yy#&1ev&uc@*KM3!gw)O!biWxpP>Z! zqGxiMz5i5^FV9Oue|r!16sWKc+)sK)%WL1jO#?kPy6bDAzi z{`!RpB-^<1;tHiki?up+F#|NTs>~!>%d>!3f!+9_57mt^8xp#awr*Z|_{d_*$P4XrerOD zTwHh%46K6qeA!l;a%?J|WyAJ^{%SXFS~a0`;NO{(Wt#W*q`b0N)*7YrLa}rlcfjHK z_3+eh*MWu##9a_Djs18zA;p23SL(ZkHvP%Ut3Zr^zXG`jK^Q?|e*$6t7h+~Tob`Pp z&j$ORgj1VPJyc?%>--gdgN@c-{wy7RSrKfhP+4tHAh4t5`l%SaUi9L?Rz2S*v&;ZH z&4gNMWR!Gv!5tG@q3Y(NL>JDu+gT3-LQ0)nAcXcbe+rz8FO<$x{`1Oqo$?VN*)@OZqnz{5{QByW2C8zEZ8hI{$BCmfZ z7F$@JJP7ph{Rtn^XN%s?!aY6jBk{c%xVs*YG8Y)8>I$y8x!x+n({M>r>A=veJ}K6I z5_x>s$?mj1UX6PaufnpBQ&>rMZ0rwdF`?@$3OeY>e$s^fL`%e7B6uo>=44rL3M|YJ zmO{hT`HH$%Q%w4iNAbAi2MhOn*cu$?3xYIbk||chN5lzm?Wm6$ zcVEN*8omO9q-x!w?)M~aqh+H%)!XLnydY=$not|Zc8f2*wuG?0(2}@3SIdV*SSMChg)XYseWq8goIfxn&m2T)jdo?t9Y4 zF0_JGI<}_eAtyWg-z>m8@AZjf)>93As=!{vNE}AD5^{Ri>!nUy6mYW@*qJX4_`@S{ER?Ft2n_s5po6$?Ho@_ND} zI%6vk{r-2R+VLHHv`$~;HEVT9PIh)s5|p4-b85PlfSlZ8V#Zr_7Be>MGG86c$7+t> zKy}Ximm18s_J$G7nV+VVZl@o@U&dx{HXShVajJ4n(xnI{m zy>QcMpO1s&_$kGHx!ke=^^68OyAH$4BZYSo@$XW(ye@7~F{D)7*UypxEE*i?!{o8> z>{ECPja|&3VXvQokx?uhF0slLmSL$ql`%O=CKB{#dnAkdb}pIf=jL=2moiZS>B>mC z;P?BAJRt_e_53@jNN`JCi$<)h#L2Z`)!ow7s#0HY=r^mz(_*39vo`O5+iFZyfG(9- zDkLZc71q9Zp|T>b6r6Pc7Pj1c>!pn?O_L5S-(36n{Y4~4X(NaoPf&nx2YZv;OgjTp zri(nw{#AQ8WgteN3 zDd@z5m4Mk0rQZ=Y%Qc{(YS0_)RVCpMCx=ePzDH(+1mV@1NS;Rx##-TOnh$ZF*$h5I zd|1+nNXt9un?S0syXx?A&1*!5dvrYv{6b0CCKmshUJhP}{wV03pip{k=TGLTMsnY) zX3X0bZ`!N2*#xD$7YsScanaQQjz(HgIRrXdmc)!{n}ZaAls9!to`XVP2p`<%1-@ z!t8xAGlC62eO;JA>wJ{d-)=@?r~vY*IHd~p;C08I%IP=BmeX)FtbnGbQ`ZvyQ1=iB zVP^2h-WfCa5jfBwKT}rJc|~@DKmp)L4nZzzOVCitWGkdc;e2^9~QC1BV4?t)J8gT7^Y|u!AdN3%5z}B8Q{&5CPT> z&ms>we*f|Z;)_b)R|SRa%PVf1VM<_pyI_%gHE@$B>=KyI$j3xM#8}~7;7wFezTZDG zLLNw{@%nXU>m)E4yZ9s%>rntvmat1|MgqH6K3dm9MQS^ay-}r&au>4`Gwk2-rV)>e z*iVuy_BGC8mfy}b+i0|%2paMGQc3x{P~<0obxrYM#_S>%bRQZ7*CiJeT_+ZF*E-@V z#G$(uzSn;iujd)fy51pIOm)U^V);`)zD}H;nTg2Eqy{1CofazXrdV_l>9Qo zhQe>(qK2wm+V5N@78eCETtMdemFeCG) z(}x|F_WNB_G=$@y^db|fWBl1B0X11rFvfLD)qGG?DGWZHo?DtXU-Rxed9>EJnq}Os z(XNZfpl44_20Jz6jyRM!3C9_ulmexO&QhnCOLKTue+%fgSbyLIT=K z`@m{RZ=fmrnv{|`SjOu@4k*9`2ZMK=$jdgo%dN#IUL__-{YBg~y_|WKXz!R(YFbrZ zb$V+9!B#+~2aYMZuiTl0D#YzxnLC5!CI}MlSH|2coN4Ijwkq5c9#kx^k-w=>x zaRyibeB4F7Aj_B#YE)bN^t)T}`Pf41$V+QMq1>PuKPz_^k7vJb(K3LhNxYuYkzGD_O=dW`0`(4u;zVqS}SDEO-98|}&TlSybgnS#OuE{R-W;#x~Lph9W zJu}NIjipXYO?^9(IW#fnhdW_Q_7A}%BJOjPt@$8^#B>4}MCXepAClG5U0?*}a(kZ8}X;WRG3ziI%2>ib)@p9T8pdSHwt%C<7UzTSBc4A+WG zNI}iaKIlKENy9R;t^-q}_kEj#5JFbg)Xkm%AQx-m^KJ+|Ga-SC_+&`K?e0x%;(}u+ zRx8YqVn14{LE_l2*9aiXaits79fp7T_v~k8lalWiz|`C_F9Z=_dH=uu|I3~$%+El;#GZ=WTBotZQKDe?YZz73A@=CvQ^HEv(IQ;|) zWyE-h5nl;vrrKuAen^g8rStF0LnCuGgj!VUJ;$`<3pJDx^uER}hgZ;aO-LB|7^D3; z{*F4odkcW&pEs2EBEEd?Rszi3I1QKZK&l1|`U7Q#Sve?2vms|JF_)!)u&%d&)h)+C zL4q!}9e~PNa$$VSDc3FswS3@$gQ(bT8ExaWK&FvB+_TnR65_(b`es=izKK2AXM9+e zBbz{B@9X#PK*;v{jS4C8+3Uyc4k~ZrMi5|qYcjhjH!OXfZxhT7QP#&f9Y#%1tqvE#sFcta3&V2L4)33lcmN?8)IZYtO7 z5>-c?!9{wj2IH~~>7DJo-N47l=M|M%4<6P7SPFpkDSuH67oC7C(YEO|5&8S&7-IB< z^Gsy}%EE?@gqf5WvO!(dY(2SM$-U>vwbS;CTMpXGP3mnWYmb*95Nkohw0Jw_;aPXboU5a_8>D`OYr}A6!FmQuv)8t{SRjZ9Qz-}r( zH8Jy60l?>%FZmV!^T6Y1gdr<6-+J+QhCY=N|NJ;d@FuM20e--U5P&M4=P!8d+7R?Z zu?ARt*vLpI()vey^~*VD%(8x*y6oC2ZK{a732+no%y6dS*6a6d0*|mVOUro?%W4z| zhC@x(eKBY)8%u~wroVr;rBdB}`>DyBQ*MB#@P1{K}tq`|Hp z8p6)-v%}fd0j^cyra^ZGW{(UJqBBhQ$lKwk(jGDb4^-UoKXl!feexfE;gMGN)*MXeKyhTdig1USiP|8RsI(!M_<9L zoVzB*kOJ&d@QvnrHmeGHN$G2cQhaD8RsFz?E7|8LW=jmR#u06nPtWK7-pl%!vA!6? zx1-=CGaAlcG*yrAtlnNkk&2K_o@6Awb>@vb&4GCR4ApJlkGV1`eq=q_go)wE@9>DQ?S$&oDJGj!QIWi<6vrRJa&*xFR6UcI76a+n-1@@+m_pc|X* zOdn0@duOME_zXNFpv_`tMy=^fG{}9Y(PZr!LrK2*-9!_>BLSV3xL%(zvY&gw3OI5> zpR~*Qa!Ozzwk0CQg!K`DNDWb9F{ET@=q!LpUHZ}zrlhRete#*rkwj{Q)lhOaB*s3n z;g)u5?N4V1$ukkJUZIr`F(PIb$XC`CZ7Gm3@J8b3w&RbDwKR-~ zlJZ(IpaaF=z60g;KMg3cN&hsUB(Wjl`iDZ<^r89y*0iy;Wo~9BlWCYWWl-fS!Z_Ix zzLby4#38p0lq?f~ z0KkGTJsy#5YS?%_iUkIt8dIT~2}u|Tu`eY%aH(ex z-~cFv_;_!im`U>WvRQG$3j=Q4Am21i<$=L4LdUITMDOeer=8AjBpM6>zSOT#Tr3JW zeAU|}m`R5j%atWoRRQ%l1lw;vj)0iDqKfZrgenmu;cVQd?+Ajp#sTc0$4@$|xNS2t zn!bSxloNin3cVZA?v)Gi0h6;UOnpxF+sv(L3 z=QV%gI|VKFog^hARz8!gGIxyGQArZr|FoSHKo`0QrDM^s2#ik74-OmyPC_4bhhX3} z_UHg{-wklL0$0BrQP~S=@#csl2$T>n{Yb0l1MJYhUZuV z!3K_%zUJjWm7mXr289Yx!GjW72vI#yhu-ttw1RV>5b{4VB&M-g7VH51d<5sI zmeEW;jSE|!y-}eVLumlapyM>t1J<`s*8fr82Eth7Xt={to_6Yw@xfPCH^cnnrF5ae z{8ZIlBa#0i0~t6Y1Iz`2pfyaGFH%g~8AOLO4&1HqNu+*`|Mi!O$N`qOJa9PI7|MYgTmsf< z8n-eX64gt9fm;Rp$pru`=k{|)(pg$)_*X=o(}EDP za=zTSNz@9&FU(fup1__3H_uyf%U zcapJDE>{@hh62XXyU(JV>b4jeKhy~z0Jn0=CdP}Fh*$se{32eaMEH^|R23oEt=ns4 zOdG56{b)?Jp^N>$@Z@5EiKcey>;94iD-yc;WqM$<^DT#oNq1#s2Mq%gqiH>aGt=VU z&INf4`OUA+B*V(M{#{@FmaS7*4c(_FQ*q;aLp;p7&{hX}70@95Pqv}em~M>3iSSq@ zqjs}0LrOjjlKCNAW>0a#`%~vNE&vgc;5IJ0_0iqG7QibyG%70UX+I|!E-=_U85m@v zHBJM{7WKePGjhjSI*s??iINV4<0J2`$<$NdtObv8c0bY2Fd0v%K=~0R#F4M4E$AwLLmA9lk(vYAiN_El)U&W!tr(FmUE;MK28(eh!ZKY9e8SD3H+ zfcsK~uV%&t-gYz8e33;1P1H6j;e&(~W+&d($9_IMYlVa{(dAi!!=UfRV^RR`Yea0s zS%0VibtCSeV9aQmAO}-vc-4Ue1)VNBN2fj9B%cw|+wY4oFMiCD^T3lkW4>(>r3D!b(e=di=6sg)3mDmPWX7iC(>+Cz|De=jF#;`5j6o^x=iF zv*>+=?jJx)B=vo)I7#s-{%~svf!oi7 z>Crp9aLtZWw*<=b)*Cah_$T7V*=H5k#NsS2#VS^a{FWKlmSmpm1B3 zj((kBt{OuDIp{(WgflXe&XLHI{Fw2EZmcoTiKNRm;t46b7Uk`mzR8VwRgGUQ}d=ai*gQIg_(pOlfm+WD4SKrHq9ZC zfmqCRi6G1xxE*8A3X~%e*hDPJFWzSD2ZH%4fI&ux*v9&QGRI&9>>ouh}VJupX?gH~v#V{J9BCuOg+xoI$ zOi+CPIKU@}QCd2vS0)UWjqTUET>D zZ4|fV7MA@A*my2#ICOJ}#%)Vg&Nqv%fd-XfwBy@z!Ne{sx8zplUS-%N@m84LHI{T% zjpdU?z$?62G|NDQ5EF&RybAkN1~$pBB;EY62fc21B+>4H0;6c{@nI&LeM#eE7cs21 z)>u{;VArCaQU$j60jaJqtrfNV8|uEpg%b%~C~H`Xrg3iUAl4;7gCTf_0`>Y^-yMbhvFadg{_KKTk zny-MBn&A@|+?oWI^Cwl+`7K}K5hFN^c&EM~iT)A4o@)IJQ$cT(lg~za0+~hZjt7Bd zsF#GxJ_zjFx1kphDkqaFiOQk`trAWzE-C4k@e+H?KWIzDF|u-xS@*hI14})P92etS zdBo(oFVRby+i)LVkWo^;0`^}U?K(1Q+#!Z9$z#5;x4*aEk&?Nk-C_|3KV0-T_OI0^7IKy&n#)*C&jtX60E;JtW>)P7H60 zo2+1mrULCDKieXvzEMT+;2$SjO$5JYQ7KB6TK3rfB2tj+8s@^38Kf@9dY1RD+66PPC8O zi*b?N&&gI&6AYI%!)By&dR0QH?YT^#LB3ZK9E51Q{O_-~xWy`4#lwT&P#2(hxSZ2t z04wN6rA0sh|JwYiI6@7{>!rqcq9*Mnfmv;TJV<*S?5?pmx+mY6uVD^hf6* zxqOo8l=y}de9dW9jtW++I$77w!jhJ9uK*RI5XKR|v_uaG?6k8&DL?l?e+gfJ{^UnY zw7&2jLaKViOsD?nQqCR!oReipgb-q*QH3^pQ zDTVq*XBZiyqgrxfb(AMj3Nd`Su37pV5Nx8pK8E@-^x1|WwCiR_W*x?tAT0F0xfms< zICGrdhYk)`eoDpXk2#YV3Xl&2-x5!7*$XJoE-a8LD|KdRJq1Wa1+Q0x^XqQ60aFX( znr{vqxFRue?DXUXI9^%`H|WWz>#S)y09ax55wRk6lnwB)Zg(eZM=V1x%77y2zYUOA z^ONSgFM(z$-D%0r;gpk7(>s#?ub)lS#PquVaRLa+-tQC;K)b%a4)U}Nhqm^SB)5+j z-|mw(7O5o{eA)oDU8qozrU; zh*#*sk?=cVZkra3K)vGb?afC1<&lidbD46pdjB9M`OfzuMJRxaq{jl;N2DJ2f1te$ zUmh;CQx<;yydmFeqj*}E*B+*_zji&l^#ufF^=?>Kwt+Ml*LmVPYXQ9~kA)K{ZxVG( z+kqaNTCt5Eg(Qei4!TZGi?xL5iixi*#WhL|l7j}YEK(n>EY>o5J$t>NN+@L+Dgu

H&o~1pt%Wzm(v!Uj#VMD0v95*dS01=s32dsNX{c zdqd#Ms`Q4>#fmzFOlWe;%9Mc7P-KgBUbF7!AF956!SIPqSe=MT17i~a`GkrKtSU^j ze~YqI&FQsaiY<>sC(TUD<^{JgMia5IB(#!x3+H3G}IcmAW7VjugyZ*PhK=8bzhrNJU-0gALUO=>D8LCe8`oS1-Y;TU>)x6zN8{6R4qYB7iTC10Q}3xb0!C9HG|8PYvEL|iK1 zXPwScKsn|mY?I3Mybv%Kjg5+=$%VTg9xD*InxmC%~NIu^2a? ze2e9o)@ua+3sum#``}5dc&b@ft?uq@O)1`oUg$?{ug1UcpY-QF?DT1GAe27Z?cpYz zF?;^_W7HYN`^nyu{2|HySrisw|UQL?k9TvXZ?3#R!(?=iw?WSix>6%)}OTW zLLyLbi4DrbOhtMrLBX=;uU`4&8@`#$daB4a_R2`QG9~B0tbm~&?QnnJ3w`q@O2v%5 zy^nQ8&uTLy)`JndZmFTd&;D`v)m9#5Wn3yH=z}u)to1$FeB0*sgutYZ%EeAR;&+gL zp3}nXRQLVtt&)1hs4(o^04q^q$o4{hW?Wie|30~MH3`0C)jSNFPaazpOUt(8DU=Wj zRBxruAk70XLD0{utH(L&c;VQs)0r5tPdXVB`b8*#R%f6hQBWzm0-JGOF4U<}W6vZLr0b8A8KA5+fK% zbu2Vx8#OMPn!K;SX|57TqB9SBavjRZ{kl@`@yPac8ZiT+qiE6|b6zbC1v2IS?=!t# z*20vQKQj9twB^eZ&mei(^T$XWYx>h@@mvWkqsj#bo&XZ;KW_1I&vo_(Uh3>WSV0a> zm%>2RKqNNt!;2aut`x``-DCa`SZz1IGtd*~I{ZLJBTtF>+K~8ss>;Zj5hK9nM%KLDZy$js4i6dK+(S&}3DTbM|%{U+>LqWyFn}V_RMSPp$_7yh3QB(}(o||}b zWdn-Q84gTCjV2vJMaqHdP&_I#8lKjfG3mdwmwo25zb6t_bNb>}b7vj{K4`y3zi@@}A;p_Mg;&171)&ip^ODSsiL7$jnFs!x474t6ry?&Kce#{SLhh_ms_C#qzg+frhP%G#9!M>sfVboCi|nor9*6-pE!+ z`95%-`EF&DH1!B3CmR@cSOg0H^{wTvMT>}KC;;ZZ!>s&kK8~hQD)$c>58)}Z;q_*O z{U&rn%Z6>#&3HqB9yseQ%U%`5S*O!A|88@IPQy=P7{7cG&Jqqz!uKovX=UUOgHd#; zYN&jyx}SQ75WoHi2LD%u2rYU|0qQzO7YWkr9TY?#P#5m!E2OgLsQCHa8=!&B=22h% zD%JzwMAX;1IivnDZW%xu0(MTfc@+X=36f5)tf=s@4+>2QAs_`Balf4cl#cZWAnr3+ z5i%ojrFoR+=}IFh983hQmBOh}+Yy_zqq8&ao4wv>M_9&8PB+z-g&G2K@X{w_-139G zp0V7$u411w^QB3Q##Z#%nq^#9yaKo@ft<*Psn!>$$)PKwo(DzQqbn4Nsr8g5{;Y&dE9#F3t~|qa_m&1o!&3e5iC+D-xc}rVUl1dEEeX z*aS?lU{>)N!k<)*<_TmxP_T}*(p>Y?hH-xCKx;ToRd$Xo}UG| z2&f`J3x;<=){e9N2+-7wpFRiXly&Xr_jv3H+43XCmppZ}Qw>yS$Bs9#9FCGVAN&%| z>ZsIv;KgY;vX~zlmZXdhjOj(~s|;}}_mlLJfIA;9bN8d;eoIfU`_3f#&Ujv7d4LLmNv`E7|y5gFY8&~)LKba)*s;(cFonTf(S1{ z^fOSyzC*qh=`Wm|Y%*JDl9baE|J-K2PzP7%Pa_?VAPC_82ReO20G|-Kx1ISiF~BwC z;s_-1@J^@ub#i)&V>?g#GyBEro4;(Y*XS}we8E|bRZU2FEcE0R!DNj5nrIl8>+xqoL zg-Op`&s)z&yGptSUGPn-Mo)subFVZZHMCx(}V)~0fZ*^MuLgM@YF4IQqYTtLd zuW12RBZu-#!9ZB^Mu!WrV@vY;>NuIea4u@;`h1=w6`*{{nuHP^GB|j;@#U{Ioanq^ zMp1@hFI~q5C!GvaaXzZSS*) zt|R*Q)9*rn<&3=x2lhYAq!shO{ASAC>?SNmYj>^D7vYV*6KjXKwisIzS9lX#S~?cR z!sUJqehu2Jw`6nTgEay_nb6d9k_ z=`gMx8+(7palP<*f;4K6yv9gi+^VZ|4oKQQdclFh?BI{8Gez zU;r+w%Cl3%HpSXU4!RP;yzYhuuhk~4?ZgLGMdkGm?!h6SPd4E7yX(OmtkYRNDX9Qs z;`qB=0dIhf zH_^-9IGPOFlK=E>er~A~brZLkc&+&9c}_;Mj0U4zX@Gt&=4|{N&aF%+PxW>^n@sqR z^u;Z9Qr~-%foSr$|LXGK(d)oIZxXElV(!_GX$fldizshisfTr_HKBkKxZ&HKZ4CP+9EHur~J94R#F}p|6y-)%IT`Q(9W5RrH@b zP6N=bTHkPUn@*pNA0dQq`yJ4no^^)H6NFTmHPPytHb&XS3nccGwkhi8*p%?K38Q6; zlZxFL>M$Xf?xV29#V07bp~LiD?=0tihfhdu$L1vcwwoIaPV+VEL$y0N z?Wz^zcuww?J7Oth{mTIJ#G`1TE$7u$N{+aXyOrK2>r`748N16DZ2wGBGY7^mHXd&V z!0)0Jv$Oic8o-&wvQxmN79Ki#dUxeE1PF~!uLsc^tv*6fpFRzfTO#6?RO95C?&aXK z#83>QEickg`kHJ12;Hb-)BRbXYo&7{si$i4Jx zARx+Fw0F*Eu` zd8sPlH^1O838UNt8IHOAK@L{wm2|Bt^kLKnd#Uyl*FU)|)XYEe=x;Iz`A}2JZ9{3o zYr`4x3=7(m=1oiTGOv2?Hz>%5%NllGMZ^EfH~52LPI7=%6UpQaRWQSnE4IFFVBf(L z(~R+{tr4X8zfN%B&*3I2dc#=yJgej5L_n@Q{4Aa5gwSX%YBVk4E#T|dUEOqk+IPx( z+jadgZPweM#k+O4uKSs(j`{lpp&{g+s0GoAn($3^;xg~=fwb-BY7)OoLjeB*$|jwQ za8#!WYzvJWF~U|8P+Cf9zT9U0G~O;_>mm2Qg~`wNg-Jj<`yhS$cDUV^&fAl$Fdz_h zx*zdDNmG}iBjL|4CzLx-3BYXwEHiT@-vPcHD|;6}^rzSAFZi!XQV3?_T(C6!QGI2^ z5K1DQDG0AWbO>pE?M7T z;yVs~;vQ;*Ee>TjHerAfj2^MxD=ST-JO01tRG(Zy3kqsL*^AqjGcCY=2cl>2@Poue zjE8HO-_P0kDXHeloeJr2{Lrj3P=9@&_ghzISya(dfewigeS3pX7_yIX;8LzSHO z94-we;!QRrT>;(4*tjITg`}CTCSxd1H_Eoheygw__vcx10-dVz_K>@Uv5+cTk<}ND zbfQX3D5{@bm2D`a68L@)_6HoW3(o_*hbjW9z8BZ%<>Elk1s>k%&+ppTT~#`(h!m|4 zGW0wYWByqk9G-1_Q1*{$bD71`q)7qb`ntD%%dY!UEHz6AOFWf((Bf>}daG|yjcmm_ zmMW%4<6rijEPs52mVX90CiqVQ`M=+j&z~Et>pWz%aeMh^9?IpLQueCCR8vAj7h_0Wk}`8%L)k9I0j6DfFB?>3C5D!LH=@k zOlItI7WW1Oz&62X3$bfpk~5Qb#c?O0kT7`s;YPab_l9L16X)*2B@KX1TU2k`@?O9BComnL%Pw-zj={#n6tu%7BA z=L);({jz;AAQUet6D4*)?b|4|bFwQS7aEhqL_~Nj%;YGzl$jW4OC7p_3pzP zZvgm`lSQE`OvZJOlZ3@m)1{)41}|~q+Yzugdh3NyHJ(pRnqWA9PnZ%DFZPPu!V@~Z6h)Xn z>8Uf}OBD)@uKy`mdvfDbvi91ftW< z&%(sRfCyH>sH^OZ9L$^ffav(OKexUq(pS7hAIvE0Hoz~AbdlGU z`*mztJ5{uup{y%M;pEcVOfncIjHBuchzn1V{1rR}%c6|9Jp7@0mcd2pP*(oyq#rEV z9O*o^pm=N>xl|-sLw@4HW&WvelWTfn_a$}A^n;U`2;JIH>Wr>`#lCw<7nc@aq*T~p zHttHWhk$ymwk`9%88rO*qB_05e<=6YRGVAhVUp&dFd_zyvNAS1uDha7MkllkdnD?h*u z7P9jL{z%lMUf(6tdUoS}xp-5z=Djj|@ALRSNU2ES73(lly&!1qf&>oalNm+U)pK^% zqqoip+hok1c)nGyiDcxYT{Dm)*7~mcz#9NuDdmt}s|<`QPEIxM9;9BzyrGXQTS(^1 z4uSF<>hr!YQkf)(_EDE~Yyxk>h=07esB@x0$VX8L0Z$5$DJ7PEd06%F!o6Hm$rDju zZy_g~c8eIrW%-$=RQ$XA(bs{abcscUL(~`fI%dISZAW^+;-2PcT|K=)Lh~Hyy zcy+LG%`6jCZYD8<#z$Bm3KYwoV!l>sJ64?S<+I|gy&?EtEo4v8QO*Dv9S&9hsYq|v z^?0F-Q_FFN@U^eF@0?RURuALYH6rB-lhUDa82>W^4M5CH?Fz^hBv#Vi#xD?JGfkzq zvUG$U!;GN#HyElYRR0#-R#&bxFY0yiEPt88m#KBk9_?sH??|z~u?tx||f%O#z#r3XH9S|~+5dlOU-06U1`Q8!fcY#}{Q{}HQX=Ti3{&D@4X%uJ738l$TB)5D9*{cZ&lW$=8B1jV~XHu0D z9Y2DL%~iJIaD)lkBJY z59(Jh;|>*^EBg439{=yhK_u%+z17gWa5)Aba0SK;7JS)ED0+rx2OSC>H+EvO-wfqu4M`ivnBr16Z(e5Vg(`xE(rQtNoV0BQQ5CIst&JkRO>lg zVLTDic`q6<7cHl=hogW52xymKP98wOc-gCr-Z9O~8+5Q&8@`zbvq@CAz*i_)MX`WK zT)RPx5mHIrkmkoon(1V3@S(8K9JH461>UL7u@$atJM-X8BF=%B7prCKrSA+-#G^!4 zo*&Lhv?;Y{nKjv{5C6u|AR$&y%tm(l06`eL`sE2*>8y$16jZM0@rs(XM$d} z#gEUz?4*Lcx?F3!4UiDz?7kP}NG0=X!Lh#Nb3FSORuS;#`b`JC9~{ILkWg z;;80PR_P^uO6`NTxGe~0PX_rye3zfhI1VLSq+S2QnhX0SP?~H1y+qzDu(vjW~ z1*Ib*y#)|yf^-l<7ilI!LQ!b}1Qeu5S3r6T5J3q95C|PnibxZJ^j@V({|@&)cYI?! zuYXT|B-v-LwdR_0uDzw$rEf_77ad6SV0)JRrG{a`npLFO(49Lq`~}Hh*xwvL`EOnm zak(M8bM+F&xTnWI94}*DdCJvF^+KR@0q7@R0`oOyW-+aibQHmK)AP}~Wf(6KIfi*d zSAr5N^Y}fF5ll@?50xN)LjvYVl{>;uqhYsQ->URLx7i zT9;-~mN?5jWWJs6^R*9E=H!1_S;Fx@hoMhh91kfMVs$Ep$7Ei8*4MSe1NV!eqMW)L zof@5*2rN2TTfze*$1cNnjzQpkurIcs_x&1gAN6te3p%$x6f`ffG86cyZDh>+v&Qu5 zoT1;PcSh3VZ{2*Fx?IO+)vgc|lju@=FT!rd!2h)0WVk|no8uC-0MEVaU`OItoQWjt z;E)?qG$Pt#AGxhtd92b5xxSi~Oqf;*MCDtR8K+vBvDL$QUh2bn-p8F*s_cKaIoB$A z+Na?Eq2Zv`<#Z#sy{&BCw3w8cW9m^t{BNQ}F=E2K>n2YglBaxW%TocvCF$=7f4k$g zKG^rfJzd~uM3uNWd9|4x6v?V3@6dt?eSQ7jQs;8(3uDbz0<=$P$s@#ojIsOmp@_A$ zoX?!#S)A6R-{a%fpbcVMt9Y{!HUu~vdR%l~t1n?S@eH}x%blE(Jrs}_+9-%rmU*QA zk`cH0S$N&x(j2y!Wcv#Ja!PoRt*97xgTf=K!OvC3_m@u1^FAA*%FMeGB{Id8-1jSUP=&tc_E z{d%%s%z#*4yXT6f5ps=Sil;&7Ph_MozBe9jzv(w^0Ne(Q)6y`|-f zF~O*oKtDv+l60Zh$1;w&SeKY6b=>9Whcdr&KpZf6O!Rc*Zq<%9cB*k2k+gfXg5Sc! z@{towzt+~SxzmP2{`k?xntvXIKWnVZsL%}=N0&>1Z7;pxxVh?1Ze>PcU~7;gX(Gtl zQp|Gfq@wlp%UAhdK^w@d*7PT~qK#(GQF>M**ji*m$zEQyzx6m){-Bm{>^r$<`)vOw z`PiF?Ht1DT!J&jyA~{{s7q^jtw-v(PzI|(}7S4oJ4QmMvktAnh?<$I zE^H!Rf)?N=e$?5U=%=<6ZVoY_9(Q3&w#8Ul5J(Kg#M;{0RBz^eO&iLP6Z2$1o=F6H{1__4Bb*;GVVu*FdT{W&yk@e4H$&;?&)6!V1)Xrj#J->^&# zh~y<9O|hv@+ad)62Fw2R6wnhnL&ABUfFHf=@!=~;I3 z&F*jVjXk==q=47IMW&xk-|w}BCJHaWRb!Vw%@{77)w4Wgt~*D}k!V@>qmdTliwK36 zK3~W)K_s2`_$bqEk%tZvWkRWHoH}_rfqNnEOvFy?If1Q&Z>lk5mq)+NbAEnL$!2l~ z2ckEyD2h+RT3tJ?EniTfSo`e~Ly`9OociGJSjlJ?*p98#vu5;UcW`Me7WE= zAlU>5PE9-B^vg+U#fnxfnGWC%uwu@-lBP&PWUE8QU`D!ZnTw$el8IM|9FUu zyiR-7T)t@+uIVE-+(aw(Bd#{)u8U>IM8g_!|8m_^Acg+URhz&aH+9X6$D7DMZHLGV zd3Y#16%!XnV~g$u!n?R-W4!!E2tR)|4-PVcl)Hqz2_>C6j)YT>KgZnUmaLo>jGnFE zDXTViN^B@K9L3!T0vYw_kzVctE(=+){x8aa)q>YJMAaB1C7h}bffGtS`}g-{78V!5 zOY*vIYT@_^uSHK`YM9xBgGqsW3T7g2dpq54m9rZ`WlS?;!vf^@6^jiAO6awD{U}HE zIqH5py?_6{12C`s3iQ+9I(iiXKS=|}S9L7#_?`QUZrO|cNC4HWoacG!dN4|V=3+z& z&5BF*n$5@hn|#w>1uka!zlqh22tLqjbEY@bUmedC74lk+(v?6f0&6$d=`RwiUcu?f z-7<{xzZYWSPbh`tBq=)VjSWB?Hkx{jCQ<6{va%&!5?JYZU@T#_wt1bueMpzxHFBq_ zv*Ed|UUgAEiLLRrMypt#n;g{4Lm)+JL%-j0%|%;b_)xO1SLN!_EDEh|BP(ZRiiqq z51Ixt{f+;50pu4?BbZ1GYiPj@`<;*j9I^#CL5_!#IU=;I76bD^hn5YByTNif4ivJ5 z9&)?aF=IYtk%NG21)^89M(uhPg@)yKPE6(<_hT5Qy!>W)4yx1izy#nn89DHnTuDeT zCXL2ZN~h~-$d?o#vnH0vekA_-aOTbJsls)FG)HFhm&B~j7*5`(b6rVhbRO#RNh*wC z)>iB&r9a^olOTz!9ltg>+(%*t+gyD;+mJ{_xInC+(0}CHH)_xn5M;T?tl4)dRCR9a z(qoXEXtl4)_wu9#P~=heV;C5u!Jkd`Pc!NGi`OMGk4;Ed`FBt&Rze0&Hu9b2KpK_v zUGoaq{!$IpTwzmfEUgAtatCcdoWLK*|m=8IcCaww+$q|Ro;TsS>7qH?jXr0ZS3P4UAv=!R4-uU(0@~~VBD;* zs-PgWg1@;%n7V|5g~;K+Hs-CcDvq0~^mzBl>2Po>f*VMwjsGtEI$*c}*Z>2Z5QgyV&L@oJNP02+dI4-#Bb6jPW*t&9u4||5dM-xu^ zL769Mi@>Q%nVxpPCOd0>1*PY6yP0t1Odc9T2gX$H6M4H6bylhUlIeft-!}__t8;f6 z^GOIF9*9q160R;H9L3u!4LL+f1~xJ&MUw~~w7e>z7IvpaqFFGYET#SnmtHf#uNR~S zX)@|0N2O-SG- zUv|38sJUOD&Q$bA>4%RAW8%iG)55@F++?F3gyy6E_#Z^qK*sbQ(csD`ncazba}4>M zjSPr{ABTnVt7W0 zC&6nNUjNOZ(>yvc;Zg%2MVgnr>s8=8_(i%@5XD$c0W$%TWr3;KnZ=~YZjOGzahc_o z2ICPMtwm*(H&YFKB0x}8ZtRVD^7BomigXssrR_W_(YaXSOZ5jT)#%4z6}scA0bXI@ zz)Mc#9rNc#`KwZO(P5Iky-EQAdOD^Q5K2bKXhb|?qEUsMWqLP(oww#^WZf3U-uD;m~G7*DcfHG9? z=gy4p&~+jCkY1T$!)~EUvFbwqMa25HCe403MD3ktdVQnB7nbB8|8HCnu_8@@D|UbU zMwI>cxiB{4ZROUoW{xktV)Mu<^6keI*ajxFD5liL&lf`{aM{r-jU%Zt$)GKd<72jl zV{u^4g#YX-C+|mS`pPd82U%EWOL8*fC?VkfXPR5_jgy1&y6uezgPw*vBaXaQW<*N% zdk`yu=DF)OTL*THsU#L|RYM7` zIzLUJNg$4KQ(Zk>^ylbT^(0*jUv6Zz%*^CQg(W?*)`_V+P^&pVESdL*3EZ}i`@Tf| z$i*crnlCVnGGxCx3FsjZnGQMex)d8W_&~fahj2d5JT^M%k>c>;drpVvM}|+J`6t1t z)@8|$sjPew5aPyG>-HLI>0I$8`h<0%kVi$8##7Y_ej*#yuLfQ8%NSq#dKjkqp#q}2 zp$Ane)y3W;nd!$|@1HF&0SjshRw0a0a{IeSUMs155;~#lbsGV6KWBYehjd$~t&u-L zWp%#zTFP*h{INut5`}#Ny^9&sv(%N)0vey7Wj(tKq_Wwdk$mFdE9`n_UhcZ`{?KQY zpc4w{=Rd^Bi}n4LiwM72*RQLkGy{phHmUzoa*QUyvQdt~XvHuYOPPNP&yB3dPRN}G z$0@Y95z{xvj3Yr)F-(!1i;-}(fPl}Ns88H3tX+nbqvj2bw@tOZGBZ+=IGoPuTzH#* zW}T2&G;V1I_<7}680MTO+;%?y!Ex+vt-HKxG28D61gdqj%$K;Is(pH%Fb__>jfOa< zHI3;~210#6msYE$IP01RQp+Q8fAqtLtj_Ii%3seGqjaf-`ks_H+1&V&Qf3CBgS_#y zo|yCm@e=GE(!*>;AGTfQ-I}r-#@?Lo*3<33UTyQ3!bw%}_|gX9(3BeUJ6UR<$v&rJ zw0^a>Pr}|~RptWpIQNw*q@Dgc-Xt!5qSXy%(S050vq^k3RG8qTjHs2Dj`5k8ls;9Z zICQ!{t<8E3U3tIfa!;jdz@JOKnf^Q@AA+w8vs67lO{y#cRv0+9W=QS1hey%Yn8&13 zlZ-toUFU8G)xBz9#oyj*c*AXZoiXm{63#2cc{ujgJtj{R;im=i`;m0K%|GscnC{Qf z5MCFwp{|UlBBvK1Wj+euQ-OpthzUt&xAZqn8~dyU&qi+kLL!fOX?Yza@J21pLbJv4 z`}m1ZMqf*Ax~vJ=(}|B%%a~1z==WbE6VK~4p}?1jX;qD6KJw6wt^A-a49hC5+z2?d zcfj7{zf2eIVdEa_8XA6)c~fG45mRANznCiGyWQ?lik5|SWH{wqw;Yw;uLLmG9{BxL zf9+ULoMkwg_SVb`xmC>ly+a`{k1!dD&s)jO`l#qTeDTDh z(Qc}y3-h2-Eqsg+**&*&i>E12v`Q}q7m0U@+ZBX_GuZ3z9m!)l1L5~6 zKrVgnO+4-|BP1S8n1qHyV@J%SYrne@o7?;c1P#6aRKo4L_XN~X`N6hn#kh~=bL?H0 zEnXOGx?T2+1k&JP{n8kDr(SxsyPG25ZGkA@Q?liumngJB0#k2XkiP z6tBN}<5~=oDL(7kaKf#}Cpd`gvh;>s(O_U- z+)vgUmfEM=@(&HLIlX=A*18AsB`_gyrf(V0w<_(AI;Fi=$)8zzL&??-xo4AgjfUlj zR0BdMO45?~1IM+Cvo;~>LD}kfS~EW-`O~cKju&ES6waAiu8B-0Q$`TJBCONu2qUh* zS^^PQ(bRNfBi=gZT89~qievV3P_NI*aDE~3eSMJ0hF2>b*y2I3VBW>^c2zoG7}Y5> z+h5}QuLJZ*s<#-)(v`fGcO*x|tQ+g=;Hf7RR(^q3CcJKr!0ss=lzOQGKh@oZmOjNF zYVaId{_GSuzcu~%$i}@}nHKlg9>}XkP+yGAwFb-`(>wL&_l=5%hJs%aw-=nRn|a;i zs3`6zr+JF|469dhku?0oUGT!hG5uY(u25H)!hz%LaBraBsR}mVJANFX7hVN>@4HCK z9@IXrQD5GNh(B63f9g~Df=HapiTMYEl$pL)>c@T5b9{uNY^@bzM28K7J@FM>=Jn1! z6Ql$=SuPQ$$!#u-xue%#y;_9s)sfhhlI9-FA2%Hq z5;!QCY8eEca>#(iw*yR5N>Lb`RqRg46MzY!rgHr<+HcGJq(w&Cd7 z?@$dPF`jepDl7U?qQCfb-Un(I$D`S{sE)2ZLq{j)VYO*>VyAOa9k zR8-MV*Rh+gY?{PVEO8YQV#22$gY7mmzbsCJGd%eso#3w%ZH2_trKi--k4m~@tiLvF zZB1X31IoS9;hf3nuV2O?R3=mAHP@Xw$N!cwbwF^)G1V@^7)r**E_Vy>buLND39C^$ zKl<_G2OBln)75f4M@d6MutCT@$#pca{R@Iq^e7%Tx z2JIgV_4MFd{;U=W*9gq#hlZDk$qQ}Y$rC8%J=ou`E=HP}NqRDN)+KpvxJO%$OMh5D zVmQ9idD_`#)BPv-&$Q1yef?KBpTq8OAfQcjYv%SoP!VAI6p#Y$kI~mUl%qKm;zN($ z&4`1=y(_CugT=eTs5~q8liWu7PBY?hrIT+2F~u+Ij_W6435Ml*Pr$F z(k?74fcoq6!l9~rXGojfs*cI_(^0250HxB4+n$81oD{W$Gm(0}A`0fDHl?&Tyg@M< zQ>rYm@^nNwK5eqkTWR<&*pG5zCs}aHR6B2*)^t3AL>#4H2Iy1zL zSaSKfJ;u25fcq4S;$^BbFf0Un6N|55#`x-$y@DW}Z=@_8)incT9=9_U5gS>KYbWZr zZ;TGiEmSu *;5qaP;o*+xVSMvCKCi@KTL*o>>G?kDtS1F>jDV+>W*%Bjs&KEsCr z{37}Fl7@krfl+x%*~ZDw$;sAE-rzDa){bAQ0#5}dQa(}=B~#Xzos&)dq>`U5 zjK}GPjIX?JE&$P?hvQ4cpO2LbY2`_!y?xtkf71}GgczHx-J{Cac*C*bc4m7K8TIwn zW&XAkllzs*^L^(-c1}Kz$nO8D3s-%Y-m3cRv#{?eX7n9KqLLLs2&P^uR6c7AGvRI< zBquN7`XkJ8voI<87@#oWzdq;8*j~yfjxgOyX0cxye)QU3EV6McT!QQrPkuoidEeZf zJ?r&r)IU2!f#HSZ&i`UJf&E%qokJKOZw;qp#dGWUGuI3Ep1o1L3k}|A(#{g3{H&78vZ82C_Q) z8irx}iM;}QS#kVLrp8>*8e-1QuC;-_YcdQmEh0uP&3XW6P+POSb|%EsPGBi_KiLhI z27`saXl>Wv`0{d^f;%Cv>S$aZJKU+K5%g@rOQ|-YR!3BqmD}8}^0%Jnx)W{#<3<-a z?weH6g&-zK*hpHjT8y(cz-WI6QRqjtU`1sM>2YsFEU?zb?qSmUo|!K^au@|H6B%k) z2tc289h&xu%yArLUhp%80b~xq*yl&_QAmu*Hx6ymv@w2C^V{>f6!u!Y?(TXO%(#k-M%QpVj2lcd@_Bvj3k(AHZ{z?{t%`SdF{V-ekxqvU~pS)y;QS#wi0V z)jiUbQ^@bL0c12GC;(IhE7vyu!Ikd5+rfB}1ga;-1CT*mu^%mnPa*7;OuXL) za-+)OL(cT{%@R# zY)Q4pyL3QLWd{U+%c&T29Ud({zfd{Mgx`9%$^M0E9c!JiFm%#5lF?t!n>S|vuf%R$@6#)Q^3Hyw~W%AoBH%@QPpG*6c} z!sl7<8)Co*HI$~_*oVZ!fhrYpD>D!0z+pFt>?idx7of0^{(^N&;n+bV7O(hzD;;=8 ztlF0a@J+u0cCLcBZ!}nvO9NT3WT)8e$ZW zk3}D?Fp(-PY3Gv4Dzv{=v&+my?Mqv6jG7-%X&O|ZJZK%a+p~ycQajGrT(ReDF}-(c zGzz?tKghmTO{-s77cC;N7A$7dii%9+i--j_R>5fZw zgSj`G&YiyX^z3y@Qf5EM<3LU=9{v~TM1_x|x3lsDM`#bYs??qffFdL@MoBYI>kCpSta~xze1nmzdSC0sz*n0L|4vhOOH+k_#=|!Jh6=+4Eub;Ylh(+%soKT6 za)^f%!M|Cb%x=%?<&OAC&f&u$wv9=H5g+eVlnWc+;y>LSAr(%lU`fYF%sXm&WpefF z`_rP1ou*Jk%U5j^oh)A?7L6F)5jSZ-(ly0N^4Vk){F$LE+XXLtlWfG)YSm;7x}AHf=$=P&kg^d>++#6kqBZBmF#X1GiDM=;msx%`Q_c!mm-^$$J$@br<&DiA!HDLn2 zM^KDyS5QiLwQJMJwAX>$`@o*O=r2Au0|0hMBG6m5NgX<#f#}SpU3m$sES`5<+BjYN ziTo4Y^pw+YBLGdNK=iy^2rN%tUl-s7djM|0vJtU()xSolMdTQu1lA)BgtBd8aaURm z|J0G(Xa&&w=)?pmNT%Y)-x`)=;I8|gcB3Ad{2?~f0!vaxd%o~Jjl%-fs!RDa2-8kb zyqCsrO;VqNP|z3>LjSW)p3sMdlAF_~8%@nRF96%UJwF_KdpA}f;GAp~RStRVA1 zRDz-^*4oHjaj{n35(;g*AGFPQ(Tfn1nwImMoGX(~r3teh12QmB8||Vc;YOf!sn<;Q zqa<~Eq&Mfhqo>B=9JdQda6OSx{Lngd?qi*|2@(kvPcjK~A<$@BNRfau+KCA=d-FQY zxOs>q2<>tCQrK5H>pd&$?gh!0Fj9`yv4v;^wJ~A0Du?6zG1)FO53!#I9o1j`iSJ9z z(~6sxINy%M1)UOO{a7J{2ekdzLXx@tyut<}e=(wUrz_t-rg~7XKpN^+lYlzHry2{D z{ag7h0K@TNnqUxJZGnz3OWCY@*wvv>hT?OgjixqH8rOtSPB}vN(F%hPpkQ+WE*C{j zqZl;{@aNS@_ww+Iy}Dd9;?bmI-@P%gxT6thrZW z?;NOS2T|j|@6dwa)+G5MGU||erwSbICBWbH^c2HjX~;>+=x@+%GN8)b^HE)`m3rcz5a(myOW_&^yh5)K!2mYgOEY8ifU! zaOZ&(K-vJ3B<`r<&O>cgC+Tmv0@TBq3$c_wF(3p;!bT0 z&Nj}d2S5^_*nw`>zxERLxlie%O?ArUR^u~ucJ}liBavo#=kF$yFl1* zo-3C>S~H2(s3crmKT>dNLoe>15^OGFx=@v!FL>JnA2>9sM>f847MmB(FG*%2fzy3Q z-efOKA#E5J@-;PW6pOmf>wTPcHcYi5ZX~}0k&Lj~nZne6`V=u*-x50`liZ*kDq+H0$*1CGC6Kz-TgIH;#J2~Cj(N( z6Aw4u>1Xl(5^HpJzWAb|_DWO#=!I!O)iT+4Ft4kfD^(J zbE|iis=yCXDx@#8`;&+-nv~b05)x7tc_*XH%A?9OZ)PkXH-~Iq>`Oqt|K|_^$iH zST&~9YRayU=ouLGXvCJL7doYi>}RSdw*ZER8Nj@Nj(7O>9A7lH8@a}OZykXl!_!vW1k{ok6+ zZE#J0uCm4D`$WR4!U=A~WqXJK+zWJ08ui6`5(nL z^YBuBYl>-qa)*+sQx-ss0Jh8{q|*}J3lw>lTXD7syuU)+ck1l9n1jAdPZ-@M@n^Az zC5t&L8~d4?0qJX>0)bSp{eS2S4o|)CZb7OC1N8bfzl%toUTYJJVMHW?sOzJsVH+XF z?%kwcQU?Z64pDipZdVv5r$_2MQClAVT$T7RQzOY&97NZrkyuI;sgcyiK0WL{ArY?U z7Cd^p+U$S@!&VDw>i;a%to-2}700pk5YpaYZ47RM2|oe08XCBls$5XWCYPVDRbdKE zQY=i8U&1mcG$L}qewo2v2u2@5j(o>qwZc%~@gSV}(E>k7~2uaML;YPzku6))_X z&n@!5c&-3X3)2-NxSAfLFjC^Ib5_#V&(F-!(<>k1JQ&Wnyq`FfN&v7jpQNV-NyaQa zhrf`0dR83AhT))?U&kx zY3h;>jOtC3E$~NxPq&U%C-0wqh89%k=YQjTCH3%rCd)NSoTy)ed)1l`0Q)5Y={KU)3<@y*Z+x@$y+B^G!}Ir8MF3Y&7U{n|tTSW; zIeg5hBN}> z=c!xvjK}O!2S>EMB88pxwQ&facKTbi`f#d75i8M$#p`L+jX^wLzlz{|VJ0-cv~B#7 z{0qFT%~f4MyBxRH5;d6mx&0|tKf38_V{^Pma!I}#XSC~j=_>+0t4zf#baPSdO(Xa( zR}2N~@yW@A)WJ+UFB1(wS@LB2{7AH7gkj(XYQ#Rdo_AM`;nAbl!__0i$zZY?yxTuq zwRDo>f_gg_^j)bp{M$tORMJVShui{BPlyeSI6&l@dfh4tnqayP+t9DBUGi^cV_6u8 zuk2)uk-Sbum`k79UyA=JQZjOfoBwCB?3hdPaqMc7AJJ354A~xkbaHnZ-FZ4o@;BdV z8wKw4=)*Y~)n|qQGR@pmXYGtesifmvi9-=T_hQk4cwkXJQuAwIkpaJ72(K*_OeyI+z^C;B=?*I%0yL`}3M!C^d3_DdY3^ zh_}ESzOZZV?(zZBiV->5u_I)RPq&n&fVbWkP-NL~YO>@32qndEbyWemJ45YPDA7koF+f&izPxmV^Z z)SI-x2araovSWQa5Vq0wb#y01>d-vR*4F1#BAnU54IK+*cZ*i0{`h10fxq=XI#|I1 zbH=&CWd?IrjUReU8|s;NR=;3UI|bA^L2cu&jbb(2)yiMg0v-3%+?T%D#QW91hpkgh zo2!{{v6S9hPVvH*%$sA3$9OvAzIl~B==O3&BB{J6L>QTCRD)|Na2R!a1*{O_` z_7*mJ-B3A825}Ff4qZ}0Kmo{UP;xH7_hmh&3-v`W&i?Q4UJ;ohQ~HD8MJeDD2c9!z z2R2_Ny@d@S7QmbG^%|mH|F~;HU2-HUrvd&b!BWz}H^Q##FMc;q>Y_2cumOLG95w&J z6zMp~r{0IwUd`tr99e_OmJ&HkZ zL(UKqAyAbAxPFa@l`|bXL-J?}=AeK4W9_;`++Yz3cf8uZNYlc^AO(&ulj%gYUk6%H zmqfAqW7rUYay#>nIPi{92v3B~dw*B4Ti6p@y?+lz&47U!REisM;h7JhF8~gRUf+az zpxj^H%DAHrntY3O2u?IGd5Y)=$rW&hQ_FAfoc))tNH~(Zwh`KcOW@hmk z9*X!9sxCorp?kC%<=7NQB%4L%z=HZ$_9$RmgeCJkE*Yn%j{{}}z|C*gMX!xq&b6(n zHE@u;Kp`X5qby0#D_1NO4G)YbO1^^iIGKt&uB?C5mZvSLFrz?Dj~QhKxh?$Q1L(V*?>FDWOzmRtuUPS^<5T&p9KNCu_ z8QV}3${`w#T}G6ymMu^aK3XD(8JOtR&Rlj(CO$GMx274bSm}}jGy)*xMQfk@4MGC8 zpIV89PoF*=*xuD7>oZS} zk-ez@W3*VApJ;E*sn(N{Z(!q}+s4y^mFNVi7C^GjkPY5c-F0k&Dk3s|x}GZtm>{@< z8LvL8{qutmQj0^hlsM>!2!?B#MffDTYyM189D^iB=WK9?=4+T5q>p0yNLt1_Q_Rv1v{Cg?o2*6!jv|B^=;aqr$8dNdOt>hWXZNy{dSgLzbfJgNR=-G#oj&fA7i=*_*G; z;$+ncN47t%pC95@Xa#C*h43Gt7P9L^f$54#-dvUbB-m0;a>F4XtGdko0^0e+Ts7gq=wUYZT!X=~}UAOw)_%$eg}68DfG0Tx%!DI`}s| zx69+ZnYsf;aS9Tp_@p8p~ru&#*cz@O$_&F20iPDsHQq)NB-~O50ok6@h8R_@ElL>q;i9 z!4&eBk8GmG*`qk?)`(~(CSB_)_XkR9VoG(1k>MA%&eDkFu2INO~?hu!@=!84i)fc!O`4&b*6b z8wHLbrhj_#Mn0hyolEozVK2LWCaO~I!n=waHGB#)Xd}D3R-rb!N!ftQvN+&)X-$^l4pzUi|8W{p_mSqW#A3oEC!bi|o&ci4qmr)Du)Rq&am4?=u!M+Y-V!9&_vMSWu8 zug+f~6lWx->En>Q9Qp18fN>tMXFuKje)y|S%}8$9tye3P({$NBUBWJ3fdP^rRE8A;6k%Nde%nJAzQ}e6NG#@ZnHRZ8s z#2glPNG#8>GNfMrEGo&%_ZtcFty~E`6hNdnsTj{lv@>^~;+)~|*z$0jbiswN7PEVw z1UF}R<2o<;Vvi4j_m#-(Dz7j`mZnEYnM$7}j2X)GkZV!(D|q#2-8&KJjbthNJ*lcd z2m15FTGrZTye^3`7}x*;i;o(cnt)lv1JKg?w9rW5H(ubUMB5!}F$F>SHW@)Yqw$o* z?k3tN08j37Zj&1$(HW56W;YNZ=T+sn&d?rkySBdJXhpSvatHiZ=7Q0)^lT;Zi0YAR zPT>m{cOQ%wsEuki$?1)iAQddKyBruq0EP+7_+ki$*@9#4p%FnR0_8vY+2qC(wLzC) zv>F26$opvzbz)3tnINQf$+v(prKkd;x?--Js)g3(?TyswcUuOO{hAFy1>9>ZGZF=w zk6%h9^QvmS3FnldCJnq86ZH@GKGs<|)Q)Ll>U?|A)tsI203N+T)b9*JK7#oNqO!E( z!>I-(D)BasvMq$?o5D);r}gMdLSQF(L| z3BDXIx-vulbmXQp{OEV^qT=NB!*6I{10Md{#h(wx=~RPYBBMzlk{5Ul28lQFHkInY zm#d&6I~{}0HY7e_K{15Nt`JdO&qd*88e#J7Jm0Vc+iNhmp+MOWjMuzxST0+%cvpET z%#C8T%1!iyg@vKrkoKjJZ-8D{8Z9mDhP=8?r^foF`5SCY8EZy9LhG z>n8L&b^GzO9DX+Kc-ry}jmd(W}e)uq2xiw4fYA>QQRZ*V&s03xb zcOF?q)WbYtX&G(&f2Zwqh~QTCFYIuDg!{-RCi<1oBT<}fk`C7Yv4~YN*|))%a8t(%7=DQiBf8LJqPn8fDyI-(x!=B6%GNM!x5Smhg6Dpj;Kn`8 zsWfdWa+35cGvDoVE(c~l7X^ZpLI!GUd*Or{S4DP)QV#SZWOk$T6%`fJ-n|pPDxn@C zF5a*EF$OWtAr6KUkAbfWStw&Fi$is7etY0e%?{h2QjC7m;ldbJ#)s9aD|6|UX?#AX z6?8uL!@xG=Z8$`c9&C7x@(0Htt_b{d`5B&Q!_jinDZ|zWabMYmJ06rJNpJrHeKLC; zGrCFNqCMDN@>;lQDcc3naw~XW;tkxr43Jp-Jdq}AmY%h%K*X+m`nM|p*tG&o)4+I4 z2EaC-ov8o=y4kWoiWBbAA5iPFz}lOr+v0HQSDIAh)O>96N?!_*Dpi-jMEL;=o70;W z64E8iW!6q$nnXDJ&1%aXaJ^@ksl?{yY(bn#3mxyXIle9$T$TplF2!Oh z&reZvh+d!v?R^HdG`V<%nloVB_!c2Tw0C@*ro(g@;>pOlE>m$L;dt+_u${`xZHp4GD@GJH!}7uOY+z^bd zTw=`lew$^0R!IQ&LFdEJb=jJKG;*L2JsS!&7dO4T{Q6RthO-$&!@r!!3nZAzXygV& zKdM=OD|C>jj}+CRt|9=E(vR)sK(T6mm-XZJQ1q_d1PmMO@hMq@cu%Y{`o#*Om>+Vj zs$6Wu&l)Z$%S12eaQ>Kx*2zIRN)A+avPM+??tQ18*RmB*kgaRrXlypgHW#f>#vaH9 z^{X%E_aFG%y_Rs8>LD7*;t|!vgzw2>j0M&# zx4SQcYsRYdZ?eowM$hB1kw(n6h+sDR-FVSPgnU7JBYvk-eP{kDg}9+vmxQz`l8R=m z7m8t<9`kl<2j_>Ra;;iEH+VNi)?}E!HzV;-lz)nvV)Q0S==V^XQaIcUrSp{{ic%Ok zo3$Oi%wQElKOFmLYY~AH%zjcOvL58 z&dv~PNI=d6lPmsCjN97dg@QaMu|4OCkYEF}{oA`#y4_M@?bW=?vEVR`^+(OxFHJzho8WuAC95gjF*xZ4) z^-_?tU6H>5Ra8Y`a=Hm>mEw=i$N;=>w@MC1oKQr zalbFsa)KWcS60khGH`o!fE-y{TWj0GzAZPwmPk^1R9 zQ`_#v2vtd# zK;ixaF?}L6uc&CrL$hx~auisLjfYovHf`D^P7j-E7Z=Q#7jZgj!Zrul$(&}=^AVfc z^Fj3LKW1kv=@}NFg!C zf+HDVbn+psD_m6}GzD^WX54eQ@!;W-5}HR*2tZkQoA^JC>Ur-1pN$Eo`1ar=6&XU?pXI)>z=az_=Jpg zCu#gyg97^}Lws1e1Z#Yyk)z9s|I1;6sjP&>pH7CW|JodYHY#S};7!+JrMUNHSye^# z-{PqMbgxTBV1_(7Qraopofvi&%d{Xi%)E$@WMLCU#V<;J&akZr>C*ZPLpPe?5A3|> z^__yr`P9_={1o|x!1w9KZ*8Qc#|em4rlwReAotZ@&gr!Q3Ta-`)(8nQ29tKnf~DSOj)@?(v0`uR@0# zii8WygzUoD1!C#|D7SN88Rnp5Wr_q-Eq$bTY}+xE+@1tTlz#$kLl58+65IX9iw(eK z8Wb&V5rKtdbJNo!761eTT)U+?FCnd^pQbeh9ZFg}1ZkB<{w^hObXa)sEQX@Fs1$8Z zlL206DYt4r<(K^LsXj2;NxcGLNMeHyPyA6p=XSK}NFB)&XzfF3e`BYrtN)J+P=b-D+3dCo z(P0)Y!ssC6^UHu3dxg~vXJDa z$pQaj#9&kYg2CG9^XK-MH?3Em%fxb9OMr62f1x$>7oFNJZsPgJu0=A6C&_ZR0q0Gd zw?;XRO(wMChlqSQ0aGIGt1@pbf&~gpVvX_;9-y)015`FJ!*SvSbk;y?7Gl=5XibCN z-U>ihfKea@?CvH1pO`^@m}p_iun9q81ISBqwsFj70IV;_Uc8{C*wPPZVx#E;Fo7YM z`rYye5Af;D1`;jF@YhrFE-Cye*47CT3{e4qpN?ChNc@T*suPhvwe&k zj3FpAuZi`{)r==XblTy?X8WgU&y_=qh)0?{qbj8EP0V~H=ke{Jfr1lXo)Rt!cTOCq zqvcVX7x<$=IpA&Zlw`EhUatc1==Whxk(Fe9(J1{YAX3EVd>j=P4wQxk5EFWkEyIYm zQE{FKBBD5$h13#&(DEzb$F28u6G4CjGo(Q}sUx@b-H4BlHUM?y?~VMJz53h32!kgDCVS0L+x$WY4ZXWs0Wh2Kf|m4yxP4HUY*7dD8^nG!;T-T#cv z;GpYZHFk_81nRc+;&*V6O_4&R5dA(eIBtXXtf=DGhcq3rNQv)2aT9}Ac%i9E19m_>s7iK_0bBrHzN3|AnNb`i%;Herc6lHV@qnUfkO3=pe+K0%$zi%)wwUaYcae>`ujhD8Jr!;wrl1MZT* z#h3KxmRyZUqLzy`H-;-_P~JqR6 zPt^xLgS_14W26VGgKJ)89O)M}xgtG{ZYz^74+}ps_kJ#DLMF!3^SLEPqPo% zmLRx`wDz2%zPer1(@^R+<-AAqi>RzL{t-Wq|Mf=1o=dD5D&wsclL5CLI7Q zNG&bcA&gpar>$E?h=FG_&Orwx;67vPeNuPD>O}(vki}PjPw*M+>7an|-N2)m4DXze zPvo>qENwU0oaUMlS@e9%o%s3+LrT*?+w3HrnbUNt!xOr!xA6(6lw*SPu9#$LzyqzJ zq-)(C830t`a*KFoYijo9SJ0OI38Ut~apuHuI9k4Km5kc215uPF5eGSJYc?a1Eup)+ zyLpFCa95Vz&amBsd$gA9U@<(I1U&HD@Eya~JA#2N^km!DOsTwZAN^r5`5gqKlM^6F z%@95F2HZ{r|9ZC_f1X9q6@wRgp{Ym%wzKOk{eE7<(-14%G+ieXITh=}R;cZuNkcVU zJ@LtuKpjfz{(B`sEw1Asa=`Dp7}JM8_n8;5*B%Z`5$6cu}E{O2P3K(`!Tq+ z*NJ#9Ccs4G^h3qmM2evdI^4_xQ=sx(1`VPZIQxa6s~HY~zXfw9TvjspCUuJD&xRWn zmP!YJkuvWeBpK6fC&#Z?Df$HqJW4rh?8#o2EQU__jN;B-3TOE^z2DrFzO@0{I*T)~ z%)_Rr1LZ<9vwdTg9(2VTJZBtMD=eP_5`AX2a8EvB&U(5%4$~5aMqj#lS+5s^a>o4A zIfz{)im@TLk?^0f->v&gTX9hx=BnN_kqDeaoPSPQVbpAz?s0Xy>%LVkOdH?6kv)1# zoRge>)hn6iQ!!a@-EBqZOe`{iUe*k-l*HFlxcZS_S{gZd8(h=VHA6jMO*$DFl}^wK zgO-yb=#*1mOc`wLBpa~jVRQjzfUmf5;tx(^x5R$k>jBv?a60}Ro%?#L1zJm|#MoHt zw{d6Llv4t6@36GKPJ>j(PdVw*T=HMDV>(65WI+70kPiS3Xmkc(?1FJuVoqydO&%1cIJH`yhYahIxXkn>CVMK?FdV-qbmAmJh4R`#&;;lGC9pv z09yne_T==rMPMs*_{D-5B^x)Zz9MBwhEL9W5A)UeV0+`6y%y>%YhDuZB%puh*V8ec z?zrL`{h*oIytLr?!adLA`BdJ-A00DY}Cv98P5t%aCVUU(#Go0fz15oC2(_p@fFyLl1gFlAd|xj`MW)()vwn z0R8OX;BVfOlL%-3u@6-B7#yaPQzdC6xXev(ELyv-=#DuW@U5MldgxQvENS*$&A}@~ zrSK$P(-5W52Fr19Mx`%D;g9*GvJ4(0Z5K%^_A@OihUEg6zs_9LcOt<+`i2w@bpO0% z*{)}D%7W$~Xg#9PvfpRz=k~r#ORi7@eJ!|TEK zP!LdNH4)B3NnXo~1F2^cDXu`CqU7esfz$CX6uNYNOgupVC3BOWtAt|tmQa9|`tJ(~ z-H!a`-Q3C=xQ}oC0>4#n_pJ&t%CH+O76(fxtf<>5jgcUef9CG`D!EP^xyjg%6l3$b z?MpTrJ7fY$9I%+|uC|EzoBh}mzw9ZWsYb<(vzctjB)gw zEEk@7Gh1KEqjN0=$JFo`x<{S?r^f5H4qek^cUzX0Cgp~t%YcQzXIhH(>eH#_K0cA; zJ@+&?^e9l#0$LN>(|=;=07ew10HOnE^}$>`JmyayE>tw~Ajr579Vuu`D1L?h)sjm# zpmA;Qcg&q43oU4QHBRU|k5l#w8OL!R131a8v$#7ZiwYTlaGAN_Zp1VfQV}#0R~z|9 zTcDS7=%&XD0JKN9+*yyMEWR7FkgRw=XPXdd_rnaieXGZNL# z1NucOvV#49$tjbJ08+K&CcVse#hA%Bp)UeDF1hthIW%IB1WctAT z%lc^=`M0jrzj9aX0ryEW&^h@TLZ=12+t|F9EAw+So0|P$5f$Dsx}aIt_N$}nKfYAA zdd*Td_HGlYRi+~RUaib*++fN3Jc88=q{(IJE9kmijd&g{V>{{u4iM^>7urP&5Kdhk zCaB^1dEWh`8*z~!!4mJLL5Y_rZEbTg!jkw@X!rnFu5lkAl7Ke8#3C%>Ur=gmGz#C< zpnbJkaOI2re&k-`U{)7;qJG5TU6l@C?NYl8S`=HlNq0dMQNI!^}{|-~S=JF=|8tfD41UUxG?>KE3W_G`m2bF< z>+Cw)y98+BtI*MEq!y&EKz$tH7?f0C@eyOd9F3MTR2E6R!woPkUO73bakMyfCe>{`P{_m=TqDbc6_HYEMkG-*8@5+ zdvvh3y#-?#*}!Y~33--frwq1`!ms(zP_?S=;kTZ#JmG?2=Jxd-d8qJv?b$eguXiHn zBG*1~&0sdGdssuxcXfdybZM68-l;FF`+~cNC4F>s1X@|k<0wVu!shB0rG+SNT|w$S zr~!u(Ez@3hi!T^03SUE2VA?>V+?OI>ce*O>W=^xkHvQ>OC1yM}8q}5yolL?&oBlOR zpi~IqGq!jO-B-f_>x z$j;Sw4A(tF3ib@2vVi7c2x_PTds;BZTbX}>aEni&HFPYe5NNIdeP3BmLOL-V=SCe5 zOmw#Vsm{Ib&QFpsJY>^UW5ENDx75 z32n~Mnb7`|lH-YO$Gse{cdnJ1V@_(5=8Ejjs^3zaDO(EXvQTXwlQ&MZ@Mtk>c3+nC zGBFn`>c8mtIxLk|(ZJU8{>wdipWUYI{eQ;xF#oKA74Wn$v_mu3$q91g2gg?PSZ&=` zOrDJ{RzX{kZtt+o#n-8NbQDj~NrPFyIfe=qkbeQ9{m*W)Vp%jc;m?Yh76F$ZfVW-B z-^6XH3~)dZe4EY06`}~u@l*WGhBhNdVNIG7MQjTu#!(TCj|u|C&};+>#6d9Kz=K>5 z{6D05+%o}la>B$ADf8;Fw-Oi=(oB9q#E97d!EiU_%M47^>Fn5v-VN6jh#2FYGyA$Y zKZcMg5HN0)*>BzuLxdsyxfy&2w-TjRVin=KG)+MD)7KpF@DE~`C-*w;^@XApZTY}} z|5j(G#yg=C0i1uFQCm%+skL_{aVQvCt8I>kD+JQ zCp_qxgL0F3uI#mc29f^GcitGsl{QxWSA|g;Oo{NJ#xp9^P_HticA`zb+cf?XMbfpW7vF(i-m}2l~@#@2U z3(+>iFB9Tefxpid-_I4~wDZ7f_&X|wj45IR=Y)HiPQ(=hrOTcs%MgyTXh;TlFxY&f z;_be22AT-K1PlO`#IJuZ@6coZ$tC*S6a9g0X#X>v%$%yWt zj+QASFg{5e60stpWW#sdl)b!5vX({IceQpR52S zcGY2kiWfh^Wn=@!g{?`B(@qf_5(6jLCkB;j5IQay zs^l;S1#S>ZCp6U0jFNcKqc3@=8umC+4yZ3WY-+h0G?LoV$!@11~-Z za!i9g7WgdsaXaqMX?J>N;b3rx=!F7=lJsbKUd|9OnacB@yR_L6py9DXoNA0+`YsZh zYQ3>1UKt@~HYx{8c!c=p`0D1C3Y)!AU@Icv;;$dNrEJjJCNvvmqxOQK=$~eHjkNPP zDRnug)PdmG?FWAw_KqPdN*!Aeu^xTY^CSk*DkaiaQOsunP?2QWah+$SgRD%=ugYGZ;8^q z@v}7v994B|#e3q41Bs(&an9!P&Uyq$(~2{Mo0~nA*S&?He% zoBBL#^Due%=f*BCZuvmKywpRO)rxo(bFN^$cvoC8sJJ-`qY$0dwD>jULf(aa8JfAA zpkpsRu%8P)?ficJO#9YE<{#EMXaELrT|Ao@`B}JVv;I|7{Ov~7Y9+mnGsl`-^5n$= zjHhYd?EPPI?4z>dmo`m1E)XT)xCbtOk0ijNw{stKU#hPrVnZfbZp5SM#6AGpG{o0Z z_Fdtti=6ic0vWFZ&o9^My3!RkSj89YH=4Q;pl<{LcYLKJkD^jzR zW}`SRC^Xoy&3r$<;OxKx45%C?Cg29j{*@~$*s_dmWW~k6Ebw7WuPiJS;XTNg1a-XY zCjdB1B9|hf|Mt^)Bhfk~B0+kfxZ}bcn3P)@sm~cu5?GjVVPn_MUh(hX81NQ*50G)U zc#6Osq|DB_`1CsaSdcdhf~Fa-5(|#Z4AT{EZj#5GYS?v|=CaVop!3I$1Ae#f8`l?{ zA9%aMbE8r+$A0i7aYa{O5x;lusfEP5^4}PLnV)@&2l_dvCXOK0Bru8{Kd;?=UWoA* zOG@#3BNu{jSpvY_KtpOjpDCru$)A7WYmpwCIPa=BFbXmK*Z)bwP261(1MREv#VO6l z=vbW2XNS+hsZF=bKYdG(a3Qev&&VKV6UHfRR>tz3Zly0;t7IbxMj>uJ#GaL}!h%*w zOZNM+VH@`ktzqQQ2~J!8H1qFvWwK&CU>;|C`w>fNPqJGbe1j(eXu>QKohLwUsr7}* zm6sr}B`4%Hm#ULd+w~sq^;-6|LTn4}v_Z1d^BGTi<}VZ~$j8W2S4=CuQw>sIy&*#t z=fr1k+&W948N_qmP3`TvGJ)*JE!cQ{Pgd1;%l5>D4GPw}C^2*80pmG|HAJ(RfS(*M zei&lV5dXA7#6`HMaHq8pgHPf{Hz3ON_X3u$^QG|hP=3r(_U>OAIQQ5fjtu3;tkzuM z!`vwVg1z;xJiej`3mp(%kY=DC4%enOD$L|;Yc`L2KPQ}9^W%bTGBI-SJ~wj`dc@UQ z1h!FcGC(B)unJYP{fUA*LBM(dyS-3V#0Zy@IQr4ytpJT#9Dw%!FI(V5P}3O%KC&G*SkG?r79ToV$N7;&;!J-%krZ1JS%oJ^l6EPbA zwQ9 z+0tr&miy}IL$XDOxb0Dy#k9O#oAs)=%uHIqO@h33y$2Ftq^ibVt!`Z96a|O&-Fj7; z8i^46O&L6x+uRJj{y-|fMY`V9wWh=FhAsLqlEwGVXr`<oE-Oj6S~_0zd%fz+qU#@|tdP+*@ah!~Y*J2-k&27`_=_sQm_)q)zYgEH z3sX1`dLN^hYaphX0Ra5;2J3YGc> z5Or$H+0oyKBRFG&MoYT&qt#< zY@0dkv5U9T6f}A%wLnySpp5Y51V{N;}3P$yqAdP4je2h6DT6cj< z*Wz$}`@ZAyAB!^?#((HK1h@?VW9e3`1ac>&K>ozHaC zh=Or-4KI#_ZL*kCaj_nrWu>0Ew#U0Ap3fh8qz=Gfr1k*Kz0fi}faFn8F>AMb_tush za7vuBZaWjYp@98%L0}TVV-dfI^I)NjS)8PxfYHMl?{-a zicf+P?TpwW_L#rLwW}(+47j^=3!A!N%EC$9cs6wMYE8!JIFWd6rkra>O19L7luDEx zPaY{%x~_d@0)4L^Z+2Oh7U=t;J3RBUm8c%nCBj-a7V#DG&=TWkkQ0%;}?} zU4$%^xcl^q4PM&P!#;AQh|A~rv2R*-vhYm3PxJv@a#|Ng(LS6-vf$~ z&k$c~Rn=m#QXTKy(je{Y=aveUsf-diIF=|XR|%oIp>TKLZuL9{vl>^c`E7)`xJf;VBq)K=;@`yUs8 zs#~@AAGJTgJ6FW1v5#P;vC|kBfZ} z&P4ZV#>hD6>8!a6tQ&A`E9r?(r-v^OY{E|lrYJz@;JGx2(E3&#Kw0`|PwnhwjAiEY z5!;t#5|qWM!QaW}bt9yDW0R6-P7_q7{re@Ua)M6V0bTpENr~c6&V<4dOK7LN3Rr zn?hA>jdRlNb8$cbvNkd8G5kobRl>HjM*Qs^bO7JpVIww(kN<{w&Kfxl?Q4avz<$&v z733tB3TGuikIDc)7ht!8!;XB{4j=d)Nsjx zcspO8)Rb{j3XoR~GGMVcPEVM4>*r>D&maXwgFxffu98#vk_&uWkKC#p01u*D=G(E` zY^D`Qk}xZ(_$C0@E%mx6gURk?+t?^(49;o@NRJ!}G`g zo#3Il6%k~b<(&7+f12*tHYD}q%$5$Y4=3`g{eOp<(EDJlf+#`{f7>sXlb0O$4w0#> zdri!@&#sPXgtUv$#iCkr)l%%|Ree~aqLPz7m>L|61>{S_S8^mt;5-KtYp>#uBcr?j zuzaDsJK#dm0OzRUUv9?K@KInGk__aId+_cRT?L#ryKB3;XjG) zYszdQ-%F>g4E{_T#9{K6Rm6MG1o4l*{&g;qE#D;*0`vS(u^6#$PL4mBkG)KM zKi6dTT_m{~a3XV-{xj_b0}b1w{K1T&X}sq`)vd1hX-LqlLy)%`*X^-h@~Po4a4!xo_8nao68 zr9h2q&8Ph`?bB~ksdj18jj)tl-w#af_bcHN(UctH;P4jmj-)CXU~;b zC?vX}S^&1g)}u{$%ZU0~^2yQ10N&*TW3oknHlbyHkcepmh2^TmJ5^1?I?~F(d<%~m4LsmoIh-?6N3-`P9nVuGQl2;#f;cF{=&71T&Sd552 zSs=N?LQVqk`UW*^UTns%A>QenZ<|<16am1w2QR*=2cVc21p#$s36kM_AeGhbhl+ic z@4B}a??2+Gq4Ep9KhmqP&@jBnio!r)py-7-O(uh(7UREy%4A-Za#A3I!m-&%-tjUI zj{{4mS}Au6$q)#X%!(8_>{=AV%M{APTeXnsRaqjfi3Cf5M^Hyvt;wWw$E6qXZa1-j z)0g4a2jLfq;%cg6)vjPvA>=VLsHY7LCf;Zm!rWL3$8_hk%0joov2_Zh!i-dXs6fCM zT^K~3JFKg6D#aZx*be#OZ!{)~K}^{%0P5PRXAj`V5%uMDtaLQ0UfJrVY>xo?XIWAE z)#!UxgqoXsm>$!oxg7U;+gZAY9~94KSt*thg zcL`g1Ub?ESU1#0uwcm_OfyKelqDUZf7l^a_9{0uTMJQ+Zp9lzFp z6OCUm^hekBEy9I0EJY#$S3wk&>>Z+<$Hyj$pjltQJHh$Zh3Piw@NOV2r0>z#09hdD zb*55Ukx?}V_IZL$BC~)RBk;ISaq42CUS=3gE1#jEX5SCq`VyCpIuMi3($y2W=cnzH zGB8tq1(@MQMMV*IwG=*kE)~-E?o{uZoZ~Y3Pvu06`mo=3!Ww{alo%@a)IBRp5Ja!t z^4b3O%6jt`+hZ@+o)0K7tLlgq=SFj(NN8%L* zI$r+(EYNNXxr#f=U_mkl8TJJwg^ox~RiAliN0E^L`La?!b#ZKU9454&hh=Sgp-?)^ zfN#xYnp_hDZEu=(p30s>TkI=`x&@z*3ES|OsTL>_^J5bxBj9Qivb$9IDaa!TiSluq zT**<-l*~=nXwu<6?1(dERS6LvIi)QHeZg3XKQYhocR>5p6nO<1Ej>)9$*HLm zsQ-659zv4o+WUdjbKFF8(ntSa^0^|HcA@)I(C=45{Q|2kBA9P&uI$%Uv>h!py?8r< ztEvAmuE>XCG(LnV?zpUK{&ax-TG-#<3Qphbjj*foU|<@j2Wr~i; z-K)x+)i)u3MHW2))JsNHbs4tc9v1Qvj()3=cDzksyX67MyL*G9Dd9-pDCFI#bTB}4 zrnptFUcLypis`jLH+$5Eea2Yo{ZJc~+e6GhYhZQqeNMsd%56V@Z`<@MdAW+mUfp%; z?;ABK_=V}-IWNAJt3(kB@XVHYZY&DP3N|YV)(fjc1qou9GmBC8epHz|zsa0Gb4+Ub zlLAhQY9YyhWc}UQN?S>HkF?9s7UgUk46p}{jJh6FjYdYW6D8rcPITv=Ek!lIN=dLT z9GV1dd%1uNfvQ*WNO|n#P_nK+>sN*tGQyY5{efKKLAiY)^T;t|Q`Y!G^~Mc65yUQh z*kqs{703>&$rwXNzH>}|St?pIP)piDIiKnYfDAzFh4@9aG{NeE*gUdqJ6lz}b*Ru3 z@x4$-D+Fq>p1r8TK|%K2f*FYh3gPn?aJ70B=cXzfNZ;AU$0!5>4_%FTcNm9+r0@&y#Ns z)npBUv6`JjGkR325T{9dmF9j7V6>OaYl@kZErGCDUih*l37P9)o4al!q4I;Qg$_z$HQNlD{$cx3Qx zRl_l(iof?O(E(IvtkHlJ%$#7)G<1J~R>)TXH`mdM6kw>-rm!~CbFFMX{5EHAx~51V z<-YVDZhrJ}*%xp*vX8)P+Aqi7z+BRbh4Q?=1IKA=s(kuc-<|v5H;mX=^(S zhzCzS)d4@dd!>2KmX<=43fqnj0srd6#0h0==$!Bx2OzDnt-RdVO>+uUMY>sWE2{io zyCe(lHEBq*AY*~OTWj{fNDG*8Hl1!;?2SDrYC^cdFy);=7?kHQ+=E7 z#&-X49cz!6=^$`FC%=&=o`dF-zu_%0cXbwx!dFIH%do5M- zZ-P`891F)~2P4f*8}D)QRKrvEN+uMgT_>5!bUyZzO#4}Y|AIYlpci(1>iDXl=lYv~ zF2V<*;PcFxe&QR>DVvOdt`Bt(9#FGYt3V12m(Gzyn%O7WBfzE@1`NMwH zSJ|wqYC9s2^fB4d)~AmOoRONO@{)_HNvH@U4;^GawKr<;pN$;Oi(jZq4}=RlJdGG? zl4^~|vtFjYsB&;LJ04d%00e>GD;@naj1T0cmPol-q({=ln;yFg=dN}oVIs)TwjJU%SHfT@ikyQ?V-DqMNGk6F2wi%sK0HWQiCx3C`v5;M4 z#1n8V7Z85ySb5OHd-)i&AXHqe%}7A-bN|MA-`IS4VC=<6fO@KBtYq9>TvNq3Np?04 zu4FQE0AYDHxLaB`C!b&B^AUHV<87`a=85_1W(>9IqF3L{?OyStBU6oj@#8)n#myLx zWdAn7CE7t|0Ar>9`Gk{GGgZ65C_et(Q|36*ZVqFpFSfL7T&+6Y*3T{R5wV#4i1|0k z?CeV~)?b{W!+iV?{6s1V6`$!>2nHswQosFW6Y`A_Af%3VWvxP42&st4!?k07)mC$V zADXg0F0hY^N8@7arX13XpvvVLEnj5XgG&eu#sb!td`uqJqp)%DLO<30f^}K*(PjsD z>|v1^Tw{)Ok5|iJQ=P!InZC^N~0TAukMT43qp) zafEtscL;ah=s8II!9oNzT3Vta z972|o{=dsD{49;_;VT7-R-pOIH3`YG$uHK~SMSj%jf(g}dnaR4!)w0|4^jUyEw!5J zJ!7pSC8%-iSYXf%V?Db0*I!GIuN}5^rXZgtBaPYrzj6tu8TR?b(&LAV2cVno0oGKePLb(%@@6onh~4IC(|-As5h zvj&KYm?(upBnv};D}M0h4%yN?@X;%Yw7nb@2}J}^e`>tqeI-YxLK+i2ebi{BVu+E2BlO|f zfA4I*EP}J^YqBfyqf{;|HPyBl??bZ;r7^KfNtnW6AWz6!?9wBPEl7`STYTMl{UbFp z1;Z`+Tad)A9+C;9be)H0Vqwkr7dBxSVmy^X2 zJ@0Y_5{#y!>578lo4R{)(Ee`zraM|MZF>dUoHd)VIkVq}aM=!;+TpoN9{g}(eMAX- zYHe^=URqUsy*4R1n>+1j|5-mYFlZpK)TllwBJ57dP)vVohiqG3kF?d*o%pWhH&I?k zYxj(7>VM90>i+DEdty-b1C^4^?;~*R%S?XXu{(eJSgTi>+thlb4FkkRMlg(09I(vH zX5!X&>`5TM`HLl|#((Tv%)ObR*KP5APL9U zdY&pfEl^W@O<9yBL+5qjQ)(+KM?B!bvnP{H)-0yl*kD_#9r2fXeEZEEEoeGbY?l(m z+;qOo=aXHUUJt5!_I|UJgh!^iUpsj9k~!=NI`?Y>4=Lj7^k@Nv- zEtn$Gs?;N6if9g#o3@srUCw>X7T)>}xa&Ih2{O!YA%6a2I#SPRV=7ONV?qbc?=wa9 zChfc~lQJJWunZ6VLk9Wz7~jdoJbo98X#BB0>Oh@r_I(p`n^ud%&}xiasBoNzD7=e_ zQ5D2*pa7(}^r)z)iRt=q9cP}|0Nkk1ErDz%I_ipZhhep`1NDk#;Abi+EDbZBGM3>* ztdg!liqgOTQ7midIXwoiOlk+!l?xF(%M;B4p1-cX9z2quj0)D`qm#_yR0}(e z6xqpTQ;&L_pk}WdCK-uNd#*@hNeL{+FnEw zGzg;nd%6>jeLkzsM19F(iz&{}$4XC62c$$XncYtk>Vqowj@L?Yo|1^t0qJ7v6Yr;X zAQqaXpgV-PKJa~wWN1RjKVWHp3Qb@sQRI<)oXV-+0hcclp*stF8X~O~&|*3rlny|0 zB8RH0R0+M~bAF@VqR%*{G3y8HSmqPVCj}J~F@S}K8q3~ZXSVeZkcpe7S0|0Y2(f2n z1gjFqcJB13d^y)MN`OjJ*#C3%3ooaH`>Zuu_EoE_u|3HEF$ut#XR)IrYie6$ni^+DmQL-> z8+u?vRowVnORe`R0sig{eeNz%vf2cB?}myIuc%K?YhOuwD!ia0nEw1xf{xOW*~X368D&O>HVdyplOS=dDaV zK0*7(Nk*1U-=|88R7a8WWMvJ7Gr=mRSPfOxO{W*9#?0mIt`Bc4UsJXF{#HV>CH|DP zUeEe!F&id8<{pKN2dikm(t1Q(ujq48xXYW<_D0iomZJyIYy=MvtNQ+4yii@fU!ueE zoEeIY?+0QUg7jeyi)xC~6*Z-rPM*PYyl!a)2Am*SqGavU_)1%(ouN_sG1qb~i|T~k zgNHOUQn~635y}QUHTZ+M;gp@#`}~FtW8O8g5<|B zA3l{xW~t&!JlLSvt9e{yn~*pfpXa8s{gAlOUfK7<3%4}^bgK{RFfax_pT6$PUtpnQ!q}364To-My~lTXOW5HJRBUwe>Ef}CnYF^~AHPs3QpfCm zwWcOjK_#`9?rNwkjOdSH$tG-&HM*~4$A4rqQ1Emo<9p#VtQ*Vt z#^*v7L0CZnggy(y)U=P!5zY?wSF_DROti!TwvUw?-0CG#7)H#Mb$(Uig3+InN6Bg#^QRY)scEyaA@O)LAq_rZqYMn6^MPKV+nZ29GD#<$h3K2n`nQ|dF%MD60%a$sOjAI4)1xhegHx75 zj#Dz9Fu*ZaJ5&u|M1GlAF-67tunMOY}X;V0bvo z56jQb>e=C2o%?+<-A|LBrJAP2mNlvOQO2rb*Jyk2?sdFSnQUOY)INnd+Xjt!&?i2h zefIe0&b6Hs^iK1Kc!>66@+SCwSy7QJ`wcP#TNuw_*68=|fET+8srC|vhwZrKsu(3W z(!kC8K04?+I?8YMWjFsB73R|FQ-bMMh^#ui$OtzK(Xs92%mMassL1X*2l~H5$NX>n#PHkXz3-QK*e(~?fIPj zu*dLaXaOfDClj_pY8_s&U}+NSn|?fypjf`RzOGFy=y0c2PZW>?Tk{wyI6#z3{>KF% za9>l_w!?o%+tI4bvXqiho=P*#ccqfp4wG;v}1@(V21(tTFN>YPznBy}AVrw=9sH^C8Fi|qz zP?4p~Bo@CN7%OY|`-&xPdb*15ueem+E89^%IT7L|#EP4w|js6dP?(MkyPdjT+y|2~s?&S2nW^@7%(M?w3U z;e_2UgB#2lCWZ$Wm?0zK*9Ynpg-h3TuT0#Zb2s)g8M{rq5C5cS%Ol(9w*D9Y7;sjG zZWFF70Yu*4-{aFh%X?e#i2&AI+Q1x+@q<%Y9YH}{vii+kTWFU2?a~R3-L$`vsO^fF zamuhh$}iAh7`7qU0lU)kh=53PGizsyLEoJ?A6jA&({aT&wMV3AEk9*!L4HfsbGx<+ z3MGz-|82sp?uc`_9&r68s_SbI^^>n{9oHX#%Gt~nYyQ*2p1Tv+LhW@{WwMeJomAwD zJ@jf5U-@Q3lLdjyvB+AVfiW@|u!NCT79rHUE+6`Ku{l1G{`-lS%K>02mCalqt+lox z>u^EMPhVN4aHinq_@f!uK~X`WM@Ho_&KIkea&Ysg-Qwiy=N_Dz3HH**_3RBGS}Lj@ z6pAW*svSn>qEsv+D=QCoo1B_TQUdbr8_@GS>h6>F38KFe?!X#m$xtaz5&;Kilu19* z`MVsr|=>o;J)!BQCDYWCGvmWJm&Mnn zieh*7@Ob3Mkh0#;-cbwAd#t!oE?=bN{7U07-6Z%~z0gJ_Cs|yDY7=$Y}evV57kcFz&6A@4>qAA%U+C9>VtWw~{L&lL7 zW0RwBrli^WBKAf9U$64gj41Nf`gE*hB#JEYA&xghX-^EbXTQW+;dl5)Uv7M!a>q}C zTjDR+QZKAp#e9pYhwV7RFj~2ljl&f*v`0(IpGb~@Yi3?g_0SX|wB+=i6I|F^Qd9EF zYpA>J9i5%;481-AfR#%1)F*$qh{5)qQE9P2}k11ljZn>aX>|SJt5N1U_t1 z73aFZZ})y{TPva!?;)q*kUu3pG(n?LhMk=F(t=>s^$}1WG7&km>F^h*NR*mO#& z$SXgWTY^ERAFk*WHR9p90ty#s-RxGR!ek=G?O@2RozIW`{nDo)mORMUpL~M+gDGkV?BXJQsFEyO8PW(S4 zgvgwYICKV4OOyYn2ytd^(jYUGQ4S?)4e~jq$e_pEiobEEd#Tx($_$FAfWv|5O<{6wB-`EZAp)68%vzY^Z)X|?%tj^^bk3eC+Z)8#l z3imkOZ&B0>Sbge$l~1g0Y=9#F3-;TyNaPNcrb*c@hL4p@$4+MiH^$S=W;bS=(EH4w zX4F>|e3(8Hhn;tV+p^+o{0IfPyUkO^@j3{>*y%X{jY>+Qi`AEdr8U_?^IRF32M*<8 zwHT^)y^@m;rqCI+rH(;NdDyS2N`cmm$x&MdEV);~~EO6gGP8VTuA zBt!`*sR0CrE@??cKuV-@7*YW#Vd(Bsx6UVGMB&-1NC z%#7k;6c-lfRHqk1p7|3amZFY~JEcG>V`DvXKaRyi25nH*YhM(H`$5fkw~p#~=)@r{ zLP*oCG6t#yKr29vfzE z)M8Q_sS!q8q!Z~_H`_h2lRfgUUFvChZU<+GU%yc6ojf`c%sy%mKGM@YpmtK!15LMO z379B;LMSyHiVdrq{Hi@tFc}nXK@GnZS0*Oer*(1(9ai5FD0c-QmQm2b+VQCxYiNZ$ z`v>Ko#M%c{xf4t?`p4&Hx^I8(Lzn^)2-B5gZHbZE_=qf+rrd9R`Np9=#Sg!|55O>$ zx|S4)k3|zly@2NXCDP4nqjsr#TesNo+OgS~u`VmNGu74Ap-kZhqUpL0F|R6jCRWCT zQ9TYy6tbI}sl#09gP0N;1Pad`||)Y(NP_yxFV4o=Br`pnl^Suq1>0)aY-*vmi_Q!4`x{zMn4&oHPl8< zI8$V)$5fr0#I80{e1C^fdI>$D^S(wrZ@(Z0odRv6_aR1)L6QFXa{vB^9nWj_ z74=C;7}AxGS*5C5Cr(nzX6IH^ASKww3^-doz#v#LjU7SD3xDXB2h_*jxcX`M+Qr`4kIHaTft|no;qvS!?MS z1pZq&&S>VlQSmr_x6)u)`hGR?JC+~%!+Vhx09FEZABfRt%YQytUhhm(s0wE1qlNtm zT%Y&n`iVZ0NfXy-d*`LWaYF$nZ0XeSurfAeEzYky?HWrx;v@(f2uo|Ani9vPh} z457%AT{u~o5xWRJyz@}p_LoeqD@jlWS0aYQ>m>3*^hCaVeL$R7WNNcAfY(oDroOfsn;iA?4XXy z9a4&x66(?I;y1!%%qw79m6zSnsq=Z4oH?qhdNwZl1++~v&nWoSEYR$|(tiJR-qAb1 zPIaZ}2^oC{*NcZ7qI4xOC}oE>su6{U3yk6_yr@#LY#pe@a_r(mJZta5`HdZ>6MpvT z_w_Aks+qrWJDRW^7Myh5H#YJxrzR1QKzlcWe*&f!Z!%7CkPc)d$tu2E9D?fSjx(5R zr$dZTjDNTm2PfdX&o8|kYk^l;_bf!u=Ce$p@8;B9&$^82D*H2?&o{Z^O z1qO_4a1Ly0US7}pq>EMUS*?9ivY`z5WZ|wvk<9vfUeLyFZ9Kudvf{)MJ^(-3+>9ML z>a66!vH#wDC3-n1U-|0cyirjA?eE`nT+-6JXGel4a}^pIyLE{|dtV+X-Mla}Gu7N; zMASIsky2NOJ~SkL2PU6+Kq?95PFpzb13eI#ZoIxN7NDB_(V23u&G2`@zblfO)1^%*uE-hsFA`c6R#luavCYxE4iOKpNjAd&LX`_dS; z%(pYHGR%vwmRDBB4Gmok^$k3Kkp08xSex*L+*7DvaSrS~iWJUKihFI5{p`=m|5`8+ ztP&<4nvybtK4*7|aOPP1g$5ce6{PdT+frr|!||hNZq>ZDx+nAMkYSW#N&)IMFn|^( z=O=GqX9W&mX<#S{-^gP6_T-v$;zg&iww4xs5kb59jNT55QQcIyl?|pfNB09uE6eJH z#H}E=rx$UsW>T31!A32eA8SFfqZ{8W8lKDAlC*=jBZ!4So+|m>(KSwma;Su?Eq2_> z)@XcMjx@P|Th{#5|V}l04(qSl0W8mph13 z>cYIZDB@B4F)3y`wS(yL(Dd6GqA&@U<5N7fe0}XjIna}S7d0z1aNavB0Ot)C z6RuMa{H1r0-1Z_*XsEjVO0SJMPlwSY0oJYEWMSdx=H`dRD#WnTH=&acSONq;%p2{8 zcYHFjeV+tvrn0O$sF;H57$?NY{NUbu%)B8cVM-AD7*uSe!BVB#9691s0Sp@=@e$Lo z70%ZRXmT5@p$ca5E{@aWk5&`pD8ZuoKb%EV`rMI>=kGR@O%K;H`p68ARY`Sg5*|gR zYo}x7$tAuxZ*2QbSP|-)LzT3KVX62s(uU-*#|VO z*BqPO^{;L_6Y}J29F7M{g38%YmmDeON6`a3O4XyZep9DylJpR9Ht{&r?jT#E8EcKP zKpjs`qaa33$d}za5+k4@zkJb{Uh!#-vF^F<7|OLOZ9jk#ti*}$aBgQ zmm4l`{@{A?4hROW?ggF~JatY|&~SE)uPHoSDOR+@?h1IePmkoZ z4J)JDQ?+rIWUb*vtX1RDT2cApat_gS4M@`PyqN*y{%sXH4C3-#* z{;F1mHst+8Mu;uOMvNS*gp@~BwLCZs!C-FNNNP_V#8?jP-W?)9OdBp2lU63>75 z;5{{^c*u+3hmg*VK2v$7>A{$=I-i6W8vpKaI~W+_iKk(+{=Or$ez-#tOk@JqLAK@E zvYA?*q{sV(=*I9W05;sS>*>J^vQgnNWe$#h{>xxm32gQG`NV+Gm!0yJQt+yeY2*qb zrEjBe9iE+4S{J*WPJwEJ4dq;HuB`Kk+GKk%Nq(2xQ!$Pl)pz0rR2Yj zWgIy=EbxU20X9pQ%F}lWoEV=0N&tREnt*bMCSXZIGLUq&K?LXD@{6HGn z4Rkn0;AQR;YI%N}WTOu%(7?Y#JAxY*MHmStxtre|9A)wu$jGS5=eXvcqu7Dk%i*N* zOa}#FzbCpMr{S>e4M+>ousx7hc-0MNZMYRu!NWx5zO72jGQme_5uZDXlT8WP|r zJ7CiHk7~BwfL3A)re7YAke$Fh!*GeSG&D3`XwED6bXW!=!Gp=(jKON^xi;rC5rUs* zA~zxR6l!OB%x%$3nt-|xG`QK8eJFo$S9#mLx@~-m(uXqQa#xakl7-r(onSLdM5LX~ zI{wi~CSBwy?S0h%)&PG0u5vcAaj|x#eXrP5DzdUnm^y;D4y0;q=ys_{wELSvw*`bp zL$@^=N%6ByyfbRf=}?5vQB&%B6}PMMnHoVs+AuH^R-vIe;I@MQ!Q;%l#zwKuTOxPF z^Uk%BVkX^{@||!&BtzhjxO6g1UE0oDV6s__Pc@gtswbts+9O7(zucOYkdYxO zDH&~V&d>>XN2G&>msN(qEXEclw-56p(xfByCdQl;?YFIOz2NZ&|KS!eJ)|$$C{71|24~FF8p^GdMFm{7j-jB98+*XtdL1cq$ z2viWVxqduX6=Q23<_&=&(@11r>bQKKIU@1%m4#H~zfeMUBbnCPzV27Wxstk$&6SQg8-XR7wi%O8F{3kcBhjmBV=7@Ns1(N4vM zn55@&D6n?E_&>?joS)^L+`(-=AhXZ*Y{=4RlT}a0`Z-bsAo!M9x)wXO#63f*W5g9p_?Yc$8 zudS)QJ!hdav_3ePzk3U1c59=AIClLiS007~lKf8bbbMWf6$s92xa8ywB<>G{BB#ii zpH~u2E69m!jihX?>&s$C(Zkxl$-lg<T0>Mu~%=C z`0gRjL)HMAyf|2iw1tjDE5NRb$&cSqopAraJ*2`acU5DYhO-MBWKx-ug;4 zd=Y3La1n^b$eBYJ-<}-yoGOSoehN3P)AvX2DW5=JKD#w$Xs{7pY3XSR^ULvWeN~H3 zMps_u-*uz04WH=2Pt~X?4lnZZ@}$EyKwYbusEE?2a%9!Tcj}TY;Zl?`S4H|l-Gq*EU9q9RC zPkh0bQAQPKjP&3w(3IV!p=p|$;!t&S8$tg-;`V9d0<%L6z*H}daT#r_4Aiz5FL%(# z5_6cg%vd#kV17SXd8R-b*PV>qT-J`jeQrx&oilAtRn10rtHV~y6I+_zbN@aS-~~Y2 zmVV?6&}GYi(LBC*O?Teu-RcUyOLi>P`)SdvMp$j|$KxO)=ucP`vA4pCl6v#kq#FVe zuw{|1yXjW>PFwf(VO78uj)B^rdxjA7%w)#aJPp22;TQD!L)HxZ`^P6=0{l-=h~)|M zO>M;`j7%qB@mc$3^KW=I?x!|VMxZvkS+B;Xtmi>9BQhly zoL^>}DiE~cE7{;ADH|6pTZ1(gr$e#D2oGTocSyCYFV=A7<9L7!={mgRynV{Y=~su> zFRoeLDwU0yRcRMk-gtw&F9ak-N-gq_2lX#`JI77^LJAmB$*y#oVTzG3#J`roMG>dE zJ62bbelON)O(3A~qRRTt?Kq;yVvVF!w&He%j~lp(Xw;4wgX?^_Yz)DkFkj#2l^;At zTzgHRljw>0-&dX~hgkKpq4>ri>Uj4fEzCm7#v=oR+6R1(K3O%z8^Hb_(>VDO3T0+{2V033nM}(AD zij(qkGCS^8Hp-=A#=;?so-bHKArHVhj}#_}P<%F_#NmzlWO#8f$}Hb$k=+6zlt`>P zXkVqLY51{cICzZwk(Ha2oWnnL=h!PUpm~DW>yxj>u}`N`BG@dh>{U7wy^1luZj^yd zP~3i@GYtc^xr-W7$fGH%Epzr2TBkUd%#N^+e|ijCyGzkxRR{{$c)o&PU0el`XHyZT z`3jwCoCQsV_9`$<3rVKL;>0{$_r{q%WtD|a-#N&Fs>_X3^A?aDCZe|(?VZny_a=*n z8@Gi$zU^;#7xH;&$@DjC`RAK2DTQneoSc5PTQwZdxb0he5klctIG5ZT9vU z-<>WUbvtIjrH$n*@|~90v0Zh0dZvqoHIr8S!g4ecpOy)~G}6UshLu&ky}|Oy$(PZu z^?p_=7+B>uSKhjHON9-=(1rk?XA*u*i&j%KHAjRqjDb^blnx~%G<2Z@&S7n9Yh-LZ z{l4Dk54iPn8=V2SyiRe%f!T!5AY|4D%vFnae&FhFLz>CtgyX?Sva~By}H4j z#8=mv^g}}CmcsC4%+UbS)J^@h?i}u4C4|1mxQA-$7Dm}A9f{{~#{QMye*XIq+F$IN{G~ypVyXK4Z z4GHFhG8we|oVsWHY6`*;Z32%TeFP91jo1Zqpc~(=b-tNdrrPC`zJtQbce7){xxpSnDAAOdtRZR_=h#$edw z^t*QK7vy*~Id}Wi$0`BD_3FId&?x_VD`J_?sO|$A9v+@a{ae(hRa4=BgW5gWGe)so z;B6WkdlVBB6TK|2>IYnmbSSct5>Pq!Pn`)|;)qTZfHD_VzSCcuHD|Vlf$u*Y=H!Xm zB%+7aRtn_;G-)(i_MN>o4~2cUbdUOl-*vz~4Fy9JRtqrfQsST-EUcOOyx*E)s$e7*VB1dBRD_Zi2XJ!tp6+FJ;^3NHsSnmM0XI{me>x^wZ z$}!J+mfUh5MT7@TkiF86h@W$sqsKYIrEU_r8RKL(hx->CrF1Sv!@bZs%UoVhmc2?v zxRem12N7DHBsy6qv+eoludZ>$~-vpuDMUH8Do3Q3~%0W2Wt zN5>C0rWf^giv4mPi4dOfy^PJhU9MnIzLY0h6ZQxc@6h1v3- zoffECq{|rd+ONFoj(5h zF8tQKA1wukxlO4x)WSnSz<>Y!@lIf7e$gYR73J7XX^A&*q6J~VL%Cm_nxm}d7Jw^D z-;Ck+|69ui_nAz-=x9KVfN>YvkNrwzQzP!^Ii!~&w0B%uPnng*SI4j1kN7b&qenb! z2>yS?$x~*3h9rRKzDtr>H#8WbN)VQG;h^)wi7n3=Wu_06G&`6mjQ_#E;J`X8Nd%== zl$sd|?4UB!3bt^32O6WC9tg^&hU+;1pwfhMYJqZbb#qe^DCHcl2N2Jv-LMcF{anAW zSr%VH@-~g1I}NED${%|CXq7sh6Jeu(uv_>UGWxTr%EV9shV#u8h0-ypu2JIC-mhKA zKwiW7bT+VY@7*jfHS8(KIbXgc zRfeZw7(RwZo;Vp+%jF}RWgh!G2mlRgHK(jf#bzsjo^bvRJ+W4P5x?eA^RyRWuBx)V zch80Hf%vQReJOFpU}z$P&lVNLgJto(jUSOq#LE7gG3gu1>4kv5kph_E>G)8mJo@Q* zbiYow#u@v(+}w!V+HVeZV_D0~au^{x!CI5n33RezuopFg+dOP&$@zV;)j74N1TfZs z5s2928gfid0th`3@t|2$J+`2mG^}UEd0=B|MY5PJ`X&M05@?Nk1oLG_Q;~(Hs@CYK zj;jt0LLA~*`BJ#UlNap^_S1rcv=kAd{?$3vD#RU&Q;IJ~?DyuwVg999!&C{jhU;>w zA@CEHZ30=QbbjJwPU~`<80PxQOW)!-NC8LUGmE8N~;zo{tJ$TQeh-C3k% zVUYw%EI~G26TU7(QHfnt(!esIt-~uj@4zZL_F6Gs<9&*Y0ZsICT>FIAl-b6*mH89o zt>Yzj2JhZscmflayqOK^I5RKFD6b!Rt;9m=j7E&MmBFNs(V%^Nv}Q5X6|Y7=&=;LT z{X}8s8`3KByC^rdR(ZPW9%}!wu3W{cnOaED^W5yRGJzXOp019?F~`u>CM=NPgGA%? zmBnbSMUi5JWP72mU!Mk9OX<1)MyI~v$$|rY4u;{gqk$q%<>-hT`5lT2`%<+f<=TUd z1feo=))y}%h-q8O5E{>lK@T&dv{ZJt%v1T5j)Y_$hh}l&nnn|{SZA;j_;CJ5dP55O z%k!q&>Ze%)ao@i_FSud9RqZc)C`TIaKva$qr zst0{#tDYXxKSUsHc=r=#0l4}0tx%wIrepHRrFL|_RME&=7Z+s~(snrlaARxb8Jz5N zQd^;%Y=O<{uJZ3M$7T+yMBfPejEErm^1Nn#2vMg}W+27>sm4(nH#Y@%i`HJ#TBPD8 z=NuIq+GDF^R8&wr-50n9DCkT=;twpDFc$S01rqawN(D_*;<0-2OX8PtFi90X)cF=H z3Jz?=E_S5)^gbPHLX6i?irUct>o4URa;q{NXwCwV-$zwzqK}W%%G!5=;bN{?Qh5X4 zoBf7*K;~!z3%2-27bo|xh6(86?kJxlJZTow{?in__D!pa`rI2tluv+tx##qj76XOX zMi!i%d!trjrM^lKUVP)h@rgR1CX79V-+o*qu2@Tpy~kNeF^KqMXwzX+J*x!MhTayE z*@Eg1m@lZOIRSf5=el}tbAQ%n^CVl|x^0*uIs1Y@=P&1pIjVFaOe6ZLdE~ph zHA1Md*PMYOk8y#G7xgr1^1^d_-Z9r=0IHsl$|l5#(%E-Vn*&b%#q_$rr|D3&!C7kurq@e%E%vVXsA-sHEkHJ+rhNZ4N29?U)pJN=lVlF;YVi)wJC!?E7Uyy$ zB}jzPmM6qWN^WQ4x0E!3*j_GlaVW_2)#($DcpZRfVN0pr;3SE#I~7 z(;PgEYZIv^omS}81eH@y+T9_b8;n0{bbuKq)22=&oMi}o*@%pigoInYc@tnAY=AiB zt@E$6q`vo{TE)U*?Lqdg0VpC4r@6P@cL%4h>W9zP?mKQ6=_tdh^$w&+X;9|=gT{g> zjN&xkC9I#xwx`l=tn9~)YmXTT;UuH)mWBz>a=pavGNvhk=5_^ju#IRTZ&#D2eJ8XJ z9GQnA_ttDF9u~AcET+s5>D(x)r~rpCy|q8xcUqk_|BK#4nF0Wi{_CVt_vt)flA_8ew@r`s&B`ss%T};bDD~ZilU;Tm&=BE`AF?*W)ivKfki9DQtV8^*bqy^6Ut)W zoRMUEEJ9M9CFo?h1$=9*BjdMl(G0uxFym1s}wX@>b;mhCo>a>NijKF z5G?c|QOb;PCeB13qXaNrG+esWXlzQ)pn>e{`|mM+F3KZaFGeb6d{$gn*Vl3D%uD`) z$?nrtqPh_zX9x3JEbyM@h>y;zjE%wC$UX(+ zH2dktt)2NkP`>BUCal)(V5qw$dS0%XpIld^F%G{^r<1~@Z)2uat*+++XKp)fG5%yK zu5HKH(soLSriRIis_ch$Ri^HC{eFg<^hzIVH`gd}OU_*|hql8wxTaz$n+?8Zr6|Dp zrQn>Q95-L14NyWrmr0h#?Np{HP!z6ANamZ)8l{$abpIdtg9?vEXvXZO6hbue==n=HRAJ z{{G+)u7^PVkvcxre{_Zn@HhJ-6UiYRouBsr4Rjimt?57{&;E~=WPW{^{pB+IYwLN` ztgcF*h=qjs_^^zvk^u3T(R#w4>$a<-DOi4HearG?Tx67=zqs!oW%s0JwvL z{1C#NeFy#4f;`;ZS%>u;Z32&7sjRGWMpooEuK{B2eg5K)fCS#jSg2WzSN%z(?+3W) z=&nm}B4=ggpu_*P|F=0G8d$BNUL8IsXb^R!@}Hd8^*`P=%u;UrEzc#@Dj@VW_@{TE zel`4<2;r8(^YexEFx%c#~yngnk!r6-_!lEVskL?<|RBzow^U-wP6<6LGm!GE73vd z%=dY1ef`m^4@TBNOVnb-b2!$ybTvKtRT4D(2*eF}CSD;k(Vdw5+#lbfBdwOk+uYd7 z>PgD))0b1hu$2MNJZEPFx3KUh{mXUDPGi27)z!P(Gj;Hjo%1%x?4(n#8<H3MXsnGW91B(Jhi?yj`JUv_5-){5Un`Vqpjp>H#=;+j(drpnXWe^9o zq#o3LSJIh8y?y&Okj7mlS>-|5P~TO{T+QrU=0_eUB`2Hv`;GhEc%Xog0ywn`BYU{b zQuLa7^w-#}TBvm6vYuvcQ0#}c{@mu8f%U;t2I8IpjV`cGXIFY{R`IKkH##F~3WN0W z7lIfp+!QB=JFPXU!DBmgmbNik32pV>aC0z5=@s*Txu&9-JW)XfjSN4*J^jimtCHzwIg&=>A|&zQh15 z;@g}u<|Y$o?$J?`u`w3SOSGt#rGj zfOxOu@Ki~_xq(;QZyaCpVv~Pv2 zJ^|JKRTsBeXC|BJOWk)9T&#a;cXxh%atv{Caru)Oa1D?Fl)0WJ`ri+^jQ0lQGDQ_C zR;AYnwP_~*80c|Oe}o6!HA?ef#T=l|5}?fxfWRfOONTiJ!|$BFFtuLkt&??_B_RHZ zdhQw=EWcu9b}#Ye-pdDn5Z+f>S}q9{bj9UU{ACc<%>oHy5^>(N^46$QPqY8-^|mUV zH+I^nG(gH)a>&6;FQz6Yo|OsPmZ^VfSo)T&5y`eCCxzGb>}x1ASi+Oj-0Z`rU%!YJ zmX?NEGt#E>@&!vsCo6)A6cxWTEwqK(uMK`Pky|vkIcL=#0S-}P`@Q;+G091#qE>6h z)@8d5S^H4bJ_ptbT4}JXCJo0phqgwSY1CS@LL44HIcJXdpnVr3@42DGBS-gU-?=%GPy|cm*dqhJWKKw)5p9Xv zEc14Z!755_Kewg4_c14?1ku^JT{qZ##a8h}?ulSgxJtD@df&u~ZoSA>t$N{ zUqk$(Pdl^vjbLdiz2ivyeZl}47OIM;>}m}(ZZ|;&=H`6c;S_{_C%fLgyq3K z|G<&jt0L4jojw<5=da(s$(%c;=e|qw2j@~;oU~oHB!h6|F%vtwg)hZ`b~V?kKI+T+gy*08lDn5|SQe~{$G{HGL4L6?E$3gOI(6{V9PvKT+Dcb|b|Il-Q zO7kwdL5M9&0s{}7p|LSXr2+z4ONwoEn!S`M1^Z}zuv_YEsmg{7*a%#U@*_Bq#+BBa zGvCwEbF^TzqtNE~eBHw3a?Cj3^V5k_{TME?sQOl?K6f=YH=_heSq2Mw2S|@sdPgtR z2g$OQ2c4X`W2=5^9z`#tl((8hEe{@jh$>sxygyhv+@r&JnU|ysRTn~Z<(}gV!!+2? zA2}nv0a)vxCp(}7G zpVD133}j5riF2nu?9ZZlIsWLWlYqJXMwA2RLOPzNPiW|4H3aEC9d%FNtdyM{S3J5p z(g9scMJgl@ShSN?mTdb1ex!SmKd_94$l1Q(z{83(yPTXkwhjuKSC%K#RE$Mt-96Hh zWPZED$%X#Z08z1%X^m&(aA~d^`*TrH;?J%LO!)`s9OBhT%QYaPrPk;)*3r@`((n`E zU~`O-atek|TzV`MqW$gOv<-5{Sifjf1% z`|z@H@v~_*x76hX>8S&K+^4UOy-xY^mh+Jh70806rs^-rs+=>y1$|_l^htb5e(JSy zOlrBI0O|N#6)`=(9P$^G!$AHGABT^LE8TN-)yRxb;6`sGRl#@K#mt2X+9Y8>g2lu{ zc&bc{(&2ndq{qASbG+DX7gw9sj+Z}8S?FMNj?AWG2_>ayk+N%?>?%gSUH)sC%L@J% zQil`ioPs9td|LBE9xr4hgmFnIS@QYlra!Oc&XH&?^~6j;;7)z%@9)wGnCG|L8gk5h z-{4r(8^y4EJ7qvm4iZX8CKaKa&QNx$AO4*R)opYM7&}3%Tf6g%zOUdW*?g;j8t+Kq z&ke@sCXpQ`0dtock|lAtZ-7{bPiX%((P+OZVa-Yx#mL|+?;v2wrbh@Bm5*sQ%-93BNdI9*8Ma>F$EM1*90G4fm-*#GZHjqllhA3)F8*!wMeL zjtkG-H}lEbQxO$WtRAgCxv(lh8cpn}L>T#EBiUB8RihXBFRwhOCjC8&>b=dXLh^vJ z{(2@6%L_VMS9yyii0y{u0$ih+c>&mMJWUX8i$6TSoZ}+uH1a37j&MmF!tn=tgdbN0C8mS&U&JcaeSjy2ga$+Z=wW~WmD)XI|8bZpu+`z z=9^dr9V@M61@r9-prcg2i7)8!HYz&t*rQ$POKvMNZln72gZnl~@BTjT+1VM)zlocR zO2~GqadkB-a`b9GIN8v|1mlkfL87F}aM1$;FcUn2f?=xJ7<~uNu9M!a4i63ao}ShK zpM-@-c{XY&}&rgKm@;f z6*o$*sUc}v`lkk(>wxF|T;TI=H+OTBS$+&e|9~HEZEXeRs<@-|zJP)8Y{2&e5&lF) zfX%+Pvjg4eNs^Tpu7emTsQC9j2TlRnx8Bw_*E3&AY-QP2>kD7s!JFglFZ~`Zo_Ca8 z+i^vL6=CQSpx98&F0B!?*D!<+82yNvnXsH9zEU-X+Baeb z8q$qfGN-=y_Ag-`rtjW;{CWH!vSxT#{f5*wHId)8Cp`4g=(aN@+ZpPp?0(y|$NmoE)u#w{E$X3SmlRfkrDVDgn^ zkXQWUw}?I_GOTR%i>Sb^Z#hRLg8SLpWnq?Lm&5HW>Pvi);P;_p1DE5`7o?sXz*RjB8Gfi4@ zZPuYCELC}H|7hwaeSIrc*eu9qKsg8UItDDuLMrU#gY$hKl2{!8_M+p(m#d?stD|J7 za>q9gEjj0%U3r^EwIYtS!+WC%0tFnmmKql3>*t-JRx1x z@IW@JXbj%#vREixNvI_ai+sEA>=SGE=#hkErujO;6dT%;i4&2?%=M_J<{1UR9gJ#F z(V0j%gECix%OQJ_{FQZTbZHF5@!9j3(F_)T6s3OzLO0O#_J_GxbLf@m)90@%`z=u$ z9fv21UwktxzJoc=5CVD?h1!C(sKBTQ=R8x_zDhUrCHGG)(q9>pWs4qcoMg$#7{O3J zLwkdstvILDOqeHl^zeVUXAS(|!4#g0!nrHTJ>Nn*4LFadDv|E4z$|f-jD;z5eI8)N zwKhXsHu5)i1B@M{9wnyB6iADrELpSE1P3{)RB}Qfo?4ksC#y07f;wBjP|i<7NJg{r z1mc;ZVsZ{&%VR_D(H>es$<0|>ET3uo4kcIdEiAcGL(c{!l0`N4A6ShgFBo{84 z)~hn%$*s|$h-Ez+M>~7^fCtpcYl1Nn>N8R00-;e)VY8G9`dC`6GFr++qbzgvqUp4{ zgI>1dknG#0&n)qRvEB)b1&K=%nh@Prs7P|=;Fs*U4+WK3Rlh-v;+G!xOlsPtb8m4$ zIh$LGFf3VZ_v#=;EI{aSb8~z3^z={^Pvo;|1$7GCha$Lkd=lxbmP+`?h^H=g;w4>z zgMh2}f07b!a;_u>ZzGYn{g7O zN{dtDsRt;%?EE_FY$$wi$#aVP$$js<#(%lP7HM)57hGWlU1 zF{BM9>fGe)6}8hp=|iDV_iDDg39pj#mjv%!pTIh7Bu;W_MIRkQt{OUILuM+&lakz zmNKSC*w4rphh$qSPL1(&M>%T04eY408s~EF8yr-Idt9W%=uS`eAzxLqJIyU;oI=7A z<{$@oc6FG22QJCe=uRU^VIHGD&(c**2e@i*zyyOe{VQF=m3(TxS@7N@R;`86kVL{> zN0G{-kI^_Jr7R-v_*lbDMW3d#l;hmM{2&z(mIn*a6bxI*0sXpU#l@}JI1^)g*gr>YL?!-DRm|rzz%k86$Ay3cA z#jFs^%}{k*&mM|?Up(&5-Qr?(m%&f_<0t~q@#9E|(c1Xe`f{w_u8^u|xJ9Qb@fGRn z8?ffg4UdIZ8H>8pK$0@2veyDciTKdAo6rs8GzNBDUyD_U#(N2mC}i2z}o=298SB{h9 z7O03Nu|P>p9XxIP$Nd}d)A7DHRidZ+zGy129v_~ZpRS{~f!Jsr?hvm2HS#Hh$s9KQR|310>ej;Zx4I6EJ zp#D)!7)L-UpqZqp2otA_Z-BPjx3#}iq%&kjpqZODFvSlQj=_R$GgmmePE3e`v|mbD zzuk8C0|!@r{+P8IzSZR0(&(D_VT~E~klY@yfI$6gkOrF}oB3d6iaA^3N;2!Zk5OP} z2f%t$_tG=$3{_d#XE^h}*RuP^tQROw_1w0c0m)|w#L;b$qBq5QpIhAf8S70RWYHR( zr8~e>FF?L5tkV6SG0>?pmffVi0qeL-uZ{*$w~4i|GEs)4b^h@L-9-`3fb=F0=MD*E zxrd84OYSz*k*)rDZhpSl10LmoGSzz^dd7U678kc!v_CrJF`(oCIcoBOTK!@HJxSLW z$Z)|&?{P3k5dXn)ERSM=%H(5kwgZFlM8pmh2fouR%8=J>&L~K2f;i2R4+fjrO^azB z{(pJ2|1TQjQ*9{=Vv^B>wZb-4+b4g_iN1opN1nZjzi9k*+ML78y!JDdUe;ZwOVnRQ zRk_cMbEab~gGom@;=b( zBmtFgdbpLZ$Y3PzFzYa^+P|C>;}jBoq$93!Ua;Yokni>b80-oJ6Wt~f(4HRrwCEhX5U*b4Y%b zbA2Br<$PkeyFmS-RW@(o=A#xg`zSDW5vMo2HAr9#Fm%na0z}T0AiqG7pEs3wu_X$xrCoA~yc&zjRnY`1*=#E8@Q`)o zH?W<9r`z2#&2Z{*xch5BVb(&SJSC&>`cqkBI-$;8i-~WYqXr2cKc%g!cMApz1xuqR zdp~X2Po+lxPf7_;jVQDmSL1tS2T6lR`|^vW0Vu+gRw9G$^z+$42=*xdQE@#MRltAJ z@8V%VB{eZ-LNvtBDG9RIu!cP_0>VPSYb!8zXGNHXs>Y~FT7y;(81~bTNWOee-4>8j zc||(fI5ELiT|-)a)qQ1BpnfaL~mhREVk?Etz95=u0zPl9Kd7{^Ku*9c* z?exDnISd61%R)NiN8cEaKTjr|%<0J-d8EE4uPszBR(d9F{s6@Q#O2oD+*UF^sFu5X zJ|8tQTBnlubZwUU=1sko_A_ zBx=X_C%O`<0)hK~rR9grufTIy#QZ{##ftsJaPR-2>#f70e!J~qL{LhlTaXxX06{`p zYNTVRp#_G9K~h>pP#T7Aqy>f=x)ep}PHB{GDG>yHZ@$ktzw5lubIxCmm&i49&;8kZ z?X}ll8-u~@REVqI8GYeA^=k8`NJZs@R3EWQ<;{$|y!ImdL~o0@DaJY{Dj)N;+}i!L zW+u<55u4SXhoCpXDDF-PsH}q?PUe=|>*Ag}WJQzQNfFO14{;}cE6i-m&25K9IRM1# zW}&K!zVp`i5tWy8V=|3iSwKnan_d}@y}1nbO8uqj6P)3A8l1MNSE!Nb?{z$r8vsGy zW@h?wWvqM`eyVIkIc z83*c{qo1>jAA5VTNu_oUBW}{E@$>KWRESGWIo~F#T?6w*YX4?xvS-nMpTwxKSQOX? zcSbYN-n}bwIJ4h&YQFWH?e>75pWl74XT%;JVk5w~B6i?NDp3^zlokMkcsYZp6aA$K zz=wY^d?^B2)?Qvz|A2_1qlbX?AK&I&`iIBM@)^u06=wt{7(l48Iz{F&wXpE=U*z2o z;}s;hn!eD?c79t~d1tC}=xPXMyXvPl$V$d{4c{9`4=FUw<%qx0srFq^Fm3bu(jx-2 zi~nyzWxvATcfhRqxa4SCmt*$?Oj$e^djoU{on5Sz;tW%zjkn*teto)fpFr@L)qsxt z=byh0mZhg&t^0z3h1&I^FA)Ot!Go$&_CVEV{7!<<^Yq` zzym~^KA+n&9A@M}i$~RT%jb`TRDciVmA^nJ9o6*MQS1DWvxEn22r>9KnKyFQ1^fae zU`TYdQ0w|%Q>L75%k+J1qmn7DD>M82{S@{$SA`A2!h-YJbDZo>@UE=E;?@q|+pnw` zz$_i$%aW%ken+X^e)Voj>xrf1%W*qT!S`U!f{R)bOwRxe*FARx+)ZAosyBOV6oZrk z;F`-o$ffPbgQb7e(x@Kuk%*uyG7)Pq)WR3wG^uM9;>$GzKkB|?C4OTvslJ_up} z9fOG%NSZPRl=$}cE)^M1e1^SWC+?Fz_zG%V}#GE7~ch3K|G! zQL!r~cfPF%sF2#*m-f>0LrN*R+&5^>Jio(<5}Dt=-WB;5o2vrWxx1Tpd?sQcP3yNL zWvv7XBv@fP^t(I&dG4${KU#h4L{l8Aw(*7}}AJ^?DJjr~emG9is{Z8vuG8CQAJy*y-otxyi?iV3f+MIQf7DUI87 z9Dv9rM_;hgE}46eu>jhiF+$LwY`NE8qeM@>8o{1qi0=4*H0c-L+n0dP1?=ljQ**#f z{fEB00$*$@e&qZ2OYNQk3#tKqs(1Gl^=svG`SePkLYk)g%OX}_xy^>O@+4f8Gf#mo zqUDZre0Qp-RRS+`OX3%LH66O0=x*LnU;h+%K}but{p!&QQs)s}GQ#JZXnn0;Huh4s zvLen#U9hvN*Ithlt`y&Tt|T)?brv7?tXYNU<=K(yE%8eCP=PUA9dh*skCV!=+EXPW za=oj)6jz2U;P*vc8S-HB9@&{|V04?{RQR9GuS-$U0C0QJA$w82{4Q8L(2ofCaTYb7 z-V8@^OqTSuc9!eTQ+0b%aK?ozSXOJgEIbH#WGhk06Hgh+W1$ljEqyu1e!K0ors$2w%#>!JWyWiXEbo%h`xN*{ze^eE%vTRFg*_S~uXH9*f%5MVz1~7;U z&(1l6urdS>{Hq3da5ximA&!@)RMiUnq$PN!HXk)Cajw=bJ_@l%W0KSk(}QA!|+{1MvJY7LZnn8 z2Qbaj;AtY{*4AUnPc>|ku2fHqa=1QrnELRoZ*%>awEdCcX*#Vj~ zvp)Ek&Cs|v-B71o({R?vapKpDHr7SZxBydn-JdxUlv-cZ>mMb~d?2Vo5!KWNe{(Q6}S$d9fsDJ>xD{+!zY4Aw#)B^MpuTa8e&{8Vf)ILt>1 z`BGq?sNY>X-3bo`HQ$xB-Ay4^Pd-y}=nDRE@_ays8)R>Yn|# zg!6yy%J>Sb=)zrabyn3AAISRE!i=4D(2kF^gspP1k09mB&Yn*I>)hW z?D@b9ednvmE_63rK_9qhg-d}{z1*AhT-baU$|q5lziD2aCouyWL$)y*G>5cGk{|n0 z9Q0q|j`Q|Slh1#)lcbq?lv(@8SN2-fZ?^JxO=DLloov4%JFaEi*6Ed0$#vmD!=BUF z>YAF`a{r8dm$rn68w6@l*e|W7SahDBOK@B20LGz$y^%0DM9C~(57nTAWD*gry8_)mcWke0w(9}bV)b++?@ge+`6 z%5KT|bL?@Yw~C{}Z|2P>lvC~cmTqBO@WKMIvA5Tm#4FptVGn_*>5DT2CqnI;zDBM_ zc>Vd=JkEQl)Z-##rM3Hy>lt#j{nP6?4$_<24(#`NsNM(1t!wUlsjyL^)AcBJib^cY zPwKk_&V4EWm>P85!w#CIJ}R(|(laJ}qksJhBYgUV+q6&l=)Atd4a9a+0_30G0895< zbvzb9pVs&>LOBClQbk}r6M|Bknnp>a8+cCQslqGDn(s;*kBL5OhLi}$C*Qi5`aV2N z02I9ms%dWTRE>40K6=KC=-bHLdoN*OjxR>{VaEXMckuM=|7AA;%-TQ?&VP{Ze*@k{ z_zhA7u)OsClkFPd47l1PU|V5LQ4aSCR|)LTw4DTF_YIyl}m9GRU}gTFXzVAJ5u z3%hy0*+%K*wqrp11N4w=C&t4rz2Fc5y2Tm>iPhY(;Wxun%5K9`t_ErVBe0hyIfc!; zr=~Xg&@&3{ZX>+pK=q1KtNzDI4~3L3R%z>FeMM6rYZi>9LES6-VL<%sc75I5Dh~US zI6V|am;y0_{+V+xFr5C9Uh83(!BsL^w_$6&hm8_+n$=6_o)|G*7lghSCf8$>=-S8= zabWyj)iUjD1r+z7(LOmfmANiRppWKMUmFvLP2n1)nzDTdpe~MvW_eB1@JmfCvivaV zbuFADi3bc++0cDpUu`bUAROryAiZ_#7H^M8q7vKC5g2F*WB&V#8AGI~G9vg)Ez1)fUWb69HITy{o)@zuKUr&iy17 z9qdE%y3~iWFT#Nd0R{(DnJDC8fFT>Oeek30)ruewSZS1K^W~jjy8L5s>=)MRyu4x5 zU5OP&PxigQu!OLRk(}ME*1SB}DU#G^Q_A<5HkSFXNT$ps&)(t(Egl&;>Ynae#IhW97;->ZV2I!UA<3}F=E)sO{g=9Y;B^bcah3ZZ8sUhNXh)t$3&S7&m8UMgSC7-ir~16eQV16%F&<+^QG^L@mXyFJs_pqtOb3 zN3@@R{2(weWG;Nq?_8U=yR~KYG1?9HYLXdD{QZy3NI}0km>pAUub3&+n^H?J;E-}RFgC-tlzGPDk0Pk2Kc9l zC#&SMUFojfWNCmqiaUZ!YrTR2)K1?Imb*X~UZsw-bb`(3>r3jDg>%_A`wr0MSPT~7$kas?I~s69Ypb!eZ7tyBb!W$F!$2b59Z( z-!Ze{>>ZZSwXPXF55${Ofny0#!eB@$DJkip&ksQ@>y=QGkI}Cuq_%o&A8hPupi)gB zjocTH&Tvf_zzfOFL_+G*(1B<4jOkiH7 zx+}Z!KsiZxK&$SEy?C#NJ0;&jPjbW!%*51J+K&EylG3uWLPzFqcU1V(Pw<%d^3`JV zQWh~J($P(Q8OD^qcz@*#_RgH?$OC-HXte3}0uZX65N<~;fKQFE-zl(_ zovlr31r`?{i0b(E!%v8L$-+rXvMSxA2FX+z%d6{TCP$HRh^Itfx92^QblXVV0oK*WEu+IoASTuc=JY3QnJGo=Lk2}yJXt= zhTWjL(DXB;%URlhZQRg0m^ulYob;Bu_@PzUBKT3Bgx#MvmcaqJ8=h@avm)2_gq=ar zv^F7X?O8fQ+s})5?Hz(hyqa-Iqx))Y6ns$fo%#yTS5tz$(1vS<@U!fILqfb)*S--( z`XLHq(HR;m95TE{#`Tjq=O^jvKP}ze<-w-CRg*tZ!A*1KHa?bmEzk0Kd0@1F zcfA_&r0otou{92c3o{Uzf7iy{;bZMTWN|XM&Fh?JwIQ= zqA@Dq(;I0Zp92*iVM{f);hk>I9vUFCFG1I* z87Nd6BCJ}LP$I*Y*=rP}hGK<}*!Pr=XYkeDW80pKuX{Yir*;k88L2Oi;!9U-+eWS4 zl9agkb)z4$hO=}}_;)9ia z`_&Nz+cm0f6u0;q(&Pqv>}v;4od~p=qB{rtlFU$So96lXU4mlI%;_!BPwaNZL+9-C z3h5id$%Go-s27iYta$iz%xtTwEJ1LVPkD~V2L1g7MSCa~l z|E!VZl<5PySL=R-_#Pmx^4AH&;V#MKk0?GnAhH#i8hlPV(uZk2jba9gX<;^Y-Q!QL&RVmZoq` zB{nfgKOR1-4<4=@qtvfdJrClqT1srVsbLvpLE$fvZMSdlVcSmQ#zos`xron`a|$QR za)#IW`#cnKVphHP$)@ASZ-cid`D{<#%+~lI{6CYIfy=JsWilLJRn_G7etr4W} zfHiHW13*_8>~*240V^qC=$EFC)@||iHA0NMOO7SBv-SK?e)D*t@UC*k4MXx&i%l2U z21P;C=owPWwMI85s0~#w8oY9FQZBuVF`Qogvaqn?7l>7k3<05EL_|dWR64l?C6v>$ z=}Dh%ps24eB9sRC=HU=BwR;mLu|gU&83!m@z~XVF&+3k7`FhAM`; z$R%-^oH7fh(93T@z{&ad$n$1^y%9Z*d33K^kH6RU!FCVAT*jpn-nx7Z?Eti=PdA2_ zN9R9l7QP0$#XS}N?~taRM4!h6>gO;nGiLE1p>Hq}_8yL)g2RLO992uPB(0z0qGicB z>`7W7Rm#JWNm6e^mBfOBN%&L-?wv$Oky!irMMUDP;V1W4PdmSEVpQ5nP?0DayZQUv z`z-=0q)}`YZsOZ7Ag&rR2YajA9#z4%%Gxk6IEdH_%u^JTFp4>C+O~~qU6ridSe5+n znT7M@+D^hgqTFzLW^gplmn2mFU1@2&rZ!G1r(T+h2&QvGL_Chlb~7MvMY81~S#3W% zesUYmOIH7>GS51yI!unPeFrvzb$Ao2iTP-F9jR4#szE11)NM7O>(fOOd{C1Y zhol8a(mDI%U_A>9*{yAcf>brOIre@d$Z>VR9-I8reC{Ok;{P+&kj@>uliXK%C!<{5j-NQ;C$g0C2g_Fv{LJ%7#UXC1DPNcc{|ccrS#4C;}s|qE^XvFf-|;S z)x#rRYE2AW8VwCMJlvOFa&pP*_;}QZw7x-I`7R~OAm%{Bi%nNVTTV9DEN18??4cAsM2&9i_7tjk*rpUTO}W-dj$qN$qdL>I1r5VKj1x>yyVXCNC}$DDBu z_Fb(0_M>Dgjx1yDv5WW&vT(&asMdp~?Q#|y4s(UJc6ZA6rA^3NRG^}_x`=+e%wO-R+`r0CdBKh`blPzpkI+iOJkE45@( zUZh^WIXxKT%ocaC+|nQZu3>113l2O$Masj3xoo*ON3HBRH$8{njVmyeGR zJW8LO%#R%TpX(B$i0J?0uw#NVy1nDT4RdkXO?JKCJzg;y20x*zYfLPWF=$Mh>vajb z!yHt)l75n*=V;$?a71(#B3dS*R-D%}KA2RHIqx|(5Z1N)(9KG(H)G1&*l`s1Mx_X^ zLZ24)FKxLI-B!&fR3L^zBXe>+#dJk@AbMv6+oOe-e~wgLTlT#`V2q|`gK(Y1)`20{ zQDBW;UUj|=Kw&fySa+DAofV9&~DnSMySYt1Tpcr_~@F| z3Z86C4vl!kIOp<_?33jKiW8|J%|Oi76Ta~N2xCnH93eCg<90VnDuJCL zGLMn3>1>{Vc*r|P6Cy@8iylp#DAxK*j-Tb&asI2C^g$mBRe4hrK2U9e*+9A6xRkBV z>wV*rlH7Kz+tx49{ha=4@aDp@`SS~PkE5DZXtde2sGSjT4GLR*%}Qm?Z{TSWPLO<9 z5o~a(XIv3wwF3cLjguqp9KpeWrM{1JkSu$HnNChN7@wH<_WcV!_nNMj(DY55ikKYq zMyFpC#>BAsqvJrYb`F)dNpS?_{Dr#VXr+;)SdER!sZhr|8J)avqd+MixrdAONb^z?Mv$@9MB3mhB?2??nNtqEe0`FZIIMGAB9HF8aqmpHgwf)PYA(=0(0 zp4qU7=Hh$a zpNJLQVP^Vyq9MoHbnEt>&|N$6S~fm?W|hB(qsbFafk0ql8fzh%;gD6ggLvQiD`o`oPiuYSh4(;mYX;4$gG`JBc2Ekf?yC8n-jk$j{DJJTd#(a zX<;)UD2KvUtmee4J9SS53TQjT~bQ>_VWg5N>&sudny+ndGu$tiB#&HAJ7m?@>Zig=PN zv8J@Ptj`?l@l}-;OY9)do1aPa|Ep13zO`c^>}n1=7K`7%L%3Iz@`W1|^By+_*x{3D zWwJAz^Fh8Q?IW!1GFN#TMux?(N~VSv$}l#u{tZu=7P0LM-VwBJc!U;h+ZSi z>04?4*NirYEon%&U=A9;6VpEgH-Ne|E% z8r`omGb8MCOU`e9M{}N8KWFn_AvsmHBF%Z*GZUNB0T7*Lw$#hBv!=2YF1kqwuUuRT zBScp|=g%D8iuHX|8(Er0OvpWDYQk-{S ztX6w}1(}I$$i%P8g=~KQTyi2NV$(Fz&L$EWbTqmB(5UwrhGi=8&mTETB40*{rja)@Eu{VJCM=Q(W z*Nu&XTT|j`qi11Koy&}tf|`}?)UMzuK? zA=3eskSQs~s}u-pMAxVi20|^HZe+=?VaFfZq~xgfDCK=t3bqJ-JL?wVXt5cxu)q!; zOf$%1qq^4P1b_+AJ}$I)g+ft}a;r+kpB-BzcYD8t?b`Lour1T$_3O^|-)G>|QtW-#omN=a+fW^!W3EGVKA*1GiDb7^xu@8 z=CiDGTpfDj$i^7K@837ch(fi^%=o?pY~{}Wx;pZk|I3kkF9tq$YPrkGS8r5E75+(; zu_l3X^=9iA!NVJ^vu>liaGPYBYfplLm?kDB-uK9RTZ(s`f0jt@31~7M)G1}u+HeyU z?F97^ODm*;${Ri#^|q_$Xe~7mncHZIJ$9%%DNfrlv-L;KDkoj>7oN2rOk>;=(ZLjjI|&XJ_J!pq?nZkEBWNF@h1MgTtC- z99stMQw4T-G>;PTnYE z|CzS>D$P{uThd(y%PS)@WBi!)ua23h3O+zI;<3(|H^#y2>}UW0EAX$t!3;bGKpt>V z|JUvI{(E`KmZh0rUOs;u%^%31KxeE!`c*@bg1d=K{HcROxWA;K*s`!=3J-&yo3pp~ z>!yoU{J=b#GI3jo(&iAwbU_}d4>~((z4zuq)j3`%ykVk|DfY`Os;84%m{Vi-Ypf%J zLTt|fqaf()rqZyRB$#&RE7xL@YCv9BPfOu_xzCJaeD=HD1VKH|P=Zb+o5)P5gZy${ zm30q)7nQ=-lP1J{1Y|j&nAhQ=3~*U@ps93cxaC{%Xl5AOD9DlDuB{Zg!ZS7#W{= zR?%?}k1SdL8u-ST08{Wu*J?a=Y@kl*r#J_9;Nw^swyaiVd&da2oT24gu0GdOx(tIe zf?@x`^HR^@Jh5Hd(f@>BX^;*DpBP+Rlu0rd-CtSR?@3-L;sg}U#RX$$r=~fC zq{ltbGAU+Fj}{y0ylH>#cAJDGuU?c$gI85IpGj=fI;f~Q9ChHxxf^9itWW(_T&w%x ziGPI!YaKIp;EU=42Tn_DeLeNJr-+%ORMa)1ZioPR82dYb0UqDc9rKO zmxilpv6Jy-Wk1Udvjt=)?1mc#95w%_E;kFTU}bGxu;2DU444uNE~JQxVQG>RkhpcN z@thW$7||^*@vyOPY{rIfv6_RHB)6u90;HOU9=7l;uZ>lyZ`?{F<)KRZQ^yRoo{m{L zR>=&R9DU)+9%GS4K{~3Y1>85A2GnsUD$R6QMfR;X^z+b0D7FH)!b5*=`dHaNY9*hQ zaMc{%%+cmkoFk-US$ph-cBhVK+BS&NZE40lIV+}J>~|(UD^U9J;PQpQ-VltSPxXNXv_hyhybmC zq&zBZch4uO#;3TshgFcCP(d-Ov^@Hp)voD_gKEy*l30--5L*0(COFmU%gu}?bLl*Z zwWX1nnuRixAX$Fn{Pz(4QQ#vVfT7@2%FA~jdhgJ2e-VveqawhQ4kviE0``lHK$Q|0A zNs^}Hqa|Tsid{b5B;;NjC!p?%JDo{VdMHRSZ&l4vGR3mALpv(Ob7r>SWSA(mrijD9 zI2XFP>A;=Cj62z-ot!9BxvQe~O@CCK<2NY*UTB+bgTlX9U0Mc7?xa@bC)0lt3`;Yj ztk7uMy4F_cmrVL^KWU9s0x?~i4NEZV$6E<*cel8`NU~G|F)Z9ZmA(UIO;YaxWh?ye z=lv4=Jj%Gfp#hM2L`O#+_9zs3>lRO7It{Vqn*z&f@;s!5B3queogJ9yxI5bY47QPQ zmRV15tl+Lz_&S7Hp^Q@A$OOcF0J9;P;$K`}qS>E|qvw$GuJ-nBQH%=BBD~YIu)F2!n;pbzjucdo*Q!6HJuzJj&nYj0}-^WLlbX_va4Xr{iNv5EF>h zzFqgw)DM(a6OS1b%x;TaBP-NS4hrX-SUfQ>^Rq3N{mr)YLwd6d50?&q3kQPg+sm zIqtD%g;%SBXdfB*xmz{DYMM3WrXuao`VqW=7|9ZQKsk?$ryW2IKF;?VjnqQH0e^v$ zz*2apYQf(|YqLi6F@<0;?1yIIXmRtk!OCKDlXr(4|J0>SATM^*>6g(URD;j!`c$_P zt{~!azikc3l=(F^#OVf!R+`b^FF@BC8M8j^sA=>b23e2zUt1PFM5sG5zm}RoELow` zA(RZNI|m^fkYw&j2)jfcPKMgVy61n{M#Cb7F%%;RHIz_;Cj=Kbe&O~YbA%7G$j-+_ zIU7|TdPG2v)HyRZPua7>tub%cr?+U&1&eJ--TEs-6pDK+{N%J@QFwCsD*_`TGY*EE zH>e#@tHXy6K)vtfMeE_Qu48tWI=k5(FY;K@eJr-%deuULVxNmJOw8@o$KmrcXwBT3 z;#U^2unT9U4AonND&n=g!@tn{>r`dFlaZ*_S(wR0wuHvp*M8W6|{f=ZWQnv0b1G^I&kHO|D6)M>W~JWUY2j39-g(Xdp-~Y>1(^h zJxG~x^al{~p&|cZ$FP{BavQCzLjOx#*Q(OsO?6F7bo+DieRm}gQtGkm&A5XI0@l_X4 zYBKvERMaL3SR3%t( zDTWvs8-M!N(J?ykph~CL@32SVT}8!DC31IMG!{{(4ml(#JKEvOqn$NSS>0joI`VL4vB~? zyl)&C6fUpngalo=VHJq^OmZ(z0~rXHVB2VQYo?MgJ(Wx`jC5qwiJofcgx5q8SSv=> z$o;n#pdbrWmyItBi4LVcg}-Q*r*!|cv{Vs~%XDX_V$t1MPR%-*XXW($_{hjdGp3_- z9(HTL3??{R?6Cy(59LkkwxCNyBXYG~~=}5Zl}e7*PvsjXy`mb*UCM zPiuUn2%i_Nw8f?EqmHxv#nMQ2?BQsL!%OoqTE+sw@wNKxKj1O-Y_aH+y#bdkx4hg8 z@RI*YQ0C!@wfi=wF?8SBd~^@kNvjl(6@8CVJ{#oMgueq10qH^e{)(h~!Vro)_x&y= z>hNV+qEb#--fZ_s@Vz_SeWlUGW=J)c2YJA(tc~vp2ixMnEu8-N)g6w^rjPr{1%<=J zfuJRNd3nA5v!G5RS=UC0j4TSC(B|gt4YQAYR3@FOsg$5^1)Z2lT5sAafZ>>ivR1mN z*`&;F9N8d|h(>KI1GeqS63ps#cg@JSY|Opwlv+YCj1Gi+!IVdiAt`uL9~8w#gAG;$ zp>;vPM9>oa<{94`JCR19m-hi8C${N@EpE8hDY7-BZ%{rtXJz=>?K*FXmN(i>BVgwB z8|FVHp15o;lcYKylxT_i_A9qXD>@bi$_6jh4wRYWSWn}QlAu)ry>$uube`s0LSFd3 zTt5kYYw_VlP4!g;N^^x=@aP#BL=Iys!6FD&Cs5Q8sqve)hMk}Ljo5HeX2iGopSt_b z&ANV=pBy@9)S&?cYK@1+Tt>PC+rWUi9|k+AtgsOF%ujbwi>}=z8gtLO4yd!6VUl0b zY>LE`CF7(x&j)G52xV5EYL1D-S0AYJx?e9rziI!t<;Mp1!74~CMBSA<9|0nnjSWF= zC%msa+^wgEBfqnC_|B{2JrI+DH=n*A3Ts3~fCL<+@7;8(szT@WxUmR5*hMXKRFm0z`sM2B>s@yPm(~boP?u?f+DT@1xfG(t`r-ybmyDsv5 z{qUFU+Qf91W;9Ydta;&=FJq4kO}L_StbYAe5R5i!Y{hf{DFm0I`QG$=`}9e}bA?GK zl7Y%UTe}2!xDNyUa9?EB6~PsGm3zZ}Z2NbIEpgbyWxc_6A3dS1tEc(rYWR+Ze3% z1#U;qLOVn#oD4A%oHP6ckWN~j74vfj*%V^Po_H|&E@mb;R19=FvQzZD9%E=@Mc&a7 zLMK%BJ{@~cX&}lp${4TJ`v`)F8IGS)}g9J_#1&^0qWe9tCY z80ET^ka2+1xCkZXV~P{6E0yz%_O8+ezBH@v0~>z*Y?zOk7^0tla@=Zo+`9GcOd@0g zp%N{$xHI2!YRgVO4-~v^+-nmALd@o|Y(pZ@45XE?!8Bl8HKK#|HS%KeDM~8m){Sf1 zm7kn26;YXYZ9R@QXBka^9y#JU3HC*&8WS0<3i^TdYSBI$xy%v#J(QJ)v`xTqqW-lK z5$M~0aswCSCiBIOln-TiV)#HKQ7_71oEWsBz)X&akk9?`s*CwK<7|WL<6P|@$BW?X zEZ@NSR2@JB*fofSh1u(DQW|@gmXv%9r^p{|8~J?r(6)x|F`tyucsJ1{f(_lRFVg#Z zHo2r=BAVI7Ua7&W?twu~eFav|*dcvlW4(2z1iiknVS~Zev5N$cKa{#)x3#m=HZkG# zG>?Akg!E!m@i#EA*0{oXExkABwxh)s@HED*gaLVKLSG^iSL>3BnMJU{wWoqkX`Bkt zg;gf`?|!~0fN}1|wSBk61Wj$c{`2Qr!PpT)wpLiCVGH=#2?TKGiGROq$2t;C!3n!o z<&x1wZm_HCTk-AVM>BZcA7Of@XV2~cj2pKx3UwPZNYGc)$`-*sT7(ZeVz3RI_!uWo zA%pB+Bjlso2&KAmPh1BR?!H#ziEbiJ7ilH%haYCP-Yc)LP$}JaLbp`OfxG+MM!XW^ zgv6(FlF9kth~ees_32<(XkXng1q~wli9AoId;t3*_+a|_R5h>9 zAUwi3{2FY-DN*oR*pwSG?d`qard`VejR&0>Rak7)STSe8ziw`EX^-%ft#wkH24txf zMrKX!#h6tqKTqPp_v&6p%_THC1xfV5@fg>P4aZ?N0c-9dRY5G2Ndp_U=1bb)xNaVk zZ!zUhNA9E=t^b-{&9VW89$LPTi9vN5S9tJ^9eKd-yfw!2v)NzBn3|or?mpSO^$?qG zSkq;DnQDGt^((p@#x~a~(9K5HN0c^$mmaO3T)@ezI>Dt-nqkp3(ue4?thjbmE3=?7 zuepStyjkUSeGkIAn!`dye;dRbWKG)1XZEsfO;8r@?J->`1^g=1ChU`Lui8Ziu~VSO z1&Xa9zhnD1RnF;+IH#&H=()m~3#oV~A?yy!B-X0{gdsF82 za;j$WRKo3zZRj@rwF9x^a!|#Vj1al&&TC=|-zkc5ieNu&BEmgcJ%ZujiQU`FE^|!e zD~Yuur;;{spLaW&Yh)b7l82+Nw06?5Nt_t?j}2c)Y@g%Zgs#NZMs)S$ac8KIW|z&gFfD4k@!Te!*2l#zrh~1H_P-!mSUG`$Y^hF{d_>e20?7;qU%byQQN-N z&=T{)`)b?UdwX(*hVs8Wh?+s{?V^vKyh0%k7@^`5boGJ0JOLopx~CA_2V) zP!g%7tXo_#2;;G)#GQ11e@Gv00d-U_UUxg*crZF}0%VHp{88-E92${US{XWQ=+j~QmE@nY8u&bfpe-7q$W~}5myr$34^`R19~u!sq^GaXLQA4@cHY_NcB~er z%I*g`lH$2tu~N_SPC1Rq<24$EKdD6L{p2LedyCF=^cqagSb{A-HqojC@vXZA#STj^ zDry{_`t7a#j{tG0zD|cvmFl0|_q4+y5}vN-xKZkD!p=hcBC)&?=b6ZP*4KN74<#JL zSWJi+*)WcYg@r8Ai&7@kK4|>jZ*w;$I|*>WxH|Z-z0{~gMcWk5^Ha)y8E#)GP zrid!bg)f_b#vQ>{&a8_0-eO#22)&0~(CaCSQ_@1NnuFJjDh3MgHy8ERKRchGAMRUj zaqw6Z^FLjPQp{txnuKf~4E&8cxR?umRwg+8SwG*)lwT$AMGgJsLQeN0#YkSCN~D_6 zY#0zva4GmdYQDYje6df0zriEJuFOCnZrwr31P@DFhFKSto&*&6RY*)TVQbA63&L0% z4Y~*!;24%KyW8skD2e7%zm#d1ue~qQY{AMP`+It*QEKny^_z`S6?sxkJ_oE@+uKSh zxuhXiiot)~-^e9caUxEfc@T@hBpW)cEJHSEJ`VkD&AucfI*8E7yowhY{vNIQnf${b zgV;9WwTKZ>zAut5-ZymJx5NGJ?>3J4s%QHH_Rdk?4!WLm10=T=vVOL%-)@;S4ilNdy+`@kxfC>UxLsgXrLX|4P3G_;4&wU8A3ZK?I?%|Odp&e*| zlIOo?V)6pwRtB)nurSR%E*xhmM$$YcG?aK$B}y2hcsF|+QQtPF9LCxW&nH6-F<_bP zgy<|53`v_(W~qMHW3S{+lz0<)dcd_6*qMpV)p9|QHFUxvUjTzb@$%85t)GdWCSQOw z*la@Cm>Fw-WFMmLVm4r0Ltn?1M8;VzQ!`D1orX5I_y@S`lgEl#198%#N#J0ArV?}# zS(f!e-D#9)G|0e$ZQk3^bDJs9$#AmDUWwOHLjsaSFAsY3(=}u8{&F%9IzgmQ%@iw$ z=G?A6MCoqc$oEzPvL|X90hLASxG+V{K?e8o6YIN?)Iqzo_VXm}4EMB59({n1bk~W} zmn*oql<#^w7U-{TY`8g8inS++#*K~X{@1T|Z(U_7FpHkiX^>y-V)GdU*e)yC7 zTwmts!G@D>C51)I+o`qVlx-;{b&c#(N_4aOqYoYMxgBEps+F6OJ&#qqu|sC{t| zaAZHRg`Zt6d%`E(eHQ3XAy6wHL zULee3^?p9=)~dv!(4LyqSSJD!l%&uy1Vk#Ja!$>ZioSl6iOMX78v{@984Pzma`9Y1 zQ8x_`khxq_s=M$^ALl$0xydEHC}jGom!+iAbS zX`C(Uq)J_8W%`p|{n;d^)@ZkAm+(Iy_QyZs8jxwY8o$AwKJcTMtNfYe{f#@Rs#PUH z^;Q!qZHorfN)i(F-=^(~3lnLtc^?h@zR^M=CVz6W;Tn;w@Y|@}mqCN9oK|VD!OXJU zbggCF2ibVz46@;4X1F@Km(c%ALE+VXqb?#Qf1+4vg@PSDBB2Fflc|`m<4_T8>oaY4 z(ah8>v{=~5tFZkE{*~%hx1fb-D{_0?h&As^SwvSpLQ z({Q%N{oMEER6q^Nk_Uu-g|&Jhyh$&zbU&;Wo_Z_|QZN@~t02{!X6D0}YAO7dD3qqM zB~j4lWjA4A;d^Q7#(%(IKJ-cvbnsm%he!9963``n`gR{k6QR#F%U=$Jr#}y!7iq`k z3^w5oSAI>C7E}oFZOdiP*g)b1LLQS1z|~10pz>A{KXrQ#KY^(D)o;)?@%HNa&7T(+ z{>O`+*kqf9Hw1;`zY%+VsBeLL8|&0h8|smbr`i$!ss_Q%#aLx_)}(G_kU-^gm!fl* zyuW`Y#KXO2`uy_b6OrzZ)!|$PP_1rkZ$G&Bv$KO)J*8S5`udeN;tQ*>iOH=Gm6Ppj zuz?SG)j^|>?9|&Sp+3Q*JX4v^tbO7rkp*{j)((@}h(llyaUW{ZUA*`~FGur%R5Aw1 zWrQq-&$)H=RaZTgo2h?+Gi$9dcBBG3HP4+FV1Fetut`@YU|5ruBzpwE%s& zNy>-Js5&t3aE|C@7b5>h{_11R)hG=bb&b3AvmsQ4Ki>R3%lRvqM5~n}6YW&lHn|=_ z8RW6jO$N57F$8IW%M}YQ*9171q@^|3J)RV?MWa71lFNKF)#c;S{&c9KGcRbHD#%ZfDrrY&Z zdW-g`OZ(~XE5c&VYs&0X1pHS=!-q?k)(s^Ap^F8u52DI-Q6`5M{%hdRq0ptp6aKF;eCOQrghpp5-J{7dP1FOS%qq{QO4UeD-@SLoJ z60A- zaXv64VwE9G&swu}c*%Ctbajcbe0R4RDwEHmp9yZ=C0=_c(tj?<}K9 zAj|J7KKzWo^P}fiYglJ=;_5Sh;}Pszv$HbOpLy{0Sc|+;x>kI#iO^xm!sd$->z%t^ zQD@{tZ#tgC{v71q2_$GYp2cQKK8q+-`9|?LmPrK6$z(~s0YQqTjojIy>8Suhh5Nl=~u=G!Q#`L^$MuvL~xSJ&>ojLcf8 zra?adC#)kL6F$oawmZ|nvfy4A$lJ^AP(+;St*hlUppD^t_y6PSEr8+(+O1)TKoZ;? z5;Vab7AJVH;LZ{txD(vn0t5&U+!EZ~-Q731v%umG3+y*}?|uJU^-pa9L(Pu#bU*#b zIj7}o&d!5JJphUX;QoK{^c+s^NCS9KV`ft;D?!BoF<|S@L{^?m7EUv384zNA27~?P zssLI|O#cWTC$vdFX6fG^P|-Q(HspkEKg1;h6YrfjC4gwjt*cYKeIOOzO-~m!1ah&3 zWo3OpMLd6t&M6?vD~niO8d`KQ} z8~c|+GoT58qOnB>Sv6wc_N0m!Nc;C(Ks%Ud(#TKma|0g$uS`u^27n#X3(n5X0O&Z7 z%mJk0@0WM3mLm^S!my&0sjHg_fj|gYejZ$q4^)V15i-_o-lo}RT(VehHP|mEc_n-{1=c@ZRE5DctOBAB2qFF5rY@9oU0bK zm~Cxxb}-QYRP2C)eTry3#iduxg1b(psL%(Or@etC;4#a~gYDsS!Z*u3S7!|L^nf#O zSng+1Gcz?60IW=s2ke@bPGu$QiOvAs#-WtK6v!s7p3wbK*R4yti zTTryc{SIRL7%oG@vLqRK0Fq700>h71`jInJ_glHcB{wvGrmVLw-Wp_ZUouc-_t*`Lb&(lq z9>|T$aPci0{+jG{e9&7!UabL`5dpB+>yS?ky}V9IhG$ z(?VL+XDW}u$uqWWpBR6u=PhD8Q zxT{2!*N)Y?1{DmI_U2s5mlevRYtABlx?hC2pT|8IZR^A)Zzl();TDNiQ*N-O% zBMDBzkr%n%BC$Zi(X>WqB5T<^j(H%hxR_Dj&EO3H-~088m?)Fk93_gIyI{!74z^rl zE*r_sU2=AS*J_&SoHxr$BP$SJ_**2i$X1%4qC%udSrb5#0yRW^9%$|^Uf3goGOk`Ur?SF!dTJ53e&`t$FAK!9pKsDad;dA_y?53Z}X^bdTs<1(F! zPk#A$*F2+M7!wmyEqe$6;{cDpsU*|wHYMm$M&7YP^u|BI!ZBZqy7TSV1Q0nbl>+!-2+Sc7dU z56%l>ILKx>cEcVBeRTe_JeuqCQs_|*dtfR`L*9H+0f&?O z>x_wgnHl=Z?cfSzioUxo_rpC8e5AM7l2R`CXXUi@4bsG=s3DXKyWkFnU`FfDka)3b zhM3BZFQ#u$zqz_P%F6*rv)Is36kw;x*PB|@l#`?=p=waE6`(r-Skl}Pj*zdUq#2iW zm6e@BMOZ(WFchUxr zIjIyh%)CwcF3r$rpQQd?_;T?ls4f=u{_Oe&fGK0urVOB!{<#KHt4+QYHRO{MY)vSD z%sRUdRwke7N((cWdKlYNp~+}6%iBiFU+|5NEtx)P^`}jy+udIK&BrChQ5pcD(`9QA zrW%;W_7dsUY>xS!?zdnbe68fFUm{Tv31L;0P86;#vz=)()hZU~!DLgU{fiGRK9Y)h zC0+@#Ke{3Qn2OJzZP+&2Df8vNH}dc$mr>5_teJvM>g1s_%n$M+?uFlVa7R^{FtBUl z^_9;vPR)H#Soe_#YsGeE{5;4A+UF?dN;$j$>gAnL+omCg_vZp;hA!2CvNUeXXHKQ1 z%z#krm!jR2&^b`Ao>M~ET){%724*+f`UANWlaEJ;mi)Bp4-;dpKt|LY9QNdX?FNgh zXDo*IQz(;1nHow^&$rl}6Ta687<{FsB`JTzB-ehL3LBqi!*1Hz0+$*R!=cy!20Rw(90Dbf6>D_i@Bgs{^s~iE3WEFbm7D z&93ubdmRm0vn{%{B^$s_qGO4EaFL(r>yrm&6r*al1HIX#sL}T;Z6k`|0{ssvfXAF4 zxRft07k^ErgMoBeqyVgJDL`_1eL zVg6ZOYzJBgq5{>i$`QNbX&tRHcRmI2!XI$oK5M+du$4PR-#wk}#h)${oWz&i>dmp7 zJ#HtYm_y3mnC?~MC;1y7yrS|}FeI*kXlfF-^G_7hV1?DIhU?sln&aX=Fuxx<>O`MI zPr0T#(xm1zKbJ_vLdaMAX9R^2bdzh4z=IuUVzRXE5Cu#R_3SlWyAS`x0`Sg9tgiCT zq7XTneS0GxLaij?fzu^Md=%7D$)egjJ^G@*09yI;IiuBJD${Af3fUm zJZFU53gkVin$NACi8+!u7bt%@f1oSHmne*Ip-!=p;eKJU@Zq~qhWHGxk)1&FSC;SY z6G*soP!3*KLLz5mN!vTii z&``z~pV>trwerM%=d|Z6itm}3jp!QQ%(@y6#PCW6`X}*#DkK^oT1?*855%Q4Rcqc0 z`qwZFaClh~ibeGe4`in0TcBm& zDyIceNO0>89FD!2uOxhVM4Q$mK5xq0b}9Ay*}}o>mS(>bqmM^`2t?{Ac6$t50*j~O zBt$zL)UKrkGC{AK>LV3k&gXnzR}wCX|6CzI$%-qj)9vm_NmpbUC942vnk}EF3$Xve z0Xrl~lNk`)J^xk?e>dbFcdBjj4Ksmukvl{ z16p9^m!|l$= z*#X5#U#ynDSS4=Vn4rT&#p7!cctlIw@^%V)nn+g}|Cz1OsVu|sQ%%e1eQ(ERMaQiR z`CUfr7q^$6-FHvUV%7wMmniwaBUEA(%BP zf#VyCs{xrfdxyW8j5G(OTuuc?V~$jj>)lD&;|*?pOomu5hvVxa1p-LNn)p0U{ASPPTp`)X( zfvFCKrvC>PLli>zm2iXRH|_k!K2M_i91mD9Idd2gEVT z!Epz+VxOP?P^QTs>l}x{{X-mud^Rn~Z7n2D>iCSZ*~9Q;`Z-o+{WF`9oS;g^-*|&F ztuupmi#0}LsrvRJJ{_*kh4#A()0^%7u!V{7BUvnfM$5RfYu>%E^+3rRFjJXpLF41r z$a8RfGoYN_xsYmL!B!)ZT0Ms77Z#Tg;fiXK%J$SF$hOqZXyAurBQJ6ia`H5~YCW6N z?q4vEG1}CpajnQQ90drV;RR+X8Kno5fIc^)Ars zFX;pYYEbOdy%>HI|BN7(FRi^(;ZG=bgye6(4aI}nX5?cY@qQ-XsKDP8WokoZgN;Af($1=^*S3qYw2h=hQO4R5I> ziT&aaZaKn%1Ze6tsk@X0}-fHon713jyEoed!BQ!)8z>J^?;zJx|7FsQHKW)s?L+gPvkjb6xR>)C!6K- z>x(CZ6I%mo_uxZssLW~g_@`_$)YVJ4eV5oPn3Gf!q5?k`Hp6}7)S$cqdG=2I1=?VR z>egR&R$G(DF3;Nf*|*u2lOJ6yqO{h#@1ow9B3SPhn6_A1GY6XV(G4P`)n9U31iYD* zwEmo9Db|R5)@&7=jZC0Y+c0OcGfh`YI^P<3+2o;K?_!{2|K{CvGe(s$=|xKJ>6RX$ zwNa1fWHt*R2h{0%D0)hqDOBa3Dv3*hBgVvRbln>2t|gdDfE4(J+tynAt0!iZRJH5D zRDBsG0TSau+GncS&r43AKP8Nz+TRG|9@KU1wRxzxYZ? z6mrDe?|?>Gh;l5YOvfj_)O|TRt9AwmkgjC7RaP&!vvbRzQ(Wncf(Ii+eRo6wn znSC77K{UmVw`|*TEdm{evoX;by@!Y2H^|A}6)P2J&w+#B$HY+Hw7QLtWq`Br=C|m|(sX8raI5nH z=GpuoQ)hzRF5&92Sa%=TW?7(W#utoyGtX43M1<=Uva(PKy%=OcmYSZU7Hn zrbxo_{nHaGuV`9uvg(*r|N`$&&-&N3vSmLu=%zRqo`OyV)H)Y8fOP(Mv_ zc0Uy01^2YgjMV)?H3K|dN;b=@J+skPn5h)ts|GxeEeA(^{bfR<{aS|>BXZOc5NAn% zQgKT3%Lk7DHR2CZ(6?vqH6{3x)yi-WTilfSLhy`#E0lw2(ESQNZ$?q$t9WyRWpfW| z4-9SU3FD}N*|l!b`B;>eOZyD)xId+xbfL8bB1Q6Fti-Ns@LlEA)REW@wYguI`v!Pm zbWTgSpTv-zoiUtiQQBVnF0Wj1diz#4UjL2tCIr^jLISi2_Ld(%EyLSpvIt=D78VX1dS>K{;I{FS>QU%v?<*uXuZaTEdcbyeVII55MCC4m zvbbfT+=h%eolSgXyBO6v6$FBpC0*T0Tj-Jd2~k+pE2FFRto6`oYvzE6sC`bh2OKULf1NB_KfQ(ad_H-y~(Gu z9c@%>?fG~tV@Jf^8}?gkSwrQI(+7FCr^m3fV`U$7d+(`>%A00`zwmjs_0t`Dq8MM2 z6OW-QS=ZX^CLphSf9%(FN?o|-gDG;`)X@vGm(Bj;f@*lWL1lD)dE+gOI|-AcDeIh92KPOTCON0pahhP4PZuCXKuU>(tP9?_mZc>2+RibMF#q zeV%;w%EAM`B=5Zi=|`BT_uWk`xu%np=>%nuT8$QEp7yKk4{Qhlz$3V{K{BDO&>9dlrU)&A3q|y3=$223+2HN7q(3^q4Z0vy7dvM?@q*H{ooDR4 zwOm_IsBp3@F|w|&MpN@G5`NTs!V!2no15&gmbp2^bBSX0h)ZYvk5aroRAx9CeIVg` z9AGg1&6h1M_n-mk+l)|Yh9;2Q3KJkV(%GoA3S^_!J%sjYQ7WK?fLe~ccznBE+m%P7 zyCX86xDt?sKsiDqLvp*$j zu}grh0MUb?0ekA)EfIFPu-d2$b?!WCyt`)b=_f!ACY?|&w%ooQUj*9PtC(6 zD@?FnwuX;M;K>iJ0E81by zMaBIE+vX5FmHm83YkfS{hrrDbYHI-o`75{Y^zb{~K+a~d>^}CXW%cPD`*J4BplvmJzM4_Q*Jdoj95L}v;14@8S65AVufvuyYwZZU3q%zY`qpj*XdV#*$f=&k2N z{{V`^`iWuq`#cj%-|$unlOrb@3B{Rg0%zG+@0VClxPPBeU%#lM-fh2W0emY{#}i0a zf2=DZ$3sZNmSV@9<>CEZ*59!r>{gFt?j#8L|ceN5qp4u#^(?YZ>VU=*?R22=}w>hdIp;})v@~n-EB_? z;w629^45jDH^=cKwB>Y-YBl0ziGY5+>dI`O-tnZ?S+oh$ujZ4ldx(L$iXEclDu-KS zp$90RiI+7Vt1wqsdVU#2csKbtkoY#Q6GJaMd*=1vFDaDlJK)reB<&`1!bFo*j``A_OY|JVlg;=FAF8}rL;}bUb(1rG)*+F!y--50 z*Ca((IS!%q#@Ndak$h1y^-I?1%Qk*KE4PuC!AnMoFSW;wC`(qCq$zg3Y@&Y?qhN~@ zr3hxgoFh3k5m@M6EhcMeRjQVXDZb3M6rbheG4i&ely{N(jTXHZgOY7Y%E-usQ*1xL zo?X^0*D9DQ5S}Z?^ho<_r*Ify}jYT7b)=ixl`l?$Q z#8o8UfI3J3o?Zk{=J}U$5`rIoTd4hWsmdT%{`|J}*Uz#s1{Se>dk4G?@lb)XxBFbK zFnqeE2%ATl_#Xdh7E7tQef*mFpWBKYI=a*MQy&wA%9H2){vmpUWVGkvIB!?}XpTEV8aPZI<)E@Hj-GH=>M8XiS*6z&6j^PDt zTdQnO$o;JITcLcu=vj|2uS!8uF~|iNYnr)U;0n`wo#19enMye1;lgz@3DQPBLgkGe zix_gQtT2AFcGr*Bc%}#z^UC&DTYKtozYJaLi-XYOyhe)C6Ai|CIzV(mpPWfMt}`AqMkRrv+ZO^frT9#4X1u0ehj24oxgTCECTXFet7qUohD_dyx{N`1UphZ zJ?OFZg&8gcIbahvUtrQw68E2JU?_&QhaehH8NGMiZr)KobLfGe#X%m?R-e|9A9idT zHp&Il9HD%^q4I1VFRj=f7$_es`HtHgsJaf7Pj@N^PV*~#kofwTkkHq!s63dS_UG2R zOqkd@FARpY>apU?yA+>m`bESZm-omZzx^E4#rH@-*;qgpU`#67jPUw0i;Xc#3BRcDi zCUScW?gA!nq}@nJuEvbN7@px>*Ubi~3LD#tz|eUHP;o$boh2E#yvn7j@aU_%jRFe= zB^sx>P<&9+7{eV|V>}@{8*#rZS?eCH@WvIr>xNB!^iKYhwMoPFWa51_;1|KxdYQO) z*Zp{Ve;aj{Cj4$x^bNxNupl99o1GoP{u>{m`LYf) z_EtYXUXo5`i!)ihC*;Au7}0KKk18sXn*D~JD^e&fLCmx9m05o@r>^t|GgZjGS zg*ljC0vru@s!=TFuh^+0U*=lamUVN@Kqqy9f$ zAV$1v{`mxD6V@YjPC5>He#{;d9>T5=F_3taHWBM@V5wobMWQk0m$;n$Kv``!3;ROi zn`4lnQ$n4RaIM(pB}!pot%wSrodpPm9Z=~hoWWF@z8~EN!mRj0s_M6Lyv{Ux&9*uF zeA4HCzVqd~%jI6CEizx1JN+OX=$~HnA4AR|2pBHhgaN}OZT zn;)dZA?8i(+C8iH!Mxjs+8~Yaxr_HU#1Hl6LG;5R;uf2b@)6bh5D(lxp=>Dj4!_&# zUg%)0Ej%|r=RO~@xf61;p4RcepSg5L;qAO_wtP`dC^oWnm{Ozdaf#>Nb>&y{lzg6o zz39f0UFh;@>h*WUKs^G(>xqKXD{x6yQxLclzWT%>#8VTfMaw8p9%N?mDz~V~v2Day z!-XfXia%90xxUy+y==Eqb@nqqU(nq=vP}u?jf2FVLhZ)plk=dZ_+cwd>09fj_`~+5 z{23FLaCn&8a&kG4!bCzEypLpL{q7!b9|jmspCGG|Y&?84 z^L|WrYX$-7`QkIr_Pj@YZb$dL&SI9@gZh(DzO7v|H5P5o=3_4(j+Xt)kNVdKbJ3tW z(qoIUt4BEe#*7vYvam)6uaYxO%>s-?ya9)8{g;fz2cNaHLYQ&pxG`SwP;0tS=7kOX zVA9MjFC)sp=!%vzgbnF#cUVuZLV`B;x%lsAq6x!`cR@c9drdV?L^1vT6s*%g7 z9@3nu8=S<7Ff2qa8-sG3jVAn(CboSH+OtqFlKJw+ykD9k!fF(kv5dm9mTJm9kB;It76Paa z$%(lAG50vR&zpisWOb>us(i%$uXL?=fScIWIpJ zmfK2tDNasQq8gs%}Po3{L}GdkM<2eCDJCUs-i7@s^?!<3TFDs+9}QKxEm)T zX~d}JWe8Y$%uIl=6C-!H+sesx<8i~83)f(eN^OiGfb~F&$kvZ19U7Ye2+F8PYZG5v zDn+0k<<|eIXDidH2sxLO1McoJ?%m{3*&pJhGYo%8+RE7z`b~p{s5q8lA2Ln2REyq? z2FvjQA{`j-V^96-bSW9ZW|?+S%o{}shXI4e5;&&N?WCOkLqE-5mm6@7U^a3bZ|&Sk=W2z}chP3ewS?#n zwBB5)eNP89DVlPRi-OasFuSfcKe*Y$M3$|Lo;>k{2Mp_M#m!ZpPSL7l_TdM7=`Cd+ z-NU-_YBa*)?peF@X~-Tr>W{m5d!y5=NU|Vs;hF(Fu*>`9=DbTK;qq|iV)DAPj0{FQ zPJdaJC+=1!1AEyGv3uovGliN3(0~f2z8mP;Y{;} zJcU-Iv=8L1tJ~BXMh^XI^pm^WP}Td=*WA~}g(^3Fk;I;ARU?R3@8+AHSC!CXh&56O zs$B+2O}VV_ToO(GZ9&zdY{$K#@M+9{PX9t>t&NP2SixGVmS720ui`1Ro9y2W8g?+K z=lt<|#gdHp>RWCgytZ+j@m8MN$i*;OpGi#0Su}KBUJcrsh3!F`Fr1Xl0YFX#0b*Q>x;jzXt+af)u0Q0+rwhE}X3512 z@8Z{aF``@Vb|6o5LHwo+z#y7#LGs$f_P8+orl(si{b==w+K87uEL;`qlBQX4Dv<0x z$N>oKaGQ?)Fa9|$t|wQ%I#`N2l`6hmVVXFD(&QU!a(usOSHyQZ)o=3j@Zj`|G@d#v zc0$TalZ1CZ@ouD)OjBk0+c`i=^dF$}hi2JZxNwwngwks(poA=9Ml#_+^O_MrX##pC zU5SbPws4upCWXcR^9Q8tL1)9-<$)m8?ra^WtTiel!o+3NLAvYoH;qJ<|Sdyz|`O_kd1Tx=_G^klYW7b2@oFgB`K|AGGr^c=n9 zFfcbfFp}xmD>X?sX~ArDm~+Vnu`@=XZEWRzbRckN&{Lpm;Kx;cpJ!eQJkGpycR`S-v@P2)}8__Am@O->TIYw2yG zPnoj0LoS@?{ng+bu!h!n&)fZ6gvsa(VtcY?%F?r0ar(<9toxl}G zS%fcQwc)bAc2~;G$AbNO?eTTxLS@P#$MLdhrtdzXtKGqPFN0p<1UDh~&xkFw6sL&` zbgvCkl)BSAqcu<8yAh+#4=Wb){vd0iseTOxr$Fug)o<@&m41!MK-&5&lQa7zZdUu! ze9WC4W8V)h^`ufY;EEiWE^3vgXnj~Wvsbm|xbyfUd37Y_{r2x0J`TSpEd1#T>e*d) zJ=8}j^|75oD6F`WI)o_jI z+|}+^lXRRB-+%>;k+r6HL5b*c%%%ki)^<{>+Ttc3b3^eZejo*f-{ z_HNop^jFL2#Xyooi5KOD{WYvYATmRVK)Z5ulP0|#=h?KJxy42kO>Q`INqK2agM?BY zNW?wkfQw5C@;gWTI-l@WV5&KP4cnC$brETx6{Eb~BEl>81*x@3g_eTCq2tE(aBPM} zu@|CRlz#kdwoTqy;YFC?BN374DN&1aS#Yn5>FF(Kw5^HBcNcTn+fTVXMJU{U6F2-j zOfKuGOk3>((l+E#e>~DXiQzgHTBeq&@pHj~E5&buY4g}?VCFG2NINjsVhN`31hTG` z(R_9>__(p9xh-&y_(IcYr;1-73W_ZP>uX7nsb^G`S@{nf=CmPPx=`e{UPyVD zJobAnJap$1(8v6;!ND&B zo3;aE>-|#*X~+3X!MlS{M|AHBx-)?NFx7!(9@cspZ00z05HT$z(;U%p9P6J(nB3mrL8o~&%Y z*@lKx1gBUtg*AM1zuGwD?^&`viC!Ru>6wG?6)Ga~+HYJ%1vih|-M(g!jbI!gKS#kK zA=$ae@zM(EKlIaUbj~LS!@S_IC6S)bb0lBA|D?|qO{{e$f=AYy1Te|@|61o%HP1G2 zTnVd#mF%x-XfhAr#eU$~tC~uVX!&(*{`_|?u6%BnZG!zqmX^Xk*HQl0PcczZ17q{USeW=hO1z<)~2|CUk%z{Pi|>T#JgPg&D_A{99S6e;9>(=>+-SQR*$LM`&g*Kr|87GxP}dty`*>q z-8u8XT&A@S-_gL_*;>H|Y~bFj!S%N(lHqB2pe%mh0e zB56(6SUEIXz1>vznJqXW<80CK@$fQZHisReaiI&8)RUmJO#!V@eZmA;5LqgIys3+b zh@hjT{jJh^ToUR8yiGS}tu?{avdJg-eX%V_(Y{z{2{ObGn=KJG+abJbebB;PW}ue2 zq2OXi>VlG9?hNQg;^5$jz$tg^n%x%In?(``F8E1;ZUmIRvaZ1UL9|L=!`1ttPI5;`Z>o2~FqP}_aCj9&NZ@1(b&ly;+I{2M2 z8;8^E+ZWb-Xc-EAq%NkUr`ybz>L@BHDP`Qm#Z_g^&W_^~5~^zNWm>|I_`de^^enUs zXB;gxH0|(@4-fuTHa5o1$;t7vuG!wkU#yj*W?)FeAe(O~QzRW;%{Oy?JCcmhv0j6y zo4d)&!{prE`Ms_WuPxRfb>oR(<>)^r4fe|BC#%8)u^u&96jdFW%XiHaz-iUhxm8rA zuF7lL6y-mC@@_uKX;oCD$7^Z|dyS4xO=Hs05VifIP4TFrAQS*874AWMdufv)AeJ%) z;F={`6_+XP75e6I^KTql_wE1EMwcX%;UtU zH4q4NxY|}SFOcu;pK70})YC6~xK+A4RnaWMa=dvzgZ9 zS5(ZwSsuTgGQ4h%4H_ezo^;am#%D&pz*l?kg(11+PCuA)hkW)|u^%Oj>x$qb zY*|l)PCLA1_HTO(&D~H?*Kgk@HGoBdE&>b%T(YGH`z$R6)y6VTuZ*C;K%pm(ul8!n z6N_3|Na{{bZ|LagMAmK+p9cZ`yPf!3iTvOn5q%AF@EiU)dJc{V3c-3cRn<+de^zB_ zb_MEcY<%awmb^Hnf>dk*h^-j!i@xu8Z3q#I;S01|#l)PWBi@RBYv?mOpAX!Csp;W> z4e#?+3^CA~%_a$8nD+f5J1{f{W5%j~#WGod*--g;QlqOA9b2e*Wt8|D@?4Gtbai!! zkXcmdLx2CS?;U99H0AWTy4SWnAakfGS)2eG7>9ylE6KX!?2Kh_WaR4JI^QazB=n~u zy{NHC8hqR1Ai`hI$*DR}9OwtqQi1}xymtI`RbC`gacTOnfB0mjCor>QY;3&0Dtu(Y|NAspJEoR5vr*+ZO1@Q-4=!iIubks+ zdvE}$t!Z7zcQLRVZx7C`NH3TxDpK@0A}=4Q{&}?%c~jL-O!~~*laRr!wy5p6U1Zns z&v3)0d? zqfGD|l+!eQPEa7}YwZtE@aM@DXjQ6;&zX#3TeMtF_Xdfz#D-W*4N zA=WO_Y@mcmnu1p>`yvT0_h$w+oM-zn@_1c4te)EeuYwvwBiTQ#;F&~uW87}kM*aa{ z>jB~;Bfxz1Mm)N$vMSZ-ujC)MHo;2xYS(Xn=$QyA!l6XxIL6!``5EO`Qfi z%ijKeRdsdsvpx>+hnkk>c6#+TIlq4gD`g0LAr94xb)l}VI42?|);^My1H-df1HY3 z#0f^jm{q4#t_@?FWnkYeiyCWZx6Y~=xZb&e4_gU_`OvW&vBfeNs+IG1kV!ORFtS~x zDr;;1nz*c^iMB*B0%ziktj65kc_1008P91*7$&d&YMNN;0=QYn&(|6^bji$D)k;>y zZstdQGJO^2ZXWCu9>F}{H==To9qiMZ1@LFI`#-ES|CuUMGuJHD-o5zhvUBKjEYjh_ z!tF{ux~i4M9@DTo(z<{c4<=<2B_fqUK!Bc)ZB=_QTk3v=!J|2^{mjmx6mbOQTfb^Y zxj|hPE5YUst|@saiiRoM9{Rp%j0g`8Uz#O!DDe*Hn&I1oH3v)R>MDQy__5V@rjVEC zWvDmH<$6S#Z+Y_q5Ryr-=+OflNyDstYZ?6&#Brv<5D~n?O04u8ww4U1)aSC!D!A_< zx?fw+feQ)u==*@+o>w6gEXv6_?<%7Eon{)X5b*OR*!YuuB-hP?IU$O6{UKJ?y@E?G zMGmstRcytTpCZ>yM&X9EJ*x_A%)#1V`~>e0!iQyVH{!`n>T@o~wJ3MY0$hI~|M*Sc z?R|A@A{g@ST@F4z`PtA@c`=YRNS@S^xch_0-76j6Y@$*?|ACCfQhwKr>40d>Zu2`SU2Eg)tK`E-+=4sI6FCo$J&cq zSQKh?kf_!nZjM*B>P-j;3HetbF~HnAohPFVcnsa47%-n^L_&g^1>o%*EzRiEm?bJ- zy0}bFdp5TsfU~ftjn!Hvs8_VR_WG75{rq`riU35ne*iun;5seV+sY^?Fa!5t^S5$! zNvb4Hm|b=4X<}&T9XIz+UfX!!+jfEjK1Kh|^ta86C?Y}*6AZbo-rY8ZKZM*i2df3Ak#xX+;0O28QCF{p+%Mv|g^?X) z=>g$1>4V3SHDH&1DfkA5hQ=ql{77QayH@}U8lU)SdFL;}1z1^ESzLhG4j7%i1@~)D zO&V7&z~xeaRRgn*+yvoXbE!Nf8LRXR3}NZ%r?!F~X;)fuHdDD>fd3miDs(}ffPGrVaL*p0*tTf?pd-?@%8@%gVUCZi$?_5;CO9}4o09T)`lfi1e+GD+ z0}XH4*cw!>{r+_hA6w2lk5VOI(e&#d7RIN;>CIB^vfoRpLlmqk`q)|mBmqs`6DWp&Pfhge#1 z^Ah~~L*_tGNxk#GXZsyDGC25FKp>TCoIlTS$?t9_+0@MJKsxu|#kqg==l{F-rmRGN z#MPU|uRBSnqs!pNyU4EI;51kb+Q0Mt+koXGa;f{jlLU>Kl|Zgd`oC|~K@3YST)nQ3 zcRRbjds5VR*a(&3>O!pb{vCd1K$;f$?*cR!Bn5@NZ)q z86EAls-wISl>hRM$$Wy|dE;Z{0;8|7Ow8|_6}K%a@`nZ=S~|M9{YF$wGY5E?+kDAr zjhSd}TKKFAAzCQ#EbI+^Z#`ffcIU}$bZ?PQ}b$}GQgrHC2)7Fid7GVmu$D(AY!#DC`dl(wBy11ems3) zeTy`-Yr?O*V5F1dmjeB>hv8S4tTgaSsw7S(;PdtC&e~}0&jsy=p7=$3YRz_66LYH} zj~cMc1`(?5wx1VOLK5a~G^!HK@>E}8G2};Jp4E=YB$ z7ow-OX#ZjBXo;A3eUF52zRjDi!6!Xnj-CBw@U&2qsJU`ejB^XOpzA|5v!*X+?8`M~ zlbLp*SJ8jIwv?xTn-59nD7+Hu;{!bVps+Q)`e z!SsSw;EHPK4zGWbr#RV!y->q#3c zsJtUf{F~(aGCh3f`Jpe8VKNsx6HB)~8Ww%gl1TC?i9SjvAb(#qsN=+kFFOcsh1)x= zrk`KyjCoS5QZjOLVhki0hjb=nVpk@%D(JXwuDgPbupuV+j&{PnUs1l$oR~a`!oM&M zZ~NIlMuk!NCC_RVOwLhN?wnrC%(z>r5wT{RzjFI#Dehp&D>(l!+MVTV;)b}8<6wk* zK-W79IDZ^{@*ih2P?8ai)sO~ym68!@T60uvjH3KGsL_NcYRx0D#eQXYMR`S1^w0Fa zffsNegJ+G=sDasVG%g_NpG6g_@`MqdF7fj6cp4?@4|?bRk2Jr|sR0(`TV#4aF0&dc zR9}z80w`i|_t8W9qwW+m9oA^+&DV|be)XDQLKM#0al+VnKqR^B&(wI5q!uo0H$iu( zf6IU4hu_%?xBDV_D=p$}hDn967wx;nOLcg|Cn6N$`)+4~7hP1r_bIsdW^;7ogZKFu zCMJI0`4OJ;t<4y#Q{-d#0ekw0U1s-C*+W-#j8?fvXlvYaP_;J!yar1m>};9WmicHD ziPs6@(;HRcJ)9+Y!7k-ycA2P_BE(;AXWjK5QwF^5S(TkA3GK3<6reyBF1#ffDje^} zDxCYXZe11=bN(w&VVn*2mX4pJSD3E_?ivFjKHt@{NfR@ z#A{`@YS+C%Q2 z@@CuxxBW{gh&j;ZoeY^m{l|J%?~vqGL<$Q?GxZO;$@Cb6vpV|D!b@l@=Znt=?Usnc zp0J!A4~4dU^hGm}Rjhn5o3lKIF<{L}qyBZqQGtT{9dLi;kD^ z`|`4}EDKhXf!Dqmu5sXjVZ@J^bgsvbp0%&@OqZae&E~xJf7-jRR-&{8P82cGGx}OD z7O^crqvMxCA7hppe~eKH_x40>rktN%p-1xkg=ax-dtEV=+XN%|5ysW^NBOf4H}+_M zBVEsyswrO73MCNt#5Q)RxnCx!r^3HpK&`nv9_~WE`MTTO@lg(6S5vpKC<}YObUfTh zXtCc|i$XoC;NbXi#}kWyk)?tW@9i`2Wi}RH3SI8mJS|aS`kURkG^^JVtE zN3SF4!CmKNLV$H>^5mX~Gnm2;q-PSHJurtr$wd@4qdVp=0>_> zECEs?3Y83Czg+I2TCT(Izc48%Gcb4D#ruwawj?!spmtTEHyYs9Lz1xy#{p=|5LqX) zF_tWUip%6L|1CfFJ6>BY~sd&9HvEwTXs!&ox=8Bjq7`o&B7%%B2zSSofHqyhA3mRxJkU!+lHh-@R>Aj@T z@xX~ov1@+_7jZtUQi+J}!p)<<~_@e*@ummQeACuQ9}NvSiwrIvX{hRHhq1cG``|fMm33J;)>p}G!bDrs_US=dZkfs z+hfM{Wod~!GL)6tWVa`C5v9y?MsC4E23qZ1_%! zh3C*Ca9;456bVA|0u0~hy-LPm7%Z-y8$e#^josF_vJ?y)>-g;CU%X4E78T{gqZ2;U zn12Q|x#Drw(0g{{z7cMIVx-y&IWP%!U4^$uO)az?SfU(pX@VbBmMSFaf<`|yKl0b( zcoNQ?Y2J-i^hWwdPc4KPJ)j(eV>0?)J?uDc491o5pNK>=kIoJeMeQ&I#$CTG1R5Qf z7T1=WA*U0YG8r5RP_73d%JnGaTy;CjM^AM_E}d=3a64Bn*qBfa_!SN?ljJew8c5( zHm0!OMhyk-$;co<`F6N6YL97~$JVfYIpCySb37>a3P0lmoD|uQBXEAR8o(s1M<};2 z@J&9|<;9l1(PiOc-ux1P1sj>o(H)2wE+k}I?uj|q+Ys%rc~$aAp3t$e2up&f6FWuh z2@Zf)_Tu`w$EfOosR{K!fyuIuUDIt_c>i#?{6|L0E*^-$UuuPqUkpO5f7%>~-GoCi zUs=yqBddqsEVQL_t#+#G8*Xl{5|hhGSLnSQw?9RlP8A%65oqX;N0UG&Ws`zLpXBO=65--eA+2b7HZlhezMWAVTfoHAq z9>b3hA5CC5k`G4A9DhMXzbdJ93%#gN~mW7M^QkvMHZn{da#9B*`k7UcIuZ!clF>! zBf5tNdS1g?DZ_Q8eu;+54O(r^ROapTRdMGVL0h7Y z2XrRSXCe5*g)z&+!-jZ{3RweZ0l5OPhRKl8%HcA?L)f=ubHJ$eph&7Cmw$l3>$rg; zj%XY@TN7WQu$}w;5roo;#Lg3-4W_91ZNkKDI^4^(U?84Ncv-cWmI!h$4lPLa?5W4)_icqYbl zROppkRI3Kc{7h?gkL$3DhTBx={EHNKoR*t9xGxitTNcZJ|ZA7>;5qk ztR?nG+Y^hMu(+QmgtxpcnW9L+Zq2f^>0-^_@fgL#TrE?S0yES6ko_?3w-$l@N7a4n_COGL_Wr(9unf_qpQ$F?J zC2+=4)X(?aIRR$4JA?*Y*l-+`o*vr=^|ayPVqcYP6f4n8F@f6$keXq2f;vhg1UoR! zujo;_VS%O#{|7$?`IqSAK|k3Dnt)zFUSUu6in5Wu(8S1T(JCi*08#q4>{E-h$7vj? zR#bS2ghYnnHWFfuqI1vY;g?3df|q?y37#@W6(G{wQ|~s|o|PIfj~YXoAsXq$u*KhU zqNum+5H*?blKXx5;L^N?@hlYEFn6%`Dx1a)<8jq8B&#)Eso*Y>^pT_lWrKqF=Jpo% z_0f3B-PlA{gXl&bEbDB98Ovj{nC~sM*JV@Fezn*E z|DIJ{ihF&*XSf!ug%MY&%r2?$3!a4MTSiR9ogGy9CMwTLpC^0$Ln(r^|f5RJp5~FGx z=`Jzh$BMh-pu6LeD_Hb>M>~8pV9w@~nwq4gCMi(_4$_}yQfo_9xX|?VVVT!S*#~SR zspSz$OwdjuP;Y=h!fd@cYs|I*^g)g>PHVfCTY!Dr@wgooqsP*vLeE?;N{_5GrR~QA z+DIGPkvs&qAlD^vKilz*8KyhW^|fKxFEW|CHFKxWcTt3C*jCz9off?QHRCs-=Ju`r zFiF}S(X&Uyg{rz%f9y*tV++|oIuX905(Nnbsn8mecn#Z#0sJDacb3Miy`8I4=qwW# z!jz}%*MC_Ao!Q4Ho%P2fS4S9euvH!yLMcf+rd=4^9QQxx{2sGqD6jOHu?jgX;&|h* z55o`b)kknczH`S@;dhrV&B4j){6?n=OYSCY6#%Y~UzCnv`G&UlB_~3qqN_~3eH_)|yj`Abk(bCZ|*K1W8e2Bsv9AaHdZR$Af z9bulUeHB!pe&2T$wYTKcXJFJl%45g;m!YMlJ&px|#zKhozW!bm8ykOsfyz0loVQ`o zsPuO`T0rA4=zI`1jzC;PV(zYoriYts7hEv19C^$msm4|insrq6Tl+jLup3X1?>&=O z!DX?ECOPG>)wa&%!!GyHwX^8D;OXBMK=C%3 zh>T0IbZVB1d3LR=YI_Wd;zFH3-+&Q-9^-zy6+yNR9ZiH>TQl|Tm5ffHnu?g&%5x8&;Nm4Kalxm zDSX_XD? z&714Lpx1Y#{|`j@&o#S$-~HFcdOV>6%4Pju%F6Rk|IPTn>E`w0-;U1zP%k6X>fi1C z5AFaNw0{G>|6vc6`3D~VAMQ$L*KTOSrl=&9&8@B2#Kf(mA78QFS?&`Z z|2lCcARrL``0>%;;NS||-@wejSv)}{w&ji9$6Q>v*eCVb*4xYn4x0QxrEaXS$;MxI zAQ3V6bdrrG`pjyjogCPoKYykGpfW~?uzRvmsS&6xBvq8PTmE7yO<=}!=JxcrlzGKa zJSVvKUvP6;Bm-xVww@knSnSKB18;iS6{A27>Sh+*=Guk+^RqJ&UYnHR=vmcYGv)ti zhrcdCMrSAiKMbpY8m;!VFTD}PNB`4|AA5=4eIs4!ZSZiCq`3; ztKqUWb`=IZeQ%!`^p`m6q@FOTR^3OxJJwQ+CF%3O9`EB{Jf@vsyFQ5T_)$Uv|0Sik zPdXcR%LQlqqW*U1`j^kmk*SC~&JDa-9Fww^9ggOnC>AESc{b}W^`^W*=}PO)jM0|M z=S=PyBEf8|Vo*Gap{YH!YvP~ihdJEp@J6HtJ>17yO6(!}Q|xE7uYWwIR7xA+?l3cS zHS)IJmJ+^d{icmv>c1Zy=X~4w#kHa+TW)dcAmIIf6c9i5nU?Esl=I_0fdhKy$nFlG zGmSI#qMvtSl>ocr(MZTmP^6TXfT~QOzd8ae!4V*x3o0`YZi6_mt8$nIDta z)X(520u*QJuGNwNz@M=8tNk4V3 zw^VFL9SNnlTT)L>-a5b*y{ojiVSZ!ityL@?R6GM4cOfOaqGoSi<%>GY^_T11R|xT& ze^L^>%otk#f!*%C>*MwM<4=|!kC(yA!`&i@#`e6pKJKFCZVEJSxdH(3dS;2fiMZB0 zi%IumLByg%;TbWFZ|hiX7h{aB7WQ*p3WylFJ%>a|rb}MFVmu{Qt*)-VfuE0;AO?qq z&fM_3Hp8+yL<8`TNL&X=7R*XFDh|(T7OHowsWN_MZ4y=W(qEc((?Og&pCwJ#2y86v zXms4MvK=MKE<|O;w>a{O$Fpw+NU?AI3TWH)n-1F~vfb`k9RFdS&Tq64Pb%z*JB*ur zvgo#}4r=yzFvzO?^M@&IrebqcNZ8u~`;DLWO3un1uhaVL3n2Lwl?6ZLj_CeU?>|4+ zt-w!xg5-azN`~5rzqSCmMCz~yGQ#yyy*B9o6=b=I|TvQ2S#(=dHyqd4v;P3$O36u45L*)-B(> zA&>LEcm-FJ?Th$rcJs^qtyTahTKo|Wki{caX_oNQ&WSxCyjQ)$edl6rZ3|g%vt43( z;X)_fhIt{>=BUF$1%cP&tkeU|UlJjCy< z=y4tC(%YjF79gYCimtSmD%TNhr&@DTAseXsM>JlQi#LW)(uz`vQu+Ee9v6pe7MPfN z`F&xpTuOr(dI^YJ?(1kMtM^mUv;yd01+xa2zn8e?6_EM>I4EyXnYZx`B)yE;jm4q?c134Y=J zGu7hXQvm8h+W6DBzxGpoeMt0fk%d-4^ja$XY3u1K|BpzndSBR6a?IskN;-lk??U1P z9R=gHS++OwuQX@6Nn8;M7co~ogcI@Bh0*lLj;yMJ*Xa_}2>H8`&$hHH) z$t2(2S?{vwh_%^}#pL6)jp2==gKIw7dyRpZ!9s4XtKFo6?Z_6t7nFeyw0W^0cLBf1 zsaCtMUXgsT6}S#4zPLq*w9nbH%W;q0?37_gLwgA4!_o`0PA0X#XI8JlV}zAb*8g7c6- zX=lv3`Lw4{^t*m>WPixkL#6E@Cd=Rjn>iE+cJFPf!@nVU+ka#H>}cSzyN>M0Y}T1M z=M4<=Q!7xUg!ib>-$2VniH>P^*DvbLSToEFqwm%@e1ANcd$H1TnnCuzEZ3jrG?w6_ z2)dn_VtTxy+l(Kt-`xXryfOm?GbRIiX72Q_YGqGq7{}l*q-`|80VCoXXmBHoY1&F7 zB{Wv;31PSXxUl2UkIhf=)WSe>Z8;VE<#`&s4n`t^%slsS$dSmbq_4*BCSfVZ>Q0hQ!s zH-}Bj4#U%gg$*v9l1?q0tY2TwCoI@#Tpbxga@bRO8yQ8suky^t^&)+IC0mDi_wD@{Kj6Gz^YJAqAyY|ON?MnAXD%stNXj)Xl8sTb(+ zRs%`1D(i}TI(X^gQr>jr-i35#zn7H@*Htn9$E@?$CG{#KyG$XV_p&Xzzx*yunS0ym zo_O{J0rBXXskeYpkTg09wJ!JddlwVY+pG6x*l7GdE?hkMcyYL^h~EgFYe8jed;-EQ zt?ha==j2w?KoeR^LO^0*kb7($EBL8CAO!N5<1EpHg6+9g_$$B+7^HhwIf;TsHCyI% zpUYLud5*vhI+iFW6aEA71B^QceqG}lRqDQ4BhQ` z`i&9LDuTWO3)s^w0Y&lJxU4Rvp7Xn#k$P$aOmBk^QYUOl>@&ULBM$vTnwACp|JzEj zlI4bId=KPn+fEr2fo5dmtf{^6#^8yydE%5d6O!v_3vl$~nv{kU)njTRw+k4|=WhL+ zgOt5-`|&b_|5bON8hEaY-_x*o|_qnepPM4xOX>{ zUDo5FyA}6YOD8bDk&szUHX`E9Tii|xl24H0YacP&fErXP6#q+EZtNYR0$Yd9Q8T2y zrvpp&U7`-e{ee+5Art1y=W zL%AG%Ua1^=f(+Spda{Z92oJT#*@2|k{Q2AhqP`!zBH~GZ0peD7J$?it26!l!LB@9g zHAONC2j_a-eAG26;uKi*`h-X9*0j zx?{gGwSSt!ROqx!9^|r-off(!c=B530=wcc6&yK1 z*_1=`btZ^?D_nKHvSl>p17cZMC|G_w1!SImP&vRG1A#^*xBT}H*Q#@RS&14bY z1&}~|gE=n4bE_3zGZsGGbHUk*Z-xaE-z+2i)3@xb2>V`tITN?Cys-vF*MLYmSpy|0kqGjSDDhn*p6*O4 zLhl+DyBdoLT5t@t{ym;Hk$om4*`A@oaD{)z+?QZhqt$~GaeL`J*e=gNfJMw^f&%Ap zsr73u@C&p21l3BW>HDqUT3M_AHSjE()ylNCj%a^RqtXOMRT{ffg)u$-DA++nhwS&i zK#68YR%cS?&c0IliSk7~xpb3BD+TieX;0-|z4(jAe?IjmE*{zy)Mr3}wr#rMxw4vq zzBKW~CXR3lV~o);-^4AYsLhWVI+|#Fkb?im-2i%j!x%R6#oQIPFmtBW?Zsbu|M1HG za?P02K6bJ)Fn|{&zRT+1XQN6zG|Fbk?s(t6eO59Z{u}m~vC3lXpIhX4`*vti;y>^A zuPaM3v<8&loy4xMm<8}{)g?s3?y)!pl&Ucw%vLbc(*9W3L5+h-KZKW{>;7h(G4JEC z+LC`d8h>6FlKf8np0dpUt4r!!57eBTo&R)gm3tqfwq$ww?AZ@ggvbN1Ki?kR+}@6h zkKf3Nt_&*$eKUrPQHQ4z`25ommrl=NzR_gmt1Rs|yrKL3OS zLXa^OCNQ9m76?VPF-qn(-QO#%|Dsri9uDk(hl?n#QJttP zM~+naND|KOMG4DlRHuy1lxfSz$UxnGH`9MnTBO(GB@~DyfhxLyq1L&Zp8Hp|n{m0N9<#!~eRGP;BY3|5= zjG;B?wzwHqX;{pbQ-&J8gB1tZ@{;qWN1#cU7pGoH`sUJoV~^EtJev^ENAN(GO6fObQ%{{Wota@2ohtkdGe4q9I~`WL_a8{EvP^8D)vf{0s{_d5an1?NBZs;--oe*Bp$ z_*ZYlhW_E)iSua{jOLwQWII$Wq9bLytNn|*yzsy8Q`Y}?!X!!}=3mVJgZQi~-kv4= zmev1%)g&Gz(VuylHxE$YQQmQ>kf)mmf3E(@$-F3Qo2$;>YVr3s^cgj7V`BATK$lCK zCqDi0T$?L3)`>uRd!|s_!sUzYlNtwuL2(_9N-Rp17LNNwm!T!cCCU5*eLqwPl`qG1 z>87kxbP=|=JAZBGXKRvJJ#XWBGibQd_*|Z03MzWoh_yDPpbv|(1l z#W5eTPSrT-po@#Q2aV#0rvRB zR`u8aOP%wc>8AY&pgVYXmccRf4~SST)=mp~3dioTBD}HI8cnSAcGmEWQ|>n~c+0&b zJZj32A>8wO^`l+H z6g#8p>LCg9qCSP3(eTGmKxO2QaEP`B?C0|ZT{zo3+l@H5qNho|1HrP;R1_rFamTof zIkt(HbwEf^R-rkNLnp;=gdBtn%H@u%u#sr6YLs5ijaf)82&i+HTYnvn*i=l4)c3T# z{U~{P^s%M)V_XZa(cu@ovz4@-=Gf);`QFJ~=KC;g1#6}BUN;v~{v>NNL~@zyAYIB- ziU%YrWAeuu^|!G$>V)d^15F)QFHyldh1bQt>bIGKpaXrqP)s92K$+teqk&L&!8p~% zLQUBBnRc9Swt|xf30SGTJ3?-ruh&crx5OD^y*6eOAAa$B9ho*Xg4NRGE4(55m|WCk zo4#oz&J$s;3 zZIc6F{zzA-z*%h%uOT++(=vpQRhj~caktMk#z{*eyagyH`H7vI6EcjzOU}<2bJkAt z8c_d-nNoahhua97vR$C9Kbq@`rWBgHIx2I)+8@;w&8so)$8|fL19ul^Lf!3OQB)s8 zCtiwhi z%Au@x3Sh~Lt+X(^?F!3q@$$cYl<0u@~1d;m2nc|`X4nDCH4Ul zIz|MigY~+Z@9rFj4}A7 zD{Gj(C!S2Hvux9yD&2=!ZoS-eC5C*i-jWnD){*sextpBo7FvW++t$C>8Jb_q`Fcmb zw$%nrJNjOs3f15BBU#cu%qNk14?_Xn)kjjp)mtJAjE@|L2uj`#)n6{lSz5BkbLaTc zMY5Ue4DA(n9kVq%@83!M39tTb82KFUj%a#BA2=J(1Ox;;!niRc!MHc$4hS#{Pih-* zHOG6!S|`FpIY|P5>a#3;QCRA6OEDeSmF|cyH}2Y|t)$v)AhusGMbov&nvAVoOFkQD z@Qx0VkgY$5V6q!}Xko^w2u=W(Mn`lVNyyc%+JLNdcG}V_SDre4lkYKbDF!-o_|BnS zh*se8Ck))C$k}DWawlr?uxsI-FVuJpN0(Q5BMQbh$w(tZP@9CT;=-oa-?;#qR|f`y zK#}z14kV_z@4G-Wd%T^qM4(fn5w&NjmN#AD=!tYc->vhldqqui?|IG>ByRF4kgnmp zdqY2V>-03g6y#00gMA>eb2XUfLfL(@M_pO`ymP4C6Pdj+z^I{Lj8%rhmk+OuJ?!M> zA;~pwmj><{KoVKMa9xglpCym`MYSjj)W1%2h0F?j>{(#A$kEdaBqZ^t3HWa-#1k*E_x-JU3WCO1oQN87E+{aEG= z+1@{=GJ`ZWXlA*lEJGj)ON{aSCtad%>P3rP==Do?N2el?23xn|_gQUs(a}GwHu&$C zmkD1y*^46bieG8DP~4SxR7@N0k{=X!`b=8+LpY6uYWPL8bZq&%y|!z`hp+PvkMA(^ z9#|UCp!sDvZ@+glGY2(Yk1fxS#CyYD=c47>ziiiNjKOk0cJf?waI)KzFR8-hFqZ0z zjo4Eeh^_9acRsvv#6_%tBEdVN<**U5dQTh^SQ2m!=m2nyzAjiq)f%S#;n4}^4AR_M zNhMWjR;IHj%b=u?K8lY&D+`65cZSb>pg_D#iHXjat!Ef%q+ngI^o3XGxTPW8aF`8n zgge>W$dv`{d8Le-sG4Ok>P@RcSfx~=j&)Tvv(+U&YW22m#7{h z?1g6~CL5rbHWVVk)1WLaS9n;$=w@J>?%PR1yP;Wb3}pkzn^4wp-s$u$HX%ko>BR1) zK~Nh_T{Chh2Qy|?ggf8VXNL$JQkQF?-^L+OWAf@wsIT~Po^~wrTbZcGWDngPf6|%m zioJ4VZLv+2+?LEXZJotb_5*xl0?Q8>>nNJ7z z*|R<}r?fuAfr_w{B-b{ZR64cWi_;;%Lp{jtyDV5pm#9wOBwx+VE#k8YR9fbl6dxB6 zwD2zY#3FwFkw#OC^;_M2LVEM05tDKKfTSKZM>ZBCYSga&buZ7+bFau-^F%ah0mD?Y zmbp2i6AdAvJZ}?!NbeP3YXfnx)Q;KiB4hjj{fOx-mHLlQWfP7D&pHbW1|yxR@iC)L znt@F$vv`#!vVwm!{Gp_0FJ*J2vJqeQ`f_oGL8@0@yw?+XZPC2EM6IxzJbv)$wYOw7 zVX4GPpLt^&5JUG5;@2hmM9-!XfjqH2*7S#7;Y~~3bHbbG?GWmbE97*x$+s5?mPjmO zmT^U8G8dm$`t?Q9T@;!Fadg!A2f)5tlF)p_iK#(UArPo4*`yU?058NT(rcpl(!L~? z0>fBja4E3+wq!CI7o`(Ya=I2tr<}{8P3>@+T>gtC;bq4Ntmtfy1-E1U6(bHqixh;B ziruXq%y_)VqMkHa<>03^DiA~3>6Px9mH65{NG9fm$;RFB>FJ|$@7a9mXq!zIjo5mK z-Hw}0mZc>5;UTS2RgVdWLA63aW}ApxSA=DJ4Tdim?}zEpAF6K_Lp77d*6qwW<(0{N zoSp`0t7gBCW-%GmBt+VA&jZ+m9pM4L(wrhfyhxOt*-Bz0kzb4-o=svS0q;9q5(4rtBHAI*>Z*I-m18ebnzh zzOnIZc=v4HhD`*)!E`7*>^)uBL+yEEw&sy$TC+BnS6_SI*NMs9;C%S&!wmM&NN71_ zs?!p7aJ9P&d2{*YR*fktyTgW@;H|!yY6*y?6{B5&p~~>%m(Qj)eUYp}C@2|Ih!-fQ z>rR~}zcdnE#!W5y-LFkU!S5FvPfS^vqC;z+FrZ#rGP%Rdnd$6lLgHOAF9Cc^HHmkw zGfA-Q$--j9AYTs}bHGkV_EEWp`h_uY6&|4_o%C4a$Occ9tt(S|$t z;^J3$*MTk|t18x)QPIg@>p}JXa*Sepv;p|5(h)eJz40sTj+RO@O`zQZ5O&U&bI*NA z)?IGDzGO4a_15?)+7yzn;6y@VTh3@Yh5%wMake z(~Y8q#(Z1w<|s-;U)CVm#TTv4k51fg(IHe=bI$Nb-o!qE8;7_q>F%iA#0o=(MR{n- zl8N>3<(j?V7dH>N3oHk2EEV{t7PGi;!W>U>NhAL_#^(`>WDj!ysl(U5e%qf4F_Tg_G9UUFU#>7{Lk$IZKjXDf zfZ3GKkw@l@94d80OYm1YGS9xa`1Q^ZwQ2kG+SH7I;{%5Qxw;JA~B~0Xg)aVZmBhe6|}{5F34v-Qb!gE z@kmjT;^nNrz{jYgluph8>^W|E(O17WRs|eRyaKW4PkReg=ki1H;y;Ir^xOgS44y2#y&co@Ryx?_nV{m z?a1~UHVEADy9y(2HMGz!;VQflr_#y(NXP9ZX%}^vVx_g!7q+OQzRjQt3zNdxdO+FI zN^^iO?n?`eK9NxTdTbJGgC@Z&sV8NcY;7^@#$Tj;n|N^PF9>qp6O;!&np>QC>v@It^j6qsFmgqLDG^5N z+tGo4B)1XOvzwCz-rf0&)M7dIXdhfu5XMfrL1wjXW_kITy%)F%oxMcuXz$Jg5! z`CTo@oiWtt#Id6@Bu?>n;~HL{lnGkF4`L>TGQgsci0Gx`5L@39_72 zYB7*4R-bT$IJtUNjFQ1t01Q>=8En{*!+^W3O+)CwUAx+0_>h^kk?&*j!i2r~u&nd> zW_J>`aNO6)V=+RrS&ZVB7|9Jo`hZdo5{Y(gW*5gqrN4j|;++#+1?tI=EDZI!-VV zmU(UBx zN@Y)jkrIH(Go!CW(GYjBC-5;b(^S4_9h`z=u2Fe&W96N**7%9FeR~caE{OxQSW4u? zg`X5B<k7h0@sJRQ-?4LIRA=nPTCS<_vRW*`3Byv*B-v-}4zWeU>U; zJtpP4-WG@CrMxGS_Z!`V4242M5hKOsAozT2gB!Q3xf^)Qpm(A|a9Qi+>PUS@li}ka z?JsGnxCVPCKvA+jW*bo~B2b~p)Iy$bb6?nz;lyOR>i(}pF1>n#1DV0G%%UX0{i;k( z1p%_zfryw~oVjM@%H_ge)yS~2Fe5p*$3T*%bE9?%9-_p&cfz8Rvqm(lVRY!K@4$#O z@z|7Ob@@W-ex)W%1b-N!Vo4-mo`janMQIUx^bXT5Ay<26JumX!Ete6XH}Pzw3#&qv zuhD5^?^%@tV#rlG>)S;vEC?fm`*zLg{MjrWFQ3=y5q{f4G5)$utQF?07#32*K!N~P ze#g>>fuK8K>7NAW!IZPRn}I5|Jqru-&&lFW6XKA)USZnqoy)^?S7W^G_d_XENU#Kd zyTPmeZnVHTF8jx?zNCMi@AHQp8kyORjYx?veEPXeWV6h4C8KV&qCGa*hHvS^yXjkj z{<4*>e8=M!;!zP{@)Jy*TqYH1dhoTdkRYeQ{sjqsg!p5?o+iG&cI73DM8om4XQd08 z5XkZwG*g=+9hfQgKFZHWnO&$@!NBR1-u~NCBmJpm2a~gq84D~ljdw9sFq>!k*%pmb zNPVOhFx5f&eI|Gr6L4mdnXbfcHp43lAiL$H_dVhyv2h&x9N6ur{8ZbG9+0QhcF4at zx2_Bqf!Ac3BiHUKwz<#i%9OC&?U%v(+aXe=o=`Qra@|hJ+;{%TqQX1p-Hx`lu56&VDfwHdA@L1pObnBz|$98gkQjYUm@g{HpU%A zEY)6#3OrLSoa&{Fkz9&6xj%v09m>}3oTsJASZ=(RM0zDuF46aUFBhk*prt3wTdG#j z1YqKw745!o5GxQ)ge>Ea)4iRaNW z6dZ4jITxt__8p0xfZe^6sP-E^_TdoNIX?-;^MTMN<{UNdw*t&<|0-(Mqx8l46TbA% z8`SeU?23hu@;G5wJy{=&5z$OxOAZZ)B#Q$F_5YjVBh}!Z0ioUu-m|Q@k8ABo@rATPwLHhQXMeHyHSC zPGvP7pqdVeh-HSucE2U&WawV9>MLn=fv^HJA{m~vOMKOT9LVC&#Ir>{+qtym&U?wO z(1hry*;IUt@#Wm(D&qSV5#MoR>??)vqFEbXnFG_!n+@tRcX#gdg9&&&jD(LWaF9fC zwJuB*_*`xw?2;|H{E^eO1NGaZue=LNbLbRP5W3EXpb8WJ_vi(xRC#jA(Igmn=v3AA zBT|vLMRJR@=_Egm@n4$pcJf&@5-Db3g;3x=&^Q6D+4y6^Ku=e`CRZ@(2oFne3l9}m zz3@1ua2Kgwe`)J1Ui++4Cq=P;CSnk=$aSTDPM1G1G|e{oimrqK)gL#$lnq{#Y< zSZ#c#Hejpzc8@e)-M*29W~K}HGpkdtt1QG=F?DN*0-MrIW`4_^-JG(hQ$o9Etw-#^2{qdm99W|B4>FOkFWwLO^n8qq=? zy2#gP%8=CZ7K^W9+24g!nt+v*&-KRJrWH<%RyxN_Q0VY?WCN)Z^o?WPJ?0jkXTn@7*E`mv&8KiRoh|7tYa_ z#9&Ecyd}B~zVEall!iGKML-W9`EjpY&4t2&4R11ZTsybQjlHAKr;0V#Oc&yK^_x^9 zrDx?aV@$6gly=^$$pEc>qbv|Mpn%vKDaj|i{NvgLT3f^TY^A#{Lj7rzkAL(@`PY5C zvR6wD?450Q?oYkS{g?xMe{yq@JCxl5ctS7C#vmdC$<92^_bvtZ8F9$9bESVoJez&5 zbpz939PxtJ=IV8tEE%fU?B3|x#>T~Z&g!*M*mw?A~D9mM{>JOt;Qgm#I{xBz}BL?ffCcN!FWdUKAPjjC%kYyw4sM#7JW zrP}P8;N)5Enle{19cStxF8pL=I$6_^aW!SJbT|SDR`SaUWhvJ?rgM#Pl~%?@BvTdy zlJ3H~Ck`;#Cxkve0>Qdllb2r$eGP4>VfeXhZYEdZshh5KA(fQaZ{|ZgQ86)@s||KB z6sj0veswa(QTm#5xAB^YH@|pCv_)yC~)bt>c``H@s zohsQ}GCO$I*sM@2kH6z98pH-%G5;WZL4&&A&KKS;wPWb{yi+7XNYkmHZ^EF@$y-Pi zUK{mEJYQ;&G{e!I+X33k6j(+T{ z0wh{mpjMqoMAnZgu*<(#=xkx#BHJ^0L$<5B+NjRMg=N3+c)`|9)xU3JZBGs{hVtGw z)_5B!_#o_kX8Yu#a>nVrJH?oeq5w6tVs!7%gd$xakEp z{yfM~oz1Cdf^ z$i4M)mEkQ?=v6=r-8Yj9#US+?v@yNv_XV#rGlk76Y<uX17$!rdN*r1qr#}nOF>1=HV;YfqZnw}(%?(VXf=x>SM0oS0K7_Qz#e2NYa zQM`EnG9gcLm+a%s5EcO!H0LOfW2BzJ*WU`oq~j;z@>k7_WD~M!rW@fCt9E_)VWp_>n#P9 zREK^EM~x|i&5N_;F4phl4c*`1UM5X_QH#hNgp|@gu-wh8x2GTLZiFYby%|#=Yfui? zOhE^cgogdG1(Wt3@TMRI&4ESy{MM~DwIw>~@pd(<3IWEp?~3H_$}<$5L0VI5xPC8M z4xGz27cM1XE&&Z9+>=T@7RWn&GNY!594_`4zhFo?)q%QO+sEKb)sJ(LxSdwoU(Hy# zYxdIFZxE|TQg|)mcFtD)&+0R|gKS^z&noq7LwjHw>*A$r4fE$4(%X-d3JnuUB%xlT z8mu|NDdIm^4TDjbkLU=IeR8Qs8n!{(7&r)vKW%l#2{&O-Ei*E! zb2mRz3La@zrV#B#ek0gjy=KSX4>sRh46;B&bIHw7`UZ?;4cp9D7;(-E=Dpmx$aR3i7X(!tRQM@J=} z_RHqFWE&|ThrX`-Y<m7VoYwa7Vg`0f$!V~cs3gbHR;@Nff1 z7In!$-h3MqNsqIF@dA;&=1+o#CWV2uHL>PueW$7!B^DA5mW8hYN?fM){R1mwa8(}a zzG3wOtCG|_HWik)Xnm_LlEsbn@OUuw=!Dtnwmn#tz*VD2xFi=pD8$xKog`z(# zNd1Y=&3AA0m}=+_n$PL9ml(k>{rvT1FpnYZ`U2FR8Hqz4yW=R5!o`>UWsnZeVSv$6 z9%9fZX3^>CR7G#``(uT|SH$t?>{VtYFB_Iw&)v6=^enzr!WHi*R*8 zsq3ULIWm%R;1J#YNsriWnepKqaO>qt&Fj$Txc5I(E5@d`?oOmQ>~!eZkS8i&N{=T{ zKleA%ZGz=CDZF7SIS&jo5WZw3cCQtm3hN7TuPSe#TdkxHW}onhSaHvA9P0u)n?>;) zX35+;LfXj7ac2d5+1^+Ip%)*jYUq*P3Nkfrgt~>4*#)(g_ylWIRkXjor;O6yt&||f^wLwE**YwAvEBHAX>~&A9 zH7Fv4IV?T)(xEmva(+(>sU(XDq)(N`OA*7nF*c>e`3j za&>hDsYds`NnMFJXWw}DVu($Y`nq^@iPzcl^oCw#`x^FRnC+JLZT|@Xz%O9>!w4!i zhaf;i@ow7u{AvRM_KmSDlYHi{=PWp6x`L^;Q=AH94sSE?n|g)w*-N&ugf-f7J-kvq z1SGgF-zw(^lD8i-L0LW}Op@|SQ8FnxH>(~D%$hoJJTTu^S{VEK%ok?6uW&3@Vo0HB>A?Z_h6%z#lw4ZZ?KM)*`y&35*B>8Z6+}91 zxm#n;XO?{)+Ts#@<#+vgIklJS8=`_3)XNF&kiKA%_={^HJXn7 zpi~M3Z7j^DjZJG!=vU>et|FGA9S@RwQVIYY$==+)haQrC9H4lJbDPMFx&?F% z7oyV?bFc?DoT08|O42epAZN`qTVZ3r{ck|z`4WzEC%3k;RsBsc!=3`k5gE7Jtu2P% zeDpeQ=6(?C9CTu9+& zzmV2M;gHLt{O;gM{pP)kpo&5e=}P@;bo=xw=RxWD@{Kof<9ur&sd=T3Y$zoQzo`k1 z9Y|T4(Efv2my^c3 z?8ZqAg;eqh7No}Qy>=`$+&BKTBKMzezpa^rqvJQ90>|xK#*C9hbK23Tse2uzlW}Rdz_CE@& z01+dH66oF@YY%%akjq1e&*{!+GVOm3qN=q9mo3h$y;05XBh7JPhWOem+U?ryT<1i=%cFkDFib_vC|^iYcyDGCLpH;5{J1z-I3Ts{c)Jk zp%D=yZe8<2LWZfr|D+T}1E#_@NWDPe6VJ@yCZKevzZN{#U{dTkv9i1+&hRKt3Ew7v z(H52!TzeNt1iq@Th?5DH*xe>YRMt7AEM#LlfWtHf!ILgb{F?N;ds{>OVH1X!RLOm~ z?Tt5z@pQhF!Jzpk2M2sPMUH7Zsm6UNi~r2s6Qc%Li3{YZDV{ML?FlbeY-7bZ% z-7P`$^bhe9OaY(WsTFXzujaHbq}|D*2#dhQIT@rVC@mA}x0>i}U1SAK++2OORy{MD zY;DA;BKLD1pU2mNk2Q#$p_i}uDA}Ii<>FqSm6m9Wx`Rj~dkNw)_aQ}K95DO)oo`3~ zqvwU9!;x2_qdU`QC{AKHgD-0{RQ~1y)Tc8@y7!fojwj}VmT^-kW_b-0LLNM}QGaG5 zWpq>j~ct%dB#a9uiz*Hkqc27`hwHenkDw6`5G1{vT(6++wHA5A_!p7ysW+pl@hs5E{d= z{WJbA_A@-&X1s)Ul!bGUJU!oX5w=U~&6iorG~3f>wErsUnJkV<(PQ)eY`LBeiRcgY zBS;k_7VZa&5pJFK9|LU&Hf%$oT%)xoTu_L3k?O}UdD(!!L<+Ams5M&Hiv<7819hhD z%SHJ5pWP$0W9u0 zmjqFek$L}jHYqVza^@e=#IMl*t>qYvYwZ6gr$0}5=Ki<{NF?r zqe=e1)$LC^i^cyR6$|gw5 zDKQ5)F}y#_Nn%*m-+Q7uTy_Va9M4uZK`PT?c)@|hx*#P`c6RpfzvPQ@5&o0W3c6#R zEKmnJ=iqYMK~*nGw7CJJIZ=_E#qQ2l#r|Fm6aRMC*SPQXjWrsXr zzwcgNO*#4DLjNXzux+1pk~9$=3}oEe-t#t1UXee2h86M7UNdiPPNB$veGadp~-N$Uf_T=NWa^mdn=$Ubl`Dk0slB1) zB!gMARZ2=f`qcB86}F>hC!VR>ap{MW*HBU)x(&X4az(mx!@4(Z1L_8Ul1Kiox7~zq z2sglM)Op&M?!uGfhlAFr6Ik#HotvVOOg~o+$75EEdJoBP8g=8_(@qgFx`YYA7p`DD_>H`K7aMMBrR5Qz`_a4NfY?*!Oe%n0RPxdk7nDF3Z= z`r8zpnMiy-)Hjd(I`=ItJ&g%zr6VYV4tqPLlj|sFwxSsv&;@9Haz6EY8_s;ccu>b- z{1`VedwMartFx={`*E zOlm5Rh2;n&-z%dg&O{M=Cl1ZE(VvRk=es29T`)YxyR;&&P^+cSMc(l8f^^z9wo`%- zh6!v;ff3YJM%@>@Xrd`yUV|hAr;s&0#=YFE5UShC1U>$X;+dE4T;gv!`Zm7yJ^CEV z?iDTW!)q{~OvlKkgOJ+@P9Imci8oa|<*Fl3`5*}o+pOK}uVpXt zC{K#tyZ#<7R|bF~zVE*SB~d%wq_2`15PzG55HBMOW<_PK_)sQt07tr%L^obv3HruYa5(BHs}~RB++ELSpN3xPW!2N@&i8`)S!IaXIP~&jh$pk zgR0z!QmFMv0rw*I6QQhV5w9RxDW%#*t-y?ofjiGReMgy@u!;A%i zxNQxMP1`YfnCFtbqU;K1&uWPEj_tb=J8BwPCC9N*)aq}9)NY8~$M^c~6a0NMBa-2` zjYXU`1e;2Yt-9Q&L;AhTvk(z*5JmHz(1!SkF#4@8Os{3Vz?+ox87kFOZ)a?V-IgR( z&#;{P`C)cLejyDGCbIbQ4dLCU*cwmf)k2ZhpP@#|KXoA1v%Zht`ueBpXrC|b+}e}I z#c(AJ*JwYlI|il;=(<;A6qy5}dxs(RnIVihU2y7&*c!%vVx<+vu7=DM$!^ExFs6C( z4uE&qxG+j`jqL9M51B{f;z|}_rcDLahz7APizB>%{9GT2w*I;v0?SKe0g;at4G zq(LdMm@jC{0I&(ydp6~?bcr4i%Wn;WemoGo`S-|3 zZ8q!DE*s{POAc78GP#M`QpQsXq)Q}`uUv`Tee9itBbJhm=yJH;lZ>ZT$3C_JW%v-| zc8+>c#E}_K=Mkwl+2x9-K-QxQb5B2LW!w^>pYZi$2}UFkk#Trh&=NQ$ZE2jJh9=bG zv6ZiVHZkkeDqC;3-(fLp>jH+z2#TnH(^)Z0;91h4#KST@G@R;iyVB^d4>F~4I(wH2 z0<;6rsI+b*0~{Zer8GlN_j~Df>QbE%?POO(DhC-Jge_7ba=;%K5LD0lfJgZ6%Xp( zeT}LQ*`=n6*UXk(onn8dMWS_z{ho_<=e#vw@$IGgnJbsKG@)R3xKy#haUZjNuBl_A ziQsBEF0coI3T)V*s`!W+L9MxWQJ)6-As;DiZ@nWp&TE#ZaN3-$m-J+}uNCJ6*!G!= z^J&^v@^jw^0mFU2u#=uq_X?;}oORfUsGjGMD7zP%%~M-j~8gpR@yon+YKih z6JhEOAX!J`9cH8CY%rKlS{dWPq`c$tX)u0_?$il^jp@fJ^JLi z2Fup}!h!7KV9p1-Ex1`<}T0L9iglPA{YQ4B~P9mIm|8Lvt`=hqXu`oWMk0|-(M1(JMv9-{r!|6NC zXX}->04SyI23s50x70A+c^kl$8*|F6W+P*xhPuB+m?)gbKswe7&}L1>?)V?k2D%|F z`kwZv-_BmkWwe-gir?@wcJx~R$BaM{LGXO_s&|lTRId?9>LZ~RYT-*6c)4>s(9Gjn z-W97OsWyR(FKwGIj%xJU(oH7dhcb8M*YUXhxOFi}e0X^`UX?XeCqXpAvQDjnja|l? z7d@qFnm`;=_2r8n^;=F0m{ucGfp52z{fp}c)l6H?_Yi zTv+(%+VMFEqa-h-;Ea>eM0}v%ObwcYY%-}C}}Yz9!xdU=|)`* zLRCTTUDWmu`18XV(#tz;v3iG*2}fvd>JN1G;mA2I_JM#9(_w1?}n@qj{eiTZ)Y~E9-&fX8Y z;-GnuD$ssAU;%gD|y^pRHy$HFwW~C9uMz`*`kt8*-)b{fVtL-6{fyf}cs74IP)ECALn`6p( z!t{G=o{KwC(ncRbOCHz+McQqrMFe@PV5d_J&JvW+UE4*G7U=wJ{}y@z-3ufjDeBgx3~u1`-iNH(Xf$ znv0}%Z|mPxc0J|4&mEg$vMmZkS$gDa#}9<6ODu9R*$RKse3|$;l{TgulY>n27`hSS zzgR&QX)j(E)&Hj20`CPx-lv18ZuF$Efe(YBIr+&WwRo-rCc*waQ_?j!!fgEUSyxG6 z_9cjS`QXUMux6Us`EkR;6GM?esgrlff9~P96OX>hc^eCqEjMQ4ZB*pIAbwz-rY4Ga zn$tNq=06eHkpC;Lp(j2OJ!+)R4R}Qsy&N45LhvCb7~^Zh7jYQOJc#^TCtNUsJsz2s z`NCe8KKTnh&!2+FuK_nE-?(}!KKgL!KT&I0W{_!~VS&=Kv+Yu!$?(Ydp6-x|!mT*2 z$Z(#qp9fwcWsX&8VM1?P{+Zt*6B>Kg|CyN&eq$W$V$=fciY?h4iegme-hS2>vfE=C zIbjYIJg>_+@{6)db2yqb`b=s$~ckq43=6M9d0g)=GbTFVM-I3jPk9K_R z6}zIg+HV3hSy1!`X`Z3hmV&`41vNRcZXF&&fCAMNHW$bsqW8G%{OZSZBjr!n49dhw z6&kv?Q$Df3RD)(FH9WSkS)4bwJpyb&O2+DMd$6gkS{=*%OjS8>ZBFUOQP*P0jdo|q z!gK^Hl4DM;%htOq5ZP040u5Goly_^q>^Se>v}*e%Fj}FQ`V-1G6wo{Y!o*HI)0+Gp z+4#&Us8T77uI%oc+=k=$1_EiZpOE~_U4Gpq4;}IBH#&O|Y3eEUlb!Zi?^wSX+?WsE z7%Jg@bz^M@Nh-8b|#FdIC>4UNmrKS;I-GCjf^XnSXqLLv+ZX}jWS0JjqXUQ zWX#CpT_cJ_;D@P6sW)`BYbLlbKc)hir@0U|w19|34%+N#1?g@&J!HeTOsUNT_Bvno zrEE#^*w!dAj*Q@;ivkRLRizkW&2?}UUsD={^@`P-S$SM;0v&hia`FEc_Ss61Kwbf{ zJcdAPZspK?@l}2YB4Wv#KBilYNKbocJ>Kl8VNL``x%zb0VV3fZ3^jFTTn@LT_`Z)1 zVB@HCM)FK!@G+O+HA;yoeLEfu^|VCt_lv{{SZvuxM(_Bd$zPSG(Z5t3K^h3l$?Qik zzY+p7v1igakd~Wx!<4%GgZE9%7T+j0iR|9`ib76$CJd=7x;Ps4n{i-QEMFX~7 z;PGATKFfVjrCC|!`uU~$ebHnKb{V7yWv!9d=yUnQdS9`xieO{Q9hE;dfIkNv&H6*= z8GgeWM{m(G^vMTmZC`G;f$r~2N;JN_pq1rJy8YM8ngV~(StM%hqxMKFL zqQY;zFY7TO3qC^-J?*2X-c|Aw(#MUdy>;cbdq%{r&b~nuO-B(4Qr#LvNbs^e$SSvQ zhG+1<1hy}qoZcl$m+9Xvb*p(Afi=%K0UNfom~|LCd?dveB8ymSr*Mdd>m&oro`K&G z4PJ0&r3uz+BEt$sI|N_xfMBiCZ2Em8LC@UP5EzfOdJpLvg;h=s@iL(01a+W%)t5Ua zw8h0{3pw<2BGw?kKHpxHJPc9fS4oC$4-Lov)|Wx}qssPY%K1tJPyXfi3_a59H?;6v zNooOt@4nHV&15*Iap62&cPde>8X)Agghb8g2hdjs1f8qi>UOK+T-~U3Jl`o8v?LH{ zDzddy$7c7k;WVJaXo;_l?=#ioJ{_njF`T~7I%{^Pz)Z!ZfGL3xm=34qGcfTd%x6KubUsS&Hi>s}q#N>n{A2!mQ_ ztXyxg@oI(!gT{X7Rh{#eZfwi}%gVvJV4_34fd#AY!ck$8*ph!pzEG$;>YhT4lyZ{p zWJ*}Lo?6(2%}|ZoX3|6)tWWASHdT6bFzJ^T8~QT?)Dr_s5!bWj8DyFPFyVIa{MfrX z1kukmBX2JD+-ZIPi)wrcnfmFHUg)!3CCT}Ii1JNVoU!D3=QIV&nMbcNuMSUwK?@ zMg7C^rZQy97Da*Ku){tI(Maop^=><0V89IfZ{jNm;k?b)-26??f%59??IpRIyBJAg zx@_AV=X=Z5Xmz1uAxDbBsCBy3!DcbJc_?TeF^vu>LUXKa(p}n#o_r!uZnzNq5p4OA znA6VUrn59lj8T;?)#$R>d}9f@!_eFAF5uAEf_CWQQhl-^3h3bkAucJ+z8(>;-2x#ZM79fN(^sEt^|yA=bSN-vJsiAQIeQ8 zh~+U^__vPwUz=DP^S7ek*ZLh>*pW22$q}9h#fZMabuG*kd??*t>AJe11o5ghS_31h zd*Y)F#moF#2X3Q@+>jv4ZR`%>XJiJJ1^y$PV9ERP_y+<06G{;4h_~r>v~_Wk?T>n1 zoKGJNTN1FRA23nU?4ir}WjofQw_ar8F=u}$m3?Qwn ztRR2MPApZeKg&B+{oUO7ag;v*f5jn$qJ2rp{}7=6l&NjAKQ;^xMj6v)#*B8E3nthafS>!LS&5Ei4Z;9>zQe&nSgjkq^4QS?a= zv8|`?8YUd6DwBdXj?`-KY6{^?&}ZO$OdJ;#S7gD|eX3jWK%K)jH~;?th2D#OnU)!Kk)m@FmOK8yA+mO4SDvML)bB1+VOz~WY;vAh}Wa#yN#L=M(DM&=w#pS3WE(|m-3BCQaK=Q7I1rBgl>67Vn*&ON1g9+i^ z@y?*_Y2ykhKB2E4Yg{30daR}MnlcSyByF$@RD0ALjh$L0n&5$W?|``(F6UF z7^oiUyDui!;f|EJvcTx}*MyQrTvv3(hql3*GMVU9UW&>}F_8lJENKfZ-i}Cb2WgG# zI*x-E=?8J%s04B|f^~Q`=|x`iL6i6N|AUpk9frJZGVI+I^5bigot(;TCAD(nd8~+Q zmEf769@hd}GR7cdL{t_0``X>T6Qvo7nsD-+jtJKt!=&9ZU@un8X@lcB;8zEX4SPD@ z49|pHQh(uQxStI8^4m5fdtJHX(5N>t+sH)!i3Sc-!}((X@uGi^yB6b{9sp>35*I0# z*?u9XJ8f6(T(eE!Xmo%&KRFEW3|LfiP5tz#M*rO{-DnPhfu=ME&U=k-nsGbeJNgXEpj}5)QGhr8{d1;GkH!x+@05RT;ZL92Oh5@>R&|7`;BATV&yJOOJLdK zHxE&+wVDi6o-f1z_Tww=q7rrJ3PL;T;GXW!G59UKKSTZgM8*(%&=CFE{oLVsFXexc zvA4f3BJpudNAGVgfCL;!KM6t|jsMe!%{PiTfL~)HhlPa&=*UD_UxnXn)ocBw&e6tf z3Gfp6UancI^d(-7Y93|MjA2@ZJ^Q0P)+JG^!mMHMm=-6z!`HI5@jZ&-KvS+X4}6!; z)w%ii^)tkArWiF*zs(M-~fG`q)3278~4F}juW zh$%mNu_0sX39*pZOwP`}oV<(FdpixqWA+=J7Z8g!*49!DV@PqB+@5^LN#hDIJ9@Vg z94?Sw(w{2sDZ9Q;_9&^;?H8ckQv`4I>u@xbgm0=(Eac$y#dh6L+7yPayuY+Mhn(=E z=-xvn;mzbyN6h*W;jT)+YAAWZtw-}tu1C)bHX4VlBRa{s#jc9ghs_`;b2C6-gmad8QJSrCuNS=E4ugV^1A}*le;DGTIi-lfNGLS~)l!=0Jl)X8ETVt!Fa= zo#<)SBKi5~4Ak6BotogvU%3L|Vzz(S5HvBOEWJ4gHO4vWQwetGodYI^+Nn@RX)Cs+ zFtw48_1o3^j?RDSQiA6yssV3R+tOU2-cW7Ta1eKKdf%fTm2VxM!}FO^6XRX7|RmJWHA7HvTPSJ zm-kg!n^tBnrTG^74!cWwB=hZpBozUynDG>AnK)KPb;#y!&u(aV>ha8K)EKq7I_$Vp zra|&fTfMr!1oIy6+Ch_ym_I-uj*H3u(yS?V0-Pc_1lFHkXHo{g_g56vDEVG(q)&)S z4xnLl2ubk4_}n~O7R?BUV@mIlcFu*X-E(X&)+VhMBnZl2^D#{v^GgA9s{y>ee$o%K z7Oq5sq1HDUDVc0|LGgFxY!}NPbx_cjI1i4FJcP^LT=;$p-Q=xboy9!R84*P{w(Qf* z)GBV4rClbbc7;7Ly%Xhaf#W@@678k)?+ae%6zS!ecCsI71s8bl!Ay>TDQJL@UOwUH?dJ_ zCbh8y*<71gi8)HwP0X}xUbi2?AIch_oW?2~&ow}NfTy)>kmZU*6RXsjDZi^l{s1z^ ze}5i0gWj=iYVLz<*TjSpgtE~d{Q7OxZ{xs+2dne7)^ef&8m>b$McNg?0yVN=Q?R3V z7VBX-O8qu^BQm}Y#+30T@R?Ugg(5R_`O23Y%{1r_E3GGor zFavr1I<~^g{jNW}@f_t^**?-UQ{4uzx3y^~!R_GR8_(EPXP>v_b;#`Wzy)tlvQroK zpgoTK3xnm$?ILfR<+0>FaJP}O2+je|<-28<1gjdscq-+RSF&pgn^m){C2IrahWVWh za^sDli13O<_t;ZGktNb-5`i#y9LW3y1kl>4jRLwpsgY}?k6C6CdxK5_54Wv*Zp znAyuUWw@Zkf{Q0F3!}I1)*wIOT@N&}6z+x_iLUHR!bJAf*FCl??WSgL#g8JB)(XUe zh}^od0lZ(HM5gm?F_X`L$G0s;=`X$CmalQy5B)8w_^8^8{PsU!SiGnpx_iZ{p4?-N zCCR~(XM-nW9ABDo#XL;9Iy>dVJc2D_Emd)uqmebR<}faGnjS72lepMQp-dHjs1m`! zoT(xRYSOQcOYQ;sL}0mJaSxl-ensg?b{GZ9utwoIBFHV?pkeH}Oty8)r&^5U1;5Gq zj|FBPH@*{&WfTfV?7R0sc3}*{!0Dr(Dj*fXPtQ(H3a!_^Z$QyaW;Nht49`_`Y{b(E zX>PVR_!_y=iRXA-^zcaXm1BF{Y*tSy%)Z}R?|qZQuF;I?dp@|5@LdccJomzk8x6Be z%XIfG{uzuKq~y;QtKnG#Y-L96nx)+2MRSJiajq5yx22Fbbj8G0Z`cTZa|T8{A>8F@ zvJX~FLAbRG)vmjQhekA;EwOiBvr z=y>m4=KuT6_&rMiB0DDswh5bq_|obd9V7wG@QL$kMI4wcZl$%BmR{oNXbQT&KW9&G zU!MD9f!Wxvfe&}CDegK}IGN5v`Mdp<2Qvx6!i)IhEYc(_`RQH#`<(mtblS0sa=$Pb z0G=8@ZJ!#=78?V645g|aW!NOb5wc_wesGW9Pes|p0%*3pEo_gq*)3&sWLhZo&8}RQ zDZ5*Q$vA&dg;v(V`H2}fMcnrRm&D3QJxm05su6%Drsmu(@Hu69?;~}m8?ex_Ep3=Y z;SV;}vM_Fgld_0nbie1qqkIGrt#6#WNFs|=Hdnd*&5y^UpdxL2!cx*@`j=7qQ%56h z{6?1vjb2|q94#C9)Unw2xr>-imn0A3VNbQ1L%?7e{j3Wf5^O8*IfIY_=6lE%AFyH$ zOaS@@-kI-{GSj}o5v(f_BeORe)2XD9F|BmNL2$CyJ^$Rax96pJQ%hpiwbHDw@xsi5 zUG=ZoJFN>#9aa*P-3*-%ltP^ZiwtD1_?ffkp2+cwl9C4N@f#PTs~KLp`AW|$YS4vG z3diX}20@Fs4tb3B_ZHZgr{?{K*$7rNm$2L-^Q9bwWt#c*%DzJS>t%=?NZ;gwWR$3w3zQ;@{obW1uHkVWR%L`>5|5j2@(Ws1Xv=n zD>z&99Rr_L3x?qt7-IuN!rofw9(L!L(`$m#n(wV2SH8UBs>Q0xB~Q7W;mPunwZl2z zP4_?U3@<^AnrgH{66tnJH=P|eG3ScMy(9fm^HpRyF?&_&`&ogXQ}d2>S`^5Wb0Hje zr7;i{JC$zl+XIBXU40o*4AteYtlZON`NxX3~E!PNq%<2_&?r2>WM6eHkp* zY{ki-`paJfd2a+;{RDq`a_z~7u(Cs2Rxy*Gv`H?94 zIEY#TrLJ%%j1gQW?>PL9?Xx9Es~XTLgn@nQSN&6MiK$B+uaVEf4Tsau`)Lw(ja@Ty zB$ZW^Vm==2HVl;KbWGc4C595sCb4!l9hDU*w4)f8pBd5{dd6Sg-%KB0@M4kXlPbIC zlnRM4iiy1wdpJ)LC|Js~cCgE=h+&$|*C3>z4R?a~f(~=7`POR6)4wiCtf4eMS4ete zqo3_l-e&X^%MjG;3n+96F${<@OV@ci*vtbBp51ftt=M(@@~k+`4- z#Vr>xY8z+DP(+9pC@OS4O&rk$}UCaM+O+JBH z2!K%>XhB8^A&U`52@Q#A!XKg~c$!E~XVfM-IeqLN#xdY2u*xw7_>_R~Y3obl+N;Mcm~z_B*&~34GO(Ks>Mj zmr9ii3g)v?nlh432H$?%5W1-!t~idk6OyRt-nEIqd%=NcHllGe&tdbEipippT)BJa ziw%Ak7YVHe+gGzJ@Po~z*N<}<4c#H4o_C1yRh9eS=llSfr(d_v6|EM?A_qFACG5F7 z>)k!JJ;vVKeqo}KRBrxm0c;yN!I2E4tJhT{R|N2R!arQfPK`m-K88F}o_ol;clDnJqS>4cOs9lL|-d)CUx4*!` zpU4-=Q=Yh-?wXH~a$?x%Y-kP=l;?MUk|N1#KQlsJSmF=pG3{qZu?xS%p9B3X^{`ui zWBu#%T*D_cQuSBWGM0>^n0~cid}PwxdxO6a*o#3ItgBJK^sX22-;h1PnG?z1C;WD` z!4F5WDxTxUhw*Rc_^&tq13A(LDQcoOg3+hnLlIdlx7>e^gp74E814J=P?Cimjob- z1qBfo07R4Jqoa|<08;K`kz&ET16StO%!g0#2psEJdjoRro?NgB1p5vh;yUX>S34sF zaKKBbCVQOCEcn86TdPsc2X5H?A1kH;78Zuj18BZ3H3doTyz34C2DRnt5UO!qG5+v2 zKlpgzCGs7cui<`qSc6~@&_jW*6Fo>c1wD06)+P4(nF!khTVX4Mp$LQe1YgU|Ak=85KkQ8mRIyT+Ya984T&@$ZX}Qq!0c+{+nVlqFA&o#1c*8zA;_v~!(3MRV0? zAzA%*ZS?I3&zpUJ_CvXHTT@xq@s0UohC(sIgAHc%G{ECS89|IwsHVq5$Of?}G+%FM z(i8p7i9o4Z0d}nRY&H%&ks^csrG2&>33B?G&elpbyZxDjzB$(1D3=VG7RU75Dw$Mt zpl3}I*0AMO*5EK|nL4J@K7wrk&91BwAu@KfPP(=8xXc-e_v0V~D?zh}P&Q<2pVDGt z7Fj}0q%jmneHu8M=BEr872)^=m4lq`1J~S!>sjj1=WBV5O;#{m8Kjxvo;~@4A&tkA zDP?)nT`F>J^9&x(E*6HkUb&ONe z_jaecE+<$Me+Gje6jFOlW7*e>r9BTu|J>TtalY-TSKp5PUG}&DhuhsMMYZ0-`go3} z?0E`PJ*JMj%_U0tHr5OB&3Sgx@g;p27%DMs`9c=)a=w|8zCW6SQdpvzsDV>vbI=T9 zbba_De)Ywr_{O-Fm2})|7O{=i?I>}YvNsXsmAlE6s@1%#vL%M4$=+jUWj4=_UK$oH zPDjf2IUa{bl|6{=vrXin9)W~SqY=ZuOe=D*&F=L5U%za6{(PvD|6^%cnXMdM*?tK@ zZgoB$`Vte<)8gWkmUsF6P>1u$on<6H8hH!h421oRYu9`kxDqCNSzp9?Z{-l^lzS}N zdu}@XiC>R2p?G+ROkS@7>k9(5v&#dtdk-HBgs+XD7TZz1=n3M0Yy< zWok+`e1}%RBF=^bEovg$6&(8&5JauHS6Gt5e}ri38i)lM$X!ry`1vdcY$l%%Zq5j4 zyu^Un2WK)e^k$2i)+tMB-TIms5%m{MD?JXP%YD-iF1lqi3oh;&fM|7k(ftAVQ6%_6 z>cf8WJ-{aE7;3LdI@GtzoV-1Z&A^$6ZKZfF_x7Y--ZHWB!$H7Nq^hbXwx6k{2fk%j zFl63Ep?Ze@>b#b0H6T1GtcHBG7KfyqV9(o}%te0G^ioOPL}GcYWy4Cf&j-LR+!KB?4A@(|+fM3;Y(Q+oq_E~&pnXN*AQRBU~+cAa&wXuIu5{gf_o15@2 z$3c42S}$|m(S?~MthgW0OO_7#wyIP$Xu)(U0*ae6K^CmV#y=$demOZx#iw?UE#5MW z=(;wlJ1U&LB3#p?qp~n{)ji64tCktu&rlw`vkB0kUf+@I8n>@ts?T%FxSlzfgTnJe z4{o8Pq?0%g^JFNR0DDxd>RedB{div|v3BkI0Xnx{n&U!{YiKc9N5@34w-T&IsV%UK zl~GneimBXHA9qBO{zqKTlbbU-HI4u@1Q1h1B^J9n?)Fq5Np==SFlA{Z=(sOFOprW& z&7A`AuF`7L13z!vA^%SED;^QgO^K`RhB?%5GImaZAz=R$+8Boz!p5wOtyUbpYosfw zsr#+#d08DdQH4Wu7-fG~@a3kG7g)vm-pAkPFt0j>#gK8YJ~mK!9Up~@*)g44^yybHS}s*iV{x+l+9Nc+Zc1$1Z!^kQf+$) z^UCV_eqJKwgD)}1y4sphw(4H;-tPq}3l)5}fbgg@OrC7gs!VozDwryZy1LO0EDtlU zafIN|02*;g#2oIi=HI{%$nN?;tkz@9lhaCO`OniVIgza}?i^nJ8>gm?vbyvRVU4!%2rjaa3xpE^)<*^tLFR&hxbJuGe5PlS~|GKJ^Re~ zV~EAxo7|Rr{6xVyu9P3K?yN2jFW8>-}_JQ@BpsI|GjRDs*N)>W) za=Krh?u{ohJJ%H=K;(dl3hnOkwRMo*gJp5ZU#R(KHwh5RhDN0@a?1f~X3s{}znotI zek4a!zxS83H1K3@v$EY|)jDHtb1(Ku0d#Abb8?$%`J^;W@VY{Xi1Gw!A&hayF;r8O zPNZPPs(T!QVn?+>4f84e+wzfvH4`k=1$I6f5^q4RqeZvePhy1TqMmuWs=)^5($mf> zTkpp66$KEdj-JaEchGRS*eCb32tNy!nR^Z8A)5=2XvaHp+*rJc&Ng{&I&b1`udKE5 zr`m0Dtt_wT4BX<)U^9LU(D8?`gY&-ds~KWC1Wl-6n(!e6!sXV@R}NJtZXedOgBrRt z?@J3+hp~KOwZf$`26?wxPl|8oAY+WuZSS-&zv2AIkCb{Z?I5AI_D!*Aj3(aHO0`qw z`r-j>E#6d^LmZ;qvRr5CT)L2>5;~r+;gk>H?;L`*VlLzLW8zmwgrYQ>7Q{QfM2EG$ z)iDUQuvECCiivvx{`sxqoPvUc^3xd;7VOb|S^}ECr@MbO{zbbWwM=ptYHRqM0ZY<( z`Rk5*48mRCoH?$d?CZ~9ciLNZ19`@7Q&rHVc6hMBEC_>cDsvH50Od>O%BVY?jySYe z6(ortHWCi?VubJ$_E#U&)W#m2BU zz_yIqNFG6X3(8v4%D}Cv)lWu7r(T`UKyWyKBOtwy#wTLbFEVr_3U;?79mjZQ+hMe< z5>#2g*hjA|(#3C^)}g4Elck6E#agVU#FN~@w5fl4%nWZgW~t*3v%vdV2V!Myb(nGVl78CoEo7r0@2k<3SUidis;C zJ(7mLSp|K4M_w<1(W9C64@;5DPI5$uY3Y9^W&i9b_qgL`eMPmS_Yr-IyYbhp?z5dR zfm>z`&69)>8M(2WWV6jxt9~6>Wr%PPK3x7q#9m*4c)M~^Syj_lq~n^84@0ax^{LgC zepQisd-Ug*h6KuQ6!-imAQf=ucZ{eu5HNlS2E8dv8!56at+pZk6v#zc{lFq|`{1R* z?~AB;F7q6zaN?sYeC~EcBpMq}QwVm;NIs;?mAF_t-nQ*NJpg3cXP!AvRYXM`)01H5 zi_y@$(3^_f>$``M)AKSMscJ?9rJ@om^5xVhoaaFCak|UznkVA-+xtmt%%!SnFeHHQ zrT2ido_!m&L5zni4O8?75-St6AAq=`!5!O6HGECT=J4ru@WmGCA@nDvR zbnq`n+>fZl(0YsWZ}QVU-nG?hW<_yKRvO|F)|GDBsm*yLCp;-v6R6yp z1p!b7qJ`sYl#u*|0lk(UOu@|!8_`iG)b#Y%dU9p%)X}2nWc&~1FAybk2~)+Po$ad7emFi3YhQ>dlM54#G*&nURuE{N$C6<($qxtFEfGVnpi-xd8{-oY z-_G>uYKu5Gi4nWAgTg(&$xpyLNLcuu&a;fJDCTKB{)2=5Gf(<5{8s#qje;dkIwM8$ zlkfYOt>Ma;$=KVQ+}tZcoP3+Nc`2vT_-V%{bqyiz{b%WK9CPa_z4t7MwVESMZDW|V zYN6w+%`3Oc0M+dXjB@AG;WHw{NeAmZ`Us_^Rw`4ymxU+#)QW)S!%_|YeSFUg_Ipyu3CUnlQ>g;^2C-|CDZ<95FCC2L#8 z`YxN1o#t}6mj92D{`b!FKB}8n3hHQ{-)hmGj?d5(GF7vVJV9l~z)fbPZ@}_HTNsxg z%_w~}Eg-GUa|iUDa%i>U_Iwi&>ah z3wE4!`M~z}r1K^Dj=?E7Ch?B|7R>R@fs(}p!twDO+ixEw!bT`$4at`?^7hV^m?zbe z*Rc>WROKlRP3}~CPa8(SNgl6s9%pESYm+D_MI4u;R)(v0ZUiqgq$RKK%-quA)Vo;e zMkq%&%CNul?ImCvFsE1eYMUQ@Z`BbCjyLJ+A<9zjq_!leu(nbUR#DM9Rr?vvmqx;< znk#-ajTdU6fbA-d7O%j{9%nvWUOyc!iQ?q7sO!0Fx6{rPBgsELM>OS0T$JO41y4yO zu6Gzwq*;;|Q;hOEF>s*mpH(!MaY}ThHfEkQ)WpC_~Xw0H6C1CVAo#%NwG) zw-7JaVv9JWvDi^pU_vY=d2n`%TYo5YPsu4dsJK|i6Rs`2yuKvjnAaUX zeFjfcdBK$JB`#grDK=X~7ENQAHa^Y$2xCi$m?6Qot!u`O8pRueLvHFe+@nB?Nq%Ex zaV`cg2}k1UCQT&5g9_PuxT732U+)eL7|jWr{M1y&)SH@0u2%TTf@fUTq|by@eipRY zav>NGcNj;L0S4U+vh0yNYiX;$cmlq>0)S(QQ}sm*^5AbS003TZd4raE7H519I9le1pk3pb;YH9B=iT=OYaY=VT>03SrRj^OD0HA{P0H?CPDMr_tiodUKuCt_*6JuTYosr?3 zWRRdXPBdYcbE#Ny@yf&pL1l%P+E^80GLn6Fw;iY}aJwIraEwbNw|TM_6a(CiwwU#1!K$0~J?lU5nxv?6!JDD5fOV z*Il|gGg!+9-)mhBVKi0xxtNwLN-Ym7V@4h4D1~; z-94RQy%e2C(j1&2IEN9|rhFr3Zw~orn!F0*jXHPIt-JYqR`Wd-KpRd7fG6O4 zzbx25rSZ&%`vcV#7zM$hAFP(}d6V}s#ySNb@@U{m!?X1F7(@RA3w_Qvp2$<{$^ReL z-ZDC_E$I@pEn5s0v-B)xX117_nZY7UDP~#B%*@Qp%*>QxOffS|R=uj8s&A%$^jiHV z*S$$A^WHcSaU%BKQS-Y(&?2q=NA~^|>Vx4F^QcJ7=BP)^zf7)vbT&H@+u7-C$H4yC zh)GA9rlPu*>8DsCU*cXOS}jv%- zSHXlZc~kc&QR)_Eh=vJy$6pjYyykF5G~iM=9Q-H-Nuu!O&F^?sRjfFb#kQgNidSvL zNdS^S;u~WNtYsM17l_?iGt0PWML!s5NNP(sW5q$YGR{c@`^1-;8|^^BDKu(oTs$BS z<8xGsi+1L4f5vvoJ{7Qadi{+6mtA{nxfNe{>7lTrgC>e8&b77>X+sMyxyAxK!)Sn2 zG+$2Yqjmm7`uAMV@M=izg!lgTN7>yRE6-aV?Lc}tqaudM?SMxY3`%X-rXW-v?0EAF z5@M!zPI!KXZZey?GzRv`sj@&fhRmD9SwFK#WR{9j^ZXKsQhIK5wl#9?*Cmh1~CRH$eZPTFJ4 zGe~rYB(lAFMzUU}n{%l}(!=EI%{c=<(B*(>kK-oX`=+Yuzf9r_e-M$tkF-$8YPu?m zSN0Avm1*p?wjSk^>{}+XwgeC(LTY?apTQZSW6HX;rzYiWZykkun!YB($Mr@giv}QP zUf?n^NlQydo4l6&-Hr3%`g2Jkm7YIn5CQ{0 zDLJl9>@fjv!C}KCBY3#803d*}fxJGpMhUU)ZT7zB@;$EqL|aciQ_%!hWEyF7b4C&S zS;i1ej_!0<+XpAwD2Ivk=?PVk?`9*lw*divY<)kvi^R2 zI|;B&A~oWlnLZ)+;%ITA0@X3a?H@G<_D6E=vh^)>%Q#7n!OUScBKis#;0$wM?afx3FLG2dSQqEd+-9n8ZQIXRbm)bfthdf;k@ z>0cGWc&5g;H|M%J~=VH7vBZ5A6wZd_btQ+`Q)KH`Z%gI-y7D5?{RJ=~%_Zz$5Hc z#maRgJlB|qpdjTIz*6V=!!>TXoxZr8 zhds(>AymJz$geU40)16(Uw(RX-sYG0yZNuk9Y4<>$aeZPGE^7?gUUz+mDmB)j{4W{ zpJH#8ci;LRhfltETqi5>uMc-W@BeOO5>+dS8ZCfaKgcAaF~aOy4ad%(nx)i&MkVC^ z7tG_|8y)|tTXbN}Y@T`>WjUu?Sa)^MDR#CoAZyzSI>A6=7&0RlV%c>KiNEXC;RD8Z zs%f@Qa`1$AbH-7FY9p=c>S#qNlc#0EmKNc!DXk9s@>8qmZ;v;xgv~*DA+SUoKTbaO zwgiaa%d45>^(`#F{rv22yn!1Xi~zrv5P+}<8*M?Y5GyDd8h__uWwpUx0Z>#ou)a#Y zOj^KA_3QAkhU_fWZ2OJCCk>x(YjEu^vc{W9ve-9 zjfgKgtJE0Y8gN!kJ?m%9n5sRx`?fN|6x)vFr&^T**iqEPY#L}3=1#P9tG2ll2pye! zkilKnc%h)4X^2BWdS$6UUZk)-V3iPzbtq;sz^?;NGG`kaz$RHt*w(7LV9W{rNcth6 zKX1;KX4Y(HA&!n`jaR~U4Y_Y-yImwInqsoY6E#bH>3cu^to?!3s<4SZ&-F6pED(2u0TUf8x(A&GBsz9kyqbrFXfv z>>&9ho$dGm?tH5;Z@-ePB5=vA1h9v=olV_G(x`)U~ruhJ#e;FxMlA!q(YWoyX#c!asb44u?LR8F5waVE4T@ibBci zlz82zWU+kXhRO8)y}|E)*a?-q*#Ix9*V8unfvq`UzPK4Cc>va;x$06L+?0uvJl^CR zQ>UUV`Q}(5K5&s_dsMrg4r33FvlC&=#io49kUEe?uB4Wt*2z_` zLzv-sKD2I7IONSP!1KPRs7hWx)K+QmOw3e2E;ZwE$-_2fognidf@=-O5LI-0Q@J|_<3NB z$ztEYhR5rta5Rz@)KPVbB~s#n^Kt9nh{m|I#GnJhr z8mf_=Lz&84P5up0{b=t0y~%~{J*2$Uium=hYsKl66)cQE5m8gmCZa|s_9M<tCd(xDIh$i0dSpvEpv1Qn4YZHj!lJpRc^A)xB8GAqqyStrn8lY}Ibw zZiy{i3p=-;7NmGQZrFj%k{qLdu*FgZU4HT#gHY`wErW|Mz8^?>s z3$gj}JEa7EfBz}BxMgwu&Y`TFJQz{kaoafJ8BS$|%V6`SaSj!Lg5!`?chXsuDf7%! z$ixka=hl;{tGe>1$yl9p)o5!r#)j2lb3$$^!lnzqkDejf%nNgwWjv%=98gX>chl#? zw2t|E>p)4@zjF&T@iu;;3Hx^YmLT)K1&RP~qDP07ey)Th!RW5Qn%JCCIGfz2U|Jm~ zBU2Ox3`Oxh(p$ft-*btWa~qMX5kR3n6Zy0az3XQOSv)iD*G4%JC-St6jE`!jxE?j? z4TS-W?BWg=vj!bjQ35xoSm%-=Wu&m!4L}_N_qUC5T7xRF(eP>4FS}T|wv+jxOj-mN z^$m1qi-9*(G(J!d7XW_ZC%T-3pFL4JG4HsbvTU6Q132>O248MEHY(VJ2QV%jr(dtF z|4rGaDP6NAGuRY0d9fFnw;+^?*egG2#X$8G9!z9a^~{<;?J|05XtHn}r6~cu(XMMQ zW;X{o(bX}G&dkpIR8wQ8El4+eyQjdpJqrg6a`&gZj#^XdHNld?X&KoV237zV(^VvM zzkG2a{+#-q?X5al{bIiyM>A`O4MUwPzR-!-nTG#|EY*rPH!*Hf|KKGzgEEXt<~X1{Q%>#Hd=M^;kn2K4=1??pX~L3}9eP zQA!Wx2p*xa+;&cp#7G@tNlTNI?6KH*#V=t$yDr9j6PeO@=YbMoqd`JMnJg2I6x^^j z`J#AUDkGur^3XZ`OSf~rsnqpz6Zp+sY*U1LveP)qM+FtO6it#PGqS65K z9;vS1O7`$f@_&Q4)s)YQYO>{weks$1g(+dLPIL^Hjc4zwX=}^}ggO-_Yoh1aH+_5E zISYQv-hJ}sPZOH`Y^yBN#^k6ihO<}|5u_#Y>sG_p_Ib^d(hY$&oa*W8$y zt%gQk=C(i&q|t{BM=T@_mr$_q$jdWP?jLxGI%lD@ii65*8M;8wADUv#NXHzYRifdk z<~{BK$xX8T9Lhz_cv*>a@IAZ?f``-k1M$+uL)Dls#USA@x% zEb|eO{`JmA{jyM4oIq)MfT51=RP?fH){<4nS)grpR@&wgo-T5TB1$16IcK>j53H;- z++7EHSL9L51m<}1TB!FB_#veOV9%@$J0npl=!1=3)%ksIxA~r8*@#lc+}{Ot+K|sz zv7<&PfzA97T&y{g$Z^_ym!&YS1pe)&>~3voc?Asp1uFEKT!D5UKhOCYX4?@-7#gvx z-B@$0JMjuk(4QSE1V{Vazj_#qC$4&P3VE}FAry$}-j{PN@O_30#VVZ?PKl<;np|5u zzk(F50htHRZ_EGk*eOZ5rgyU(Yo!dV4TCkwaEs3{UwPb9ILlhc+vy_4o@y@iKk1!G zHvLbJtya+u0nBfj;$Z23K*v{BFFq|{dgq+@P!}-6#b#2m^x|g83gz1^xv=tWDInh0 z3^$F_qd{RR=kYdHE$MTh(hK22z`dEEw^J@QxbHE!H7;$W;bVw`<=a#mo55q&Vo#M@ zmg_#;a2*rfJ_HI8t;R#V}p9&Cwa4nzx?*bMZJ3@x`aN9CS+U*#TUZJ1J$-O^CV<%%Ex(a6?9nMI zzZF9?d$LCwqL0QfiXpESl&Fgi@@~H5e<{wg16TO&*QLfk;Hx#hq13o@x|>UNIW1~j z6xdHNrzqt~DGiGTglND(W;W)13_Gch`Seq#x0cIDWW?S6ZtClwh7StGPxd15f0fI` z9r7LV<2ZU{ZX(h}M!oy8se@{vU(wyZn`MP9|8?)w&`||B`a)b0yZM^ zpSB1MpQ!iJP382r{BX$fhGMlp<+{z*-7;m|`_@P3CWHCoSH7R}$`4`+iC}2TuL9Pxjmh#yqA? z@Pxbeh1JDXudZh_&Q-;JHUG0T+cYQXAeuo&!WFJHRt9jIFhJR)WDU82BAj!ZaJ6~l zHGN~RQeVsCb8BaMf=Ub6&E&QEcFfFGs zdL!vLCy_=!ptN~4nOs03x?ToiV2C{nJ)1|iTxWU2^jEtRCwLK{_RQqjlQ!i);q`=8 zV0b;2BI^~;dRL%dO@oEn6w%UDto@o3Jm`zq5&`*TMPPiAnnn$XEMTp^Q2QOuD{D1t zUkD?Y-HSl?NgGie^^x2f&#Ib@y{B=*R+#-c^IfGYA4P-DeZ1hAsVtF~O|>wY%e7Xe zjCj+LI)+s!eLNP0bfWnJ@K6V#`#<+zADgfqv^W*BZ|csCdYMxvZEj3}AaZ7a`)oB2 z#FCD|7B`ZtzUW{Utt#>=QPR4kqse*lC>9D;r@8ICc0vouhOD8bSZO+y}*B!6S4P3vHOtglhr1XJ6 zbz?em#rqY3k+`qP3|J>AJr)mE68iqmt9NLrfP$oUYj`4K{1$N*KsH{+!|K zg2qTxkvbzxE^22u#_P4|o-|?e%Z3glabnx5@9{=L9J*g~3*z3RNYL#6wtlcEgmfHV zJDBUDLNiO1I(E-AZt0M#G}uK}0OH$76KRmMXSMqj`JAsB#ujlc%9updE+lfBlJUsx;-t*VDA|qU8YF59*=7Uybb3v z;RC=?2p@aa9 zw>f1l@~ve@2So_`pG*OIlcCnrfL}^EOX8`kg`UcaFSgrJr~_E8W(*0m`#z+sgVNdS zgl{WO)?_N>2^31iE=Pc%!+Qdbv}L6nMNQA0c*(u0O#8Vd!lmO%_2qc5dW0L}|1VcS ztoPB6|8yh)m^v88rqCvCffo@6!_yQSVw5_|b^pa|DB;QfuNu7T)1ub+5Am#Kub;R% zt`lWT`o>m|64p5}xAl^}=0gX7+w^*}~K*$t6;1%4WotLl3( zPEJlWzKdu?Asrzh{YU3Vj!i#5xmxN0^ER=gk`B3~l$Fgz9L{ct&or64pss&@Pr-nhcQfK-5b6|6` zTuP%P9E(v8x-X7P#ElQzM7sqaM0M=Q4Pbs7klj<3j(VBLDrG z>Ej*%e?+i56{`)Q4HPhbF%KBmQ&S*M2wsO+ylk);{BfK!|RL^J1u ziM0n)Gspw`3oWW6dxzR#qA;4;;nz9){jhqF17>rV>;R$sIo^H-zTMS`ai9Q zyv6!~wCDH}6C5o{wde^HKo0>ok}^=ek{ z&0F{O3AO;-c{dP8r9U%T?8Y71`t{;*Yk3m*uX}5Rs$xn#t|z}HQF!7Bngho&Ndq8n zx|b2Tcaw~+u74{Tp6J7EJ2$`N3YJAKPs`^nATF20FE6ikzcHM5xajqDRJ$8f9i=Xs z7G@>fi`1}}_oxLyG~4ZpKHH~N2j#r3u6}38l`a~2#B1+;3;xRqo>gC_E2i8n8^V)3 z)w3qP1G6s}n!7jO5bDW%>&utga|T>kIA$rTo)XU zOy>dBp{rttf$Z=SR*plyqKMR=%FW3)XC>58kuLL5XF}PuS<~Y9018EC5{MJg8r!J> zt2K#EFW<7~2yB*oGN(Y;TN>cetpYh-)!F{<$22in5X+xF3D6S0^%q<&+*lVIe(yj+ zBW*`+Fd~i(o$qk@<}VBu>OVtjMSu_2`kAjAUg;MXIPGIbvVDGQzC2^*!k9e~xC+fG zcI0heh6SO2_<#TRLw}mMj}{#z{!7if=wH6RRdil;IAeszn|~4#&^0SC0t6Mdej@yB zm#@y40fN4&Wdoz5rP=fm*`B>QSG2i;y^;UM0$8;5hf;DU&K2eV>F*bgja8iW!w5I$ z$Yy7A?>tO8SR_QE}CWl#FR&1mp`QXneIUd!QfZ15F z@#)V?u_G~U>a~oK2Y#*F@pqF9Qfa9^GUFOvK4Z?A-(P6{bn|-~^s{@*7ync$J%ONN zcSER@dK?9n!?*;hq7D=cFfV`C2)ma#v&Y;j4BG)V(x$^ikbWZ#s5q-(To5Zz{vug! zO(W3>NV^O_Lb3+aI3YRWX~T4Wd^0Dw9_nS)c16aIonZ4(5J4LKim$IHz8VIjhIuo# zVb*dabZ_*=<^WT}GgoRyc^F)S;-FBZ{_1@?I6XE%mqPO##P)bV&gHAiHVY-gd zGb?CgAa$MJV{AK!GWt0=kAGa>-C>Z%GB_e+Xn7<-aS>90=?5-G&Hl#NZ>)j_oU!7+ z{t(^Z5Gf@G@~+0z+Th$wiRJtVxztfgcIE(0q;*Q{c$vy>^sSSKyE-IWY}yRvOUdyK zvn^zQSzGL|K&c6@!ptORQV|op#2_2zkPIQF0%d8~N&C9*GaY?yJwkouImc~;ED%}2RxTAui0`BMI3to%62QeA zjvUZ}uCEjjfg;T&HCM%lO?vt>*AgyG4Lnz~fzlb;oI>K~=chZvm5UG@0ChdnwDCU( zWYOG|h3!m{-YnZcV?5+#B706nRp@yS&PKJ@<-$dU#Y2NKrRaL)!{n`#~A18vLVH_ip_(#27lXj^}&zt`XF!Qaay`?AwdSyHa zeVmbrNm6Tm<293jSozVr!fjbiK(S-2~roOXn;Yn?!Z>MEzw#+q5)wUz0UX zD?H1QRj0{fYaLMiWC{Vk)r?xnwThscN^jW4{g{Q8W<;wMA!5s$&&921@?LdktvR9B z+B2u>N!ym8MW|4Q1kk!Jy&~?HAv8tCbDePoI}HC~QE>u90u;eeowE|Wid(V$ad9mN z#Nz3884)+O_5=YlGj)2YgZ@sV0E$DlJHhzm2!6?)zHdtaugcIy&RwkQZLM0g{RMR0 z^L+QnC>~q`?#2)`v)L82HhA0}$86rK8SW+M(WlCC#n4bMig3rR&T9f%vPe#EG~#SL zqs>nXv;x+P0u;VU!x@-GoaL$?(?l|AihPEQyd=!8x8L0hvWz%p=ybpPRvb0 zdS~d7whje7<;d}BIhLgzTz0t6Ic}dtajHmS zb;+Fy(qeL#hbrgy-Qp^z)@R7%jTR=oFW5WJNlv;T7U`|Do51|NHvb(@(J(MD=rhs% z{r%hR{2-tZr*njYx*C*rJ~qKRY$4&{Buq@T*=h>TghoG&w6uPi#VA#B2E#nNH))xX-lUX-Ut;~(!ARwRzVTF zSlmw989yt!&Wy~P?}YG632=nBHjrw@A{^zyZkzq+y=HV$d zeaQ?67~luu{xeBYklzc*rTFe`#^4K1S*~>F%Er~m2`^QCKI92dP%@emt3jeW@V|GN z6J{C6`OqTp{T}4lr+X>%8gr_} zS8SO#yXuoqQ8(nrMuaAhjXfS83LMLtM@D>YdXu88{?!p*RsmNH=SJWGxc~jx>63u3 zNK}OOnL_va@Mtq1;7tzAf&TwZrNBq8V-h}Tf9F;orV>3?Z}qqvKc=S5@2c;PdaX7s zJfhpa{=5jJ%e171oXOkdMQPAKQcv6HsxS+8pX{IMftb6%^o?}>Wcj{TD*S5ePaJRvwI(im*rJ=%Yl-D zt3@rfhrj9Qt!`TBuYl8Q-GA*gNK4?ch`Y!%$&stL3Tozj*J*nBDAPZX_|Lo$Y@nnP z%76XWzx!XW?{tuWdEEc&^zWnKhe*L3iX*yzJ{|nv^R*e~Kl04~_#zkje_f=0e#$$Z z-7###Uus{HRBu{JD31`|;_APC%=*rfo-(lhHW(j?|8qXwrS$5?mFC89cD(6w`3mtO zeti}xvMU0dd$(@;e$oBHFUOVZgf!T32S_Fq?tIpR5=Nxw(s$;+cS)tA*(j6 z^Y@*(_zd$K^&h|aaVTX5)Rgx1{5`pr3apBlb1_{20NgK>9;yQ zP6 z-R^0(pKusiC_~rfCV+Sx39C{owU(73&GBN%0-{4ZN^C6O!t zr^Udg-ZO5)pkuMvVkQY*pf-C`?bAmVt#3KJw-#okSDvJpCZYkz}`?ZVo|GEJ1v90d^JV4pdL0s}}K%E{GWe z2S!WK?ytdGL8b~P&n{dM>tY_dYiPD|RV=hn&PAyzx_`cI=6SYTt|}{Tx+c~rD=NZK zQIRKDGPlhD;?Q?LJOsu&-aM?T|D5w;+H(iF5C`P&s&GdcY`2E6Fbvy7pnW-T&R^Nn zKb~41ig4f7=B`eT`c?YT(1kTfsM&w*FYCh2AmJ_Io2lZeiI6qW3OcLt*!Qz&=IkPb zSj1(ra;CU~iQ;(kqb3)1G?)!J?bB~?R-5g5YXVyD3JEyyI3s!auB4tjWI6l24mDdq zYcj<6wk%iPPD*+IAM5tJ;NC>n9cSRNSfgf?c2X7Z~;S>$Ng%k;jkr_1Jjm%@6wz!=}u)GQAn z@39V=yN)mn0o3kRn5?=z;7vUnI@|o+d+>%e52a~ZlAB8T~us-`{GEk4IWX|G&z-9KIbm!)r2^&%mTeqr zD0fBRES_VHq(geGPfUU|sP@MX>$SEu?6pRmf>Rns)|&p3UuvD)x6riN2)fb_J!v7( zTC&dUnA(zR`(b?}8uu~1B~xSB=PUu75NX>Qc|--0%GtZ&al&T(UZ7k~<|=ZPFim{} ztyr9nLx#CFtjIpZXc@#B?SEtes|A>Gou`s%a9Zb4qP@m!FOQk(!U5iATN#eib-uiFO&nC3YM;QOHK;1hH?U1uaveNj z_OVZ(9_jLvKVcKca&}lFrMk(Ks@K{HxSZ+(^) zCFxmPk=9-KDBsEbzki_Vu$ake4^_uPncRJvz^BuT$g3A4WwJ-hxsY9eg{^#n%1^+U z_pkQ8lC$c{Oa`pXraKSsR!A+2Lh+rNKQJBrSYwOh(k;maAi#JGjNO_z?UleoI1`Uc*$9l zdoLTl&>vh@{6^#K+q^E=2AU#~YkL()qf6mZsw3$@T*0D!Z~MUu$f6?6x?jV}h@^!P z5wkgzaZNhgy3#aAavwe?HORLqp5G88L!Hj0`l=nv`LYz4mHX}-%UZN6=y^wtC%~=e zk`bM!J$v3nDBsa%`gHR{Z7ykd2%l0mh5-`QSQ zzd6>tTS0^6WA4A1vW(N+B}Fd#K}ldWrtF&019rFMcf7Git-6#2#BM9)K+if~b=L%4 zo;iFb*8S9XUl=xfXjY?n(;bp~Cxyf~51ZmX%XJlwJ@(OGU@N^Y+s*j722BB;4iE#e z%T45iY+a|l@Y(Y+?LLmwmTk_2f=bLJh-gul{;Jw!c)f*wAR^pp%10DaJ0-oMcbD0D ztX!+tvP*|sve})ZO-=CBx|;AqEN?~WsViDiU%Z6PD z`xA8y*u2J~bO7qTVdv2=4jdjR$Qq>&w@wk6$x;fLVfHbSFF>Ef_g)wY<|a?265w@^w8=$yP@}%$~m%$l>?T- zuty^uOZds(_E2XcaORs=Y-fZ&_LeKYFo@c2^sUYCWTqy^vGI^9LpBIeB=G^w{QMEX zNkxeL4rZfcGh*i1)g5Jy*>|T#7dTMviYpw#&R=kbR5Sr#-`(9^`3@A{p3Wh}POWLH zDP{r?+;pDWn@+~y?O<`W*J)syU0A0+SN+$bdS4^ymO=YY8Y%Sg*S+hPDFPkSw@(m_ z@FzXDuZ03GNR$)QbC#t@P;|hZ^S3p;j|N_an^tD~zTGaq;yGT!F-)Zvy+)=L)p$2E zwB`9rL;bnaQ50~xOW`5`)LzZnexYLWRJFxJ^P!7e=3roB9dWoR3Qi0zTm1z3I(Ds?!Q>zhr)qKd~#vYPTYSZMLwkNXXV7N6aTL3HQfn=-o4P_mtYnm z0UF~XgeNPjsK?JkL2{1M52pv6030L}V^(G~pH2WEH34Be*PDh5g`@u7`PNO^SlLlZ z8B4Kz!dR4*!K3WH&SWNb+iz3>x;q=KL#%%HX^<6fEOA^a8eTbIcC#5+fQ(M=;B@&VE%w#kZ@ua)mbjW^Md6CS*v% zxt<3w$wvfsTUi>`J#D+nll$b?6hp3VbLo4w;nRcP@gWLL$!r}rsFh1$cr7=!%Ssoq zj?=bhU;awy%nEZZIh|yNr8#cOvDslWo#Yl04o!R%&?}_n6AGn^G_!L>_&xW%-uP=B z!XQ&ol2PUP*d6et&Se*)@r-+LJ7RN|%$2qS7isq)*jY)GeQGFO*OhO>$ye%7?rO+( z7c|%Uxl%P{NYOW>1ZISBroHVq&wpjyAEf^XGvR_If^u?55U66u@Ndy%0YaB;D1LO5 z$rZb+N-HBca8lfoON7I@bqXsy@*&#~Ub4*|9vpLiDELuo&V!9Wby;$VR`W@^BcX_$ zU-Kf8N^9-}bx`s7{g-~A6$l66Ox@vbH@amF&1^c=07O(Ta+0^tS#!1g;v>euAm6wAC9{BJRe+R%Jv(Kk_&`O4%nD^ zX)V~^$@y&bvba>%e^YM8!g%utghdWd2!UEi{Fl!N6>_XJMpdzT6R~KK?qzb~#O$mV z*uW~_+l%_6V?h&OS8`2}NgdWY^O}anx7OkN!(nOLy5Z9S%gNg32@FC+p1By8-XH|Iw7I5^ zvob)1Yj0lBuXMZ!-A>c3V5LGI0i8Vy3||zHdT`5HHH zSr%JP{Hm{Hg;-7RheqX}IW)4uE0|Y>97o(s>WB_MBZ`hb;cNSeLK4FvTd_XHr7qX1K zB#-k4mUw?N89eZnW6ddkfZw>_!o0l6W!u!!&+>4gn7gr{*q3w>!!{Gf`cV)Ehf1CT zjUqk(be`tV=0ZtqO7&!Av#AE52FRvb`?FE;Yx{ghI_3E6(PKcGi+8j4*w4;(g9G#0 zYaC=?XdNWP$bRf9mo0QE+$znJNcmD1*=%Nqm8_*7Z-o0_F->?99MjsNVxiYt0#L6I z-<0>@XW>^r(sj82!;Vk(b2FurpDuL}I6VzcK<;Snge42qh zGxITRTn0Yo{Myt$gQ51 zZ}aWX=p98Fe^uxgeQ`(;lxImwS$8HWqIw_R#x?K{*!W?7VLl2nK~x&~|2EW{_y12D z>MP%7i><2byd)nxq(R5A7s&4nyQx{@S#j;jD2snci)>H{Fh(=hPOhBfO=0&WaI<(0 zeH4?8%*v+xs$beU;2moGHzP*8LuQA5_?wPKC!pbsLl|+NhU-NJ>WXAtTT*3Nq=bM47(RwP2S|Y^`%Ew zF$#jj3qljW>U3qiTojVUhk4D!U+|@~6->xe!YSmRi$g9(7;a{Uan|Sccg}DuW*}}$ z%q#W2vF{dmrxi;g6kER^*eP*EZ2gXq)qs-*n*}&^ z{SKFk-m_aa*Yd(c<$0UH#j@%g*K@Xx55OS+B7!Hv6SqR!0E2rgLSHu1OEmwpBHI5! z4K6c&6CQg*U;pjokY5~uaNakiWH)OYUUfdS>S(}%_d<)G0hc$eq;xVzdCU6dx6r0H zQ7k`P$KNsUuHM3X_9OgYkxNy#T(B$CrdWInJTsxVRZicy;nrTGqU&Jy8M{TyfoG#5 z@h$P~=^!rEf;3Ljal4KF*v{;XYtn>AWtKW(>GGZf1OW>;ZY=hj{UB;m`WzpR=NZ22 z1Df~H(NERo6n)Ix27-1^-|wW{8cIKEt)kA6wK|i<&AXmF_DZwHtni+dPq|~s*dzsf z0}g*fHfNZgUF4W6O?EC|nbxaSY(gKK#Vc5@rc=duMHNB1{2L4KxIO_I$^8uZJk{d; zhVt2Ycls!8S3A$Xa2yZpwKhWUVS)ym^3PDH3s2Q$vtnWYEwuQZDR;g){yi#Uk0t$h+j z=cPb(@bUa%K~JWwGfwZGwV#W$5_PBL+3&BOX|d2859n8iX)RWwc|H5;UGm*R-j9zr zwA!{u-qeO(8uKC$%WNsxOQzMi#`FPc)Be!_HlOd{2#I-_AcJuX$Ixhp(aF9bzTtDU z^l+evRm%g@t+YkOAQM$^_HcV(9(ticlv93r+TiPrg1I=6#}e8Bz86%94(bCl;F{o^ z?B{4+pY)3pH<^yx_0L9&&*;mI=Q44@CLSG^JTWC)D1Vw53Z;yT=cz$!LXfO6Q zgHclb_PuBh+1nC-E>U~Ov1Lrz#Eq%`9o^KUJy;0|WhRG|lFEN>?cRMR8*3bDj?B)h^^*k)^kVc=hQqT)Jbo#@+e+cop+8N!o}zF^o$qQ&K?-^ z9orhG9l=UfLIL`R`szir50!A-!@hmYkpNb(ia=~~{2x`Q)IAau)Hrd8EX@ERG03L5 z+Wnz`bobOywsQ>JPCZe96sLN+v?$z`|C_jgO}LZX7N=7Zc0$n`8mjm?YB45#1Ex2! zJMxOslEiEcM+)r&IN3v{*~;H-dM)@4_}={dudlDo^|m~$u;@h}$91RgKnTy;Nn1S3 zrpoQD1cuE1eq?mFQ1raPnh;Y5n`naX8SQDGk9+HNQgrT5!oes{$L)$JPFjOD%n=!paDDF1lF{?@Gb!4W_YyT@ zzF`l~%-7^9YcgM(qvv;ZVx~auK+s{yu`OT7=h?M6wcf7Qh$0yL(P-w)V0&&sB*=DS z@C^_i9zKiFz}{7q6$ac0InMYtrM$JJyQ#%gyD#Vtl7c5 zufM3tOCL0(jptfUH8!B2Ou%k|7y;SL+eG{=ws?ZJnrrw(B)?nzS~n2<_1lu}o3=UTdCDICW~%}}MqEM-c}3v|C5JbTrZ<#3s4 zQk4zRh1=#dL9GLR^smW8v>Gd!QgiL7s1hbf!eGr9?(n4Q;QNXVaIu&J1L><;XS<(F z7~=jXN@0Zal$sotW^K}7S6ync5g=-PB3a}(d3&TE)+w1#h02#A6MgNCjRo z&m~7@N19>rtWbiISi%5ywJDMw`pU@GulwW_jcw%u2-K!;vDpyoH~LPp=i;PLaO1S6 zC0zH26-ncHNgaRU-Nlj@iXdfG57dj-FZpy+IK#xYN{KLsVhHy6*L>uLpgeTOFi>CI zUcWD;-C2stb9p{1+E|&L1Mz{9UA7BfCvrMVkVTy!mY-e;!nBeNjE#Rr$-r1pQ&@ps zZ!SEny8>(qCK&CChaTj(>)giFlqbY~RV+=+r5%uX8+{#=37p%UPD1xK-D{dh-k*a3 z5EGBDRgvtp(09;;GcZ{WPHk&;`(yCi7`W}jg;yGc)x?mRv{e*LXE)FgYNC*4yF2|q z)V)=3T+6bqYe|-5u`Om<%*<>tGqc6a%(7)MGqcn!W@ct)W@cu%J?GkMpEYlsh<)kh zzK!VUj;>K-RApu6mw$#tIAS<{ry=g7jV$3KHa|Z0s}nNzc*T`EsC!ACnPqx=lqG!~ zhbXo5RAg(QWc}Y!3S>L>|1^T;ouI>{)yS?-=mQ_OFlOaHG^3QW~1 zmQ5|@q^3MUGxYod@&DR4fewPxLgLYr3A4w%l!6BVHm5ubTNIz(5BKd8oNV6#T=O> z<)wt%;L9O?S*}unUSXXn?3NC6EW-iS$Z{&!mDSnVC`P?jBU_8jvXG(9=Mt{O{gT`? znAf6jF;ZGvTou?sbl(0!_&ej@0`&IXO14bG@#HqFEkQS_IU{W2mur!N zx=r)YD$=!6O|0+#3vMH>Bei4uEg85l^{wed=y1$DgaLSJ+Zn%wrGE-rn9eH1z(J8FWL55cLlV605(^P*;ELY5Nz< z0V%@N81fM2gV5T{?Ql3CaSHDpNyqxT=7wwsWhFkd%&O*14lh6l`njQX#FikkPi-m0 zM}`^y02LtcP@iw}7#V;uJz{+J9{422G#yJ>X}uKJFQ>-fJ{3?KD?zB0^0>no>goPg zFsnK4#KYSh48wm;Mzb<&rrCW@v%Ro}0V7Ml;%IYsAiat!m(cHAsf;QAu)@6B>=APV z>X7^X>MlEOCP{d6Kg#VKZ;s#~S&&0Gc%X&;GLSvjXWwIr+_737qSmraal;T;k)*Ip z8{L9MniN}J<=MmdJ2!TU5?0^bHmvCvY=L4XEF57k&XLM~NgPrmj+1|h)`wJ=^(RS5 z_~pR_9D!ADJK5hW>)+0Hm`|UX|G3dcJ0*E5br`p3cyg(|K>JJ7=HRZ`2fl=GP4=NQ zx`WrqCgv!$OfNw-py490BfUm$#2Go61-G|`SNI_2+a&ET4qA_P#Dka2OEr09`~6<| zbj$O&f4T(@Zv!F!bIOodZ3DQ;_G#yN^p2mf%laSZg=-P;)n3p3=u{N%r#f>66dt^) zT1vTz4ZO!`SH`x`U8ly>sZw84CpC!5lcgxG0480vpGziWCwvV?Is?;-7?g4g2;**b zz8Z8=8nx^lHu(N?f#;3O>f5(nsONRMp%=Z_6(&?8iIK^0C+d}_6i6&f6*-bHhA;Ux zZq4X@^~ul~rmOkey=A2Y8c=9I&9*L+u7yR)!sRI>}N`1Va?51ZTg~U5r)!8_XQL*Zs3~4YLIE_i zivlZ9e;LrlHot`A-xnaV={{c=6r2E!{L|1T**gI!M#1F^(~t&Vpf*H9Xt^vOdB*dS ztF0P+A#9RGB{NV@_c6Z7_Kyhezn}HHkV82ZNpHuGH7Y8Op^#v{A+N*zKX~0{YlKdv*n-Z%Jv z$<1Nj3m^)l7WFMQyOZN6A=h$zfsc1iY4z+#_3@EcJUrS3F$c(PHBqa^9*|{&|Nhek~NCtcOQ89>K>2XKYnFRVQcz3CIljZOLjl%g;UJF;F%tv zH?rKgjFSgE7`*HmswmG7+nTP9VWGe9Gbbdb!KI$|X(uT1-5Ge)DtKhJ-6rIFbofL^ z^$9`XL~QCE!WDPyRsq}D&~cvLcUy+dYZ=)US_vK@qKb0Hud73sh;0C+I1)&Hu&pzI zC6yCE**V9vl;ho&;OJ zPM-PZeM}x$UnDExtPc-AW?wp;N$(AzmuV|=e6>{BP4n!*i{v;b@sAgHTjjb}@~@|v zn{7^jk}3a7;Ks$C@|N${3sCWW+ie*^cOdW9&+pHU-jw~KJ=J(y?@aP{HfQhd+em+n zB&A+I!GIJgVklXyA#ht$WsMDXv(DGe&zbzbneD=khdYXx3&*m+*ox8&QS-2aNewGL zmx#)Ns77Zq^t$pW;LM_TFT^4KHghTY4Ka81xe5G4mad6}{||u6Q~Vj@g-PM(Y_-%x z{}!b&Dtdw67gK!etkzUT7d-zGXhBPe8?H-PJ8T*Xz4GPzzQ69n$EGgukO|k6A=Dbv zJ(*dYF;Ho@CX9_~)F28AcEdew<-l-fdb-o!W>=1ObN?tR=k?_5K<#G%4(Z;*h zdHogPcdpD9=#EY+8Q12C7J+xeRhG}RSVOP7Adl8_%|p~l11IAs{ViQA&BMTQ3b#Ua ze)l--8F13AMc~L~aKYDAJ*QU6=MnefO20j$qY@ixqxZtDAeUCzID-p{3 zkLTuoW9uFH_a|2$LLF=b6L@kJp!0-r1wef7TpIga;TV)JFVlJQt&DZW<_6D?>pZg2RgdO z_?NF6n0N|79eGk`OdRSd`WELu0_OFuUoudCB;Bx4uNbJhvUSme=f-j}jK*veM@7dP z5-8RXB$cu>BrA->_v_L96i#cNE!7T0E+4~eco6U)YcZmuIhA<3jw~FLW~if;+S%gM zmisj6;A+oIQ!KqF2_T$-8ry=XNtN!%aj)|->tr#1Q9pB?2}efqf#=myG%F@oZ1PKg7QvXTVW z%wZj&*m`P2MI;jne+*!ehl~fmO^Z01=*ktN*L8N+ldyVB=mT6Caf9%_r{Nkj#n#T? z)Jf5kc`qf9MI0-%rQ>8mByAHUwT}#<)v}fKi}8m8tTQZ>olXX~84zNC`!f?WSe8mC zG$2m;tkL>&$KjtuF=*iQ`Wm9+UkO8;{%Kq8pQ>AyuZnu(I(ZW&%=zxL#fh$lo%d~}s%mP9v8V==9EffDo0XtDyQ;d* z>0#`ZZI#0sCX$y6D^X^=0<2)LLMH!&b(mHj)Y4nCZ&^DEPvdu^Knpu>@(PIUlI*Nu&DmcTZSv;=AAn=MK1++*xoE}C z_vMvcrmuH03jqy$`|+qJTqzg)7IGO5vW3=?Q zZDmf>|7m--+sOV4$-Th&zX$WQC_4MD5k@u8>Eqx%R_3jZWCvNTNbg@_x`r;6Fg7?D zAI9XugXqa>p^~f7Z zc6{Xh+8~`>l>u8)-cju%E-|`Hzwhz$`>%zh$t7GTDAFS)PkwfSzOQ)oS&aK>m-wyW z3}r+E*4OjUdzSsAB}TI62sty?{G20 z#V^mJ?Z2T&MYtad^cT5QI|lvox1O8lw9Ds{@Qte@4T*qcu6uDKck1|G1%xO0_@=B( ztbYIwIdt?_q2GtAHpzLynj>s0+|X}v$L1;UhGT^mFD)@<`<`nEzejhjU?fj5w9M*p z86e@4=r5W?X0?q*_zQ)6=u_0ZDT3imweS_3xPEi9hTA&Y`NZamWDs%D;{{z~CUkE% ztq;qMgtwQzAq&OxmP)sS1T=>KEPiD;AcC}y$2YN;#*JxGnJ9qQz9;bFyc+J&|CXnx z-%^K!2goE1sg>6DZ}sW9oFQHf^9tUG<-*meO6u)6WewSBv6->yv!~N;iI8hBQ@ywD zV@KkuJeK@Ck*RB_(L)`6&Jz+BlHJrE95aKzQ}==xqoBY8!#6zPJz|(YY43Yy8s4ss zk(DMF66z&*h(#beUn%|)*#?3eMD+Hqd7+Dyt30oy(x!`GRZ4$fb|gjvucWW|N2^TB z3nBP&TwtW6N5kZE<_@e7NA%?|A_5L8x~b|&5gzSg{j@(UQ+#I0d&ZKum1hP zI`#hy;rt?iDpN;~=|r?0SxqP&k;WNaCWWrN#}-zak*+XZ0f1%3Av#`dyGLF;hRC%v zWXnp-+&n>OH0S{}Y^31cYV9A0D(Yq4?x| zu+Kt`(=GC$?nGi|c6M=impoW_oLI<^ubws(Zt?R`^~`i6m$U~uA@8f70HsHi*}zSN zB}d}7r~(JT3%PDQ%jd}}w*!lN4TRklIm?`RCHchy>Y0Iga-%WLaloNlttFmVD1u3K z0}dH1WWTW|lf509}&1u32F*Z7VN)a18+*ECHi!`*}RtiS(MNV8oRPQ&p|YbB+YZrx2cD`%I8*;1dpU zEu-*&Us1}CR>lKtf`#Bjs_SEMF>BznN#iY_c)2ScDg5farG!t_f*MV2WM3eU_79&){>2~AMUkeeq`+onD zp}bJQJP-`9zd9T}4w~xiZ5@BKfQ26&WwIjhI6M**6eKbuc7Nsg79LSHM=r7gBG^ zMX;xSRv23f6+~NR=>H%-!ihqIlAuTp`{u|q|A&Z-)8@nn&9tS5IIbW*_Zl`q z^S~yoUg3dVzAZVNuKS!ZOqY7DkqVLMWYm$j4NnxNX1+Fd-XRCh;cjn@BYxbHF}$nl zx*YYDIrRpc$h=HQ)qT!~Kl|%m$A{E^6D^R3n^}JQ`^Zoq*+#pk=k(;|`y}TKVQOo6 zqFFX>?Ybtb)NMm-K%d662^`nGA9HA@PdR*v^wOoIWL!|Z%#QFiT7Lfsq+G#ramo?( zuDI?EqjmT6z`(!^UC4vB^j9$rEiFTH^N@xHSD&C*L7c9lB5U)O!SoQ%`KbkNA#A_l zfLOl%Q6AqAbsh#tam3wMV}y18*7eKZbdkhTs`kKRie}F}S|y?@(XS1$Id0;g4$ir! zbA81m)sMm1;_pu6c0$IMoOx2;MI1^IVEv{6*#7%({n_r=1~vq{Ewa{!Tm>`&HB=C= zlP2N<3VOQ(=RzDy2GBwCsy*vJemxJPQmOK#=!c~23;Zh2q$44VjemDyQi!oPD{~0V zdA5uf98KL{XL^3I?(#g7rDLZHk5L@S6N#W`mQKsmR?1d&UB+qHP0D!qd0`T(NmC%9 z8p1+_b6P6cgn^4>9srBt-}FF1D?l1UjKalqbbfHk*_6Pf>JjY}uP?IlHKxe>TH8!P zKQN<=4(WpLI~M!xr&@*87J`s|$_hA{9CwE>Zbr>wjr`V!Kiur@W=267F~4iM3PNv9 z6#f!Vc(8HQLvZ2xq?voZO4z-O$DM$THp!$cZ*q60ygdE_QkRA4nct9sC-+J?%kJ2I(mO|b8 zOIwL=Pxjh@__g)uh+!^eRRwoy9Z(ebp4A%wvzMYb97Scq*^oBv&JctQ)p4o4`s|I{ zLEjvfLs7?{PbOIAC?Me|tf0;)a5?{df}f=e8eAjj32u?~@t z^u}dR3&_cl^LB{f)W`MV7?`nC@Q$a%Av4h`c{>w3%4x_~$Wm&TqVjMy#K3I4Mhct- zC{IEbSi4i9`*bFfrX8Nm;8%bvXg@o{wDg2djtx+_TIV1fOl%(c0 zq5GSgFg6s}uJUb6`h4E(M;2I!$&1UwTg5Ez_x!D6;v+#yLPQZGxsS(Bf2i7Rb#Y={ zi}=!Mf%N=Z@V$W?yLlH?Xx{pbtJYpY*s|3A!KGUqX8AI1RL>(_Smf;hkw+b;vA0JCq1iGNEwXyIFAJin- zox;MB9}VVW77=fO5*@Yr=1~R|?;0cVeFqZrw$avKsG`Q<3t59~gXpqnTi2CcCW#qe z5f7qX{mpj*-PSh-0<|J%OBCR>Ae5}mXc?46a}>?K@YSc>^v@M4<$f0>W8+Xq`%$21 z(lXKhqk+e#%}brbljj}bV0!tS&vIbwz#$-q=0@TPGYRz)ZfAk=@K%Oh^7xY`E6Avu zA;(Ud31lSy@M=X*$mDC5l;@}g=!Ffzr!Z#WlLjfuevqAX==G~a$-Z951cHy$XQ86H z8E1k1e?RMiO)!g!7CQ&GD$6hbSy_7I%M3|ObRij`0)i$&$kkPEoCA-_QKLf9Z&GG< zy4?rFjmbrkplBujn(buptSbD&Ps_nOueQqqr!V0-b!o7*-?X2Izh>mFqs~U{4%c5i zIr$Lr&fk#~6c+{JFqbG9=sP3orpWGT8+DIpda#r^FH+C0x0g;n#8Kw6Yy z!&po?9@u!$>7q!HXflw%1Mxu*i#R72n6y{uGeO!}pYRGB|nlUmZLR z#m|FHer>g9Y=K{{E^1Oi-=o*lCM$L;FMChdAhx-r(DaY-Cr{8CHF;oPvy%rO4h`R^ z4K^iiFDO@{CyKqRv@4N(Aw792mbRhip8J!o(R(=YY){RDRgg*AhaI8+luUJ)+gY$f z@oa-7NqRzAh=5(axvUvDaV!xYt_&8f8Lb>KyG@@j}IN`zNiKM@N=y+?p zImX1zUAmg4*w#)fz}X+IqSb+)AVy#k&NsB_(WkMe{#8lI6iV`j}~z{_GE^I=j6UBe+!@_#7o_ zEg!|A^};{p!v(}TXGt@yX0A4(Sn{QFEU&=%KFn%5(xb(Q0xiKut3UMTJA(2!P4aCo z4)xN7@l4H0j&kS~O;Q~b7F&-^$XZ#dUQ=~oY3wK2!*ue-`W|o1IDL(bx77TJD^ows zG?EqTUT(be0?o44j0SqUyzn2RIm!@4WfKl--RN{q(Rg^gl2eodXWndBuoJ-Q3pAN5 zw|<5e`SqsP6XS(OX-^an$~_fV)2?M=?dVqUpZMTOPt9uA=3A~L^J+;ng-{NO9^=#$ z?!7?*V-+!`7UKgjCtY+X(zsAR1<+dizDEFi`18D{?0ICFy2@0MRBhi=9c&qD=S!YL z)b2w9^EcVei5ZIdgEODcH0+IV(N1u{G`rR6x^e~(krjbQ2Ioi~bt$fIpZqf-%y|r% zl{y|{x6rK3amxBS0hrFurTSfdL=<2$x9)7Cy1}kJ3PmtBjM}=af9TmhUsJ4q8km+j ztTCb2V-uGmlGR>VPmOo>=y*I*=*rdm>ikjPsuT|*NZBwebS(6_Zgtu ztLgcZWn)`D@t7}%lv_S&TYZL+1LRX%pB6?79)E+rx)r>EO9VS@VXD|Nkj8R<{P!`C zgSS7dl7Vr7R5hs~xuf!2L)Q&Nph?*;n2&sy)Q}t>?`4#Wo4H z^^Vz~DY=SVQY%wEi*c$x+YY2ITK-7j&;h2J^XJ5lb5pmeSFUW!5cQQ`$3dR<2Kqbk zit_}&7m2-8o#9Re?qd~k=R$E+$ahkbQeS&Y)5J@UG z?%LCr2PibkLV|%i8N(F!ZhyL&Fq4$kMBmxZXB%BLiZT?&c|_OSOzrPaTyq0#-J-E8 ze2TC%X|!7oHD2%nK$?wo&iE*>PZSInwZBF(t~tX;!z~!OH{Hf(K=oDs;Vx8shxuEA z;BjG)s*9F{%aaGZ$gdY--7@uF>-Zg7Q-!Qti-~u8Vjq;VgKM7zY=hVmsi~hQ zi^LeNuqR!M1s4iVFt_5~1`zNrT)gJm7yuWnRnkI_DV&eaXG1f>2(ZNL$G2Jo)w%(L z26jvWK6n4;#IIxQCK+f@!M+irFgApQgwk1jcz*O9uh#`6>;ZyIY`p_=N2?*ErrcE| z{QmOp%#$C;5PGKQ^m^^r!|%>-a;n$2aqN*aC^}S8oZ^$o4Q;Ew6|YC+|GrV8F){h7 zfAKo4js$x@AVXfD6&K%_Bgxu!(E7@OZ6c8EExA4uRV4OC$vAZWh|!O17-`TKWn}@N zK{fm+nFH`=@_7%}n$LUzk=!gS@#ZsttJ|X)48RkGWa?iz=>J+#R|KSb8~>W%M{$%@ zCmwDl_uusA#Sbm(y&EsvyPUBoSg~!o;iM@Y{m(yF47p)0*lT@%aYTAAq)YbUR?%cf zwHFbSrXe0IbT+DuqD<7W3KeS2hJpv0pcXGCXpr|Xy(WrD%`RmfY0N=7_JFH5&*gtq zhk?40uoM6JN|aR)u?kX7NqpBd8QBL-CS|ra4n;fgq}AFDqngZ!N~@Bk&JPv*-7XT+kG{(pd}FXJ>ye zRw+r`V-XM#P}k6Co2dNnX#-85d$v5qHTUPgr}7GH@Z;O+?8l`LD_p9K#t=qCsJ zyvt!_PjrCplxHJ>aY{Q@MR6$8Ls-(3+Lx`Lsugy`W5-PRpgO%YfHGl#_H=A#5U5`J z#~S;`L0?1g@;xOf5APMtRMuDw%;~Yt*Q_evnDqL}-A`nR_4zmZv-az?3h8f6&Dqf#`uiLP$0Z8l3kwjw(E5ly_8QgWxG~3$BvbOS4k6T4fh35e^Wu)k;m!%*_Vp?(4(oL_3?3oXhk)TaG zc|q&PrB+8ds_jhBhMZ=%>s=3UUAz1P7zrc@N$!ECR>>$z+H?Dd)CA~R8jrP(? z)*@CG6Zdz{ks{`CU~R?3e7&c@Eu0K=<^9@$OXw*pJO`PWq_OH=-NZA7BO zWh}t_{0Kt;xYWi+6`+C|K#OiiNfDea1!r!UIODm1++<2}M!uHU*KEn-VHZ!+*q)YV_#k}N8Br-|_)&rAxJvz!;ITbT1nuUDab-uF17)~CkuFhB57>l=E8 zXH%F{Hida?yg%u_rD3mkgK@h)A0dLcghpA&lhy^ae7bL3keCri4KmW)G4pf8mMj#252 zBC6W)`(1Qr&mNe4O&Y&TAiie|weQ(6F?UX`1`My6I5N?kIg^S&S?y(YB+ZNy(RZ}V z>`zSTs=KV*WAAO=Fik+qcHnxOMCRIeH8@gcH3Hf1&$AqP4Bv;ebb|)-c3Vy{Z(#b) z!WmgWp}Lch*Z1!)a96v20k>v~0S5P?hld=Dhw=u11#)>swX12Lik&M`ApiWyPX4F; zaBlI43XiRFaCt|=H3rT3%dR11i~@a6HskfD9e?!?cN8yN>B$B5?*2TsH}s5ygbspf zQ3s!;uh?j=oxPo39f7g6>7Kt@*|m^^f=~qy0@^2m$D=q#SyGRw2fs!gxad1AZ5?}Y z4Ml-a@vaU1@&#f?5*T_`C_Aa)xaxk8I}2A79kNaTI9Bm_5Del`<4NA*OEn;)A0DIS z>jMMT`R#Mh9$nm0kAEIcCq~w(X!AU{*0XKV1Mi z;qY6uXk}N(8|*Iso`M*5d>gdK?`WXk*a1}lvztAz5*MrI<$*dF+>r#T%9RWikva_! zy&`xr-IZ{0U{lDaB;`LWtT8M#{mPrrt+RqmRNYKAORf5xo1#v#J1zQ?3#`x8Ng0G3s za$?|K#t>Bpf;GGX<4+@lbbaFau0{2%5WKaVid#RNFq_2^1lK$ z(*tpvi6Q$i58INHrsJ~X8}6NV-f@&ZHt@91WilOP64YZl4)^YY#I}`HYf6B6P>Ihe z6BH_y^xDa^=dk4dQ&aBnYqPHP{(AV%QjKX*)E7iV=bl0b=w(!Q^J7#=tzv}aA%LM; zX@3mZODV z*NGRE!UHer11kUtvZpdzQ;>Y|!Gb+e3N?Q%@J3XsAJ<*n=#nq+xGY=f;OR9^raeY* zBh$fJjKTMeL-&zZmMSB5=aG7U>E?}ZA3SaZYkR32!q{0i^WE^PrybbH&hn-j_n9d@ ztP@SxjMJp_ysULdpH!9`2)jNLsBnIUUv&;zY#c~WRSn8npuqI;kY|jx&oYiF9GP=Nr)LPq&JN}oqE{~~DsEN_8 zTN|EZT)i9|&rx?G@MOqeb#04fAoowu%L{b=1L=2`PWvlhVrJX^^p7xKMqq_}hVmdG zB{N~}0EbXwo`yaa#NgEt7az2FW`S9KwIse8goV@ArcqoG>d9;AB3bP(Rzwu4z;hW@t&4m(UFxanrx&lJynb7 zMmJH%pb|NexWQB${=9KVNqWHg(7;&i?!F3YugzHB*`&?g&YjGpS-HP2$aT9SJh-;! zbm=hAX2#jh6Q693Cz1Zz4ROL2mps=(I7gM(J67)XqcJbeJ>M&_?S| zsE+BCzaC*a)Hykj`uddQ^s;BU4GyK=nX3b@JYGs_`k-``nHHzUVTw?yyVcDuQl3>pcM4b7NVNgl{o`@x)(NIGf11)1F z+|a~J`S~Eh(MBQDUa04kr4ooTcBH{qk21J7Nlsqg*6_u&Ea#Pi`-8&o0x;0G9HphH ztfdw#$XWR^1zv@rvD`p*UcaxduBorp2*0MfKJ1Y-Msq~3O4lMCu(dH&lnmox!gu>> z^JU#M@#b0M`T2yaxYC7Qme)9i&Y_wHtM!v_1rwB{xWwt zKFZtRl7;H0U&_0(?Js=Mfi-H(%^EPcWu^8sssW-2>Fci$b&?NH_KQCV)~v3>9G&q8 zC1ei*c&r>T6AF4Z@oS6E{4)gR393;O>&(@UVOLz%$92;GVa|lf2*iJDy-%)cb#>}$ zRXsW2fGybC?>zJ4W@)4G)-Hv=0zO&0RJ3u(^ncvlI!VY%d+}wl9lIN(cEf9N^9thg zj>)6nVaa8R0)3t;dI8zI&*yJf9c}^CYKjDE6^;+%9?dK5L`qWLAxpe`JIW#EryX8# zY3$`FwT_s&Ttz3UOFu2q`rkGm4{k`H951e*9aaS3mQ5F)UTn}iZq=IPrw5Wx4(JQQ zF(IOH2cJf;TczA{{1Gz?!tzkuBBelj`8!Qc@7T|MQd{pak@6r%W1An80z2CIb(lmI z21IP40Br!aRkmAlR&e1H-c8L1)Vo88eO3i%-dZcXavp;YDIvJnTS5Y!mZLPGjGL9j zZ-EW{vS4PcX3Rio3e;$)fE%^g!3<27aGXKe1uShhWC6EB2ynKjg3Juq5tlIag^n)( zS`1{jH?9Q;jG1}(S`U%SH+uqsDB_UDmZ)zgI9DeP;VsxA^*6h;P42|bK3$T2r`>CVLKz#C|Q}j#i}l+mn&q8c#irr*^CxTjW;#T zv?3VomejDlmYE@9$9pLra`O6}nlM%kAJ#w7IG#_^Z6T~`%-a0saGNup-v(^>NV#4K zUR!#ZDsJrR|5z%ZA5A=qfB=`{q34o?ruPXAz`~HhA$_ed9>PMKHxeWC?K`0p;u zpL|-Q;mtx8pE%Fj;c|B7wf^um4FeF_ALl-%aL8-SY|i%o^pLpV@(gETxJ*(z@w6Kv z@^-vSHFw@S8mBlO($hg%n`WSS9Qh{W82;T$h$Sw!Qea))2k;ZkOf>h3k)tA~RH+Zc2=#vD45!g%PVpGi z59xDHi)!y1R6-aJFBbTkDRCv`gzq7Mm-n{mkAU}rl$$Deif4l8Y?e$^_J&KIC2oG+ zQ9tjFEq@u~rPGE71~&{?k{li>6g)6c>1vH!!)=jR8Ze7Ysr;uE@AX~raDHAXymtpd~^d~Bo3ZE6IM-GE;Ci1oVnP@^=H6+;AER< zzq#5I!aV@j>Xm-3lyle2) z+itvXMQq;x{`@=f)@X7)Rytz|4I1*VwSUNJtRarO@6JJ#o45Q&D4qKO!`JE~WP+OoVDSwF)o;3hP^Rso(qkExPOL~lOxIxPq2!U9^Vi|w zDu9(@YG#ITe_e#`Gw(i@hq}8e;E%UUQW-2wiF3YTLT&6RpA*hm&`B0FCkn`V*kTKn zFKZ^j@&+lch(c0S*)IO6)<59%l|wjG0$9r(qt^Y<%jqo?m+D6>?c@*o*sMZFogcfh z#2yb+8Bj#7h#kK^N!6OYzA2F3HxcI=TSkyGd)~u51|+6e+|6Os4$3>|9%*OUlnpCR zibFe<6>&UDEo0*z$akI;^kUB9bVgqTC_d>dh_c+a_BHuY)b`rjjoBVLVGmToq8CmA zC&^K;RJHgAjQ0myVf>%n3_oQbh%R)|y47!~MHcL#6=@$`YKVm%LYTQ%8?t)RdfuEJ zBvj2S$al8kDT&Q(&sSJ-#O3c@jo0DQ%|?az=wec%V!FGSXm>ERKCVFP4Bz9*8V1Fi z&auy5bwG$<@mYRFvvv|#2(%y`nB=lR!FiVk*Wta5&HCzej_gVlr+~$&P~VCp>L)3O zWZWw=4!!!FMIj`o4GFDHu^|n&p4eKNg%MNVAUo7JpjrjAyr{T$oT$uD-*0P@~Jwtz%mb$d)3gZ7v!^&4ga$ z3LP;imo3FB{3v}CJxqErZj+RmufJT&mt(|g)?=2d_a-fRaf_y?f-an=Bjd- zz)ejCNXI%^Jv%xu1NNor4=ng3%eWN-TSJIeXmyh+-8f#nQ9COD6SZnQ8Vy1u3?1s8{3N$wX9Dk6KqNfu)XLnwGAZ zlhs~!&(DW>cpo?rvAn#8Hr0m4l$C7mZA<5L(>1bY^wd478*JY!4^$BJjG!i`r164a zV%}SE5<;-=zi_k$W~u;4kk$q7ir| zg!Gr6CjQx)B#MB1TfT7fMwl^xa(r9^q$|WL2?x>@(oX+NS18oIH*ayaU0&1BG@~9J zK@OiUP_Uc>h$If^94%njCq!~Doxi-DLb0RyWB7bRg$u`dz5Qq`S$bwQZMg7xgOKBj zh#ALIsZ_lxUaaWXsiYzbMuET{>!a1a6tnf@=!8=SQ3nm~rIJSQz_RB}dLYr9qjF#L-f`vZHct#!RNpXinJ zta~33GRrAk4 z^h+${b`7p{8IUdL?O%t&UnNyXFroUy+U4r6u=BR9HGJ7Hz5dPfE%cVJHVF)}M)vB; zj5$WdnoQ8(3s?!%Ozyx}?UHjqg+DVwhqho3Js~Giuyx+bbX@};np{*DchH)Q{<)CE zKu|i8TWGzc0IDAuhhNy1%`COAep`e* zmqKwqWDWQSVMuqAQ3>&BN; z8&BJTG0zQxF^&Ay7xm78s5mYnSD%)Na}$0k_=RFJtzX<0cfd7Hqu~ad_WF(rBLP zU?+`|N?&g@eZS{Ko%@}SFZ0iz{Mi@}2dck9I#v4JW{Gcit)J4#D1ZHVbo*aGS9J2L zAWD1c4MM%1;q9vZav3*Fg~VjFcz-)!8U)w#@FK* z&0^0&#=;wpAm*Pko%FB@jObfnOEUa0>v?iKF_GN}A%Y==EIqAaoDwNezHY^RU5$U-F5?Y*;5bx_&nD|Q4(;Zn(JSI)&lSz$(fD45d+GY zYIzK~vns??VRB;hj7cJi@6JC%T8%RZ#)CY8uuB|}Ct!*23_g1_`#Zl5gb%85SRgkx zI3hbDlJ4?Y%5Fbg_4KZ-%K7CF1SMaev4wkcD-n-KlR?&xH7oKPVeK4zh^SX5Hm0Rv zalcW}WpF7dsQuEJiJWb2OP1)+CKW9qy}ziF*6_+yi|8u2J{(6jodqp0)qT?6v$cfvV*R2cICR42#e;z*fEU3Skf@FwhGHT>=i$y|H>& z!Z=JEs7OLGHHjMdFu^@u?9gDg;Y*^v%?*>2Msg(CUQ}$mibkUmzAwbCw_c3wtUF^7c-MoU*^F zkb#$ES|OOzYN2vhY-a@A)0+z}HnO|Jv8gJq(x%cf1l|uE`}8a^-=0JqN+B_7T+Nw^ zfWR^4{Tov=rqtvPjgL2`a*x{V6d>%RouP>etee+RQGQb1XzVi;x7z9cYT1BruQ0Ng z4{=@){g!?J8;iXp=X~p8M-vAU$$4&)GgxW``~;i+UBW>?tCgdfgzVaQEUPBV5DZB# zd35xvSKiEj(N^aBM0!8|%M|IZK;OJ&{B4;A)jqB-lHxen07N2dYxWbb6!U=r>^B}L z7d_u@Rz9`Xc=(>{-Y$Plyb;HRVPE2^#<#hzU*u3VTGTUs)ZZ~GmO8@(t*{Sd^C4@3 z+QW?$<`-1L2DYh&KUjf*fs{y={611+--e4=*pJgrpUe@p%6oyCA1HqTSb>3L${$;{ znRxhtT3|xqBQj*)c^L(SF8ljVnard%_Ek0FJ4S1zRd^OueaFd-bt>zf0D=txe^`^p z&iDQTu*_h%S+jKK)+%cp0E!zCsF<}889P+1q8ePRgr?|I9jf0-$40BDrhg;U8>;gG zV4ErIk2pfxL!XqZ*#=h2c`Xg77`;^Gh&qa-uO#aVSIoY9rdujd@v8BMxp&tUwgxfS z)>4MyxG4b~oHeDrMdzN)Nq^{}38`AYc_`z1Co?XGlir0Y<(TLkyK4Q?xRXo~Wt;8- zN~yKJFZb97MLJcauPrJ=DW}!Or0|Jd-c&qI$)M2tUwgPv<<`=M9hPxXIL_m)v{c3YcnfFMDGJA@G2 z-912XcXxO90KwfU+}+*X-QB%{yF=HTcklguySw)pqtEF-=MMv_2BYMe&suZMdCmK7 zl*H`XU;AZaLq(5eIykv^0CZwh3?Clzh%H#^RdWd!A}2 z+jwEwzxfc`?D9;ctW>fMSPd7jf)_{~oUX8!JE5^8Uohl8Y#XR`*p=n30dA&EK&(W! zu1U~}-NKSCpSWcJ^G`cR3nT^AKdu3kJo{2f& zOC#Z)iPc_}W^C@!z~&P-MEh@ql_ySu%5%KY_?nvRD_Y^8Ys@@p#?~fSD`b6B&A9?z z?NF`w(ss}+3>U~TSbE>(j`jZrV1-ifZ-CXWa1`&YE-+0kEe7T>t(8Xga*^C=+uPqt zzvoNu7j~9foQ^GYn2gXqf4*4I|6BRwE7|bya6FX??damz`1qy+^Pe2yYv&NY@Z|<* zjN#A)2K2~VzILIZuYB?M+-Y4SqgzDc5x;-XR-5PQe4oWNpDefJGhZTiH-)eFm|H7X zevN3*7cAA^ai2yS0BgS^q#9^yPQK_jn zd~T}wU-GP!U+HLfk25P3yex?=zcrr{=XcdCqtG56@~3keJsyl@d%}Z^ZQKeGG|%EE z^$d*_!^P_1vadLIng$k!$1bVfm7i0O!1RukHUed*#a2&-w0kRhaqTu^Z6qXT+i8 zf7JoKHVOuY2)WzlA7X$o`>70Yjvn8BhMVXVVwrrV!7a z)6?`#qJInge;t*0ZRJD$HrM%Ip6`PeL-~8$@PB$&pg%pMLD2tS|FPpG{%=Ie?-#@) zuYV^}zU{m46BaHx)v-{F#*d!c?z$lz|F}5+>DCVU(PCqnvQOh;`#vu5LhJRSm@Vn} zy?7TW`t^XmS6s>Dw-Lw2zhlc>po{cZyt$rBn$2DS_Qi8G&dN-IEAUpbxnl}qPH?08)B`TC}+F%RoHdRQJne(bfCPBeWDD3 zew>pF5X^SH%vK2?w2vXl@oEd9mF6re^Qfj`=!F}0S!Osu4PC`HFg@WfUO;_(6#J4d3315Ok8h>xsX15>;fj`PL9bj(>^%U?xWt{3~anQM4F88 zxs4uwcDosQr3f2_z?jJuLl0fX&CcEJ%MuC!XlL?^Y4uAyw?_^prAd1)+8p4E!Rk&l z`OiI+V4i`F9c&8-xkdz#mfK{NvzN7Zf#f^htj)8D#1oCt1 zh-~qwnK;_3o&rP7xEKhyD%}@Of_5>7e?W?FwRP%`^q>#`U5#JC{jZAX`adM|KUj41M zw^rdE`&+2noo8oMbJw1Iplic1zgoJ>v-L*8l0Td(!6H=W%0TfX`BXKv^sE4r8dp6D z2A$WA5-M{ebo&C3$#xN6f0w|)T%92j>Ds90(sD*Op+OOsK2B<|!uEdH;Ek6(Zp7EX zl*yc~+6Jv1{JEnwSdtG>)NYTd5sxpAOf$JV%SlAhaeQ0#b>_D{JKf$sRt0^IY(1@K zyD7HNs9`-ag`N4L|J9(k{{E)@*MHr>e|`TkY=1+VFfp5srSy(>SS@o@{;BOOkPm1Q#Qo{A*YeAMBY6`$wnFLG6uC6cpF*neqtby{CGGv;w6`z^tP(RQ_y^7Mm+4&sY zQC#ix8_wu}Y)k;Ky`8xV45&9_o=1=CpW7y>cNa&S2?;1K2SftdZhAI)@ZcmY(n8rx zocU4oaG$5`wxx2skE0q}xz0AcE~Dm9ypOm%OI^2g%|b%}5F{yH{WgtpAFS@K%Pb?! zZV8(K8J`n|-h8Fe2<(&dEDe5m3%43(y`=&Zq>Aq6xuJaI)5Y_7Y$+C^r#%P?BJ1M+ zuQb-}D6Tg)2Z|2%?P_bg`j)^C?N1-hwhWj-#ij5X0!(pNo}57Tq5-^cV8u*7y8y0Kv#~+5-urwbwoq$ycV#p=Od49F&xd?F-Ld&OHR2t1Q!41 z24UvjV}GCJ#l0TB-91s{9{(2ARA-&cW=7-LGG0aa%Eg)^k6cU5 zdr|VK!vV?Yw&I4;AS7}GtMP#6F>i{vLOX24UGYDG9Nx1pq6uf$yH&otEgbu0B$~Pd zg}CG_1}ODXI!s_Jh1Y`Gk=r6hK>8-=a`R_hlV~Sy*wGbcYNr4zE}KK|I*z|ruU|j% zWj(+1b^O^_KA(qw``gyd)3gpbjh7(UyST>n_lMuBnr(PO(>3`&aC2d_2uBiRKV#Xl z%mFa!*C8i0 zW1a8=7@dKb0P#b{`06%+u7oDd0hHcIJBVc7fd3`MX}P0mS6_J&Ol0`Zbg>y47i+RLpSEBG%3#BKv4aau>AQF- zb_uENsX1-pxineS*fQN^TG~?NB<+IXyv$^Thay1@o4-)nx8V~!g#HZ@kbXv z7w0IWZ46qLd3?v1kNR3gWXF}-hfjPa0By3c?9M3^r>zfm5Nwx&fG|xi`kzZ? z5D%Avj9Dc5hlh2~w7()XY>=P!C{sDtwp89lZPLban(I?h5#yHZF35efmjo)OE*~N} zZanA8^587_R1!IY-gfk-oS}Y~XUmk@xGmY!2y9Ptvp=ykXtYe5Utyzs7=KN;0XCt% zP9mY=-37yimD)S@6YS`y9=|WQo)?iS1rT+hGP{)qNbxT|8x;-vbXw%TIu0b44Z zC-Iv(vs|32{-UaW6wg4BoIw~Qu6SQ4f+D|abj|)Vgn(k`Qr817XhfBsYk#7hsn*41 z!_5W-x=|}1D+$n*5u?Qgw0@73N^Mie&xRv=kYo;c4LkVCKN&p21Ff*VLx}+`nmgU^U^I%- z(7%vnWc4iR=R5nY*2UBgwuxQWN+aC+dF=>O#7Pl zwVu5^UVj%Ab$EY!ZKDkZ^?>f<{rw@Fot+<^pAVhnGGe|T`JKTpDa8&yw``SsxG~qC z*R?i_*#>@upr#I&8!SQj;jD!MB55co51^|aE9$O2jiO$#cZT};cvUdK# z1uL58-DP}yZkamjaL{JN9t5UP7a&E)Q>3=}G(=(*H>$<)_J>B7FDwLK;ceNMyNrdY zmW8k&NWdI$Fzc$=%JgXd=TnDH)wv_}6XU>%+9NI$J{tr36b8C%)o>DgMSXk>UE3Y? z60<%(osZ;)@HQZ074~jR*;ZF$z1fGXtDM(&PT3_aewn=moh75iIIm3Qp6(A9W}|!C zqvYIrB!dHxJGCHR1lYT6(`Z5r*sexYgQqd$^_p;8mORUQB4$Ua*OI*Uwv=Wc485Uc zFhyHM@JK~`*4RXc=c652r|lb+RL;c)lGFsj92( zmC#DI9nTc+nDbJZOnyN-l4=7!%wqVp)q1>*2AAyK+1s0P#~eD>c)lWl!)bH~;uc+) zvn0%)zFt!4iVH3gjy+j^xfPUW@5m<$V5AV2zi7O9&&P^GV(pW5JIilOOJH*uqo}H? z`|_v`ANA#y{qNJPU@&IhVyF3U%RhU;rOp>H>z#5gpEquhFla1^#DS9>D7asOPL^wf zKsA9wa{wxtG)Pc3Hp*{phl8sXRf^04tKn7U3BwD|Gq0*^1bkZJLD4USM{38%p0w02mgy*yLDtRaKv#>)fS`c!;!An!0a5 z!XsSbY&cS<)@0Eq1?)vj93s03MbqibkT__$e%@=6Ig_O8{iS6~E~hxxcG!H{$l$(_ zBGlUpc`)ncgl%C94d42R+c+;)=APg`o+(XjKq?WhM&H~;f*ggCFWUrS0l3lXP78DA z3*c5$_Rc;EsV!uQ*T?=)l2&Iop7`eH$d_GUbS|@Gv*Bx(wsNr;K1ETSJ!x{NsyByj zUr_||C5aBCztYS#4_6j+^{sIBUh4gdAp&{Y`}4*G2ODaRV!B@K3+e>~i5m9`9YoG7 zKn}ux+EG;M-f;bTgG+JD5nJC|5lC(LRY$F3Ai2azJp;rzndHRw_E2g_6<5k4D z1qIdNbad5^Hc(IN=a9rv*36c1&Rae@RD}ksWHT6DNrtRQdDvC7=)h|vJXo&;w`8>H zdx~H$X_lN@wknn?luBOo2J7@|1_#$dcCdIlPV257{)WNwF^|E2vcagozn%G#_3O@* zWJ_bYgiILf%M5AU^$7zpm8fPJo*l(hQcMiZJJ&05g84K`up%5IDEiL)6?Q zc3+1fzn*w&{q)PqO0r-*mn^weL62~<1;N0ZduP?YvI~?ux5M2xNT%|4#!yeMXi`Mj zsjHRtW&`OcPU(o4dV~UwNsuJ(Unk&y{NNS^NuFw8;^Rw|tJhz(V1b@`^S6KgZt~X{ zukBVBE~OML(14w>nWfyPVS6;a6nL6R1kb-OHoSu&$>)^l8mbSHCfJ_iz<+~y(XJLs z>e7KrbZ8&3ZFw}p%#Y~-ta~(h8*@3Wbx5SgmmSD)J5pB#MUK83S+DQJJGS-~&)!d| z(EbFUTIU=GnA-gQ*yfrCn5m|O@P3E@<2#boS?yiK*O)evR}<{4{7C-AfXia?LaR{# z&$=O@y|iRUKZoDL8wH&bf1+x@BvHUO8x%-nak0E=LMOc+Z|*n}vejt=1;^58J(0cq zS$8_kaSw4YdNhj<&n6MbYkp+%!sn`uTi4Z^PSjX!S6M(%jAP6Uk;Yx1BoI&BA;EMe zz?eZSk#2r{u~xrOXY`3U?s~w@thv4*9a+K^81aU}G!q_Uy1ky66rw7#b7tI|h*&kf z7=Ym?lz12qI$G0l&M$V1QE9GNP?%?R+Kj8v*^X>xnmB-+8KCfDln+56Qz3)t9FU@6 z$Ng{=((av(1x=WyB#x(rw|$3TZPu+0nYF(Vp<(LAImBWhMWwZ7%TU2T+1`4j^5yz- zW=?sBp<5{((IanR5>no>sQ*PtjsHdk!Q8ti*exHllq7koXkCGXj0q(keuxjEfE;Y< zU$HChkeCk_CHKt~LrGhRvm6w<2|}qK0_k)_$=4~AW)jbZXk!GkEx{d`rnCjiGgSYyDrq+@3ahyVyPserxFY|Z&-gP*B0246hlpbnaN1G0&rOs9=e zJW9g2ht3q(*p~+h2YElJ6YzL`A8F!;J;54%+k78%AjUeJ!R0!*xo>u5!08O^*J-l; z_ZED(HcPSJ=VsF0SWvDoBy+ajnzShVVV&nL-17VEqjUIXO>#v5`ZrRLmPq`StE{ww z`TddKZlq1}!=P1cJww`)8D3Z}&P;8Bhk1~+M-0oZNY&9pE?KFR*jEaM7{dsHc4;Ab z`LANbDTUyG8@biwP7x`8?Ne7)y{Xw_=A0)svL^dW`0noRkI>K#j_O{LWf~W|)k2|p)V3HDv`A7TfCoL(Q4BKnm z2WR0PzKn+2i_O_G!6ed$KchOi4#cNK2@eJXeB#pVNONHwPgQ?v@!c4#7&EPWoFCw> zO~6*p^TPFLka-MkcTwO+9e$%wSjLN67*W?J956VOgSYV@{sJiNoG|V!Cqrfy_kgy{ zr2`oWvSF_?GUhrD8t0Xz^p)*Sn~Ht)Ty-@*^I{#`l=uOXU(h+*GDgY!equDEl3Hy# z8}b_%%QXT56d4|z%vRV#LGGrdk*qlmx!&zEE6am~j=+ZYBB1SoA5oPw~CH)e` z9QmUrCtVs1nRQZa2&lx!rj^ued5T(YlgumdLj{mwP&ig~8j~4U)?#d0{11J3SWX_( zxVRsZl3(`$1zwK2yb_g)c_xiJm4_jP)Tcr81%|1}==$r2S9NgC*br{UAQEUaG&(Ib2!6tAHU|+&!`=NkX0sJI zi%0KE>j}+PQOh;2p0||Iu8>Xx`BDPkzz>|XGL?R6(~}&rSDHjjh3#DpBwXxnEPhzG zLe}Z(qrpUQO{hzuB4@>mDdDH3j>i)#qk3sRpu~i?I`OT8H2%pEZczCyuL}0ZhBOj1 zQwnXw1fwp?>SRC?$H7#tn`fGtqq}3uw^)?8A2Zw>M>o^YOZX=;aRV7w5dU1)|E%!A zNnbnZ{wjd(@Cj8e9zG?|^}SAvVT(5TIN`TTs2Z4?r##ui>@*HC2pZ3mRc{xHuri3$Bj1PA#sfa(U(E zV#y*-Z<^V#cj4$v2*iNn%k&%)d`|?q;`pBw2%zzzw`SjX8npm*r<9BSX8pM<_n9wH zAS0NZWh;@#WqpHVvG>im+9hRWkPOOe21~D%+VU72bfJEo`o8cWhBQ`*VkL8Y!ALEH zmL|q*T`&Y9G^_s9rh6eA5*Ek*c8o+Cmn zz2hVrihXnc`UtrFK%Lyn7l5O)T(rFf;cTmNSMLN4E;OGXV&cKG8w5qc4rF9*+GJsT zSSo@3yX6l7u{S#Khq>hkfyLKJjje7^8 z@uD`gwFM@ zy%{nr`R-2+3L2iP<$ZaJ;u!Z-;V4ss>H6d0ZYLd=P5Me9nlJkbDe<>`-4p&@71zNf zZ2tIRtve+jr#^e1BHksG?mXup`@6Gb;|@$U$Rlf7;!`Y`Qj@(7)L5O80Rc-H<~sQt zh}PH@oo5rO*p&2j&fV+7j4br$ZwNgsB*hrX^A{ByUbK5}$;A8Q#9^rh=4X=^y;1C3 z#o!nP#;yn}*X*V$gX8rQ9O_OV2p>E2Lpfp!BMJE;V`BEU{x18t$vhSONvqDu0wN-$ zp4$CNRVojfx@*>p}nE=~M{&1#()s?|!}@UcGV?tF++YqZuX@QSY+%SJ>*1kg5u zCePUx8XvDG`OK!Wx@S>Yx+P1dgPV~Tmf~N2Asq91@9XVv;B!{c9P!VZkp+93ibjnG z0X{#dUx|iHa-Dg)W1p-Te&pjF zpowEI%_|pZLUJ-5Z7x=HH)ze?-=t6?Z!E;r^@_oI<$)R3y1)*w5_ls!067RMvXch?*;!rUIlClbiluE!kT2P91frL zIdr1vvxrVhTRqA66Cr|a*fVT@`fILy!=Lk;k>9CKEg>GC+E~M|nbUAoV4rDm#oW_Z z=Q9lC-85Dz#fIEA*nT6NW`e$!%M?RA_nVD&4@m%H0LWM4VyhdXKoZacYARnHe$E$c z3(cdle5u0-z&ojOq8-ih8M#`25>xc4{wPox#G7#~;f{P{9Mzr<%|g1CbJ;TwPm^(b z%?$Ns^_ZjaMcIa>N>cQu8c;{K?bn{pvk`HabKIOF%mX`unM=JV#r28k3Ktvdj{>>i z9_D|22(PrHg6)T*9d@re5}~Rj*!uzEWE@3K7M6@NN+$D_8N*ASy*oGQI!$e!m$2c}ksV{R&}IV$9C)okBew@o?{UM;46vG$lQUB&EG*36^n31xNFv~&Qr6wk zush^9! zKYsC2`0Gp+e4hX>_oPl?TQ=pJ;ieVt5(^H|`hgekf~Ys=V0NeW@bCvadrIOf(v0pt zMZ-MP?%3D_v&Ay>;a0t)z1v%4Dz7<{zk2wAd8O2^GlcIBy4>Zfb-KwO^bW@wzO-rm z>l)Yo=6D)5H~FS>%7LuU!3)M2cf}XPI>q6cVa#Z1hR( zNBJx4TnmTkW&gzA*UspUKTZmL&lKlOO=ffq^Y7g|5f3ki({t73qbC<*%5TA_VS!BU^N=+- zb+`Q#6pEclUR=ys`g+Hbh-0EBT1{y~BE;C6OvKkGmvP*xs z;@@F%ps2E7N=j&NuL8}C*Jfw`%19TbIu5_ay6ldZf~PYOxfKg)!onG8*74W@7(|fS zS;~7r5mHUcbh`w@tc!F$D81NUiovM$Y}+wEn^HlFymlu%BQ-q@7ADgGzn|{|Al;4f zM1k^2)wt4juL5Xn?{83>{{Ej*>}Xl|r96BAS{}8%7L20S!uF?Ii>@cC6EX2+qc}B2 zh}SMU!f~_K?Ubi16KM(xd6pE^GX>Zfg&=(eqCz^u8ZU(G?!)Pi@wtZXl&lKk2~;98 zkF&qb_#JqYKkv%NUrXV}iTg@{`ZXfy`zNP(xsad(>7Eca#G>}i-+NCDSug*e{&nz+ z;6L~KLQj+}WB%cc+#~fK453``xpP&*pdT*kQC4A<319^o}9en8xN4p=;a)6q;D zJmeTc*OYHpRM7Oy-sk5DZbS#ho9x9GHO04M1Du7k9>G-xYFsU#n69F-qOjRoInkSR zK@r+OlNWuO%1q5_e|6 z8D2CUxTb*QJ>g$Fj(&7gN1@=hScjA7ZwJ|Uv&*!nsInw$s2j4IB2-n;i{O_|d}GQa za7x3Wre=_dGFQ~MHUqP(F1n3IDuqYmO?5J2z9~B+Yq(HXP6M;O-YFq9k?F9LzRH4nBQ?@=4}a)MjU^FK^0G7s z7^iWo_@XoVews(-?m-y32oPTKaN_Y2ExKoDQe+{`j5~g9rRCsI3-tT5;(dPfyOH`+ zQrM7r1UdhP_~&}L>!Fd7Vx_Y0m?mHV^17D#g5wAAmA&TV4iHVnh52mSU_EwsHxm+E zc7j#-nvZiFt-g0Iu>Q(eobfbu32pz;pnqz0=eZj9v>z(JR7%gwn~&8-OyH#Hi3ph1 zCbs&9jD&Z2#q7g4-iIo)IH)#oGriXK7=1(oK|%PLpP&B&7#N8uGco*iysCZ;jVX$X z_jBw-y~MV{5}ZxuS4BdfU*GCeKH?vNv{Smq5L{Zx+|CpsVRs5fj1z3adcdjRf}<2n zOyU02hLte@h6f6|dS+neET4eYaGX24JKZy|aFAFU>bh8jqMm`Av;BkF11MBsY4)$6 zs2z&h2>HPFq0F?NKECQSbE_1*E@_#)hPXZqvuk7thG{To?t~$%7l|>EE+&i$`ceSd zV@$G~LNyz1lQ43`{lRHnt0Brv=yWDy35SZoo0Xr$4T-R|7^HM7(-}_5bPAdC{Ra8? z=*0TxNH+B9tdGK+z1yvBiV9t1YXXt@taF*fNK<@l&nv4PaI?Rz-U~3Pj_@9S(OYqB z9BZHPh@Lon7(O~}@nnmG;mV`+xR=gjclj9K$uyAJc3>5pl-Jz75F-U++t4-FlORvi zxp%*+mYJC{d;L%(XB66;Y@oX}@w0vMZL4y3!x!jStck@1nuIUoAzwAeTkYL+Tm3jF&I-D{E@hN3A^_Noy4hHVK6> z{IF@=BTm}Rnb&xFj*EG{XB;~6$>cfc``V~&keo+U zFm%*8H+h+zQ+;3Yx}bCh-{fN*NcHR2JHy9KOTTHyZHc2z1JuY&n*+xsCE6gZo%2sh z^ny_YvYgGjnYLl6axxM!V*HzU(f~U%&19giLVOqAWeRBSg-g;u4HO?YetI?l2O|@mDVwDHO5j6HhKDCL`UXwGv5SU8plxim>LF>p9HgWs3{S48 z`sm3&DJJnqG!%B&0wYqN>_p-#8b!e4-CuQxYBNSvU#PT=m$Q0{Tt@gr(ioPo4a`JE z$6A8C*!~GDOIgFycx3ltf)D*`XkcWuz5C}&V|B!$RH4B2N~ZX9bk1;T5gx)}VSVnb zI+w_sQ&3Rj+ZJjrN!|GkaZ=4uCRMl=`Jy{HUj>d(`Iz^yip}A*v%#n08`MGq?yszt z`1rerQ^k||)(5NbR?A_VOsV~!%3(?p5-Yh1kE0W()Ci{y>KR@eb;x*${D>7oFYmWl z!=Jgr=vB4Y!&(~;g8I%Z+b^Ssh;?@BYoW`@2z>gx)F5fw8?WhKIq^ny-mfQiBw8q} zlm`r(jQPImTal$%;!JG|JxdZi3|l&Ic+$4@F%(9vjAdcuHm~V&WHZR6rK=>&W;W<9 zRV)oUklWcjBkv=<^v(EO_hL$1))-=u|LGLOm}E2~k^M9GnB{U^m6NcvM{8F@{rv1L4$bfyttpMAW+ zu3d_2lXXJcb7_Vbdzt|Arc|&NC#UGYbXo-USD5{K;%SR_F3zEYry*8g-X6>#4`*UY zv7lx;BJf)esQ2Yj_!(7{$BZ4mt8b4N&z9mIScuRcH2Sy|fiYjM@w}6zB5h8v&ZfP| zQQL7sd%mnOsQB?d!PH{nf2Dbo*kAQ?ej7|?(PLUf6~IItTN^HIirE)O7Lxhu%}g)*om<6bfRg9TqSYn5qMiv>cDN+eWz%oFxR`x& zL%yN!sXts+)2UT`KrIO!4_~ERUV}HjDEY-=+dTEDK}R!rbRCagNk77PEG%3Def`)c zagL#@dZeP+Qetg0o<5VsPd_t)Z-uaNr<2s$VfkhOitCEyZ%u=HVb@nsO|R_D~hzCrRnI23l;IE zFOZ#D5@0uKbhUL9%JUt&;_iH8fc4jP3T9J63bjOmIH`8Stk1@sgTAQrBJ8b5{{+ZH>5e(lneWSmMv zB|D0|ydS21T~nVbBnUPvu%l56k6!Z87sZoUc}xA!x;roqWTS~{tffiBXmE|U7+v)E zItA83b#1z7f`4yAUC^G1#49{<`M9xX(h$?LJsG+)WzM~MUnVmTOLBQfEihUf^us6c zJ7MoMAf5cs*grx+kJ9lm!%P6u?z}TKNyt^?? znb-VN1kLF6WjqmcxqL>fHx0l=NMdeV%~Nq6&O-vu5;i^$7%ZhJM)xZ+n2&6#t%+%& zVFImqIulZ-zN@59)sIDH<;-7ibGlK0WCZeI+8`b0wKs0;Tqj7Mc0pC0V_U<8o{ElF zoC+qW4eBRisbLmAFZy5bH3Xv{GEO!XP%fkiw6DlEmT?^bzH&;&&vWYZ3h7rA_Pd`4LtnMlO4mOOmT=8uX;TgdykQxPY=It-s+Q!efOy!2- zLs7!Dr8*aib+>9ZVWk3drBTxlw3)y6g}IVmGYE{2_! z`mlN}cft|^u`8Ab7%X*K@ck3pP0t?ue2f07**zuCI{1u&vleqQdb>KMMM&9}a-~$4 zqpH>Fk|E8qTBw9Q3j~+<=OnvPrUSYhlW^_G^78`^*jCj zR~O@au|g*Y@#M4o?Db{(hjAl}JM6wUb3XdcLN+KUZBOQNXmh-$UmI{eL+%&&kkVG9 zS595hobj|W<1M#lY*JFoB@Jra2$gxVt&>N^$x`T;(0FT{HIz?)RU%ki93%q2=K>5@ zcJ{56EzydjGBZv+41@`UZ&ivUC5xw{(&z5+Qk_Hwg89{@k0V|zG^0v+%IO21&K=Yd zp*+KK#@bdW8W=1GcXa~~oXh&>2ZPYB2lgl4cP{yg!tV4&O)PN7NqO?8?#vIS6bnjJ z+{0}-S0)#9*F~6j*yw9%mnFP@xVKz#-Le7V32HRo?B5y*ldqo>EPvk$1OG#vR>8(U zSt+wGFq6`*&F7OP4cxS2GfVHnWNw^=`SOijp(>LBL90#Pf`3m3HlHP4)Zl@$tA^Sx zZXI-|4I5*5hthA-1V~_qD?TCBq3q^5%5#m-r}EaHw+7%0-utg0j3Nee#%}>+p(?pM z5Rr)+d9w_BOymvB^$F6|ETQgz`gwl-Bw2inpM>ALYhZ z&GGHBKd{8Z-T%9F+9av^RBQfqT!#$l@tkOx$x*V#O~!oG*Fd$hvxK5$&H}#Gwhj_@ z#=s-!MvitpG^aGBrTSOEyce9oye9#Xp5Cv3vBG+mqX^j9gH}G62-hED5qwzY?TJ~u zVNKZzhRtK62?7A4c5XU=5Le}l`K1mXLdQ_dr#tFnE?=II5AN|5w-5HSYSujA`)4r} zXk7Hs6`Se8VJM9Y>qTA$=$&{n9-)E~LnS)w3LUukVZ6Anu|wN*t5=;&EUKQ{y!UkH zJ3cE;Wo^;fIz?=`{4i!k|6~DNCo?&0_X+H#lTl^bG0H<3OR|fgWVJTOYvW_+zW{lyh1W@3z0vRJmLK=@&_2YnH=Ux4 zC*tk(JxWm9VD`>f6Ea>(!zHG-%dGidQ zW@$bs1Z1ps!W#??n^S|JM#njx3PP=kELhg!Lsi7V7~TUs6YFOAf^dhYB-VUU?2#oc zkPFzaq!O8Y3kfJ^KP?FthuxUSc#lEVsw=dB6t>(ss8Ei)}l3zHgtgBE$ogrt! z;qj~#Y0rbidPCIJ8zJbeWcs?y=ttPGgs$n~Mgn)oIo<5CPL>H*Nq#?=7C5zaZ3;dj z$M^~tPmw=@P7Hi8>zV2JMu|spU@{sIcc{&|rL@QMuhMFQNhgWe=AT)ko!6U}p-7w5 z5}4k%NMqGNF(}_nTi&m`k|J}DK%Au6w_D)QNhc?7dq(9T?^|!Gc4{v$VVfqv0S-gU zJjOwdT71@KS?-C4#qL|&%p0@KWXjPU@SGfu+32aGKys4(`C*pZwZ_QOB2w=;fI-G) zu$G1CzTVh)z%0}FVRbCi+Tm{cv^YS-GnKG%KrgE)T!_H(xIw7SA>s1s zNpjat!qh=+&6%LZij@bWk$==_2lV7 zsc2pSoPzh!$w9hiMlq!=^p_P9g`uU7WobPAvRQ1G1-mjDFjo^VkCl1sEEEUDYE`r3 zG}P5!B2{lky(9l0D8L#oG@5{|emD-`J@Pe#&ZboQ8li*xoSk`9)mSuxY)ErHWMBVP zo;eywE-u=WCQvlmJuTQJ5+363V&N4WF!c}R+LpP|4R5_8C7=12u9b~6{ej{>lHQ;P zmVm`l%xSib768gfVrt768;laBY2G25`W>8|xo{*U^_K2*fEqV;7cu`V{lHw#WGRyw z#Ef=Dj+si+>1}_~@pD%mAq^|e7(x)jb|VQUgofVxsv&O;xZG|$#@_dew;O-4wZF=h zK3BtYk9N{1o}@KV9UXaabC<1(CfgvK*wfeN{@s^kwYiqG?FI{yi_ENx$VL|V78n09 zx^G{~04STwt_{gUz6TWEw+j-JFAZ4)Q&s5HfUCnztmTrH+1VU@ycK|GVR3QqD6hW{ zcHR0J_D-}PhS8I&OT-=KypzObS2W)|%$@)5=-(R=GV*W} z2KB`r5IX>!fPjuq(h4WP94-=j$K?I zI*PtiQ7EE5Fjn~+HBd+i$paRuL4WT_;#+oC^C;fJO}*}Qq0^Dxh=Dt&)c?oz?2V-~p(!CN>p~=9HKT&N|&P4U+vHc6%%{ zT$f(KTiKic4U^Bpx{wvA(CK<0?gg*GYc{rpIGvM}W-liDI#;Fa%@gOm~6}2;8^-P z+;RI~1R&y}aS!hS9a5otWyJ%?N7T%E|1DVpK~t!ll&F2jv2U>7KObGDgp}p;#Lx=V zqx$1n?El(an0-dyD&QErffByFymUKLs=HfEbG@}=y;g+*cX*rx|-%d3D71p9NeydkJUhtwFW+J^d2w3$F`2G?m zSdP+v2*O|KoX>`)B2qAg6Tl0){rgY~H`E7DF)d{5)o zrquC0$@O9rVtD6t^kWbmviC0MB5gV8kP?6>nylVin{!P;4`jVY80G!uD8DlJojFEYo|XfN++qw?w*s6jTK6gV&%6);=5bo z>OEa;ekL*%FHT<#mplDU*4rW6lG_#3z0HY%W;fqs(;dlj zcfEWzE#$61u}dPK^c%|y%%u5wf6=J3WvlFdIL!V7T_{hBUM zV%3ai5A2_mI(3qU8vH!v{Xr^JHCsMKHf!aJyKZiC?Nr~@-fOoz0*Nm@ zg#C-YOV6I}{qC#9K!on}rKpT@YV3D;{jb9~Jnrd%d3oPsV_9Tg zsf(gk23}aqac<0m25Yqf3Kz`2-`Ysq?(bmxfqG(yhzCb?Psyr{TZ0Bc4=oLHDq2?y56X3)S8juP7}>MV%NoIGbp~Bo{hxO2>Wr zrMlyY`0!AO=vEZPI~E1^eo*{b;QtenC=>`U_fI16w-H3zSkZblHU&ug684|J4RsXxN05n`>o`zKN>sBnc(_!7}oQyT@JH5N`1Nygi_WxS5KU;=!x zX%&tdGfbk8EQDu&C7)lP0YwnRRB4))3`&%86pm}0Rf*+=)~J&Dd zVjy@m=BmjoLR=|Fazq=0j(gZ2ZK}9;iO~i^?~a5V_yntiP-|J3wz7wQ3}ZmaX7SVh z-CEitType`({M|wpPx%`VPf~*;?vO&(yJl7L_As9Hb*)54_;%NW7rHa5lIS_nv~~v zHziK~nS(TYnq`T7xT_ELzqMf@y}m0Ef51;FROv1|I>d9E{=sz$*+8@0JzR?1S43!k zJf|)Kuhx~`rOa$EV-iJ+zjEMCe@PJl5wY6sT{ zgcNMdb0NK1JHx3vOW)Ha>+QcF#q(vP&+jztNWV`}+%NV}e{g z`g|0v!B^2>Avx0#Jv^SYe^ zMgRrIKB+AykE-BcdHwaW^-Ri!)F~78+ZE6WXSHeP;4IQ(Wpo2AUCey2X`%|J%t;ky!B!gCdg}se06i&u6~yDt&JrpAp3pk=o&?B6&6|n5mPIXf>_F z$P!b!4t%|FKTfcZ3lBeAw32kS%6FIm5%A<2&2Zj>E?12f&@Dm7{HOiE0w6=2&(Ka`_j^enW^`IL2p)^ zT&DIs4HN3d^uLHVR#2}!U^|ztZW&mFSR~l3S=J;+>{9B(lk>DN`51lvw7JkXK9MlP zgCt)s!4s|oRa8S+RP&if`9#;zxBQ0U+%F*kpTJ0+-dF+allv533#j(2AwMz?Wr2%1 zg3u|l`^W@5$@#Lsz+2!_{xc|@g%#2JBR=)`{WX-lWIr69DAY&z=Y)NlbNYr@R18{{ zfohCa&lHBP_7rBjflJx7vI=dsKo`+08oRmO zls!Zrh#ad(w>OVdDJ7<_xUUGKGlgg=;#Te=M@ES&NYUV*9Ue3ppWgqv5A_TT z;=C)jKr$X2v{fGW*6MYpmm+W^Z>u09*dJp5gRi%aisN1OezBmz-7PS<+u-gF!5I?V z-Q7L7yAy)DySqEV-QDH#+xzTu-uK?KZvD|~R(G%IetLC3QuV2CN#*J^+q>yvdPx%$i%A>qZMG>VVvyxtBD&(er^x2ROc`!9th@>k0Wjc7;fcpO>83(Q7 z8lboM=ThkpijSBfRpt>ZBpJdp9B`m)@PeqaywX%e=b2?wPyo zCzGz%qUX+xLcnHFESAq)REzqooVE97^0w@=EKg@c%_nU2&&)SIApv6~nKApwgM)*^ zrun~QPAdPAIazpmc|k`*>*?@%Y4Z8-24R08mvB z^Aw?Y=il;ubZK6X@-55CHiki;2!?Aa9tJL@(iZG}YR+Z$Em{t3b`yuEMjY9^)`@p3 zm#Y$WKZpUiz;gWlTM@A%-g?QRZYwtlnZxsPUYhw(^kvSZJeES4$frtWU)gxk2`fla#@J*CaPNG+o; z{jo9@j58MS`u29y@{e%K=No}2rM~oN#^YZxkUNjNsoH?JQJyV&r;cOKvUq!yp*Ir| zMf{gc31;9t@uvYSq7*gR%`LrTTBC?_bE(|G6R4 ziv#2QzfS&Fd;hh0iuTpcY+vrrii?i!o(Vp%{^!I`L@?9vzeGsV*#>cs zY$6M50sO=hWUA?lU)<9jby8RT$+9Li@Sd1%6{SJghkr3T(-xA9QXS6`iFj>(;!B;Z z8mO3XG&)B=dsZfvj0;hMKmk^-^~ndoCsG#5P@5LhwGpb^ho_h&ZFGw3SJiZ zi^+jbdYq`1>y^adK1r0Jf}jsZ?39_czUW5~gQpKyINeR_;dzahEWUa2ecysc*i|h! z&9KMglH5NkDbGf#sb-8Q6nW7a5+*K?sz`iGS+B18Q7^d#ww-c1&o0bXR+!D@Y=XT4 z0meqEah$`G_ zU#=(%GmQ6B_*6ggVEAdk=#$lvi`?$Eo3wHB*sKOyisj$`&3e=;{G0XYC^{y#H=icK zgKE+@(+~gUA(b`>zdvs-FR|N=dt0W7A>n{NcFIfrG0jq8xY8Gvp?fc&rGD2xyar2- zfDM87Reu=QX~D?b8{led3N7@#t%{w!d!(GL9B@jOE&`9%tMTAw5Zb0ZJ5G`)}jVWn|lSyTU!)({-mlF>$Q&SDRZ#3k~gqyGdRePMi@_&_VFD*~o`L zGim`Sw_NvouY9esmbk9`Pl}>bf9WQSb3buq_Rpn*gMb`y_j9hEeX9m;q_)DbpB94c*!^_JHNk~=YK9FT+|ooTG4J<7aVlA&t+YL z8igO^H*VTGc@VbauRh9#Pgrjj)-xV0zX$tNB{<2f@3&=0964;`cvA&^`>budTzViD z>Gmwmy`Nw!_NwK)V|j&bqv_69zp(PcQTw`#UZUB|3UDkDA7e!?2 z(5neey@=d9^(y@+68O#O?Tjhm)EX_~ z8vxJtR&=hql{qS&qC$|zwurKp)cmo5P?7)9B;sZ|qc6`@49=1=KCAwVyz`|#W4VGZ z6wmR{g@f?&={o*%B5);5QL?tSYi!%w8tHS7jnrDg$kT5tcEtidMVIY}s!mVb#|p`B z+)27R8*POkF}-He?0ET|_iaxZUM&3DX@&K)1|(pg5aGhdrVW@TQO^Z@R|8I>x8SpE_{9xiS8)_yLI}oTjcS+H}{kdJlxgfav~$v z-Jkg4Jd~jtkqRuG>XS7 zGr7`OHCU`?FGh>ZF}_=k0Bt{C%ethI%M6pn?E5^4Y;ttD$GcceV16~K!~dw2^`g%} z%OSkCAHw=5V9<0rrNv}J=LO9__{S)YpB_{c`Mb{!*>i;ch1X_2_wjc7FPHJTROIh# zxJj?ZNF!P{s|lh}a_kEQBk;p|Pw&O$46o6Xv2oQx&0>e6vtRpB_B$yq8(Rr|T2^vF zmG}AUU-%DhX}04TlWMJ(rR`Vr`r2KPa;%6B=c8xpr*ZIf?MNa(&!JyB=YCH4=oMVd zc;IkbvQ^6JNh$s`K{|DzcLB|2W;%djjBXJ2cimiUy-_IE-r4D_xKWD$>b81IKC7d_ z4xW!AEl%CGhI!UMVrzk(5Tl9jAdz*QnH$?LF=aURlwGnrbollu<=5)z4(DZY`2rEn zJtIEKkz;`0O;-+(K&`d-^PF-ATL{6nJ2JCR{ST7rrjiF1*$36$JXX!d5wtg$(ZAA# zS`j|K>k7=6y1Wm>gKOIpJ6_-pfq28;YXzXqq5;rF{l{PQHC>33!UcN6t>+?w)el&_ z#CSz(y$N13J@KfFeg*Kk4R9?Biyf%6`RsMw=M>9VMCQEENswp2W{%zI&wFgCe0fM* zD2#R>>TodqMBI_iNZ;Uzk*w>flQLh{?h;-hSmp_6Cm7#k`e=Pw$J;Rx#lKW7(|wh= zLev~i;TJ*gvo|B_`C0(1hx#u(L}?&MHSeadadx>)F@9F!*5q`3^7=^uJX6c+i>!F< zdHX?X#_>c!1h*m&_R<|x1(7E){e@40%|vUMbANGyKxQ&1Z8FQGUHoDnGe&hYM}{H) zrM(^Z<@y(alerU=qVos&lFxi%8{3)qij7ie{QqXNHpwra(RbvzSp zD4%fky#dtaT2E+oG`*-s@m&e0O?t;=@gQ%f!gS_Dxc3O2TYvc<764z(?!5E{ccp?r2GksC@WLRH zS!0zCN}GG-Oi?~C0A;Slv4}aiH9h#<;&mWwtUJN(fw62{k8mE`bbI741F`2OcaG-Y z+&MtEXb${K$@T(#qs_VsxvdWjdQmGOx7&j_wmrQG?N44ww;PyOodBG*J6ZUVrH8^G z&({@X9kwTffdwf)t-gG|7TZjmZikKbVgAI$>tT8?u8MK}r+GJHKAz>j!G}HO?+pIb0Z@n%)F7D_l)^umg`Wd*k2gQ&?u#ck&Ti?N3h; zOgA2ljLWD;2jidJ*M`)3z1d;KcujwE^#M#lADhC*yy$1_qcW;M>+`%>zV29_QEE^sRqJ?_1=Ah1Fzf+eyBM z-TY|&XCL$Ns6R14tw#5_*;aOmkoPOrF=IU~^RopiKK5jaDcV%-@A2SNvVF}6XZ}w0Z1v|>*o-KJYY7?;HbC1@c6u3hx>0q??Zl!S*?5!XN zcJ3H_-PoUzQQFJrG7*#+0oy(885U`=yBk)xp7ue4%PeclJap)WJIz4I(Y!iFZ~K1t zb)C3{cwR*?ey90pW^nmwrTB6C*qP1k%xv9;D`xVgok(-^;=X>7ZVBhE0co(3|tAY6-u` zIbj1p007hMOr%mgUby@|{#&gT^JOmT&+-WG%oF}lF)!wbb^yc8@0j9Yy-rlQ{xg^` zL#O-m?wF+r{QF19t(P;{$TJKNFj>6C_;2pJQ->!fPl+lri4%I` z$NqY*EF``G{TnEpIe$7KJ;3Osm$ftOfr{C&Oc^0K1FPsa$@7dv);a$ZoGUQ z0c$30xd#h{R~-wuvslcx^G*L>2dIlmLP_DB-P_gOnK*9Xr@bZqlQJdH3YWxj{kOgS z$Wu4?XQe=Ijxnm|x9i_2F!-Fi+M&q`-rlHgJYSu^T^I9>^y+aIZ{WTtwP42@_upVM zdx8W8GCEh)*5ag(202Oybl+LSP+L7G=KpFb)*2%q@!T*Jy()9JrF{H#4Zbr~h!{XL zUHZ-3>ew8Afxr=`SLM~UV`J8vgr@pOhZ;BC5ebN)qyeiqw1!=|9T=chtDDiAG0TC^zB> zD|~1(H-6bIX*?4YUTIdI$e6ruDHCTHD^N^=f6&imz@m(ZhYuf zX6-!|&J59f?gZ&XghSwnf2OPc+I`Kwg$#l<&-5flhuOQjp6XpLbSGRP^5Tz{U+rob z`xdM2$IB7dIgJNMoDB990`*_>)SU;UHcpo=1{8#Ncg@K02bFg2Wc>vd94K)zvDZR= z5vTFW@Gp-XwuwNkK})0+>Oj=Cisopa4A{Z8+w@g2eW&G39V!*fD(k&U1_{2T0Sjo( z28PL@r|i!y+TPnc=gsHxm00BFJ4YU80wD=Kp-VJ4P&<3<*zk0c&ymXD0Rk zu@z__3@6}UR_qhmu-JXZNYS1&X?-j;2}8qrJr0+#JOh!`Hc)4lIB2EPX+S>y8+LP2 z|M;uesDsw)0Dg;{=jD_u)~OG5al<3~V9wXsjnpy!qe=&j_SN3x@ayF^)aQjv*^R4@ zo%eiu?{?xQNP&waJIm&dQi|%ZIU3brtZ43ea`3BZsDpYRXS!F5(-Uo*jkyK@> z899h?)jbce9q-9)dpe3ZRicMsA-4CP-Os$;;Lt5G=>=HGcE|QdYhm zsFhV9euj5>Bb)@KI1CA^QDX}SzHAnLCONut_dBx{*`)0O%VeG&cf-tiO>%&k6D?eg z+3FRgCDWOK=j;R8WWh|ZScWKXmSVFqvv)N4VRx6+yn6DW*Q`0QEH2NUc4ba`WX_Cs z`s{=ZtlkiBcJZ|5XX{xEJE>T0hq3rGQw2^PW4*oK8Ww@eypOBUxKz`PO$?PPN#YMb*hbWg)tP!@nouB%VoIs=QvII_6Y~>&FeB>It%V| zlW%TKk|jD#9`BFaac3Kd&u9~8qOV)+Msz>+5?Xuo?*72tS}O%1sh=jzwLkfcfi$xJ zuBtluu6Bxg$B?85|EQ?O^IO34&;rzIhQL_dq(5a1s?ldu1 z#8x^*>_Mv84M;V}*v=l|iJ6IqE~CcSrNh?J)$_6Q{H4?PKUdrV;SSCZ(wcT^%qt0c zGu3#7GGFIE1&U5EEqLQNWjZ6MygeACVf9$nDH2pXWh2_vg(;0xDls6eV94La0!>mo z3CpzmndbTr44ij@Fxeam%p_-i%o4Z8a=*Cn)NQ>o@KY96qQB7Vw#mNe{VW%Y{o8q} zyo2S71(7R56u<2-&|$vJOusI#>ltoAd!Dys=A7PWDpsw5kq%YlfftCeoG2=QKwX2h z!0krAuD;!|^n&CYzOSYemfERBUQo5K+%zEj5&kQ=DjlW0c*<4S@PU&-MA>q}tm-+p zJdCcaBiL#|(t&QF1&q3|KDxF)XX$SFrF>zcnH1@uCRpDC;?f=i8uicqk=DMddok_=z4B4le(cYzFsPek8X#vYuZ)SA z?Tg#DC9oX1WPtej7uW=Il%~Hyyo1A2^9nP5l$O^QGz^ z`RTQ1%CxDxd7otfN+y3*@{SGjAi%@Jqx6txri&{liO372;tj41IoUKGJd2Dn-(;1# z8Q#UNx$C^4jKOx8Y}ZG}`iyydE#}vv*6`o z&Yp02C=#;k$=67QS$|}|5r^8(AMRP4EV?t=!@21{BhckE!GEqsoUwSkE__h*AehMd zMWbAyWo51^xg!N9`DgyO@U(=DY(V4O#{n{a^T*E2v#11R=L);`?JtYfjft z3~Q|f0-er?E*+ku*bw60#+9~aRFhJYNeEaQoJ51o+ zU#P=g1hW%zDwY~F$-13{Y_|3weJ_PDqbt9;iMnVvzB71rY1T^S?V6^9EZ;xLmp4c0 zIxfFk7I3lqd~;rS_Sd9JFOwjAf$qmKjDX_RkUX2-D+l_);!YK$OQCUU_*|K8P>nrb zmLlELpC-s{JeuOw)qjJ2< z9(2WQH>n)=SXr9w#L0w82trp^cbd07Ku6#W`bxA{(6q#24~rY247L=Eam4=z_j_wbmTrz&YLj`bEY5$ zZa$sd_8~*Ra;}5xGYp8tcZMTAWzL9>l5{Q@&+ZscFqdF8ba}Yy=@e6Fzs^e4D^Zn) zLJ-Pf>$r%&M&q9M=Az}Be64^mBKnFzjf$55-wmV|6i42Q^(UG7{ktc@R~9AEMhcgR zw*7a-E_lOCcme=jkOUSs4{!(?5i$D(Usp0I6Ji8~OH3W)M^g}Ein(wA15a9blpVuj zNFJJfAl?~TK3G60_{vku6=(S?<=!%ID-^=+~-h-pj) zR{R@SpzxN&+k#&-JOwQ(gy-5(vABC$NSM;m<`xL*|etoVf6Kr4v-}iwu7m18MfPrD`sjT#o5WJRgslN*oo>3PPeh_z{q=6v}p$w~> zB{71ajSdA~@|(XL3TPJXpBD+_K>t;E;D+&xI}7lm#Qajigx)~}shSnD&-)8$QN$6H z<6jU7>l}K}l#sPdUI6>DWdv@jq?b72pHrs>rRGJ=Xw`0`B!b2ZI~0L1UvyLzRxOm6NdOMuuS3RyIR+ ztdXxDf)2HGrcI24THr^A8aXA;0?1h=!oQg0P!z&Bwqb`j$`YJxD`qLf=e?m)$C3$Y zB`6onZV}uTgw))7lk#oH^#4%N&|@>d>M-wBMeU|`Y>Squ)iWjRVVz@jVaX&(*F z+~!k;A3P^*_2?uHmn1nMwe42 zhCdY8^7Wln<@O3v*G3m9Q+sYG+_RJq4G+kqMSUFnUI!a-Zu%Z@u9op6wP!iuq>ZoT7v&z6axt zkx$@>nR15$6`t|CgKPtkDUB{VxL-7Dn3v5rNxt*4ThMEOfWTUipUsM!osr>)Cc+qW z5wfFLB#R6G=9^(^g@I{A6_1~FVB*QkXfz>H9Op(+$YfNYTw-c2YOrlGG!9o@S3g6- zd_%zruzD^}fPdL7%xCTa8}~+uiI1mj-lb)^N|6k!RCT>T%fz_|@gttd?>glnqWPm8 zin4^+cSFH+!lVdJJt@=0^(!nJ&|6JU7jBRgkqx&4qOK%>A*vGiufbbh{=>RiAt&?S z{;hXr8l*g=MG7Qaz2t!ud87}WAR*#G>>sPp?@S9@`lXk|pHA5$(1>Y5> z$+1TWxxx=Fnp0|F8jD6I`M+xsjaNyzIOu0SQXlfJw;jls+Yk4x=8-GH69J%gL zK~3%(Q-4c^e26^FNg)}zQrtx-*tMMww&SBWpAJ-93)xjUwr>F&f;zwqKac3mVnoFT zbMh5ug1%pwJh_~cJM*z3INTQ0>5k#ocMpXZ0WNmRR^2lX8wU+a*!IUgh*Xtd*;k21 z535C%<{`ryIHHwLIZkm0DtXdJ?@NcN({D`emq;jifq_NSkZofRj1Gf@aqZ&4zS>MK zY%q;&DU;id`4Vb|bVi53E$pll6{O1L=13oVc9BY8l5TK$-c+ezetWCKY5_jb@7zB#V(s(Mch$_mo(>wmmi^)kd}PaV zeTTmv0l(C|omKu*FW|es`ik9PSnQ|3WOmm4l_!rsKwV@$DHCWiqcLHIhGe_&I1A0y_Ck7T2syX#bZlgj+A!;r-lVf4l5cjJrF zSJz{D1|V7R76ewCgMiCxCASFl=fkxyPkgU*6qm&Fl!RX#Z^f)4jPX^Jo9kK^6#|>Q`np^XmpD9QF zl}W&?kqr#*hi@~^_b}p$(S&c9Lb@FnAwPt+IRj#(a7h)D1(~iyydiV?E)%3B(S@MW zMNtzp&($CT1&5#{6;VY|(}pA=wGYdlg;)kSin`1krOtecP&s)INOQIk9l=FGHU&oX{*2E99)dG*^Djw zM?n~T&l@Qb%;?<|7j>!^Lv?_%7I_(;h=#Qavzf^v_C=!*l>fl2poXpNDYS7?6$;#( zBv*2+)mGk<VyySlNn`9@Za?Ilh8`sYU>s9jdg1x|ah_Oc|iChmUlJ!hwka{acV&#}^q&i-j9y z&4EDEsl2YfFJ<-Fdy!ZZ!~WxTLudfDLJZiS71P4uP(yd&Q(9Xu!}Sc56e?MwhvWNN zBwzNkgwZR2FC7$_;SYG@`{OB3s8n*N>dD!i%qJb)(5<~sMv!w@uIA6#TsNtuG13`G zPKKjtcR}EzWb&WV*bGyedWw?gRBo%Z=`vq_vP(cnmK!!r5s!S#aQ<-wz)`q!<{|*hkYkqn>)j3?|Zw@9mj^QraZjk=A zx_tOp%`K?jPW(vAN*sM$cCnqZ8AC1fam!XJM%wRSRErhLe}lL_>JBv8Im!YJrSz^| zn{O<)*%_ae3uGX8Z!QGfZ|w-(xNgm%bufQ$s&Cx@ln+*n+aBg6SKgu7uKTg|3e+n> zoqE0hz7gMpERU#9!ZUTlpvmg)cpmIiU(N|(NDj7JhOzzj!`bHMy!B$H+2P<6`^^T| zX-a9WvkfhAHDmB*GE=U$ym0GfQ1WV41YkQ>u2*ZU`(57WNu|Q-pu^^>)nbSCc6HD5 z4=+y$57KKn+;z;N({+*jGdMdMUZ24o6at~zV{Z$i{N~oKv9`%>c4^pd* z#Q>kM+F26(qt(slK8@Fxc!M`y>!S|;aYM-Gm)$eFnOdhaCCo4DQJD|EWZn13x4DmC z+K0~2KMEbaL2@5uh`P1+NBoYiAC5(ld@Qm?Z!lD>Z|+F^ci7g?kIqOVF99@f_$ToS z{JCB)_ew35Rxb*$-GFS*o}VFv_pS9ipHFG`vKM*d*{|?0;YNbH3-L2_*M;~F=c_#* z?p6q4jn9ewUpvn#A)DNkEy0^86qW6|ZD+N?tix{h7Qi_*;WsG@ z8VP;V+wZ*zZDoWTtbEgNch$f+ondX!_ctuN=p7LqeOGP3*Rnb;#HE!#Csop(fByk? z{;{L%;?6zve$^ZFrhD^f%Fd@{KmG1_a@_VOx(<*#KTl!T$G-Ia>8;9R!|$H%gSU|2 zahiAes$^JOYsOJ`Up@NKU8xYw=1Vcd z{%L9Uc5OfZyf$%fkjr}im$T9|fx!hIFM)$>4^~E5UB9wc&cSG$UaR89Za$BH(1B-@ zQm!@VD)&2c>*l>Aw9K`4#X{$UaB7+6?MaL7Y$~Z8aP%kZuI#^2K1p-olWqpia@<5s z=zFXYZYL`zZq3`(ZEX+4lK3TGJRetB(g>=Nog6r?b{xo?tfX1xTMEs>Y*(|3eSsHk zBl`^!(+$CcEk`>|+a1J5OnI#A1Z(%4i8;s9$jm#30@ZLOe9h+(5AS`@V6Zd~nM08s zK9=Q29OR$XaEY~xXR{gMuq+dNxkb$&cU0qqVo1Gx&)q-=Tt1OcoY8 zp_5q69?^V7Tp|3v5t^_j<^&wJC44SM4mVY`;=;RWdSJ%1B#~A$(vx_Nd4Kwj&&&%Y-&_G-Fz#Pp$aOrd9Qo*8dgJ;*c z8lc|K7i`ZhpTQHyNGPUD6PY4xJ*rW#m38E%$PuV(%m>S4Cw)B8rVs~XXd9T_1sM|MZ$u0^3xrK zL#kB2DiU$H1j?6plb&y$C2c@C&0(4W@nKAGG+2xwt7DXoJv*l%|nHfho!2Ub3*G+ZooB~ zJP~EogBiH+IWR@7m8AZtd1!QlIB^~&AXgSiJkb|ilTn1Vtf0$Cr%YeF{O=W)bC6cb z_%Od2Nuv52nQpXUO&a)-7zpXbbp6D^nc3~Fo6*36YzQRTSL9=aa4WmbTUIoJc#uN4 z9)VWZmt^tV8|y$ThqM|GJAH};Q}O>+Uy^*UxWZ}$mkY!UNo8`f;N?7H%b9+U`BI`K z7+ViCp|@haGKirRy8o)OZ-EYT5*Pc0%?MIU^hYCH>lX;|BP&EU0HPobq6@Z&ADk+A zzW=s;!4yf{+z?oaD<}wGL^YEnF}^`?l`e_L+=mxwc%AIik5Q~21H*J=>BOcRSIr@) z;Yr8*+gJ$iVQOs=j*#W#anlE<@b-XZm;Vso-Ig!ASqL_BPe&g zAyqm+US>Ai)&?GVY+Nb;Q51SOnE1l`>P-RGO~NA;b{5`)g|J_Xq>ZZFCfDhWv1ogl z;D1KA=4WjP>zeNFTb{iKD(cOHAQ|dKL-pfC3^*mfg}*RU&kw&x%xKXH{+x>^JG3xa z-UT>zx}KO=K0m^{e|=AxP>|cJCm&&cn}|PLFd(V#@Jd3rK)5|l1~$H6juBsyIjmcR zd`z?7p3Z0fyzAV1m-k61_WLKcJWE{iC{hk|*thKhhe>c9%K$q3Rx4j2UZw*Sf9PRO z>;&buA94CX`bjG}OoG<<%`jlzgA?Lc>Dyydqmgnh%w(t(W3)T@00O*z5n74w2jYMB zu5_Hu$!Xqmf28Vni9E^4LaLx%r}_!PzV7~pqOm_#;kLi4$)T_UqsHt9+KJ1Uf}?V0iK!cqqMKls zi?~j5tx|8K(Gn?BR7KTwK@su=Mz2y!ZQ@{dvkb%z`2TW5;kHk8!$iYUDr2Wg?2^+; z*BC@H6Q;b3qyf)>%Z-N$g$rS4Kn?`R`JnXR@RsOL-UX20s{0AL_i({}r&Es#cCrAg zvdC|lD^W@ecl#-Po+lf8htB~~WxEXDk<}iS-;dgGn=FM%gWLW!!WSyF ztdb-u6p%`A6(Y0y}VMv?@7Pn${pYcv(%PboVu+?y~<(H6=^`X8Wv7*7qp>>dJ`1oyjH5+y(r5*3!a0O zTwCBYdTgx$L}zM8=~TCZxZXUfGMVL~ba}1Lwy3h9BVwq*XU9jqC3Z6?I(yuT$cqM% zXe=N@Fc%1$Ng!tT$n(CuQri2LMRg8Nqgdnvaq?V-=^euylRDHg72F-29ydMQk^u4P zazx>&)m*TEz!lnDNJBHm6jL;*@p(Qk(Yf_E zr2#w;z>NW>QY~{P!3v;{Bgo6fMA4Lk63AM{jvndArjdWu8g#`vC|9{VxY8Az32lc>0Bhy zd}o3c3l&kTGEaFlk$lu5>p$JBUf5fY9wmpog=D6f3E2cY|6!nSFXpq6o5alcHh7Ma zw7eb3qrDm;9pkMdJq_7lygB2#$pM#l;W}CbKIjT-9xQSW;l)(rm&=7#hx`|!43)e= zQmjeUmW4&*nh#e~VrL~f#{nsFZQP%^tRl& z$DWtRO_Sf#e|VA|wFat8v_i~yb_6KBy#q?4n*Bofb$s<&At5jD2Awi3YVVtCxvsjO z${r?*oNj)GW<;$$UTH*?s!F4CdJmF|Ozsq^cNo-P#8yoC%Bu?uHmTspyPY}WA>QGx z)rL~*F_`?VN!&fi+o|bK|K%j~(d#GfskhniPLFc1e+Ec$9FB_UJ?!NQ)S`l9pcS5@x>p^fBS1O} zdAAP^t^5Nc6`jpS{RzgMTk)x^uMZ3l*`)#||2>5K`$q%A_Y4S^|BfaO9#6uofl+Pe z7q1^Yn(!M*-Hf+6b)#m?-7s+z05e`XiR60c(QzG@f+ABKF(z;6hwa2_y{`>9+V9Ya zPrsx3ta~|H_;9!oyi<_7FqTK`9dhsE|JgksfO|4{w6+A;gMFl%NLv+Z@n#7D_=K17 zH;jZj_d|)Z3?&`h>%X41Qg`nA{k_? zcU#MgsODc^=O}d8?!Z9VPe?D{Q7u6n>9`iO6dSbxyKVVIqc#{3w7K*%1I#P$cqKUigdcBdmtavbA`)+Zc*!ViE;;h;JhPP`W5M^@U zXRnMsIa9t{4^9t2wa{5TtR(h$6kX+Sq_@A5)o%Q2$?-5t3|=AkDMSy6#MLEa|DWKk z^q$RHMnTvdj!9~Q>{e-4fing~{5`ERHnUlG0n-uw7c?uNV87I29;cKCaA24cwhSXn z3BG2DT`azddsx-_@X-L6fujx(+GWx&6B)Au(KyD2zZGGGtxBEJp!1*xQ7i6TGgolH z`Vl{>Ny}NyjDCrQ{8ciEzAJik!a^f0ggeM_NotRET}U=|o>=f8z1EG z%8k&P<0xm(lGUl2@;k~-0BsARYwF_ea9XMte!Ktqmh(L!P!4`a-{{#|r+`eIVuz`) zRypEWe?nx~PN{``RJUR`ACW%zZl42b5w#DNLePfJNfU+;~8Db{LH z954P6Z%_LUK18dx(9~?i0v;q5^x9-g4d#ITJ{Ha%YoPrT)enA%HXc$is0OGO&P|9Y z!fe7EIkVtkJ101HlTKVwyOJ(#lcFQ$z~G8!Z^SD*u?k=#ekBKoZn`NsF2( zO8c$(SBSDB9;I0*mD&nuh!yYlS9WOE1eHf5tc*zfAjl&`s{T;w6w6dHqcO0acpy=; z#H+9wOR^xDtF}MNTGYsmWx14(TGGw#kJ9LJ)sh?cvB&9a(f7kwxGf?a(^Yx4)DXY$ zb>wZksU@K~HExwc&-l2{Tc%?H=djlDFT0I$)*5)cbA4akq0on^*$pzZK~-B5yXTLu zV|6aAJ+O+C)*9rI(;qk1L=G>zo#?U8A-5-HJZ zIH3ijC@^m<0h+bQkeBMyoi)<7aEt>1L(qXkn`hrH_m8Xj^B zcq7hh5eG^u2nPWy716`cNBjW}|LNEKJHKuw<&EQ#a}_#a^8T4Bu>t%Mc!K1s6LpgrUNqH$0 z04@tOQon|pDq|#{Xv>z`sePGo@0!o3R!8Lh5&aIRp1ec8Jlpo|O|#Vd1(HXyKlAL! zeWC;I2{JWCu$KX#SY z%@zMA5cL6FZ?@89OGf6|g7gh}Sp{{js7y7=Px+r9pBOS7-%r1q8I5eWSB6D9rqO%!ca!>=+%7>`M6RS6B{u|sML zZly~bD%dT2WDbg1G*{%7%5MYhQPiCX&Fq+t>FrOZIjgnYR~rhe#lxnrgp^ga zAAguS&GMeIx==JrHZ60=BS6E!pED^$1Ysqb44 z3Ewl~>FTLlNe{Y(b9}BL+Vu75+nV#wHDv7KN2AW+yEU$q46= zu#Em{`!-;~cUiA#LB`GCXLdHz>xNr=G!Kpy^BXY(H`^rI0(PnYfI`qDgNB{jKNOY)3UpD_u41CvSW`N)g$>810cJHE(_xMkR~_rI~&ZmTMN+x<$u1Q4LE3g zV@z=)fRtJAoJNJENf4BL!AoHS22RJn`v;Q*=g^sF>Q7k_AX=Oq1@6MHT208z#I5>* z=1$ArKttb*++7vo`*bOiRc3^9cIvUuR!8tUq24h_4C7{0q#Y&=8E~=6(=Nk$PJz@% zq_bEBCgAsE((1?kX2MeE!+|KSGpviF8LBjX^@W08hOwa&zBfYH&zh+ewY#{nSXPFi z4!8eEIaW)tXpKQ*lvkH_#=EZrAnK$^OMP-za;=<}YqE(WnBW>!hPZ{p-8TRIxe>jI zfpJRR;mwczs-;p1USnbZt;GBUN!=)ml$w{PJb|51qA_eQDii+?usjpBfl94LuMK{O zr^xwEhZNm{c${i;Kj2lORO_y$H=->1lXR6@s2qLp@^<8;$w0%TA|*ZdX9!4#=~zqN zOogm5) zV_&aKn^f}kz249%{tFGy5AD=Fi_g{*1?}-d`M1HlRk3Bu;f=t8^$#H8=L+|uDE^Dt zeI7iDepDRwvfcmpI^x!5A#bmgo=Fl#RPmSFIB#-8S0)L#gs&whioQf_AUBh%EEE(@ zj8JG_7{EUvQYIE9>ATLY?>ZR8vbAsnkJLhd=W2Z*N*o%NXMrUQT56ZJcMKRG2ug7Y zC0;iKqlYU$XjA2@NmwYgG|}lGa)J}a5B$DSd$DR9$nwv)mo$C%SV7fhA8Z)&f*hGW z5MdOnp)^%q5R1{-wPwvcvK5*6Hnz)V|EBsdw`l?EtDy*1Qg33vQD9E=9)AJdA}+P6 z=$g?WnYRLLDwvHH1vCg%GG|PK(x~rSw&WB9S_6Z9OU-7)cGOSkwW%c@jYJ{q^XSB6o1dlGQC1eN27mLlQ@>v3gz1@ zqgG{q#|`EwfbNfr6>EQ;lhTLR19W50#QeG3x@tsDpK9U=Qlhavw1D_q`KXi2~b zX^!k(UV7gE3$o}87$Ybp9f+bG>FAooqnYDRC(lqtg0oXbwe9u)u=Un4bwpj?XrZ_} zrMSDhySqCS4hMHFUfkW?;b6txin~+XwYVHyFVFja&v$c^yE2oV$t3f~WbawC_WH>m z`BFP51-x2$nZ0akLA%9lJiM=Z&?fkRTCI2y9aRR5Z!{1gjZ}3O7$&xyej26c-@cuv zE&hu5mK*_6*b_+Cag+oU$!ev^-1mUqn(;H6Hl*sJ9&{4-$jW&4P$EQzS&X6NSL{Qb z_!XDy4L(`NWbu;JzKVs>;rWFu3K+C*T6nAj7b zZjvl{5xyAYw30Yy)FHKB9Pr+7r%Kp(d0`TjJTbEDQq;^LyhrQd9&GIfY4G?1YJ7H0 z;22<8W}pJdFd^K!^Lpb@G~_H8^{P2Vkyei_V}^E;(S+INz6X-j{?WE!R$l=VlP1*7 z7od!@zWC#qr8nJ4+iV&=43ai8yr?u#kA9no%485^){VM%6AWAszzZ^hAE7L)i%L_| zqXJMAy@V#a5h@vIh@)}(DUa>zVSb&=%`lH3&y8e)8EZEg>&vSalqI{`WBmk|wm5od z!i(SzXZ`e-`)$l;b1BzN@MR|#_p>i1W_SIj3D-0H^2L^JA|1PgK}D?`4K{AAiUURi z(OB{RgTbTwTYJn>d?S|=+(QOvBVdlQ*-oGZPtze+r*Rool|e7vJn!HbHhn`?{fCBU zjMY3{9C4Z7@X#ZtKaRQujb5{zXe8F8$5zZjmBZtdV=S}}_no)1hmCwv58Uei5UFn; z=96jF>xo2cTV89vZL*~yG<}~h9ygp=>Bf)fX~P0vTq?~EHG$&igQH5#-p^p(1e=^7 z1?kU5L3kf=Nk^!lB1bi1I%0Qb`FA$%bS28;8eyeO&KlI>za}2ndp*{|Z#JK8D8BnO z-*3bY>(6!n{kZ;rM}E4nC))<7rr5K7QEj7XH|5*y0QD?#zwAHAsJ>Bo-j7_Vq~%&g z2$IAfBfCgviSJDSYS+SP=FYv%*8ZQY*uurthqj#| zZ5sb|3BG-VF%Nv1IQ&q@*~u5DkEgJi*6iu$LH4J8{^bXdAgHbBA?`$eIH860uz$Yw zExw}m9`l0m0a}s(OY`^BLH|qZ8+Zt*9fXMNkE)>t{7@Pzj0dWA6ls72^81*{UX2WP#zFr8NpvKT^a3A?dc7{6iVG2WMN zK7V8C1T!&N8q4vyH$^Yi5cT;RJw-ZLFq^4|u}*lu*q#h7ofVE|cg>@(Ke(`3Q+5%5 zWZbd#XTG*OR2sb#P+z)1Vj?IVq~s0HQo{bgB;J?_Gl}!>M@7`GW7W(#B=mAQu3mCc z8+ZO?cGO_BA2x4%bPIEIDYEX<-Py^RgS#~`cfG;zu(|b;-P7v)VEV@{O|9tS5^R`K z$UXfZ_NYRpFF)+SLs^dtp%OohKWUAT8&{gps}Pt=D}Mz&sP!P1{@9>p|L#~BfBe@t z(LqD`{F9R=HcXdboHt4xL*DEw+ksLjN=H&!851R_on9KLJ)}e0wJ@3N<9SSBZ;GDU zWm~ZY(_a7ouO$e?`7oyZ{Cm~bzXm$dbdUI&7F!T z?mh3lfPME9!>Z;J+s{ zt<1WTsWcH~ zl{m&YiCsx}GUVP>FdX47B!ILm1~DPIkK#e$-GUz(+c@P{H_Mc0^!L&;qa%SAp>HggJO)G$;m@vk`M-v})&&bQ3)} zGV115A-o~kOp|7x&}7JR1`GaiLaN4)hU{NZBg+9pUvrAR2AoeL&vr4`X`ph$4FgQI zxtJrP1gWc%z1b8v)09HE4LuLWREp%%{i>~sRynE+V{?0C^ z3j~tMfpM#mGk7TIu-nfE$w{v!gKKK6& zr%;no4;9JqWRzh0z?vn9U9&s?TKAD~4a5q3oY!F_OJj90GSig&hjoz9ng|a+<_?9q zIHsM+16_BONCO(drk4d%*U#x798+4!G>HsYeJyHCZ7$PCqd=6@KX1%Q62nyh-jkAs zG-+w1Z!X;IH4v`ZF438^IY<7xN}fML)b%0 zyQe5mw#Ysxj+bGkRhKiFllIO%XE++gR$L{nb3z03-Tiy*H4=M{twxjf5o@ zAP22mUVUDzW)(whNgq?0LZ%V+8+hHWA%~u&3?usQ5U+(%K*+OZ&;OqgF_A!J0$j?s6tcz)N89|D|nyU2m4J7ZtuB?uqXeM=hCUk&W4CXFV(K_uL7= zTC_m#(SnTeGM>O=HX3|HEHwfa3C5VX&uR%y0rRIDYUlo?D4 zNe3*Cz0_}xu75m|O%b`1c&AoNHbutp*3b7Qd$QZ-m~Sj8yF9dh{pa3$3DIixU$|fP zB0{+v3*@CT{ntu1?b2pZuitSmL zrxN}=nx{h>%m)3QNB8Dwr&?sz=aMxaoqwux=-wBH{x?-gV*A&+-_A-GHElvVpRP7l zdZJdrrtqr_U(z)NN@nS?Z%@hpv}}P%HoQkEQo+Vgo^$CUo61F^S!Q8m7$n$u=F5RnDY?GW#?cXkEdn%g_p3+W|PXE z`;B&gUjAV>z5J7?&rwg7YV;{7A$0@(?Hv!Uev`_Sk~SFV67(qWn?xwSIRanAlsP?L zFU|X`-kqIa2>271WI8YWDfR#0^K+mj&ciC-N*M)@J`x=-I0U4-cV1+)+#e2DWI1iY z%JX(lK@Opw$>m{IULABC%{K-E>6~pEw5OwZo)U@Mj{mXhch>wLjhnp?W|o((`{b+- zq$A?BFd@&poA(*Rk5tFGq0xt%kCj769f#A|*x2NF z6i1{J3fdc&aTQtC<}xtucezLC9UT?+K9~A`U6k|sN#mG)tjHvd<90bhW}z4i?Raxn zXRr`7<{xeS2BcN4sV}yMAE*m&FN#V#&+rmHzW){kwUpX@T#4PUUefXz`cPjA&Bjn^ z&Ocqe(0yOP=y$#tN4oIEBEGy)CVFxu=Bm=3+IOH*)u^|=tA2lFJ__1-aXE8YbDmzC z=WX=my)<-zg1z*I0UEClZpJ`|Q{D2qD^C&l;1cIKGYUppgO>NEVZ#*3nyNF&6+c-01AWZ<~xYRfS?lob=jTI5S{;`^-2nsE@J0u)!_ zSk5UZ{XobUI{(B<;)CH73PNR4<7*W!$S0Z5LMNJ%iV*d$4A554Bhvq*k~8$cwIa8Trp z)bk?+JDw4WqkroV&(JAfp&*m|GLD;~Qbu8-*J8UGez%r7TVZuGKW<)v4AQ2qqhMs3 z!VE1C{|N%gz}d;CFj;K zu5yr!uB;wc9GMK9Je?6nVnL>hENSyd$(+uO94TgB37HjK^dw-H+txX_7A(zH6PcAE z(fO96nAyaHT&GpcN)UX=LCtomh@^yNgLy3#T67OwZ+# zs8!66qDc@&w&2Gc@XNq5TpO-@R6U{z@FM}2)jfuGWdco$^*-LpUR9JxPis1Se|2U| z+pD?^ibWibiFL>EMaqy-bpeU-`gk2V7tG&s9nMv-aHZ!o{_ zK-khw*@=IOkCSEw>}55=n%vgDk67-)60hD$<787C?WxXb6UF! zO|Q#^)DkgjX1CNjJ?$B%<*G9)~`1da0};v8W$NIgEPy2iYaKjm_!DOS4%auMNG zO(t``Vw+J2&q2YD8M&!?g8210cY0fAB}{YKRP(&`xeu;P^2WS%W{bXPnMdEOHoSKO zn~%#ww+=2{iT)cODLOBSNINjucbh)Byrmk#JV))uqb=;07Q}D#FJ$grc4T|@s|f-s z3oj^CZ$9Mw`w%y_-gh3a&X=1~3FMZ;Bk>JJvmmNsG;FJcVyy81m^&bV{g(-8~3k2NK}cV(VtG!{KUG{=sQc zlbP*fJnCPne5?o09wCme2liT(N`$>8Db4wZ!1%ne$;k)Z=KeynZ2ICke7~{DGv$VWfrV=YqZr~ftyu3!cK5CD)RGulySZpC{LAqeV@=k}@&E!MQ-P>l zLW#6k!sF!w2`T2}34bsG%JFQ3mg4uhd{ug`a~Gy*r7B3X^Cf{+W@K-}>7Q>)Z*oTb z<;bTfeo+;AYbrXutvca;`ceo7hd^I+NT#s7>cxtInQ@ILt zJM0O5UNa(HEdCPD)yXvAzvG=+@t|L1rY{kFQ(Lw7q|xqVP5Kr-9G8FjM|C2@N7$G9 zL}nPdd7s!p%lrhi8`Qu*dzK&7wiCQ@+~%ge=+Hw8YXlZTyxnTVy_!{&t_7YBaoEoW zRL8Xk_}@E7XC)aG-3yD?e8XnGEz=z)$Md@=xZMQ8wtK9E=TfitYadvpfQj;zgQ|I+ zPS}?{I;#J*&jv)N6R=(eW$`v2d2!gO5T>*VMEq*CgQDO@+~auPKtF$e;8Dr;7$F;0;48LX5Gib`OXCXU;aqP zlHR1NpF?0Fp*z6kEr;UA#s)0gzbnDz zQt_hiJy$TE^bgp~+a<8ZWFFgJ?rRjG87&9R`R)3pPE%)#RcWgi*M8k)VzYYeO5oHS z8_5a8NHe#mNWNVjcK3G7v;oyKTQ-6T-Pf`+v(T?M!Vx`NcQT?o?|7O|XR@h)r*$j8 z`DaUdE7p@1f4n0Ce%`OZ+g`UI@>IEe?c3ElyNYw+{qd9({nP&U=I@Gz4SQSeBk0^W zYviDj{{O!KP+swUuM7z%Hug^d8a@=;fa61qh5v+*56yx*H>_8Jul_e4$rC86fbjM! zdp2T@FLn%a+K_F(;x_T+om%>jv%eNbL_d{gBcn8huRbX*JFEA8HTIPbXvUJn{OLAe zH*vv{46$)q6})d;EoT09YM;CFg@~_q!a!d?x@p@Qlo8001BX17}g4NtP6Vb=(*ZXuY zPC(NJ$jnF;7NzZ7^J1-n@GjMFd?e|BTVW17=sG! zdgf~3!kzeeBhyUa3g7YW2-_u3AzHc7`Y&T``8R+Z0W)`x820w)-zoRr9+LtrYz8Wv-v+Uq^V( zU)p-6tZYZzGQrIhw@93;YsTT)4|I!}rw(bJ)_#)Q)>FW0&T2TdZPXm)%DW6s*E^rQ zv44O^i?xi&y4~%{vx7m;+L1xM=SU##^!^O}AIC5(|j&*-}{?68gZ9(gAx8N zJTus@(!+BnhACMic5k!4`6#~N6nrqrua294BA@&5%CYGOhT+2!e;t=W;oWvlMeM`hc-@-BC|(^ufP7axd2b(s^QuJ0_a)U<)V?0&=) z-~5?|UhRygyc6*C;ZTh=TGhCxZ!ref&Sm7pB-xOw!!=~GNnx~?q2DD)PKxgI^&R;NNzV_&?UhTX4W(a0YYes>0PlK&xu(-Z?xWHj4Rd6A0pPEc+CE& zXV24B_KrRuS^ErTZo)3`?T#ORJRB#cA(&^td*I7Cp0h`|^yfrf=^C`&^cQ%?MTe4t zpq?d@#a1`NFg5{UIYhHXh>%ExE7%>|4x*#OL0aiBmbJ_yn2YNt z`s@AVu{>-KsMtjUV!v}TmDZ4HiqZ!*!*Q1MqnjLn^sR&X8RfB zMOn4fj`VBlw7IxZ)RccU-_KAkGHSGBv8b6$n}IS!OaiFc2Wi~-lNPgV8e%(&n7Z!A zEQX!99#HoJ9s|g><~|2PDPb+kw3-Hz0WGi^Os%lm)DDCxqYrgN$k6M6E0(ms;4w~R zus=k9U=;+CsCLd*=wJ}iQ|#J5>wNnTtYCpl2%sQ7oNz196>sxVdSFgNRB_2gg=XVA z8WV|EuC|x7Zm1Zdg%ht9Nkzm6AuGpv44hd$D7kO)LPl&%F*6-M_8Zm^$2kj$i0W#7=W<7kV)? z`!Z7oqTia;`jVE%3NZixg5g6UdnFaOZ?$ohNqHG@$Hm@$yn4kFrp+QmD#^Yh?h|*`ZVtw4oQ*30Xqz$LkUwknyG>|q>&Lo z>nsGULdY@RruqsIQaY7#J0k!BbP*cv;9Q;0Ul-aWPgMZznP-~0?VipGg8rE0N#~zT znFW`OQNSlUwZnoo{$xh0xwTIqQzoOL1K!(S@ik&bz)eS4>p3OYB6_k$CXZFqivf%5 z=D3q-dKu*X^Z&#v=QTBTtLF98OfJF4zQ9qGz?Zh)*>7_+Fm5_IuzTrGdFy>nZ?G(7 zY*GuSf0Vuw?OXuXsxz>RcJP0nx}bSPM^zFctP)KFYEXdV!cRz^|MT3}&01Oe9%w)R z(;x)D)*~LJCuQy5UZ*sA@FJ-VAc7N4kb|JhKFGKy{YLU&)J17_bDi7bI8zfZ?r65d zxafH2!@LD%@o0tZKtT!>Z>V@L_wYUDW&mKr^xG&8|I^#&fZ^$YJ=gaNm}>hsRr9a~ zT}30g$Y<^J zwd;_pc6E-9{nocu$~|v}ms2|~2XUy^r*PHDyc|>}4q=JQrawjeg!`3Frb3IhfQPk; zx@9Zfw_7g^Q{SFYa2*;DDK+!1M~X0)ud~G~*7~%42LQ@brkAH-_44BaDnqeHxs!e# z_rSUn#kEa>4K2f&=xXIRSlF%gJnkMk$19~uB}BTFI|roA3R1|Cnikj&523V{ZoT03 z&U9`f-&BJh3!Z9kTGAQ&yeJ;KGFZI!v67|0A#bO#Urfngu&Sq3%Pxkmiimb{Y&^_S ze>n<1=lbywMnX_D82wED;NT5tnOaXZ=gr?MFmRg^cWvEQ6(ZWqiDecV(m#i}QT>Pk zG5?y9cI^GLhIbclXqC$t%O51DPl>ua+dA9^zC-5OJ5^t9_x!?9cBCuLdo>jx@HBd0 ztF9%XYJwx|^Uj&H>iQ|rYPW1!SuA)UDG7x*1Rm7h``2hlo!Pt|T&-XFw~8Xx?8$Vj zTsp{Wu^9HwO2t^M+Y&x8v{IG=gJaW)*o(2}m;a_Kq<;2n4quX#%Sw10C{e$m)u4W; zXSLid*WI)sWkR;>Kj{onw-)U?M^#T~aRps>=ZBHd)<2z#i*7cDNir`K|D@?K29rhZ z8W!hUvvv>5+95M0U7? z5C0tVF5qRCp37-C{o|4lx8skF5+B!o zP60uFG93f^Za@?aM-^%m4ujY(yuClPM8Zm`D;EQ_$d9wy>=;d}7jr783RiY^Ie3Cl zet-;;=$H~q@V6{CTE-i3XNG1jT}j(2CG>!mFR{s*6_TZFn$!n2V&9*y#Sws>)^Kjk zA!SVB;S22w*rZ6Fl2paa4JNjRS#0MB2`eJn>#zyVzKvbDb7bPh#aKYhFiEqdy1G3I z(nXNs-Y+vB(-*Fy2tW8^S)EI4UR5+p@A>_&;s~?BTz5inoDdADPS%{}F&$*vB%2&A2f7xAFUAiPE1CPPQ_fVpI}r zl5^pO%R0QJ&5n`9=nE{(mi7`q4mp*o^)=5(RAUQsUa>32LT08?U=iE92GG*}24pE8v)2&$s`%yOhO#rFxS1bdD@ z0Q0a3i-sx^T$PNWNX0_zT$Rlm^lZ)yOi3Rl!C5RKe8yo4{-$`;5}5RxlaA##iWg+! zu5&o$Vs{i)4UJt<)xnfNQ~Gndtjac|Y`$PukYYH=%)TzYVfw3m0ul0)Vll1p0jf8X z+p~f)wpK@#P*J!DRUO|GMv^qgyD|TFhRS=xo97r*K z{$TA~Mrcuj-h@zf-ejZD7JqKwdGWi4FMa$E-QTP8IEiS<#e!yDER+E(!Cg9;S%n${ z9B$LNBy%qkRYMA>nRp%rRrZ{+W6N;TPRTfFi|C>OVqQ6pdnIENHVjFu+7d44=|0%S zUu|<09rskfCDySolC`1IvDu)(@Nu}1k<{912mPrBOor`40*ndaL{)`&wQ7`vNSCbC zsz|pF`)5dhQ%d4fWsnv{EKqSzvO6gh&@~w_Vu3&mDk+I-^p%CdNQz>8@;A9-jA}=} zc~VD4>Mdd@>&6DvG+Lmv_8(*>o2*M+7XuYzDY9Uz{ByL~BD8@A_=Bw2Rv%<90h9l& z*!GyCgn51Grth_VCX}^b-4EE_;`p__S+vB1Scrrpx)Kx|``Sp zb*i+mpNJtMpccJ@*yW4rM?$Cj!PM=$Ers&LMv%>YO#lzZr1{~xdDYTTAsS9of!+9* zLE&Vu(0;5*n&Z~#7MlxiuqZZSDf7{K~Yyg`mkRz$s)q9!4txpqSv13FcahWf+y^Xo=gg-U{cH*a^7;M`x~C7S5oOp)*{ z#1lcN3GT3;9!hI;+*6 zlkBqRV6190C8)KJNLDgSi9IQm?p6ZX`M<r6Bj)$TcvR~ z7*^NCfGYn1H{09mC)@T!n?2f=dYj?iPEGi5K7#uNpWNjlp}Rf;!&t(hx(&Hehz(`l zG(YakDR9ly_9cF!`%)Z8Ip{g?)xFGdM-*R0_}6ns_V|jg{lUMZO_SqO zNVAG$XcYCalu9iF}u zj?GO8MdBh~gsJ$utSpk$@ko4&1PMo*d`wh;3>@2uj_t0fNWD=^XEu{~on~WTe6o9_ z%u@67pMhTrKti{73@xpB3B9b=ASR8WI{7mUu{?{djuJyDTi*u-SsAa`-DPu`9UA%! z6!OC4Tp)7vj#G&lhOg|IkzI_ua{_6fY$X%AJX+|osb*euon8?XZGya^{A}re zTA>d#GSf-Ji8sqHG)BvryVF7c0YWClkGaK35%$TL{`6Q`s3o++Gs*N^iP#X2V%r(3F#z!6>HM* z<4H4Ky(wD*)ifLuE%OBQvk^{cM5Ljr6734~f_%i{lR^4xSu&kVfmY|dox0n|vVgE` z!a8h~P_WgL6N9MU01s^wnIV=WR^hT*CH+5d(h>#ui(2Qhs~m`9e3}463(77!kzTG=96;xz)*?Ryq=DF)3!$g zO$y@U)!5rI__LF5gg0oFrEBhK;@xhqmY3J_xXL4qGjub^&1%?gcT4YISDV~&i8oq& z4&yi>MgJUSf(v3BJx1`bA9OI4vg~5CKpu;^* z63fjbb$id$xS?s2XX=*PN$w+;1>j|Z{Z5;|X55hD8*9*0{%KR^)0-KUa^^^@_SC0M z0{G>}arZRtK|y^Y-J4T@Bx2f$a9>R;au3RN^2@h{593Cj2g&XXo)B3~>Z@6xAZY-Pj8TXeO}o)S&Q8Z|f)>v`ewHrL7ggmp!513CG+O?JELAY8K;a%Olugo^slo=Dh=5ZkchW``=7-5k6@6Ai zfd9n;6^u77FG?aanKfYMy{oJh>nG z=y3%6>0zbvBQ3xO|Mh6?AqOPi9mJLv=bvsWSG??Zt&CaC z-=AIAe#WF{iHM9FPVLp9QnPr!8)R7m8PpXbncQuPTSa^N}~& zQ`zj#lx=FcC|&Y;vQ)?K&HtEGFa3*hI%p+MSJ8R$6kSvIY#{6U7?Ahe-8Ka^&}Ml| z0h5)HcuQ7op%{->n@Y4?*wS=5TeU^tqPKb1-`vr3DwC(2o0Ad5TnTzZRo)$suQ;H&}Ldvh?3PDWvzO`VUzPwbC1 z`OuXpZ+zZ+(6Ml^wifF0(JA2LLkK%(4>&DX8eS=7bcl$tA0HYDZpC>hmY)$Y6SS^8UwiX{BWd?Gbpi!2!czGmCN2PG+N&(Q1<< z@12e}-wLcoxAhc3t2x7pI&i>1$6Tm+G?knJ7jAxasZYFfT7hB}z-jPx;kX?-XQ*q) zp9-nKWmrJI2d_7$h9Q((doeU~*vpM1jmgw$Jv!EKRfYKr@5fjBt_MLnNe36T*+qg4 z2SWGG1BZ#{0;Vv52A9bbg(tgz-ZJXvF)bWCdFxc^THMn*j{nc(b ztM&D=W&S)BbGca)Jq1jCJ-8-3>o~n}EO4ipn>~|h*s>LmLy2rPTc6C=OD2ZSex6hI zROqMdzUfMM!fB~gS?UJgpTEd?O45V<7Pl3Q&TTaEZ^Pm6Pkp(7dvCSR{M+Svi|h^O z?~}@~)+;B`9{IRZ8OXHTv_T&K=5J};E(x7`z1KbO@EZwOlD{sYMs#~eW(hL@mvTC0 zyUTwp9x1cF&iSj?&%?DJL6{C1E=4Iy-|ogZ)R?Sk%6jZb5%AXHavQi{#}RM^7V%?0 zS`TmvusY~ZZB!$Py8D4|dHlW@x_2kh=Wb>BUo2$~UcM)t8c#GFov%@wrlc@Cz4C>z zytG>hEcG<5+Xwns0-~>w*g&GXVUu`A6hS~{IBj0#XT*! zlM+&Wujnqh&-=@>o`jiSHB}7MqN{T$7z^tF-iKG*;&zDeXrTpK#Ij>-?nZ52CXKl6 ze@Hz^uDQcN1OVgkLIZ?wVBiz@8yA#i7_lON6|X6Ya^eLkp22W%!80djCO^unX`cuy zSLA>Sa7Fp4G(~vy4H7FdDWq`DqEhfwn)##9P;+Wq5rFC&408Ao(lSH{RZ&_`$}xco zMm0IK@=XTHB?SOgi}KzC(2Ry= z$)aNj9m4Tx$vAzwkOhRWa?aO3!B*_L&7E|D%v7=Dg{|?az)#;pkd3UJwB;_H(%;Ky zNx-&`g;VQ{8X0yqe=O!rQ-ZT|%786vQ8YGbb6;|NEF+B?PY+{)7PIYtcCr&Npk&*m zQpZ7v2oQB|MKJ6r5n~1w0;TdzC#iLHTduEylBP*kv_dP9aS>hB)s#S6ygE&WuMMGr z8dfSR%mCe|ND@_64so;M%wS+cRPr&ayr=xb>Z?tTeHT}SX)LzIs(DIsa0w5sWFlfV zv4;+?GD(hU)#@B8$DYMn>=0a$B_(?USyep)z9RNO#c%{<`ax4vgseA1vR*36#ve5l zd2kW^M9RIOCZ=nZXpEVG*Sd@^o?GPvYLJ<`()x2#TR9Y-?)A>=`iPd1i(cYD7M&Qe z`Z*g=h7%>WFXK*cwT_|@@1xHhrMN&`_UN>4WFIF}MaV zj)N=b2q6IcBf&cN7@=A@Nw4aq30r!qYb}yhJ+$h+Cee~zYf#Hqtl9#TnF=E5={j9@ z3In2UfvdoM$&@ytYP$F@?2&`Y>UZw9D##-1veSBi2w~)33JB|*wd?akacsRn3TeEk z6A2)8;)~HYIC)Vf1r0>m1!b2f5&f1>viw$>r$mh&rT9(Z6h7-hrnJr}>eMSMLitoC z@;v2k00W(IWZ3_W55&e{;#elbb{6+DolUP(#>0t>hUTojozJ+Y?z5@sY92fK^oUCS z%#F3zL-;lS$&Zr9yZ$coF~n>ZyxFbCG)fA>ICn3sUQrLtI2c5 z2+8ip{klaCJK%=WXE0ZcFx1HnfL|dgW&NmSd(AE?n&bE-*%21cYEHa zxF(s%=~i;qdiEYh0=e=)@3_q6Z%UnO!Kw2r zIWsxax3NFfp{!1<3s&_^8}8o+QoPS%4Y+b~nfOxJhm|bKCsb=Dxo$gN%wuh7)87~M z4Lnxx2-rPYopi*a>|b2^!_`+@C&T2XY^Ot`^Miwk^Tt8lZlbB+$&uddw|yOR2Ihi0 zb8pt|*^jHZ4QmqdH!1J{!VyKO^=b_sIcVtxE0$g;8g{e$SGD)jR|>E+kwhiHc!q0C znu`colHX~3y2izNY(Hj5Xh86?W$$05N7bPj1FnB>5_fF=_{EXq_A_bl_|y9idz;A! zk2ynZ`BDY@+Jy%>v#}RPHRLZybtBz%9{q4KYof%>=OHU@qZ$UYoSq{;5ZOD4GByzyAhw`8#AQ?Irq_dj7GZ!9qBrxALT0jZlOwocw#{eSn(mn8!0%_MHLky3{6q^ zb~p9XsCm$l))F)B>x|n$}h~g)$fy*h0%Vt`tr) zz(auu^enZV52k8PzpvCwIWNWvUB-YK^O|T>>_I1^9MHjkIfilH#rTFV7s;_-szWCh zy_$`?2zF)r2;C+{GC@kqLW2qruZSpVQ~E_!A)BGIv#OGH^ThMnK1M%GoV*Wpi=?$n zM)TmdT*|JW3tgy5>#WgMD~7idjn^rwXwFcgb|I2Xh~2BGfRs<8M(9AqWd^=3=zh`{ zo%j&b7>X*`n(UHT6Cwu}q~-?F2OTl-Fyhe4W9;hpi#h7Z14S^^cW>KOl9vbs}$;h|}pji>nHW!be zRTkH^jI*33wy{kR62?XREhKH1VHh{SThqu0b}TZMCroP3S>@-UtX_V_C%n|@&u*IF zIFa?TF~BB>0|`VeuUJ~3i6TiK2qhgGUB2ozb&CK}TUVKGur<^H zS`2jRibm8q(etvMRDjl|D%R5F@P9+Avd{*RWMy?+lAT+s0Ie=I+=;j-xA~P53}qDTIZY_CG?+s2DKxzVkQ#ZBNOMhr(G|tnRgsQi&jx zaki+6qiV4zi2Igi0zpwKL@6({wGG?yxOIHGJSB8&QKE{|~FPXq%FkUiP zDSNLvOwg@MCKsBZz99)b;VTqN$wqm86l7e9dikFu_n)}7_+`1?TIa`?!(!4W$NclW zX^Ch1*H^zKssHYSytasaK>Wmpv#;rS=kq?R3wtryk!M;nVZO*-2_G{2n3^wADxHta z7X8o&&-gjLbM`Vlo!(OmKP>zJk>>i))ABf3x9|B}*2}Z& z{=E_L&FoAJh<1Qp>Y?Q9p781ZZ<3W^keALN;+qwFar9A-uB2oYr`SN8w!`oz1$z5P zTdA0#L-gRC?7>Su;@Fm_brw z^2Ky^?xOc-(3x)uSHTKZ6h4emzsNuDL(|7<`YR9=9f>YS>Auy#1mXu$I9N-it}zv4 z2$+vx5d>xtZq_Lb4^Xw1cf+4eWX6|G@L_4`&Y40&i=o#n@W`l_2~B^eZIDsFt3-mA zxzpUmSYJ3GlNr@G%-y}6t&q^+RT&PQfo_v?u&$p69C9A}E^4v3!V8z$Ww@y!_9_;i zv#Q%2b*{qOFH49?8rHwq-~GkINZ=h!fcolv$LqLyhEk8#N7kxJ->X=8dA!rOCz`N! zb_d)wOgBno`ch_S-mV~U0z}sb=ch)H%^xGOLviz`7L!_P;-lH*N|s9V*rDHRj%M@w z6W5PJ@QbcMajylC$n!MraYbNCI$}=w3e0?fDi{N^YT@kryz*7Cd9Ljj15+ePy0k64 zVQs>;@0S((%i$|eC$|50I)6^+9>kuafB)yI?)&54F}t=&o{zWV?2k2$BYz}_b6A1V zrLT+b{O<9IRv!v#uMZ@x#n?zdsCty(j3wIQl^obb)|AD+Jb-V8fgX_xQ$>L4;xJT2%m zZ^6h#+5(;C_j;&j`{h@@QxEl1=@zlRP4_9w=EqH3^*rEwZ?A4IftHpoac=o}$DU;v z$BL0oM&1M}o+)9{ue%;Q4{KKW+#BYbWV%ja^`~Jh?G6k_IpSP9gR?>^WvZ|ks9Xbd>)zmcu3BbCQz+X;YY_oMJYE1bT?rK;g}RxbJ$S?kk5A)fX@h zb3r{>f_60xRyabaBc8l#50HR7Sh6d=4!rmM7|l_{yP=e|^hs?_2LQv?wiuo#iE}*I z{4q!gS^mCiM(&oWa1x(6VLfQA7j2b6C_P7suIoxzkXloVFuRW;*{F89u#Z`OQad7g z|2+~A0aCrAp43@%i*!|s!P?j9rUO!m*C*iYNG-E6BeltoWn#50uzF8m&V|j`$mpmu zv9Xd=U(1cEg?gGg7vYuccS(vYRF6#XixihB-c5t7jJCYiq*Vr+a`-j<8ORdZ z510^#$i|n=t4{z~2LSY?V(ga4`Jyblm4;IA_CCFS$oOc0`+M47IQ8F=S!=M;gA-$W zbE7t`2P=anYdr`@e(L9?X4uCZ#)Bz_DY2CbJ_CnFnL1w)sbi~WJWMu%X7>PpE#vYW z*&+#v>?3P0o|KLj+7=rim%%?S8ocOOk7O+R*bejo_#F<4{M=kmY9+Ys3 z#nC6|yDMS_yzu$|z~9H{_WkkYEjDN9=3C_2?Ka4p*kXjL$$w+SjW^jPPB$&opQet% z{C${v_5-w+Ziq*IQawHOmH4Q8Z;e;j=Yd6sAH4s$@VBBfTyS;q*PCOE>6T0!zSwO3 z>e~Cgz`qdkn@`3xp$wH0frM6`ws`~s`kHMJ2n(;_7M{xt}O?AvlaC8fY%oF~28#&FYDD~%q|Z}D!Uk!q zQZOHs)EKBxpY;$(*(z!CDZb=UDr<)C2xT%Dg)6J5D9ERNUp%1K>P_a8I!IoI|3sH|ms*8?+-Ys*SD<~uZVD>jwNHtH!cW{nn?T$uei$Yg*CS1dkSJHEmS~56i zBd3$OXP-JuwX~LK6c=7vaBP>=!NcM4X0((Npr0Xk(*J}MBHABH0RUlnDigtI8<$>_2*ed^ztVRdRy3kbE|be82RW@bz}SfOfL|?aj#iP zcWQc=-=3?Q*wATaPq!+>PA`v($rDo>nbrFs_cj|vcXwnm3>U`2<8RBXh?_xp%P<&8<{SMgNK z5}NSIId?RaJWXLEbojC4FITq->QY$%q(95>81l->ImAYd=y0**FT!dLaiNTwq12ql zz)C5Y04PL{u^0oPpd!LQV1sLs!yw;+**2lFCRE<33j5@nIO(+}+t8WWFiXA0s^yFb z+u^c=v+ufyVoib)$?P%@zO-NE;AbXSM)|e!`3fdMbJSE447WuUB@&`EEiO>E0sU9y^3-zs-2M^ zC#0|m8wto;S+9A7h55{~7qp{fdZ4MVO0}<6ab;Da8N*1Z1U1e5C~W=I_|VhV1yxcz zMm@J|OBLV@4j=bx;yN8KAI~tUbov!L&f2PzdAfvOzV`cKk=|`Q49RR1^XtTtYPdnU zRTZ^+=5mRjn5(4&V(HuXm-l^W>Er}*EGpHBb&&s*{D+rguP zFr%Db7pUVGK@d7e&32-2$|dScl`pUpGNcA)D3)*hwP}^OUxbhp8GVFO(ab_>^}BSY z$^1nLTIwJNoJz|m*^GkEC>%E#oRpd7mu*V?R&&{=B$XzI(wF$ksyKPOx_cGY|Cqq;CaZAd{1 ztrS4YR!|llNU6V_Csb>7QqcXa1JGKRmY{v6-N*IR{aWoZ3Aj8p0y zQ#i6`32(SjdTAvvFGMdKTvpaYQQ;o%F5^0H%!mqf%H)MkQnp~TF7q;H@C;xE&d)bh ztmR48p&{EH3KdF&N-SW{@8pWFNjJ{QD&2&C>@KB|sD5nm*j_7U0z|5K`I(2=&*uT} z_?v~7=q6XPR-D8|(PO0uEB*}Q)qNxY2zp~roUE|TQj#Onkw}_U;}yieG{2m7DJ#Y{ z=q@(>tn?6n+0e#(Xe6F>Qtx{rM<*S%Sx{5Uw+bXtA)mcpZk@B%Y22U^p7~T4=IH!; zd70WwGG|hJ!T27mR*#p4pqELFf2#ke-ftCWOFpi_?`*wzVygl`w)R}I@ClTzbS7b( zM1J`l!wIAUXm)-0v2vbKEW?tCve&A^|4ud*eJNW0O_cwIP`g&(Sf)>mPuS|O7@-=@ z2(EN1ov-11k*`Cwv>IJ4fK6VEP0D3!@HbCiVB;TistM;`_JAU$%X@jKq}Ndgz%?iv zvEGCT)5rGG(ZpcaWeV#5y7Z^$2x<6+ZQ`7NE^WywqCjZ>P$Dfo&puD*=l4S-e%d^R z0(ePe3u6_gw0$R_`K_)0TRL8BhfFBAo46D$q+P=IjRI+lW z>QS{NbJgENqwR(gLt1`=Q!y0JJ(+a;`4~{ZZV`U1KeN~^;YEKoz%uMyy;G{-O zrSPie5L8$}{=HHxJINyR$ogqWg0-HW8IP`+Q>DTXc8D!JYCL2CV~^N X4(zB|U zCf*KsI{rGgoyzs`sFBQ4B5&Q0uQ%4BxW{)*)n+yXe-Ol#S0%1Z3PldhxH&I)S3;O; zC-P2Or+Q!rv?#_9wZhW8o!c`be^Nn|ngG&D#ip`P^~gJ%0HN}EQ$#DSIIB9+T%~$NWc9bj94g7hGQPf7o7dy*lYLf5Upz< zlf7=ap(Y9CL=8MOZJ08y%(amkd z_+PyGLO+VnQG^U$SHn*n9vp5Q)Mp>anJ#5rfU-uF7ZHm@74Iz;_C4Q^mNR(3@_-DD zoaG{r{h&0vgL^bN>-!N;R*z(#?EcCj-~QMod40oTWrWYYp+wO>aKtG!CJ#u#fu+F)EfABFK-K^E=ga~tV z)ok)~{FKbmb#7M9st*h2X}?i)#&~aD6ulO`vw5EOZjWX&^5=9S_nE63XroN6%jxS} z%%*?mvN+594w~Dp4Wg7f2!xkC$nergBYrX?XsSjuT{U#gRY1>TeZfX_WQ4-Lk zN!UA;{yt)-eM$jbzeAfispIUs!0E>|vHbgPj^$QCPynN~o={N`eZL_ufYQ{a`KL0H z_=~Ea$Y4^3xQgqbO2R1K;*N^Mh@`sFU@sn;#CHEus2M8?ombwRw00qWFtfykv#J3?r6Z6` zwKV7tJZk2Qp$UpdQJ;VK{R+MP^gZm)k8k4~Uy1nLf1>$m(Q_s-jLzm1q|_CK&YOaq z(x&UoNIpq~-OkZb5lPWW^!=E6MfIIJu`2Re(4=ZaD6J!a4B7pl4G2|WO(_%b9gvI% z_4b!KJbB-I!=P7B!YdCesgUwcKow;nMaCsE#E3`u;lFeyMm+6{NeT_ED=O!GTCjB;E?Ji0V;{LrcaD|6q|G}Y)}siHm_iZ8EyR)!NHpeF67EkJ$y zK~xi~B3S1a{@}TMy1ZZ*FQ8OS&CE+KDsF+rG^(*h@5;_`jXV;0f5fBqxax>fn>N)NoHin zAMu7pEI1o0=EyTb@DacyLg2pWg-u2XI*c;eY8k)I%WQE2D^xA|U{!AUJ2V+?GQ8N! z1t-d(?S0HKwT9@jt!3mfSa1>PudVyHw%R+i?G;tMxw=+hwIVE8Y(c$)oWKhq@My!a zAZboF$TB#h=e4lrQg1@Er-$rdyMD#YmfiDXycKg466g!TO%jRcz5CgvoFF6WFwMIC z9zl*1LOuuOY|V1~=wiUI9Y}W~j`?lC#pWUBB7lO!>b>i(^8K?-X6yDlDW};8ZnMMt zjK8aX@yjuVpH_V2GAN;w(_&*C&(`@Nj0^AP=u1*0OFMPA4u`KaH2v;XXZk`15w`61 z+b-fkk}U^=6oF8&8^ce-ZUfF1YY#x1V>v6yL=``x&N=8;6K*;0``GjEr#C#%TGQI? zgCnAq?u5r8UQZ7wn|~S8rPjsZa~`Z$)OtKK^ya`&v6f^sD;d}gEX%({i#CKS{i(KH z@8k;R%u2H!HS5gRr0EZY1qJ)}dD`*2ZUwn@;<1dPF@y@Xa-h9-YDJUHsoE^3O2&Zz zRbUf2x&qcm^#KvNuW1Dit#zo*#3{rZgXnLQnIv1Xk-!iCaaU3kZpGYZs1fUWBVrRb z&H|xttD~|ul*QSBz0{(~F&UXnWZz9^(tiE=eIWGJ?*nam%$PkUpMgXrQ7MYcULx3@ zRQRdEOh;mN@Sci(^why>b^7PG$ompuQ|2|;()a4&Si6j+Eo#a7JtqO_u)LJ8QR<@c zH0Zyw@y0(LE(AU$(U#|Z$D|Zu;%)ww8|o4r>cnb+vdudAvIOi+c@nx;s7@Ncx6rC3FYJ8x*6LCy+F!_kRhB@oD?K-6hEy*}H7thu z8)JfpD-GH(Xr_`Z80oMZXScF1_`5G>vcs=Idfso$swldU-(KW`a_(9wmOn_Z+(y-F zPO`u&WNgeP$u)M9`we=n^H3tV#aN^C#SEt4AkrDLy4FD)v9?uue#MYMU(bisf}=P| z;*O&C*{6|9dT7pHxCl1y#cc~JCUZ=ws!4oceuebjNUhpRbJyI?VnC+Xss1*X^j1g# z{}_k$@#2KvaI_)3)T|Qjk%!`#3qnuZ=EJ=57(=gWsm$IdZawkftbJvAh)fV z4>}LquSU;C9d4Im#^+8nn2%$hbe6#k<}8fk?=h zB^=1_csF1y0fIk-two1PV2@&&rK5C;C&Lq3 zV|p9eZd}5>8(vLhxe=3Qg0WN=FyW?*`Y&N|izdLGr*-RtY1>@n2fv3bTWdY$rKdYl zdQn8Y>l(sY%k%Et^OM(v6$tHP;b{<%?>jm#H(-AfwKrmE6Hr3)_Bh&VvGO=FxZSen+ejrb|N)V)WyWCBs&0tK=BM@wPE&A+Oj%2?9aaMm(S>f^a zAm#RePY$#i$noJ5>^^R`J5Xo80;ensA#l}ry-T(n??4>Mef`dSdq0Ndx?Q!*JIaG2Zay_4lIdC=zLHQG=(P*Ly1 z7qsb)E^4U;y~nfBy{#nEear`Lp(LiHHuCRczuA!nO*w8Z!T+irPnPQ6CR->ues{+w>RhVI|$G7ECuOIK_u(Y&v=-wpyXy9)l^ z?pssv8VU}y0RVAZA+UH0FzLd55s*xt#9gNLC!n9em#WiV2wnJ9mRY};F8wvlv*XFS z^&?95`b>1lSGECcswe(mE80Q7pgt#7^N9c5F;|6r)|Z%jwug%5dqQc2Ak=$5V6`C? z-p$_HXkPhw&}z+Tqfpa#kl&P^CQFgQ&6%sOf$A-*g|CoF8-_ zUvO&r_$K!MtRfloJE+zzGKQ{bXP!G7v~yx!ovEtM7)bjaF?^GUcqaDnbjr4R`#y}7 z3>gDvSUz%w#bv55wy@DuQN)}jr3%(DW(%LSU*lB`@7T9Ii?{Aop=cxh3Slv(gY`vJ zrBOn|5WZ3OVoneFw`E=$v9cji;!CQu?eN(RZk_zucaOE1@n1(6C$(%!G|kc{%z{yN z&~uhI6yV+;sfuTbMI^~i54+)xx%1K8}S_S`~{>e8UT04G0f&rt0 z;+B~QWgjcB8vAy%T8+3!A-3N(^?!~eoEZ?JsNj)Vh*4c(FZiNiH?o>vM(2kqqYz9T*tLoo$2Q>$n*<^MHI zSW?n1%f$8$`{`9xRbyfzs~IWYI0KwKNMVg~4pzw#Ds-rL^%ib!z!?F^Sxp5DOLdNv zEbo|Wz@OwuOF1ibTiT~Yc`-8vZIUSDNju%dR2*+uNjEfLaSD8$Z&3;|G293--(P4_ z3*erp3z}_E$ew4Nrzoa;wBE-9(h4$L`kfUliuui-H(x5!zsxC*cmcZyM`!?ZW=59ErPd6D3Ub|%YR)>U#M0%f62fmBn;h*Sb_oG((Q8MGJ17l zyfeB8YRoe}_;Nj!+u;M}*lOd_1>(J%fEW;u0OiCwv26y3<%iTE9Jj~ngFOi4KT*o; z9jCwblI*5SWa83Q3L5jU#7&=#)qz!?N?j|Dc&JQ3RTt>am~JOhP}IF!F9&Z2TS@e z>|S$=Z>F>&n-8wRx0lc}Qw|*O;3EgX`A_t;8zKo27b&n}ekx4)=#= zJl6*Y+A!*dsQqadw!^l=4gEEWXnXx<-iW0~g`)Qz9YAV(OtlVAvJ4V_PZwqirC!N^cGd!^y;hAH#r>J1lHbFsKNN{7Iobkl%5<( z*XZd}%`OdZXpQNXGS!@yw_Ta~j)ijiNNnGI{ZmsCkS28=HcXI{ZS}BYD=GvZ1 zj4G1VKfiCnbWn4#*QJAPz%x2_%OZn6v?Tj7?c+Z&_qdVv@^>oYB@A&DK~Ltr# z!vbsZ{E60v1z&cuX|oZ5wzzuih#kCmHplp*-*MTCfsOB=x`VrMxaw4?X8Cj9ZW_A9 zo1cTs*^qnw+Zg+yWxqKB=%?l7Ea!bya*J(wrrGQZo69D1?3)RJm~1-p(hJw)2A_Xt zH6T5+J>hfa@q0Tn7PwhZf1SE|s0weIq%GH%PWFWl@#*$wmPhs9&)jr;bR|G~3fmiu zdCDBiNZzH+$4l3@PRJu5wd+Gx@CXtt9G|zS%@WwAI(s~U}G2yl~1O|JP$}&C$`@v-<>URZvL)7+byTM)Ex*v zUJXLNs)4RO+`10!Isg?&%5XJ?Qp986jP#ZIN%2o|))SLj-=SvM`Wbw*2X zb3ST{=$*K9onmF1kzNr5GPLoe(74+M)O30SnT1yjKyUVB$MaNIn>nNxa&BU6^Lj70 zSCqbC_Y9LI5FXdeY7yUodPQ+S0E5LFdNNbNqo)6c2RbP%G36aBa@MKJZryT>#KUrg z^KjalvRK{f2W^6JjS&V=_9!d=-O~YS%2m0i1?G`cRP1Y7wZ^5EgGJ9psV)KUe~b_% z8W-mznoKxYmQ&Mlp@xTuai+FVD&bG7te0>umsA$TCzu(Q2`lo7koj@t#>BGxD$Az4 zT@50aXADmeE1wm2{&73+cfzzveK46G~!G%&sia ze?aQE`ZIE%zv-U*2s9Jz{KZOVu0(}iOf;alCs*66k(!*}LF{VWWT7c8Xyvh>RSEGa z^TeXW8k5piCE;+yt+fDux#&hNs~7cESh%Y&>j1=c9ZOi!EZp_zC0&bEM0y`iYi@2l zy2y_+13PPcb6@cT!OSA}mt;@z6poxzH~_7WEv!qn_6S$Pb|e~$T4_yu!Gt(*H*i!? zV4p(8t~X7v9w@|5`5PScXHbw2jRo_#MQinkJY?#;r zBzD;}PS_5Eq7kfSkA&uRR_qtHc>&X4G%XaX6#&zyr7|OkZ{z_@y&X++rpEcJq7MA3 zOQ=4P2JVTv{^8I0*gPxR4NW1-L63|MZbq^bil>S?^wGSc__cuHyGSTPz+HQ)N^<~C zLSbC0eUVtM>51$JFR%LpY14pk+E1Xx;GY0lKY&7bh>*C{9UhI{O3-j@sxz(=0=66@ zg$T1VPuM_AV)W_>vyo^^5|Dn}IS$11g5jZ*5yg$Cb?jJQkgc5;%;C%;0wSC5NI<3+ z(Gs>{F6MNsx~3qgL#U1LBbKKG#h10M9BrhTCR)!f@qLXD$@?5e&dfe0^iGQ{i2}OG z$Jn${dRn$*4nsLzCQ)9gQGN-an4JxbAmwZ;shkrAHMQ`A+NEx!oc=YXPi}owEu0+x z5wKy5699|S8yp6mC7LKVBo3}- ziH4cJs9&!~v%}bGC${tWf>J_7Ve0jkS;p(YPiqb%f2l^&_waPiV~Ob5YF;Mkehupe zqf5TXos34EL%$xcqq$O~c07=YPO7$h70zaN`0V3q5TMh2%Hdw8qVdtmbFCp{uqZKe z6TO)TL0H;Knu*&9ayx!Dv&QyVJ;AQJ;M-I%2*(#h$99Sl_w9 zTX%Qvn;W<_Jz8UITF+)nHKW^YF`v9wx9Pn1TO_Brxm+L)$9&pb;7#SW{)hsa35T3{ zPmY&ud?pC)v4NCagx(~Ngt`MH-Rp^sIBj(!e-&F^I|Ij@zL%AK*d<~d%uu%*T=k`r zk}~UNh0_hqSG5Z)C+d47#9Z0ps0x?Ae5Ok_gl&n7^1AIe+~UV>)E|bgD>M4ayrj~1 zFmO!pYV_~UA-3D1k~5aw*G?-tA>XhEHJC=0L?sJ0htprB##qDGN zo>IMhmzKws%N3s5^|OuSyQJuCvo?jp8zQgiQ5VAd z;u`!haSF?#*S=(M2{(SpnBRL7iuF+&9;Uczh)Roh(DDf27?K6udT5fzBSDRSol)!x=w8QQMA`z=_o7ddpTD(s+n>W$cp0E+iEDTx50bSk!g(Cl_NUn9pP57Zwe!A3-Z1)Iz_8IXU_@FlJN;Be2JqRa{71=U*yA5?s4e> z4ks1PXKs<*Lu$Lo&8ctbX7Rg4663A%MdNNwhx`|-3u?QUEb{j)mj#mw#|!yr>w_Em z%UaaFW?M3lEAYApYs<4S9Sof^c>jtw!1gOU^nWBc`&-?xRkE%(=ZCtHkDNn8@T(eVCzlI_w zwhGBmTf86Vm%wX_rrHvxC^|#uPxJRkw=bCWDQ^e&miIlac-|vp+pp7l5+OSrRe&2q zo%JVKp2usnBB`wY018>7*N$ro`C9@sqkW^P837B=*1vww;k&v;^y@)3&^{-XczkC> zT(1{)fE1R*k$Cc(`xD92f3W~BWUKN7uL`)PtM6inRqheogxRAh+=K;AS3e&{iF5Y2 zW?H@36pKSi)9GeYUYvx&Ot%B!gKW1Gc(I>POr$cIQpK~^hia;_o(Al;vJ-WX%Yr5{ zM^ga%<)lWrI)CRF4t+pqh0Nqk>Xe48vTuIJ=UlU`nNNit;Dvm}MVX&YD7u5#8m#c- zvc@`ss$7RWT+YWZy3%?YS~`X+31%SyRs88Yor{II+SE;ZYlncH-Do~U-E7AF(-E-O zZ%Db3Hqd)kdzM>vwXyWpH0o$8s3gACp)IJ6;OxzZ{dSLAF@<&CjsEEQTQ|>vJD`qx z{7>0>Ok}&X$(aZ9ZtHb%=TJ+lMePU_4Vg5ItK;%B?S+>W@dvxM@rei0&w?}N1M51} z)wv3=FaNRID4l`KlM0~sbb=grkx>t9LQ~7eT2F{S0wMWe+~2dF^x|*l{VIJl3kF$cyb6fU{jKzj6pW2~JvIb8Q_%Ocn{F+%xazJ{M$%3F^d_QN~3gLSXM(R%M z%di0)4vZ}t4;DLFZuSE%s+Ial!D^#FVGT&%ZZq&=o; z4Me%vSmboI#pgHJZzG{FUgP~wU#^3Zk`Ego?=rZtwVHWVW!1V~_~;vMdZ{d?PgN(U z>dK_;{u7kI#0p!d^Lnt=n@qmx#jk-=c|0C;&Y0^UFahqkq7|j4=H_{=t*oRl%1m2F zeaBDzgso4<)uvPvyX)Orf2|xI_EKKkp>>bK2p!%bP3%rJCF6`W)6J~S^9pmOy?qZ3 z$kR084s=;2-7;by+3SWv{Ezi~m|0e6O@jHlfS82Q24_pP{}3!JR2xr=Knfl^*zfhvzGx8-JfcxhRO{mbmFF=Nx$ z15WzZJLED%o&5zHAB@Nh(o#RrzdJNjJudMS;By! zsC7s6nBf9Jc*mXA$M&s6xbkv+MBQY4pvCl4o0y~nsx+|j2`7vW$im7xiz8i`H5AOy z*-N22X|TOE(&0Qbg6Aa&FRJ}Bqp=Gp8$@w4>Jz~EM2%HC!H_to^=>k>1R`Oe znWf!uba(G?st`J(ttLV|Nwt`3u2g}1I-2~X+6&Kn4#4z74mtaqcvKu686rKdV}Jh9z9>Wo{wPZaUXm-YL=HXYBlRf=-lqjbV><_0qNe{ zZH;}=FmSo%sJcJUj6>(wYg!IU+0MvGgqeu=P)axYH`hIhcu~SB0^2CmM+s`pips*0 z-r*C&i04_B!>C5{0>Y9B%iNJWzCof1=kTDfQQjMUnUDLGIr-R^PJ)p9#E3Wd@%y== zv+KYxyDUuVxv%D~1Yuf;_MF2W1e}v3*^`jfT3I)BT34folr&?C^71mm!kqj2`wgWq zI*C@)C1sX^+D_~|z%Yc5Yeyx~=g$3B$ zjP7T*9ixp8OK3A+T7N!6^lqpsVCx^vj3#F`=^;*PKvSDh_z3C)lT`Rz(KVOtK=1l;xIw=Ts#Zrij>E z^C&v}q9TM)>NFG=Q)Kecla%!jz*KmIa92o{zevS*9m#Wy9ztBQ8>t^pD%g0P2t1*I9^FGqX6-g~Z<(}sCK5iQ-c3nD`+UmthR z{n=9pFtKR(RVQkQlI77{@#}Pir~x!1hJD9vpdKDj7wcV89Qy3P%6eN{SGNHqE#gO< zJm6sXXU8c)sZ`GR)OzEqheAz?;97Jq&KFse8qvkeVXHTxs&n0;oK<7v_utp`z4|&Y zeE`cw9d@pU%ACA5T--}9YL{r;js%air>Cs=Ww%WC6_tf4hq1oagL%&0!WN>QP4WN&wv09*OsCXn? z%m&!ktyGkpOEh1s9}{$*(8%j(p0rns1hf4zg0Andz(=Q+RW818ETwAJWbh@f-+1C4 zden^%O4B%5#2bIjoH%HzZ_fP|ts^+Gr{)Bq$vUU7`uzLCY%NT&8hZj9-fZk&`BHyN zKyhOj{bq^c<2%-3QbpeUHlpRD!b;+znGI~($m&U^(_7WfN6V3{CmLI%30i9-d74#c zUF#Twx?8m~apv7|HgDR5n-z3p<2kc^>9{9laKZ15)l8PqS_(R+2V<&QJ$>nWVVSBq zu-2-4Fc7Q&^mn<;F^mdjrYRTi>~Rt#HX{LR->kec$JU3r6;Z?g1g-xPh? zoQ_6|hQP_^h?|jNT3K3Df}Qi6FBcRXE{#JR*5UL@sxCQ0#vuERqe=A&euihiA@6R& zbjQlVq9%B+$&CKLv5R(Un8K$Ghpi_ebjQ=VK`TLkZ=lN}Er(h0iev-M9m+|l;`jLW zhxCbOO_#i~u_&z#SB}SZFO<`O*~OP@5-pGOd`}#v<}lQ%Tpy4GH8&y9K(fegHfvr< zWr68VciY8$eHhv$bKLsWsj%y`=v$}VXXv$Cw8b-($4=mE-ND}KGtA2Q3r&z}#LfdI zu{JYst^J|6s4gx|cde&_ET5yIDQ@&+z17ZKV23uUJ3d|acm#RqZfK!z7JhU8&B8{1 zJYlLc5l;ZygWwc+E%dFdvY1+aW?ERwm%AVsC|`=sDw*;YM%r)tP<;~no()}|3J z^j!s&6rJVx!|RI4f+&j z-Wwfkw`yAQqyaOrTY~+MB2;qXhkxT2R?ix(W1=1#Eh#Pg-S~o|QeLg+&#G$hXvMzw zSNp|&i{9(QsTrTGHM4U+o&(#;U2?mc(%8_^8%j%ZDk{cF>-KL_Nt=F1*PA?X5jQ-q z6dzF(H0js=p~vt~exO1Nx6_yr4o`mqkEMFP?Mr2O-a`<$KHzWQ@ddIE$?6?+h+wcc z*R`}JF67C|Q&=^jg%cx`%JwXx^(9||VD02Z4MRu)ik`uyY5hE_0eB>d1riv7zY3(_ z5@p0lpgs#gml8w9L&B2C8;GIBFs2vS(^k&l#%qxJ2#_rbLygA76N%yIBb26a5Y5aV z?-|9VS5PR;d5g`B{L{c@(32Yfm9YO6Q2!7R;1XAH_`5RsX%`WJ68U3VO$p_l)?P;{ zCG-@gyWi}!_pm9}nQ7(SkC#3aHsU74(YT!9bZL1ofgCUHx0rF-^q#Q+SKKSr3Tplv z?=D6@RqQC^#-cFwX+K4*?iUmjTg3#01u4$be9k#+#+Yki3U%rg^C2lzoW)xwl*d1@ zB8tZWmht>iaqGCUairO{D}x+W!=3{kJ}1wH#a3up&9hb~rZ#fMtNO>}HDCgEvTUE! zd=^m#!WSyiN#<6fq?PzMAW2yo<1`u3BX4|-^<|d4Wf|qCJTHDrx@)gNrIP-`CaY4e zgA4S=lr!j5y$|58D;@Rht4Kshs>*Sz>_hD^yuR-k00?HLMEeS9Ct7RyRQp$0qVqQ9F+qH&@^qP zEy|{im-Ll=&K6(1>@}9f8yt#`&bbW(OFy3bpEwj92H~VmEBwUoX&hu zBJ1YpI)uVE2bP;2g)gocs_ET)zGG;wAvVFz7mYsn3xOon$i5FuPF3&3Sm$n}*yM;c zd2>Y*?fw~ZxY?dS$AlP$@&4%eg6J8uRiCl)!Dz17v+W&OBK&MBtHv32)G9IMn&H%Fa4x4YnZg+)A!!Zy3+vqk58R zbAthCJ+nC+x@;YZ>g?xv%UmCF59NtsH!V=jy`G|0t?RWq-gbE$rLJ+=TD`TsT6B0j z6V?fIxXlqczFGJHJYSL>$DTm32SY*AuMHDCFFoj%ubl|_!^O!qlA9)?SI_Z7RacL% z*%01Xw+$?&2Rz=i+&cBJNbiS+b>3$$8}hEfw@ti}h%V9Fb51JrK~ib6reYbM>{jpd~<+Mbp z2F4h=$LZV8ZZek{-S15QAuven^4Z*-WR@{1j7g7@_3z=KLqI&=_chTfYjl&Lh511Z z5Q_?n6I9pRk@f(T`Gee^6Lg(bNiF6ZR7=N*k3q zUlWDOR{mEZtw2o5d+`yMuol7R>fB%c0w9G(Q!3F1jRcD?WVJsh(2zrm@38z<6MD=Q zxQLZgt%8G$E94TJ6hK&{B$-t2Y5S8`kR9kVBl2@fmStWmiA0|1ohDwi7D*5DSvWn#PcYJbav(P}X?Z zlj-7!!lI;Q)I!^`s)W*vbzh1Ma`cMjSW!=ZVAs+nZ++8(##4{?1L@#k|Ma*0;@{p9 zmAQo#lIY0!{VQVRD_98&1!94*n^FQ5h{Kb;Oa{Koh6Uf+(!(I=ErQ`hspn?`fIXGi z798a8#+UB)xMHn!cTnlm#-SjlMd!f{>`M7`tVE+U!6`z!nwB>J^HjHp`r<#p<8gp-cTtaU*kM?zxwtp<%|&TL0#OE(m(aY4U=CGO)VHDwlA$#Eykz%;8nVc+?u*@h>qQq?9W z_ms=hVJ@f0xHRP{Xwpzh6_aPp1VJp;$@@OPrs;q3A7=&lJ> zX`DM^fX^0QmAjGl17U{@d8^fY?l6S`f$`Zm28-}PWP7564LIW*Y0W<>YVCm}Ft6`# z`t$E`>W|y)u^;ZRXK4oRv3(Lgp8`E^`G{FVP_91V>0qCJSc>o-e`sdctF0%8JMDp< z|3B$R+Ec0xOulf-@_&1#o^@x~F5NsE)Pp|jeelQvZfzz64+bo_Zj74wHH@am_hK=f<=KHd*)9F^2&TE;M z-mj{!kx=L1F6|y6{98|BWuHZXXcs)jNHPEm59ij$@6KJGEGAvGoCZZqa0|)Fa>TN$@s(V7f1^Fd^~m4sn^jP!^4QLoHnLS5<@pRc60KUSLGC@mKl9(2V6~j@6l%}sq(cPp>~8U zbrbyQq*P_2Yz3DhVXK>BDa`4cdP!`Y<5J#e6qzrq`edQt z6W!xSzq_#8c7KsCWD~!YYyMqPKXr1Ay~n(ud>Xv9>5}e@f?(Xh7gEP3hTd?2|+UEl5FY^lfft9hCWqoM~;>FHtj2sp*bC`Hn zj8bWmGfc{#fS5jo+iJ3v3aiYBbp zL=o1R6`V->059Fb{-)0=9IBR+AB?u=)5p^m0jhGBi*aIJGk{tqfZ=hNjbmqSY4@XX z#*h9wNjBuFt41})*}PH1e9R&w>zr9uSFr0gO_BMUY$J{CB(VH3jT@3yw`W*caICJ6 zzB##yRF#Oaty;X%7OhUkXWJOuvE)c=x z2K$7QO$91ROBJ80SV7AONqN%zGI}=sra0KXcJkZkp+Mt#<<;sHIen4qQ!s+2tSB3E zoe9mJy;H$fL6J{tgl|py| zdBh5DKKHbp|L!COk-aOlJfyksniTLm&(}UruUoe~b0G8nA@$N^C>8!nCXhYpxcLa~ zowlbvsr?joAAWBCZIeaGvWp;g|IrEh?!pkp+?K;+H`miM%&_j@tE>fQ)=>R{!-V^@ z%wCk|d8f<>5qo4(b14PvZ$b~@u5*8!gHam;cVxbU=F_Dr#KVbc3YgCeco&!2Tc}Ms zWY}pko}M{UhMiO1xej6zPuXRL?hMBt#3vfA&*Jt{U&~cQtH(C7ICp)%v>u3z3;cpG zXnjQ9Klf%xMK(y1{o07K{bKl*t?=iO#Ddt9){&{v2d-x0nU&C$q{Mzsl=!f5Gvwtd z#rx6M&X7q)u;D9(#zHpP3Q~ItPty;ulwrq2pSxgBK9g6xCwB#b_B7ntie^OLu%Nm+ z7ALcnWP!Eb5}f*(HO`;t-I;1%EJi)i9gyGTUsSw@tL-5t+S6Z`>%Avz;LJ_p(TR%L z@U^Eb-eX@yy#(DS!r_Z2FmnyAD=Y`Buk9Ekxb}8=>Uv~()9r_der1NI^XCUoGV<0} ztIi>~4Xj}fj}zr}VHfr79~sn&pYSo_w^z>~Z|$gMT@TZzE76_9B5#5%@GufbB~`MT zl*1s=4+f=IxSf7gBAEnBp`tVX~Dtg9qyrjrg{%%i`+^3Ub&W$SbA5{%J zEq>pn-h2F&Du1@pRHUkZN$|ZIiOcnPIwvFkm&S5&mL4cPRAUWA{H6OAdk$iGU_GVOQKXezJrCdagAXE${Jh3~#XtYsW7I-OI91q5V zi%?H9WrqJo3Atfw>KAc^!F=H$>H12iqP#30PgzwyXQ6c$WvZZ)!f#8|(taCwgg!3| zL0T$zyeMlEjA%)xrYNc+s#de;AvrrZUa?5tkou0E%$Uq#GWjt|8TeU{mv%To!K*}i zAJ?PoRXfy~wi+IVMu^y!uzg|g&lCwN8d@*r$COv+A1JvPKp#qbN(!Ka^ykYOMI|ud z`-UK>He*HtT%abHq{=<^Tm%{8D{8vC2R19m^l{4l-YKc0HRsA_yq`3Hm@vB;b2=R@ zL?Sen;0Jig>_@ZK#3zsvS6-AI)H^PVubZIsT^2|{Y&(Q8myf#A7dJ)wv+L4J?JZlf zbktOz5W7^_!Dq^Y6o&2}2GY=5){O{{BR%=SsmDw{6AKqdGPY>;cby#;HtYgN1T`>I zMq=pcK@+lEfq;I+wb0bC26CzS!3nm@JVl>&&5HoH_LSuy50mTJ51nmEb%pzLuKgOVc9=F-`DzdQ73G-~ z`5OfHrIZflAG!6+t%;xRJ2K+%1!f#C;q@NE3~Lp-oeLC76z2y;cs)2>j{sNcj%oT? zW2uIdmgmnjwFCYk6gv3Ui?$zbQnZD09XlQJR`)9~Xxcz-zmL`Lvl;YDxf@;2L7(*7 zoMhLbp6-dnhVFBIJrLiqRF{`l2TFY+xFS=FW|&@D5?8m!LXc8_rcc`#HbJt-{5q8% z67|iOOTEaC+5JCN*9Vmy85h?7?zsQ!FaOWucfE%I)HMw#rgo1lV?DuJ9>KRw6+0b6 z&^~rW&)7m5cbFg*NX*ujnJy&iw8SFytY$ z51+lTU-O;=)D^7HSg;o51=7DzNIUfN*L>q<8qQEA>~6`adsPd*9Wv8|Zif9cjA&l;x~MMVaKYI5Wl9;Z(HAWZjt9qul1lqnG!bASF6<+^azEhL)-6EVQFt%qB0@tb6tr z;)VB~0&%HET5sFR6>3n7SB}i&dvflY|L7CTz1NdVy0F-2+4ywldaev9n)+n(PC+)- zHTYbkY#+sCAdVyHn??u3vTn|}!G9dT_oYChJ0umd;x$N5RQoVtTt3tK37g~gM6~wo zT?13=`)9TgancD5TARo`dfhy&!o%k)%QFmyE-YW7Vj2YoDXJUHfh^^jBzloxCzD}n zszf%BIUQDLQyn(>K#6+wfPZp$S7JGDI*}|@r6d`hwo)jevKpHj9EL2PIPK7jLYXWb zgN}))Qzo5y{*ufVKKtyP6kAEme7aZ`m3QE5_!|-))tn9!<8OK02JkcRb(V{6u9iL- z3?oZeprBF)WsEQBVk1ecpc`0b);7EATj+zUry=e6YfSlmEQ8fr>eoGb*Zsn`4zo=a z{=Vi>4wjHJnhebZfq{)I(0-Id+?VqPAsu8k!kT0&9olz%fn^>Mp8f=yRT?BUdomn9 zQs&2P*2}CN&AHW6O_SAfw$tufT$C27EmmubjiD5;-=CX(n6nTF%}>Wh%dcE!1*NYz z(a+ip*{b<8sUalEm@E)V)tbf*Y}{{aG;m|Gr>4a6%Btop0ZlR^|G-1vHKd;}kILi} z5{F4npjOB)nb`Xubq|&si74-p%1H*U7qc$6_eIvKX~UON4i-jQ731Z{W+kK#&u>o;B<9whIy~K{fdp|H5V{wv-fZFvrII#Up|WWrOmp8b>Ka9P&`^qsd@8d z^Y`n-L)M+7RzteIjV#Oc6~iE^S9Ow}cJVw(IJn|j51G)YDYo~;;csGz@<)SL_Bg50 zbKNvpV|7K!*nH%`S?>rJs#(wG{~4<eONLB_y5l?#P-m*)Y&**myN0S_S!+Gl#v6Wuk> ziIU&=4Uh!COY_{0E7qL$f40wjhdp?Ys8aywirFva(X45f@e(jbv>_NBOf}miCGo3af{!(6urIRYb8BB zMx(s%oQVyF?Z!O$1gD}R93HdCb5Z>4HB~gE-F|SpTEqEe&UB~}5!tRnDr;*iDpKt> ze?`QJ3FBS2TI))U)`bsL(tv3j_SHEF_P|VBK;Oo9ikzmUvYrQD;8-&STLUt6)3|M! zbLDeBbf31yaN>Nd)2%JFzV+1+zs_9v;ED82i&puPD;SE4$>-u(%EvIC5Xz~WvLR&A zEiqK3sQ}a;4VCztoWGVHZc=?0M@icaBT*Tbbjut_J@U&8uaGCfPN^)|X!jXAPBcEW z7nv%6EK;E=$jt;*W}6BlQIpD(`Of9L^fqTI-F0Y#)Tdsx=}-lfCchAtu zUR+6MT+0Vhc%OwN*9P^6CWos#aFq52UcYBl98fUHorcdGOqk0er47i*u>AXg2jz=$gPk+^CJ5)U}iNV=x6X z5CXsE{7zYEdA)tPPiq|Z{yeX+cr$xP<8(Sf!12`5*i|6La15hA(qWm^Kk{7FNAjt$ zvhf6n_$Wo=Fus>^VF{}~)~%|zmxFOvG&HO+`t+8Qn#&u(#o_PA%ziSF$#>9zkj;scSWZ9pP)f#q{SVA&zJT#XrG(21;K9ZiTBwN-+?unqR2|y-sp@pJxMp z6AMQz)ZMunxHH`S>8ikM7^HnQS?4)8R?N2AbkqH^)WLvZ`ke7_xpmT7 z+xI1_ksXR>@129z<^1B-Wi~rL;PG>P*(fY;?P?eLRGmo8`t<>=x?`c>;^N)n1sm44 z(1~Bh@LsO_V@jXPMc1Do`F!VZ30JsY$g2HV7e!pjx`ZE%7TP?h%UukSU*;tATD@;0 zbq@XmW-ckjT&KA|{}OFjpnJb#iCEA!JHT)GU)*!qHCWdfMqA_;f3(=h>yvUUZ$une zjHzgbBu1%>_JM3)+6o;X^q@%JwhV>E^i+@h6@xvLl2yvwS>Bj{7?+;Y1d+ahZ9j~T zrFKlN6o&3Z+zdI4RB#Gb)p{p$Y>dC>J_R?_pp(+eI*;B z_SY$+^5hdGG9<}_Wl7+BBk=}PD3DB|5F!Zjn7%xVFHh6TO#}h$69U7F(K8VikiT^p zt-+|sh)3A!4E|78%FNKGZdN5k(> zEcou?g%PI0+xk&%rePL#&9ZJu)|Q`>v^ML6rlR><-w>Tua8YFW6(YP=UhFa|rzIn^ zJKM8z9umzc?3GHaU49#caa8T5Rr)HHN)4J$X#FXB<#{V*tg~PT>Qs(-?C)IQeo@s% zCcSgB&@S_cYOB*Kq`PgY)McU)dSt^wq1Of$f3)VGOoiod9Kx^1dn54mPZC-}v+!sC z{ds~qNyeS^;wr^Pvi$?gJ%!+?>%WHnFqvm#YrAt%jX|TRw~u5x7;U`id;e+>^E4wq zwR_id;N^bGIyjTA;u_M%(;ptDx@RDW~9GM0a5_t`2aNiQ$C!kG#BI%KNF0# z@ldE9g-?N*?A#o{1LZFi+Ge;T>j2G0Q(xb0AM1OR0=4dU>Z$e zFRmI1NSkSGI+ed^NfZ(xjiY%^M;p{O4UYh59BZ4#)dOO+c0oJDNor-$jq%HF^nqt@ zR6P@0{ZO?ybwqDA|(dn5LRXMjMpaWY)pPy7h_M9r z-V$XK=FQCD>7J*u(N;vGLTfx&<-qB-;^gz8x$Pg65&OT2waCb5cF9Qrkg)g{XV(|H zSbIMNqyKHUd@v>@6MTSctk*)L+j&;^sY`ddEbBF0(VCE=M=HCFqv$0(-vGD0+PN z_RQxOp~|FxxR)2HhTY9;G(vt;ka{N({!-@29fPLi$GWA#I#PSk9x%UR>mdCBg6%awC~!<*4e&KAq#Ou~ABIt8#HPc9oYmRcwkV#;7z(cW2wIKii)oM!ZW8}AK#tiL zL5Iy1LfcrjVB9uy=`zCuBDLAEGNcLH>f}{}4LX&Ue7H70)!HS@{7#K87cM|4Yq@fl zUpFe52_jOk1=U&3UU8F=28p02Xx1IDlc`9(Qt2TlQxh!}#>+#wRD=110T`(tuZYCD z6K;&+C*<)XCgp!x#z_6ncA^XS&3=&hqydmu7_pc#N#X^qMWxLcBc&L{KuKv!qL^#K zBHC0wx|CjON|r~i-X;YM)suuJk}lXJ$FB`*oq&LH#R7=;TDtlScu`pwh=D4nCxr@` zx&>9#RAPhjLAGeor`6HxJdc_odM%?H_Y@bs61_5RHeqNukucX^622EI~*(& z^)c>bJ8Bz_4(6mrDghw0#(TQXULc#bGLO-V zr*jbJo0n0mU2>ScRC>lXtBASAEM&a+nUcP~iZ&VQxV7}xQ@M$mBI;SDiT=7L?Wlhg zqJB_5_T2k-%i+?ccPi?a#>3YNnDeO^j2E?p#T~12-zU4L>TsFgCWD)vgkdB%SPH^w zuB#amfBaBN9KJg{+;+8ROSpFgHzOR?l^d@06KI}^Kgu@#9pEo-LMU7R>2>4f^${30 zz1wxU9udY>dfUOXVNS$Fk0;zEYmfqmA8X&|No6R%?Ecd6B*nC8P!mH?Wumu_qvXe2 z>`zy58QHQa9Nr%YtL9g+zG+W$L`7R09Sz(>O5Sr;OM#VaEN{YcJ<*eCezJkEDW|t4 zpl?b}O-`6PKr~TTY^V{Wdg2C(<#>K%jOuOb-)b57m|&KZ*1r$i`I{nyYm;Z?(l>W- zKn@~}&yvh=G7YwS{ynhIs)a|`hL|LX+m?LcTPZo@rm1_QXOxkOY-zi9nu8rEb+ADE^91H*5Z9{R6y#83{*4&ixC%) zLs~I#=qkNpWL(Zb>`$w}3^nOXTHE!0Hev;Rm{t}zSQSk?G&F;7hwqrsOaw`Cqr3Kp z!Tn{FJKTt>L56DNXJt|h@XcJnZZ=%d2oV}Q^))=VJc;$yGIcjNKi_II8Ylhyrk! zGj{gR=wo6bwK+6k-pQ58I}UCItJX+8$?O-%rz0&5vloX;UP#PaN%o>P)V>Z*?D}Uu z=L*U8XK-eeidmzhKK+)v8C#wRl$cyZd~B0nnVFVz)tHRu@u#@&{VSFYY-rokM{_Ox zS(eny|F=!zCHnG)yk(DPx8aY^ zsP(40cdIa={~xW`Kd~7%Z6pJ}BqWXK?kTmmdn8vs-Oa-O6VZeE;;3JmOW2Ru~2!NVqSq2%NH?(K<;n=Q&^=KH~aukR#bM6Jc3?AS!M@MT*UzF4OT{y z_9nkA?TrF~%L(~V5~wkqjkTE%5+~~zT6m{S@5De+tfNyVjU(kD6YTrJ@29#LXYHLP0+eZ>7=azGlzgT z>1Q!~H8xsn7g-6qjP|Vb9CkR?yo?a}Dw>sW_3}a=Mb{{F-@%3cH_o3ih0e&vp$2)h z;Jgg%vTHyLBLzmWJQdz5h1<8_#6&_%=dce{dy}9L=U-{Z@+*uB`KbUe1#KHKAjhb( zE%?S}3JLYcPzqsk(4{fjwc2gsVdF>3|zE{!a2D|qy(Ip)pE)zzRq z;&o~4-~IX9+BuT?q}pXamRnl6dNGL0y)9Y`Y%y}y=Mfq%?wy-dtc8?$!o~q?WEI(2 z#xUUSg~!ktOjY}dotDU3iyuSZ)sUpg152bEDXk?a@py7?@CqlVm zL`{=Tr6-vxnrDBuO`Lb^AuAOxT!|WciT{e>a|cG>{hkI7X%xRep6RkRlm#kfRj^{d zNKiG%LT(Vem?-&JLAY9%=2f@RGmjlO?>eL9F&%Q(QXMVcw9mV1Xa2Il zMsN;hnboqf&sw*2Qm$-tL|^MScB$2p2Z3!ACYT_6INZs0Xnc{n+o7Yh*Ve@I zP*E4(2~N1^YcJm?@{xh|{IylTo~;buvo)Go!6*Jw0+KJQbbn4Iu67G3;bF9ysUm2P zBpxlEB&hIbd$aMG!ga}SwX{iJm5DxfbJelf+#GM zDAhuKp(mg#O){!fxw5F}EiVE1owbE3u%V0z6f)X2gsi4 zmd!FvDZA2?ZlG9Hjr9lki;9w#aT_)H+*6d^p z&q-v*oQ(bGgo-&-IUeU=61i*v(OITNS_nzMPLwVyY@y`+9f^<`v~IhIxm{^%yTJeQ zuJ^9XF!isui-x&ZJ3}`wH&Yz83zh2jv46Q-CAjxIO#8g;_V(8Ga5?~qd+C>V!|*?V zdW#0ea43>Z7F8_JRKcDwe(+dc8wx_K0R&;-oKHmOO-GcNxQ%fpS;R!@JuKk~9mtvw ze$VA%D2p)oEbvcpV z+h6umG$1U-wYzZ)CrqABp&=Oc<|S=y$x08NF@0i4=*uu8Gx8Nz5Qmw>GCOPNq`y20 zcits&oRA+L3h(8)&200_&PL%Tu}4598eu+=dy$~S>}|DK^?mcQN;2A|IQ|%l50*NN zun-T~CBgECNn*C>n4p|X!{n}l4x%;EF>@v}ss8#>IgSs%IcPQu26e}l!cy^JZ*O4E zNZ^|>`DBV(P1|wS{uy_3#5X~3mAbXx4z^CRFR3yr1ylZ%B+$T&7}-Ei>R|+_Tx$%t z6bEOQT@9~;GAhIvjwqG^`t z>{m!mJ0_M~20H22Qn2`8k`*i`a{@e428hkko22yF?yQ_v5rX7SsG4+ysdoXOC|&q_ zs>Xt$z}9y35-ZT}<5ILlnC}azFq?W)5!y#B=mqe(7$%4&lmDgT5x%!m8YdgQi{Tjl zr2fC6{r~@)m+q~12=Ml_(oo4I#Q|KYtpaPBAt%W-4b@LZ=o6@=T*mbUUCW6;$w2QugtP6 zZA7DQ2|1E@6+N>%f02Ta&k_!!Go1QhwD1zr(1dB)*!(er_EWhbBj~*iE5GTL^2~aM z=U`T5=egG+ZxS<_hVW|*(hpUB{y`Z$fBvd-tO&-un3fN-SE)rS1--)kRTlh1l0CG_ zY4BK|D+wc4@WqeqL$|>T^mwYAg1URu8FIP`GP?9)wYlm`p~^e8YTvh+gV8m17bu0f zKrJI`K8ba@5eTZ(oL1=?TB}SEzM|Y@2im2w&?Y*dD`0v(a})Mas1bQRR*2esm{tut zmNTo;Yy@ATyMSQQzrR zq_j+^T_7?HU766!Q{9=nQqw;=9}W4IsdZR2($G8ARasThJQr-)R`qupA+C5RqCEqn zg^1O>YHf{m6Af0@nvqIf@11N^%kr`5&7^hG_UDqjdf6!Qys7!ZxV_gJ7K=cXsaW# zEIr5OnOQyw0XYaC0S{En494Nc3ex^5quB{}iyH!`mSr9osg~Uy?OF(V#puP4S*-UM zPI6YJ8rl&*|HrT4_)n<+f7d7@37Do8ht1W;3O}W6msNEqOtPj$xdA6JSWrv)MF>A|N|_(vXKmjj|@!6DGvr#cdG8Kua*-v;L=W9_~3EMbfq6}jH`2#Sj7 zNn0ArXbTu~<(_WT1Z~V?#NeNk+P0D}t7zcSw=98evoKdvaX@opr^H!RLQLB;U8v^W zj*I8P9#>o2fI+GWi1Cac@l#z{0}a|Y5LONjMYw1yk;0u9Lq}3k>@*df*moPWZ8r43dO|}wgi?#DPbentL*8;qQ4p?{H`fVdWpw1Cfr}; zgh4wAH8KQ1Ex&qS%i;0a(idb}J{ zD40#HH5HClg~g|dO2}$V&O}Hnv#50^{Y`B@U!hut8~;POWS(!3rxc#>T$$J15aNp4 zQ4;xz>IxeR}m<6&>{8N>h~*I8Tj)_uUDx3J5z&grD<%#bGKd;@0?>*(GVU< zq0zM3p5xYjw=tac;(x$1wE2|&zg|&97}MiEP@z=hg)Bp}k?y~r|NopYz?b~m|7V!X z4r5~Xv&EnS65EfM2HFDr)j#75U+$FjzRXiM7#8<;yTkdDFCs5xvB~(37W4@)>#leI z0~p94M{hnRGeBe)62&AtCuT&n;o~lEv}Zkd%MnrUqel`u9V?+=@;R$S@u{ZMr%okB zVahoZKk8lDG8bXy1eRv{bVhUMndmCK7X~lXWJ-|FJ{&5~#eT7;hZx>-*%dO*RJMSm zQd#k7Lrorh6)LmF3Y^veJci+ve``PR*d1v5{XY>c=gdMTLVV z;v+6HDaxgk%EDHlrWc}m#=aZM-Emj(25#2syx$2(He5QSw%ojuy4*1IGp0^y^m3Ed zaWucmn#yR7;InDde8Mcb-?rCC8aPc(4m?I!n72mB+2YD+X@WF_;8Dy1&SGI8ZfwBA zD%?&k_YqHL5>lQiR(Ft3QaqoTy`KdGl39`YSX4F>`=SMusUpE>Kgk7qU2{fORGs^H zz;MZ~mc@$ciGFeRbtckH7uv#!k>31Owls69^yy6+V@orGIc9}}U<`&q%I8IsjpRJn zv^CqMtXE#Vg;`l%fwnp)Eug&g0qv zU-gyJr#Pqv&FLIREv@hN>F%xBp1{Fbztg3K*LJas`hI_RT4gtijv+<#%lmF&R>mcu z*ji-fWvQ*?dB_WUIjgoMxh5UOx3g^TKrJa|)KC`VnJQ3?8?1b;Fa|}P0>hkmWtCoI zr`}=}!@SD#-{mag%Nv;aZ{mNC5O+@V5_YwC3aGY*F}>gqkx=B%YKz(2OYA(aNc;O| zeQ}?1c$Jl$;shW3@2Ulr7t4?6c48aRt9&m`Woz(L@0eiPweA+UO=W6v&qCY+10kW9{+*Kl9Z zk@1R>X?Xi8j8=gQj2OmPob9;G5zQy2scluu`g(ism8rm}zkmdh#%76@lfj4bDaG{z zM2h=;J|jk66=fl3Vf3_yPHO(Vj&$jb#`0`nNnB+-o3fG}a5od5`lFIU22Mqxvb-7k zx6ksT(!>>odWEjvh~ed1*YS=ROjQbNv4soyJ_IJs4NG3rV9_1qenXIa7TgK2L-H)* zzq5(t1)7kFH35J-AB_Vs&^ise=8MaRK~_=fznZe!^! zm1AgDpzrOr=#gWIy4OGh0llB(1OjmrIl&ju*t-p9AI_C&-?IjzxG?cV+B7wyt_dmj z#5H^mFQ#nvwhQ%x6WKD%_&H}uy53D|c@Y}O^*Dldh?~bs5(!6lSGkk@++-TZ7>h{J z*sHm9B3#)b8#d$cM`GNiWs<1p_=eS}NqOT7O#X|u!TooQ_j@~pi03J{tLBxI|8+)- z>BuTSBdV)QumT%1gdIj0jFQtva_((JW>v4kdPlYP@|yJd+S7k9$Rz`p*NK4ecMQod zh96y@&c3HTrp{fKvFJtX=3IQ_dNQ8(3fq!d%#O5=61WVBDK_3%R@&*+=ZAp!^7O~# z0Leehm*j~f7I%v2a9~q$1=4b3E~J`fGt8|^{hRO3)K112a?h{KsR8XjdPFk0zscn1 zcW?imq5*Os(0D1&f%NV&2;i@_&dU0^+y+80oe9l4GCv?cVTCd9TGx1*77;Ws&bIu02yQ~A#qfR)lMG5ERGNg^NJXj`3@E#{p=w>-{F0K0AJ$6&o-xt3Kz~Y7HsrsJ`^b9wl7)9PLVQ%rD|)aK zMA;T@K_5(&bX6%%x{UBauH0|WZI-MZ+6HBs=so}g2Un`!<=ZhI;WcY+xQS0V#~&@q zr4cO1KK6VYzBE|@U-pcapN|B6aC8A~X%1}LAzdUuq$~)F0wGWT(2t%0wPfU)RLY-s zv!HKw6WL~)?Hr(QhjDu<*Z}mVVnAkejSvxWYwnLnB-K%dkV_x;f+@Z;7W& zo>)?7-Ymv-|ES#KAPuhUhmFV84#d|jI%F+ksf|oCF>Ey1^07(}d*n}$7e$LRW1^ra z@}P7scW)Ol_C)Go^tE_~sKruV)-sd4G!fT}IxCYbo<&wCh<(-F=5{gXT!_8rV=JjG zsq8Y4a7K{iJU_|OV$fjn7nUPWCoK-R(5j0W-N5kKt8RtG+lsbq zbeA#L@mdf-YI1|+66k&nikdw8(xyIUJ%rNwf9AO~Skui!`i?@bHz|`mW%HPY zS*HAtfy|4>v0?qa`ZhR!8$IRvh3Tfo^zqxG1c-e?$*o7Zdvgk)sP=+#!EO&LQ*zfBaWQXu`GR&Xu<*W1lsIgA!Bu7>T;qhFLSOvVj`kyX3g=oCE-VW-<6Q}rHD zn;x }ahoSs|!Toe_lV&sH8bE{KP&a?eC%o}I@%9*706dui=>jcGSJ1_tw%7e7ER z@NQW!3UA$7$>sg$8Vv}1P_(2_ZTtvP?1L>FHlI6)NsBnmO2=enmB$JrMNu|_Y4xpY zqO7Ws3lSeFh&wm5!T*mUBEg~hN+?S2gNg*3UHJ1_O+BQ&K~a?oM2vJF15RGzc{y!l zDZdDcgLG=uA^56527-V@S$VaO2qbjSM0i^?0g>cL@Qt`Uj3TLw zOoSoA%clq-M5Gbbd!r)#SRrXREw1Rl)U%Gw3P^ue*UiV~b4C%B?DuhocsxmlBc#W? z_ptK?fC~bE>LDjSl6G?;V)~9hj}Zq&b7|%|SBTwMlXe zSJsmQp>UXsL7#fQpLaZ|E>R52GSMVNf|q;4j>q7NB$8f{_%#<13bs!u7!La}RNHiM z4K}<6s(qk$?L!!nleaT>od_GMjYc zbQ*ZUZz$4^6gim^CH62K?$uMGj;hRRu9`!R{uu=6jCL>~@lXN!mJ!N_1^*$}M)`Np zS^*tPD$CavnL10uQW|c=jk+~dx+q9u&1=hbEst!Uh4SGc*w00RmK;C(WvI@W9Q%SD z1%AG%da2!s?%2+JXH(8uNcMG1j0-h$WDVNHv=;L`Uch8=(zH0??5v0(czcBz$HIE# zVy4z4V0e6{#l<0!tMez$wUDa)%DDTlWn6gB_9$Ex@8pFMi)*JWeeOfjY@+**xq1+6 zIr={n6f0!jl^?IUE$VwbY=vzaC1&=d`A!WnmDs}z-23U>g(z+J>Jkt27BqK%zm}5E zttD*sG1rynqxfm{#m(e$<&*L1W)zG5o4(JD?&i=?6EBntjD5I1${YLS!Y?$G`Z0^nq#$3PS{n)^ zVD5&(dtTYT%qv55FKtOo*W}6xtSoQDHgVtCG6ey2lFX3(2QWYgJF`WhQ&}%5!**E- z-J23Q4Ho@eP9*JV=6etX!^Y8tlEToY0PRtfNbgJqSEh>r!rai`A+1rDYp0J8U(feC ztk4G33Q|z#;!}!3%Dr7VvK z%P9;ai0x7!`a0!D0BnKFLIj%@cIezv0Z`p=D2!*!qHIXzTWqLlpQ54SdwUYVP);=5 zQ`-|>B=f;hazeB)nZsB)OBf@mMouQID6&Zft}6l1_A9uc_=4Re~v{3dNlY&=+?j6c=#jD}%22e7MNacCx@HFa1bdk2$ zBs<-7#9hQNToP{v(L<@U-XUJ~T))M%P|oH=vXP@#+9H0~G-Z%v>Rf)8`VF86AHb~j ztUEr=P<*YuViTCls6Evn#`}4tavD|Bb=pdaE!rk&(k=a5-35kp^5AYJc6Y1nPuRHAUl8RzkqSAVC621uvt zC#CJgb%E*S8S#o#q7^3X@B!bp?h4j+ejK`gt?(ZJ`R`#sHsr6laWa*?LrmHY*>^FZ z$;_2pyn39@mm`<&w>*=BMBZ7ULCA)m1bojV_1gCFmfQlIShEf4R#WxX%udEj&2V36mm9Z2eKL|F8{820ZGS+SL>5UC)EcchLn0M5u(m(DS z6IevcgovQ5wrPclgeiPxCF33NfrtoqOEo4Ij}NXOOkn#@d;sM1%uHzPm-~~7d?N(y z!EUqMPsP3Jn0jcE#bjLad_%YSRlp@kTSr1?4{QY4nRJdQ#ciDza$-%zWuZ#p8NkZO* zXXl%kP12lV#upJ99AOc!lz)&1D$KocNFe=xTl4r3R9!eW54$e z>4eCW{f_?+sn3~ZZhvEL2fF5O0lbp)F0|OpR>Fa=Dq5!X`c7-jB8W=^9*5UcTMrmH z{cFVEd=GzIy#=uhHoFtRK|D+^`hO)rdE(^Ww89;XC5)O7ZouHS_b=?!aQA=3?eiPJCMEtLB*+iYMF!*FYt+tR)_!`L?NWyLCI%rM! z`R;Sj2svCQ(~hRR_#oduZhQV zx}YE~ccWa`{DC+S-%6T8QW`Jyc)?B3CnJ`zzbsUw*)!1SfMVP$CUjJvU7&=32;?~% zNgthp^e>r5R0Xa%GX_cBOlUvvqQ<^HYP+{VDutI({Ay|T>4YK)#VF;ip(-ZZgS~>s zLyF)+8&)`ymSzB`>xmY_9Je6UR?>(-IYU#RIFlDs=!Ar7J#{UC$hE=~oT%XvehHhc z1)C)W0Ip7=2qMhmc74jsEsphsg^+pe`S zgXf;2URSiQd%NBoSGFkC+RPU*7#wcJnX*di;K?_z%jp$9(KWU$NB40sc}4xGzAnG^d8rM`Q|tk8>_sN4wm+L6WczV>;BP)B!!w})Z6 zx&#b|!EFqK5v_l0?Q3l8UFo<6Yra;2F=4_4L%rLV2IFZ687l%lSBSwl{Ln3ltkBc1 ze%XhoR_?be_*QA+Sy9q^%^u}=!URfQa)qTv0d$E>0sR_ekF2|9k*-_`LA+ZN=Cj|oJ#OZ~p-LVMBS@!738qYih&2PKnF<@VfV zz02rDR2~W3S`fQHmlOyIsHpiaB$^Y-2oKENkgu-YEXc1PJQJ2=q&p!*zVIxIH34Cd z&B#h^277r&DZ^!FBGuN6N7eX%U&}JmMG1GpPUX|f*)LA@MEW)Mp=64;1@T2<=MgUA z!X(MjgYWpRBvIvq%XP{vjUa535_P$McQRidm4zt3mOCezX#+o_N)~n>T>a4ia9mlO zcN;kvsj}rub#ij_O19;sR?+0NbV5edhX!LslzdfmT87)geK# zHZE2`j0Jp-M%Tf+4|`@QnVt7V*27BFRCuC^o711M>9;t2@e=d@@Xh z5_7F$4T<(hb6GGP3?nDJ) zq8yG|fs8v1@x*>%ucPiRE&Gvu(WU66s!#2rq0^xDx$vE+P;pzh_Ga}-23g1(J`7`574UQY)Xo|aPcPTANT3Lj@RtyO ztA{qz<(lso!52n5y6;*R)EMV{ZXBl%^O|fsvqCeEj+~3$ukW{VP|1FHq&WEXdRFtJ z@$WHld3%`RSNErKQ6PBV<&`T#zlm{ z!hsnD`LYdQ zk70?yi91cysYNLk#?bjDxZRts{}wK!MA{P{oz}3fwX(*^$=>4pVwhHs`U(37XJJPb zdJ3xgik}XMlO+ z-ka~od-ba3)S0T8nyK2gPxtDzSFax3IFD?s+w!|L>65oOHfUnftgIs1MddqGRa5;iZ zkbLQC5|Jr6i&?8FBu`5y=}ydKpR=eRGg}CK0>*5iMC>c>%)iRvl}>!b7dc9@;T$p`H#M89!>~yz zqXn2j-TqwQaKF0AnD$g&zQn#OM)N=>_=QuTp?(!v z!aVMRS4_)P@61sFP1YmDfwv?uV?~f}GH9-Z?--{Kral9M-!xfKoZD7}_X_LGd@SF3 zCd|vWCi3c_COb=7R}-Svm{Aq^LpfDR!jGR&2cR7r_FocNJhAq*tf3hEd`%6~Sl7wt2AySwGJ~y1hguoYMV3 z+{rduj#Djb2kLzTtm70GEn}@Z&N!`Z(a+mu z;a<)8A-4Q3D3!ZkNrQ zaVrwO<(rCDd+8^k_%DAEPz}GcGcm+OzBsvMuB(=!Zu!5wbw?oV%s>}M92vPIZMq|e zec3lT-v`gH4-dZUzPoyhUFc8Y1p>y1cIuW}H95YGd_W=P!gvMUeVVcA#W|m2K$7X@ zfQ>5rFk|(7%SdX*ap9$6W*&InRKO5J-G>V&_2YxdO9jJc0+}4{)B!K--)Zfi{AHjT zB;zpfjMz}EJQ8VBim89<+L$Or*R!am(N^9KvQZ`6JyhL2u(W%7O|Sh9eu_@p8a-;b z+`ZL(92QmCoN5t|@y_>vd=R^WvY7Z1Qk`e`?e4a)MYHgo2W!!7*B&oivi=8LG)1v5!B!+cz>OMr^MibX*%>*Kcf5`wdo=_`FzY?7o-NQac6 zh}dnKhFsbdk|T+^dz{R|e?&gbQ@Z$6K9FM@U`E^`jzJ84MtPTtK8m1E&@|K|*F2Pw zd<*YxKu*lMog<(udtJ&&*i;Tt)Bs(1sURyOYtr4Hfsw?4)ezAophB5~9HK&nQE{|t zEVV3t5cENe)1IY2*tr{J)+h1Kkn4?hKVV7whD)%3N=VpK1Tz@r+n z{18OlJBsal7Bo4-uMBqVx@0F)lYQGCEaTzGp0Bk^qWTgNAW!VvX-X%>BS)4u>V@6~ z)J+3t$0BAUzKi*{XIkl4J!{>mbo>haVgJ_ArE1ClF(eJQ&! z8GBGQb48Ci*R#O);vvI=gld(vzuknD5IaxFWa2cF-1p#~rW_eUjIm%ZCq>@6^XXCD zTs@X~25l7l*ueAl{Wj)jpv{7o?daJ>1DChMw!evO?}P6@EdbkB_u+2P2&m#DKin`v z@LFdvte+5Hi zfxSr@hSRSmOtg3EdK}{BCyfRgyB>NYvCoH|gwe~~tV?(3;Z+9EiA%S$4&n!eZfg20 z#eFbJP<2S%bMDE$6^4d)H?X5UP6`QJlw>YiuDU!vVX9vxLWk}AB90qaj^!WX{G0MT za1nY$d`|0zYwzau7t%c6-*Gtaj`06x`G2L_|I{`ANs=$wI!8$M{=(MiIi4!`_HWmq z+Vdj0jO)bcOWPCA98llZ;$6Qk1%&7VS&-9-FBaJ4SKy-Qwj&B*8=u?TY(6L8Ug>dO zEZexhwvT|gGH-Htr14qRJw|4zR zJTlUTG~S;F@uo%q3Etol1rPjYWy@iWMQ7(oJu;Zvs#q}Y~d#)_FB|JEJd2kj9T@Fl=tZIRqa*jhj4=rml@{e`QWtBSbi?J8gOVE_8aXseKz zely~CJdkccn8R^W)ahA{yq8=27190-cKQXMt?g05)~}y%(SNP)kU$6)KHmvt9^4as z6%DWN&?@s6&R-p4zL|PdR5ka9i`^D1FKFr8(SpnM{!>W5e;QTyYLQ&KMrUKvp)}wB zZj~O#OBVwq!j=Z?PD>na)L@^Tomn|JxF6dXdQRf7Rat-5=azzwl@65t5fNplTFhGB z%A501UsZCCUp?bn4Fb~p2)Gb<4qnpF8UoP^wrUQ@7vtYOv~Ip|{?sf!k!zYvlB!^t zVNzf@(~CQ5IM_ayDc$*dvAc_f>63YowTN7bwj^o3U2qMt-+jUw{g%lpY86LvTJ$Je>wr{YX_(6L6Y zbLL_0Q&wqe^s%bpP1Jk2@yT!ofvu~M5*seZ(5JRdFE&C!togLXD)U*13|mh37tKaU z_m3=t>ASMj_Uj|c+!U-j9Vgc)f%T$apSqE&$6)t&IK=!%N7|B`ahy=(3aWud2=+8! z`LCW4O)vg~bJs7t`=v!91VKD^M1L44tHU(L-$ZY`t+=D+5DzT6Er=B6z^%rqm{E#U z_S{Vprfg+DWeDfJa#YBm3s}i-DCcilaifbz@M=w%nXIG<@u2(mg@!5(0;7k^)9=eq zp=}+ux{G(6@ad#eD&j-|<+X7>f$iU=C|7Mg4% zp8H%6d{aQ7bEuqZ*iKFT`qufLnHvoR)|RX24FVNKU|O1D)pLCDy!JVh{+r0E6NAx| z;cAb2?QR3JsVE`*T|cf$gL9kYxgAc1d#9uw^VlSv6E4HArSy%24?Bk+9E%5hY<=T3 z@wP#HAvJ9dN&99}kmz+0I?(5L^Ma#l|EmBhMJm4qt-w!p64BdnL9FDxsfau;0z59Y z!%gpqD#nhqcUo@#4yect#e?4%%5(hxU-%bG~dQE<8)M;`4*Ar4`?P*?Bnq8hD&ZbKi3L?baLF z;t+jvkrlc0kQ*xJ4`xyBb~d~(-Y_0qKiEkR?;-vq_R{0ASvP#S2#s%CQ{a2|DdTE< zYNz4BHdcWwD^`$wa!|d+Fi6FY69?|Yf?etM0Q{HWD|#@l%2aN+<=ZnM%Ht8Fz{>%9 zFO-hk&1lARWCh3eqs`^xDs0BuzdOJiWx6^XA@v`^bbC zkQ|8$!7Ac*@ySYQ9fjB}jO(>-#^R*#pa67fHu*sxeJwg%n7`j5IS41auQrx%==g@b z7n+;JYAd)EJmj=!mdxo?fKy=?q$Dj83L-o98j$(p*A)(6-<_rC|w|DCZ!~=LDfxSLm{cx zHq1I=oJCm9kEK8UvSh^SWqJBmv>O3nW3`T)P2-%iT4GwOU;%ikEGWy@>88=PzsmsD z)`C56(l-lAE&p>}xQhp7pL-Iai-{uty`u5l3rb7zMMb-;((sgQW`5fimM%#)yd$%E zt7aCjajdRMJTLvOL%X}b_{?14fk`0+j}6yaw~*$e_1d^zKF3tH1wd~$MJqA+hQ-I3 zn`#uxID9vbKsxCU-c+9N(xL_M%V-2oj@f6KKbr@ykk`yYg4m$lQowr z^*_8Mgf?vv{aeX_gK~U*GH-d9tou0Kl7R(OnD;^8evwwbwbGF@1olt0z+SKZe919d zVnnE%?^r@DS}Bv!qu&~i>@$Rw&lN7JO6hfEDmZta>$Zf7af-vb(7QA|S;|!Si~{W? z5N-x!C|(T*CL>8{W@VTN_Y2dEO*U=m9+E;B*A+<$P1dCXOK)v~3ju#8S(SwJI;;YFr zelK9bHQ1=tdt{+&R{v(U_aaE7t(&Uo6C~ z+Xq)n$ddpi0I?${Xv(&Oulu26*y+XVWNTxJZ7B>DU6c^so`VDxW%w89B1W~x1L}8o zJvtpKXK#Y_;srGQHn+QY-29tww8<<3Mj!?s3r##dzCHFtvk&!y-#C9gk9ZNlKtO8^0aq%I^~wHH zd@Px@h(y$WyW+wK`}1NX{}=aFDl(Y-ms=0rj+N5) z78a&PlV?2toDpG+^w74+Bo~+g{3G}X`Yhf^$mS)4s1Bw`*n_Wn>5^Itbb1`^pr)w7xYR8+;gqPcZ!JPF zCV)S33QHD!@HB2m!nmRMYk&7Hc0}F5j&XOR>H<>|lp>Gxypx#X8+RuGp(8Doa+cF1 z+&12U&ikpQWto{RvGRTtA9g^$2Nddu%=%0Uei%~)TM@1bGk-0^duqkBBqbZ2KlB7l zi$0v)avBaufb?Cg-@}iEYn*hm9y(__EQ}p>zC$=8a^ZrQG)gW^mOnRJ2HTT4vnO_c zN`HugOj7M*QjM|Zgij0vvKlK92*x`dB6K?x^*dFDCE7W2D;hwKKH63d3z|s1sGR`5 zz3DAp%{GL`$PwG0QcX5&P0_xQM6qfj%9&gwz!cxED!knkRTs*hal->yX>0}{YHd~I z0oQ4&RAWG2%4JwQyjeH(D?N{W(1We-6<6GfY+0C2cFD(p9p9+DYgYE>elwR|mc8HV z9dVwLW+#-fy=RfO=+R9KX|nFyF6dNryBeN7f6jLN42OiUyyddkyR}PGlVbq!n~TzS zy42Ds`b?i?%99^-T?Scyj6HTm&WW<0ZUs)0rAvP;u&P`{`^SC=LxVYCT1*$22?1o;D%L$(oJ-(k4=Ayg`YvflR>2BA+A1D5LBH$QI>#-Fo zrE}R^dX=Xyq?Wo~Owjsl%EE$g3XIt!07I(ydFuz(Zsu?F8iEXht~T1x@Xs2`^O1uk z-k&b+^up)>KR5`MG*(?W6teBq6B;3S^pBu=S{-;!#XmADM}pz@mNs~mhor36C^$r@rFwomM;27$XI6PJ?qmd6=Eca z=rlJIV2)IVm?b8J@%c6zkA8Jez3tGw!I(O-{AP`-N68`adG}(wfi=}R=51pyNscth7vYt!LR;N8Ns_Kn zYAFl6ignY>WKv+xmQpXAa!x7Ivcp}CyTz`Ik65PN0BQq>sD&NC$nblf;Qe?_j-Y~J zjG`^5@KsNOWHf?6u{`~{`U z(yiE`^m8W>z2p1!U>IO`YOH46bHY+BfJ*I&3=<^l7G6ixvuLjFd{&~On8}pZR3`s< z1BdhAipYGk@OrnvNT;#+1KuC8h-j!@6azKJG4kEgc zx%@miF@nUe^nk>Yedf=y23fW~PVz6@G>xB=KWYT6F{4CF2!3o)stu>f$0zGp`k{Fq zYd{nBp<4~XLX$3vN0*G$&FB05P=5S^B~!+xm^9pIkG24-yVR1SuLw z0PY+ll~ez!;&^?2V$6_cG7o6k0prz#m+8k2!=pbjgq?dLb=RI`Jp%KRIchE8$T}^_ zw0t+<2+Z4^9#m8YF5pQb)bGDM@cvxt`c z)dWZoZgADYpl}bXV1U!hubpX~8)|`5Xv^)2Qo|5Ye`kjG2?F#!ca=SWZTjlrc~Xc= zGN0`P#@5Z8n$59X{{Ye9&VX@cL40(3KNhyU`s?(#zqC&|LeFi-ewK~nB=5qXv`isa zrV{1c=aNO20aX4@#@GJ>Ee~%%IH{Y?5}hPZj9hqj-k<$-V*kqvzJazK~jz&HJPA@K{?4p4nle7 zHw83hh=k6V7qRM=5UZm*U!z`P#Y5#=Qx64d1nZLr2@59V@VWe z7!K@fg3t4^7N2c@)zs){5KPkX?9e1Cs>m0j9`t_8exi8@9%(yZ#m622ZH8G&cEcD(!9k1wYJ62)cTmQ}oIscN z4n%YzEw6hjJmsDhDcuV1f(^Lx#`j^;l=zdlsevaaY3h!YY|4ni1lt$K`G;UMZ8&4+ z=#nST$9Gh~`3Uu?h^9Y{K_Nf^pLkzNt-_pRZ!m|4j>}VbzUgOnaT1JEp2g%dZgxmd z%DynpmP>p%!AV|BCD6|7NLSFBn|c3v458hJ z)WU~jNjkJ<4nB~X9!B_wPLnO!b_4SYAW|H9x1pDH_)m!}^>|y2PuWd(1+^I{z`vfG z8vxpZoAZ)0EK?fF57$E^9_e5u1FyFr@hPhRwyFVs|LK$3B?+KPQS{^P#)D?Z;$_mZ~LNfWtWY-}@N%(7+>_f;8K26715v0#(oG{%`9f$auo!KgqzO#ajSB!($MIs}gag0?2WWR2FAn7+$ub0$#v<|GpM+m>iUDU_h z@~IvEjaNppoP}uk2SaT9u&=R^0{0Foo1hDaaKa~(m&@{+twq57P*&+=AYlXH{oB3f z0+)>Zh4L(c&?RURpM^|1JAL2L);qF zWR(|OzwSdTpRKMRPMg;fIyT|dPEYJ&u}vF9%IfbAuvFM3@~<`b4N^%B$~L83A>MW9 zdLy46iAD4DFYA|L{|&R9zE1B$W2$Vi|3%$@C?(XixF3a>kL3*!$UP-;Q;%ES^XB!= zB$GM(RE=ukukL>SdfN4{{!dgl={SU|ZG4dHj<-$M|97Fbzi;Os0P0`(GNcW_wZaV8k|*UPz^3a zE7BgBIbZ3(B>GoJl9}?VC5CuR&Z*7s&Lcj}Tz4gqeO|>BHmqq6JdhAK_^f@=?5uIt zviR&5QsbozP0cWUgDHjPxyLDZrl!8dg!%pz0WCMHR$vy)6k`glCT>0-h#H$xGVk3Y03?R83=5U->N688y0YX2+U9qE$K_!l>zC(C~oNR%p0 zBt|m!D$~&rm23iYCfy^o>?Z+DC^?rD9wCfMF+e>8Y?`+gl;R2%47yQ zgifuQV7s?|&+LrA0BT}?s z{x%Dojij#frYz$J=w&e6pET^=Jn9u z#ue{SqGhATJYaVtjgCG_!??+u`oJ~p4r--;D zTlYOsVhAKg^C@vlnA7j*`v-~-c*#`uVkURicGT9 zT`6d$InvPMhy7rVLKFP)vx#Ij%Nt7c1`<^P@JXsLavgHS5x~_%2?~5k~*-h7F z`Lwzphsd%)bct~vPs1&3!uN5YAl^IjMmYrgC`4;pthj!|=HedhkJSbW|Mo!46RQh(E0R12fP=>KSzk5|jR z=+Cj7ic-;ugcMJzlDlTV2p&c2wSIOSFD}p=ZF+l?C3JQVr?vAM*<6B&6QUf z_&CzPK9p*P$w1{M2Z--Mn^c(~OPr(GJBqlQ+D`zcNaZavXwNlGA&Bh9ISmktn*;I* zk`H~6z1hqNuk4ZCmZkY%NpB-gO+IuI_();9RhjHHN9Nvgl(^8+wXWxMbD5J zPpph0|28VwmS9$f(sLN5b}34&PB4)Y%ms{Z#hGt!5E!)E5*w$Gy$}=(Pc$SQru*?Y zSnW&fb1qV(w^Ihx*;;@mf zY>n|5U5JW6S7}u$|6!ZwG7x!IvDt1)7(s^VEW1$8S1ZZb_vEQ|H3x7ZnM6MUNBnGr%5@S*C!{69EXg24UzWo-$ z)UTxoyb{g!M^iGx944zOj9+bW60s(zHk{Ls{7m10kAIwUv%NfZG3W2kod#1UWb`44 zLt!L;w29+sI#cC2hWGzAA>xI|v&IUJ&wcyw)l#Y*{N?<=od;=HMV0;D_VoWr<^MhB z9nvSh5DCgQEe8DgsmiP06~%XA06n;-r+J$HScWTM4&O~R7r zMP*#<`tFD~mWawIs-7*UNjHa%WZc{cfxu#8qNpk_Y1O2sQ`?FRarvTv%;~cJF7kV! z9iLfo{%SjeSMyEl`C-1fkhPlp`<{9VkjG}eFs6`7PBnH@bJbSOEAp!_4o^nLfoWI2 zb^l_LV3c)c-K~Q$l5iTz)cL5s#TW^V!^uelYGQLZbtPJZCtL{kXily!hC04NEHgV9znW_h zOH#SH)P|ZZ-8#RI(WX76b9u^4H^zlDgB|ddCX*WYHAAgv^|lqw;JN|PyErC>N9$g0 z@Ed^>{p&P!dPHtLc&MUIr%~tfUSxB6!XCdGJ~sfXj;L(8R2n0v?k+N~>Czfzw&Eo|Bn~fAX z2ud4a&-?45X=rrtD_cqO+Dm3)o1@fNfWfO8_=D#EYJtCenHH4v`LUSHL1!%f3^2ky^&3fmD&P z5uep$osOTGUb_;|QWpb7=}qcT{Npz15EMth1>qiS2hB@a8vt>rinDiIbS@fp!w+*E z?G@A7qU-ZLMde1Q($cVlU?@f{UnH{^3j{p3bGOW(B_g((9qVKEG$@=fE-YEsaSzT@ zN{3QnHL$CmspxX@EyZvy1|DS}5kzRS6L}fwix86u+9EjTocr@{+D4Dtvz)tkM~Yru z9~jn>eFz2_8Y3xi5mY06!Us(eVw!|5!gOM(X)%ygMM|asFyVuVi0fF0J`Go&@tE;) zmNbW(HeEkSq@Vw;SE&@Q`w1~1o0g;jlSafcdbPMUj`1P~VWGhrJ#Q9YqV3@8+qCLhK>I-VkFAOUl+mDI0C z$$sLP>TOKthP*O`l?)kK#`XT8Pa zI5hftX)^yLY^eUSNw$YHN_+UEgi9edhjm=?tHPaazIVlcBV*`xF3kJ>TmM$s^Y;9= z3(jdLmf!SzwT*d&_F^Lm$mx-d1uJRPvS*ibua=e|9z zPQ<*DrHuv>@vD6`d)W%0zf7lor(-rcS-h%W5VW3-X>cuqQP=Z)1G_>0*jXMTmZKe?{4N*@t~xn?&D!f>rt!A+9oI1wpe3PL=5 z=V$&WUHbE`$ktSASSn)L{_~|1O7?Rw($QoDGly>JSf6GPg{B4zt$E$|N7ZGlaqp~* zp5C&?E&&J5lBsw1F`e1DU<>YIN?NKE%251O(BqO`3S|>xCsdRYl4gNJeYLHIZXIJ6 zzG}77fQEuBQ-&icv3n+?XJ%1af2vbw!;bK{IGlNjo(VR;xLRsx7jK)XLdoTzMnVV? zwp_>H;UH_W8m06Zc{Nc=(KN!~><`+ZLStz)C2lI{BJ7|t)q^WL$6`XZd+IL|5T1xR zRN6V5ijnjao)N_eXydP2Q&kaxEG5 z6Vp{Yrm>^QGn#)Xml6{Kp!vmY^?uJb2VNWC2{H|54NV_9t3g_um`Nt?Z zQNW_OnndfjvTl3TfC|@0!2+CI7-|icC+vyK0w}*65p!03g$aUWqs_Bj?<(CHQMca? z4JDDTOg5%nhdP;liIWAO5j3Xd(ZKb%u2fjD16QlI9gq3xW4-X6vKAFknX$zCiFn z?&YK=eWzam9I@6S40Z8qD)xWqV;$;e5t+H8weYJ1FJP{frx50y$#W1nzCV&z@5;%5 zOktJLII(N4^;mL-=sop}=JfsbapKD&EX3jYk<_T#ny!s%8tX$FO^U2rYKUyJjqZF4 zD>nJ~1L@dOOy~By{gHd6uRDZdVXkAc)cN?Dq@W#{>{fD>zZ5hVxJCmJlc zW>{e>`o28*(lMOhJ#`Wh_1BI0@p9`wo+k?8V3T}4!U4&(N>l7Q!N%ICkTk-n>+9iW|T7m*8gwx9Qp#&-DZ$gj?lIW4=_iB)7C?)uk_~x%TXpW$8 zEeVs#?gZ8X1@0nCV;X1<;#=~Qzj>e#Aj=>C0PzC_o#nOIRMI*xiB;20FiWy5;Vezo zK$|VMq{kSsm-L5pZcYjTJ}!svG`OKS8Gskh#8eVI?Rh15kIX3mWa3_ z6JQf|*`m5n5cCCqUOW`4mUp8A2VXw}>$Y~8@}~IwZtn{7e~&3^32axca_tGF%|G5* z^c&ilDK!WbM&jYGLK=*w=06j>?zM_MegVUmDgtjclg@{2vT1Y2rZtw z4@`sDaj1O;4yG#^$e1KO-Qrt@_eD>+eZ#2Z6Ga>mogEU9xyir#JAj&5g@h(Ex14CZ z>CG*I7G1VVRrLGu@bNF z#*bf#O-n!h>aAgy-)(l@H*$IwyXgBm0B zz@NO$Knbu5JznUB_7s@Wjr@ho=eZ+)*l?u_KfAg`XnuKL{qgR1)uIsVyIfD;t4t-o z8v`6FVIU&$X^_KP!^)ceH-5I4T{Io{)6XbmTtvxkB4|B6-#qiv+(e(5a|B#JRSNlV zz{UIUHw*6itTqX}VEr-u6}!=!M;tRWy#=Vf2gL)6Nxhq}I;&>y>xP+n5mQ z#*RGKpYNTg*UmFmq*mdLX)&+UgX`z}lf3V4?@hM~i#;rW1|r-5Hhb?&>zCJa`m2YI z{K2z$#o^m@JbV8@r8(L@mYVqd%+iR4KdT>Rzx&$*?&p{dcllwcRVGg3cB*17(cWiIe!(!Sl6DO9ujBd)K?u#I;(~))_Z6z&W-ylIZ&IRw7NE9u?`U(uG`RbCv!uGFc?a? zudcm}s4#{BnMR7I`eAe*hxck55H?)S9eUsQx~|UXMLP z6Gbo#7fK^`b*1T{DWw%QRDPLQW}Q689j20hS?a=AG4*21AX-YIt@=y*(RO=3F;CT5 zbYx9o8E9YEbg_&PNJA!fXBXCn{J`+c%wK%pA=w@FIuw;K^m!eZy=wx z2a5TL(3=4T#ChvT`ak@H_J8NyoskUrkH~M&6UU1H@Po-T60%qrxsMt7%OXjrxM&MO zbY2%;c=`cg+3#Tc3JU^Zs5SR;u7bQbIvNi!e`aaAmMtC&-SYr3hTC*fcS>$F=l zLhzI+zI7C;z;UtUzv+*j6C?4K9x<@t4dv%_;F8he!FJx^=q=(o=Jz-z-mVTk3A!AH zZ|;4l=^=F&_aSFn-1YJ~E@I}$hgh_9nvroISjbyJJlNnRR=}I=ht|%EIUDAK5GGCc z@!`+mb3uPO4Q$ilx}Y@Ze1#S;SuT6Dbe~hs@<)w(ssT7X;2ms&E!cqlrPV+g{G7n9 zxDGgEgj#O4p)F7z{PV66hwnPes_%Nq<4LIhM%5R{xev97EpmFHQd*T6NY~OuOkqo>Ra7f(uDKof=J^&8G1WvQ_ zf$i>ZBt4#$Fw>DrC8RND3uJN1>c*Qy;MipGHo?5sE4+zn@PJ`zDZx6<)$#G zD!u^qJEyUxZT(pofjI;ZoyoBTICS&}=!c0=-7%Wc;FU0IueiMzRpP<&eBayfY2e&4 zWJbZ_eNVHr)5aH%PS})qqd4-lRygIyzQ{%UIX{jP=z#@K@%0XA;jvP-;V1seSnOYK zIL$i6q*g|-`uUHvr)`f&FVDX$Ea*+vFQ$eap2?#cx^E>am#4mS+ESCerK%W@kh2Xd zjU%#uxj|m#IOp&=i$LWp;vf)tGS2ZD472ji-T$wbN@&R4v8{4Jl_Ha!`DeGAC_D3Z z8M9C#&FWj}`NEc^j}8r?)q86hSF=zP9@dcO-rKON-yX1ApWZB;ZeFLhBk>OaZ%KO@ zJ!XPl-q}`7SyoN*je4|MRb0(8EA@wn7uj-ERqvrN6_52Dew<60N7kFGHs`$3s%rQ( zq!}xKk)mwpyF%KDXBSZ_wO5_liGlW+d5G8*ks~RNLEG}vSn^p$hLm(sLpnxl%)W#r zX!~;&A;07se^*q&gz^@|sL}5vRR$~=l+nmh8>+>P_d>v`S8&24xUv&anhxQ*q9BaS zE{1tYYAsUW1_zO6=F0tn`*mu4ZlD(51BhPyLytQBWj2`sr>&Gp!IxdwJQF4VRAJIe%wylnlI z8jfOCVRHWBwR0?Oc!vxe5!}mDF;$q=#?@sx0;EHwGJd;qRx}$Q;%*ophM&^PeCeGR zz0zpe$}&GmCj9avXoy;@3%zdOK7P8GGJ)~kXP4K(#=v`mT-CMSq9oYp8K-I+1kn=8 zE>fohiL=B?{Sr&HLe4#Y{2Fu!=Fz5m>SbP?V+tNRz%RavB0%sCGd~M=o9(8~wOEQ) z!D88T7oiH6QX=~Rxa;q^?z_Z* zUnvc~)Q<&?I5Hm_xw^>wj0U{nP>P|-jj~k&-a0Wjjo+6D5mrro#PVCW+aNc?+<59! z`70$W{tTV|l#}mpxYj)XO3#uDW7#_FMXg}utI&@&dE%g{N5jmr*SU(>v8gad=6UAD z|LYU6o^BBT2T?GGMl?B~TsUm1rADNd{TD8_K}ND6&Qt}DL3Cz7Pp00=^WN85|LSxh3@2_YVVMd` z(pKc#-Ge;T=4_=tOd&pXAWVmnKyuTSp-53I_(K9;zmkLi7URNWU{i&eNA{@^w8wj^ zM%#3VQ%K;*x!gT8-|GDrS*;Hu)GGOl1TmfXZG>B1nBf%VY9i(juXWI#P@ikPIK_%s zw-JO%?72S%VwUYD*@clWdw*0e^eh@IErBrJ6CseN4UI?H&Y`7JJCD89A&(5lAAr#ldC8>u5= zEcqGGYwT=rkPUj9RLFPlmGQrdm)P?$c=7jO^9y3Km#CFrC)U?t8Vj7Lz|cfPs=O%Z zW<1dm6CveCo4Ks|^{-yzZk7pg(z4}`*|OjUl^tfD^;G*O<3~7T*sUJ4vF`{JrcPu* z?GAs{d7f$1jDr1g#%#kHLs7}zo!9@$BQ^16dv@h)iXOb`pX|wq20*4bVBt+uuYJaZ^vW9lFBAT262@_0BC@#% z$)(E++ju=j%c*~wCqRJ69pJEFnHDyMKx&0vGrbjvv0sZnu+TGheHhiB*(ZdiB&eS_wLsfNu7IpTKYUB)r}G zEk!{)TE@4Jb%zGt>;|p}j2UWAzH}z@tuwtjOBw1=pNOji1se`F_XPa@e-l1*R-wj! zi|g%4Nzne|sXICx+atog$P?G<{jI@!|Do}bLi|pCi)fsA-lusTcOtaKTfdjfU4^R= zEaZ+yiI?47m#YyA@}c!)qVLs1I;JuvRd@8p#*ouND~{(uQ34Ey*1+|+G-Qbq#e z7tf9iant1v3l|5WdX09U1wS*Cl;Ny4OuugHJP@gm>%;`951wuemk(%~P2k?!~x9d0C1<3)lG| z75CGkTK-&Pk?qu$^~=}UhqlJT0`vKwveqNmPFyXSt7+}st>jgQg-P|?e|FM8!;?+u zMrOSNzZ{fB-aIM-Fm@`>GC|rUCn<2d?BaeNniB$5FlJ?}>g{Tt@j6~Z%iXOTpG06Z zSvL4RjY1kHM5HCvK7U-5VXCRz@JV?R6`QnIx#iUEVDm(#+$&RY8QYJSG4rEsGRo~J zU*o;8yN;)e?dvVe$8%(d9z-{ZnQ5^l3liUXHn#ZuW=`){y!? zQcL--FW~>qxXL(m%pbsgll-<}4t^&f0mtzHPG1w`TxxpL;41flqXj=WZ#0+ySEtpz zbih%aQNMBpX>2G#n5&xzR!{efj^bAcodXUZP;|@IZ(&8?ls0KR<)``n>J{6_IDMl` zT<8t3l7aWAwZN5)u*r5GvII2H__a%U*!%+If4_cU*R=#Y6At}9xCQAW3-j_!h z2v4E=F(Am+qz@*ZYk~rb%VaQs0z($_<0ZZs#16;M$L}LaulSen1e~=JGLXpvbv3@# zXWkbN=cctC<@4p|2ck8sm!iK~=I4BS4wgFnHQcqe#noyWj*Xi0Uzov7uPr_I2H>xgSV$1WALuZi~fDh%Za#s&(jR0q5tUHD|pMlj{Jq*f8cF->P-pM^L9A36#u$A zwd8-h@fv^c0`6B?HUh2q55M$0PMwOsXoFoq;(i;aQ{d42#{AcD|FySlqnDP4rDw}G zQILMmwJ)gV?RSp}cwgn^;=bcS++O?{A1nppe>>i2%m=woR`)z=pY?!OjFybR@nBxi zk~sK%Q1+|JD=o;~?}~jz{K{SIYb6Cj5Cwui$sj5t#~Kr_Nuop&4cuVNg)g|__01jJ z`?h`|BHsi)aCpso{k4GJ@EZSi=zVW-qP8)yUB#|`0iyh4o;F<@F8R=j?Cm|Eu+uU7 zLpnsFM6qLwXlcPnQ8%h(*vj3gEIady;w}QaFttE|z7d`HF6G3>uO_@&%HhC;?nT3l z8Vw`Ex$8oAl`{NR5y!r+$|$la7g7KCXTgaTj#QIh<1YE@jPr5nb17_9qr?IVXxt!? zo)P=6VukQ}=}#Q-d*m&9{^KWdhtQ@OHFbP5GbgC1WD8T3FH_vO`ly5sn-5-rMjWok zeCC-^)AM;j^-Jx<#s0A?1ud2uDg6zP$aOxc6P5Q)u_Rz&D-~z>WyH7%PbKe3Zw&7) z1BKgopQbQr!_W(9o47Q1uiq@=ZlBA?dimFkk|lCC76?4V6`fIec*v#>Iwno-1y<*1 zgVjJLQ6my~eS+a6k?5ItQBSZ6g0aKCUKziyne_riJ*1{YA23B0{)0ZS_35N=!`wU$iUCH8XZJ03TGxVX#>FBjR<%A0x_wK77Z$Es)w%Q}_VX>T_SaCnn5LtjAkPL6 zqCTTqCDO`jCeY~N>Xw_(Z1xMWh!O6Qhn_qSPb`1kPa*DcFp^77fJk9qw?Zb~v8W~au8FGgR>J3=;p83AZ@Ue@u4*%y!2>Ank zPs8^>;|%2Y0s1XqeVOL>oOX`oyMy&Hbno}R;+ON2+g-?GyUpk0ZEbS0_cd(0$?wU_ z&%(^i@3F1VxbL2)&raX(aqj#3+e62N@+D)`tCESf+%nyvc6v`w!2I{%o=rQo%idSV zr`|4|tz&Uwk1zBJX^ra()4GtQ9!vmeZezn%-7`>?Kb5AHfHRl2NtB4L1>|~zm=%l6 z4U+7n&1buY0KtQc8sVg+6C*ygh{JR&*x*HH?<-1wix!leA3t8nnK62Ask3~xmdRQ@ z#^Uw{xp|HfH+ohrMX}coSvoI2wUkn4>%~_WL1>>H;msPp7_ET;IMF7;2UtEA`5x73 z31?NkeaX{|=_bQ__TJj>CwC=F*irjxV=))|qpn^rG166=oTkvtY{gw@JhM0syIW2c^$3k`>o;DB9*KCH{ihift1MTePXRd#BUt>0 zpaz?`R*z6ejJhAwB26=n#6_0rakWEXm}^oW`gpAqyOCd8(}TSj?DMLb-Nd7D;s5Og z7!k#vycteovP9*zR4gJ0KNeK|LcG#~lxNhr_M~_@yZ-Ej<5{h-9Uh&wS=|e>QyY3q zI^;MwL$pnlN<@%i9OV;dzFTqrem1f#&bupQwH+9!iSFf%Sg-`-_xrHP``8dLGc(KM zJ@b3f{(WHEm+}4-_xtI(lhF*dnjgiSBKyD0G6J8`rB6&n!(7%}Z6syhK$V&YPksV_x142^Z_1 zy)4J@{XH06r4)!;sw@JPQiaQ+P4xqau9&4&NxKRc)1vC*7&<>4brx)N=%&as5!lGI zr9^wPG{XX|D$3oKR>w<>KxhGB>e;61)M5QLOX6J+T&05X#j|W9QN;=l-7?p4uMa7f zDNNC>bh^4$sATFK8iCZjf!;n~ik(GL!$Wb0Bul7Z0#L%?bJ8%6+!`{j++g(mF+5Rn6y=JfzKvNA{M@n|VEx$O3~QifKC z48y&YB_t0VE8r`|=W9g5>zw>eY!Ws3YBS|}j}v1OVV%o&Zjv19RJIzl&>{6W5@R2# z57cU{w_DnS-`lH`G3;7zGl1D)7zy_DrBE5ni#2K^>YDiaGXv2+mt4f_5Bz2wHn;f- z{_}do3*z*AZ<{-7sg)^_g?am2NluU_w#M``wjSXp4cA z_Jg0H5V*4aCv(1EdIQYNe$NQJ)xP&^zXLyhc?mGGG|kxAx%PdFI3ua}2788Bm0UdY z+O;JX45fDzwzjTa`t3Yw={v`Qk0B9WMBz_Cl;vi^w)V@H*o=!w+o+?{cl&$@FqG=v z`EP9T@Miq7zaZKT!*T)}={Ezy1NQT>B-wpje)GB%p{Fkc47dk0{cDp6fb}i~(feKZ z7ZtapaypyGgWY>ju1^h*;peb^!j9P-V8*p_rC~n&k5GIrM)imi+D6C&XNvTrZgyCA zLZ{gsuIoruK2l{8J>5dSQuB$vKNXeCfoTsGbCB|=rL$c779 z;K!sJ$m2E#H)aYwtE{IjFoTWD$t`k$clKkI)<-OCr;>*d=7=8g^^tFP+fpBMjIkBh z%SH&z*v1YR9Yqr%ho3wh9=xeYw z(~0u>>asH!2=p8)I4H{wX$!@+G_0Q!Z{LjUf1hd-jdsylN3M>$(7RuG7@PT)_*@Pl z{)=9Aq5?jeVE#rm|C5RSWJYaRs&?4FgNSIr?qhSi_0szhX=?JUYWq*s_kz@GXJ#hw z^k!!Fs9Q<&=(Fxqb_4u+n2;g3&EFS*I^Hs$O#dyJ@r(BTB;5svZyV6N@vQ+@bt4}e z-P|SnJC&pi0ojWWty;4D60FOf=b~=8oT6O?y{&s*>&Du1QsLR3mt)5zq$lIY;g1e} zxR(+pg{;29qv1})3!~7Swd?20j{tI2r}Zp68p2bc%<9FM>Lnsh44i@mP83vx zDe*j_b$<`MtQJ8^4qy83B5rRQWtlm0fh0??9vC3o(i_cHpaeGzP~MT?T2Sis!C5}SUU}1PO`1X4YJzOJ>zjUnc8x?-0RI1Ie%KY<$k|VbecRztX*0EvimA+?j_wJX9)1hFl0UdbFctNK)Sl(;5h;YCk!*~ZbeQ^|JG^;7myn#Yp?9Js!o zB}Cd6mJOXYn^MaPt29See^ST)cmTN9y>FU&Pvjf3|A`hUbdi6fS^os?p6~^$+hM8c zZ2ejp>&z>z0c8sk!|n2!i5TfulF$Yf9%ELy!%GX}=?0>EK~BZ1JY*Gh@8Qfw`dygE zSUglCeIHZESJW!T9FtFKhB%&+*xV5kU*k+CJpw#`Vtv+G@sj=KTjA{LgsP!A$_0@a ze;WyvfZ=~;@JOopvL&9%S5pG=X0wEV#k(*J8e6LAC53-tcPF+FX4*joy{)NCU4!3f zre|!bQ!x}tX>xtJhx;ieCuqsM!ah?UHiwA_KeFdSi)8$>A@6Ow<7{&9F|*ytUC(5g zyr7%RXBLFT1OeTZfm4*T*NbhsiCBTv_H%*Av4=XvV)QyjR9(c7NVLuPHt2~DDZoy3 z00w4PFD1l{LA>b|ZUob>Ob@Dx_l?-qa8r&N#QDBubFp*0lmXjt{O79G$uH^&aSCvv>Y!Wq$E5(* zD9P4u?&nX<^LERfD!xkFkAT>yGtL+UZ~vdih(5ROKkJ?SQHZJ_QOkQM80SHU{MrbR z{Eq8D0s56n(O2?Odpj1Ie}Td~0J&f8@1@VvAJaclpF(hbo2o|F;DtpF1`` z521u{LethRAaP3zV^>ki>cGH7XE(H?Dr#Y2-=k@LhR|<3G}ziQyUt+!%gEx;v^RyE zPA3-zaQTfOau$YihTinpJ<}^j7C|X`9K`%pF-Sy-LS&t~upPySnPz?2AVaZQkxGap z>&)h`Kj!-LV4fvoW@!1((})U#roA;Ys+*P9FT|Knnh2HZsCdxZjs|P8-@d{O*IpZ~ zAz1e$*epl!z)SpeTGSug+gQ~jts5f#B1;aYQlE`~N?O7diKeY%iphwyv89Bi{3Dc} zSX+O%t{{SwnvSlk-J$ago{`wbm{(2RzFqjr-jmPa7@KRq@V4W>af}M}zgm>>EcE|` zKbkRgGVdNnGq*F|4!Q3(8iLx{&$zXTIE-BEGpq7KlDrZp#i4diq{&5gCHoMH=j$C1 zyYau>o;tHVP_1p}B^*5CMWf<35~7qCvZ^m5+~@5S`mFONA8lGR7Kzf;)GE*k@QoTA z#5I^`HJ`0-FeexlIp^<<5RiM)5zySw*Y`lPJ{Z`rrFQ+RW=RV_&5HUvjr=nn$m1{m zC(+p1*_A{)ZYx=KY+X>aSRCVRDp5&Yx+`avKFtxhQN;vnRyEYj)Lb7wpt?_kX+|nfK<~B&mB>UDlnN$`t0qVKgEelOXFnolvmQhs6Og#=%uDRaCDSYp< zq1R7&w_o1b%jGtN4SUQTK)si7*0f*wjWPh#HckRrOe8bpwwD-;h|!+TwvgR>O$J{o zSRt1&1`WmtKffQas^D7Da)|icVTG^2VCmExbo4BLS=6f{Vmw&Fhc4GWT)UCh#q_Jn zSGI}`BL{SjbM-yhLkjrHYLjjJm5_)hK4*bw%K`Wo(|_+?;>BUCqV|sy+Ui zF}2q}3B@TTL1_D_TITLS^q6FYPOsZE)r)PLD2cMOakL%2PN_>2ulnE|g+QUbv0>Xu zHe3~3nedR8V>BOlXC!>}^g=Kx9^5a3{ds0k9J$~?Ke-}7>&7zo z_qUOZ!KP+9|8ir!*4dMQZGHwOx$-QDGVN+ER-Sk^1KGzLu)9rCOnPu!lnKu~`8*16 zn2QuT@@4}0{dy(8DzEeju4Yr{SOOKIT8z^Vaw^Noikh1v6q6=>@d|;2ZyX$~iSB0^ z=8k+?8xP<1??-N8_Oe6x_SrWi0C$Wq6tofDJSfK|Zc|aWk2^JWN~ItVf1%x0v)tMx z={zU-hR6!-jA|EbsB=DYS162|lS_vLWz;VVC$c%mI- zVW;+e1ad}^N38|!{Rn15Q=@ceDOQcc4*c)OwicaErNJvN(!D|eEgKr~t*dYfP7;RS%a5a(JY3whwADr6P8$LRXH`HY!U$zC zrv3Rplo;-F)HfZ@f|r@uIt6h)FQ9h@B;_a0Rf>^{_dK%qft%L(Ka;TyYV8e<6yF7! z)ql^I9f8x(r7xE%(m4CsfryJ1*YG;7uwgb@ znegY8z7aiB2%91UhWx%6wvO4p917$;a^MJ3l`E1}g{7^ufqU+iUfH+0Z(suKs#17P zS-P*0?RDs+gMh`e6EI)CFFA);0P&W2Wy{mX`?OdV;LZm9LsX?bv=@mDWq-ho%cnZO za-uvdyEWYxj3ENvFBNfv_@nq}>Hat7TTY_Xsm>3Vc~7vThjOgvCPRvDPB#rq&~0+a zNisKjR|{RT9X{OPyQS|!po_DG93Nc$>Dy>VGt;c%w~f=xQP`eR?AS^-MYHLmVGHBl zDfKPczbcylBp4pb9E**akOzR-lsZdS5v&1G zkn0bJxlBHqWx3XP$r#Oa896K~q)0s~^u+?u+01uIFz&u}OYk08Yt8?NqF>(3DYco` z;M}&UgH773Y^Y_|CK|6~ST^r?6$chW0a2u$v=z zu8`POAJ}{Wx*-wkPB~9pZRTK25v?nf_MXw}7s#dHChZZR#L)}Tii|Q#uSNN0D>%Ua zY=>%KCEy-%tA?OgK> z>bDs-4?`B7hds-X?>@@`?NfksK!ulni9l_^`ShPk=?YjDYQi{k?86iqonSWeeD;1= zkwP`eWCqCr!FH%|!WKFsdqXk2bd=uq2IghAjW5+!mhq$=_HoYAhuA6g6kOT!ID1&U z1+r;~8-`~a)Hvl>{O-gXIq>KdANGjeU8`We{x7XBm;sLTpRG1%CNInWFyEq8l5$EZ zQrS)BzWJ3dWsQ6XT8cx?MiZ4oHWRmP$3?=AqoCGKGszolWz5i7^L2ya(Vg@MW?Vml zC1zlm$Bcp0Gn^V=L*b07&QlKZrep+qh(fhJ1D`58*h8N$c|3kG$b?IEkV!fC&${{U z?|oQfUk>3<6X<+yb0b;g>g}EEQkckOAY*qb;El1#2%QP`ou2m05r+trEqM~b>*;;Z zp9N7vAR-pR95aFpQ8=P`y0ndlW69^f+O{%Hk}lPTlX0vv{XC)q$Bsv{*J(B}a6;u! zEco1pRgd=O+q7YggaLjAy^vUr+-$IU$U^swh#sZx$GW8%HxlcF@|NIE1lWkC-Zz&d zrgKC>MAjdsbTaTYd1Y(cj}E2&lW?5mIKrs>9Ca8szG@Pwf#UC=8mi1ZzuM*W?mm(4 z%){^Dj%1EGIj&=T^5T7ehqaz91>;)ft~JB|b?7NzZ1XKLrt4gEo$)O!8FWaqA@Pgn z;ug}n%Tqqk+W-mPfYrTllOho3RrXhBoX_g*pDV=K0`*ZFaI!Tm(bv6|g#d<7PM*7- z8Fh607-D0_SLt)r*7M0yRMOG3&? zoBbYz(#dIcLui}{{5WsPlR00wg^|GW6qb2KtMD?~Cj9Ch!zJvn6}_|!`0}shq|aV! zM^F0CBKU7@_GiDB|Hw|=n>FB=X(`-Un;(>|DOxJ3n0M3Y46pCEW~BtD zixD-AL)<)Uk@wfYt-^7X`-lN1YlQC=G_QNkhQ-Y-$z_Ukb!imQ%Eszl2AT*AS~0_e zw6!}#jPw4QkYc5B6CnrbljqDjI<`v&%ajaL8D8i5jI*ZzUS%mSnbZWzj_l1{=R zjEq1s?~&COqm7gQMt7q$(^NPtd+rGKCr%ag*qanX1wk@nB zyMbO@Y_M>l@0sV-q0cLoenPkPw5x}c%#xCZ@TI`!A_jLuI7$f6^q2EIK;YXt;q!F!Z7FBW{M~AC?h)?aanajn* z5+jh$ccFVLO_5^qYO=7-AY!yf1M@F|hVwrJn#Xl*AK!3^)25m`cMmCFw@5ZwT`My@ z650zqot+m;EnTj`QRq{UD8@z%}=@>V`CJ{0(CG+0dP@k;TjBU}h zTg30!@1W`^awgZ36sz`@Y`PwacRRi~pqeD8adzNJg$#q&q{a*7k$fg{y>PKQC|yk3 zXKJ%t7m6rR5)X7lQ*ZWz&J!zPkFr#h_4@0;F8Cff3L2n@@AWLshkXhd=f9Rnrfv1M zwmwy1*_Al&G6~)e7?R)P9u4Ey;o*a|87OTh& zK`EG)Kwvg|*``92i@XkZ=jR`2b?eJyMPTQszlpCJ1wd6?}(^X^=r3Z}9z57oq-48N5}hxxKN z(o^g?Om%|sOuKwlT>-1=C9&w;hwyMkMR17IwvURZvZD6w6cGts%`0l5SHt5qSm_Pj zeFZHfT%d8}DolUgppA;?#>@20UY}*38PKqt<((78OJYVWGlhw3>C!^>^I~~mkNS!2 z*Z8a!&mAR9n@QGEhn9`gUm7jY;+5fxhmsy^pwIwdnsH36Knnh~PCn>YRfVL+dX6!e zDwFKJEaqMRsBuAJ&!aSkZDr}htWB0Si<9!pzE5OiQWwGod0CBIpH>dhblUUMCO4aH zeMv4wqc6_CXFh_=+ZQji@q7@CE6+Og>l28HhMb3<-nb-4riJXQ zn{eLJ!npU4@7O?L(;b?w=%Ji(4ZI_n_$gEhKG7o7VNO1Y>S2GiM*rxMgf=8mnd&B^ zW>ic-pSZ|7W%;tOw(Ttm-R@{CsA)5?9G8+pHP9Bfo!q$TWp|u(Ma?rsPd{GyJy8s+1bU1nr@2$v8YUyMOk2#I>E=dPC}7C<;X% zl=j6$V3=fE#)BatVB-2GEQrF%1e^)m3~{E}P#LzwpI2XKG=>}OL~$w2jX@nPGjyb| zQ-iC|d@EP<9NGwWiw+FR=<_4lKLO%s`Wd7YW3iJ*9Y4?$kfJWoSaH;1Ujzf^M|3-Y zZkISg&^x8sr-!P;EKrOchmt(fQwY>LkdAuk#jMH!^TI)v`!qq`ylto>09g*~HHy_1 zj)kl~k*$85DxWrxfd%PTiM=m5*}%HTho`gXJqex+9;oyEUzg-T+^tRcsBifzm&i`c zVhp9Y2;^vLO_pC#e^VX}tA85<>K&Jc0aFTcNaFML}E(T&v;BYq#9XG#_{F) z^ACsv=jiO1#9y!$X94~~J18CwLf7CDkGv9fz&GQUYpPg~T>*ssHgW{8m9ghxi@zY_ z!>9DiVdSY(BJzay!|wYLev;YgMyMN-K2jj^YUmKCI;Rh7U@JfOzXy{49sCzo24GO^ zy-wX0#ZG)iNzJRjND|jYTWfYjP#z9B74)8we7gE}V|9CBuJ$tABY>^+_{%2_-+sh|){VP}XixcYf8<$A z=+<`G1JC?#F97P23WC~V_t^~@B)Z>t2a+nba9}b;4%~=@Nj7^b{mb<{9|G~=UVDMv z$l{lIgjTFQuguUPD2~n{22{z)ihiDx^>9c<$jbJ#H470`nBD7|N@yD7>1^zDkWWOy zMiWo~nLg4+D9Ptuf{b-op4PI2?rM;S79S&TR$!H6?YDkBTfLscr9JNltK)fdTDVxY z5HoZII-+T7&HA5*peKY95<#iKQOiz;8_xRmlc`D;-}``I16$!ShFDKxEtb#_FPlPsZbqXb4g)CB+qGxK>Ol=^0mqn?1e5e7SpXZ;IvNx%vhsw=PY~n^2DL zBu~fZgLL*e=Afs`D-zP=+&!SByMmex-n1h(2x8oUhxc-AWQ)9oW8^BgN0oV|wW9t3 z8xS{o=a+(9^!Yb*crA2DI&J#xCu?Q;9}b8`oG55vOiI@ejE8pVe~lq`Cj9^RBgrIw z^gA1H0qv4$+NI?CXQ>%jDh?SN3XB9y$@Z^mZpvVgOa1xY;3;|o?E=O;ae?No=yj4U z&?#B)=qFmw06XN5d-*9$w{-pTHx^atY?xpp72A9d5ldwvu{;&6S=_oHx%_IjNW`VD zpNj9J+S8a7Y3d=-Z`a&_Y#(Uam_~*nRG76M3d5#SN&VdQTgX-1_wFM+ca@)6x+G^u zIQ9gUtYspkZ!|O`Uvfn#*zi^9zeuK~Sz;npDlPq{7gwiWu8^~H=UGe@Y$>BIL`5#{ z^_hndwh~c(KIWDnAXH?g?JrY43A(4gZJ+wlH%+Clsehz2ae5IL5<@DuIb}e1X;t+h zOu0i|s)bs-g#UFrIo=?r?YYXWtpFVR6>$XBHtU_?cdafMAopRVD!CldbwrVSUzh3d z^YUmKP^(gxFVeX_FISk))tX0hA7vUD^!>qIkXs>_gfrK{H(T^WJ zPaB>B&>5wu?>k0DuqJ<^ME2WyUW~qyW*$@Kz_IR@y5^@lbWX6$1%Fo0xU8Yiy>7$@ z)kOFb8drzPxNDa3di}W<-b1#lbOSlwPR6$^`U9v{!svBE>;(3b6^#gbK1fcR_0?|U zkGZQ~Q=e8qVM|jmid^>JwH5O(Ud+~h5t7U}LWGhUdn4m6P`V);m2)q$a zLp758Snk&*{rHNKV1w_4B~Ye|!;UkM?C8GAvA3a4pU3m~gX|cVS1sSpo|e}-@smd^ zZ4(hUSy)pb(esn-GLuDH>`V_}Yt-xqJ$0)IUp-bCn6da1Da!-%OwIGSd~VT0Lbwu& zN;c0(66}Uo{j~L^1A5?=LtHjIy!-LqLBj=So`N}Tg2`N37O%V-{kNjO2GRc?w^gbz z-2ZgRgk6RE`#Yjj1J)$hrL;(DmIM6a8ihCUs45fYW!4hUhm@#>X`#FowXMoy@|hzu zQY!ywDRHc26bIP_s%91J&1b?wq^NOVPPD9+0`ig`3cL1y|0&331 z38#osS#q{y$j?+yc>Z=z>CixZhRtk&CjaiZI4#0*kvXlcD}z|e$|b=*uo5Z3pPIpD zR^D9S5dpm5!nS;2@#D@VzpQsi>YRI6+nQk}&qAFOtmE*5t;glF-K2**D!$x*Wb)Uy z=)3BfkYfaiIYhB7_4o$B@#jz8R-ZuSd2E56Jb_-iT`M-*24i`u71^0g4}sQ-LZ*81 zccni>E0C`T*}@!xURJIiD@fI3AT6W6+85)~?CH4{2$J+q_%6WjmNpg6x*Zb9L&C`(86sfvuN@&MNu9~ue3($T@ z=bqtKy~4kSOSw1DDzCc9LZMm4DucuBGGb>PnYi9E?BA$WN4Q(#Zyj`!vho1qXPo)Q z&2m;xZ*W8227UhZ=q)p9;TYglG(_u#jlw^st6s#pI#~eyaDXjNqoo%|a8LhGBjnoc zjw2F*;A^M&vNZ?&Q5()R!{nLu&^=ie726&&A9`EGlr$!IxySYCKp8ZyA1Kc9qTJo{wn<^*DBN;l!i zHb_%_PQZ7i7%LrJvCcpMpBr`%6;#Em#@&sctv4=V)B#+;x6xZK58;?7R9`~_&jca5 z&9`rFyeW|HoUmy?ng&^^2{i6CNTwf%rL5{;Bv1Uc+h*7tH0w>m`ZLo`tTV%bZ2gjQkgzW)^n@|N~~^*t8gD! zS)+(h#Tbu}G?P9``SPqEBY&}P@q}t5U?H+w2dB(oD!|EMU$98rS>GZAdEjxMZ9n>P zM4k`o!CMH}uD{%@wYhB@R}JkfsNXH^s4I-v!Qm>~w{Y3r!vpSWBxAqj)8=eSwMy(B z^NloXZjGASg}5ynew6mFdJj?Qaq&=UJy6H~<#y6X|NroY`hW07e1&9QUvJ3;57qbK zM3kLkt@3H~J+J%LR>^vB$D@3?8BEsThIfgrSPQYV zgE>|7U?Xd}Nl+wXF^aRaDfBK|-F$whai_>4^)A2Qda1Z-o=>?bfp@eyOtoN0eZks- zhzqX55Fj1yK?)(tihUiux^Ymz9+BX2ZhjG>i+gI{!oB2&_u-C#_dP(w^cb@4+O`6$ z%9f`*Y0BW#%2>skl&ZmL+pIy^w{(+lg-S?0(y#kS0ZrwAuB+s(6wK>H>o{J8U|z;2 zDupyiC97~(`NI6f-d*dWhmq!+G@g^QYQo90sDAE5$Fuc4&ja_k$PTXw-Y9Fw%#l{G z1DW(ja{VFBd|f?uMP|n(SSI)J>TgQD{*NNDfF>{>`!ho;q7-=V<2>0EDuq*Z zw)k6s`>u>8;@90+TeRT;Z~j&JfVUGbJny@6pP0B&bL=*U0teo#m&zslx$#NX9hI6{ z&p59kZ#gHvC9~Ib^F1nFA{C6w!3owWu)V3?J$||Lzv!bx=pXc9Oq|%?enn7RoFRp} zAi*pI$@6J9LErlt5i1At1DWmc{hb;nJE08P(VCqn2u_~=3s5{5sTn5&%Y@>t=d5(X zoLG@~jh^9;0anVrej;&7!WpG*q>B=HDL1%q<`HikfOThIFy)NyuCK2|b2011)^66O8J;h~)%>o434|ri1RF>s-nBO--$RTGv0?Zn0on-%;kUxC z1VGrjcFZWj;2lW5;kIE>$GN4U)L(alLhoH`q+3hf#w=_;*1qAZt0Kec0e)WkkLjFb z_Ojc{Xpb`|Ji7?4-)k|r$&iPxHdb#WW;*bidq}xDp9y?IMPHeS^t;Ieg2x-b_}eV* z^=3KE4tEiHivC8>_LX(`SphrB1$=X`xw0YK9p0LN`Pj`_6W42o=Q7aXw4GQwze;G{ zG@Kd0Im6-68|K>M8e~7bOvqQL$C;7fb-o6I4iglOvx9#vi0@m`JnWebxifu^OIGI_ zo!;J|dDOqQ7f74^UDo&H_3@Yf;qCAr4kyJPs>x9wV|{7TV>0Nd10_rdTqL&nNF%XN zl14C;^n5xP#9;BL%Ye9fnMavytj_N>VXd3(FsqI9F;a8pTlsapSIpR@RhQ?-H?5$3 z1!oUD!$S__u}uG#rm)#%GNT`Esv7++;!DZHh}PhUdfOniCqrV}=4M1!j0kW^MqcQ* zEwm;4fSeAMeZ22(3J|-v8t+GA@|DJmtq3P@mF1e>MPIXd;vGhudFf$#xt?HDyS?qt zpwg4}xAMWY1dEa`{EKr&Ta&rF4UoP$?fm$$n(D@F7p)L<$GibwBTBk3;&+_(t5V+7 zsIeU!LCYr!D-(Usk*%>~q0m z1>u)uva~gfCv=z7`Y+8rm;q^p0}JIJeuBUM1`GH|{=*lC-ThI0Npo&oX_HSXmn!AK zjGQBtQZyb31;S-={qV?q=A-zIv<>y zvWf6{j$jL$V$K?drA;*w4N?N!rs9@Ig(hoq-Ns0_0g(MxeoyN3fNgt|z4A4GSGlbN z_F1%UrOCD8X>hNfwRVKrRD{m5I4x^e;EqcR>ddi;#{$UVLT(cj8upOiSBL#c+Q><6 zR-UNUW$fd!#V5w)gcA@G!(Kg)cX|4&Ekn25c`@msI%4U`U192@6rtXnl8qMVlG2Hf zFh)#M;u~NG6Em8gIyw(`)bV{r=M!272DewIn0fx7{d^@ z5b2S&<7tRp#xfKg++`M&&d&amM16AX@-FYCD?~T`VQ~cehb`w9ZXe30R<{!nh!zrx z3s^R&p)@wG#rJ?RFy2oRAO6WONzd+_&YoDae*aHKp2EiD!y~it~ zVWR*p^_o<3*~0LX1Ft=pE&w_%05{OZA3Z`T4OrCIdBm^tpgrq74-~WM#*zg)76f-s z#RRRx;DEylge50)Eqh4Cnq-SOAzciva=z0olkevBfC&w=V-XLCpwMQ&Jz1hf79rUU z#pTDzeVoM_zrdglk8|Ybti4T_`E!S*EggPQhfjV0d^-%5>uNU>IR0?0B95`ykd?gN zGM1Fw@v%{eobWfNd5{%F(dH)axe4Hsjw3e0(Nw6`ATk?x!+5rh&r+AQC#@|2bBhCk zZHHWIkLXU>aV);FP2#k z6)ZW9G{hVwp936)^642Sq#P&`zTJ zr7K=pxnbA61y5Ky%MuN^ryleZsXIiW?@G7^pcDIL13$^}D(BW=u5J=`o(`rpHX@tg znIwhkEv9p-1Z2SZp2!sbOTruGUKa}!iyZ4i+M`6Us5j9oz4nCXUbWcoE6yM)HZYDqBnR9H*22UMf;xiu>JN(jMEzM6VkKgP?CmqIQ93<6bEp@H`r z2Gvhw3#C1hajl`MODs8SIn)efcP(dOtm*gZBjI0s0#4HLH1HpObav?%0}l)b^&MR# z*4b5d3j+VFZcnz*H*sZ-umpoU0GGWUlDBuCg%s`2)XIp5aUbqFrsH`>Yw3^NH!4a^PRrkQ3+ zC`B0ozjw*SEYmvmI%>_KDCh;Zrrl<|1}^XDq;C0-U6YpbiWr-6@Wy!&G(bL44NcRP z(E=k5!!%a`>gL~5&y$GMj({$KO`Z$Ml2syqd6WK;UWmaZMZBp#cy~_CiF=6iMt{{V z9zr>yVdd}K!_9w}Z%muXB?0XA`&(fwU~Wl;{z&~1eS|X4#;7x5o7PW(7qPfkggj}U zk(VRV<3WNn#d=B8TCg61H7o8nxIpcD>z)(0$SJ+gXQO(!n+^|K*gqrD&kH~}YTi6r!HSaQR$OaJ@9 z-Y`65Ch*pTAR;&10l>j&i9#L+4Qe9Mqh+ezWvw2lr$(gDET;v@7(@xwr--itMV^>o=a@(Af*z|L%#DmBR>pq$0+(v*-fGpZ zI`G*bussxX+tl$Q88V%b;(f#rI@3VM*xlOy&J{*1$5pZ~)<`wvJQ3Fp(2L)WWzT=t zc{c|7ROu_HZ`L^eaEdkPeHgGe{m7Np)>DRAWDuY0 zW<9jhM(I}c6-otC2jI$~;UhuDvi(`T70sKkVD#mQn9{jsH%jyscHSqqkH>++Qb>~f z6F27TC!AxR24a63iAwHi>qPeSHB}d*#)BbZr6-Cf_QNldBvSLg!1-cdU?R}=9cQv7 zVi{KY&qz*jkWEVK+^gutJ{6dMU0ikW1@O0$1MPXLP{`zmroi1XQ>oo;+i;L$!Nc{6 z>)Rf*@yD8_^aJ>yrIRl5xjtLP2Us^%qG(pbSebF$A-oQ4!mCyd1n`Di8L`8DJ*JT< zK|Umi2&(%P^fQRaqDOM4dQZ{d43}SmKK>GXTzE!lq=^o1g~oFk_z){4nmEXQeYW;F zFp2D7)9iZ%`a=^w(UVT%FUHV*4;<`%N5q=Fjav_@9|@#{uj*k+syIHlLN^rGGnU^3 z0d$0~&!4S{)_KE{&ocdSiWAvY&jzG%X1_jETpF1Fd6H#k!fH62nFqK%Lm7B~(D`k$U z&rum-DWij@5G&?OPvyfro)m%N=Sgj)70+l{bI6JYdjq94O+Zt|d{oo;0>(tsIZ2%) zuzAm4MJMlVRo1C##P(t82QeU8Xa0) zESeq&rkUJ*{7(|&8WJvZfk*e5o43gYmBw{gFU}!|KNWPO{ZGFQGboSZSs5KDtSFO+ zdek`5^1^;MwTX^1(%@J4CNfCAGF@?5uH^#sJ#xA$JZUh}zL?A|>PoA6neG8g@)E*h zBgBmXm`nQx_k;tQxwi;~@}Nn?^Wk%@yH#vz`R;D~abBSxz_|z%%JuVY*k=fpb3;7Y zn5@0)u?9wfxMhdMEaaUC>-+;}Ja#H~T+;WNsinI03xOdXwM0`^Zvf8Hg%}_iOZk9 z5X;}+pDa5JIF#1-%s0uc(BBPHhPVC3p@K{5K%U1iAHZ|>j{X%u_xP3EZ#^k?JC)oWu&Orz&HF;I_9Mycm>l&d?!Pdpr2_|9nYzr z4A~l^1K<-j7-DOgLJE>-YnB;z$~OTB#7P7EbWK5ZIBMT6n}z$Uenl7BCv4?$P(Z!Z7_L3*Q{i)r+GN#cr* z1|!~lL&qp84iBXomtVefkToIx(i1yW^ZA~|<0r)>p}CA{@vw0@n1f7_pmcgS70H3- zqO62^a+GS;VCX&OjpcDE!ca^4id0bE8~>N7p`r@xW&ruq*|H@AhX{aE(x;Bj9rbSP zL6Y})1F=MnulBk*Y(Mj%A)2|wI3?1ZM$Wc}OsWc7PEbF7D|J_eZNQ63z;3{&{D#e@ z%!he#%q*SjVjj4zz3&A?S`0HfXwm&%{U}u*O&qSkHxm}Sa7%w`&%fWAbZGMkyxR}Q zGc#)z^Kv+nDg(&)!cAXB9$1AUH&u6uIEX}3x_{W&BF9Fm)IzAx6jMi7QjQ>%u$T+fqmtOU zzBJ$w&hql?b#_j{-NhuusA5Do?@d&>JZIB!NbpiZ(#Q$To$nF`h&gHS9AM;Zvg9}T28IuDc$$Xh0r@3;s#RNsv^i@)@ zOzhOq1N(*GERtyv6(erV9fFT-v%}>1wuf;AmZURzA02uJAP%0i*`HmMbA56#bN{#*I`AEd<^=E zLqKtzn;C}lgiH5K!I`TxEMw>|<#cOfc5GNM#5(*SWuF2M zmN7Tj#_EJs9s`Pt$}I4L(8tEDe#Z}boV#lCORsz--f`3bthUL`d!KidVc!xK$CJv9 zdf*S=K=+L>*&mtV;|?4u*&Z^U7Fb#rbj_JKHCLyOA3TIt&+{uBXk7M{hOYWNx_bo5 zG9%dLLaME$E_&;fFbfuKZEwQ6}Wqm zAh^jzF+%2(I&&H2)Qawi$sz=p{MiSlgA{TKxVCNdo14ZT$xLXYycQg3JJHHvSm&OU zr@0&OrC9^kF4~tE^ATeVy14K?xlD6uVoLS?u2oo~^_095(nZF<%j7hq50R{USgOy3 z%7$s|l1gQOGJhmwIWt!a$bWXzH>@9bZ${Uulve0G)Rja-JC`bT>)#bFe9yo2-gQWQ zBIH?AMo?hdZw!Ew-;wY-GFHvp_aA~jalYF)bY{3own@?G9YK2Axk> z1M@;!KYV(GeQtT)gKr|G@MTy+HeuHOIwVE$t+8lLxf;$=4o&Gum5eXGJaM+<$Avw9 z-6PQj!iMrm(!0aGDy8T66bugd3t^e8v~(5f>MWLwWmpU*&jU^%&2aja<*5i0;(|V< zN>)rrV~HKmktXwPf+JLF%d@kmZSug6rH?14E4m%CSFbV-ukA#?!*A+`OE&_vgU#AaBK@;H`0_<}i$aFGMSDA@ z(#y>mc|_8YA<2erwG(Uln<@AbDCar2ZEt_tDTX$EJxCPc2#l<%L=V>)57P#JgKj@Ecxb)-d4-|s% z8&n1r=!CGVxuHy5JmNSrsH>pF6c?(M=mzj#ir~X(J_C{p7u&4hB^xn(YRy-c-UC?=jqAhYT|G!*Tnx|iLlWsi9> zep|F4ysJ@R0e|q((;)yBClsYKFisa6iJ_H+V~VgMDxB$E;#8clOS^EfFaE{F+MD3T z$;U>`#vLu2eiS6O7D@(da><}n$^S~RfLkm9s#tJM1D^w+GgDc>_g$LPh@19KLg@XI;K%Y^ICDUG8ek4cF5$1w%9Jg!Qnd;G7+^h`>6u?Z;^Fua0DN$?cs6`Ayh zusk`I`9_WPz4?mq$F28z1Dxu-WpYYPj()z=&m{LRBHd!&DfBuj<~oxKa|wS6;3i>V zOC#yX$Yp_AR*aW*K_%yUO%b`xozT6C-YxOFmFQ_SV>LJ^phT2~{U#M}JOCT&nSlKx z%lfHd$E}eJv;QQoML?Dw;Z)>eY-lmf|6=TcM5QPnVVEiMvxNIS!*<4^oW%6kYQVs` zH~{u_0nnIONe&%@ZcPV}>@LN^6Q|Rc?hzr4bCXBF$VI(WpEGBpbLR z3e~B&b|7GXY`hX-=ygz>z0c6aPi4nAIj)SJ=yDO-(EaF@F{tdx{NR%;SYWH=NK7lO zsdGy#>&t;!xql>TVWw!0zEZ*7D;d@G#6OT-tI#**l;$WqM}Z*Rk0sXIf=!uWDMvry zY&YEB22}h>O@N`vKF9>)x?eEf#<#et)Olj9kU6# z%KZ0v<^M`192N-jyQ4g`@WyI+G*TOZvb*jMh#2R zI;^K$(-Ai(V(9wUO8L$81Zmb0hD>w&>fSG3jqrVb>8|gqpwAAWGM1RjPgYECidQW; zqLpmZt%VHK5A*5=n{AAf*A*S&7R0umC$Xi7tF4Qov2k^h#)b+l4%P*SeVN){u`P)= zBslc$-0!pf-Zn$Y?pQM3y}59USW-GYkpv)fDMGgT$=cYmnkHO!88D2x76pNaHOj#OCp znJkrzzD-KPyd6i!**XEC-fr%oW6ZVrEdQg&Er3n5HCJ=d_L$3XZM7uB@jvAB` z)gx1!fuavS0o{e2gG2P|ND<*^xR<^tZJx%wl4c;QKoLE8fynZ6hXd&i>R=x|Y48BI zBrng3Wn6SQBv~-!j^ZPL-oor$NWbbs^gbG**w6jPpztF%E@Zqj?FhSm*OKVP3mqO{ zaZDXh)Z6M4sE!)OKWy-U||+8L)oFwL%w{4 zkk82?ln=Udl|kVe*WHqOk`_6LODZ8%d(C6 zEo4%)0r8TyWv5Ucdjo(v+xe6wyq2Quj0JLkonYpclO`O$=tTR->Be!*(FQcmB7P{{ zlTg7zAws@ce{}WPN#78>@?+^ZniCl(CxGcYen?dN`%;5S+ItG-{ciz+1FLArBtBQh z-`SDB2pp*ltF}7=GxmdKCHi<oM)++H{Jlmw?-x1!>b6jneE5xi@5H|b)L*)cf4 z*@Mc8r-ccYqJw70hab4K1pC;hfT*)K8yf+on&`53(|&C>V$gQc0k?4MqbtI z0gQ&JhpR8xe>*7uS0N@sT%V;>h{%!1uR;vrA()l{BJ)=Q2}?kt>ZRb^zA*>eoG}|; zsC$W9Bt@ro)BHoXXmVipjhm=0=LP{p@hh1RGK%OmX_gzVgj-tpz!&X;gBIk}$vYki z;q|T;5$waUf)NSmo!;8^(ACtV?9{m=L8Qg95zZfbZrQQUH<`~11%U#+2TWo<&;w~J{D5N?>_ej12q;AMX-bqt|D zyd^l@McK}GM8i_W4PlOW7~g+!MKQ15ryjHU!pkJ3|1(09QFzUqkR416^%rhehJa+HLnZDI6!+<-*tniIH@dd`xf@v%BqTt0_ zuMl4)vB!LyAOn6Y7VUGoG?y!5ToN%`SEpnHR+doYrbtDmI6qK1ZzT7_=Y2MCGjAm^ zuwKfqPdaHQ+S<-b7g2yW!3>t@f$dSLppK+;uTqO0BdqPDNu@Lb@|db{2CcLwuBfkL3VAY+|#x4q#sY0l#C2$8Y$p?; zR?sxn&weKcD2-0}I@s6>?QyQO8(p}iTZHr{XQPc$NqVpP7`a|B4zm#pJ$a5@?HQ_U z98U`2Mi^nG)@-8iOZuBjgBO!mS};E2__2I8nQM1I|K?h7$19(QvssjNu745PB^+?W&S&lbr8T6VNXPj{%5$d`pN+Vp{4R6d;4RvMm?bsSWqM?V^*FRA2zbUMSr^>T2Yn+kt>Iw0r0lgc3Hx{qV zJH@Jsvu4doqlCt%S7l}Bkz^hls`^5#d^3m;MdJ)5kC<32McZ4ZZWCST;PWeXY3Ri?K^%g=;j^rnkv&+cuHiW2u?R~ z)yK!rwZ;J~y53WYqH`#t$KOq^1O`HYtjjPBHo^~|hpK|el--w4dHGo~=xqG(7@>a5 z`c|LvhqFo}o;yb>B2L(wXYTEq^%uBevn0I8)4=HcK!CDzkJK< zg%Kq*hg>|u;HEukEG!6NvMFM4yK5ie ziR)2SiI^a#*O9Iyz1DKhp4Ah_x%F}bL(Q4_XdJQ^VYBgkW0iN ztdxZ+bW;Rbcu#2PdWfu;VFQ}KI3MYjdNpd-8Pe!b;*k)gmLzQpWYZ)DovYFJ+K|D@bG zj%^a@yN-75-G6`CtM3Z)Ip>vyD6jaVM2s&0KiY5Hfav_a)=?*(>$@Lh{r4V|_EUMA za@F3i(F7Asx;<#TppRhqu3!@Q(8?+5DSoNz!j%?iB09DQrW6Xlzk>Z5e>!EWT|+b? zBXdBSFhDMIWPYV@T64_zHc%Smi%#b!diCJw?6F4)s^aDHj&3DDxN!uH%c(RCddXEIaoi#}#WL z{AUeYt@3X8dCj;KDMYogPn5_j*D_O>o5_z30jeppg;`>xml_x<38&sgn?#JjIkbFa zBwu<#xJOyQ4KDwD04KbBWfHEs(#BdRJr{DSBHb{ z`zDi|&UYC{mKaJpIiQJPYlSjOUq;`Yxe`mZ8Hkvyz?}JRv?g7fr%n7IGYZvgvN|7^ zkxWfJ#LJ$H-N4KC?%jc{vWM*Wm9Sj4l5&0GBMHYZMGgNE7(v;1nr!%Q68@j#?NI1{ zio$|Xv*!^k-yFP+SyydO|KW*UkyT2U_}(=aDAyi@X)Y?+r9jW5z~zCV^aI+w)TpjY zqGZV7=VupGXq7fvGRE(6I1=Ad%Oq!wCBBEAhN*;+#3#MT3s4!8K_{cD=)g{>H!qM4 zgGkaZ8duT;mP=7X6761omFE_+?jZUUEzyryMAK?DRBi6R^(q|;Fqgex=+?jtS&Jn1 z@#2%j_isZU_nu0RYe6mNPsWoePwK3DjuTjhZ}j;=QnCO2jm<-+uUZWDFwTRHDr+0k zR)aAtXdst>TN4RJZ2aEy`3Ggr*)e~tg?b4U`5+mxP9aQW3*QU~_X zMeAZT;^aZ^i(Y-d=Zq8c*S*3=mf5}`#0bMWtz8|F8jXh*FPIVSsWIzHBHUH4gTleH ztR{}VK8p$jVuG$ee{Abw9~f++>M}i?FJ_z5=3V4C!M{;=o4qKU%>Gs5Y+2UWlw<2C znHL2NX#ECRiz<21pPqP4p4scvv9&yIE)4$4p@Ls@c&vJXc(DnA{!$s}ZX%_J2&J4c zM|-K2-wU;BJ>9KnFj%1zhN^L1Af062S*1yTbE92j_ACkN`qbpwO3Stdw!qWCD$`x% z5v0vnPLQgv+-X`N+*trHplWm3)Kfx2@%Uw#Fu3{uQpSQ29~8M1@bZX0QP3{UVk_tW*^E0RoPM}!ddj_e(~r=j{Ro;lFg3fN zzWBWI^yHPXJiiOmL6NQH2S1ZM*r}kIec32c8G-j8tv%)KRqP^6j$HjM9;p}b3ofpq zoKZidMKV#u{s%4deY`W$odJruUo^@cIsIwP{ctqAV_+3_qyB1}N3jTjSH27?=L(_q zZNBNU(D7teGsrCzfnirh5V)no&!QsU7lNjv*?saz-T_9o#OMCTEKtL2A7OxAeL@tp z`dCKpF(A>|uFCWeKmP6{8yYzxyAE2S0~-Srt**ltl8M`nWH9GAxiy55+@uL)1^>2( z_TO)N+~IE3_B}oxVPbq?9fxw_3D@2T$!CCr-U_-HQ*WC5{c|7&)wM)?bk@)=13f1> z5z}Ktf4Jb0SASfZB%ezdBH_CjLdTc#;q3AzPyCm)2iBqK=?7d}l1}SHx&H5vYledm!g(-|L|A9g9G=wJ@2+_52x?c(eZig@`l zG2Dg7(aHDd5HV`;!?FexQe_ay1qK-Xjh)SR z1_W>#MSKqG#Zg`noUl0%-@DI%gGynn2|~n=j~X}2(%=Y|CNy3SUTlz zaoxi{r?lKnwA_}UW6fm{Nul}tyoBiJ2Sshua$Euaq991idlKhj#*nMCI_pO%q?9>F zxoJ4^{L=s;xxQgN;#PGWDtwns*>W+JIIi-;0plt@wh;3;6Bg!l83Wj0Txak(>Vn|2PKjJ;Cd?}t@91Nal| zziZK(NzSUJm7|8Is!BBGl{Za^Z#mn@Z3a2%m_ofw$2reUm5>}uw>bD}_}EwXyGopr zWHXYJX3zCsO{+}dYqA!pc@&9)oscsW-_(s-wS?=VctUlUI+zwv~!=Nv7~MpIn|zfLyfaO+7+hg zSIbZKKifMrRv`M_K>EmT3+J|&Y^k>(zT4%_9=vP22uVNGLH~#JL*u{I4c7I2YkIqt z{kTP5jpBEFEX#SOe0e^p@m(_cE0nN_cF6OVC~)xaAVVK9cJD`x=j0Uu5vwia@!Y7| zQE4T;RKJ3T%{5!wIZ~GetUoEEu_5+Qy=uH;nHX9=4vdjg%~3$FvFrGgtXTJ*yAC^zv z?e8x&UkEr83^gO}UY^NL+_N1gh!%7_FT^h1J1s^02ZaX*&uDUz`I+yHnbW|v%VkbZ zE*S||-NI~pkql=Q@guuvO{C4Hn>>HYr6`u#Tkzr|A6XY?mVYZthXYtQ;BE=zV2)3H zyFYnRnr*@Dw(^nVOH-8DW$KIXPG+$O-Y9p7_u&YkmR{k=7bxCKTn{fSmRpq?n(yUq zPMxlXO9Y028gC@ErmUo0JzjZUH(WEy36rtd22=s@@u8L&c9}W>85NdoX-OX(#{|xF zE$9hGd+4z%g(P=%01XIT6K-YeU@_m_rr^b|u1x(7D*(CD`KydZ=1M{=?~bH>=OW9& zNvGycnl6s6{TYoXbyBp26gAsBkOzRM(_)9_!RRv&VGRVl%hkT>0_I9h^Ih>wh=QtZ zKby;7Y(Lr(SJJ3Bv&*H1F)lzu9P@qmA^bqeJ!xaHy2R$UTl5|7tYhmOaT`nZs5^~& zPWrDzd*!V*bV<^YX)o*SMy20nZ)KK;Y6?wNh6b+L6mv-ojoBv%Wfr46zgE#J2v>Ia z8GprB)T^~=PDV=IXsm1HR(79xXHw(@w*|XZeu~Scz1B7>@~g^OnK%Kk0t2Ora0@{PaqzPrg8O z8jf%%G|=a^B*`govV$h{!%LE%D7)SyZ|&e48j9GLU*D6zkHLuGU59@uSW}MODH~ET zK_QVA{$BN3?RoZVE}W!|JnBk0f{okCJ>q1&$fXM4Nt3hj`Qr=#4Te6i#F-Q@i zYGS0|;CKkH7^?V6=U5V^PU%tMDnC?C0)-ayg$h(5!f>Jwk)_qN2^W(Ij+NH623z&k zXMmTfmZ2WGO>q-yd%u(_uO#4Q7%mF_s7)pS8^1UrOgOmyLe6^~0p7ao0V_HRao%TP z@~jSZ9wr6Stm?A<9K_we!gwLuL78$HX$pXanyrxuWKeWGrVT8d}7>S zyQqBmlIwH3`~|*eLf?`{)AS)b(dmeHgmq-{XO-sxpXkUK8)DboOP%vHw0>{#kjqwQ zZ~vDl08WU8Aj~n&K-d;>Su_%IJ4ftmz zB_a2UB%j|4QzR2TyresZ5}_J#-HkjH%A8xG{^kKEB6}Q&znY1nzD_SOBCK}&M^7!zwE+oaz-dhwEsR4 zPXoOr5Gy-2$Z^jRtkY&~!1699j-7(`NgO&B&)4WaiORjBI!_Hlr)l9-=Ba%Pv8gEtA&K?GDPCx9adD9{ zG_B!atZKrCCE5A4lMs&OuA>EUWu8y5lHwzTev}=^2 z;`JfEJk8l-)VL)ud#X32OnGY&QO;^YiFW)b?+oXbv=(n!ra->OzLEOOqGPGug-EnE z$$jfq+E7uo+-B)-GM{4uaf}z4Mf(fVPy{m>!Px(L|JURb%9uGhtKbs7!m?}XRB|(& zCdwcPU;=U!RJsoJ?9ta1ks3NZb8MZ|P>huYMC7Y4d)=g$_oRctoz7@OuPHc|_d+1G zhXzo*DKvBg!)ccMFI>?;SM*wIoNDeu=e~NwD06k%LN5UYSXN!W@M`*)sH~;F$QL19 zec{h6X$ZuSS4cgt!?YEUU7VRRb{11a`y$w72(HnlFwiaa*>h9z4K!Ky{>}!$axHvB4u>W-=fOp!N^G@x{92sd+H zOs1wn+xuA#)opsM0t^++1HjhodiDYAoKIOFKz1qSWOt!>mQRBR?vCCe%<32JkwD^Fg|yIdJc*@=ooPsPFSkvd33Zrqipr}US=9bSKc90jNfsPZ zr*#zId@FVq+|Wza60>2xs4CE|zbJSVvNW|d$HK@fmJ=0!;Jnj7F7t9fb7-g~w@=^o zL56>WdkQNXM+Y@sqlgk|*>8+~`uR&K#MOXBa`2a)-n8vag_Y$>jr-#1`nR8mSl)N* zq48<(y~;ZqKTg12ex3_yy0$#FsNkAK|4zm^n>;)53k`@Gs;PcxB0$Saxm$R`6Ubi* z2jQrc{~<0E!-j+;gg&I+3uw0h|_kS$x?-56a+Xn2~0x@q8_eBRXGT${$Of`5U;(^}Dz4lVOEjyq(`?2{r z+k3@UxAmdBll0RqfT?LnjV(bD@o{gfW(F7eDQ%R`c1skjRq{+l0m{u4iG zpuvAm6>10i45QfqR2?$PHKQJ?dD=MVq*~EWYz$63wEXRCkCTOxYJrEoFZ}C35QdOm zJO5qYiTuQuZLvt+s<_yVb>ptH20gPc2JKopAH;dONziv+@qzRCWd&O0RAcy8v;tMy zvpumNrKsukQj>)4h~th@uQsSg%E|`pVn+xG1f)+G>Bs3~(|6UT zJ}&kM3C&+59xD8tWyj*je5YAuRiUTtjMtjsq9(HkW>vRs7fFX2Mr7d6rSbMh7x*%c zSp~uF>0@uLcdiLojhnK+Hz_7V+~=xl(D~2L(<_}DnI}UE#yZnZEgP%ni|qy)rlHB@ zCyp&`{9FMC9tJ;IbpoQ_H}4CzpuM|sQrB?YT_*U4j1yNlhe|4%+|qP&osRfKb9Pw) ztemI#3nJ7}p6=ay*?PK%`^GSCE7IH>v6@r{I?#UxM{?o+vc|B6xP#;#>$mOIOEGr- zuzB9poruwi;ns?fz3Ji0%eRNE_fXfZ4tN<;*Q3Zb2%Ar+%!bU~@ZoxobM8O4v|BgU z1Wuwt^N_vV%#vTE8g|R*GXD!uA-2!9X132x`NH6jtDe$>9o_gkY-6vEta%V@Hs#SJ z+nTR_xugCWWAvtOka{`V5GE}c3YihpfKxvjqB4l6db;NJ2kE@;ZL^#+k$mBx@G|h1 zoH~6(Q*nS)qrlrqa!bUp-pH<)%#TT~n+lrsgo=lHK(6ECh(5_wFV#-Gc#$8F_qI_{ zof-HcN{P)YJzF%dn#jeikK!CVyCHIgz=T~6n>(wLtW2X>lYs`Ck zv%oL>Wm_aoQ3MfYQrVus?|TvrVwzJ4prosivDqV9n8f&Jgm2+SYQ(qS2O*%R;OCDQXbz~4rxIkj)d~t$mm2(P1GDVnicc(om~#qXA;*#e8il?kU?<|0ObnW4 zv$UmF2WJiWQ{gqyr02Kdrm%uP(J8+xnTuu-(^*pnlqr-o8yt4EsjM(;h}}W@t5=nD z6pBQqdODp1H>@Qn$Qf8AO8*%ZndXQsGuLcyfp17(Qd4*U+y)O#ptAln`H^p$Be^*@ z-b`LRfvj=>8>8868ud`$(-Nh5Gk-{JPj9<&1!zw>5Ykw**Qbh&=il#zHyC2mT#>t{ z6kIkz`ik}*YQFr0a#z=E`MMFDP6%+x@U8oDs@_3AP_^E-S8pnaY1$~g~AmWtg0I}9tb?_cioN&d;tDVJn1n& z2b{HHq@Jxu%xk?*ho1Klx~|8P$yWA zw^Z7}7PZ@Y*4a1wCuvgMc4he@grKaJoWE5sd(ypz_j9-nYjeCF%G1;ZI4<1p)Q`FV z*F-k|?Y><7oXz1K?%(=OV@BW3p;f3*&IQ&8zDect8+C<;;27IJDp+UOXx`>oO=wxNx z)fKyj$;qLIm?3n%h|f5QDZ$r2$C4*)wuyXzx-7|WGB_IHHqMuiIGTe;n_S<}CNr^M zzLy6sq%b6{hkG>%9YZL29d7Q6VmO%min$BPxdM$zf$Yi5PaA*aHeC4VLkYLgb0$y| zo|e!8iL;}As1o5SEMCnN|GHASAoi|iwdzHY7e;>omL0tB{EqhWLlAqaC4XR_OpH#j z-^S)eFm_y;cp$n%4}14?&qWWSRf2hd`$>^L;Jc#||B1#5)r7OB<CECz ztWGxdjU^gpbyYZxS;dJAgV6^3%zu1bRIp}KFyCu^9xo>{fUX^pj91rLPl)x>L%?XQ z@hqI(t-zZ7Y>C|{@4=P`c2;6{CI!#)rTl68zQ(C8D*^wjgx4#8yY8&$rOw)p$LB%1 zy*Q^=PDF=r&!abcPDt!;9~#a z&tEq)!2COeaLM*>1lXUD-yn3%KmD8wgK`-$~d{DVCQ6+l+3 zoi?CEkl&8S*ZgRXA?+=|VHJ|XUUG@lZxb#B0-A=u!ZTf&< z+inJdA}vu(EZ4)e81jB_Ij&;!ex#U2dT7)f*i`Ym5hEdU+mCPD)LJ0Xuo)g~WVJjD zLE9O*^DR7AG8=>#)*@?%>yLWYbv&0Vdd}JQU%u0aXnRwqc(U_xkE8$fui{FFZEVvP z?c=-|mgb3a6e+`-3F&(YD%J4?Ad8UH-Dlz#3DcVQNZO&%H9%;=QF5+2o)y0mh&gih z%34`;TOJtR5}x$sH?Dpsh)L$|>_p6q<_HUyMp(*UyPcNKf8#)r{K-0`Z$dzzN`F62 z@zC5Ons~`Vf`^_-+H%=B0=&_NZ*6Nr?H-6eYLPlWg~69_Nm<2-0&r+vMC7-HIzGT6o*-Q zieoa`_IX-wrX;=TR0qf7tNH94-?6C|!L9a{qp-rQ4(ox)9<`H~&d z>8310s51w0l{AWa>ONbJ@5N&=MST(DU(3yuaFW=6)c}&3BgSwT-K+l<*~yPldgXH) z?lTli1tKe@49Bxs_cKKw5fFq78o-<}el6U+bV3+jP_4BG8mw$MVTi?k<8io*y{v05 z9Wqk0(n1csVTEY>Jn>v1TsJBvan-hY^H(o72m6$==ovSiYKJ(|ErruQtc8#rXa!UN zlD#iEVu&<{pMlLlpx7gHG;IISw}n}I0`8Pr{S&CAu?^J;H1(~8mEGIfiW#Kg>4M?7 z7~T*~8#jhqea_6tJLk}vY=eg!^lZQNJ2D)bXUwI3Xi%%ri%0m&ip`M5m;Bjvj(<7U zih&IpGMAU-M?#X%qLL3PaIi<0C^Cj8t=7Da*%i@{Fim~uAUU#8Roy*L?-m`yGRh)Gh%t;H@_wB`U-nF#^w zx6H@h%DE6~AdCJ`=2Emx@dR5e&amx7tb^up`miAboN8rQj#Zd8qQQ!Z+i3Z(l!%nX zRXlRiq_&@_b(xHj2hSCs4dLnUIgQIs3{hc4!mu0L?y|3YQC0`CGv6-F68qB>On5}Y6U2bPqLD9kK%+PidG*=?>$ z_q3UF-LeLrwuW<%rlwALZ651Dqxc{=(a73<<6);v2VoHYa_p5@zc)AfC|ljF^Y;_f zO#RFG)G>Wo)@sWDFImK2A!Q!_8t2bsHbe>7tcRuCFSW82fz_O{sG`Hq2Xhx9L+=2q>hf`5i1;!@-$qOeQd~4neAD&zduaaF0Tt&`` zrFOLm()XXAhg5Mr9gd{qwA~j|fUT$ikKuj#nqZrLI-Y{8qj3FtGaGbw2a#k}sZQ|O zkYhkqMU~M?s~>amd~jbP_$xWTp<18K3lt5X3-OHe2a@@Pvz;f1%O<^H%MH7~_NG%` z&fvdX{eKf}fA6_H9Z07)Xx!MIbQ`dqTPj}H6VO*n)6RuScCRC1mpxg{TQU77myH86 zpNoI?cM9QO!mF`$EnuoQY&oi+MD^>hnq|#;2na<{S-&q;bWw+LS=IZA2 z4v_v&HP@RwiaIBdY`fQRGPlQR;L|e_4N)6BG%-PqCs)icu{Xg9$Z4iy?a?8s*S=cy zQTU7f;qQ7@bG6<-I~>_OD?Uw*&eqrq3&`8E4+OoBb%ySz_Mdv0bz{sicMm;$SNz+H zZ>EK#I*6NgNVOiYUYq;_*L%K@wGeA}glZiJ4wW51ugZ=SOtrN~?k9a{n-|H-SKkkq ze&Sb1nvE9&8lN*~ob%R_x(r)DY#{Fjq;kI~?2?!$O0 zK45tZiVL=&UNb8asRixQ^@PENjcu;H;Zo1MI2(3Od13dvHEQ`If!f?m4axo zkJ{(cC|SKsbn7mshb#J3tQ@KFd+~76$E2$gHASl$JORoVA7Ya6k#>{V?AwG|_^l}TYS{r}_wObs>-y1$lP=q%*V zO}-dN9rNna-_x5o`!pKCUuj{!1vuY zO5`NZ-5E_^l(5sPt6tZPKvsB*#)0XZR%g9>O|wcw(M8j08VzS@6Nz3(e%vDarwh4l z_o)se{8EdNoy%R;S=4N1o_|iC*&bG16Ps983)I z%!PzTrWY)xgqbqH?QRI->)$AS@a~gZ@4=iq8`pGX!^b$C08Q2Kr@JyIKO$U^HW`0o zncs$TkX)}A5M*K4M_qd;l|(dq+pVq9s;Iu%zkcS`q${ySy|~}O=620GV1 zDbCDI;Je_UzfWL@kw5es3U0R5D8D4T&+H4Q>E`|FNX_R=cF)8foE`De*Znv5Zpv#a z48aa^1x+KHIJh8n8Bj6N%lohvDf@P1%>jT2LCmOgwx+nZBJ@j!uf6CKyE@9?^Y5>y zz`@F>wH|G)6_fYv0ZH;jcQ;piTV1bpf57DM3v4+_i3QFM6ZZcRwd%CvpWrpc%(&O` zr#_WgyDN(Y#uy?YP%pWivz>Oi;RB|SL9)ZUR(6R)|H94LW!d4ESi&}3V!nYKe1P`7 zf>zfR(V7Q+?Mr#2-Nsf=O6OAdfytWJiGWq>Gg@Zz9;sIAht8V&ecBp15TGB9RXP$ zaF?du{N9h=wZIzD70+$0GY|qbcg`7XFKn+9yvs{j{j1dv{E#zZv6UwKjx+xc>__H{ zA%|g=t&PvczwHaP`Ubq*mR~~jMU9;F0#DJsM|v!V;CZdP(z?IO>EH2v=Xo{0=)KOD z@`K)p8H9d!MOgJAG>32Q^>2Tt!}7g`n898T+502zri99zcai> zzT=F-v-Q}#i_#ErRTESHMTVQQo^5RiN%C-+LG@6wRp3y3^QbOrsDM5$^5XhUJjs@` z!>vibP;M>EYs9Jo?T2c5)Njv_He3@AaH%2Asm-A*;dbCHDf4{!W z9b%q-o@XyPjZHa4|6K5;Ed-Xtlt1GE=qRxmXRzz!P3I~2F0sg~|J5cX#qTARJ%vL3 zFt#1w^@h&en@goGw+;f+AJUE!iTTuN4s72vDKRw>4C$X}CsJ!^r7%asnRuuc4qZmm zjoZP)d0Q@nI$#q4spp$foFbbroKEt33!3f-G##-jg#RC1Ul|rh(zZ*`;O-U(8XyFB z2u>ily9IZ52<{Mq>)-^}8Qd)}xHGuByB~J<-S6G~&N)Bkx_WxLs=9lgdaRzh?-C58 z4mv2*iy&|4@z^}?P7J3x#T-Q!tp3Q5Z(scg0i`w{jR>0hoQSjIfHWW16Y_Ixwus7| z6o0JQ40r!9;f0x29{f6wcBh4lmRRA69q&D~#9JSIlp#Z|(U*N2bhZja(DtM8DN2vX zwkD`S)!>#4#M-a2m2--tO|t^7skqH1{lHH288Gs*oZlE`Ds{nBGHG^~;n5WDt#z$> zhRLq?+6@`+AEp^OdW9hgpm*OYThOr-9Jf8}6>h26f);&QZ|x=T&e+?*unFU^VT@%< z>=USM*o_99Hci@Tvg!U3BzgQ$;Xm1n^W8&EQL7E3=N0O&+P=odcBd!imsQi`O-xgz zc09;c_t*2XSt8TXCMs)_fwqi+$&-0-P$J|)FxW^A)cgI;!@}j)!9x`a`w9|$XsvnW zBi85Bg-?DmRz|U1%nDP$R9vsu$@rR!v)+orXb^Z$FU=O|d4O}@vxOq?Q+9GWAUj-XGCTif z0S>Y8a<~JvK8bU~XEZ-J>JVQ~2{cscaak{W@Kh`j0&1goHgaKJKNi77E$xB_4|`__ zhLNNl5t*wYZ|0s{%9pJCNcVEd`|WQz4Q8h|%ugZd|a>xY$o#})s_MWN4-D>j1TR^o;L)Mt!C&ud2~us`85c%765&7&0K65oUCm`(%SA>Emu5=rxMtZ$Z zLdn>+gLm#G#RxGT)m>F~+s_ktMR|)aXUXhWv#IsdXu@Js;Vc@TRYSiKJiV_kN0gS% zY3ZxZ&I2G*ePPjSc1P>$-jojqf+%(qwtt!^xKwUecH*=R4w@P*2Jr}!7 zyW7^-+97dvCf1;Kh&7{x?gN-B_=Gb)k}IIzU-4F{G1F%BEfKl1D9;^!^>EuJN99Kt z;RfX%3DGN-T8d@ZG||@fZY@I7O#5H@16ukUIw!s{T?gew&}56KiOO@y)%_>N^>qnh?F z9>>b0<>ShVUYHBL!PyJ5{X@tbJ22m=_nwe5Tow-cCDS+kGU#aT`7ue9vBhmcP<@+UW=9b=F+n zatmefTKm`rPfJaqJrBcp3`?esz*#;K{AR9&c<$*)!*@-6l;6FqwGR1vbo$zZ9}E~q zH$i~WFx0I>&?zO&n}EBd?vH!unU{OJzCoR+7gOU9@b(?;V;PRhd#^g8vdGQ2?x-P< zN!unKpoji(gn)utF;38js{KqXPLVrmV6J1a9Ph43f;c^rW=gz;h06ZEieNJ)uf};i z@)LG`=wyH+ub>7A_D+9`xERZaG8sj#Hb%uZrLc6)Xl18>wi_QK?Rx^vQi+$Gdo!$- zJ}Fjbo2ZO#Cebi{oOEn*8hOMxM{axlaD`3o@RM#@X~KOx3D>eZvBPkmDA?3E+UeH*tV(CfjTip-8KO2)vu3G{jss=cGnoSg^Hz#N zy2DupkR4fG0=UeyI>q$ownbzM9F$B4lUNYSjYH}ZC4tuP)0vUo@`{3fJ+Kf*qXHk0 zeNG=?8BL{iPvqU4Ue9JBCF3k>EOhW*VdB}Sj@F1}XhyxTQ^!-0&CXV^*lJORXM&C^ z@W~RZcw)z9fs%5aZ>`jT-0OV^pCA;87c{pohU*Tx;aO<=+gsxfM~251pAGc$ zEO*+F<`aR&8vIJ(CMv_*TcJP!51dol@1cTk`2;&|eAphJ$$RWi3(rCW_k`zQP67m$ z$@`8zLteJ3(%X=`MMK|k+docLHLsw{Am0Y-!wJ1Ievt8@y?b->h;qn+xcKKnFCnu9 zDoezNeZQ?AKpm8*T#TfhpmYA{E;#v(ZezKU)V#0Ael20|%SdxWIGdtFU-XV$6KYME zN4pI;H|y*r5E{K%0WVRRwtiUWgq*-)vI*Wa=*TFMt$y|-@eKd_ujP$+S`60hi$8l2 zfI=fjh}%(i(y7zOi-V5CeL`!izV~@O>oE4AMPfF!3i`j&RuXJAJc7`{rQ80OWQf17 zVCS9&U(BPVn<32bi4Fz#H0QMxbF~9pjLT|$6ps^%#VxgWQ{QbC8E4G;px=NvgaB}& zI-zmQwekoHF#)LZGVWS(sHDp^0kjLRFaq0#KAzt88LSqM%5e0$fNcB>KSi=}lw-$~!0D*)$612I5 z>B=)xMtMftsaGXLd9{iFrTPjhPF*+Y<|YBFsg0aae0$Po;#^|o050+5k>2;7ja^>IL7yz=ZPL|6|_p5 zoc6GrABYflTp15tnFw-qin)w-f>_Or1)BlzGug~3&Ct1ROB&!OcK#xo{M`j7M)~k> z(8nc1$?6e2aX5l_qFBzGx#7pY#a#&y94`I8qDu{PQJX3w0%AZPpJbiLSc9r*4yvE`weA#0sOotJl_XF{dikI^W6qxHL2FBPIV-#|CM71n;ER9xzwgHgBdVp<+{$;C%-eqg8`cn;{_nh^4Gjsv`^g{aT=S`d@ zYWPm8gKi>A*Jj&^!3SnYZL8YV-beK#IvO4N4hTtCPadaFLjGINfRskJ_m2~Ru5+d5 zLz~*Czl=+OvOOx&D=v9BOlz6H44pI~#HlY1CS1f7nJU59bnOZ0pR9~K*Q+Cneo?a%X8i&$%>^?ZKd|#5& zcG5fyMtP9Ft4hEev^Iv7i_^&cG-I{-LLEWO(E)FXQbgk%A%e?RY>FMsmBU;C&0e#H~%%Cp8i z=RvTdQ10b)W1AV};%ZeuYtPozokPkbGUI-N(T__%vS#>el<;IA$AMbJ;-VIkz>2Uy zTQ1;2P6=Re!EgVdI6jxEA*{m+!@Dhg)9>x^A$IPF3<^LA56iCsMK_+ zEzuQUJ%HxU(?PC)ixFr-`k4ocEcZugA^|Mfu_!h-uA&%Eb`i`uB&N}6o$~V+>O?xy zx>*<}->N!5FoLj%Kh1}1(K|tE(iQOOoU6}G23iFuUdBKe3U^Q3S)&=F7oLOEs5reM z+G4(GRK(85v3z#rYl^u&?;A-B{)Bt1?>RAwQ+%EeTv|jgJDt9wbjxLTGLzEZ?qG@- z${}%j*}^vUZzxD}VN4@un5{OZtURJ%@f3Rq57_XeI}9X@8cyvdDI!8lr(WrNzbx)_ z(9zhm8SnaVjG`V)@C4{4CQ^q5_9&O=<*}65d_4Hs^2Hb=ehDQ4WW&W1&q+KWa6h$L%yo5CClr5x}GkG5{wrHC#@}$h#@O`WzV)=0XB4 zb$?YrX7Dl&5{)uMR#5>I&V?PKzfKfmL$T**@jPa#Yec;Qn$+GmCWgteg`O|1P=8l! zWJ-wN{nU!IW=cuv7TU6mjA0a64AgB8ka{0+u)gQ?LPAbL%S+CtHsHWrp*`IS#aMEKVnUPc}2$L&WQkm)IE% zA5OvBC`#@S+ZzE~JP$}G3{q`$tN_4i!XWDM$0ZG<9a#xQ&KdJa)H3+UXOhAnOa8Fy zc#smKsL{j5jke94rD9M_uQ?K}t5|;dQZXG3fSIloAym6$mi@&R%`0i+T+zI!>`9Qx z8pU+*T_XsW*7;W@ezWW>$n>@vSx#O0rEgbFv1k4sTl#WafFoDM3I(yQa3b|x3C+sh z4ysVE5hs_J10%*!)@;E&&xz(Db3GBo$dEZXJ^Hm5bStXUhse{CY|b11nZYXk%j?}o z;wlyhEygTMg2T~cN4I#Bk*f2-vRI4prI22_N7lRNVHxOlLgZ+daq;8P)!z`2>moHp zoH%IgYJn3O)u8>??HxQ*J3JrE4mRfCV|oVk8HWb5q6j0}YxU0r!B=N#0_?AJ&3szg zBKewn%}r^dJ!7`5=+Mp)6Iwf*;iZi#+1O?w0uiPp(em1+ruS*H>zp;k!=iQ`Z~u%# zd*;Cw_ziEyI%{5yr+s*SB!9~IwNJQK`M4n{&~rMJ>;CLwqwl~Ki! z9u>^ReoR^uDKRy%MyXGuO`DPIdM!V{zLy4?e=+{>EdsPnBFp-~C>c#umb6w^;W*YU z$mFyq=`&&~k~-by(V$jJ*2i-8^QRkuc?$iLvpW)xrG6yMw#RXQvla|v8|qn>2xyp7 zjNm4omF6u7O-><$wyyTd<>z3X1Ous2-KXU|{?4k2zG$CZrgzoP=ZewLTsX=!(uYKet(mcFU~zP71bCn?}anwPS(?Mu?NJh~Bf=Pl?COaom68NO(W!qPXM! z#1WIm>+)k@!icR>z&60cH&HF|mzzlo-M+33`0LtoD}wnD81?AFlKNmK#~^Q=E z5i&nH=KYS(DMcSb05HN7#SZvt;>)OE8Ni4aCoA8>)Iu`q0Pghl)8;eSW(-%G=yh4= z+1yT2vAip!Ik(Kr6~P=dPYYp`&XF(u9KyC@Vkj|*m9hGxU9W&sQe2XM?&K*9*X-#Q z4pSUQB#s8%z;IdY4yPAG?pg0;%2g@uF~El{KY)QUS#Qc;5oKfZB_spdo^h;EM4qiF zlIKhsuU{nx>^u~R!9fu2lZ($i*2?$}`kXtS+zV6xBR$Z5@7e487#aT6 z)cQ?$NE+YuI*y)@cZN^``pozYu@$_3k%?3L;>mrA6FGk*tl7O@2!B}By_ch%67hxU zHqQ%!1{JsEpnC!NIt8mecUgPhA61X_tC}qEg}tCAR{jv`oOUJ$IGXI4Z#KIxYHe3oVn`d< z*XNh*;-~jI%}tz~SWC(;*_;%9d<9(2I`qjrQD<5F%qtY>RfBr{V~BLIgs;95g65p zK?!mmH>OdH=7!TN5da^ZWAjfDSpsX4a#?U}vg?YcDoA=wiNw)(2++hCjmUR5R0vDZ z8_-$WvWcMzF2%%pU^Oyf_tALt{{Av*T* zt11C_l%IfM!W;pFd{#^!7k<-gVb1~@PI=Bf+Cdxy^Q~oxET$T>cIOUO;xTrEDcnPj?w{my+9^03Uu*Y! zt@icO7#0b#e0+k2o_)yS>RRNB#c50916S%nUuTW9*oH0Z_z&{LX3ICOjESER5t(g-b5gC~pM|;}BnH||(;4xM7BUw> zw~e|n%9HzHvgVxvODgfS?fgU6I87m_hm@UPxEvep`eMx)5K}8KN7~XadK>-=X-k2> zQ>sNt<`Dgw2}!%JkaJvu@9XG>YOl76oNBmz<2&A$GIB4BFo$Nww`cBO-_+Ac5-O8Z zLhM8s+Ve};(;F*qw-sRD3?rn4<@k*l#IrDWp(7wuf2w;%p!j7Hi@fx0ry9b!gY#pc zFCj%!ht<+n0;Lm_lYYpq2{#(0exVwCC2zM|?}_2D>L0<9@*WrUNLV4Dh*GafwLSLAlT z8Asl=wqyQTcgrB08pC+1=AFxNMzVd#IEb-gbRlgH*eGXX2MA&cp8bs1>@lk=Z^J|w zk&-%5P$M;^FzFEcEGHsM7XMk(*iooBs%#D*RidT;MQ2zLFsWb9F=$Tu+e)3D-9y(6 zMU!7+c>WsvVYBeeTt8=Bu;1sX7DfKLbYCLGw8wxDt1@wvsbzzOFmm7kivQdB7PTEt zJ_y8T1X-^VLXWhCkMj!=*o3{n?zr(CbpxEH{po$V`%?I)|BoLQ#7&=j8i~!BixAKt?;o1{~gLV=Fx4cYAEuE_vQ%up`0jd z0^f;D!t>Op`>O5z(N5ON{qjzubN7Qq9Y%R0in%)vgt;M3;&0X83js01M1oz<^^Z^t zqBbSQUpz5U(8&>TmDEh@vgOdwzT^AkA~ptO=dst2+|#~;d-+tuH(=^mP(BKrP~`4# z8idDT5h>-Wr+!P!gsiXB5(?1_rak7M#6+n|fOwTy;B1MVeZ_W*x^YO)K;8Jxyufdj z7Qoi-#$nAN<}|DV_jCUX!u#$hH;pbz%g}`+?IM!Bh`3#02QWej;G+P z5u$GC1XSnWaai9r+b1gN(cTqKtyINY@89EimNq1D>rvm=T2md2C2I5@$<1U&k5*m5W_>$B7cZtK6Ba z5r&`r)}c|z#9$c%jq9gJqu9G~NBi@8V9reKMGLOqyv)4;o}n zmgf!X7miqXyhS_F3vf`8bFniN=L2W0OoKX7c^Zs!X^%7G^G(|7(K9ukHs9xWD~%5fNs$>7`S zFooUwOC=cwX-B7@hv^Qv)4q8Wg1~Qx%fhuDOt_u1+OXud)i+Lj547dnU-KQWN{+vs z`>bB%Z^Qau6Z@ChWzYSW*`-=@Cn33`m7E|dYpaysG^ZsQ&x14D&-J_X9~Ajcjy^7% zA>!5ZTei`qRv1E;rf^3kMx+_gmC}(+oi_FwTzV;7Nb%YLL&vlSeoDUJskNq?bOYR;~*&lFk2_es{DXgTOm z;wIrQU`1yU0@A^*epf z#GlUkCqA+Tg*kFGC1}Q+PEw+S%$4aM-if=E$TIFJ7W=Vr(hu8lB}%z6L1ND|LJ}%T zG{Y!`$B!DrFviWiRga^KNirX_h-c?{h5F@=v+|OGXfs~JeJVxe$mMM~uSnr*pAeF9 zOu~D-Hj0ZbdBd9PL(97nc~opMVq>Fo>!diyL-Xj&WF!%^OHUA27* z*;);Y-O#^aVR9Fsk+--A$UO$tP4bX3aFohKkdX$>)Hn!?Bxl?-u{2rL=ML3za@E{! ztoOM6XOk1czwNGJ!o3xL{b*4#wJI6uVo0Fjj&r1})JDcnv_^j9lU(13UTzrjxloA! zB5tJq+p;NbFM(bdO+2|Mv$n|Vcf2fOQk~MFoomlYA>-#14e{T@7le>t8=7cJSlER- z-9s{N`;tVa%J}eNbD>KShC;-QjUwR+kS|!SbYC|c*5FX!VJQ3IEvVLNTtu=*5VUAD zh8bAy1S$juGjeM1_>%+B_ax|}%N};Ip{jnH{N&ChJ@mpM@;uN7I??wl_RmLr4uTAD zIwE+V-e;ljmcNY)S-;@--PCEL%8Z0F#GR-CfkTqe+%ta4R;?%8j|~U7kMsInB&2B= zR-11?_zUI*!r(ObCYlV&e1`LY}oQ()fiG&Pjfw*{&^EQT;L=8a0guYe;QrR|ud4@cGk1-!1)F9=vZUKMTS z9Q+?=A~`H{?e&~?v*?h9pbIP)Xezot_4xiIji5_|Q*qILQ}T(~ttp+MMXg4myk)Z$ zX9|Jnvs{t3*gVin@t29HjLm)q-c*Q#Z!$;WMQnATP3$%hEc#-;^ya}P-zk{iE-hLr zko(#nGF1FIuLE!s)8gx5Wkw&^JCYak;|9A)V)%R_=4VMFitenF-GQF$(~++5)C=VN zwjfZC;Hq_=rx7Nb!#LX`b?3*{iQa&}%FSbg+<&AJyMXSGlF$FdApbmakodQr%s=&~ zbXH_cCVG=EhUFB>6ygaKGqmjaLC)lYOSdVNjE4O={CXQi&>ix+9!j2Edv~m>bCF&d&c`bVMwDNJPwTQw*8pEYb`X z{9F1IkI;mGP6<2oh3Ms@Vkv(#=7<&*VazexlkWVz;^4Ts$XLS!zyyDr8s0K3=-UUA zWCzsZleE}3%egqgIV4bw1Jra#nWN(V^l^UDsf#=@$K7$EyNzEO6F@(dt2M({B{%RX z;Ya#Wh+r;GffSO!K}7@Rhrf;spr`^y=ST3U?vl&VUsf7GnQjxYiW9o#Vc;Wp{ zkijIhv0w5$0rEpG>R)kaRKtwa4n-~sTjanlK`FsA0<+@6mcseoj!ZoqGT<57T2RFs z0uf#fNie*5JbQEoUbV#Wpp|sFM|JkE7#r)pb|8@Ch6FL(Q*u0B3u%CaIdTRa z>6}C2jJObUnXz&qqj07a9nE-QpSMQDN>3(L1WyaL3YR!gVm{e*vXIzgoUC-2IPBxn5WNux+MeQimCtn{}JNZ{Lar83G zH;M^I$^Wbj0!CePMp+pckynCa^d>a(kmB-$z8#srs#=LUU7@SJNI%tQB3^#cIokqjU`Xw1fIH~ zifPKFnXsh!3XXDCKgqyYL5;K|ZnzJAc>@n9M;w2NtJFVJe{wM_W`s~3RoQIMl&3`K zQV3QENijc@A}4)*zAKfnnL*P83p;%Q&xygQGOD4UUgY?E^dP`fU1dQc9NgPez`-x4 zSG8X?Ci+cDP*t6w1t^+95NweB&NLW17vgQ+HbhMfkA>#0rN%Nq2cqkZMwpYGFjaLl z?xrI<+wwdZ9or8qsy>1mDldovo3Q7gX$=a25$7~A6nZ)C!qSwAlkTMlzt9ScT=`Q( zI@Cn>Y1h&XhGeL*A;&8P;Kr?e(lcg}!n|c)GsYCn22Cc<_eCbDm0KiYQR%AQ4^=f<5kW;)T6zGH zgx+vd7$rKhnKN1>tzZyrc~M6rf@lSZl~iDpK(2!-}HOoS4FG>z^B-XD{!N=(z_<@tV0&%gI< z##x`Ex60~(bdi$Qihc9DkQB~&%X{Og*=^ZurKDyc=9yXi(78&rub02K}~{y7bXwG({j@s$sKgcvjb zw%(3jYLRF>6@(J`Y;YOFhyQXRea>d+r}Z=*s7Bg!0MWMmZvT4?KDW1dz-pBm4RRNU z6D`FF-Omk^iUbw|#mP@IPc;#qTJ28C5)>9bE3gK7wsa>VgJU#eN5NwTEBYS~UZX6? zeYX=+goU=HMyPRiLjNiCUV9&pQXg{xXhZ|_WvqY3rGgQIom?uV&*yWa&997Zo~g_a!DoF>Ll4RNV&(6%+RSvXiQuom=1< zOP@%rilNyQ524h)KG!N_+Vw(~QpkKt4fgBfv~-HVp5*IuD7Rr7(}G69RI4b-z(BcOF_+y#xZw;P-(+}{j%VdRoMwk;M8%ydQs*9;>%Q~r5B$xT^%R554kLcT(JNYBoKfh0 z$_A-oh^s~!)BzRQ=@hJT%s7{ZO47nsR-d8%yh5{{n3edDqE=FiG~6dfJbNhc#ynnI znMj}O+m-MLX>t--6cI|8ZfKDC_?(h7&RN;KWt8o-H@}$E1x*;y@aoZ!Uo}$4L53ri zdV;w~0r~(+Th>vFP7HLHmZ_z$wivI=*O_rK9OQT9${V$F#@6hsU>ZS^F>z{QsoS(4 zGqut1U?Uc++60dpf<6!)Kp#c+tqQK;q`6~TTh@CXTnc$?<@rwr8f8Bsiy-YaNjLyv zadFKaMD*Nrf7l3dbB#J`i^k<1o&r5QJEp>}c*W0RUCsRRjVO4JJ-c5nmpA$?JX*xh zw90~5LQ#QC$HgCRC3G1Og)MBz@Q`os&v^BOQ%uf+=f|v5m1v)fU%M+xHUBBVMg8$q1480B+w=0f3^GiBw8^w9xomQLD%SRsZ5h#%>RvUWJi z5r1i`^i$%XD`J#Be}EH?PmLS%DvO_8S$FC-f&=?MnlxHpcvM5*7|S-KJ?LBaTwSyX z$B3AB(~;<*-ubdctnVAsbCA;tHP zCs_wN5>)AJA3CPO^_iT+#G&!r1H4Mwj6uH-tXV|6e)OJ7lKa8_zidWCrQgxj(JE(t z2DDGe*}FvaH8Uk`_!9GqXJ)crNj1%NW;r?$bzO0x5)>+!#|f+fVx=5`?+JoAcc%2% zELt0)scJ23Y~^9!3=Tx>Dj9efLwb+562OSyLHBOWv(CdLB6Day~!wF)YyQOF?5TV51XFL>&6!=q5b z#A2u2H0Ow>6#V4*GGDBCEAp0@$mu~PX&5dJF%(`2eAt|mbo@$Y{TZe8rEe+el1w+OR!!cjlL!!z1 znoOs^0pRdt`uICj$Pbi!+d1R8Y4W8q7e!`qb&=;~GqwI?U?73VCEh`%Dh}<3^R4!nzmADy;;fA_Q7fw5n-#6vGSyVZHkzD?HKYx!fBK5B~^Y`gLE_INg{AX_O zpQDAbVf{0@{a42sasP7A{`uQ_l-NH3xc>2Eue(I37>b(T{CE8Ii=af=qGq_i&P44t z7yoesJ(_{9v^)Q5_&-g!-~UNd`gJBTRGXB3! z-P48&>3seeami)2b4iH#MaS>yiraDXx08*`|N9{@YN-})j_cP)+ix9pJnyVdpZpqp zmE?z!7SYHBy&>Y3fCIp2{Zz@{Pxg-+{qrw7`)#*&Ot z-ZSH3eo*>m{rJIcEdoZ{plB?p2&WtN=-XMu(4qsOI&%ML+n-F9q18}pk_ z88L=~&`fpH^->wEg4(jCI=ea{;AKCK z%iIZgPP6N7zgrSbk={Z{XKsOK_UZ*YESc;GAsF7oY{1z0(0|m>?uJ|+H5iQgwp@ar zd7p<*gq*QJj{J`d`k^w*w=&$`N+AN%4?@I}XIb?+F-KNb8VhX*`p?Ss9A0F194&Wn zd{rROj97U0-JIVO_$(q>H&7s5PMr9jMAI6OVM(ntrvFiJmPg~VDYsH{p7ZkxrgC-`QbDb(vf$2bmGp_wr}%-QQ5f9yly5a zUedcodV9y!237f-g}z$d$h!}z4gmr=tXHbB@%5gSTCUT5p-u!-aM?i-nd+@5mF~S@ z`(8MPqI_=O4>3>M_3II&R&!ScLNV#`BFrwAs}HB~E7#Mv>-b0g!Cu$v=lDJp%ctAq zonB}oQNL?h(31c??e0&(x4HEz-w}Mb4yw#-P_3*M9Om`!Q^hLW}~yKD?;`(1GuppBR4IiD~}NTjT(XGs-2$<*@#EaUsLic-e z+Z7BqZszK^{*zUM`vaQJ71s*_S-~jaG4rHH=A%Y;R^?0V?GSy!O@`B-a`%GM_Hd(J zY10qrTY1c?>;}@}!)g3$R{Wu#Kvj=8zW1g2VfZ=@h-iE8+DdFFUtM0tjw1r!8*-gsCr;a*KG}5p5s*N`e&kA!-Ke^Ejs7N@jPT^FrM2b-;4yyH|R8 z{Jv23}~pb&4KX93-n%PZktYWl$^o;zM=%Wf~Q%MCX} zgL4meYqT(+qjn6gXQ7j>rQW)Jp^%ry5nB8C=bgDM5b_K7<^@~lh4|&|%1c}5nmvi< ztlNf{;JIhZ)61=rHA7SRRqO_rpBb&*jqFM^`HMdKMt|D|zWo9g6xQ)$;z<`e=_AqO zu3H<@j-ZJN@}cLM)!99BBU*C|X^-UcmGP~W-^)vv4;qyA*^ck(?CJ8&Gf~?M7{uS~ zBlt$r?orcw?m=|bVSDT8z`pI5j31TP$Bv$^cj3CpdIl;b zAEp`b`Zu3!d{GI*q!gK7z*m> zW6r{DNTeUDB3B$(H{ad&M&>>y!3=8Ey^Jb#>i5o6drUTEeoD0H$sMiGtV;-j5)kN=1 zXmv>;r!u)H`!ZjzYdRKz^e!2Ja{%c4Ahxky6y-=qSioQjUR07cSmM)37sIED!4w#L z9%4|SZm68oQy)2_g)V<&`nqOaRziG3oiD8aw2YCRadf#c&ps;B7Fe#B^-EFFs*PQU z<~VN@-#tm@J)`jl4FgNXz1l%0eFZwjUn&Fy_<4E@A>2JHtJ~nZMjt;b2GMlYp79a1 z{&PVT4ZrC6@0^x!0yHE$N95SQblY^acsi$&Nz&)Dns76!>lq?s5@){h;)HTG&zAac z(t%USJJw%n(=s2W&nz2&h)wu)_sIno7{@s02qDygnHVF)9DP6zJwe0Y~wZjwvad3TUjyQ*8RH{pjIBG z1b*xjX96ku1X>zab+iDD@2v?+%x;#W_qE%UeQp29a$?C*AtqT7ob#gg+}j;F3P4Fk z&h{cV`XD-=9BX#Cz|dt32i=}RP;SNa?&+ih>kf{P!rU#3jR^fUg8bI*l0X!>R}5sb zZ?fZ3*jSzckr%oVnDP(ABt%xJDCE-eziYpzzks*Vpj zeRI>=nB{v!UIqQMsN`UJQ&)kxcvWKIC1YPgzVP>>&b!Hb!=SLYXeWyU{z4V@7mI2E zHPQ-Z({dL}HX^jH`L>Pga~cb)3MKHmGmH1E8pUm+Gqzh*?6vvMp}<8sxd*aQKcOD# z+9r0o8+yxPx^EHH_xuN(dcv|umL035qsq|`B+l8vNlM*Z|3rNbf>z9Z!Z+>^h{y^RlK3Rz z6+V<)D2f+u&2mu7 zZ;WC1c?$|hGbrX(ad7qyPFCGujnI5^g5LBTk*2#s{lw1x)r%nC-d92hFaP?LHB>@F z8p_h>TK3)8WNNM}T0+TWX0Vx%>dDYC1fBj6-7$9@oq=$+2CFxcTY<%Zh8D1BdaxRj z;8InPA}N`qJD{D|wkc!QkiuxJ;Dxld#&>74BmCUpn0{c`Z9kf@Jl%6>(xOjIVr}hE zF7(6ZW}@xEj7eH~U1RG&qCJrQGm<2Hqk*Yrw4lI;G5cjwcJpw}2?7RXWozh}a}_y5 zzaIjog=*|6ZnTk~9qyyj+_4q5DBFXn^M}Vv-#>b`P`!~YXM6NdoXjY!68Z(Z+`YrX zUnMv#kbXXC!hvXpH&H9B8L=?0m|G*XaU(bcYSJ08QVM_iGdazzH8E>~~vz*H`Ky|EWMpg(LzaH>)*E&>()Y~ks0xHOX1TbiLo zCvr_;2vhxrW@u>d1ob~ecmJZ!d|pe~;vnd5|qN*99W2)&7(vgU2Lg#f0z(n<$a>5zwQ`^Kr zd5L(#=$(HTQYA?E(pEoKVr9B01xW#~KrVUt5^Y~9y6gkRp3z$&_dpy?f0qvXdsWuw zxh@66LlGd-jE6Z>@z(Nw#Vx8{XB?fq&0@?9s?M00q?vj5+jke+=g@5j+{wsIHJ6(B zT|G^B`b$kpH^-R$B50U4S{duXR8oSYQ6t6;nojgPx#Sp)g@`Q5yli_td9g%SmkDT5&$W1wa!c>Gw?E!X zf%jO}Zps!UOuzW+fsRF_O?rSu^H0odt|j9pV7BT8|7p9bqJ(|*SsDVl%T zR{1S_2<`1~o6<3fS#R=giEGPvtWBH0#V2fBjc<3_jTGG(DFS%fedSDNNKV7E#lLW4 zX|aA1oU;v&%y+X9c0tu;C$u@Tc7`**6uPzmFjc;i5nk)qi*kX8GXsPl6>X5PiBiqX zu}j{+qRT8#TYfJ^`hC)QI&TyHP>rtZCBNx^Qmi2U(buZ-CIWwPktN2VonPX^n(PgYErE1))p@?G zf}Q8hX&+1E2N}l+auWV4Jk1ZEyM^Bu+uW^*W8Fon<~iy~vkl14vt(1ZZl7%IYxC{b z+e%KJ!}GU19M&e))^H{Xh-$OhOOhl-n_@MUAb$+`p3xI7xidIEVIh7Gg?W6 z;=cHZuJqbcaIKDN;9zg$AR%<(e0lLl^bM&-_H<4gS}aGz#by-BU#`BkkGx5oOX?2H zv8qEgMO$Zffx8#!0@&(ky#lRB#n;zLp4aI87W*u@Mz&S0=^+J~q16|S85=;M=rkEV z`3=?$Zbe0eJ!t{qohvR-yTA;{K>F?S<;RL#b_-0sb>$tazQkk}>^1@a78+_&fo zdWS-gySV>PTVELz2duT-mKHA*FBB>66la0r?y|U+;_kXgaVfBc?&2&g6etuZ?rsYd zcZ%Br#cgr;_~!n4@7zp&B$>%fl9@bb@;v9{_&+@B<_v~wY^xF91vAfD9(vx`YS2Yp zSbOVzg+&WA1~Q=M^nx&N?_Xx#9r6_(@gCY;6iax&GK~{HUW&poY4ivcpmLIEKiuA$ zLr||*+tI8QsaH0sGvpW1tiH~TH5vMu?V~C}&>OxZYBDFD&h(@;0R9I^Ugf}5-it8p z9_`K*2FVZQZ-O6x1>b%1BVr#S`2yz)-k81X{bGC*;<(b|cAknRn<=8*@}~cvApJr&mcbh6ui)430y`$6GvsX=TMyB{34#9f0!902^N+| z@_r!D#=${?#%Qf>w*IzGFgYXB$uuZTcK#W-vU$GUhWaeUbz`pXd4o+u z2nX}NwZW}YmLjXn(ZxcV$tbULCp7V;s!>N?B+;?&P`O#I>N-+zE-mA;*$+zRItrdo zyDSdx!fsCSd>93+cO*Y>=qRhQU05{aq%19rCRt+u2XHl3kdXS3Xze5#=Jw#12Bw=s z2~LBlj5$`GF{+tbK_?YsGKL-LU)HF&C2BHbe%mFLRJbUm+K{%0)Wkdh>)gz@q_z{S zJ+nNo=cR&0AF#8{$kAPwJ4;9wFtN%Z@TJ_0n3XzDb9##j55Z<3F3bDFS2dMGw6BvE zU;)05<}Dh}bRal(p*Gus<;)N2{aUs!GRPjh+>^}R0Ot(qV)7eDY4`(UFq`~aO)fe} zg#i_Iv&|J$cobD(+b?-KuZb$oSUa-#g7m=5qzT{)lofM&P5hSh!a^3DoHci^fU;1C z6reUkwJ1&Ht4o@S8&jBmY^MoQPPoZINd^BV7&=ba9t(0UOe~IchlO#nMqF?vrbGFj z|2niVa(>TlTieC<^>R=Hzv{q%P^7gAcZqVas-T^ax5Q(HlY^0-Vi?=fwO^gow@QY! z$nET(Gs{xqi77i!@-MLfbSN|b^(t0tV}{>N`EoVqyqnB*{1nB_klWb#dr$pDc|>E0Rdl|}4{M<= zp%ZA%L>ox8kk7}kScTO9_a6lbD55jX%{8x%*I)nz??+1T^b{Mj!G;Wr4Ap~v0M;bn zZx5z*0s;bGcm#&PJH7mte~bj%kDI6SI4w|;v}RBs^~WI_HG#%NdT8~#8IOzB7Yj4M zG@(*5G@E$lF+IB7O^V<~Snmbj=r#v~xv3<0b?=J9NHH2bpvrlPI#|`4J|ds*AVrgV zZX)_}vX?3A0I{;U_V@P>ztv}d8%bo-N7GZ(l+OkSqo1o$aqCb3;RQlIzUA)B3xm*{ z9e+HV@tr=%7XDEl3 zd}BI@_<@T}GP3&dZJ`>uYV?u(Sbg0qYzEa|7(CWDUQE6hx$grYd%V$dUxRHTz-o!1 zD|Z5D#gFeHraUM6IE|{cdauQ6Wk;;lCx5z~A1UQ`u}LZnm8)fy0lv6%QV#qc>n`~# zc{AHI3_E7FDql)15;!>stB1be?r03MEs;C;9O89|HLwUS>*A~s_2z&|iVseeDYqHV zPO=&P+l5~uX@$yHw&hBa!%&A1*1J&$G_L=jgzLYm^s-&~!KaHhoW%ri^dS)~GLEE?A@dxS^sWU+zNoOb%dr<1P(A{n7ZHTl|! zG;|gd!R)hS(+ZbYFRMYg>vv_c`~sZgVj+Vn>|{<7Or|<>q_xP4`G`{Ep98K9P409= z`cY@wo&wkfDYF{W{2@6PB7?4Cai0p9D#(eA^+_O=)(PaNP*(fV8wG7r?Njf}_HsXw z`eUh0QAB;vBD%`v!(bkz%|rUJ6&00krXqwXx8#cAt$X{yUo*u5Qcc|j2OTL@W1XQX ze&i-=$FVGgz>q7$*30hS!uN-IEe{Jj{E93Ml+P#5tl zux3$767Amm)En~p5Atu4UgUN(?Xz1E;S50ue-im!?NIrV4sQ6~$X;&pXw>i~2a~g< z3fx^Cv5Ar71c%mqOl-ne7R{)4&CqM)G(ByUq0}hr!WT&3r7{dv`&!PQNimX=Pr%~b zJXRYkEHrC%ckH*m?wwoFF)!@Q#b8X9mB28<)JOC#N0(cHX=60ZY8fIG99_vbGB!GYD2z`O3q%yH z$NM8szi||;c)rZOd^Ym(ZBMIgbP8fmR5KtbYP%p>R$?m58o4{XAk5wl=xU(GNxF^X zt$o-g!6SmT z0v{ySl7*+EoRB6f+p?x2-2;}QhP42Qqk=83wWFgC>gr9l&YE81i&xJRiiPE|{qnW) zAO3_ev9M?heDl#gg4UC)0W6bFO`@m8Xun=Iq0Z9qCINu>K2%p1NJ_iCG;3{=ln~J{dEI zQ(%LR+TSu0M8||ZdCb)JPMvd8Ig@}ly@*5Gb2g3DsnAfs))pze3ec8djpXO*Z3I+Y zlJ~|X!QSRFG6qO|$H2WueaXa4^P1}`D|kI7E;3T;vf_zC;!Fu}j*0oJnygzy>HY5i ziSMcu^i^timZ3P1yqPIRi7$Fp?2sVJI&;Eyg8xP*SbqOIu?xrPQ%p$oLV;283dQQB zax_OszwTW$nhUlgwlVvvH7!NFsd9VV4NcC31J1gUBHf=D___=uEmaf#D7y;J`V~+< z5GBo762&+!5t4p2HqUWC5*|u2;qqqBOu_vSMgZILC~pbxLN|7N)#5i;(EpZyTKNa( z5BYFCD4e-0Tj(K??E0VwTyta$S^8rHRK@?6<7xk><#stq0(oPvnb zpstM~k&0BsxP+}?gn<5Md+Wq70IaVMUP!DwOhhd)E$veTbO8;P^7}lZg7P>*bJ~S< z`(W_iCb=|LUIqe^LW7Kf9`QtlXfbTb;Om$Z; zGbHd4gGq5!E5kOr##9#fj^plUuaK`kAcUN_UDE4HCnhLVp7zkHp;Lpt$Uyz*pQ&$X z)GS(n2HevGAqK5)v6YkDK8i@r`kTe6iH* z@JWK+0WSZdL*MI;!7@esnGNs@fFdMyzp+8p(%&^DzIG7!Ik>*-lEoUIHk^UHG5!v2 z7A$1(lec)JNnaV*1@`Oa_ts=l%i2=dn2i_?qX~wrfP-8n0o=KiQ8{A89gBnUKVl4) z2S3q0{|k7EO{}cpm4a^6J{}dcf*__RjK{?eU{9zG0HiA;;URR7@8F;QErLtNS#qlg z>!C0%l4eG(=ucYi3<1c6nK{2U4SETO{nEli%oJ&V;xhw{Zu^6mbOazV_g5w(o;N(_ znQIp*f+=sO_cX3bQmhhVYzq6m)oPxsySxm~`Sa^xdTOSO^(TXm#jsiWSU50Q>G_@< z*f!}U=$nyv(<>l|=b*Mi4sG~YPkqzas{eoZv;W8n5h297^M|D(b7BkI7mg$A@?E7Z zRI2Ty)xW8S&%uPqT6tdAjx^QB@}9;GLOgEM zjqcl&z+Za>D-9zL^858#o+#!JihvNili7IIqHMc+Q>N#O88OTvqk7z%KFT9 zdqEz~l!a_cnJxm{N!kFR0%5f#d>h3TAAY;)FAL-=PMXOu_Sv!aQgN^^Zm#pO6zt!# zVN+@OOWL2K2GWN}xISgBd7Ws`q6VMq)2}64#uKHh;z-W8)dD@0i301PWv=m>0_K}9 zp~bA|?&BX-U76Y1gSr>){NS&jL-!Uu0z zX)d#=q4!4Gs*Gpnvsy3J(h=vuGKM+8W+B~T*E!&0T~J;}TlWheXMBq=-$KPGEA^oE zf3jt;fpUz2epc|Dge7b0Qjon}rrF*=6~Tkq>>R-3IR>Zkx;~q;_W59aVOcL%;SeS> zvK6<<3brCX(ut$dZa0l#MD6spbLh%vh+;hv4&xKExj?vGxRIJ`yh;`Z0m70m9Fdw4 zTFBl35>+GrxK#fVUhAmKZ*6{Wr3VYF?*gy>JWM1P;6L}qhHIK5iv&4$XO_TUcFFn| z(l2AXp5W<~-NRjEWp@~P^A%vU8h3#dey}+{C77z%ScMsKIp}wLGycQpm9l@$=iTW= z2}6s8Fc-BlO*@y$iZc9cblkPuBZ_gqiF90D3PuhJRm(GtgvtQ2fh=`XLmzr_ej$Jt z1FUM}|tnV4PGjp!dl5Fob^^un)pH1$Uy4l;4M0!i3i8ga{BMkK|r;-T6rI9OA zV4eqOcqS|YwQSReM}_F9lbJ(tbSL`NXScx;b_H*2gT(?fVjS`P*;Rh3s&Y>}rkrVY z^(^5Ck?bU!CI9g1om?WuLSysOl{{KfAp}}OW)A%Tn>>)rJ#Q(R-*{B4)<5Y{tJr!p z9}&H0i1~JJ+I)1Ub(fSa98Xc(6$0TRjEzHni{&9wgOcw`>gpj+4uVNgfS^n0S+U%Z z2!%$;U81P5O_g}Lcv~%YUh1FP$2|s5`wa#pO+Z#}BW}h|bMlE6LM|8Blrs{X<4Yw^ zsVt>OTBt05*q^*M=j7BZ{O0v>UM!)L9>EO?!4;V@F%$Tfo7<+k@@VZiHl(w4Q{{v3 z5yV4no^iN5VG<)_uW?<`-GHI$oO|@F(O5yt=0o~@R`Aspi-$Q;`W2N#_08XRUKvG{ zIn8O4Bg1wkCRoW>g^`5*Z_e2MNR&Mc1~?u?5CtHg|DMjZwF=dxm4RS0ng=D2{9m2( zKUnoX^~*vun~R~ud&@tXtyN3A#@EE2sj_*TD;YkdqUrqiZ}69QzttZ3p|+1GV`3D} zo+1i;6;7|p&<$5GRdDFfNt78>Pj)wDrozTcn<0`VrSuomGFI^qh zgiVx)3jtqMZ-(V|MOj(dzZ+ez4qJ6rryQx;hxb)=yZ4;3MY9cmNekb%U?ybftN&_C zCb=&;$3_)E4B6^YG0UXImWcj|-pD&IjOGH>=Tm9lZwSIG7*ePfN5g%*v zbk^sbIpLlGnxk5XVX@3B>qmhaAH27=tgX>oJr*zD?4Yh{WuX|aj%=;N?-!+4lL{QWL4{; z@~};54n8Hlf`-E^N2ImcdKR{*$U{q5sQ127>|)P4=XgW?N#DnA(Cc4`HW%@F5Wax^ z&;oX0hq8)6P5lAUKtBOEV~h1p?o=w&x%ryI722=y+O)#61kr;~Gi++W z=@n1;z*__l@jj#x1!w>Mz(v!R^+bBP7|4d-0`0X+SmdbwOjaCu&{ZkQ?@&K<_3!e$ z9HES|4TuyJn_V9I_gW?T!^X^lB3_P9ZZOpuWmqDw5}Axa-2t7F|J{Q!0uT4RS{e=- zL|tb#BL9^Q_EoE~WWs`CF?%V@Y(|A~wpoj5wz8?!fV=he%tU=Qc`Oq4*iYX(LFB zYqVg zBpk$_-{Oy5sju#SYD6dRaxTuk^p>70gK-6_d8RWhaF_`Oby!F(2i2;3Z*Oah(7=`xvIegsk$rECbP0&?6QAvs7&6? z5>lUw0b|ou0*Xv6p@~B7 zcgTBuJ!|kk*zq?n2YPxoH#qxlFOSfk{6H-z1RNm6ruy;@>R^u|nF)y2KCnr({vr+6bX)CsPQhX;fQ1TiDD){fY#88N%`RV+d@?Md}M zb{#IGLKFtf{@0mAJjOYpxrmF43%^`^m?y@5Wnp1Kx5|XsrQpitV!ct#cJ8$EE&88t z2y^=OJCU(ZGU61otV-}7o=yvHX`te|ngzG4$b?}J=j_`fI1*JZw-4mc58*3nuT1#y z9@AXo<>LRs`Ky(0&JU}53qcQ_cg6@#%&rji&N%0td-H26tnSZSEDttf?HqH%qVW}+ zOIfsNeLVXiY>Vi*(JEi18t&?&Y5$w!`_Egu>k*g0jp(J+6+XKGU)n)Y*yBR?o0n^k zPq){MRBq!D#r?n5^5!9r1I?wduyDsqghAayk1pThnhC#DSc literal 0 HcmV?d00001 diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_navigate.png b/common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_navigate.png new file mode 100644 index 0000000000000000000000000000000000000000..46b03cbd04feabbec25faedb5304492e246dbee9 GIT binary patch literal 94099 zcmdSBWmKHY5;mHI0Kp;n;KAKp1_|yuxVyVc0>Le~ySuv#?h@SH-Q6zdd}r@{&RTbU zYu%rBe$1?X+p4;&x~lqpYJ%ltL=j*Cupd5rKoA%EuJGZ*=kO07J}!TOdViwvO}+E| z=d**LxYC#RkLMS|p!YJiqp+%@qK&bmi=MsF2NP=>DD=aH_~%7v#};rGP5%JpyXsk$jCw{U~5mv#K6Qx$iTwI%+AHiKqx0oDEwW?Kmq~( z!w13-;@<_7TvLx%Ts)=s2s$pto7kI@451kXzgCHk%;(%vu>w3^qEYRx2HF9n-h*1Ou14>go#?K<*1;hjc&b`3ecQ+EJZF{L_Zs}L4SE*-SW1Jyn zWn~hdfI#3cWWg^)|L5zEq05KA3&@+J#Nx#Nsd;a6fh!Jx`MVgjmq_xqcLshNE9dxU zgdUu1^O<6%NwL31L>A;3C%LKkrx?V((&lj&6cIs2K|!H4#mUWWpr`k0tX;2E?el4gT(6u5!G8Z|Xv5U~ebZz% ztB~U2ifi-5T1t6&dD&6s72n}BA*ZTK8dGII7c!A5!@EYQObMqyN?|pcz z@V%q=^=126th~A#A%_g_T=4P^&jPfXvK~xdUmoxcnLB?Gg z-sm#oh_Hq^rrImqh<+oDFJ=afBh}t*YWA6N=D{d^h|84 zNOPp>rw_&!cZ05kg)Cxgp>C~Sx$2P0movUrBVL_RbzhLN7b&{k1#UQ({AOq_} zX66rA3@$wXP;_z7rs+rkEtYbJZ9M5qJ}R>=r5|8ughG1aDmrdC4pi=?s@h-oJ`eLbHElQ}B4AiTg+U2Zb_!$mO&%)K5NlOQlrj zH^>$$n6iHxxbtkeBm|uXpqeCQgp>jGZCfU{RS0(;%nfc>IlbkkTFpo&l4;Lm$Sx72FT2RA9Vz|&vUcnwXd(3m+vgZ) z6CVqIr7aC~k%BMI%4}I~NlmAp4BVAm;`^un)}(KWyiP?)6G0mn2Gf~@)8RN(SPUPS znVGvV=tvGXg{8{M1S)(s^2~lqOj5XY?Vom6{`wW=o6X;|g~j0OWlfEHQVIhX`cwZR zIOkQX&CZTN_H9VbebT)aX$Mvf)x(Q=3YalC-W$)5Da8V<^4#;HKBaacKs2%`*tCNg zv7?A8YG<^C*1nh)*sg<+nVi#=rsHE+vzWY4g0pG)Rp{Kw=el{XpRs77;eyv0b;@(p zPOg>%bT&NK9kP*&u(3u!&S0>LDB(Ht$>c*fp3FVE@$FojE!mGzgTRaKbaT&z>5sn7 zOk2Z1JHR0BHR zt$cY3Mu6?YLb;gCoshIyk4a>3N4~{UM74UBEFmQ$i-0CViKUkREl78p%HaTq09!7D zh(@RKOPJbAM{fo#b$BkX+QQl~1j^!WxAua~_F`Epj3UuA{1=qw)~p`|LtW=g&4*d> zhYW_X^5;}a=n#hO5&K1oQgD$|HCRb)SeP^w%fe5kAJUp{S$;~~&hg|ld9HXc;NLmT z0&<=$MBuY(F@U5hsi)HGcdQ-mRT=2ZKmDz%L31W7fEaCaDfsWgS@TOd)atQ+&f1Ch zk1DFp&p${?ZVC#@ZEdC}@2b(`nN5RB*t^N;!oe)G`$Qtjr2F0+j8zxn#DU8yzkc!b zea{gvG49Iac4@L3j3nYMY3nL3dKbwaB zii%2WXJ_~0=kF(?o^*}D%C|D<$7STQ&efYLlJLK6O4PwuQN#r{(~fSR*UrmhwNvLa znOZOqYW?;0gaU~m+sUzKa+vzyDdh4wPK{m~(8Q6*TnoC%?U}fJF%eMyV~WP3nMS#- zKVIbUs+xSj;nWSJ)Y~>Sh<~jM;T|qd(g-@bMTa|T*3Ighc*D@Rkps2fWRmc|*^Kcc)YF~!OFFo~Y)JYF?@YDU7ejvPwvIUH%d zgAIb_7cemkEz`OruPgd|rrxo9MVfd&Y7$$?DBx8YH{lf-<320uSLR0>kG^!dlBh1L z!v(F|nEJ|u^0z98E568$D zScu_MVPvE2w$3wtZ#ET|{lZ?KW{E&d?1_9O)k0EmPKoVB%Ej}&4i=TjX&PUT&nrq# z5n#k&DP~y8Po!HiV+;caJ-m+%NY^C2c@|UafRwN~S^Wv1Y0lQQHDVr*-zuGpqU6Q# zbI+3#hh!`4pPg*_8Y5C%oXyH!aNqIs`)pw+X?Ot6?(Q-Z`(8jW%!bpUobfWp$no*N zMBB{05OmoyQ3}(>aj`~wxmVLWGW`o;uiSPkn!v9a+9>q&&t(m zcJtt5Us>vgG0&>5z*ozS+x>sEXY2;bJPvCA-h1S44)+fa8(Uj`*%Xwk(~m|h0EFV= zYU5Er2pZ)l{+VKBMKBL-(>8Ggi5|({i+f>QSy`z&p3aK}AK)l!!GJYiV}cYPFT0k- zsYM+Al{A9maBT($6Z*;#n)vTdL`<_QEiS@AJCF3=j0(2mko4yCKmfY|@Vg%tZQk57c57K_^$(ksK?=d2{DLX`Dhqd0;>3mk1u0uYwH~NjfuZpvx$M7 zy+E_cp8h3$+T)RfgG1NAz%M05ntrTj0NR}s#7#B$Eh&*3GN zg60Z}%@1`XAn57o5pg-ryT-e_yNk41oC9djw4&6TVE=RWyRx^U-myeW#;j`7muM8- zfyj->|3lkm8kQN!DvcWFrKkw@-_ApYNVLeeVI!q)qVlmcTB|MJ%66#!>TnWYmr!u< zW^9>vDD_HDCyAM|aUF=gs}@kz?{M#Kh^nm2d>j`y?4Fl!K?GgElG7N9I(7=NfE^=n z70x>n6s_&)t(ie-2ltmN zTdxx)^EBbFaHdL*$Q}kvmhnYQnrY%r1=g0*-Av&h!HkD5fY=cW|6n!R_8Vqn?;mP} zCZyr|oIG8qlFZB_BcoNdgP|s)_#>QvFh+za96vTDtMmYrHz@nNAx%KC@pLnJS>`{R zZx{l?HOtMJXr*38g57RDyQ_6=40=U%MozD)GGdDR&CA`SPy?epn*K1LOBkc5YnD@& z_x*~<^J%I;iGB1`mq}(!0#H;~>}$1m^EuET#dC|HrX=0u-B{p?cNY?MuY5S&vG4B| z5Wl!;Y-|KY!pZ$3he0D3LkR_x0MuGCu2Rk7i6UjnZ*=MXYacTAX6xxqL3tFAaE%Jp z);7B@FTcqPvZy+t^Cvo6IQ+Fj6&v1|#ze?G4dFLCO0B19w1YnRhsc+0fsSEVK2#lJ zKLO*{8V5tl(J3|Rzwv@rI!)pA*L=lkfEX9B7RY1mcm;)%wHWb_-SAg5!sGO!6V2*w zAqj7Zyc2i#77`jmP4mBp$>{Sm!c9c^FO{N)Uch9Nt+8;<^>j+d^@)m+sB>G8Q-^QH z_5~H37q-M+A?W#)qC&>$UUu#hF%5{kkKSTJ70;^ey$wk)h=|5Vvt{(2Z78yrlcp2N ziMqy$zXG(974BC##{zq7X6!z4CoN~eTD#%dIhTD8EP86R`PDeZY&L65hxzQ2Z*ia> zi&q<0Dal;4v)i3p(Q=vIfNAt-Nl5bui^FFn{vbHUv1^y(9tnvH7oO4ZxKB~Tt=vni zqkXwcEq0Miyl_EbmWUGR3C=Sx0;S@@$u%8)9s6#i`0&?BN3J(O!;m*a0lk-sjC$%FG=Xgavp;nvJRTYK z8NN0eQ?!B9&M)dEm)l!I$5Yv-TsmZzSq@!ohVHH@jwKr6`Z>KGIfl7fGUW-*$CG=X zoynpdBg2DudTznPe{!u)@87n{D_;_!nQveFdzsf1%tznO)riQ{npTDbp|B-lI#R+Y6UJqq1|QBcj-O3gO-8=!XMxVa%?* zy(uPyc6U|^ZENFwHv>k)@q5~X!14O`D0J5-sIhl-hWot6Atwl-@Udp(bUI-rU6I3f z3!fcHisWsV4_?a$Njhocx!sPi7tUF)Hz_nVdFhj+vM|EJu)wG-8v$=;Q{E^iZx#eG z{j|}9ozJQEN*|#S(MsP5k!JYTV)b}p1)_e14&l#N%m)i^laPb2)~8nI22%v?P%n1= z9g-HNjz*s{%GzV{hj$JCKBI%CTlFU?;?p2PbZtyz+x4ZBP$zyq#AxUhU^TW|F((uw z7%M?wjhJ#A+sa@?<`p)#X7R8BWQ^Bjc{2PwgI8;6NzLTwh||SxvuuWX&>S6a05F?hdo=E& zjli<$Nr9t}->iTrgZiFSAB|K3SG|Vy^NI`Qq1BpZe~dQ@DA_Rx80?5Y$!pooKj6Ie z{g~~EO>DvBaC)GNQvKZ^rKUNGx?3_oVZSd|%$b~7RU#O;>)+^k$W--@EsXl8{g5sa zj(Lyr)iXh|g>2(x|Fenj^^d6aOk~T;y?!pn&>W{MT|S6AKYYE-zdKb1i)BFT(S%GoMCI=dU-qZd(y+xPh(68vh;@=3RVRA|(09jP? z&JS_xL2|xy)_RToRdfA7|9ZH?mP$=dxJq#R~LIF~~?>9v_ zD%7(P^C`V=R`5vcGW&Sm2g;m!kC#f8U^E{g7Ck#yfA_JClw|h%zJhPU%f*x4%f{ux z{o^2IOS{S`vJuR8v+<|D&v1n6FI(lhm()5t4PZ{C_UfsPbe^e zsDiDB)%~*VoQXkhqQSEKQHbHAi$M%V8B%LE1h)yU)UjrwVQ-NH zcV`PFc}j^C7;01IPX7CuHLMlA4_gv*yL)W1k-F|*O{!6(|8h!tEL=xD0KMbcmE*d} z%i1H$ZBdP^R>Bj+S4mBG_*Ld4pjjys;dPJNa;voSmoLt=sr^-fP+=Pd_pdE$RhEms z)m+f47K(l)k_9z8#w_Mxz@-A(O{Lyh7W;`G`k`r~#MY~@9`=IIA?#gjtINHo=k6?Y zH@>M!n_^ptPK~v;UvZwZj5cv)l+0wWJ_QS7jMdwiY~bj3U^)A`O|k3E6eFNJ z(r2htId!nzVtD^FbK^@v@seVhU~~_YeMzgyV;jnQS5Is%!0wIc>W9H}1!MJmb_gmw zz1uEStRbh&oGlxv8@)Y?z1p8oxePwPfR3cpSO!e->jW2 z(_fg`L%nW5aexM2#H zVqxh$!`cEqtt3PVKd(;;e>-l`#yKHB_#7BOa;BaoPLOs#W1jBijlU)ynjFQH%Mip>SW zVJwo=50SggTVlq0!!Kz?Di1ZW-mf5rY;a;0l{?D#Kf;3WM~aeb9D2LRTZ;3^V((iH)Rn`M#Ph-yJhi$S*i$fSq)N&lA!oYRqouTtbszdmxzfyYics^dw*S1lE^|5C7ZJaGUg2Zy1{mv2d7 zViKk-fH09Q$)nk^F~ppSplk|zog5Yk8W1;k%Q50#LF0Ee5AtXcHa0d~pm%BrI<>J2 z#V0wmow_|e7C@8j#;5lh`sax7a0E;`%}m#eP3-Cs7XkGl<^MQ9JuMq)uI_-2I*Yk4 zaB#%$flZ4L3U;2lP|1a+X{;z=?*#h1V*A}fd_qg+OTVFrF8tz!!!OqT)?=&ngFaH+}XIQ1&>Q!|d(dSW@zA;T8eJCX_qqVHpIr@0d+OAW!Hp~OC~&lDlP*%V2D^%NOpWhG@&Lc$;O z^Qw+qE8JRagTq^kbr!W2b9602?$pnZM-`1NE#Rpo73V0nbhli~H9CciPlnvclrblp zD>1EO($dnDa+&b4JCg)L=@8k-70Ue6I}ukY*bAi zx7lYgK|;u2qi;s2vO`2$;z`Ez|1a$o<^;DrD`NjUCbwb#ABov}7lKv?eV3a8{-~_u zITII>zm%dUpV~_6KORf`reS*@_+lWHQsCX(3W18;P8B-Jb5#7u(Uipm2&a z#SD(sS=1+Ba?{t~VW|MpD=P;tOr&@U2ij4v8SExZ9)%mguLsVaI;x_4j~7YM8b;?- zKQ1SVEoBVeqF;;>w$5+x5Hi;B1l>I*dA5$~DrA_U_a~V-Q7pbi;>uUpBs7#9D_S`$ zh=F}bcBsR5OpSYt8#_v&POl$msZfny;Sbin5UuJarLu$oO)&;i5?U$SVb51bu6m5D zkts!;jj?sCY;~_YLp8bXn6=U>YRnH|rJznXy7I1`7aP7TN=0-cH~*L|0Zdw3cr23p zSd|Nm`caaa3#v7=eL+XWbK4=2k;$B2{CfSO+76E9#PgQ!Y`)%Chf84RFnW9xRGS;U zd0^X9h?adFBGQPwAPZG*nmR~WCc4LI}yXM$!lw{w@M`c}AyB6GN>Di!QP&}f1* zip*>GnUm^F1oIs3ldoM6E7!N`r>TwvvV4Up4pw}9ps~unUk#DZrUu6W| z=E!3&(mR0kR>tnuC#fbUS>~L>Y0vTx<2N3uq~$dvTh)-^7NR zTlb&I=pmPA$r*T&0*41)rROUgU2M9ROU~RkHNQm3Gd}`ad_F4wq9)=ywM`2 zu+siHe*0v1_3tNR5s{L*(Mj6`AfS{F?3}5R(I@wU3{t)jvicQ@>2R(YeM3zV*ZMIq+ zOl)A;n~F$7vEYO!;{3LAN1Z)%{%Knv3WK(euPhjWr?D2ZN*@T(j6;FV2vRZHoyN&%-pU+64MRJ@#?g*CXa!IVezVx86 zmYKrHw{D>!nm+Cn?B#4Y$x{{M`D*a}*`?9zQcW02UG{_5RF$RJhyJWc4{inJ_hwkj z)tDvO$>%dR{f+h~@GW~Tz0P+G>dtTJl4iVW>~=Zcb9a;`DXiSu-Mx^{6>nVkwtOCA z+IvGjPpaHy&!{*)8T>0ZQsUt?;wy_sAyYp{z^aKWTL&1&|Y22bOa_8zs89PRqUkk=z z77F*CSU@0WGTGO|d&hG!2>YG`eRT_}eru8*dna06&5!+ISp*s ze}b7RSd@jEawN2qOi;Be!GcAw-eSu@TN2;Xy%JOH)WYNh>WD$DoX2@)Y=Uzd#^@bw z<4{&dFggg9QwsZBek9u##r*|b<(tmhc5!>#*D@=|#@jgD9La}UpY#_Nzp?jN~fBbr|SDPF1LExS8kJP*R{afW!1>ylEcX>un&xM zvM5Kv7-IH?ge*@2C~Ht>m;)~bfgAvUR+qt&u1Z5q^d@2Qr!O?UWHs#SQ(X4G58@VW z&%e*=bjN@UuD-RM!p|uegv5u7uFTHFRcatV0d5@Jsnzl7)6^JUCQ_xhFmRfog8>Dz(k`^$GWr2MiM*9xZ6@D8ujix!p29 zVSQ0u!>PDzQ{A)S_o|H_J4L`|^q^T;s?SpHPM)^DZY2X@lDy&5FP+jaJJ`7XP?-}XJBsd#D=;I$h1Kn8@?n5ou644;uK*cWZK6w-+fdBwMvPbvsR?h{hhN z?>cj{(c)tey{TYOUgKtoQ;b0^wGmx+!1<;lSaXd0+u>+x{f-%R@9AnaEKce~6VFAI zdW80bQnLs>gC~zGl%U7#onD$DA{#m z<50%`j=YlD3`=ZrQE_PJ*4H5J;$e8|8@F%D1YQg|;1?9yb165~s-%E5I@PwAUqA=`HhuG;@Y1*@*;;Am{TpUpN^<2vPd?Iw0{SzA~FW~`Fr z9l~_zZ*w(L_j*Px=tc!fyMdj!Z&@6grFV6wAu&8vA#Bb7wJ9F)jiCL47e`Y>X`ZDj z9zwUbEfPg@^qgTpQ5w?e~w5n;z#Ht1bhQf&S1Jyw8e)+2% z?GfE86}C;oTzr#OMgy-ipGi(;l)rsK{HlBiUGG_$AVk}O>UOD!0Stmr>av#3oU8hf z%yPZs83{o{>6yejcV=Q1O&m2_hN*MItamU^s_9MVV-he2&0DB3jmRwQ7pFnZccc?c z{es(A4f9Pxg-Hw zw?{c<)Xi@lJ)8*O@mcPM>9=+_cc$I%YAf!ZaF5r)K__Z$ecJMn-V^5|jQ4SVm~b7# zaK_^pYMq@eI`%Q(V9P%7vu_n`F(*H}nAj-Dv=DVT6u&)CMP|B0GVVQb(0 zfd+K9v*q+t4O9;;NRcMEV6LhDr@lEo$LA%+u_>YRjh&5ee*kvvDwUfjBRPS5;;E!N zH#T0zYUP_(!5_PIg84h0QD8!a-Nw9eyEQ0G)4!$4&=~Ic>Z$TRlfGTlg|WTw3f)G# zoC{sw$K-GT(sJ3uw?rUHHbJe}sklA&gv336OoMkj;bU6jj!q!9Px{VcT+Q**g@HK- zIU7~nxt0Z|iW$Hsy``&)0D!{qq==C*nvL>>vz|{`5bf;AOyu11(2)$(}5w=df6r*X18A(jCW!y5E zC$8vpcRU#e^%6pT{R+ zO&)OgPZcoJV+zED*Dsd(g4khNt9~k0L+%_ezAe>@DoZ{$e~Z0{%H69zv`Hfw?A%qb z3d|Zf;oN$7zWs^NqhNY{==t>eo-*D!6v=*Lk@R(mGeKLsUYr~j>W$X2aV1(fkk0O* zV=k8WLUcL6yYb5L>=e^kt^7j+Ev!2sj6q}S(~^omdweVK`+qqM?`D(35pqv5HWsenOdTJbvK*RbSg6N2%YLgDg17?Kg4EB zFxJs}o2V;8)FA&%uj8!A^Mztp37;=Xh25A*Z>!COiA>Y%q@9iUpGq`p(b1%m3e|>Y$(|mN)LvLf zHKl<@+pER+v9$8OUxO>`SJdLpkBZ4`;PS`ZGE!oi|77o3cD0P}gg)NN4v8HJ4zHFC z*nH9zD6-})bT&W*r+M6xDC~5WBOKS9^dx$tSFy`iQcOnM`IXpNbc@K4kR{dno31pl zmW!tu;u)#m%XN=JrDb6Ky2vcyxQ(U43{wMW6Z{88DXN^{7l z>*{rx%MC(d9pE5Dvol; z>rrk+0M695TrqQWl3@ejMV zp{n@{_}9XI>k~tD5{?QP2AcH@z-Eg$#Oe9hBP1p)S<=&wEmBa$1l{HjJ=}5Wv zgAy=;8>(2Q*`9k_xNSa=8HGS$Skzm}FXRc}Hd(1cb1j!uoD9|T;agfqw=@qo@YaF2 z@@UB2x({VZX7#Iom~uX?w7b$egvXb8@w@97fB}` z2QyVPc|Q2mw=}%JX24A9voLhfSFUQNbn3nKOMiGeHwI^TQOnF`B>;WNx;rD~Ps8(1 zGRl=T!6PyJKway#V5qO|P*pCCUhIrDsKc-HT#N^^_JIbMoYKpt|bE$Cd_|=?oM3e)UpUCdKSc_~}To zWh&NrZeA~@*U6U(vcxB(lXvXltKp|9&uy1kTWo%>@BF%0kzymHGOCekY+rY$4D{T@wqOWHW7j?H}j{*=(mgA?@6s3GRrM#a=CZ%#Vz}ke*w! zxLGttmpV@3@H9!*Zf+%&-D3s8wRM#*2w`7>i8zimL=%*bSmNqY!F{qbO^o}90%YZA zbm!S2@(eDHBnP-EjQz{-`UcgNW!nRf)4E5xkzegIbRp>XmGj=+2rB<&w!u>igJPk; z^lRk_$z46EycH9aGCxd$h}+HXi64B4%qd{Q^#Sd$L7&9laK(eSkD0os>pzq?CCo<| zm}`1xiK<@F9gTN0BgL`wqT+9_xr}VKy>*ezv+~g-3@VSv;>5f|CES47C0{VeO-(_OG#EHAzFc9#EtNN%H8Vg~^j9~*L zYs@B(RjcVKRomG8b*L;eK?&OX-jC_8MrHCWGTRPg!Yku0m4(9PdwXSfy$f_`Z$HG8 zz9Rkz;9hRdS>HbX0i}Qoo19a$r*=K38qrj4Xy8Z1VSx@$RAW|spn5p<={F8JoTA`2 zKSnu@jSuL(euZDcD(qz2uX*YCHZCs3Ba=ZC%LcG7n5?>o00i^A`@8T+AsBY9b!{GC zd`Jl6HpP_>k6`Jgc9-K1Go$AF?VQ!+$S=*7;!EL9l~Q8IB>uU@h55?+e`bHGOttIV z%+MDe-T(HRDyX@MlF(8XR^Ivo=M|>hso%Jel3mPrU#2yX|AF}C>!#8%UX_Pyx^z$`oczppodIG%dv)NT4U6TzljSa0m^k zAuOd#8zL||yayI?Hb9DVk_r*B+Z=TAwg+YftZu3#@{;0Zglqd5;ER4~l+OH^D)m9B z>*WQehTeB;>Lrq-j~mQjKfuO=S*GvP_DR)T$yeo3&dN#ulZ*h7ninrQ-tZ`0zEL4) zDLtdXdc!`02+b$|o078d1V?@|Sm78j*}n0)uN){b4tq3z^e5RVZgVOMu;gw~OY@HNpU;Bhsy<);VC>20pb)c!f8_T$)!^DNEIOZ- z-6<;9K%2Wvb~x*!)j#*-ng9U(3StJ#boCWu$zHhSyceX#w3ss~&o8-HSJl!bmc&Cy zg2^J`#_UWQQFMQOvk}~K6^SU5g?s|sP+->m4)?%Us7P92CSRc{PJV2cc)yku&amya zCw;xDJa>$^RM4*PmeMjm;p0x^lH2ubZw0#&gVS2Vv&^Voz#!LJ{=@$4>0Iwp`=Pxs z`zNS|tq#hz@oX_0Y^<>>t>PC8x%5Q=j;&3sp*jt{!c|Hw;|DUaCfO^^a2)IE-KmNu z)i$`BvGJW6WrT+!3lynI`%_(lzL#~5Xqm{c&Sjqs>F`N3`{-*c69DcNm%;9Am=Sk? z{Bx704;r^l{h9*5fONfdyE+iz!*H^rc}~vWBCjJYIG$LT>)b7gef=kuU=U557q94+ z!8iPr=>8Q5a%M<)fn$y4pP}QYFX)mI*Z1j829~N5b#OJWh{CL8KV(7dh$D#|k2ORW zcms*Z9R z95;+8?uwW5?(4bA{0RDM3kaH0S5;%a$-*hfURIRc`2BZ{IleynO+FGXK?8!u=nsbW z8Z`I;q*~eeH^-yb@@&uZg*3`XY?<^d~`nIouF$VZFt>3D51NoFAFh*AEOs+a&D{?=%L0NY!jwMF9Qa;9&9F5Mi6o zaxmOnaX+sRuC+J<53bttAHfFq+a_Q`_BQy9$fm1%ZVp8K=LJ41qBk_N?x(!;QC4aW zHdD!y-!oDg?jfRfRPyX^x`#YEu=Qp_{+QRa(}iEYh25fEj0EOEP5&{VdD+PzpPQv- zn_r^*tO*v73UP3)+cBo4K13vt-OA*=J_aVFnLxmVMvy(93g4Dti8c)Sprqu##IZUp zviq%p4W_Ge(5#mtCSi^WoSuH1&d@RVEZaw{gbMVES?<$D*sS&M#KO_tyi}M$uG*OO zr@O7$bBH0?A)TkON2ZC-L8&RUgd)YKkTW|yv370#XcY6M!`JNxyVUICW2#JJvqeDt zblB&0q!hId$esg|oo{pX-KKU_O?G2Vk&VZ^cun(Rc-JJfxCeQx4=6!Rqr zi&?GE6wWm9HZ@2aP0p75!s$SEN~rP4ApZ{8yNaJ8%HH^}-6pCY@kDr^aN>=(83IsVuwiq$9ID^tgAIN3%Cu zP%nl_20t)fj-rL#(3f!38P)ThcYF7u%#&M}Vz?YfaRp?SDyg{mitBTN)FmdER{lti zM~RH!j99;KqeH%~T*5NrobfOX-IB5vwt<;hFj6raxvT($w&X$1$wgqTUqu#jrn-ND?s#c_)a5n!N3Hi=O!ge zcK2@Rg;a6K=@~geiy6E58eW^vYVc=+7rJ0;{xOc3p?Xw%j3*XX6?PqXJg}w?uh&AQ zAlHl^R%do&RS*A&7MQ1)f#k;HLYjf3I>uB(DRl%&89x=tsj}^;)AV|jw*0hT$f1v2 zv(?9#XNJueGOe$ZjUtpFo2{h+jA8D^hT%E$>whq`G2_8rG-mfId1AOWWj4%9UMd{@y!kd7by%+uKjo?jYyccnM z7}ZB<8vSIz7XmLMeGs&j@oc3KTQ2#Qb;LYOIc-Q&k{l*&CtVW|)sf+Oeoy(}!FA~4 z5FLl$iOp?D`~Y0)%4FI#H64mQd(BfG7Z|x&?C6L57&GZ;iZYza7RO;n9@oqt%192O5*H2JC#A71zaQQ^5xYJ_9iTQ8un1>h@00Xb;f6vQJBX+ zx0IP$fkWt4AsVr*BSd4Wo*Bx?R47N->zrz?@rR4g+VwU|ZpM=# z=1bzi`Gjeh<=?C)4f%?Ip)HK+mas~>b0bDduBR{`7l_|qb*jqi-K*E5rS-D|5esJK zHFzd9)|G0RMw{U?g#>5;E5moni7I;g*AejebH3_usdkPuGFR%#j4LU#lT&h)H-ycW z1d>zHYx*oD-E)DMax7Y`zun*O@j{wVZ{qYg#kWI(Tw3+qWbZ! zW^eQ_+C{v)=#H@c#dW;tuOVK{`DGE?N5QCO+T}=*th3v+Gd~A`DqX}m!-QHdN8j^f zacjc}YEd7WL9Bd8jF~mGQe{~VMM`Wsi*U>uMZfUVyE^=-Ugo?+5O5G&BaK&o+}7gU zlg2g3!Bw!@v}d^F71LzCbV{K{gLQlz_sxWQvy!Gj_=*OW+;?vUUy#L?P22zwTfqsJ zZH>UV+NJL_sk+UwoBdDDvwo|yrHQHh!m3Wf^q$5x>!Me^4fJL>$x<&ImQ7WoH1Dm` zeTohj*bF56{c`Rc0M9uglW8P(sT*C+lwTRYcGbddm;>*{L_`P#I1S8*`vt zZLOLagz8O|p{Te(kKy#d!!8B;XGqN(=!GNZ)!yt_Hf(gW)=i}`d=+fPBQc8&uWjS` zEyTBEOMP#Voekd@ipefJL-ThaSMRJ}q?8b19?G(432>#)!eS$eEMUyK#Chd9nS zk3zi-W|8d2YP_J>LFbFpD0hr+dmeeYQJuQKQ|8)!#D)*hR9m%S=i)Pszb&+!6;h1R z{pbd3C5vfsefk!n4?5OD@#tLj2qx{rVy)^^)eoaJPwrE#5+Rna!aQyRp$W@Z{!sXQ zP}#CZ@Z~+(> ztJ5R}E2{-5K9LpiD#1cMAN-|@t52>KkoNKpjd1DbK)NO7dlLVJTw+R!$u%}SEUfzp z=I!aqlQzWH48%Nz;DiK_cHo6Lhx0L3BtGxZ5yM|;VxFG>ET+Fp#@m!-b7sr(NRpA? z@&T;o+fHBp0(kL#OkuMcx-p46V?_K5Q20JqRP^5o0qkj_ef>?*P+_i+|;gz5oBfufV`PCyMt68Akg0zFApBtme}LM{@5=>zVy;mN&yS z+uYIX)TI}yjjp)f;h6UnX+R%*B&0|erV59>v5m7c*}-ViwZZ52K0zb@>GNG!SpGc~ ztrbz|3(@CycqAku9#`z#y8!>X|1K{5uZ%mJ?*X|mL_Kfsr(1i?!PEkMfvv473M|3} zG4>yk@(xMmP|k+wGb1%}k%UZs@CivSP zAvOP`UHeW24|(_0{}GP+gtijHNWm;u@+&u1(g=uphl7H}{XBY*D1o1k!Nj|KT*hAi zg&Ay(76fH@K3p0}LAjeHpj>=B!k!tzGqFIY(f}RazQs5&j-%>Vc{x?OOWB zdC3>wX?Hvn(34NG@XWKKRM?Nrt1l{)ZhT=|mhisSX4>1m%k*9loL5WCp^}Rh5dzuK zzCJY6$&OX;U-iX0*Y+%T1qkk>FmAc(&!SI@*y$THYf9dAJh^}R-La6D^Wc2Ky4t_a z@xE-T|Aw&kKok0Jt)X@2kJrCRSq0~owN*Of^ajVaMr^aPbUrKmKXkoiLtO2$wVQ+h z!3h!^g1fsXXwb&p-3jiJ;2zu?Y24l2y>W*Q?(Y8fv!1=z`LfR+m_F~SyK0Q976OBj zL}O!VMB4aCz~^=9Wun_$!JH%$4uh1T?H8^wh z#OD4OcMhrX7xxPI@shl({E1XZjO5!i&6C5lC)}-f1O3B|zF$_Z`iz=tX6k!Kzwe(& z_2_RtKoXfp)I+Y!Aen8oB(4?YJZYsAk!jj~C?M67X`Zyh9FF6mV4GUiuw$ZQkwlVb zMajzCL@De7{Wq3qgtXSqO~q^i0^{|o-&k~qJ~x>9vurz=kzx;B%Zj0GmkyLs90D54 zsMP%Y|2hW^yXM8n8eYR<3`q)NF1kpwJ`i2iTt79yQ?1N9(R_bOyW3jobY*wGPl}x@ zpH#(FDjGNGD7#U*K@LJW8Hmgau4meID%jbMoke|)xWQ3=4>QtuA}*+o4Tnf6!K4>S zq!QK@Ac-*Z`*GLv3z4(oV%z6ghoKOWoR|^|+me=jLH%0l!qkOQ`ne-5 zIE23eU7=N&xZun~5fO8w0q@(=T^laxtMz3~$Yi>*!O8_1s(eL~>qWLg97HJwzV2_?QgC zm^yrm^1wb3CsZQuEh3bnGBCQ8cZG+WUHWnSrSm{9@2hS5S)L2~TyU+ig2OSvSg$a` zq`>C+s?aR0SxnFfV&P?ZY87KjB*FM03+lvys35l&gG$mOcCkoukopgCnc47pjoC~| z1qqTxljmTp+@Y#~ygZ<>XL|KcG4P6z{eoLwz0DCu#ht9ss@O-?OW$Em4CgT8e95ZHrP> zj}XT8H@;)vDXHK#$86_mKeM;MnjVj{a8>91EEjrqWjhQa1uQqoFq|r9l5y>(VE-(f z0StzY-G5_9PDbmlO+hIbC|GRbG}sTP?|YxNf^@)P0JG6Oy06lMy^xEISO2Ce2u$GN z#_#Hyh$_}vWEc!E9Kq9f-LaP*HNr{V z`∈dGPXNnLA?~-P#uiKKyHC96i#5L16CY=?))zqmaG3QK6{9tnrJK;4CgTYI`xG zLdBt>M<>6hr-4Pa^O{n?r(;?2__|$|lNm4uL^-Lo;!kaU!B?!6)(pp@6HQMYbiX{l zO7rT7w9^bDYoL>jROL}U?yB>#6#X`7Ag$Y*+GV_BQkbHW;oH}|hMHn%6AEI{CD ziz@2=lQ9<7`tI^>mU$h3dp|@WG-hSAJ*cO*_u}Se+yM~{4crTqKy;2Qclhbt2eq0@ zhJ4W2RyNY@LWNoQb+6MhGFJ*Nu>SQCqALj?$W-sNw+@af7uv{)VV^^m{yVi*$b3pZ zhlbE`*M?NgMHT49nzXpQpN*h7@wX$rig;(Vzw4_V?E3b80{%Wo9Es+Hs9LVQ_r!}g z)1RKjjxX6(SgU%d6vhcGm}uApjmU9mRF(;t`J!IFy0g(;tnH~zw9$X(ve@0tdCi!K zq@@B>p7&g`UyLYWxb(IhW__Z;KTX}|`uMJHuCcwL()#rc{P0Q#V@CJ;DWE@V93dmZn=IHldjJ7Yna+)LI}n-4!#yUcFV zYg}g$w$A%INk21xu>JzMAIf&&x1E zxP;RT`xllObjL6IXnCwdTMGB(;cMoT)Mly&d52`W(v>eIM*poc=dLuCq)R| zt>)|%u>hyhuL(|h3{*2lUCaG+lZyO2*Tb%w}ib#08 zy)pa__>)wan2tcA6)E0dPmj=83S7ezM4-Na$M~8inQcG>;`T{314( z9{8YSe^d3tU)L{rC>ABs^7aYZMcSLG&qmG5==YjZwTem?Z&cddH}E&!LWnH#$-GIo z&z9$nx{EuSeRgGfq0<6|#Cdb&7b#C|Fskc}f=;X#L5IC}`l|iX>fc|fvhhsgTwe5gb9c?PHXL3a!*+Uns7BP2AYZYqzMoyflOQE1x7c7s z4XC>~);ru@sTELb@#bnTa1F9wT@mc5u+qhEK-dq7;-Pc@vxLK z?8VJqvRoS&2NZfNj`_snmfAX1ypPMPl%w={T1#DKmRMiD*=uU(&_kL!Ywv5Ynsh0D z-rjVIgx&XyR@`{k#>?rPU15eOG5WmRgz-hx-( z-Tg%#xbqW9-{*+=^_+g>yjir!s2tvNe)idu(AJ2n>h(HAk5(tNF4cc4}mlFrBq$dL-Ai zr2qMB^Sb(Ew({O%Jt!;{lCUAuE|ij}nxPr^EiKvDS){rum3IJ!0zO82tEW%T0Ktru z>+j-o0h2|d9_Je3hB$MrwCiEPgJ`|k*+|iNq9E)PUYtGwvV^MZt(a*rST`|_ML$2w7#-|g>8V;GN{+X7>C4oYs&rpd46$R0zmD%8BYj_NA%HQD^EziQ~(7C1ZfhtpZ4%D`M zaU_D0XjY!B8@rdU<`Rz5@8ux?c@y$a6a78qa+UX#f+uUEjs;_MzTzD@t#?&5ZXpZ% zFgC`9Z9ONcj}{jk6Sr*a%_F?qpDbzi8d|~@ z@a5EWvZqYHl4}bejqSBC!f8dgdG_|^6Tern-sz^dZR-?-i?vr3nvoJ=t0(U5dt-$z(po@b_v#@atP`tHa^ zi#NETVq~;ArDfv%5mpOGQkbZ*vhr<+=(Mz34d`xW|Lxe$k@c?jh&7>H*3Fs|E zF)lpAwz|HixB}h>y<|tDxF#vCqC|_2){1rT1@e<3+MJZJpVCpUBJIY)WhA__I)${y zOb?*S5V70X-gvlk2bxF=5qwA%8_HBbwmD%@en<1I)JO7$W_ES4B`P#nxflox8+MfS z-;W~Se-2@Casz^D)A3sRt^n$i5`~gEdtxBP2ult`rL2#C`5TDVo|cq$wt2$eNk0)Y zJk2EF>Eci8+VijbtPa8ZllCvm8=0<1{UMy_Pt^ZA=S9QB>3W`e;p>goI^`(wOXoIC zZuf8Bge)p?_rzBE&&Ju11W{!ALQ*> z4&-$WneHpR!Ug2KL`)nPtM8E$_#_R|oe*+0dsS#Op#!@A;O3MwkIw74Hr?ZOy}NXS z-qYn!HD3mY`q@m@V07(cUGYXn#uL%{RMh@@57m}eF}1Jxbg(vs1*ZV7a274SvBh#d zE1kHnKx?D8TkoALKe}`cS1P<$hxy2Wciov@*0cZgG@|M(qn-G!qhzTRDJ^Skp9!Z0 zCj~WCTuMTmTC0dpx~(?J=7DN_A(7NL~n=l{Wh%CH5YzaQ*Vv8*epws$C2!sg(z6j>7$~8tf27@!( zK0GQDQ8XWe2)2)CdCWKY3y0eXlm{Xw>r5yi-%o2)j7EW3XD9Tw3SO0`;y7M{^Y-1o zdVr^$F6Td8BA&rooK8xEI^=Bz4wk_qUWx(tTmw9D-gBw8h`MWx+Q`5pf~tcE6I&Eq8S`R zciz4izoFuD673*%7(`=BQ<dzcxSlWb!=H!BbKX*)9pY->RPFn?9J3m{nX z*TgWmSrx&Ph!(sWq_6OtUnoq_>K6n)J!46kiBy{bTvEJpX;atdWVG{|?YgQE`h@I8 z_!gw=l1Xx%^;U}`A?`eWvilK_AUv}_f}=vC9pDLM#C6K&xzW)>?x}JG@THL$?NPdU zIy1`4qZO&~-55@#>Ggq2A_9U0cbEQaR@%`+@mII)y?go(zL! zYIA$Nh_!WFmP&~e*ShTi_DD9S-zfQI|RE^5zPW`8PdM9OQ zX9sksL-^m?H`JJ44zX7F=j+meR!Br* z@J>E*{55#b8E$d6ta*Jj$3B2d+k=d0zBevTZnN3!&5qZPr_T(^nUqi&+4J*rkxug^ ze`>N)vB};NwQJP9 zgS)7#-rI&>B9~UOqrQBBc37J%ZZX1QYbsJq{8aAlaDKjb>(@V8Cj`cf2;`)WC%QKr zaqIt})7A^o^3WTgHyRT+om$Wfx8s7f^kZW(#p?Q%{x<`5^z{g<=bi){&M@tGzGRpy zh~@%F?oEK0&WC(YR|%R#cR4iobUEwYGC@HEk+~z^N96k;`HF;zlCF2UB_98WdO{y7+5KzGLT}AgwQE5#(gbU$)CJnHmq@A<;nz4K&b(|JRGa}DhGGN9>i>8t%}fgpF)F5V^* z>X(_7MM6wW%q;M7=>iy>wW=o+^yB~=CH>Ph3FW@+VE#{kp^Jl5rwMASiSD12@sn$$ zSPS9o-m5evwC4^#G>hS_nhjaW*Ph86vc{0`f1Jnva@Lr$vJPjT%JSg{<=-AvC7Jqs z8;R+`KaSWD@z+n{AC&o(SkWqcp$NP#NH*ct>h#L@UmnefSmCRKJMj32IG*FR)b#)! zk6Drc$4rM&tWLdZr6wWWo}jOsa{9>$m?GYP^b%R5v)0AIvu_~+MC$+YD`LIUEP!GG zVa2RqW>aT}qPd{pu+9xb`%qvkrd<0t9;YAfY2}Gjd{2<643By)w+~(CZEs~Z<*g+H zZn{Cj=M)TbOk;O^Q5)hpWPm5WOn5AUL~2D_!T=TSRYJ-FT%uUlrV#RyZqk9U%b?Iq zJqQ{vAC=tRFei za{X2WTFqSkZ%b@QFrR#9q@-!bFFwJX*|LY(@e~N72g9#CAc7Xu!HMmOk{7ma*g)d* z7@lewwpbI2f-t@hnc6^MlE1dB`uqOSyq7x;>?eswq`NwjEVA%Mm>fSNoIJF1wZKZF zin<^`HC3lJ`n2oXVY5Lg6{A5VV6?LEA(c-AHxE@P0<(s7?QU%^bxEjso2#>2W-=s*b%j=gu*Ih@G zxxrLnY1Honj%Mp+Q=Q^MXR(Nh(z;bhVEAtBz8@!#X3822--^ki zG^i6Rw~0v2AvG&+LjauTq&JfW7er~G$K8hA|1luTv{qUp4Ivh!rN&cV{v-;DixdKO z?G&rBaE--`PWn*5&>&5lFTn|^GiAqu5R$MZFeVLHg)r#~1wBwX-R@qy+d7%gRgeVM z`oUN7=)`ruz#}P!78WU7nm0yH)3v5lguPzvNkGvwgS63x&m!LL)A8a54K_=c-O#Pq z?(QyL*i&|P_JXhB*?N1O-P&V29Ob{Q#UU>!g_FZ>l_%Y;PR#BplFwvpGT9jEij6g{57?ckq2Yw)=hista(VbN{nOmgDUFDrD`&^H>XGF)hRF8s zf0s;)dM#)O?%N$t|5aC5ls{utUuQA(8(I@F5fD7tp8~midUn+E{C`ne0Dp=8e>$D+ zv{e=zDfHtI$n$t>*`9Rr9p~FBTlU89QI4@A7QO7e$u6RMw6P;74gW1htz2tkXD8@Z z)3)Kb0PPnt023Mn|2+`8CbZM&&9^x}rKp-}sqRFlM58B#Ic9&O%AtvsHfj{_LBs8L zH2ZGXBguRSi2E+C;ikW18&|$y`#Dh{$0rg1o>7y9P9*quMgUu#o@?@gz@PhGG#@m)cqB*&z z$+h=w1(v4+N1YW>(AKCLHxVSTS%2ag|eH2hSq zx!=Xr%c8DXt*+tk*v&(*=Iik1QbT5ZO#smV3i+L}`{~8&brB_blFx6^+%K6Xjg|lM zqBhA%rO0C&l_oY$eBP5I>7p{|j+VdewMZ`{LN(M%Q=7d-a7D_i0WDnWygwAn zeASRoj7kaHootYE6QNAY!a; zrovj>+Wu)>*n`lt*G|A)g&*~QUiGH1OpZdEqY~ZKqtQQ*)|h@0je#_;Ib3ePcT6}* zTRyB#`spU8Ht8aJhvHSL#Z`0)ky-(-oAQ^u1&w&49ryHOmTDN>jd2`l9KwV4PZfBk%!IisCDdOkpI7znA7Bo>=w|JXV(n6U8hCXRP~W)P+n9{M_#1 zEb)CnaXBOTJGoUi6eoYSmr{U#Q;LV~V!)SamDn{r@F6iDbEkb^!;89HZg#<3VXfq| z-$(Pqf;h*t3)3>o9inhGpZF!taZ47*FEH9%UA3;T(yA8Yd247xL;aL%W?PGD32rrg zI;JvHEiWm4hnfWK9LEv_%^#rHo{kLuVALCHrRF+%JC~44H-$s`6&iLTL72;(QOOSP z2bM|YT!sBy`#-mS?L)m|$6DAp)=p#Px<$*Td`}`X9wv|=E# z3QYV|mZxW3cOp{wv-Kl6+@Wb9t%C}sKTU(}T4WH>NveQ~<*N=2YB@D7`F3x@yf~ns zJdn3;+dJL2i8jXm8mDihh_@@!&gW_cF|R=|8@zd5So5>TyrFjE)_={4lYIoFsRa)C z9mm|5V>Qh{l#ab$TbK~Z2JW0jnwmG%%)Y*f74|!r_AB5g()b58!@^2)nJtc#f*Tsk z{`t8l%BkZAT?!mT(Ml3&1~9ALWO7dn~aaFv|V9(u6n zR6cs!mKUEoLR14Y7whGU@E_J&g>RE<%kR>G>7lTb5;ZNE zoO9+Mvwcl<@QE2Lf4TIZHD^3}-==9h6&owYFLBR;8;(Yh({8bC2|Se=9W6(=@VkSx z!Q4zYz3s9`8NCe;(`OWx+WN;4cgDN3#841LqGLsc%0YX|=*2fH)F(Pyiov~`Y|qd9 zWo6~n4m8qHl?{JpsQ!gV3!zk3R}=EPMs5wpIBoWYMIJ!;(iwa%;mU>b4v*KC6B)em zteJvdTmWNe20O&R{G);KDI}#u@L;uudTkW0+U&q^TA9TmWN;>TL4u)Uc_iwbrsu=m zmG+$y?vbj&*Z@g!RwoB}!xJX@U+}5oj-EG`LC2x;dPoDEa&5FR(06a=|i#L4ekQWho+helAuq9rddhP z=*!_dd!k{8twWoh>h~?ZCehSpjlUm?PZbjrKu^5s$P_@6w}aeS+r^ZY9j4kh4Te7> zb1)%cboyD#yNGpeOD0A*K*KviSGDrOTEpo|XhB-ovod&e@g*k!_Hnno|I8x-H8<<$J}UpDR7QexT6 zFLQp=)hph1CEu?MIAK;^hD0mpbbJWK&tDxh><{HuiVK}M1?X=Md7q;qHj+*h`rV(C zZ@aFpM(gxiL-e)yK?KcFhT|bl9hZdBL1Gxh=V-cFvW30pwqghBAOITtZQ0^b@3k$h zBmcVgwdF$VdkI5H&1wU|z1+8~a4|kCri0+!OOJ}ej%VP9h+Ds^U3MJV_FX65um1j{ zNS4+Gl%5LiN|SbM+~A) z!9TXS2dXRN|94Y12qRQj=yT<|HZ6-UT4OKyr)Bov&!erEOCw&I*4zhJIeLNw@+bWA zAO1Ldl29`sg7|g^Q%$~Z@I1+DDmUsGI_u#jV>~tZSP-@ZV;4?0Ca6@D>4o{ttvkE= z%!BE7*!Y>$4cAeHQGr7JCBZoNHAk{c1?S7Q?EHuPtvq&Dj2$5W$BRoiEx1U-`x<@= z=URw5ZN*D>m1WF+9pxX%7?P{=0bk!UMZ{h-P<$S`NSodv-asNpS6>5q#klWAC+7$C z-V`~xVIg_7{_;^X5nVG*&q`ui#W{rT9_ zo`e|I-phG;8kX)!?*TbO&oxJGX&BML9r>m1(^hos{E1z%@XnX~3LR>AWsWX}`H~M6 zy0qRF*aV^+{z-${YSp7{FoITiAK((~S0X$s=#a6bBX!zv`HL`q!N*`E^{)BeoZK+1 z?u}Gs!6`3kp6H`DK<(-#V&LD=<2Ek7M0 zcyS!0gnaHe3!W}N73ivpro!asGFa!7vyIil?Lb~i`(wWH)E}fJmv1h%PY)Aye!LGg zy9<|_Y{8Kmn;{U7sSymB?$Sb_VX5Q|?4XpdGP}~{pe@v><-(1b5}q8O6h_pgFNsQ# z1;p!?Ex*z{87j7j9|+`O%X|9wL~6-dWw*IUr)y#m*h~2IhRp3rvtAFbC$OpJ8mk3& z2zy7bq^jC9#g6>{cSM;c#+7o7L&5gp!!j%3YA>Nam{21r4ms87Ye;2j8t9u$-@Nbz z>v8WjD>2VD^tSYpd?B}8CM%w(l=}*~+9V^H8r_dyQL;BS2C$E-k0j0xA12G6$zNF| zaTO_Af0;KITH8c!%utK%wKPfzJgM7LG(#sy9Ub`p>UlRP0lBa}a`#p{8Le*oyeo&h z+W7I|-8It8&D9qQJB{902Ka*on;6={3q8loG{{80zPRZ`v83b`=(sgadgQ@} zP;q_$l(BBTrBswQT_}f0(3VBn6DMC|G%kvNZ5JW>_!%%5>nh5ppn&sL*c2W)@3y>C z!;kfbbH(hI+8HtZi}(5{is-xEX^sl>(K#n|rwYY_!WiE}@(&Zbq&$4sMC6jI^j`*O z3c*kTBm8hegUp9dtFM%HeEyGL2nJocLC)`GQLcyWbt7AR{5IUhb~Am+78a26eHCRc z3DOj+q}_IjW5zrz8mJOZFqgL!JJ9K1DB+g$GOXR5O^9C(zw|ECkUTIVDi+@%+U;%P z>pAFUg@%2Ep5I?naq9E40fs z2q(@M%NR`c-k}^~b&R_S{e;6lc$=|E!*b_N1`YE+8Se4@2Bo5PoVnwjiQ5^^uA0d+ zVx}>9^m>+7hosKslP2nvv&>EvK5s)+&>TWRFrrAgPd(_gFjmjb^k*cCmtm|N9Ah^L z3qpVO6Lh*5)^2o%Fcc16R}?KC z3BC1INa8vXN?w-;aYn{rV8fWAX1`?k;pEhnGUR;eMCo)oWJB}t;QN&0&OGNb8QtU+ zLIEt1zd5~q3q>*rx|H(u)`reD!sjxPbeLL z>2_>qdUd)jd+mx*D>9V0(CE2b=hJUlE$_>8ToP5}(2v?;luOjzM)u7#ueD{OqA0uj z2y0h?epVm^B)Ogrh3`Q1V79L2KSW`MhP+f+3A+s%=5&<##+4uk?f)2-oAFY>f}N_I!Zb+!xTAxtTDH)dXWNsBM*Hb1PS&UTZ)TPj+{=J5yT z<`x0<4m>$Avz1F+PWPDv>Bec6uAYxA6x2HcNlJzL=t+#0qCMf?XC12Zf7YXVKLN4{ zp&Mip?s0OF&C$uXJ==`VC;u)%Wf~VdLOqyyv(-Nl!k3J;a3nd$ZC7Gqkj*pHnACN% zch;g#_?zVc#nw=>*3IsM9@El1Y$X2$kzD&1bjT}O^lA%uEkZkWrW~27vUOxCc!S*$ z11-GuN+d|!mWCeQZ6|q%s|+QSigXhr;t-ZC|K*c62-2o0hUy$K?fi|Jt{tqE_cp-x zs(;2W5%d|>+I4G1IQcT)%MPG}z39`BxgYou0|Vp7kI;?3>f%DdeZSlR+xEw21C8t-%a>0W!@v!S?DJ&Df7)#c%gilFWZ=o z>eO^;L0)T3_y#{2$YA~xBBv2^xnpF2-uS`Z(ODYhdP+#<3!Oq2(v|u$uYt8fs)JYM z&zr+Jb0~oW(%Mflj$DKCel5;@wt9QBL(XQ+FNE%f&hXuSQi;sXzUc9@7c(`Am2&5A z;v#1D$~*N88uoy8bvvggwXg42f)z!$mC+?`_E(1e<>*}UdnrOjUS z_Z}$ZE}y=4rlYgqVz(9s$V|*-9z^08o5(q(+9(ULlMJqz$??rPHP-Idg|9 zkQ3NM>OJ-xHAoWi6PAHKA$rDfc2}_UuCISgkCx$a<5W&xZ<84UZdkhI>6>XqJf42P ze|Qek|A8VvkE>km>vDRk8v*WENvPCEnpy3G-A_Ccuk7(HTige$ot5Ld?u+_tjUBmW zt+)Xj({6`}P9?OBtU*_4wpWa=n@gvq$h6D5{7GjW-+o%WONTqGZGf<-2`1!9K)Ws} zdM+Iq+|hQxQ>^OR+;0z1P>E7})68IV65^k(S4w)1S!crdbeui~NO+094}fG&{>zg9 zK}%W3!14v8YX7>{2o}-W>gF-yl+nseA4kC{i!XJ(F@?KEHTolIZ9f zty2K-t}gH)a=W$a*YosS{#NtjXE#x$qRDDz&SPW+d_JX4KX~auy}jjtRY-z-#|?Kc zL1LG@DO6#KIH<&!>c$#0)CoW7u>q9_q2=Y3(pOLl_fl)g%)VOIRq7#oAt}p_9n;Qu zBd4F`y<5)c+*-q!(Q<0abQqF0J2Q~X2qFGTIf$#IKgE=~vH{0ln);V_SG~hRF`@*j zY$|dmA2{{CKbA0NGxs}^UQ>$JNX0ic+6vzLlXyP}W6{)D^?CPHxhbP~n4@u5X{C;C zrn0mabu_#){LVj(r*y1}P9vHt-p|y67jwBX0`PPys4vl2CiYnyn`(eAgU;1pxr2qn zfA>~|4`uP2`#Bq5;?Mqi3vr1PfUhMUE#X@Mu9_`1d!s(Nl^U%~tca-v`xP!=8m)7g zI^(&S9-C;4wUJgf@zg1Gt@Q6zj)}b}L2oL=OJS*-(CMg0<>10gYkbU^xvywrqav)1 zZV$R=M@-BY?6(4JD=4w~LfkL5n%z;ON~IOm)urq7`-q~FLSclj#?d-f$BPO6D8lmj zOr_7?NE@f0pe_tmoH&pchsV53#~yGRLnRI*GSFJ7 zS;QkSI$chng(q8YQ4Z#ESLu;5jjSFC zlO`(MNY;yIJH?O@Dh()&;-y29vB_9F*dV&L(U$)^wrP*sIFR*r`?Wg*T8Q2bYl4x{ zB+yB6@M3ae0u3#AFxe7^Uj^;B>raAwA$BRYX&d;lsq{L})|$i1Yxr#_HeLV8jn)8KX57>xD_k)44NJ8-ov zGq!G;b~*KzO9hMdJxPXpO6V69DMdG)W)HN5nsJ-=`^v?>jMu2(jXieL^CH8zTgQ%( z*>dMhVY4&R>Js?5E0{D5Bcq#YW;F)e!U|N=yE7>Cz4NVCt}K?u3AT*H&)nAEx$IIUAmpl`E(m>Ei5cD6N( zZygNjoNUuvp=oqpU7qfLVe5nriaY{vS{PMq3K|M6&^zbrvg+ETx%RUg@y73FQL?GZ zcuz`Djqyc7eK{%<{p7m|(Q=lWw{*Vn`a(Rk3aTVvGYGRgUok@Fo<12WESDaP1!n!9 zSoY^8%)0GXsj0Ffw6J-~jPW#xZk({(r z6qHnP871PSQk1;3v3c9Gd)1bw)qeUcbJ`qVp9tin8Ol{DAPC!f1Gj&&9(A=rPhd1z zVcdU3Bz^{myWVvthu@>Yx6-Sl8MOS($scJA;Ztt6zCvT6w@A*9=*XCmeeeD<6}gKVKW?$4RY5XIzXJiVw- zs22fTM2GZ2LZ^GaJ9o9>7e&^|u3aPJXJUn)GM`j7X4}?fAt&GN^i=g)A_yl6Qfql1 zd9X3gYCJXxqrV)8g*diA6AXyaCnK&Wx|{O$=lVPRe|0DI<-89G(#}GE338y)u7SG$ z=_g|UoPnKnYjUPc%EcaujU8N|m+NOkd}h{@Az%Zc8i9Kt7dL>hwSLo0soShcP++%^ zXA8f9Sy@l95r4sP%bWKnd9JJ3;0G4R9v`76Q*?2Cp~^`{sXIeC_c}|w!QQwjiuJuN zB@(-2JGporH1QbIqrh$(r_}x+NkC}0dsn~Tz?NlcfOv@TgSCO7tTtnxFw38BZ{l_A zFy+36%itx^ZyFqc-*+t2$M&8m8q!q~v0HBIOmL>rCvmE5gRXE>u1nwL^_nKaXp_ot zd4hbx-f1P=qNLUxu-$=-KMAr1Y=(4Z4`z%ODQ-?yP!o4sYbGl8e2;otR@Et)jc3w~ zE({~gn*CMDG-tR}|Fg&bWS9O1ZeC~98KH6*MO`)dSEU+j)Ld z-Xz<>SYcA#Sy+STaXe+P#?LhWv3Fo;%0K)5dAb-T0y|*QfjfAgf8}2G1^$HZZ2+Y{ z3BI($?7ms63_0{G-6g9Vpu)rg`^tPlSnB@ib)rY`dnI1W9pvUaMU>L1jgdOm8Qny1p)7qjwB2;4!CMyZ+4%sB+V@XJ2)A zRiMJ4^o~9eu{GCazwxi^0D7Fda50^2JNdr`mF*0v*H9bnhOoc^eYPg8_fRJk8tbyr~q!CQ8$rHJ{ z21mYEt^4z>Kwqt-^|WNhKGw--Q=ljVOF}G%Z?;CRla3?bY;9UB zXh2~CB(IhGt&*lr%eTBE`S2OB27i=*%eNqK|5?gi^221wgN0L_?_w)-+B1O&Q+#@rufqRC$m6gbwiHa!4 zR@=iSR_7ZlPl{I&OdKQzL~iq61+$YQ~?ckiv-$18L=j(ufm&L`_8m1X7^^IsR+PU_szy*Q-So+4yFO1~D zD-C{t+3&o51w?GxvDDS#Tb1V{Wur3Bqkc60yB09{PNKe`#?;b@c+4(3Jql4K1Y?%u z8osc{iLZ1j=SO?X;vl6$4~T0QnpMws_cH#{SmB$M5mp4xor(SOSrOtu?Cd+aY~NSg z%#T-IyL7fs?{fx|Eq*ELUNjco?WzQqQOOSnVUtPsgWeXu0!auG-D= zc2K8fQEL9jr;FkrWCji-!N*La*I6ybmGA1R`}%&zhB*{C;pj$2p@c?x%p+-a;>q-G zElty>=YW?c2P803al4~CpDo*-5kD((KNL!0Ao02GG+r0tv*#{y)M=jS>{hQVtF@z|CNg0i9Zc1v$xZ0!5+5ElT2w)iy7GJ4 zhzwS)1x`2Do<8{ptPMC!g-{5s+}YR;SFlcfJ#pfbx0IkY(YG*NP=QLQ0Qdo&)4<=W zRmdI7M~$TJC;b3g#n?EE$u<{HWR{p>f+*hVd)JOWdjkV-wT7`^ zv;V904@h#qEnkYXOGZF0EfaxO5N8$0#cYd;gG76XT%M)Vl9nY$lV^mGUL|SBdqg&zIg}RT*nRTj%n;oV0>)C<909T&^GK z6xJ_HuQ=T##!e$zbFfksJs!siB@XD*7hNR7WR)=wYT-YwHi2hkY5C?)RT!@h7r6@- z);WL`S4=v>Tf+O~YTNhUMijo>9D_;kRCO-xBYZsH$@nbSaFkMf(uZrf2DvGJVCrrn`AvJyk!=a=4GJ$Ch6l@P)+f`SppuTFsZ~7c2IB z62BK3XgHEN3&L*VSr>#T2~TP~EB(izS@HH*lPs6y;sy28k7t7hCM!tAXleKJT;8eIlda(5qYG8rHm z5w0Mujq}D&cRo$>E4c>=5R$xTlE;Io*# zt;XO^|G!#*tASdj<6uH^)1f0U_8oB8@GP~G`B8!(Htny0ePom^iB?+s3v1=U>aQT- z8*@e9s43T+-i#OLlz1>C?-rRq_QwPh=Sly1pI)UsR1!|SKI&oqa0c?0syg*c*?V!y znxa`x2;)zWdt1gBv+^B%yn^g@^0rSrJXb>1F1arz!R5yzZJ2_Z(?jTtXY~RX6S^XW z&ibyaC+SaO#i-B6E5EXkRtvD`;k~YP@wb$@xnrnX(Qorb zV_sKgITWPz@H!28U*5TJeLb)FcW7Crgjbrk6>x3xMj}yX>gOjZ-mkX2dv#rse{w+q>9EzsYo6>k+b$#-m}=40EGV;BjSjob{{j&jmk;u3$rFi}m;I zGVpl&Iw{N>Ep;hJgMr0PDXX5uq{C_|w)`oUwZY0W3~!uDzqu}E@=OUoxr>!(1*;^= z%6g(GO+zQ13q9x9(j2cR8JJ}3NhIiC%CQX(y&L-5@dlPndE-y+%>u=Zd}WMA-Ydu} zd6)WG&a+;8$qRGPY`$=+Uhdd^If2*qa@bCN;PcfiA@zztqAaIvb!`&H<)yky4`mV{ zWn_7)yDu+5Hm$#w`k+pZc4W;NVOc`L;{!~Z#Rw@mIp*v^U!RGQaI%>HF^yq3Efj+o<&KWxc3&ERS2(N~G^ z(5-u8u5yC%LGFy$9N*pyVoVaev;#pe4x`+yT+b6jvbDwAO={j@rdZ~)h?m-hkGUd; zq$MOhItYZR=1%*Flm!b$d)Nhz9%oi1_nlKnM5)H?97m@2Jf9J;zUqBJb>X{Mi#)i# zWx3C`2K$ZUpb65P9h(i7(?zDN!b#fx!B;n#T&%E{%zm$cW2Z(LMtL$AomUV9XTd*d zHS*(dbrguVCu%lMx5#f+;_0NQN!#Yd**mTTpDGryi86352QtqPbYkXaKgeWPm2!AJ zg^s$ZExMf|8}1QS+zl9KShtp~?2cNWK>h4!nXucs^`61cg zJvxeq2x-qM!0rCot9U}#q#sw6Hg*+vdrwV{5j4+CFD&f)YtKlHK zwAtJ*qBv(8mjUiT9ZlJKZQ*I-$A@Hg>kh?21&{cL_F$*#XC3+V=&zfGJa=e*A=>LL zN%j>1ADasZ+1Q6iJhZ+~U)5zW9Jn=Zyn(`XM!VKqs|mgQwKrk~kkPg-ueCf51Ag1B z={ZkBzymO`ge&*_n&nBVSJuN%0U^9|3Sz7hsrY;#d zF@~=jf4gm-NASGqSr*!aaV)N(Deaz=n9AustP4hL4AAfXoFnYBnp#?)pxsN=|-fXYbzKtJhlnRg`r6B|(s!=ZkodjB}CeaW5=2 zO4pm6Ztzh{Qc$pq0Drfb9|1!uZFc zluUa3BaI|ceCK>WB0LGkQDAD*U0cm5z1e>?0owVQ*ch6My zG2X06`Fd?T7_C-mR7i}!wufy#X^C=)$4v6 z_`$;QdQXIZo%f-k0}7cw8-qKXyL}LVT+A&iEKAEwJjLusYQTl+;8nCehmAagy(Hq5 zJyuZOdaij^mUeIR3U~a%B zmM?#SaKSJhA(ubQz!5x*&f5lq|S|KGMD&{lcDiLwA zHwHd^$mEf8^mKhAQ)vLH_Xp0e4wV(yL;2W$bALH~?{wJ`F*l1;TQ$HT-Vc&WltXYe zmU6Q?>76Le_uv<_Zcv>Ui{%s_1qR2DI%DL4e}bdI$kAusNhd$wm6ggf<@xug%MC+Y z39jdBm*(qi1HmI|8PSNYp&2plcE>znI-v`Ak06$&Vj5U3gjSF*JX`z1PZcQ@ zSvIsXnzE<#IXT`8zqC)9WC}6?ns%sgOomGbtrg3)(--TsW$R|jc66@H1-#x`O$`fP z>76qW$}p1(!c;&o9yFunF3hWBIDNq`H{4|pPxU6(9R8|2_)!d+Dp-utc-ituT>%bL zI9QB3_bFSOM`K6wec&cYXmUp?^jwmv#5#hg(cQ}!A2RHC#+WF)CYl%JB*_f?YC;M9 zqklVMC4j~&Loc%p22@mJ(lt>@wOL6!SXqQ>lDu_aEh0vA9Mzq1Fxg|e$xf7USD55) zFWg^Tk$x+VYi@8PlG3842LO5+H~DKjH@hWmxMI-eZrfs)FRcS3Yv@rTy$(9XC+f;H z)anlze@dSxJEq=Tx*Z?4&>!wX`xUAP>4=~f?U2@jc$BJ6R_P26hTE?25jsLSdu59b zof6kD*W@_diD}X@go3nnzErP9;l>LKxiw7b3Uh&vQ&H00N((4oq6HUW#UvW{KVIC6 z>xdd~2*6yV*GMizXRdYiD1oU(%iKszl`f}Z=vit90h9M?-2poBv2U}Gk2?Lceei<# z=RZUvA|vf9k@WQRuC#WRYYghG)*km7c+q<`X=#~V%k{S2nU@Q|Yv+Ly(l4@+_31pA z8U+Np7R1QQFTwf4su-S4!6Ayh5sb5`SNtqfkxOI4GcQd``;@V{vfR|_SY|l?W}s@Q zt?853@q-L5!dj>b`hwNT7V)6(P`+ptq4g)0UP>N}tuBThfY5k{G^f z2|+{}$#kEy@F0Lk(GSmqb0`|O$ZW2#il+p^uvNw0E1bT!`JLtcl4F0&nT!V$d8e#x z+I*7EFMF(CAH?q8DUl~=O{2{v$^FThCTAfcQQhS5`Lu5gCEUATEkZGDju_FA9 zVz*QFT8~5A$t%_?eK_2Vv zf~a^a*?OoeoZ=A>%uijSG6dOCE`pW$$^i6EtZuqBfk7+5u{-2tq=_t(m!ynz??ie& z;3sdLB3J7li38o)Iv6v-I3PURg->{+2wH(>o<8(9hJJ=ga85l^O0);Tt=516|L-6F z47{CSL=1?QL~e=vZZ))vn-n2m;9Fn0I{$gyT9fiu6WrxUodZ9egD=!GCrW@N0Yad?jUBm7~!^vSq+{WRDjg49zHo5j$Pu zIH|>qcQBukTV#dib~bULCu_|5(OrXx%fuF*X}<8yKImM~+w@*4V#9b0U}C7&KpRuC z%e0<3yl&58#@VEIZD5CSl)-IloOXun-_`!lng>kn+WcaS(_MF9Hu*~XD8Rf0V{;4=MlU&p}6Q^jGs7K(V_O` z0+X)*K{liRy?z+U8CW<;R?g&dC);;Ip?yA*rn~-0QA}zrg$(n1-OZKerNZD59WdXy zvcIGYxrek*&^7OE#bT|ESlMY&XlKXz>b>E<7B+G6)4QW@=Qvx5ua^UK^Rt3WxxXFX zK1T6CHsJmO9c;I{tRuUHB(%#?9Q86&CV(Z?%5 zd}OF~#9cjOw{ulLXbPu7EtFz!IGK|ZDk~5{YwAP>!>z3YK0g#6Xe8(kAru^(aEYQk zkZ}%tms6Mhp-A;MTb-h3nr%*zF)_aoSpPW;0p1CcG%vXPCk;tqRmOrUgST`5=qX>% z60?fH-x?VAXCZG@Ymkxhvx~((Hx}r=iZiffz2nc7M`A~MSvhXq zAQw$}lB3`ps`jHv-%*2QX9U4Wbm%?D-NYqThh9Px&2nDwt!BGB2s!wy#i zS9pN&Scue5*zX#Fn1lqV=Ifx{h@cg&py8)r**-ZLS*bJOk+b-BD?bw{#)582_O~dI z+v!taSl^?~z;s=lH7|dH1AS9$%`0%>*Vkst1^IqP10XUu0<13U*w%(qi1)s>g2!g z=I*ka^2aZS3>g+{OMyP$hj~OIae&wr)>ltFEg3%o8asCZNb$;DL$w1d;%~XBr+vb`%5#q~G<-KI-o< z;FN0`8foB;2Oiv=Eq?QG5m%(k;C14&1BL&e(%;64AK5+1;5))O`gTxY3)`Wx_IT%m zUs-&aZ21iTr+jA>LK>qwPT=jqQ|P#lSVFwnw)$Tx4E!a?(NsmM%p9LJ)5M4Ff*g93 zQxna!l{8~}rj$R+$q2~zJf=;*1^Xua0qA_7>z)sVz{?MPSYXaBfl`^*x%`*aXe(wf zm;bE`YuH~iU{b+OU`hnhD-y5MZ3>(cKc2>Z^rQ@s6KDH@%tpzVBH0sDNbFv zuvFmpoAMiCT0W={0iTAlJy{PryffFgT5C(g^=7GcMW6a+__oU}LRPw%f2!1~3;pUc zW}L07y{QVFJt`0Y{OpouvN9$j`Fax=WbvkT&_Zw@d{AN z^S{E3?`KZfUjOr9y}Hq8g6G-s2^BsUS7t;6l{PUL`6rftnKkU;1|?ZsfpBappPL&P zR3b(qfq%q34B+>QMoi+dWS1L4c}9DXhM4#)A>8#`Mm+2Nr2w_mH)7|HLcnDcG*Jok z5{c|DkMrNDks1mbMPy$bz?hVaz(=@~P3;JtDOpNK_}tNy_idPU8WpptMsw2btCoM} z0F}<|U%3ouSs==xaKCBYA-cN6{wW9#8%}h?t(48SzSaGL{j3q%ey`AYz@* z6~6faaI2+Z*wli@=3*Jt^x&JmFFigx-er6TP5mbC?y>j+5NypLX#`7gjoO#aTX>c# z=XdI`CWepx80^*ZB`O21q_(DRpEOfP5OZHO#23pyD~SkPNod!>!m5ZrIJRj^yDX&; zNsM&826o@VdM$;^5Iv8g3QHzL*b}mC{$`579&CG$fV|CJJ+YE{`li6d3bQzACBV#KaN@g0zePPQx)>{ccQ&4{NzsPUHv>LaH>qh zI+bl-aou9ubZ@Wj>uY;VbWVp{L2ye$h71m4KbKphc6*0l^eG5fuMIFqQCSANm*J-1 z6xcA7n)le43@P(g6?Ems(t} z-Xx7xRNPz7MSmP<9l9nOIc)k1xrU!4I>wG2w7_Gt3~Ifsf6?*%`i$R4Mx*bbF)^+< z_#7Kcv0lNUV)qCq6{B^DeatA%5uiH147wasa^QHo-5ro-H$AB1Qez|enQy0O7@Caz zn`ufWdt2-%8|_>6H5}eGDM?s=SxwpVf^Tx0CK5^#){Sp_|8|Ap2l|8V zRCrVHR9RfpZ6XRUSaS46?qz`7JQZ1B=Wrny?QZQG9!adASX zPdJey=YC=n9z*yBcUupLfr3D@_^|6p1~zq1ioDXpCWfCtlof~GJ?(m`aEHIni$ruc)pQNDHQRf_Zo zXupUKc(^;79HAhal>X}(+!#>{yWd0-loR&ga z@o}gIuJqOi+Yde3B3!bPLkf^MHg5`up;;15R#*S>!-ZIo)Fo*L#x`#zq~gc@<$oDL^~!IuI=jWz3b@8P^=btjP2i&xzIy@ z!%E%E&_MJa;q}bBGc~pIY&=G`UG6I{$uxZQ&gS0S;$e877`F?D?R5(Tz`W010PmeH zUPBB>Z+A0ir(1#aFjmzRUHt?84KK=;PjmAbmSB*Az-rqVRAQ>}YNyBizWRcQYsSBK zllAMcrSUB_uNLNP>H4~sB8l8(km4Y}mr@@VSf%qf^u3^2G_^KN0Y_j^+JCGr(7e`B zMuQKyL~Tt0KE7IM@)Ij$+3}Y@NtY}M8ed!rUDopQ%%mG^igpa_QWm_TUEFme)1E!c zZjv31MpM{T&CC?qXQCy|vnMAPf?eUraL;uo$Th$uaruRir0&H%2JYz}AT+w7?y~9D zju$ekfd<*rrAlQUxIn{aviobsR0*zA^Apffg+uzr9}}s}u9%-7@soYLZJ2?nxL0|`>iVi*#5yOvjk2b;5y+i zJ^ofHvNGqUi%PM2jK9R3t7=Bu3S%ZR39GF{WrF&=tuzXzfMkD8QE#;C3jrmb;C9pk zogZXv;D9NEMJ-8JQ=MnoXNwipsod=faeDN<9DOyQw$V5x1*Naz#M!bfzK!-b!W;Th zF3h5F(sEmq?zwNs5&%UB;VqTvP(^y+$a}p6iFtN4AIjg@L!xaEwnSqf^H!>Jh(#tW z>vn|R*r6mSK9GJ8MOyKUJsfFfRE73>^}0R+#IuI{gUP<|Dc?5J+@-l$_Mu}bo%15H zRhU;JN@#_^Z~2tt=`K*?L%0j=ZnM zl`=3c%T>PU;8Kx-6n|gXl)I{ATUwVctTqw2%>nuTA_cRCpj+EnKYsW42AI0ajyx!t zhk_cw%U~h-L4>_JJZM3s;a_M)JIATybSC4d$YhbC%dWEz{PbsMv|RBqpDAKP$^%;< zoXmjhYq8d{EHKYsj7+(A2li!2u8-d(HK!tTo_aON=yOYC-19#%UkFbQ9+eQDtylvM zqO}!WQ+X<(c*cd&N6ugNh>|NW21s{E**{#u6nT*w0)b%oZTZZ$~V2^`&x7jnRMzgR-PLS|YBkzu~7QJ)lBr3V;2SCI__4HGH88 z;hWJjlBO_P@|l^g?Lu|?j^(IsxJDk{Z1cMw3845c+{q%3kYp>rV{HUIe4im2T-SB% z(1RXW-$ zFvRA0Aj8Z8x1VlpUklwq@ue@;L{pv!WBBy}nzgwm!E+$a?x-`k@q=J=^qNqU;6dr& ze_Vk2_t*{-T6@CbWM${U&Lg)xB137d@`;HWGM=Ei=*79oL9DXFF$n1AR19U5<)^Le zBbTxL`R7sAH4eE#H_V_fr`YBxAj|k4vfqcm{&d37~``JT!JSwGkbrv zat_sl7M3yh&C7zZ0=IdsuO)bP`{TQUs4F?OA=Y1Rc4HRgSfU^*{+$ctgOfBL?DbVW zpQvCT2}?FUF5?HV`Z{Q5B6kDULm7f$7=Sp1;aLV=+9`CJ1s2|H!#H_vtGp5i3qJGt#H6PDXG0|H66I`>2D+WFH9CvIpDlnXh$;J=m8it5 zXOkU`fYfYqLn83_P1GUI-kFZwHE8c*y+>FimcyR z;-Sh_i09@7U#TLx)8Spx$c2Vlsg%Ui4Z$NB)9cvTA-}XqUf|Fbib&%9aKNg*_UNY- zfbahGa(6r}F~wycjb}-EcYEE}MWudd_AgimYQ`8GzoC{vU#YHnbhgA(?cnfqZ{vwz zXO(?=ru(NGA@r5!QDs`QXW4SaL0>!hgzap+U(oj`C5v7281J-*+a77v?lmpl5sUaC~qecqFB#FV^WoYDQ)HmM|_QNVrl?U=H46P6k*4Ves}Z#ta0hTyn2{uYZbFpWb5@6)8?}{Zf*%JYEdR zT+5kmp;Amm$D5EHkKVBw7dZ&6{EcdUS0Jd;{gVJiTG|-zfT8JW9|AQI@_|rJ7Zdk zhXEL3J#6GHDCPl>q>X8d^4P#}eQ{rMPxbYgYCz-$1UbaT z%`amEC<6Btf$)Rdm6ndNT%fi>*|Y^k47$knvY;x6Qk zTNJC>A!NsDayOq--XGfQu=yWnoNK&8h|nJ{xdw^F4%xqo^r8i__>TY_BIm?4oS|~Q z7ToD`EQ54Yhx=(5fo+>)er%pI0qp)(F@@N>Km1JmS zjnZ-Px7zmbxp#mmJutKde8oSDlY8(X8or|ZZfYPV4a$?(%YP{qAsfg|VN$2j*>N`e zVRR<}H_V}yH2y=P4itw=I+%hM+|7ua1W*WJz(j<{H(`g?$S2|LD!;t4Wz4)c3{Cm+Dzu_A^FWw%e+H6s}(ggmImdEWRevr%hbFb?h6{ zlnvPJbUoHV*hd{AOu;}$@ev@)AlMlJM>ffA4CWhoqocV&^CLX7MJ8dzsjB&jKZPBa z|J$pA@tw9cqa&|ODT$jS^k}(4*LZF0?)*xyI)j(N8Z0V-Gv|;yp9R&Opn{_94yUA? z!W_}tNJOxn;F+3!329&NAR^CMc1O!e7O5a47FztKsALb8d=)86u7}4rt zdvZB0kEm}X4*AaBl%<+z5~h?Qo1 zft7^E^?x`xY`6ti7Q^(FgBY_MV<#?dQ`c3HV~>)bGTY4c!!-yYyQTzws&=TYv1Q-M znrmTER#4n?IfZ;5*o5;Y7qF!Bwhdi2WJ)pm(n7}7y8o*_I>ZSv6(GOz9pjsPb{~ z9kZ~6KIDrO)6K{UmBa0aLvHsLJ|HV4VbsI?FXVrM3IEJTom+ITcLeCzBFHm^?N34z zTvAS@pQn;>1R$&qbUpzrARM=)4(2AKe_I&XkTZXVsZLI24t<&kg?uwhH7LcL*Z_CU zlRMGW;qlFO+WhS1U-qF0kGOZ3Wk}3Xj!n&yb`xG4yEu{UvVo_9n=o9(l{2KsMyPfG zoFS&&IC5y@`@F8WCPk+YUcQO*`nisI)hk&VoW757Dj6cU8#B*+)F01Rp$q$z3!1zx zgzFycGp&ou$KlxeWFKbq|8>SSH|s3>`<1OCF!^|~Hq`A4a_4!z)>H-2H}_4=>~yJN z`?Xew)of45>g;?hNqEI=UUYSmbBkiL))ZQBH4pBpuDru^xmg>I7Yn6%rP>mGg^nx-0FNu-TPIMMg`a zvc+Q1YZLt~Cbq}3ffO%JyIWG`#!)wQ;OjCj3j-=Q&l$AfKk`JCe1d%0n2lS94QJ28 z8*bs+3MF+v8h$|OjZw~w6;Y|6eDq)GnUN`6)mq)k`%%74SDd$9Aru?H(^;I$Kk7ge zk`O}+ng3pDq|$xEHlR?l6(*??&;F#r$_9i@u$B1oMsWY?k z0aca+9`hq7;&6M`YJEiEw~!uW!%?qwElQ5{3d@DdVD~d{X|~H94G-#*vwhLKJa!<@Gi&t zsl%~N|49WL#za6s$D*4L!!w!0mE7_~6q}Hb#t%2C|LljEV7eAYFdvvl2N+sj{LjuK9EXWt~E5o+12%OPI`x-^?9$s#WtkfL1YTIUIW0VOk5&ix+c+B zGza(iw<<<<=l_6Pg5!>TdcCqe_VM_zpR!<}JNL4D5&Z2%CGismj(hKKX9|a(ESi0= zW&8u^oA1Sezlyblovb2>U}hq{(zRY;xTiLWbSyEZN~kYTAZG)p;ln#p(*{M9jV^qj zOi9&{GrCp!osZORLO&MG`3yV~=7=l}eWD`ZdCZt0-a8`B2G|ZT>D8QoHzeVvNe3?- z^~^H=F+Kfl-ZClSh+7Rlmh|%oNJqPG9H^Dss)CQ;Vg2Py;m$HW);6T#Xc#-IZ=gnp zm&V%h$=`pKaB-h`pc80GBWZw)bBfp%&6vNFD8Dc|rfPT0CHvyp*x0mpbZnLC+#lWr z5*F!yupbW$v69BLIdKrabOfpL!Q~<=3cw2N4r- zjTBuK6R7A8l|7c4Q}7FwNGMPAIf^i`11h?vKfsQIWGzm%G2c}hs~XUbPzx^m4(Gkr z1ELbZ`{F}5hPsEF;f-%O-F@*^QEr1dA=411XQ`3hLcXz5YYRbhH6}k>)604B+um*A zZ$#pEutgjP)!zaiKR>BVjUqtVE(t%bFN%ykRp2cpC2J_;;&JR{ZdtQul>a#mhgNE} zU#Of_U%c4v3cv{;ru1I8JE{BLIO5pHb+$Z6mT+{%t<;5uNvuj{L;D?1VhSL&vmSM} z=uDF@vK4k(7|ht+_{k`W6L(W8LfJ+eyH=W>D)^R>Q1_@~f)fCF9Gu}+PFOBqy z2_OKKAe$Bbse2u>L&LC=I+igd&y_|aG+ac6(JwcUVguIpD;h_QC4Ldxc&^|Evz0bOh>(14{1^0!CJG8e^ z?!o7!0oJsW^LCymkUcGdpv>FNl0J$!RBeW7P&)-~_yP`<~hM{X*yZ2|?G-j*U z*LYw+qTR|Evd5|UdoV`lxG3a>?TJ{YJW-;(2$y+mAbB+xtwpSC_fPv4QIvxvOnh_5 ztkn^o0rSkxUd~zlOTXK%Tg#ztlJr|%)ZY4_RzP}UV23CAA8#V(FEsue&W|&o>}7XB zAGM&6>Zm9RC&icx|K1732t%oVSBoCo5vG$1vzAdkSi<+T8bBal(WkG-JB_% ztL$xWQcBr#BZ&Nc+_6i$r7F`krqhX#ZUwuSmMQ$UfUhUf_Q3Sjlv#$kfyOZAOJMQE zW`y&d>9H^38ah*^V(J;2rmu=YdF&MNeb82|no1hh`ERg3EPN76?lj0ZMfjAfgC1ON zc-H5J0rxY-Lm*xn<;XH)$8fL@5lKfu<*822^H zdZYxCN8ts@2vGKa@>%-2-oNp9y|YS7OCKK}w|ndHmMG@Rmq5V67U=Z_;Z|UOett5V z&lk&%eMa_G`pG(!F7vRtkZ`tra~LH2OyQ3A1gkJp5fl8z9qb1PhZ^O4eGaUHo*OpF zcyUB_#)QpntAl{~w`VDWU)93`Jv7&$CnT<#u29ZzLIPhQbeb3*K=DockKF``etNV? zSQ8g}+M(i`69zX)u-e5FSsO|^Ai)YrxbAdxOm7(x+WZNJKRT)54^w>ChMY2&@tKT- z=xIk-Lm%e0xm8eLCWm(99caYnI>|S4{dZvixiMbXqrF#!Kt2>t|K&FgH|b*;AqCj| z!Yr7SX{5S5%4G!Q=P=vUC+8cjcz|j;nt{G~l+}tdReP*ZZ{>FfwHu#&E)ZLL+n#|6 z98ncnDMppDJ^F!UUi9rG^v6(Ts zyE9=VXet@vvRM(d3m-q{>B|Sp*G8LyjS7C&>G4uyNk-5$J#CkfhofKW@djhBpwpC! zxTDXN0*K2c>84qFD&<9tGeY=&7UPuX+Sq^V?)?!egl_DFD1=Q*m@0$lFhSD1kWRe@%MC{Li z5I~`Yrq*<^pcH`Bx_GfrAhYl;4W|Yfz#|~rhoN7L8dOyI*GSkGX1S@?Qh;1K9E?vy6@#xt2apG|7mX~jf+;^ucg~WpbGT2;W>hadU8ZjvaW7R}HlI}@ zf^!7dGh&i{ipC=>?IHQ411@(v@fK!|e9F?NfCy>$6X}=c@~aT}c{Xbbh_pRqgs1TC z9GUeyw{MU#K$4@<@Qv35X004=f0OGnuspW|p_nQ2gzgLevY+!vtsggnaaHK*yG5w1 z7?kEw-zpyUpRRW5cWH<1_Rld;8V zPA!)PnoFIk{d0fTIHarHC9cGQjZOpST#S-CUZ?VNpOy}I4*o0Kt4pTC`6=395vkdm zy?ofmgY|5d7Eg~~C3WERJhI=5U7fbw*(XDa!oAUC3R+}jB!LoEbJobMnQVFC_b44d_|GTA zP;L&Gl~V3`n>LsgXAuY)kMW($sb{0*A3wOu7eyM&)3KV>A_qidY%gD#8kr$=O_S9? zjlYj_ysx$pmJ$22-qVF1?SLOwy+=N3C0!@WOU)n3c{q14r(bds)8j`4C$rGEm)?vq zaQVk{NT}V2EQ2Qzy!;EA>Ij)H1txlLlCm==H9wQ_f2#7^ICnf%k$L=nF+%LPx?wYO zk>0h_{2}+<;zVut;+)|h=@cY_z}#mUQDMh&x{EZ76p&l;+-3B~qyb(aI>}^_ma97U z+v)E(dEO~r9vN^!5Km8P`8fGn5Y#kkRm|+c&P|d)46i(CF+BVa^5DkcX@?K$ERxNG zrz~_JEiaPTS?4i#YrT*itSc7D<+v_D&uDW}JC2?CZ{V5$^OW{f1rhP+5np*`OK8_` zbRtqz<}Jan!a^|eSQf~3q&{dydix4#wllw0ZA3{6$G;M=;4lY>hQgQkSWB2il%&rL z9Wk_O^US}^b;e3|?_eLO41Io|kxbl3Lg3-aLz>FfbihAIq~#FD<{qsFLHd{dd75X_ zpU0!O5xPPNJzsZ7a_|9mmR2x?H#V`Wz3o{HwT#y$Rn_0=vcMMYVl?EO&rQ`aj~XS- zmqN0vxX25OzT4TC!oB%Et{$>QQ4JhQW9{sZktYo- zkws_i1JhGKfNdu{4?&=#vQ8_cj-s5O5Mn53qIh6x>PoV8fZkw8p6y-vff?PILADhu9Q2x!iqa@iA`#x=B}rzRI#MyFYo-{J`R8Pp_32Vfrk*cxVQYg@^Ec7_^^n9okx=nu^m-kTe|JbtO8 zi;OGSpIhDq5HniUj3F5+kZS6$Y@;aB9Qb5*fJ7Cv*1U)T$jOC9K;m+&3=>G{azcTU zBmjW#BO@h6((*j~VDT*$P2a@ieh1t5!9F*Sp@w=V#=Trj@{b*0#5?`g{Jq&8zo8d( zdSVVN9I@f#^G*)O)At@Vw2@wUalrP`aw5b=!ZzQXXHgKPy{dpDDW%IT9ue3rG)mD( zJ8G8+ZG>AjjC<+Xd;eDQb1}*FF(Zojzq++B*Z=6&pu+yIx;3ogsm&`)x!!d!_$!3+ zuGsgUzJpJT|8U_H6cj48+8ztiZw5q(;`n(KDUf@5dQ#HTyiSav|ADiv>4BU(Gh>Ui zi3QzWJsn}i>8X$O@z~qT*L7$Jf`FeV3X?b%#8{6d0v z)_LBstub8N>TSyZ?;5eF>$bJ)FFBz~Bi*YF)hMp+ifd7vpkP~9H)=+?qxR1KSCQCt z&iD_?x*|dD$#~_&mz3dS6}~V@X_?F3gb?HMR+r@Akl=u=4QU%pvn*-v$Iq8-JfD6D zN(nX@f?T^`vXb}^kNfw&;3Bbz>e^W%Zgv`(iVW2LK@!wzDM(>tH+qvJHS3{%I|~KO zESl57!G2Y3blAys|0fBk8;TMn z5U3;;3Hw*kmAe2`bjkT=V;&>6{|hwIS7ll~W?CLtIZ1EuikFGqS7c;5=8lfyNu&xD z@<*x{;1LpL!lZ(wrD2E~8Xa@zFhd`X>q`_N-%}NA4~DUwixy8V4=S(l<*_uXnH)0V zNXj09q5|OH{;sQPCB3uZUg@X#gr#&d2%;qwBm^crpRK*v9>Y-yV-*VMh2xhZwbULF zm4-!LJJ1O(jblKAumMVb$LJgD@gJ_V2^#x`W62i8B;MLBw6B!Jp{JgjGjxFZ=M;)|Z}k zE_U`;@%EE})@lPWwi-tP3BM#VHovpTpi&*+4P+SajK&j<&Td4G)B`p?pcPDdjs&$E za{3qD^z$X_%91C;qYi z!D)@T==(TU?N14SmQcMF@wojuc1)9XvI!sT5K|IgLFsOcL0T*n9zFoX07ZthguAa& z^S>q0DM)VamkBy~6#RVi(!1EsX^pV0^a<1}z$&!)s}^$PET+-Zb&aXOKR_O*w0Kop z^gL#k(OqYG%G2FpmrxqWH0IOtL*~k{8G^g8(&+wX_#WBB&@uaSOs zLpITXD$@;$Ze~?>)~V6$n50p`c56YIJOl)4RzCln^q2wqgyG`bQeHioCgq&lu(T6=$^9ammUaQ*X;n7b zlaROdkZElCs$AiSi*j^T5F|jeE#mK1qn@HIgrG_eeR$RTXtKTgoP~qZ=%n-Cm|3{0 zSI2ASP|=kvPX8s#+_EECln9O~AK|QWJGgfy%W3xa(uGG z>o=R2=IJ&!z!gA7$R_Jkh;%g9{PfFXjAL6~)>on6be`Jw_#n%J+dz}jd(eFupjkWM zy~mU^KR&_{r?+NDlRgAv_@@lfqpV?|Vn+6TjkR`om`tUQlrKo?j?J=#DFq+4{bh3o zp}-#2oW=G~S-9-X0CIyaPOq=>P7s7-k+|e;Mg5Sm2{iR5btl%y)Q84yI~62SmstiI z9q8vu_j@9f85co(uH3BJp!1_xpC zh^v=1J;)*a?qodZzA{Zh#lh67XS|tlVwtdubA;#djCP;1W4Jvt!FP+TZ(gg6a5_jn z0GO?2goWxGMhf;2lV#b~oo~!GSV3(F>n+|1xIen`hdNmAg@69Jx1Lxx5+E}G%^|UT z^FUcyGV~+EFcLL3Fo<6qxd3)q)H=7fd;IIo=164x|0|aP?YV}-W*3Ynk3@)~-4N8tOBePH$%p)OZ3x9A?Xuhp><= z;r}+$@%963e|B;|#8kmz2lEZvUbLl3c*0^2eW7~pt37HvFj&XqE8 zd~6!@h&Y$QePU6aO(d1NCB6O0%xxM(B_Uh)yE|a?bz5kivrq%4->DM94gL z<$%lFL=)M98;69-SDq}=808|*s%G-MxpKs9z!}#pMX0tTB{k)Qke9 zB=~`nCnC``k1k=S>)>L)|K+a#Cn)&GqCS`muz4$^0U!uvz`(Thb)~g;XMAgLTv29* z1pfIguT*a8y0d}HX6-9loE>ES{eu5J)W2yGnB4y)R-pL7MEZ~SLuEbD>(l7$Nzsv6 z91`jBjZ1L3`Q=L}z=Dica7Oe$^q5}(8Dg#7@1emZOpWj*EDW>4=X!P=I$`Rl-Q&Gc zhzmcSKcA8A(XDw2ZlCBGOOA!{G3_Oxm*v;1xR9JT@Nam2k|4NSLw1z4=^I%4YL%?Q zs5&Aj6`q|nx7e~)Sh()!8~LrbBWWYAP2zr@bTC{PO8X}U)h^qh!|zZ`Wn zBmrfz%KaI_e!9Fstzv(F|1V@@qhr}yE^u&gphea7{XL@t87^b2{Z-U(%Q=$k(`88e zSXMOg5lkxlO)zR5`(NzzQ;IlL(P&kkYD%6`;o7rPvr-M7o$GqI`ZKy8O%`Wn1|Nsa zRO@Tk52IcQR6y&RspeYG9~-R?-JkCWox=xK4F$)UFjjX=O>fpmr?KLu(J}>|!ORhM zka}hYWiZIl;ax-IQ4D6^JiE8rY!YrMaED3Wuj(T5bQ)h*Nj-4B?tgFRS$1(Z}0SpLjtYN=Ja2W7&u&R$+yP~`};H?1s4Ga zhlZvQfNytsAvk#e8|!RCdV9GsHpQ0geTyH<0EAk~I-s)WIdabkS}%w(74wu=x5UL0Y5V{;L`|1x_$oq#p~YI1%hvl-kMs?H z03aA%6Zwx8kg7G&sgWEv#uwt!H-jJO--s^PA~KpYt`=vLCj~tCyu&qqZnj4zT`rO+ z<2e5PI^la>#_+Y$_%T%ecRpYtBjZ@ab8bmnS3XkjuC(L5O%@31YEPuuNZYHeA(J9~ zGib+H9O(DvAf2Z+Q^q^e1C|Yj!T%guU*N8gZL-!92)^Nq&(DCJe|mU0c)r#PRc8`cL;8Dpp~Inj9g`Y^;Ci6jli0X3xG`_d8XZJCPJyoH#~NU^k# z`>Cs#8L1Opzl(Zbk*+SL^rt?vW^vESHNU{$SDDA1yxJ5Un2VyV)?SchFM1APU441b%%&$J+bhhqNQj z0#_HWX>brj(UxNNv65}1A7$gEqyPV)>@8#CP`akUI8N-C6Eib2GdpI6n3q6=Rp9aUy|OqmxpOW1Oy?lWU6)u)LGIIJTstlQnAyO{-3kes&fS` zoGR)@Rwg+dD$P1+>8X>V60e07eyQBuM2_PRpy(Atl`z#7qcD7d%$LQoMYmu5DZ zF)|KdVd3>a4}6ybW$1q)J`cRP66a4zt?K8lzX%44M07RGyp1++nR%4S5?@ULK0yIyO6}%Ak~OzT%kO=hd${fob&Q4b z!uhKCa`V3mC=@HjDkX^<`}1F|;Lp$(9^QiK`#Svt*%bpcD}~Barmfh_=doE=L424= zM>1P&_YW3VQo=?qCFiH6qZK5m=PMD|MIX4Upk-xJ}YXY`=p@o=t~*XQX5lE(x6O)oS9 z1zrf08LR6%0zDQSaAT^MNtAm=V)jDe|2VbdXZCD}ih>=}D z!vo;3!&q|u;8-wBGJc|)&OGVLnQYOUDgeh~Ja#Tq8qW(8kLnWh#m2)@RVjW0LY?_p zm3EmuDUXLoadZ^>J}cxhwKM7*M~kdFCk6yc^Qho?B`y3w@~yrLZ*gx=y;)a!K7z1q zCDq7wA(iagh!yGgb&@uBgfg^|0&)4j?WBgG?cqr3977ALI#y8YXR=^?@^6B=k(=es z%o1IJgY;4-KH`pz+pzxRs>B{$ws>wx^d_6hUw23eZ3V9PGl`DwRG*US2iMnmAGfCy z@X``}x;O_`Cy@D|I0mTO-&w&DGwrXUBt4AtJ>FWKgu7z6yB@2p(aFcsY1=Q7daitr z67r!aNGv6x-|7-CA1#pP#{D*Cb=AeHO&2JYhrz@y1{8s$w^Jd8+6r?M0>5Y_mBMdW zvzR9^X)p=oxIX(XD#~QFNSl|RKbI^jF3w`LSb;0+-bR)~Dymrpa(ybA-!#^^?rrgD ziilx5o!$iAU(!(?7yQ=Vj&xh2I`NBLsV+UV_ySYmU$`E5B(U!7LiuZ$>jQEO;=scA zCzJ$u{JmWOYQ;pv#We&T2M1y?Sk9qcArqVKW>~&=>oTvs!kGA!y=-J)D_c7XG0ung zn!E{xT)Uq<-QGsSzK6b?R5tPR2ZmyymI#4IBvz(3RUYe5ojz7tlc$*7}{?tU5L!MSi z*Ko#zhC$c5C;*GFzUVCQG^6t^RNVzR%ps=Lbw`c7nKn*IBF^3Sgb|5H-XO)7P*Ez9 zX^@R;AdlRYG-#rD3)JrXU;;@8>sx^G1X$c1(t;V6d|puKJ7hw$z*+~mlCiwGNSmsL zhM$TfUo0S)vg$qT!9IQQJ=^>l7q_9_@+yARns#xrD2l)0^8nmZ_T%gHyrl+@q72(- zmaA18f^94-PhC=*V+G3YbKmo@Pq0*>P>@?YY6KF_ok1yjnimd5naMThJTorR7Rk6? z65{*q73W+2lR7q!&(rq&9@1&%!lo?l`D97bn3tosUBj)cMUDH8Y_9Cp&YvW{n5vem zRybn|$ydkRTB!%u>S*xey-?-nrOcV$q+5|@Jft;2%1;}MFt+1p*gN=gXf~e4C=a8z zp?hBUQH!1%o2OTUlS_EiVpN2^ys1xl8VnMpzewX~{o?mu=v=G+ZO+`ig(G-)u!Xf! zhH*-#&Gj5b5ZrNsJk)kiwEs^njb)4#x@97HhzILjqXn{0wV$p%*pbf*R5xYon6hd* zhKU6u0?{0`p-;%Xf93+gV@O69wON(01Rs>Aa$i_)KQuzcBQ>U+b*Cs0qzaUx}gc)cK6x|hnB}rcA;6$z8*L87WTmVNg2;FOqa-51t&vfy^s6D z(|D0C^&3)>&nW*y9{Mki*2Ut@!(7AqmIeIIRxO5%KbsiJPy?QwCnSr_$&r{zW65 z|I*;h^Extbb!WHHhOsrrP0rgaF!22uUiMe7ilso-BMan3 z&Cds&PAa}h03OlSwpj(q$r`oF(_*OPz8uqH-emY{1d=v`~DUaUgEp0)}-s|bakb2)6iA7)X=Sw-&Ku@1HRwdPkG!#N<3+0zdzLU{XP#A z>3|KeE-I!u!9eF8M-|?^2dT4duJfL^AeRQ9z7fB_&rxr@A&GBdrn30{?NEaftq5|K;Ie<{mR(BB^szH1z)*ODQ`W6_F@9Nc6rI$G?4#XQt*h{bAv(USYw zM*YjS>86UaJl)tx&E?$y+Y@pMzOhesQO6B`jLVfU0^mlA(Jfo-`h4WDB^y(2$|LvS zLxkmR$;|_%xZSbf`%j~xEQN|?k!W16P<%YMXgpx9o==&E#N$~i0BEF>%$4dgxy!xS z!TZkw3nPLtIDK_7dX?%Qur4aNS(%U*jS}w#2pi1b_r}>3u8; z#yxLk*oDXE%#lUd>xMjWLrAhN55{SEz*^3YTB;75O{F=Ykq*2#7e%=YuI;|EYXR)hU;$$R>6D}0mGcrA?c19PC~ z7(4T%eB7-xzbo@+RoKuNLnkb;8Cy9(3gxCJzpFoa8RTsPiR;Y8p3FPicY3mQ82*?u30 zxE?>^iD;QhuGb$lL~m-H06|2w#2X*{=KlnPt5uuTzVJNT2kaiVH;hbo<4R<9-;Go! zm-cuWVhr+@HwB755+lL1UXY%qxW2x^X-858xoJdjEG~&>{n5YRbG^AQ$O(W%lxqZF zJ^A~QtL54Ed1%jtWq9fAEbQK#G@-A-Xlcwh)jaG>Ad;w!dQr7}^A3BMH(9m!7rAx! z^fG27%4a%58#ToB&62hVl4MKquhv&x#NjYvyt^3`aSHo$Tna2D&C-M4uF~NeMSJ6X zqj?HtgFmUy^w&ED^+v6&cQ|Aw%#|61Ctf{r4CedVpcdcNd!Ji`&sRnzIN=>}XB(bh z`DD~ph<4&`3>@{v%^B$|{{2b*bK1QJ!~kg}A3l_F-pcBsGY0OWl;_8;%@_|NxA8wE zzd11!u7^oZJhGvr);+>L8jl9LiG^=YTuo4?-JE`(S>i90#8_mqUH7CfavhC#CI!pJ z*d!0grpYW7%GpQ@Us%hmXJc&TLQ*+^UyxA9=I`$=PJ2;MEmyF+k-XJ~ju=YXT~7^v z|AfHecRgLbMf9~va(~)4Bp=`GojX#b=h%vgZ7mphN=j( zQ8JZcnRgPe8DRF1+XorD5!)pXk(4j&2n1Aj#7R}ImjCeiUT!~K06(_GOY9=v|OP36{je9wCFE;?Msp?21%VJ+{J6UccGr*f@qrQ)O!2Y_522TDiC?kDsl)4 zUn>@HyajT*J6KuZ@H@B&TO17zEAK2#YKLt}coj1I%JoR)JvSgo1N#B7s*k@~6Tl^K zayM|&Ln4tAcx{REfFNfB3RxQt`&DHZk73WV!LKr?%a`HrPt^*Ho{yN+X%q|z8cV=* z6Q9uZjTnu6y$_bXuC)3iZ(0N^pc>CJJB`V#kEe%Avu{z+Sdwb4%yygfRfXQo2ey-i z(X+Tt#r!XCJN#p5ng+JE0q@C)VSH$}sjWb9>a53%E7xRB6quYB8P8g3T|Rql*Qp5k50~$XCG0FeAgo_Z zBv$E4^hUT^$q+@g?Hwe2I1NmQ`}*6y(npVi@Ck|cXL&c7Viwd?*0q-aN~%(cqc=#< zADhT89Pp1x4HujHR@ZTl7p=lPzkTPx0Vlv>*OL-Ij<5Yg{*;XhK#m!d)5?wAE=Iy? zimB~`^7BwJ#`iqNINcc@MQG~n2K;T5soLsM3M(oc&OI<=R@NT)Zx{Ek3~zKhlZ39w zSX~tj&w1j@5!Al2*2eej$9w7xap%iFF*-%E(cq*MTXu@E9yX#MV<&kOnwn~4LM0_A z0G9H6xr}~)I)7?pijdB8d_7Vp7tcV70dVmy#)0bq;M98aw+?7%Rx3M3qxkylIX*i7 zzrwV0LnV8o!MXGA{rGTBR^dMo_0J9u;P1>ZyYz+&ZUf0`y!$8qKk&LtENL;UOo zDp{eikLt^e z<`G7z9v@w+^t5Ef*Vdi07q0F(kxtsqNuQU7T0JJ9Co713{J_!VZu4_24qIlZjyOFd zH*6hl9WlId8<@AvsmjWd^-1!~?;Xb9T{2eQqAr}AeyIdD77 zYc-pn%|sC(xdMmWFn6D0-;6nLKY`Kb4GX_w`Z4p@W|sWZDW(S5XC4!!C5A1@<;NHY z2Tj>6+44gyfmhGT&fXH-1b-mlX4NpxX$1CmBcjYs)vNL0ON)&)v2V726hIehV~x6&QJceyG0U76XtCSULlb zeMPule_-61HTtsi5A_c1L(;dy`d`$Joh&Vk`}(}<%Vh+4OaB)Rv*AxwFVgC_J&F3(xjK3)wL z2)~?TjI1T16_`#5eQGHA)!sRhKDTptUT-ieZ0JRAwlMwFf>BqjugGA@ah0ooG+J%P z5)>DP1r92e@J$66X0-W&S!f+JsX_)YO%{o)Y{lT|$ALQ4t$HbKe)k+ezPa9;62(Vp zY!y(M2}y6F#e6P|JfrnAXR<5@)!)Iq(+q1A8z45Mt_Y3a?{z z8%mFZlz&;Pc-Ot)c1vD+$-^e&|Mut7DOLX-7UUv{9l0?UF!VPn)&rJmyw<^LupwXG zX;GRQkIEBaBB|>J30Lg+$))u0SZD=GuV!~}>^<^qo8Xh{O@2w`#~>TU7jB=STyd&L zG{3l{S4-fYIe2gRq6d5qy6#-1=)3=9qvd0D6TJY_$O)nUc9MbKWVZzxUpF!S3!SGt z5`q_G#D2WP$AJUN*{ub$YzIZpZuX4GVn=kqk-3*aTMjJsZJ!_*L$77g&g_hkzSW4% zVCv~RVdV1;*RQN8G#|K=S@V0}{h9&a3>c1M;zy;?PMl5BWOToz$~sW)L)_i*G4uA$ zn59nyiTYgBwvPnW1X_1_pmodR4xb^{!-RQ@jn6@AKiGUk$cU^ten7#2PV6tcW$v|G z|0DL`xT+OktQn8!^!DcnxX;^u4^2|pJYD}zeRgO9=puJx8s3_vua*YQcda#O`9#(e zsd2JQWVt{VIjAEL61my-C!VIXyz?fDo0%%@J$!AOY7Io>5?#I5Q?)JmA1y%6W~bic zWA^-|A$PCeD}vr_(Eq?(TDkGGxa` zM8C%^w6UWxeJkBGATcbBs6QuT^KX3;|^OE36a2TNkZ|{0gdKP zg=If-ISDuX?62P-Ie5@P)oI$=vjCYixps{(2*nJ)&f6eQ-ACuVg1%_lwF;>iW2UbL z)_WcUBbx!v{#e=7zn%MG@OdMM_GZxTe71s-2a8x!I};qb(C5Ks>Pz57yIS;Z870fg zTB0zPF9LYQ{-V%l=c~TC(bG>IQcK3KgkML;~PFsxw5fIp-T;u>#QaK@1uNHy3jJ z!eT4kGke*PJi$n#jtvD$b?0dYg*RDnZ#q6Jd$7ji)nWdFN%nwU0AQ|8WX_ z(jbDAkz&oQeYTm@3l$~))raG%e2e_sG)z@tu@K?mU0bvB- zB3t$8yU+yu(34?e^XLhv(eHi#k;_tBWQ;}-ZpuxnBv%?&EYZRqQRd;89|zAr1c=pO zGn;=91HZKg%d|PTRU$>Sd^kxgxs-qRM@vDRUUYb6#hSfuyPK#aMvL$$j${7*cs>QK z^gLK?4Lg(9-j$KRUI)hvx&Z)p!ZMmF!eIzBGpSq;Mv538Uc0U{W@~T zvkerF6t+0Gb5-A|)|YIgOKr{dF!C)@Cd(;us6@Hev?Qt;B|+~DY8?hRI_e+9ur#7g z;oqwhG$?CWnFs5aK6!eq8CvfM7WNojHovFq_!-ZNeBYB;xH~O92Fi^n?Ut+^L#swR z@An2*23iOeDdZ92|L|^8JN^%nP>)soIeQY(P`I>S#&-8tem*q9)9Y|)vkZAfTSJzj zP5Jh=W}@MM4%O|UcU1{cvDC>cF7q05leBMj@M+hJooOKPJ1h1F1de9;JZT#SDO4IM zhb3f{bZ_h^DN)Bcjky+a9Ov%Jef^BUCy*yQpN(+LVzgaT?iox>Hn+n3z{@VPGDdh2 zO`YV7nL6)<@{1Hkv3c!IOY+(16cSLO)NvL`LJY#{*f|J7Sw>bcU-Hu-R}2Bgj&{Yx zn53VHDk`02<};ir_(OcM9i=i(3pP9e9hua!X@_hAwRfinKHJ%NVR<#nXX%B4wPxst zCBh9o=0{vJVcX+Skt1qm7Fblq-kuqvQ=d`TROO%Fk)8M^kzz3lVvX98S={;+F9Sp3 zxNl+zkS(;~mz+_;anNXlm{yGN`IGHo)qD3KU|pllC8(gyI?|EMCW2bDky4(Q|DF+; z;A9NE{mD!gXH0?ywKMDZ0r1YFprZ$8W@hI0z3GQ#jHL~?y2*od7Qb(HYCZDpU%Bv0 zOmVVwqRE=!uo!Hq2CFG_cux)|UFpKwe$pf6cLA_x{88Y`+Qe^d=ZW#)@?MXM8<|ZZ zQaZDxNHD4YP14st|H+yA=I8ie#FZ#Mvg7uyPT9>pgFRCb>ZS=@9bQ_8J^~cOa?gsE zBJYbA#1G+aa>5Hz$x^1GbE2a5;S78cE*)QX@v3#;<_6FD`aN0J;30#Bo|mlUdRQ1~ zA>AVKGcOU{S@Y1v7C6U;DQ6#?Kz2rcBlpSee0|SaA3-K=_RdbR7&;S-dD*&sf?j$R zQ!3A5tsnW*ZK(2<;<@R@pwj!ax|bUl;cUltmkbDW-D;CNSNmh>4r8JLuh2=m~lFD17f3zHhKc4NkofR8hAU4iz&9Z zw{iJA6H7`cMMAEHxZN-Go0b}zn};SRqrsDvdj{Vh!6;k>7-+ixzG)&0+GtPOa-!eb z3jkBF6b*UT-vvQZ+e*BAc z(-~}fai!>jBeKs+yjSKy0xRiZyu`eegeM(#6n0b`Q&G|2a3t@+VmG;y*~Fg|xv>LX z&9NYp`ejs|q}r&A_z1CT8)dhB!tP+o5~Tq=v$5}I_mEHQP1AAE04fCF_N z312KvHw z3?;Q^fw-YI{87Z&-cBK}TH)3I7SwG|Rcbs6#o~^jue+Ht%Yo$h=T2gMLq_6@&fu(% z!!%tvCbR8vMl7;n*c{KFy+i*(+=A3OT5XT`?;3q6Gyv72c0Yq7+J}tca&+fqU8J!{ zc2lLGNxTyarfaQem2@$_5X`p>u87Pj(jzix>62@B+KA-b#7?T%;Zxa&$J4H?r&2oO z^Pe^{oE-VL^UkBP-Cy929-E0v^#}!^tU=NOaQG)#qc0@bj(%Rsa7S)7QJx3FO-SIB z#&1T*^t1*e1eYW4`AZhUE1h)M_vAmQOte0%3CpRcV-ux}37Q53bVi0Ab0{jug5Fd6 z=ZqpA-eh2)qHW*yYPu6$8p6WN8?hTaVLDX<#43f%to;GCxHm}40&WlnyTO;DMrI%l z-)IDh@SSF?`h#trUumPy*4Yn`6zgqY)q5~WJiOYTCQW++vn}daKe$n4ETEt}w(ek5 zIHWkdKcM@gv6ZM*F(!}tbFOLW8}r_b1}1?oa&_}TjeQx#=;jT4%kO_l3%%9uu@}=QO&%Y z`DY=RsE}Yli3Mbup+G^?8P%jK2Csd0iV-lKFm`_6%iA$oM!nCS$=Q0akl9T%kRD9L zYYe-cf@W$eBiYcSw6|jX8PyHHonWmedldR~Ofl#)lfA~I2`X|;v|!F!0G1p0!!OYr z9W>iu{=oe>gJwRyL(_e=yS{mYt&>!DtwUMR&{yt@*C9)+)I>4$hb{f!h%50kaFQh_ zj-osxqsHwyF%1E)HO&MbtI=f=GwE#X#Gx2#Hiz~&0(Ee7G^&WLT;G%VRddkY1@5=e zAf{Y$*6;N)zyzl9Pi*Dpi@pnpn;UyVp+l(&{?5Z4eBs16TuQ;YuxpETuPZV9Oe15nW~ZmfPB_i^ea2vm)O#ldmy}#8XK;Z2_q=xmLD)(3#&Ve=9F(X zxEjXBiRIe~gndPixJ~QW6}h9`3twTfwq_-7Cu_z*{u}e^?e?|-E}XcZjdmXdY_LPBVFa;) z?bbsrm))_^@cLP-DL3ptq;nwlZG1Uf7Z^qQr8f)I#r4ep$m!W^dR9l2$n;SGrOAgs z;>3y>tP^4;t*@<>JO;Uf^>nm)_7{JIRvRo5iiQ41Agb>kf{2$VnLu7mKOg*6y&X%M zK+8zk7qi<2uOEk_|Earhe=?lD;pGjNY3lT#{+e};I&5outMx(WhL#O?jZO`qMk8

CvbN?ccODbBckpF&;vYk&J{$Dlj7yoT@+gh9N6rP*W zBE=koGtH1r{vS(|t`CzP<-;kgW%XXXHpDBTSyC)NRjdyWH;v z5q^18nf<&c&nr`j;d~sP}Ctdr7>e&CLrP6Fj!%1xbnb%0r@co7WjcW7d5M zjCxA^|HL~}mkQLx`RFiC&DPVBDV@H7ClZBS|CWOgSYG-E2sAoiyut$;Qh;?#EIzso zR%fBE6F3@;yZ?@1K;2eW&^3oDxKUMj1Q&vi8{@dm*9#&+TF#?Zmjl?=F@{ws=$~^s^r2|WX>Y` z=B0`~V?(GlmQwJG7kIe%J47i6mr^^IB>{Sg@a=p~d$Fj>I8v>zE%jt;62`^WA1oRl z#{XyYsi|QlB)iE^VTQ23U()14JR#mbke8cmY3HlT#Fs;f+}n6+1Bd+hy=En{wosjS+ly1W~U9b zXR)JhEAC>zV&Cj)5!2h5h4fj(iT#gSwyUKWhr&>)jn>uy1E!UZJPG-)DDv+wRU$sM zm4V^!PUPwQ^-CiPdgGeP3YevST^AWdEj^UaXA>#e=f%pD>0NH6nsb96q8OucBi(re zNd9gaW7TVkly~A=loCcO{uqQj*6}NhZ^)7d^M?R)OD}(aW>} zv;T!h@*y~jkB3Q>sTD6WQq>)ziN6SMe&dV!6u|7v5c+cW6})0>0(}42w<$YXSyu?5 z6%(JDSO2eiSi56cl5b8&TAGczqTA>9^>s#Z*19>Q|BDosj*;)u;WDQ|IPQ6+@g0Sw z@MFRQ=gu5k06#w>npDLmwhC_wx?A1|hh*exeHcWctgeS@c!Wq0Tazl3rxBRtNBx(| z{>NY7B%%F}&So+=r$$mrqadd3_oH9Lw51@%=n8<4g)Y=?3WAl5Ycear0bngL1%%AE zm_1XIniLprJF_)@=hrV{)xP?mGm3;3){{VKW*q4iREHUoy|1*YEo4dmS+A#}g2NUH z+sNSLFe+pZxo1f^Bu*y4Gf6k8u4T`QMIch&LCjaqKTVDH3I z`q##ge-^+UV{+K?VKjcwByK_|Fj(?YQE!MK(BjPfQLbo(JX7TBLwc4Q6Y!aCX)w0a z4iyWL?rB!+nPzS;W4Dw&Y*@ey855j1-6dNKH7%h3js#3~`a@)a=XWD%K5sc6#vOY@ zTDAaYu?v#j8~mbrHuA8ywuY_G2w`mUpc*v;R2g!YET>D@%o|3${&%`p2EthzDQ&Q& zusAg7!z&76jGfrnuB*&OW7-*+Ny&mGYg$1HQ$E?rA4O!G#=IhrCTwx=3aWwkn=w^e zC-4aPWs5oJ>~>UfyazTYiG=Jm?fMbvxi#O{BhE4w&f!&LvB5RxXB||1Rfk4{Cs`G! z`wB$NTfJ3GZ4H^frji$!j|OWc9`31RrbL=eLa0NwZwJJCaF-w}}Tf@v_lS zjhua;1^CdQTc=CSWM)#Dm_&I^^??(02k)aQzN-ziwEMGc{X|$A^O0kcrQ}>2yFXgd5N1Q~d2WX_=aDjK>c#v|%eEd)NJuMUWD{ z5Hg6JFKA(r>IoZRkll5Ww65BJ7DAzk!=1ra|AeW z0+DYeS8`=PLb+mtcE-qFxuWh>4{VY!%*FJrNuQCcyF}&k-fhC7RU%LN&&N0O?TCn= z;E-JLl@4Q+_Val&{co|cv-H7R9^;yHo<>H@+$Pf->%&JzV#}J^#;sy8O zUGgosc;0ws=D<~(ai>1LsXnmGb#LCr7|PXYxxJ?^2?56=rD8jjx*)*xTQ zM-sHzCD^9QAZs8lp0QDea`BqYJ3}T={e166-cTNGRx6C^Oc|)vST)Xj#cAW+;VG}D z-NA44lvu@Dq8J7%YwAeUhtDRd{o+AKMD|>7E@Sex(Gr|r#^I%1Fp#9gHfqOb=p5q@ zbLEnEdlYg&7WP1+g}JsE6CVVtRAY~Igrq+CxbGQoA3AdUD$P(X zX2)OLHF5`IQ+jX|DALpGK7T$H-)%T8tIN$r6oHD1P(L zWY`-dmg|JtS5L-P{X~ql=F2Ua17?x?0;c?#cxh_{%EZ%6IS={h@)ix1*At;I9 zJG~fuJ`7WkX1zT^_v}R-&dw7BFxX(#!FREuOv>cjWb>ioH>X%35jgmqW2jf1PyWn4 zr*M-@9=|+k3=P=+_MQLB?h^ea?cpsNPj+X=^1{Z-m}L9q3FjpS5%dr+VJ1e0L9WKM z4{y}%bg)>bO_9cy$Lh}1?ZxMfh(RSuv+%6e_5>6C-8Jz~x?+i*S3!;{$GqEFMt5e#Y7bX85C-xBYYB=J~N9A~`K*RtUS zP<`d{^23xVA0?wwDnsww&z3ms{LKD?XFAtWF>#Pk&GU~y8BWzZ?(R7Ta(o5m=?jh1 z+{v|?I3xC!gQ+H zF8ls(@%>${?aII7dOe_%Jf+~MPQ1F}I9|#4Smt9WxfI%)PRw1~8%yod&;Bo*#oq|QsRGTC0y8$qv6urvIg;M& zWe`tlP5+y|x@b;H;{Qla+p2D}Ss3HW;Dd>*es=%z8bfk~q`tMArJDeix6M@$~ z-s1c%l>JM3V2#=`W$2f1La82|`^^>%+e$5~%6!}M#znrP60eta$VScb#g(?>UI@#L zmL#IDv4N!b_s}^d3PPgRUi?!|+2Vbj`yKZnF)q8wuU9g1Jln2GR#zIcG1f11X=zd5 z5tcl1B1vXrW6YTVHhTJGPW0C>pfb(X9`i43MEQg9{`S{pPklTH*TGoF#N6zluj0X= z$p{xy<``)|BR(2Gc~I+&!l-+cM7aQfQx>`W-7WYHMapPAog~V=FdAt;Kl(ypRXNXu zAZ=lGL}N68v_BTBiDZZGuyFgskL-DYA&4>s88j;$%KK zWg-(x3InZX7TFn~asSNmU=oixKK4o6mLh6)%$LN1)a~~QfAX*dTkus==~U+#e)IXS zgnB;aje%}Er&h?xI|ttAS>i%7Ef;wY+)OXH!GD}Z{+f%N6BZT2ykmw7>!dy;;j}+B z8y_6yuZKzzb5RAa6*n1sM85B0Uvdkk^aDc!PIw=`LV6Ucc9W~wK$mXxt)Z2M;Aow-E_cIL{$qNw?z+cF7A!SH<()vb%~a@RzXZVTD=PU zdc-H}YyZ!D@H=rFEAo}foMu zmXSsvcsj_%gR!1!U_)nEjq+#PD~1!bR0t_R$>;#p@;iK$_{r7sQ^0SsBSBIN>F{s8!3Dp*`(Aer31+IYB~HwU!rvB zh8n!J(pGUz?A$-tXrhZ{>2~S(m|ADb{Arz;zZ?lE*D{dez#DwJcxcG%y>i{iTrU&w z=?9$68dLM|>>Q-}g7UX}#XlivjddJxU};UjVKfVJpV^yUw6!+4#u0TkPRLU78Il37 z?DB5+lS*`|srpFx^Cu%L5P`e+t}Bv0@kz7iLkVPA?F%^kslh@#s>BuS)Tf9@ zh9B{@23YZYVxpLytQjLFkstUt7X2ocuJ4@oUVh*gu$lntqZ-_OG9gc^om~iiT3UUY z6Htry;g$m@K4y9)c(hP+ChVf{&$DH7Zm_x1@kAI!s3z8Vy|d9Ywzn(hWFzFJm?;pw zo<96`F&0Bv#omAX@x>3=IxYnp^5iwA+nks#u+Y!h&V+3XcK!e0)xHi|vW*7#=`!c@ zkI$b0SL}~)x0`n^v7FN8jHF*)vDw-re6i+2?2_?!O!Lr0EpLrSJ7(rbQWo;+&gH>7 zr0ENNaLbu6wc0)Y_WFEzbJIUQPOG(leCr7h1)0L2S0omNO+XuMv(}_oZ#rR}NwWz4 zwMAk^#X7B6Fw9hOQLM7Lh2DXOt{#w>c(-kp9J*5Z63GVEnYtlDlR=oUi|Bq;^Ol4kv(MUFZS_qUFEk zZIl6!pz+-1`t-p*EYob^>KL?4t=jD)Z&@&nJ*f>14d9Er`B5*y_A|YLmd0fA71H!A zEz>+xF^z8W?78q8y{7AB@kY_>JoYE!?*_@C7Vic`O(I4oA({=NQeF6iQf2wf>o3SJ z1@8N&)^O~)&jJS}`|&d*z=X7YWBuUhVA2jk@a6R>s^I8TT2fR^6=y&?1C+4U%F-G_ z%v*@W2s6~iR?`^VQ+KM;WH@%;-gLEr=%}x1pueaUi}!us{5>q4*CuGHk$amT;Cy0j%%lVr*vS(+aAwt4}DlWCv=b2r)^dr%3JH3kwsfuUhNa*KMJ!Ld%v zWk}wZ2P7et>1Tur{{yCNX>7G>sR2U0@P&tP*(JR$mZuOez;qqz8MQR+kF!Kewz$`r z*{te*INDQPEISG<71ujXk597(yOj-Qk6gtm@CN;>U*6UdKGl=Q|CiVBR-a{&!;kt+ z3Ld~F5%f!kOPNPSg#FF@id!f^7BLpe>4$~)^9|h#W75d$yW<^q$_NFQyKq?b2n09O z-q4^@kk`mwSe=*u3LKx*#mbsaWDL_$JdYvY5absx3`V?B29^U!^yTmxTQZ zV!t`EAh`Zxdvb*OR{ht-C=6tWSMDVe^tp8?QlM}{YHdn+4A33DHARR${b1e*D-KE{ zd8tDS{;Jy|Wyyl8=^1?@`F(Pvh9(2kZtC4LdS8(FXW)7x`j&0`@N0`ZerBr74A_i` z5lHL_0@-cGS;if!`*8bU=VXPtl(#CBk=R6Z@N1I+fLl$Va=0W7U$EK^r~5L=m&J;~ z?4VbA@4-#0e>+`XGPG07y#4!LAiS|vMPP@5JUgxBFOgsL)-B$d$4irpg=r4t_axuC z{RAXCIh;UKaM~+d5&a{bso#nqNwZF0(vnf~&FfFmXXNSYTW=8-1NnD02oSNsV6h$9-3*$myp?}(923|h$jm*KD~Tct zw0e82y}6$0?-*ug#?ENB`wibW$2#QZ1R3M39U1fBg;9fBbhnnuZHo+Hz{~I#+A> zo5`#znV3lbod@l@SHwNc`IZc6R3LA{5((j3X^6SnOx1gV2)Ge@U;rb`k{C~Ks{WF5 zYd~s9QnpLWnwq-tX$Yp?+1XDn9o%dV2HM#sijpS>1*3~;bn)E5sUUOL%9xzVaOv+u zx<=B_2m+0;24{^8x;MurqnV|AmUOvV%}xgw)wD;)vdgJ$pX6JIL$qc!qibuw9kpY8 zX@5%H$22-uj^3fyaOpH&{$VbXeub}2V?t^Da>&?$l2wd&Vdh9b5L?-#s?;`?qT-_R z!BN|CiG*?wcmM1N0_9`6Tdt-78aXo;dJr~Cots4!9(S)1j4@)=fr>zKR5@Y-e5_+I zo0Xknp)wq7$0j@#g+}uw%xy??PFnte8EK7Jo=<8ef2AD@Fj^0uuOxPG}+gLFSy_C=MR$DQK@l4y^@uCLGB3LVzYY6 zlqm@&jc>sPa)MExRnf6FNn6QOlaY@e`e{)j!4Fq>d__1n7LtmH=6unSPtMs$e~zW9 zQmIcVH@dKV-6oOmPWXH|R9fch{Age?AyQGM%Q=#&tBpib5nmT3D)@m@KSy*fo0Icv zsCqC2Zt@RGe^|Gbi5pl)zO2YjW_AlTs73=K1Wdf=vVF9;ZRLqQJp%lOJPld}|5k~C znOR7Wz94zRu1E1*w&SodGq|I0b#?uFrTSj|U$ngiR9sQhEf_)qA-DyH5Zv7@IE`Cy z3-0dj?(VL^-QBHmx1f!?>vWRupZDIZH*4P5TFq+ua=Cq_&aQK+cI^^%T>kOLa@fRo zww{${A7}%*J1w(~V(Qk*#!$>8#3W^nFb#49%jb1XEK*(qJeZ-hb zH?N|TmhPC{eRAF@a`(;6A6l z`SJChTe;WBwlVbT8Y4BF`Ej6IAaNR+o$o{Yk;1QF=+lqfT~+ zXmLbsv9%j1A%6wC>yP}kyH1-kA_T7(RkfdhZ-;$wC#JG-*@-_*EMj&+iWRm!gfFB9 zq{*q2*4DPpHd%}cOp;T%9v~M_?^R@sA~>*L_mA6Ez~`OPbAFB{6ZuFE7FnM_|Hw`8 z)orYI5CwSRrK=|+(cq2CH7tac*rnKmDY~ z3=R%Yt_*&LGon|6L<1bd`sB+0cBk?_^_6o@RO*#Q5(%Z25 zdll@+-AvF<$Z(}_#)%;*1f70(`C#Ea*|qg4B4~vWUji*GkMV=Elnp{K2(4U5v=w%oz9)K-@vQ+5fI z_A-5HvqJ$>mull;gJKZ1q~&6_n%(G5*Ro(!;DNvaAs*M%pXKQwZkO0-;S@%5-lL)T zh@j@ndzd687E)KoPraUUkR=nf@uR8;Ddl`5mwd#>&odYnCQV+Mu+>^0(3mFHMm9ve zqS6|*4KwnM8k_Jy-eGa?o8zdYTijM%?rRKgoUH7WZ3pI55yYKL5jA^GYh#3j@pa98 zUak*VgGP0c^URT3i(p)OHa4;(l4y~?d=Zh9l++5kiqZj(UoeXjtbMPVNwmxY5^CLx zJg)nbHa@4*bsq7F>8@M^Z9#@`JFbn}pHM~t~#?5xl41R?{n`;hV z`lsDQ0@0Y&c(BXyi6NJF^kV_-QRWu-B>lFBAV19aW+*#9BbwV`BbCI_Y&pITuFD17 zp0k`5dN-ob7l$b0Y#(mNwWw6TBD?KXZ0d^V)V*hFhN7oJ7K*`nx<8r!>fV+>tf@BS zy9P6PYQdntKF>i&(jTW|-L*0S56dA|J($vZO|GUINYfTEI+>EK<{#K};S}vXlWdUp6wPoX#qVIA7d?3(B~q?*Ka27gcXOg3OXn@wIi6&{tB zNr2EwT5M8rFI+<^TLf1ytVfwOxRw|nGhmvzX@ z!|AH5ky$jHj1Bcxx4heL4Bt$Mcd({X#_+(D7Vre*Pn`Q62gWU#=jemn@MQbFVM|dv zb*;IC@vK^Es<%r4jCl&1KW}?jo@=(??t*uBj@>64DIAa7&f!y+S{F5Aa!v6RLc!h& z{0HN@Z=@Epz3L6ZoYt9`jk<^{e}MkdB@X`#3Gp9qXZzqe7^| z>lATVD98ZCTsZZp@1{3PJ-JpR`BLh!!J2b$3&757Kx>d=LynF{0>{GL%mfb?3=EH) z7p?BSGEWnFsi38~=oBZB3U4mAxIUWs6}Z^n6QCLdvoB@F^ftl?1w0l25$=++g4>Ky zaXptR6MlDLE9Z70T`>RJSIK7=m{njz!yN2L7*g5(h`-7j- z@k9V8i#`|4wky6R&q$$Fg3ni+{r8@6h~2?N$zk)Gft1f0CjM$7at9@p80B)sTUZw5 z-cF=`G4{CrHe34v&hhXaC;EE*<4i*c>J?h3Qz|bEqdCr)&dhknbt!TeGZ|T#29<1c zBo!MI*Ba79LA~Go<)|6=ocDAg(vOyMeGy35=#&}j-(QvPjQx*#(BcaQ?6w*`tzBtq zla%r=7F3BN-w=( zQC1-Kj&MwEHj}KgxYl?|@qGq4u=bNjM~<^dmK}Bvw*nSF)Ei9&ZhoME2xZiHah=tU z%uaM8$owf0lghKy^eW+wX8rU^SSW)jHaPSFOk_)ckIiKFlP{F=T`bH7Ynsa~Iu=E& zNJ{L|@^S~}j^qC^wgnEU{dq;--JWg8WNbJEoG(JHplH_^*b%HRA{}Xu zcAbz|7&D*1Rogh)uX(0l6!hPn6KHH9aJs;MuRoxyrS!=Dk!dIHI#L6*K33`M8%M+_ zLuxFbzRlhFc@rGB(x!gC1m;7-7VkQFYelh5e~VkqMXU7<#D^_$JpJU?{msVrt4FG77{ME{jLvhCSt62WsDDsGD; zk{P17?-!xyU^v9M0)p4@A^vmOz*V zKv`gm(toV}R+lEP63&bKIwLgwU!soSbTU_Jn)yo$dWI!QHXG(9+N>{D4r+1y)o$W? zM!eX4D4p@j1Me^ty$zMjQ^66|HJjN3=0m-{iYQ{)hQ(`Yw20x4(8%873)H1%nOL#^ zP5{$ILq{C|SUf0Jg;e*f)w(Sj(|owr?`15p|aAP4F<+e1OPPsKy|5)>|YA>jNYzpiU) zv=NwJ77`IbLP<$kDTw^{825uV*4AA>AOas>XOyKwq@Am=#li0?XnA4qd2M&Fx z!4r{ltgdv2_v3X2V_YQ_hvB1C{pqtn2WEpWDu~vaM_hQKoh?OqoL%%MX67?6-V-vV z_K0yplBaml=KYnIv5)eX{x+wKK+$K;1_A}Abkbv6VgNeG_Ub01);{K$u@G^Cnx}7E zh$?jUa5&y2uOyDH_MsrZxJ4A#Ob4(hwn5x7$e=>UeK z1Kec@jB3wFaO@xkd^23WadYFgYsrM5kX&-2{k0E&nI0cVXyf%Zm&ghZyFEB$WMl#! zn|Nm(-qEYQH&hp^K`N;e3bqBmb1HF$s^Rv8ZZj*sJN?h$v|rN+8fhFFZK7~-r1 zLQgphDYH73KtK9b1DB+|F}d*Fq@hf-kcR;N?hF%4t?0Oogl};fts9-vDeukB4(-z> z2^yRV1|t?^CXso|(FxN+&u7jMO%7axe(+#Va|-pByg-sai>!-%dtFyhyb-N-6-N@r zt=G_C@V-4s)7i0!gei#k#%)Z@pkR3vReDA5VdK@U*ZI?j{!b=B$lRRzN2${I5&gdu zDlbJW@$UX}cJ^1WPG!2pl)mt2h(+t9vX+R>W90rL*=lo|fb2wt`>C!kF554!DU>&Y z1-l2IOj1@WQcg5soS9B?q{dW^GkRAMFFQyH#OA4OXM*=XKFhKg^srH#V>hSgnG1XFDf!O;f?b{o#mCGk{@-wl-$mLYgl>#tY^-P`)GiNMq;=B*7JLYZI+ zlYgj0Ffdaj!)F-~*y^ttToA2|JZ&d}`7q`AT{F{M9e6RQ1~+`iQAZu0_9|6;l)y!# zXTSMVDEWizW&aQkRs#e-T6ptNKXjl*$(2REQBsrjMnczj5C$Giv)fl6M>ckX%=mIf z`3i#V9R(*}-dd2bmc*WzoHlyWgqA=Wj?W(nOn&13$|Y{15(4BSqoROFgSG5cH4W}5 zvt7Z@=qvJ6F0^wRZSEplQcA3~E3l@DS^ugl zjfyjqlgLZ5ifXQ;%en^cPR zX@1&{)U*i&jiy;fj?HJGJP@Ebz8-}6r*6Kw(Du0^%Z_o69?4r;<-0}D;+A%Vw)3&> zL`2NzlUHbj^s`N7X<#>zfIU}$gHFmE~Nx8J!~76 z3t7&Gj$3&!#WvS8@Xf)l=vf*H`Y@iPxNwv9dR?Mi7O&$*`e){e9 zt5sFkP&1m7N!O%JAF}uTOe~3V16Y_4;Z+<5GryA|j#9}mnZs!}33R8bvVhIRq`qt^ zu1T*J8oEOaJ6FNXtWUB5C`LK*<5U94Nk-Qf9yO75kVMQo7435H(>m@CGYaU~z$+e2PrFYwS zJr~Artw%+6h4aqpUki3Z=xI>|&34y>&*+r;uE4oc=nR$rxr6$7?4k8T}-Cj zdd`J>EQNbAh+3-bk1t2eIo+4WaHF+wFyY*vUVoBx^Xb2CE3b41PxEOIl7!hoh;ffy zKfqk8u6T6cwEiExQ5s(+wiaEBog(DbY>}jm{ zN}&$~-M?zC(>Q}k6Gl+>H+=hJTy+tpavg-VS2K>m`IIZw^G^*M(l|$@odb2BDNUo2 z2a_U7&s_l8ZDDhIJDEXkDq1pc$s0!YIlrQ)94Xy2+D0ZFH%a70+X|7IkGPiOZ+e!1 z2xJpA{*o_#MONxj^yTYNs7j3a(sJqM=EK@GL}7G7b_P;jztA1~mIoqgw9EF?9y_ug zsmcgm;3Z@_k1`Q#xlQk~jnX*dY4qbFg048AlPb0V?a1L~vhSGmphrA!@H7=$RZ(0K zAyMSG604-95^XjVdzSj*pIJm13SAg+l8#AF@$%6AV%reS0bT$&ur*UGmnRto{sr{X zA~IBER^>18B#$c6EZ1SN5}~1{k`#5vqOCQX0{`VlvcoHRZ%>Zq(tmLQ!lYK@6Z##X$a{{MI{?v(fuYkrkahx)-t^|bB1*c|VTMjNtvn~#TLLqF(7;5X_u3?J zJY%gi*E#4k?pl4C0}&nFI;%gHXtx>?xw$??aL&Q#EnQ2S^Ok0+P10M@|9;-_u8-51 z7o$>Z_pm>Jxzu?>o0sonmY*Lc7IsFe(9DMJ##YuMa!fkx zk*I;df0w^v`EU6v&WgZ*JSwGF6w(8-WMtVI@>H;V@q&R?+23`SfR>9o^p@aprsMG< zgFYjJzA)HXIk$4lU>{Uk8uS)S!(px@`xbs}gwJ27YCsc|OD@GPy_*=!99AoNxfEL%$} ziLDgzT*!#lK(f#J3sQ-T?NapdH;ypBn&%Ss1O@;O%Q365(18Q7EP)Y?wcq$oO7wFk z?@-CkwOxGt;c66R0W(s(0kLS2%yYI&w`RipZl@Lcvmv!XefmCnk~>Z_kODsK@D= z1oVe_@2IG#3J7o?wms@f|6L~$!V(af#Lv~S{qg?Jnwga*`p%cZ##hfxOYM?O{iD4uS-a(Z?|p`zcpv^HcD>#*LqOL#F!FKqYyp1t#(lLF7-p4R%AOZSlm~v z10Oi?Rfb6LX-cBbY!C1X#fHCbd*xb{Jk8BU;SRdfCOfl{T=$8E8pMXjOtW@68!%VB zeyip5>JJg&tF^iTH6@Qsic03Y2cRy&s%{E+4yshFxdti@U(EHzj6o?YQ>D8n**Yp2 zNY+qpXNk*2qr4_c@;Su_h2{f!7KE)&V<9>_Ixv6wPZ;&nFFPiNEdv!9AjI~znyHe} zjzXL=`Ck6Be%Pqi8!VR1@fE}WbG=pxpqUvoUMb_!LGHcXZDUzzrLdR>nKQnOZ#RUMHXHTM*ZxeM*BZSY_v0{JH&OKE zm4)V{j?8KGLr;h7P`IMs_{&y_JjKeHp5>Z=(g;= zX=6k;pO!qI`B~?gM+jejutwkvhccbDAhGI*@yDf0)+iyyLRf%%lcmOE94Qo}zY+8X zRc`qrbcLI0u533QL3gY?y(@pk0_{Z@xJYWYu-FMk!UY9tPYN|gUNA|cluK+56U3z; znF^HB9qL{|SgQUVM4N)*S+)&&g9xs-$0-Nkdx^lnBL)7;J^3ZKiGNQNL@9>+(Ie8x zj?+NxwDmW$AX$-;?>W&Br15xoBe`m9SgPId33?0yo{k18`vS|mae3sc3BwzURdtRq zBR@)oGk{dpC9+W4jY`j)9QfsdlTxf%6PmczLmP<>)dODYcSrgN-D3|9P$UxwMJ+`< zj*%Zf8Pf;XZ(gWIxymORbX`mLd1(8fWGNRZy@1nQm69RmR*~8H_tE3#`%n_<_nY~) zeRo}5>3kUDZU@3|6Les|YF-LsceO`J*GXu;kyQ9h0O8>PLHx_PGdHk>j9_?AF$n7RP*a^R>P>!l_^^@wjwJSX|@vjhuzjlo6ru zqn(NzVD8n3;^Bm>bC4ygDZVpb8>1pgTG;5}6clWztUSDAmTgbGy>j7mG$eVsrxYty zIANevH{I>|G5@*!Ry;Mmueg&?s#1qyPV^K^}C89~)7Ul254!IIO;I zi$7;m&R<=ji7>+_-fd)!k+k5>uQ@RiAGEE8CjrF5-Fd~DF4o1fzL?>km*H{P3QZr~ z(7nRXo7TsQD@xQG~?^t446g@+KUZ1d^>v zQ35e)oor8mkQHZmGS#(2pH8b!`y&VbvnUZC;}o@Dg=ejIAIUG|QMn@zbBm^^x~-6I zgrQ2A8IBvfwE}Q61iE(f#mwqLh+3|KfDhWqQx)t=UMr&vIm5p&Gx@wSU5n{1Jxub< zH-gR~Fu|Q^qUPgkM*A~Nct!Bez?~A}bsJ_nhsiBxRr}|R7&J6ge6FP4PM7-(=kN|nD~~Im>mAp4VQa-uxgJwo?2h*>ssz;DmIr};`psphFl9QLaHr+ zw)nD6{0hn}c|rMK;l(9&HvBKs;_4ja>eEwj1QK*D*;UkacXtFMI!c4Z-qTxK{j@NL z9JFKTEu-pLq^Dh9f)w959D;sTL+l7YEhJP!+DzN34K_)CpZ~Z0v3>h~yLeH>qS&>}f zeWh=|3Fj{6#5CV$aH1WEkfZOZZl3X3uJA>&(1G&YmU5{zdW(an60+cGMfXT0m=SN! zhLyM1=qv#fo_m!kaRB0>y7os-jZ=YGLG^RaRE?JyJzu)iRur-U#qmjmRapNjtC$c$ z>Ui{7qaE2yMVioTB#F5~oxv(wf;B4xiPyMXxJl;N07+}e=+5Wf6HRj-kVsI>8cZFN zfC+|BR199#n*||`rNKJi?DI6t;5VKWCL;gXhjRKx3ZaOftSwOu zd}uGg7mNQNNOHF@#1Z<7^C@GSo%rWF!+M##Z36_Oj|#LHHRXvB7)XC;Ya8sewPguw zX>Z6cr4%L17cvzF^Z3dQleLp%=f?l6{&`TJHFn=ZR2q-V5iW%~$?Ga1)8^9n11SXm zJtoBCibhj@p|$M0!~+od3x%qNNZ-Tg{=4hO#a3(l6{4DEUc*ZOLZ z$$pc>?zxp_>wLV3xKE3yPV<|c08|Z&l7Ln*8P1pbuAJ`}tQsA_8#AM1d74^uOOma- zGqRF9!^meBAF3y}81`lirXG8+zFmg)jIA!3MZ?;+$6*83#*XgPNzt=vmuR8Yib@mS zTiOUVO|nA(J5H)lmHXB9*r+5&PrjA}{p;f=#LRw_r~S{ZMJ(MjL&;z<5hm`T^bu4U z+mlBJTB}oO{^q_~CY;bd`ANTrP4~Q zxeEwukaD#`7@5w~ySxnAUok}aN#XrU$=6^xjG{{CxE4ZodMn*>gfZDRuJJl8!L7oR z>|;b#b7;z3%^=fkXN&$ax>&eY5*U1PrP6fw_#vilY~E5muP-MREi#^41PvbZ^DL!*^TM?2RAmx{Q{ioKy}#ue zFsHY(rnr*rr`{n7_wF|<#}KCGDDxOSb94X4(~mtByn7r2i%;=+O%h6)bXbn)%aes| z(DUM0pK-i6;m-U)C6Lc4>1&*Jm|*=oHNXL_w)~tN#E?yiW>j{vU3zONwB#rA^#Id= zzsqbi)3KrTf@a74Pf;Y%9L%{2FDk4RoRW;+N3iD0+JzIOX~@rAnex;1*9ORD2{?TZ zX~ktZ6$}=Ud@Zy^NS!JHL8SaUwe;@`APpYj3z`q)5HcrJ**5A#=pK`5M4-rdj$~Ir zUyLROiDLSE>iP6$9ho7;OJ#Kgd;&KZvwsb%kB+IKK+l^8%WAmmP}DukSnqx-Hq)Ty#G3AHpvkCnkvvN$tD*I4)S+Te}-KeHKQ)0 zCM3jnAYBr0>0X|_YwbN8rfNc~6eVzqG2koPqRR;M_b(e%A1=e8cNU^q9S^UfU61@i zf;#EJ>s?9Jtoy4j&;H5qevLz7vGxvgv)H=G;7tjQ{yjZewz3taw)S8kJ>Fw!nySY@ z7DQa@mKBZYPX%8(&wbG;h0;a)A5lGvm=CpS>0DlZ#^tz77+xdyg?vv9_N$pf*OyRj z6Rj^+VCL{Y78kfllM7zp-vwOBw)ap^WE>GXTs&X6$N%tGebhUkjE~kE&2UiFV4oF*dEIbx*M>=+`(e(N@3|KZ9iPZoY z$dWf&c?&|Fe`|I5`3eiDywF3`bCPX)>nATS>Wjf)>Xm(n5P_A)jUq6!p^1*dpukIE zIXz`PTmPB3<$Ns`mX-ufmx-V9Sw`l^o&n`3qvu>{!r9(Kjb;eo~q%>M;P<27Z6U2Zg4@#3H0!bDjddc?2ft zIxRj$$MjcM_wZ)F$B5)Oy>QrV2Iv98R#YRMu`WFYRXS0|Q#}-LC(fi3yOWcX>e|{om1NWXSID@D8y^ zoAMMuQZ`DIh+xoLIijP_)ANdie(ULWK(}T{$U)5do?<(w-Cn7@URl>vuO_e6Rz}22 z3p4y`!JtS?Mo~3}c}kmSR8)RnzA{|U@-M{lOK{U*IxMouB_Xn|#(eC}aXnz8AsVGE z-nAj6jq0;#`bl218z0s*8J+2w-JRScSMKgzwFM@|150a^71886ru?hU_f11?w{nm5 zhmgdj-^ckoKX)MQoqxi8?YFzr!i8$QBcEAHE*6!U+D=IP?gES>gTYK^Y=4(F!O3W# zCt4^r;bQGhtC{9cU$$tW1YN{C!SOVNy?Ld|5Z;ino7=$jL-Jj0v-9a^(tg*ijQ$|t zVl4w|Ba5N#@&@YNO}CfQ$K?d~jiNoCgEO0}hA-~&d{NW2>Z_4<+5TV_U^AEn2)pWH z?Co1ZQ{L&8)*8zM0koBEQE=NwF-82iR$FRLu%3RqmQG=3`@vH+atCEPBtItF==u5i zlJj3~&;Kobb&2PM0$K!W#?=pp?^s3rNq`Z&tcn>%BbNflB=gi3ZrNEMea>zZK~IN! z{u4N(m&q-XW_yXtIrG{-x9<~*aUyceN@gQ-2!#bhc|Vp*3o!0a8plqNhtspN3KX6f zXhwyOr89=Glz*Ad368viEvh0c#O*cZC?bu}qEhg3BRJ}zrcj@UR)(cX zvnKfbzvcFgCy`+#%4>msb*=BJdyYW^{c26+==?v;wQ^K%;NoLT0Ot9l6ltT_*2yT z>K9k2L`G0I&}NLc*azWERzodiP7ph8)r)ooDn8f1lPDJW)+ghJs;~hT%A>8eGlS!G z7}+df6yDtmkEnj%tO3QSj(cpd+V1G5j|-4ULwb4QF3dR3zl(;ll712l6zrulW;}!) zm@pn3AmrbVk}?!1hAE$4=!fb$_vT>&A!$8Jbo@FA#f6OOef>J!f+>u28VDl~c5Bg?^KX2<>vu|AUkPaATy`E~^L9=OR8`7WyKq-g;n*^@iWDG}dEy3_$toz}2q* ziIjMWRY=N6EcPC&k_ETar=0d%&@(Yf@ZfS@)RNwyU5TSEGFIXixnYPJ?DFURV1+}_ z6cc;Y<$p{&&SXm~-#iFoGFzM@A}};mQcShyqU zhyWq*o?QKS_Xrr zm-%NeY!Obt;Y@T_T)EC!btFE=s z2$g(QzE1^*F1iWoNrqPw-#*rw9b>zNz_U;;%F&0?ILduT()TH7)J!y3V&no>p;v`M ze*Q#z_;ka4_0I0B`OXay@i=87-OVyf=<9UCOb{X{IW=u5?+0m0`P~+9kv5)VEdLylM&nTw-M%(3t$9Mrz` zVm<44qUAcNn}OoH{=Me3VF2zzlU5dqOe8{Y{kw}`1KCO@ju;T@so;5eVgj>bz3FDx zY&{cy1&dmEQdM+stD>-QafG6N4pHg;W2l0wk*M7BOQohK$%N7A#MR1cxR0DUl%95~ z=pau+k+3a`!kZn$n|mdbsMf-;dg67Op)vU2#4my79b`oSoDxUui42!dgNd|xgo)pO zX8AQ;q);tBfZE6?Re=6Mfj0LxwIw0^w!_l64sX`L!{*bdF_<;Py;Z&C=%v2Vm*?pK z#)jQwyDN=&S6G9;hX$B3ZYl-YZIA`oX)Am|J^*HAKE(1_h{ah#+gLV^D@|F64m9A} zoi-e;;*Rh{CMDwCUCrgOID-oQoERW>3lsa#`|@{)UAipE35Z5U2Rs?eX;S$c(xSV= zL6+^Kv=$UVCx4*GpS@WnU)U|1_u(CR?>=yfc(<^z*BkiDlGp7~nUGnkDF0GqN_czL zBXIpvG(*jjCEc3YqE(eCoK`rOkbc|F}U)-8QzD7_ljCsroESpOh|>FBxC>AU~h2XaORL(NuFn zh%9^Sg^L}mZd5lRLqfq37Q6mrcgmztqS-Ft>IHmNpmfsWPIsXdB{?wq_Z&?8sJ*tO z!6jiM)vbkY0ONxQq+ zwr}3U&w6i6&ds_!aWN`bi1=P#8|QE*!kCh3etRiToz9`MpTF_GvRXf6%Gxq?a-CCK zdTo7klv)mkMHC)7ZsH=-x}a~wTd|~(nG0py3>0MFI?w=mnbArZbpo~H@V6$3ER9Cg z?DD)vRAGl7dIPvQ9U1KmJw}K`na_vh1n)belqaY^E7+dfm_Oa(aX;73v=G0v!A1Oe zj27OUuWVcB*pFxYX9HxpK>#u7Le*MBD(#!I^P!nAEc#>Xu zB)D(G;|Fh1c3ARPXij{c$u}Vp*o8d9FII`xm*_>)Tx2122+-F39If(?lYVWjkuX9r z6;F1{ReqR@MgDc3jH#{v#RZ6P+4@oJ?Kzk^BIoBNlhh`(g&_CFfXGLmc>-(-?QJ!T zj-QL$uH=k3CE)GS+s-rN&`F+$)*hKFI+fWtEgz!W@3Qpb3i1mpy6B9;V7V0}cT&DR zX7K@OrvmTDSOJf_p=lWp?aJ({*D(2~4&eY*&NVeTKuLjzMTx_3A5DmkmdmV(*GI z+xx?ri`gk3!?dIK#1=|dpb1d>-MadA``1sN*LPCGlVafEGW{4vQ=m%$PQ_O8Acab8 zU$}|JIW3ak4yg<>pfqeDx;5_HwpMO6ceB}iKQiTQI^fLIT>S2=I_Emh{7X|w*h3A* zWMeq6=Kw3eHhkn);X@U=B28W>GvhpUX!y1FuaVsk`V~Y%>T{k`m_VLO*TgL5bUUZ} z(-%9!X{PCtG_CH>^vtoIIW;vk`zwuf{7B4!0;OJ^4GV`SU{th>n_IoM%lKnIFSh=* zLqOkO4*pzIHi$NFWSZ=^eRu#Z5WoD=?g;WKi!~I+*=p!>Y{vayye5bJpuX*u?fj9T zxUC3h$Y@gaGuNG2e-Mq+unL@7HxbcKj&zPT3#__;*S8a3CXAKuHv7kRO!tN za^VM0NR{jK(W@+u2*qkj!tzS26lo=n0KQIw&*8pbzkV@$#F2;pYuDwS)-df2z|FJ} zgp&D7sLaZS5gUzg`4(;LA^?8z7$*W;<4J0QF`9#m^J3KH9& z2{$g&J(Sr59C#OKy92{l%NKtM&$y4l7~JU}CE7i>ul5Xlr(t!&)sA<{R*sr=XeiBk zMI(b}&%AT=@?WsRlMFj^(yR&w#El%xx02!1dNvYUPzw_MflHjPDH*poLe9s=10HlN zpA*~q+GTz)7%vjmJ+6~QJleeNwO!$FhW$9=9~|M`ikL8}X{w2R&~EQx8GQ9?bj_OB zxD!)v7F-)mkIowDKuoH15K+kQ&4F8SAidMD<=dvhDNcDnNz%I0UdDC9?UZ?MtTV!t zWVfz)CfEGX`dyP?#+Eb3mzOLB%GQSz3JO@cu+AlXF&sr+3_S?d2Qp--{=<_?^YU`+$Y-YWCo?9>MT*;O5f2 z(<4B+_EyVg5W+?w< zE!A_ypzNig!rCm->zpqg`xV12Q9pVCL`{m=7G*@cY&mCP13!l8fx*W2!ZE6}O9#KP z+DD5;k&l+q6-H$UUXG^Z=j+?u&&(Y;Nt?Rt?tB4%oIDGxRK3_cuosged~r%*qWv8G zJ*qZqCkArQ_98MMAL9 z!Xtdc=n9YT>AVQj>wb^(HPIG$6WsvI7G>5#Mg~}Rzg@BF960}^v*B@P0TtrU)eJC&O6; zxPvvnjc7@fM#fur=z+!^EW8}ohaW|$zh7TVhy?RnvbZ?x3kn*ucLArPbPIG zuyMo|hX3xIrz|-xI3@0rfBnVWtH$pZfi}~JF4h3TkUf|Id@DvU#h@iA$HIqMl$kKv#VgNC)dB5RbHevqJ=fwI+`}q ztUyYbE7|s-gU~`ZHay|c-*dUt=4BzOh2x0U=sEZ9=FE1j1Tp%$u`#*Xm=M+|00OY;+u!;6LVJbHI(Q>KZIzZ21Ag-P z1W0;7!Jx^CeE-CNkM_KeGz~3#aC`!k2$b`_({yGU1#yQd#jcs87m45-@H0pS%1$I9Kp= z>m`bBr=2ZxD^~OH{yL+wBp3p|mLjdz*NJvLC6mW>GEWrI^?H9)n1BRTQ;DD2#tlgD zD)R_z3dm~!6TpG3)?;&(OryKe#0MBZ{m25v!KV921A`10FKBA|7}8I}4th0v&|P8T zxI5r+-s<|MhGtMR$Z~eIKRH(406cVHUf{N2Uid(jeAUUtanP05oc*MTzfKmilTSX? zVzof`Iq`>VGf*@y;1h&TlyqEvRs_>OXV)k@B}@A(VJ4#Kf=a+_K4C-Vpg(3{bhY0k zJPT2sDlF;p#Ia6k;k^vg_Pn#=uAn7~WGW(UL#PTs?%6~lt}{w2Cu-w6w4i*S{gbzH z;{tPgfd!T#URX;jxQ1e;*uKs zx9!hLP!VsiD>utA8PKmW%3R0%Sq|k=Xd{MMGZWeReMoA%pc(hc6UnfT)Gs?QmTo%K zc3|R6ENk=Mb>xSM{|Qurv8s?wx9<}a0&bJm6X$;*HB{sTsQST_hzb)Rv?xY_CM!9r_$rbhTnZ_aXAbeCTuL`;d;Jt z`SNj+{szi%WHn1P$+Ok%CJs7g>dCglTxG6pOYfA|;Okmwt=Pm^fqp5!#*5Z?lqFGv zcl8^0;D!_VS0w|ZhWuAua`J^S?sl!5tI>-H+&sIw<7 z5Fc+$;61Ft@C=#V;@V6x?t^HH)3Mm#DcQx?wCnnto6%*EMqjk`l8(QOP4t3n?S-k ziTi3-vy}U1yww+1iVM2{fgOBz#NM~X%(0g!p8$qZ*YXhVn()E*va2}Rta&{Sc{{LvS_8v%U1t zgTwL5h!r`OV(AD4c>0De6PYXt2_Pn^&;j~SB(whm!n4UVr5J)zwluxWO2Z4kr|34H zwdl5^EcQGrgrm3w{;n<1+15ckYV+yyn#mHi5OFI8nWj5+3LPA%9398m7Vwzz&x5O3 z#Q=*g&IJWaJooiIHz=d#SKxP_jS9;a1g5H8YLk;DGb781aOxrgm&VfDeH-caB^oO< z50>kxG+R%*J`#}rgHUK%_d`QZz8BKS{h4%MgctV9k%eUR7n7R`_27740mgYchWEN- z860WLH9_ocpu@-3>8nXmm2{2KY04sOz%nBVvjfDR0p$sh-{-!T$H#J|n5EHOCGz^& zxh7}S7Fk!xT>>ZWx^ zD1)2aJpZevfg|uJlQZzh7k$j-%~2ZD_5?@ z|K#8>%XW%gU~9s{kN-Wn=Sx4a6ZVK5fu_(z{f=&I9f@t>UsrZBPk-Z(>Fn_h)>Jn- z9`Mr!fnt+B2FX9H@n_oegv-s1OP_c4mWO5MndYHVeS|${c-*7RX5oz0Rz`C@(yRjS zt_3f7`CGRI@oCounUn4{iP7Z{D6AM#mnH1p^|-c;qa4C?@M`+JT9T%c=o1T3QB!bP z{-;gredwbAY+je&+_avTrS;VQ@JOVUUxQi>6v#`pj}Ri{8%_m5Rw7qw2P1f;gB#U^JcyIGfC#1mDzjd+0V0Qzfb%>JPmtycJWBU z>(vjeknkbV}XC*_+89%Zf?}*ee`(~o8DN4 z^jh{mE4hXX8cRQTB2-+`ADh1n)yY%hNACa{o-P0KgJ*Noseg$tX4UY27AiED5&6f> z|L>ZhEXGn9Sb|rsUB811E3rS#QN|SH^h^IXN3lx41w+7%lU;tai|>09PRIY*j>ozQ zN>hGktBW`!??Zdl7&t^Tznst44AWJuca=K=Nhrf$^DCCOKPj0mbuG~Q|R zP7^%eRdUl57HzytIGssO?@|0r1yVNcxNS88r)SD*nt{X){P3+DF_FJF&Y5Nkl<_Z9 zx8IU`TKveSvsm+Dy_nDnh=yEjDfk0s7YpP!TS-fU)YHvvL-NYNE6@M`5))Ue#cK;6D>BtW9G@ zcg-v5d=q=QX%4!J&UT%`Y<7oVqZ$z>L0q(VT1}CcPZ20veoSrDlHxAtln~mo_0R^$ zRj?ZcQT094*8K2+g1_{`(KqR%SIs+@ezG{55eUBhSwbpp^584426)1?ir5JaTrWXa z%7qlo&IEemV_>ereOZpEas+5-&_ z%;n3H>ENhtj}PAf4Q}kX3s2z*ak}j0!r3vE2c5<1#0Yp8Ct|x3-umm8mjsOMadqvf z?2m6Rm5=O^X3vg7{N$uZjH^Xs1m5)~4lLf`vnKOe4b2d8`0d*To7^&#<$*J3hF7X% zY`!F%;}oVs?&&pl=7hMNwQ(M4H}%~Ou={h~vH=v4|3VHbzz&>$|( z><&R?9z-3}&`RTR;?JSuYDD#g&M?>u&Iu?p=w92lYCPGZ&97=22~O2I*^2!7VXe%) zk8J^VASDtpevqyC057Sf*WULoQLDZ^l^6khbu@?<&D9>BThy-N{k=w7Q*6T=JHRKZ zrt9SQsrknbsHN8icV&sEpnotT^fT$!i(SU(MX`|1e2NERmL!)a>LOcX@>^-CGHT6V zMJzAy%>4vX**QO~XW<$OoDx(nwPV?@lGtYwt&T~1ZC0#SedoiAPe_o_pQZGZ@|NOM zVXW$pey9KJK3GM~I&z%H$cXogg+D2Bi=J_`V zy;A68e&yRz-)^4Y?A0(po$jyhN@e)m#z75H_{FzYv`w}W;^rTil+OlO{$ z?Q5_{@%9*`b?r&8$pesQPp{DxeK$BL0{=LIUBv)pCh3wr9zoI7MNUaMe)Z`(m4?vZ za4oMT$(QkURwL6TKEo?<+JP5{UAb+mm=g<0lI@O__47hy3xYUp0dCxkp5=3P+g)Sb zscT_~_Rt$macj;o41ee_!-507GV!*21Qc6k!1lWR<||fuYkvTGiE-#&xNzwsZU}!$ zw4({cW-Q^}ZataWs3M4xOTBg-D!3lu;g*94e--s_x9koO$nv>IAss-eRg}@|fjH3Y zw_#wMZ57#Gvx50qh`3asdE+&!NPDTse$Az{0oTw-+8z)LW*q;0zdwFL;l_&ty+_z% z1;Ka+TyE}*O_Wm)rajh9Y4mB+2;HzzotT`I)z+LXFGvV*d)~UNd38?W(XZlYtm@5` zC~b20fYQXDCVAHji!AwZH7Zv6C}286X}N`_;jkpV@whZy(`2y9#)!VHJL)9CM2=DZu>OHYNo zK0L?yxb4|hZ#~JY#hM4g;eX?#GwO9s&n6u+vW70+R)dV!XB0Q#OB)_4w(5|+c)LuT zJT4R21wzR0c$RfkCZgge>mJTVzy;bd@rEr19wI=KWG;f%Zj!4iDQR8(FuPViNu+_k z#=cia8QmU;-Q-I8*5l`<1fR{l6GwW|$|6hWhw`PCBzk@UkFh(Wje(!?2kwOn z>wt`%Zzj)X7f~2z61l^SB)Y8sEwl_c)!esx1x$K zh&x<$Unl_~)fAfLrmFp;1s?R>Rf_N_J?A|VtJRyJ@;z1=RgM1n@jub1lal=diA#~O z;Ot*GOso(g0)=Ejmm52!wwECW+C$1rS({&}6DP=6UsR=hiBw=*<(r5`6s%gM8vV;4 zJo<-0ko92cx4eA6YbIwz_2u}Y5q0Zj*jo2Ke+To~+&Y$X<9lX72YTQUwU^l$l^~Ff zEKJ<>29`;=AP3QX3ugohefbeg!e&bDw#0 z>vNY5$ZC&Fn{%K@_U{xo=V7HFz+@n}5DotvLA$axFKweLl;bl8F>zfqn4|Rx^0>C9q0oCN*8$>cRqe(k3m+QCr7_a4?RvW^@DnA3jEiSDb>^1dw4G9(RTUqIk_ za()b*Uow)zzX3#v$-LD`9=q8 z2X1#D`l==I-azcfSoEAYZ8ffkZ6LO8`_DG3ZRnUO|j_ z{pzHq!9|9+Zl_%wE5<*x++Td;gCH;;*H*%x&R0`3LQ2saiu5HC#HHyX3VXyDM-tl$ z450f7V#ASewIe1F5P&&Cu#`=%??YY}P*yiud9Nh(T-sF-T422$xu_X!0nP7o`D~GU zZYO9dDKVJh-X^{#&_rzeYUOxPb#TYPZxOee`-fk*QsQM#+LHMk55G!y!HAg2z8%JL zHWv19KC97px!M!{gjH3x=7n@Kir(^`&NlHj6HyH`t~b{>HoFwz z6r8oECDYOlER`>wp{TKZg=pp>W;J+$&uAC?Pk@z zTbg~p>_R&|?3ch$qG1}vT#@~sBYFSC((cy2Vpa99duN2ph;DVdT%QB1?e@yaOcqr~ zv|fhxs8ddIl1%a7{_|}G3uoG(#h8stIN~JRI5_rNcmEokzf6*y#fl!s_G@;9bF=A_ zrI*t$Js7~J5u1R&^3Z>g4PyT9(n$aRhyQ0LE+epz2P3DvJaV%?8S;L6tdM7ul7W*m z0tyu}s&$y0C_w8HP6E;RFC(qwRL9^`8@W1$hSZ~W3Hyu9FFiQg*~bet^2*BxWWS&} zV0~9Kw0%aV1{N-2ZI`SlEe$845fk#DZWq~`uP-VsEk(zW=tK(UXJ|&MClH)JSOT+s zq7MY3%ZTeHA4TXH8qT7X4)hI4(KlRz(~?C$dEo$|H3vgC9gauvTtCsHEvhHbI0qB! z{vR$fpB1VYsI)?FAs-}{`-g>OwvPt^8Z7=Dg8BbqM2)k!Eemx>u-iYoB;G5v@gMsA zxMH?VJ~?T%gC2zLkm5qNKqa(Q->_iP5!hQZeTB~fzB9Ek%9az+W{aj7#2<6c;J zz}qL-m_#9H^PhscS#_`zvV9y#V5vT6%~r9vaN15;3|wyy4gy?#;Gs5lQS2voVTxx) z9p9A783Ag67#Ku$stU4td3K5%WNl`0mTphQ>IPZ4`4!~%+@DhnSz9R5QeSF#H!j~- z{2SC92|EL*NU&q|CZe3?Y>pT0SjnB&UVwp7mq4@E(w%SEtIT8W>UPtt*$I3k6MVKE$$D?=7z=#( z`*)Bf#9)}?c-+)%SlN)S)@BQJ!eCWSlN5czNMtz$&6YueTBy%+#8A#VGn~oMPpN_Y6Xwi4h6m&-eAoSs z;`QX1%)Js(ZoB!qP-yQ(l?FJ!uoi74=xR;6vWiXujhEEr*9a#JRl|h$_Ub+m>|)c7 zNZ2x;hx2nu0}i0lswjo>oRXb-)gS7b>vV6F=!TtcX+|Vum$9KuWrCd}#&a*3-=a?s zUg*J8<@03x`78VRyp#mK&ZI4~}Z*b6Wv>^hfhv z1zyest2xog%~3ikmr7E#JnLj(y^mrsk(H8m)mP_GJJEvpLS5aFu&hi$)kuBFn>psT ztgKETjk~|(SCHyhRR={i?FrH)(SNM0EsGtWne}GmNG>0(#>PEkAjb{_yW8ocC=HIO zA)mC*62t+u6}n5;ncrH+KQSFTo}-d|M@>jkPM>G}l;9N^JsuuQer#Nt3Q3ve&l?8; zBPc5`%RSl9&hjLoVUwS0ES#Y)hIr<%r;&_tf7X7x^=<{u`6=F%0XDjTfu1t+Y=Djb zUf)N?)QT)$5q1__m*G_GWIC26bauObM z1?#U?9U7c{Jxq0lJ&?P+TU#ei)plCr&SdKJHC!_iRr=39NTe0E>W-0}>*ncNjrS&3 zl@mQ)P)=@^0fg&`C1=1PZeXZFhvNhpqY@VdNhh*6f;BedSyGbL}SKMHDG$ezbxaC0<_?q^e>fc}ozNW-fEJ@anm)@wlktnL%aN zTod~!a@)`FGV{oagehY|MhK{7Y8sh8z%1uT-Cofb*akV3S%2d)S%d93g@;*N>(Pl! z5nQW5 z45KQ(j)TKD?Cs@)CIwP5rnhxS&5(>*fPu3_)-v8-kJmC9XU~waw6wfQQ^JttCM+8M zCYJYU;4vt*jXqry2NoC_n?l9FUqvHnY+KHP5f+z1RajXVY%s#*>_^Rr{j-#pQl9f7 zM#<{CL$_F&Ep1mD>X?s#KhD*ih^D!o{`Rwj@yeH3&Md^Pugja&Pd%5vp)?$kgI4a_ zRBeEnF@i*9CnDp{J^OS8_NX-=P9TMbRbM#^S5*{gL|1W@VfQyf-PCFkH4?`h1{L~7 z!?ixb7-01qi^;3uEBu1E*CUbEAe)-+Vod^C;gxS@kHzo`bhJkz`(~}V%xa?y64I7^}gfTZZ_5ANg;okaI)v#{8*bQtp}u#zh3NqAdIV*t)(H-aPx%_ zwhT$0zaqp2OT&Kjp~sAPKuhGn$>x52R^d` zvZN&HMO$Kuu8QV+OhE*&=6LT@aFat4uv`M3RA>RC^fPRh3^`ap&n?(4X)eu7G8$1# z)EH>DvNP?km9A`_=RA4)^Ed#qoGS1AuB%Uan%6s3{a`Ms&K4f)>xt`mb77UxjbX`^ za;z2ISjnUq&|h%4u=MQrGB5C47Db+QJ50BA8Dmm2Z1;fOhl#1{RtMYrEt_GrJ-Fzy5}%?QQFN4>2p zR7dE+hcbI!lBt(CesX<9kSdBpZX3+NkPU|G4`fJWb%limG7a{sX))<3t^=5Ijz){i z2pn%-;K}8ad*owT4`f}j2<~8Y;KSYuyC@quFb;-`kMRpd%r5)EBAYPKe_D~X&cySG z(@)*@u=F(}c?LEtb#T6Uc2uf8ws!rBqm=34;)VR%+C9bVjYdE^u41M!_z@9(E6!ec zJAB99I^WAlL&-;7tTw%;ywUtb(Oy!PUCt8n-aXtn?lE@YnEKX)GZ6$1uraYG?+DA^ zfaZTRB8amIfE7TqOo&yHgK&)rk`~)PJ1Eedk%$`GUjHpb!PxknY|+SOvl%ec{XBn}-Ipe!uborC_@T|^MwIa1oIpP(b?x6TE@#d~* z&+$eV(=3nMlV5an9dS%ehuf=Is;0;EYzx;U+{7QF#+E8d(tKWoECw)o)l+qu*GO+1 zIHtNUT~VSYKVl|lus7kb{EZ- zSquDHk+YsO7N9e|M1GWssm>m9-U@oM6NoJkJ~vv+zQ2O4pu+i19?>D}DEcxVx-}#m zb$u(ew1y4?{GI+_8PK6%M3a6{DRAF$W~YGquZ&`}H(9Ve-ql zA$MDQ+$TPJ#l7ve?uPFv@ThtDd~#@!@6WV7IoK?8H&&znH<|Mxl^Y}mKmKB+Tab2r zX!-y?v|4{yq{zv>>&G}v>-HFz;^t6r18FNYWTk$w8jLzGFeR12l$@i)cnCo4K9X|w z;vuWwQ3B$r>?tfy$)L(4ZY(01G(|IM#>qbOJgd8KTX35P`B5!q)@4g|`Z^6+x*rhb z2hmrI&t{Bn(mH4Ig~S_4{_34WHCjzCamLJUAKcW=OPV~8iQIm=2n72#`+MY$x&)!n zDc}B1Xvo`;o!6eWdC-*_f_}?5ZQ?Fm|IW?$eK2(@g|7EC!vhqJ=}OJCC#!GpioASG z2I+OKrDr;q#7O$zvRi+>93jL;UavJVl0)M=E9SAXFV-k7dEAcu5bnp zF2&J%d!D0jm6WKq)AB`s$L%Je4tzRqZFfp&9e~zl%%AoIKHW#`S8WW?h?Fd2+#akR z0qpTcS->jL+}n9X_au+?Y^ijhV0!#(!@dFbQ zsj+!pt=~0#-@LFDc)|CgIdov(_V6|g7kt@Takfkj)@_aLiZUg&9<3p;q%Iq7taf7A zuJ1oIK}U{bMqL!rzY=*RJB&fL5FsP2Nw8PLNyVswy1(+YO3GT2q@6IT-A|7YJJIiS zD9^9Pf%~v?D#T4;O5NnPqaRR3i1#fbMZ`&h@GIV)FWq3>cqO7GhE0bWd!j0(?^@9I zk@`ZSRlVs?tl`CuW_8EU?ET69Ka0c6Ur{UAEnge>Xf=kPNM{19A6SmE0Mf7S9dL!k z&0JxeM@bB$))8b_NJ?oKYQ6t8j*)Z$+8;bc$G0f^ZqXxe7e+@V3-J9aZFdHH^~%-q z`Qf+jijRdHVL(%@jnQ9P`5JgzencWhH?lkB+4SAv5a03J>ViPsxsia8Uk_YN`03@h>oc} z%d(mZgcxFxlx!_gN9(|U!#t6{VO|AHJ`Y_ch0m({L0?~AacQXo(%t{j*!Z}rmR1qE zN{WVQINC5+S5sVniLxdzJ2`96KEb@r`E%+39d&~1`2NYvL(jqgSc2RCbYG;xg`=U5 zn1nrO&^@ECxi9Zr?Vu=hnqaip-v%%gXLe)CA}}*Y^k0=3 j-T3cega4PNp*t+1J6Lw)%gAyJ^h;GyQ=wAs&6ocGUZp}= literal 0 HcmV?d00001 diff --git a/common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_takeoff.png b/common/ros_packages/gui/rviz/rviz_tasks_panel/media/tasks_panel_takeoff.png new file mode 100644 index 0000000000000000000000000000000000000000..01639d0bbb4a9d2d13ade4860f30e7dc5b089941 GIT binary patch literal 77416 zcmc$_WpEtJvMwrFwgnbhWHDOI%*@PSF*7sE0*j>)Gcz;Oh?$vb#LNs&>zuvT-aF#P zjTi6Fn;$*VUDZ{UmC%`4UxvuZh{C~O!hnH+!HJ6rDS&}}jsOD#UxoVm@kE1Az3b!e zvx9)R64b}f6Us37;~v9NSj|z<#@NwC&)x{k#M;Knh}yxx-pI(>!PLg_90JJm(TV!6 zPJ;GEdX8o`*7!LI?lVX2&L=@oaA-lyJh{PEwcl`ImV6GhZ z+oS23|LiwH_A37GF@>~U&eys14Gf^+;m2n^;o;$vQd2>jn-{(JNK8ooEW~wetgRG0t#D2oP;2*B{U^_TL&WJ_y4ep88wy$5O3`{X-j6G<#Q97dmVpX@_KR z$kxW;4D@;jjuP{(!9vmZco9JV;Oa}V5gR9G;Y)gPhDb4lNaCk6`IZ>cS~Q&TIb6}e zl~VL+Cp1!IdunKmTwwRMH{J#4Pg{oEKQpvd#CX6T=H#-oy3iEtk8f#}q3>E+l9?C? z3X_tKPNZ$Erm-L7S_M`>w&UQ14$V$So?pJq>$V}rnbRCJhjWb!vn!8nE{;=##p%ok;e*CCA51< zI#q5U((CMM8t$)c_!7X=t5zy3&nJ(9%N1S_qiTnQbOVL~kBxyr`kJ8|jy8#&tgD~1 z`?i(&V7&xhu^#cWt2<=4oL672wFX5A{|sm~`uN5gxfa=<#oUwaZqtFijMz$=fIU%u zI)e@zPpZ&?&*$$NDNAQgynSCKh9|mWXEEGd@G3TsW~v-?F|p*Ey>yY@+}K4e%>JWTgc{tJMaf;i-=>IWH+5&7j_L5|z!Vh~3HQc` z_NIx$ulFI-&zb=R{2ctbv*5X{2!t`8L|{Tc$pf}K!C1ar>zSly1_!fUNWo&?`T)O1 zHW(*wuzf>N2OJ6g*?tUpw_#KSCXH8S@G@j+QavZWb-!{b{(923lS1xp-o*>)LuMSX zbz1w`v9284p@WcBklvln%v;NEH8#58X-5}IbOQu)B$>D~P%yA@xapM+53B1`ncCi* zNwf)c*RO;FJxqX-SWGzcfpKo*RI6V3vA+GL4vDAkt^N=t}{GU{zF!^Eft5boBCN|mpT}$f;NEyV* zz>@<>%M?Gsz9%Ion&6Ne0-(jW<=IJx!xt@BGITSz07&h96){+JjqMZpxEJ!vOsH|{ zXFu_0Nrs1G-`TpEPcZ64)GbvSnh36ZTm_3QEedS;$Z?U1*Uyvr4x-C0*rO#y9Iz)^ zshUX5{f2vb z@N4BeV;|J9{i&J87E6#!z|{-kKgt^5>h#s0U^lnFk6#KlGy;y~>@2|Nox5wp)4w?t zOHC~b5iKw!>Y|rR)=+7t-j#rv&P4luNqyOR0B_NOCv-9Xl^ zV!Gw<6tmfgN%~}d!`@)Uob!_PE+1ly7st%w~?v z+HQG&=&8cWD`NaOWMdu2mJmY|1tIBUJho*K(C;6p)@{%pEDa_F7V+hA6z^Vzfnho( zDhliXx)o34<A4CQdGtZ_S?>5i#If7Ch;xo@tOPdbD$f3Cc(gL76>E?nUR zq^_QM_aPQIIXDrgoRVobA!UwIyU&^G z{k`H2OY+_nIgYO7RHiu@oB)5X;n>qcaFVA$Gc8CDPB6n zq|T6M#(#XxTne$ z?_aMPzDO&45*<5=C(bN}ew31i@G%HBxev3QJ*D8?=gxx8HBArP)!F5 zb|grH%M^I`|j#2`E53FPG<*p0wS!eu4-q4)$zCf9Eipcmfs~|KM!8y z$G=GO68)p%hLt;6(Iq9OW20oZmjglzC4EK_fmp`Is|<{w!07MMw@32Uqv%rQ<(WzQ zW*F|psz;qu;dbrpx98Mpp=x^Omc4J+s?BywnZDd5K+jI7&c)O_JZ!_|owu~A8d6{c zR)+SSCM2Ki;^7=sGWVY-Ho9uZ0^>|yCTF=#=c`XBSBb~t0TW2*j80UNA`$!PS-Din z?5QhT&}0SkO$&Ivo9d6gRr@~$va4)dUfy1PWqFqa%9XvbDP1>>QPQ%dCI&8N3=&1o}f|8ZUrF)kc0L@kU1?-O;p6Lol8p6cE*rK)RcBp#i2 zhvR8A-HsZIwVE9PIPcn<{YE~4H+NkPSwr9UQU5)}QqRUlrc63VHkm|=n=w0qW zjU^wM#Zfg6$iLrPY?@jm9QOWO(1OdH?$5OJ_4T2kp@(KYot>T4)YRmP;@`CPGX95&fFj5s_^*Y)=B~={$uv8kVn#D(Iuhm+$vhT1Lj`>@5}VLXIIL8rWn!Kbxm3d z4f6X$Qa93nEpEH~!0hK$LfXkAQTsn^4^AZFCyEBuP(K9+!6P}l z{doFKiL5$lvqq9FfBwaV;8Dnk8`XyfUx@knd9{^Ag`%b(P8*rs8Ldy2V%iif$l;|b z@$^2&HI~tVznhty@dnqMs5A^)ZWana1{>*P7;1$CwnRi5<$qMSJkgWqw>W(S??~w& z+qC&}UE$&GJG*C56d4(*sJ?;ZTS;pp1M~+wUjjFsq>^*>9xn0Ew9_Lh?NqEhhQCVu z6N?BnxDI8AkT7L9#6NfOzqs6xzTl1)zBio;8CxyaBugxw;b@kx#T^yMzUD2&juBLa zPpQkd^yzjy?=pIZJ8;tf+P{UtEG{bXQ(oABjtIuT=_fE&0d_uU$FisSY70KK`mR!L zhNhOs?43hHL(^u`@CpB0W@`o{c{2)3!zVG5qb90JwAAAXj;6nSx&h;`wt9_mo?9hX znZ>Al!lTDPAU8e51=x{f+?e7TqryUtB@WKYHf1XCXBZVd9bi%jf#c~q z;vF|opN{XwoYYC42!e0{u^iG?thIDLtwWEV)2Brci2rDD_hC7kWbiz8d*iH)ndjHJ z?wUpJ)x$U4MdVSl9w*hHb$A|@;c;2y+W-gJ&ggb?#(L+NK%2DCate7-a`3&p3SCrMj@Kl|5S1%B`qUJOJYv%54B)@h;-gr02QQfj@@ReU^m2)^i z060^=56I&pC;;}S@YaQ|`=m}{r5++ad`Tz8CWeRbmCR(UY~au-Ll-7KzE^X7{K{H! zYUujwv=p_=;^0u5nuUd>sARZ6IyK`l?~QxG9W!4&f#(R#!)GNDSpSWfntv|cz&Nqv zxpjX-otbl4g_$*Q!G(qO~`2PJzVluE21!8)P^?=tlk)7LQ{TI~!=_ThWL33H{=QM|yAQEA*>z51#nJmcPP_?DrKF4}M><+ke;+HI$PN}Kny_0$iSuOQ0Jd1v|vJt7}3+U>I&JesyYSo+`}d$30>MY3J`*zEt7RK#2&9xJXcocn#& zlnQQ+zM}g2XMX_sV8_^3U&W6FnWyV{k>U+XOhyts#fJkMPlFn>bQl(6E^rXe;*pex z3F5kAZ5l@5;qh^6e?Rfer5Tw?!L8|pyNsG@&_*Yeg%ajssGEM4Re9?58Vk5?-aROP zzG<4Ht6oO_e!SnOgY`~Gp^TXc#g{w}^6%IkDl93Yhg55jkS(N#C^ohTAjyP073~0= zMn+%*Aj+fZ?ObT>pN6$^=nHL|uh>$Fsa2~BcB2Sp>lg(Lv?AcCLmhT+P`8Qy@rVh( zwcR9%Nbfx%qq!%JaFWV_w#di79)m$-cj>8dut)Q z{laNgK8R9c0_gWWozm5Iy`#ac3Dy0nk+pQET@dTmn z1v-nHK%lxsw8A9ekGq)Zoch9|+$GSdEmff4BKH}oq3(L)>h&koA$~%9LGau(7|d)6 zH75;0Qzf>pL>BtdQ&?lY##Zc-p3=!MdsB=TPR zo#w;!=juQIJLnIJ~spNU4a+K zF0Ofg@t+R-n{e{_*1KTfT=?)LHrF2Fl#l(+5cN-gmq#<-u~4{tI@il$!{qZq>`XV+ z7+x{w1OE~~${UpM^_95coW5WRK$G`qo7A5m;7sA$=uam{NKc*J2p!zevqD3Tk_VLS zOm7-ku_OKc%<`v-(fzVb!gJfXZ7gw@7DnPP(c0Sb4GI!X_)M$K4HdIELq>m=+qGKE zLsaOL)8%3C*uD$1%#KnZm+kE7W60r@fh&g-|C!lsJ&zBN;(lS?nS=NTrbXVXPbZw> z+R;i$-mY-0DZdV*ko0OWriqi zL#unYZmOA5-~D=lAhqEEaAi&@r7WyrI>1q17|UexLgCyW+vQX~l11>$x zMQU8IIF%>JO*4_&ss64u+oWNM$s49Pw>*<$YM&rnbK8o64L4&D%+{Ayd_1&J0v9i( z%~h#y6sG(_{o>DX<;?=o(xj#jazxK~ct56Y*QPl;JNvbawKwOn4pzLbV61rt@l}a^ zbkwbIQuTn(q%}e+sVz2j>Z_6$(>?8}!E=bm!Aue>@!F72>Rh%(E4ufiK75eBzPvIH z;4DpVzoJ$M9qGedLOfS+;g4r^trj58@2NATBml{M)(Ltl#hIcspn3!q;suSXySphT*kzPN=et zaES@8i1xr7Zf`@k1xTqIav|{Nk{8-6X34~x9%A-^I_o-%?-RWoeO1)!e!K7>HJ)+E z8OJ?k%UASS+1-`l2DPO*-EAQBgsk~0M~iy0fxIUeXD;lqUI!m49<-9lnyKVCq;bqPO79^(*sW z;tIK&g^{vs!srbX5(eob@xR>ZPwV|z(FLE!AQJ~qm3~fD`zXP=SHOCirxE`7WaYiR zGb)m_qcB_(`#Iu@Wr+4~4Z2|Y8gYeUaOCX}^WHIZ>bOG%jk#+Tqx1Ldo7B*lOUui9 z&PYNOzrM#!nlgRlm476Z*Vi+D^#>Q0H`L69l^9pGusB|o3H{rz*1S{s96?1*&F*&f zGoDg){4@`WPd-jnJFrW4bGt80O-l)4XKWnU*m(b~u+{yR;`{gST&@@RK?-;7wG9pZ)6+<- ztd0M*i247Fu!Q=}>^Z^zCMy7u@I3nedpMSueE7j#ArX<`eyIir?Bc|*gW zaF|Skk#%kJ6si@Y>+K%RUe7F3Q&U31!n@8f_R?=Jk3*TfyfQK}F?f|?R}3~$_Jcez zjW%fHvfv5`Ld$vDZC(nA&4}B#@rM~At(<^8mqa7ahQZ3Fxa|tYW7P?=C>{#x*W=%rY5!_fa=fx^ZY|b zGynpaOZV6;d9+xXhLD(R{wvU&xb_~L0{oKb)!i83E;-+kuUP7ASR){=9K4b3Jn6(#fTBx!+f0LrX9d=lJh< zmLR|tu1#r@>=8Be(8n?DB?p@X6E1~`m&6so8*$cr4PkCPpLhv4+tC!EZ8X|$Mie-= z-tG}d{KaO>v;3X38P6S%E~q(WXrF9@ixY&P((m!^?f4OkQ{_Edd`2w|-y2M=lV=}8 z9PFO2a8$#TikyF0Rj+g{?>om1S1pH5^IYe_YxhOa^h$O+v}#w*0`-2z8-`sH_OvD? zhREY$r0}g(Jlb0K8L^PBut{L0JfB(Hx0i2dIK26hJT(~4gJn>owQ+`W?uvP_%;lf?)O}NIRct85^ZkQ1itxt`zFLo7=c+~P z&nDaYEykTAKe#AROE^D9R8g_Tny;8)z^Xi6uN_y7Esu7ow=%c<~%ypHY3ySquo$e~Ot7Bz>q(nzz><>HP^hTa5Wc+OO6 zKbx{CE^39`BeHH>xiaa#QVZ9xwQhx}kCU2cl-gp&5hMRY26l12@ve+ZJfT=L24s!4 zVbf5quzt5V*jkQTT3Em9Y(^w3HS}l`p=an~GNX1!CPESJTAW2;WQ0Sw^Ag;c0@^-Y zY31BJlF65HBJWFODMN!ye&q3N4$h7{YM77wut1xhVT^g*h|s-hJ57U|kFFH5a`)m6 zvZD?)fJJmkzXkDZjTk{*0vNip1tfXWS^UB0sGDo+usYsXBwUlepSI2G!tlY~`=94J zQufThXnWS!QA4cOKEvk8RXyy#XcmGOH>%4!@^$$IywiJYtSufUiH}G4 zKnH?_@V`11xx@scaVgp9viCqw`DCUM(~Cg+6awGR;dH|%%;_JdZSNcuPaQIh8_0=; zese}A6OYlG7*@CiGLAsoU(+v(9CTc{@CXgaU$HXBKjNLhRe|14atm7%1F?ws-oqIrgP(c ze@4(}&8JkLHHMKQ;^i&b^+G+@*7w4WQ@;H_6juFG241l+Y`=Q#?z{QtX_q_4S8fkZ zQ?T@~zN|=C9VC3S@HV>~NSbzF^RSRHI`l=0tC7IJnRkoChVm-6Mrl)6-*?3=`gw4J zj}{pyk@+ykfK^3v&CxLtn$)%1(dPm#-gSTV13eCkR2=Lsp0wi3vFrH&CGTU&TcyxA>T#Hq^l#cPIKY+(a7=4@dhZMkcuc~W}lBNqv~%gz}IQR zWJp}ek}1at{qf#?PhKdZduv#0M}NEmD+k(2(Zxu%7Q`WQRnjzqH zh;?;DxDm#-^mA}%JrQ5pj_1Rd7H%e-jUt;zkG80bPYz`cCEyO3Url&y9-2672uvZ7 zH*BPCYciTzT(?hGf__1s8-T&GCQiFN;01iC$kR#3oGm&W2@vGq6Wu&JyfM>ER(^xTNYAzK6lQa|)``kh8P}HQyRZc;paY#YGbE!& zzi8d9g;aZq@+D4F_&4_XbkO(b4x9;=6@IG6L*$frhu-PcG`~NR^1y+g3Eoq5^tvcM z{?y2=^1wDunu`3Qd2^^R8R9#EX`PgiN)O0{RdHoE$HK>!3P>%LRlzT_!L=_OH8}Od z&7dQdK=spssxx&39qv~rZ__i0mCI|4sbcmHr{jx5Jox~;6yZ!Xp16C*p1F3e+g9(s zyOrW$*7R4x`{M_qyRoEB=VxE4v}*z<33Wa57`%aDoa8n`DpXlnlj$d=wHG)9cAj%V zPfCxE@KHKUHqqfte%fY&Ydmhf;jpRQfx|0Br68`964$6?M*qRx`ib}4^&)REtgtz) z5?8BLxrZD`Px5$bS3K>feXiU~XqNIL;qV*4m#c6TFFP>P_|W9ESZf^T2diw`vCH-| z2p|fl1bQ>*Ibcz`r{agMY`J;bV%uVOhH>>8Q9OUA1o=R1rkjl|{QhC6cc9^8Ip_NP$*U@<-9hL;DM^pKXkfI6l)l@rgO0l z|IeDmbU`Ct#t=Q6Ae87nT#k_w?W!g>na;Zx$vLdlk#G7#QNAj$`Gq5gSeZ*=^JvX4 z8tVm`vo@ehy4}vfIe)qpv=}`N_tW56aryBs%^`m4BUheNSq2)hhP%9T?3=6Qs$Z5e zl*L>t)Zs>$b&Na@aZ_s9N7;k*1QbLZZ9nhwJ3c*QXK)6)Sh#NO9myOHcX&4K5R#{- z&WffzJ3)<6HgBCM@B~fdhh$jKB%xbmn9gAMu}lH&zqpsR#k0{AWA>kIF<-jd@Fap} zMp*IhC@e%eBvEBuB-~i@?p;KoJl5Hz4FW>M?bW3wDPYtM7^S47=|h(IDiy{UruGQN z24?gttPDLHzbf50_SGvXt9xC2Ga-!ik$!G+;(UXxZIRvK8x`JjE)$NxtT$zS#)hVy zl6l_Uq)KtGGZ5E3x*On?DglW%#$TbQBih7j!eWvy&K`*kq>Q65sZ6RT! zfdHA3-4~lS9ab~J6M|2*X3vJ6-z@lD{B*oIL{Fy}57g&js0&c67!vfHXlmR+MmH@6 zWomY@UvoPOBEr6eM&mFCNoR?6;ZUtz?cweyl{0$tl(Nr)C{$a@_lRQ0VBd~eKPj@P z5mQ`%(Ho)F9JaS(TQ2z@`0yC;i+##Mva`T$m;F3Fdr$Vm{cL{#NmcD}!^@s+930ak z1r{%SC4+pFJwqi-NZ77uAei`>&FdD^q%pGVbaCI4>z&Y@3FXd0w*2>P8GHIF?4*Oy zD<+N70bi<#J58URzB*nuVorX^=7AhB<|AC;>Q6ocBa4r;5~0}vOcZFKHg^@zH_^=!?T8i zZ2y{(y1&Bl-I^gD-n)Nt!y3uKjlh3EtM`88u#Pq*PPFCQNsC-arE0m!%y{}}sZWCZ zYsbDOrX5kw8Z+$aBTkp}zQe7ExN0(fDkAK`V*3Jv}-(?JgKJXGg=Qo8zWzr|B zJ^}3I*SVOSAXabYpmD9;;h{NCC0j=Spm!1d6}s0~!iD3eGb)e!AbFOEwmG(^sd>?X zXl|cEuCsiE#le=SaVl1voEbGo_Z2iRN2GM#bwBC%jfdx9Cz_1K zPS#T{ayi0NP}j^T#e*FA8v+R+X{4pSun7(O)i5JpqkxvMZjcX#sw1U>m*htL)QaHZvLM2va8VsoY zxPw2OkX4PDDMo7c;Qnzmv0eG?$I>e==^OUapGd|}X0J1PG+K+p1CR4`M=P)5fG!hD z9|_J42ImTeo(B4onf){}<`lSh&E2QRp0bx5=)Rc)_C!>-i*1mH0`6;l;^0}>Qo}Kr z2kG4Q5d!zYqa@cU8usS)?Z`{30ZV&(xdIK!4S1@WM=S9)g7)6Sf+hodORHl1wAFuHWBhh4VnzqP5I|aNH-tOjr zU>=qtY>#-^3~$z2c0bhQSMwb(j;SA4tM4i3e6l(D)nfix7V471zP?a?c1Z{0Qk#0X ziA^yl@7tO8h6DNCclqie6VdnsB3_2;C?am4Yv$EsOvn7jmWnPcmp|2&_Z__HI1|wVP!vmdjhB!B9tn|zWmH_YD3)!YbaUb%WHV58KarL2# zLM!lbIC#0HDbQzcvLr^(2-kO8v>R*mnKQ(ctBz!2mgQaDQ=tS!MY zg4Iqll^IRs&m;~;OX}T%XCrjZcbz>#YOImZSHNZ6ZBEtMvWU{xWDkoH9V+P}0MB9h z=TLH$pD8qdwMLFWgH2&;w*P7B$1yX^&jMEa>cBTm+6d6LSw(a$CYVD6PI6r#u)M~m zJ&ME~uO@!|6LW9!rPRFKOe>%4OE_xX7s)AWTgcFNk0_t*!A|dJ$Rk&U_2vBJMzqD1 zANV{}0l_n0W9Ua2aKvGhgKS}kO`F}ZA<&%7N`9D)TU!$ zautC;STHR4Ewp%ahx*N!SUI}8>AB4mhGJ{r+!?(laFFmJj8dY#_JU{o!?SXL~t_cpl$<0MxT?`DiJfqJ2sOWdk93l(Bh6^Wp zj^=XU6QRnW&5-<#`a6>pviPtL#X%G(^ucr915s2X{u6^vB%~(dV0%+2FY^ zD5XkpjW1?9r3{1Y5;Jwo~!3#R79 zQ@uM5WvZ=vw2t5~MS2MPbv1)q1bGYW-V&wGDC^yna8Dloj2Ua8bLO!KOQF^!7#*wJ}$&T84|@$i{()uPeLC>r7<0W-7O8BiY*%np5x$vD|#BNPbnesGF!g zMQIwQfaFVTzwIZwE+L4^Cs+K0O;eo6J7Gm-7|PHeRm15o3R1;vx+v1~p8d1beBn{;( zd2ymefq+LbpYm;qEvVhQLF}+y={dsbuTxVC^89^vX65JjBWa@%jwH*#J<->3a(H^{@8Kv=pRQ-`Vr-G*HNFiBXw8S zIP4*Q^lwGdU7Jx9H=}>$N1-=342vl zd*o_X*T}*j$vIPwd%{fF=)7{t7qQ;k^41op&*qhk`SL9tSD(?*4^m9^-rPHmxKZr{%1auqo#!4~Lf|t)eKU6v1$k=J%lm*%+s)lB z#qFo-`|!PhYleB|l0bhIems`gf@4`jTktQ{tgIwd94OqxF*0)W0lh+cbQ2whz+nB| zk&CVjrVIwi^Ctk1b@f+QaF@nq5-<&jiP9&Ki_}(z%hpQ47my&3UQvd#_y8YxjA5fgPpt#I0S!vv>Ks}t7ZB6k@1>6=>uhx z#`U_#U77I1{1^tb4^Z97lqC1~V;2@=4Vg$r6AFuY92~QaPvG^h1{*sTy9NvyG|G82 z;E~f4dm*yg9O9dSsWQKyH4<80)Oc{*WOr3W;e1{v5kt5W0i%cp2Nzn5>pdH~6Air? zk>@9vt9T5TDr0R#Pt4`l!t!2g3!(J-s(4iFC#Q@mY!Kw{#0Ks=RrHg2@z$luNwjOd z3k@zy?Rk3L1v}S=SD;d&bje~RWlkBX2Z$L&$d=?fV{}U4jv|vANxBB*v;E`s%N_#e zSP0388Y>VJz5wQFgwbr7>(DiN{eP6xjvaHh-gs$GTJx0gAw)CP z08CH~jGsQLjq$+mQEEbb7%n zr<~oT(S6Poxw&+4 zuw(!uI+D4Cv0>!i!%j!Y9zg-;<60T7YSTbe*rUv;AL0jg`ikHq&xT+MKc>K$ z&Yl=Jqm)ZNG64h&T-)BiaT+(*76>wmoWb^3JaEk4$^Tky=K51!W@meuy)xVWxt~-< z=QXVUW%hw1*XskKd!2LLPZ+L#Po#x&t!uy@t0c%}_td0>hXZ{?l;hZsQe)qvUHThy zw8O!oId01#oxOf770JWv`wAX$Lz97kkDfT6I+4&03S3{Sr;O}O{HO#oSP3Swa9mel z46bn1a>~S%&)Qy_H`xMbfqTcCXBH7LO%?q^tH|&WD9_{LA<6Sdu$yk|!D*foI6~ zh&GxbELPa;bo*Fuu))I8P@q|W;x8Qe%!ZDkcF>h#rI*74$U}sNMnJLH~d$3h=*MfdN2a8Z^-JoDaN_qck8=6Ae?;XD6qZw)06HUwfac@&b&*@v#@p% z=&^{^5jMil__8ZX7`p=_QszE5%SVN=Wr0m54rlm%8O43|En;b)&F0=-6%v|2H2L+F zh3aKJ_lZ$H;HF_LjYDfi(e~Jo#Ii#q5BG-Nh27=klb*TyfWJu}o>u1%2UdrdCoRHl zS5Z=s{tB3gv^$aWyL}m{4Qi?V6J7|FZ8=EsNt`g4HJI?NG`KXSe31Fd- ztDd-(-ugE(XAp2ADPHuEmMNtv338RIIr;o6tlp(hpd&yTGpHu6o_!(%=tm!=R50>B zE(9gyUtf;evhx1@p+-36%scaSHY$BI<$}>Cqhsh*lmjW}+}?f6b6%%D&##eD9VFrC zzVYXErvLJ}xvCdTUlV-+V7+xQmWbuCXLMIcYPhLsv{HvPmZM7N{e){RiiJ-Q`de|J z8SU0`y~7?i&&5+VteO?4rRn;9l=k8D1j6xS>)S`C7~Kr9`(eXCs|fx{uGd-}@7^%A zCXJx+1&CxX7PRRRRs$RL#yaEkoOn$Dcg6gM|+;XBH6EWu=;%k~^_e?B^vTenC+56e9YxaCy96+e5gSQo}d@ z)Kw#UD_JhCQabxe_%O_OgFZ_gKkoynTZM|I#B%Y}ElIXp3YRj5F}_LK^p8@Me)e6E z2p~TDz`v2f{emNnC$p#1-q`dcmHzPA`Lnc)xhAnSI?l^>@>~H-{%~7Q;=&P~SC{T| zOIIHGbVhO*q;C5bM2Sa>!nzHnizm?F@}h8Lx7u+;o?Hy%{c5**$Fs}Lbzu&S!jd)G z7%5{dG{at@+XookG;ns$p52n~pUFJBxYJ)Jp`I?QcA+CvAn1&aKCvdxmSI<9@Z7Aa z1QSShqdSRBG4r`+T&)TTq3Y>{0U$I8K zZnNM94d0|sh6LNBDmMPISa!x7!WG49Qy6AxfA!;%AE*~zp|`mf;J|$CGVxw-YKqI| z2NDO&ruG*Yy zGl@fra*X;rm?`t+0slfX%hRbe?cNJ#CvuHx3_wbHl6y8&kN0Dwj4;z-f?0p0uWV%< zy4F7Rerz}AV_o(Snlq!~jb{(|U1Qpq!nTTC=*J=^OVm`71rozPI(6mi-nm+ia$b$0 z*Ag5vb*a?1>ft6#!2)Lz`#?M=PmRfzcL~cQB_A2usX9}#d3XG^IANyitIph$pt6yh z((~z!^V(E>V}SH1fic2Gu5mF^9GMm%gLl2~PIcs=B!n2IKMuDlpl?md`&jh{ttzX8 zs&&6;EdtU_Ojk|fa%P5@I zD}BR$EutpeSBR6V%2F`l4(9mu=;UTaOFU$YdveL5;Ryuq zD}K}!E2yLX4~D1eFHBdRS!{WTyH>dlFyra=ICsJ1#5$436SsXlZhM~tF2fZ4sAvCj zYl(rXNQ)I2uD?yVbk6?i#*9L#C~E6vkTK`o(Ds&I?aeVbgxMbW*`A1Y?&I80#f`k) z*-D>JygC1KrCa(q%uu75<1O6bSl_#pSJ#+?7OM}^~{{8*Hy3BZsMUtbUEcNhr zG~)IcK7X!e9`ysb1*i%q1@%C$J4u zplxhD^i^QO=Xz!Or1e?p{RT2+m@+`eK_R2^q{A*!jD=(Rz4+m$Uh z-)F3+Io(C=Z*9-xdqfyu8o`Y!ksaL9T*CDES;=NkGa;7wc9uPjoGTYr)}%iX^_#PN4{zYxAiqm@4q{30l*YD=V&!4i0CrAOg@+Y?&q74A6#uZnBR3(?_CaDA z)^~5${(2`Vd_{CD_J05>efz)?d5KMug&p3yBOztrsW@{DaH>fXc0V{=X?;dYf4H z8dz|A1IK<}O(l+Ysx=@cK*H!PYQK+cFP2tTj#n=)mnc@CW;TDBEyJfbr!)ts@l$9P zd0PLC1u(W;Y7Qy$I6nu71;A!Ab=|+Zr!P>lgV-k=#)pR3H?Cp-2d)?$@?U^HlK)y< z@_*Iy8xsC!0oDKiFFv`YgMYAl#?Q|$I6V9(6%|!wEn&dm!06~G9Scjr2P@suQU4+` z*i-zY94Gi*LQW15Ga`_|Xn4m-B>>SzTvr$0>3H6Y$Sj@RAy6`rX6x|qQDhqVFF>Pf z=3lg5YKMe}=Y15}xuwGq^m68W;3cuSTndAlcT=5T%S=53WV zhMlhN^SJ+g%;y8bx1h?8s>n*S_2G`lh^s8QjnkhUe`f!JphxrmYje-jSTUH~TXWQw z`e7j;{P#&_j3r$k8eFLV!k}K#ieEGRHCda(x>A*Bwp?4ZqkTc%;P2D4_iU1{X3uks zy$8U>`oH9@7l_aNzvXZ141YQZzQCY}Wro8l;B{^LFEG|9v!_`q7oBJoui1Pz(a-qO zYp+=mwsqsDtz=iz)nENn*@GIN?ygTaCBcJ}bn_S#&|c4N4F@#rsn07MiD6>|Lf#Iu zfpm>RN}@<30$;{=A51ikb7X2CX8K)!RQFF0!|&IOCD}0%IDk7vV?TFbRIGEW+3iAK z1k6Z^UXG=Vv_bibkjU6e>maEL12gY9_QkWNp>U~_WKI@vM0JPs)@r-Ccmo9 z2*-#NnIOHD;MsP|=Ewsaq60Q^l#O~-SKD(g3s2hW)pLU7a87adk@M7WjP`v@g!2sD zgca?t&W{-mLtq?n@Nnor`Y4U9@2l)DIA=Zx`TJ>M#Xbz!M5U)8;TC}{TX-h1_4Yt1p{m}B1eTs?j5=VjcZ+ZjvVjTG?! z=u585V8bpla%Wb2jS8{04xKG8<`f%8QuyL#B9c6l`0)UOqFT+TQi+d2Nf)L`7;!m=ZnSinSGSjWn$N1PLmS0;$$=@D-PjKhLsr51lk{xO!D*J4<+ z)!%@N@H6tUo#pO9A|CI)i*k+w+9*dm*6=Coj_GUv-Wb<{P~{0VB6zMDr&$N9kV@0n zR*YX^^|oG0L#n~?!jeMR`h(tAsKl_y*9x%d6~~(1zk>4sU4?2}kW?5UrBc5O>mz#_ z62!80hg^{!cwW$7-ZQ`V-S{Vv^K%SbTr`{EyuylW{FMURiwhjiQ3165FyL>H5U*L3 z?L#<%F>Yq2V7Iu51x(UuwU-Fz!p>Ff0)N8$HX0zQszlU*Ath6Z)WUhp5bg$f2x>T7ZY+@{`&|k-V}*ob zw_nT0kxq${K&7)m-Pe!^Z*IPDt^e^B-;w5tZn%JnQ3~~%iI8vh!B7De<dk zOgAsA&EKDW4G0UmR(t8`g~Q%6Ln^eJFI$9Y%fA$H_|#kS$KdiGDV1en?}eU|QeS?- z6K~7~7C;x9{l=)7$;gQnPq=JU!FJ0g@2pVjokWWi-aEMILnWD2R{$738XUDR8`@dL zWO+e_yquFb`rkbX^B^sKTRJs$zH%67G=ctpHdQv5h*t6)3TLU6`DdiIiC2M~0Ol{b z#A2W`?-1K&{7H28ugbx*mbNx!zb8#4ww}tDLR8bNlUg>`zG8P5&sV2}10df})_(I_ zqeEkZsHtgmmNK_zWs4AKH7VqoS6r!4!vn^?O{|{b2WdmQ(#Qym^iO!&=WUfYKL1*v zvrFs}szU%x*X{HRv;QPQ4f>AYXL)sX9scJX>?%^HceWLEm%f=%d{zW;DNds3_X(SF z!$T5oo=#>4LS0SQM>q>2$BWR|GQD0b0IM{r{`(NzBxL-5rDJx2_F7EbOlPW(K+I}| zfax?ckr_R~j}k@r6p(Z7D;hZzhc3u*S2t$T!BoBb?8R9ViVR?=roHl-E_%PP?}77} znjxOTd_cM|hET1aJ(JN@kR8scZ`UpAa6#@GeIw*yj|sKvGvu?W`jJ0o_wKE3$?i;S zwTv={y;DM9sOgu}OUpi2Kne%zu%^&W+AZC~rXk^Qd)Vi9{!`f|+fM0MwFPFFZ{jy+ zS^eJi@jC%2T<^-ZlX7+2tPH_4cpR=@-Vl)l#1 zBG?($RaW;tW9NggjZ1R+ZZ6rP#{j+fTsna`m&g@kze^&?#{+JDUNF~3~gXvc$E8i)ebGL(n!KStaAjVg{1nCw^KI9@%<$Lk1{C* z#Aths2yh&<;( zpPc26n9@Ai#QdCLytNPljXVCdHK><=(ZNngdR)r8x0seVC@AQ&lO=AJ4ZOFq zfwiS@p3@UsQ(GIV)^sdcMtN}WF%*(_69O2nGkk&T)rwmJt&7H-7x2=`ANOf}EIC7= z86b_uIX?7mXH_F~xsP4%Ais9qKEvN@KNyRTu=vf0YL#*dq;M(cd@&<_PZpw4g;Y%_ zMpgPzcb6H&$S?%LLw{wh5Bue|%>I-nu#b%G1zJ-dKQySGg^&+Xf&BI+uz?qGDTi zISA-R9tvGqs?j0m4=$xSU)PJGkVdc(4yCZy)NZ^Jv5in_Uan%6`(2az&@LJICqTOD z&6g`Yup?CO%-k)UsNI^4V*jk0Q8!S^=b!ujdmD7bo+;xMG7Bi~+s|^4wC}Gee5e)a z*U6SM4YWzX67FDMnYOiQRfOHtnp%;=S-|bDwJM+gAbI7eR@Elf$-Ft!)B*?ZgI6At zD$ICI@M3>laKpI&^b?k~HIbGAo?itsgz3_lwdu7hkV=>DS?wu)-jHMm4`WcmP&9rJ z9e0x=M)0jUrKOVP*1jl{(!h%)+Gi~O)K+XN3#&7I+tfTNyEm-&cIZN^PXd{+B?4xe zl}!}aCF>Vp@sqrg(a9fKauik1X^9e#;f)%+8Ix-2#JdO9`q4T6gaG0Y>ex>LfB@|o z>H|zV;m261I8SF6(KF;fqTKplmQ6UbTOccrvJQ0?-~dq2o>&_>uB)eMEz=fqi=7JFOfnJ+VfN6tf<*V=zO7y65 zl^xWIjJk3|{Lb|h*OTcXr~b7-J6Ts+im#U0DJ7y52uWv?`FjiU1)IN{lo@1pgSW zuqMsIcx8B_#iDNqmh5fZ(Z47IKDbQGf~c9A8vE!@2Xj681066Y<;h-p+m6XFJRsf)e5Sn5Qq z^SQOXyLC$Zr?xMI$~i?T_~t=r+88S-+0vnlTq`7kqYO)lSYKD#T#f+{1s%qcv9dEa z!)9gS+Fo7j)7kd=)~)22g3m zj+kn^Jl5G(VsIK~4a*M8{jA^IP}wQTWV26G$53&q&DdW+80IF@1^1<>@pkGevK0hF z3lmFO>Z<=G>peS9I-{XZAMWP%gxbVjuJ2I%v9rnpbea&Wu*8v2!I?k30Q4btDE#$n z`a?p3gq&Zp3^4@-VV3F>4b}AJiKcRRRRKZJ#%?vt$t{F)|5}%9k_+4kE6_rrBaQ0k z=k3i|eiQLuV&y(MIZO00}JKjJ%; z>_rLVTJaVpziQr1u|Dq*LP06AwSSl4+)v%+p48UIe? zt=WSZoXsChFm8GC3ilg0cGTs^q`t4z@$3ZuvC(1%l9Q8jZEbC%4!Pl<0`sdB@9URJ zX-N`dV&c9eiF&NB0e}WiW{@YWul5tdSh5TGO-8mi(ZfeXnwg4jS})4zKlcDbGKiHR zrfR~K{s6o$Or^s^K2nbED-OvyNR+tr;jxU42jjXxf5$YZq>iqXb@^4$5G=jf%;b`J z8cTi8=q`kMO$j@LqQN4N_O>sD)$z@eM9H~-bE&^2E!5#?EiGcX33Ue5*FivkYAw69 z8=1IYy9i-5+|PjA8xN$gGo8z#+lFC!9_47$dizmV3TMa;ZaMNE0V_e}@(slC8%!ni`|?Ts^PnGF^HyY*v3NUADZ1u?xH zEl~!0$Q2VbbTkQxS${ccC1FUo@R2f~K#S@I+hd=jXEnbs{SZ+$wH&QETfRl4%oHJ_ z2-tjCbknfg3=BqFaxN>#EnWvGO)wjz4A3_dHjY3JA$j>nomz2KTYT+iBw|-@5uO+C z7_M*V^%?B#jF(hG2qB;)?ouW-ni=J9YeIf^?Z8}*8K6p%#%j4lo5#;-AVr53JF}Gt z{`z_yWA29uDA%`+2n5Evz$z+Ey8O@)KTo!quaRvbsD>mCF30fNzcGMI*-* z+~nYfWs4KD&?c8uuc`qEHFcbs1*#aL7yUY&e!cf4Y2_*FE@GjV~eB{Or* zqSZE$!F9}7RcfE_`eW^q2XQhujf6_EPESv5T2({U8f928@;Cy!tH(#W25M`8#V;+& z8ZIx%hkAaqbuKiY0l7(Z+DyG@mTZ@a_{H){jJwj zPqec?j%ti8DH&}h#_L?mWfpOtvp4Pm0EU6*uO$KzdZzz!D_vFw7iSj>GOxEd?iAsj zEH{MyuF~#akbxuaKVIqZU_D)J_IuLCIOg@NE!?1X^}cE&__NQcCG2M@y4M%jQr||P z$u>R88~%)Q!i+ZLzvI0_PZ}5AY<|AcsZyzN8C_VULbF_F9Ll%)mmS#-tn;`w`@&`s zSK)H~m!JG}iDgm1Tp_5*|o=O1x?)V_eb`lSCSODR+ZWr-alt8|26yC?ldwr9XOmTDO1Q3)-x9a z-yStagkM&OTE*Vg-k64_W@iAtsV#VL?CEX)ev~)Y(PB*w<@3*fPToE|94V4cc{r}= z{)B)qc6aY{0d3+_m;p%zpKeX6aWup=d0g1>+$9^|8=kbT*a^d$&8HU z--Yu1e$;yy#{AJt4Q_*t%km$suXse>$>|sUY-J_Qy~YuBaec|SYglh`ByWy`OkW?@ z7P>a>B->$?mL37f-dv$FpNIwiLVBC!dh(ivc=CT2Xus@_TRv+u5w8jk>7q>Q7|$&+ z%-=EuwZ;=uG}+CcU89Tlx!^WQ{uwRumMPePsww0c7 ze}Jhb=huChb)uqv8!@YXYluQFUpy=z4o)=Yt35*fwynKRku#@f?ux{k{&vT;dY!{g zuq6(fZb(O<*?~;OW{_?lX&*jJDhaYP7hb)>Xr%Iw565IsZD&26Hg<~fISkWTg&3lU zY)PRG{8C*-AXSmRfx*oA&2lXsDNSy?LiaeA6m$dWsSX&NUHVvo)`-(`!*_gQKA zMZSIe_LM{fCI0U$$FTK^c+g-<@#dQC$Bj1e;j*?knP&z>rAORt1(4$fd1f-}Ve*`7@qB&vqQi47YdxmAJ1Fi8sRXfwnt0or z;lL8qeRx-U#uQS@T-ouI&IChPE|RI{x$C&}!Nl*?89p8kq!a=l3(h?it8Wz8d!IeT zz09FIwSC62uxMNHF^94`NtyK*!sP%paeLH@{04iu)h`$`A?!Ufd~kwO+dRZFcJJg6 zGu)@tAwF-RmsZOdp)z$s&`)Z5Y`oQ7UqDWNSeLB2&1)S`ujw|r9HIPh;B{~I z)ZfKcb?}`S&x=nh%Ge#9yd*Z86c>!XXp{8{w`(n(sZB%jf;l@&kb18BmDF^-wFnM_ z+1M8sFIV-&aF}kDN6QeYHS&>^#TT{)uT1gfMrFC3C=XYN5UqCu0!Pt){zMY%&|=xw zVL|mn%)RbC?teh(pIg9GpL%-`I}TeDjJ{J{cL1^sjrYdSPKfXLvEojfc27hkr!J;W z+}_ZzN}k}Vd@LdMi_f$rtQTOg|8Xbxp+L)56wV9Nte7T3?cf*C2c@BOCb55`#{2P1 zh7Wc~t+)_eJ$Z@^P)1l;)lR)zz`qMM#nhQW?erskzR_lNa!10Cx?y5mNP`RP;O?~G zHm~OqOc!5+mo4@l5>Np!30vv}dA{=esp{(8%PglXd+&WWkksO!%^VmD`5zg|IzH^h zCxkut)%u_bPu*0ua*Dg}&{S)G@CKWu4PFxnOmJ6cU;6G<$1PYqaQpC*`pa{v?@Zh4 zE_Aq3{D@?#wrOPGc`g)le!e6osX~Icf%C`b=biKO97|tc1pLE&7nuG~S}Llr;bDp1 z-rg%7TJSe7@D05Bf|pQmA}noDb3_Jv;Ic1;>FO}5T_Cr0r9f$t%;55cndW7b|mJc{x9ZMI$Buh|m5Nz~^S2YG4!eQe+3A=z3>tLuZZc)0;Bk%S41evJscVCl}irmUH0}ki$f1|U`Pk!)DoZ62z?0=R3QX;0EBQ`D=ivR}n$Gc*ZJhAM@>ivf z6{SHc+iYe5OsV*XF>YZc9wp*2YsT=vio3bXSad$R+n}tR#R5PE&%DhOQsm_10JS&4 z>yh_lD$>N#^up6brZI8QaIR{F+QZXR@kT~N+7%SsmvBB*42&SK4W&#P%fHf|=ixrj zcQarM9Q75@&EcF*n=^F|bPO7t-fTus`zX_E%^4TXhpcoQb__Pw2?bUWB4uULdFG?} zE=LjoT18AA8Nr$lELPe)V2$*kv6IRa+eFE=}$iJiwDAedpU}Wj*wr1 zk$r|Jy!Qo@oI*6uKDzfBzIS3+G5^?J9{O3Il41S&h@>!7-ZLNd<8WDBX?h&P$avUU z(@bKnWRuG?Surm(Vo(>)xZ#RuMgByB8UUTzTw>j6=HIkL-I1IA2wxGF6ZJ7cP8`ggNp zoc;l{6k^wc=t!|>Tu?D?^KdbKtC4U6xQK-R(Tn0?a$C;Ljp{#I0HsR)pIRtJqc_AV z4U?V-x4}PU@C9>h1Kh&q4)f**ubA>^jy@7}s7+Iq@O5PIP_~5`(>-{yNZ-R;GC|xV zjfk$x=QcjEhiZ@gm@N~eeIdc&XksPY98k#BKx%8Wl-%-=)X+9ltnTlNvYrX7QpI-k z1ekZo7JSmV#68VuD*01)ib$6&CY#@H{BT}Z{Ak9hM`?C*wAcoz%&Oc{L!k!?jqyQi z+i2(4IR2cCdYr$OMHJ2;Be z=ktBxs%eOm!XBtQ_qJqF&Z%*;F|g2_GatLjq~5WWlK2C?Jqs$*A-TxMk|&Bi>4qGH zt*Zt2glwKpfNasrEN@Scv8!Nxa}jAm64g|a(m!PjxRdF9W$G-k zA(+{pavCdVD?*^w*Nf3nT2V8<;PZ>oN7;EB@lfe{Kw2*$lsk=tgEm1#wwnBhRG?=~ zd{wstJpY!hKE(+s@g4lIjj)>g9|9&POIXI)`>Af28^vA=4VJ>$Z1$9bPQdf$^lEd9 zhYLMF!O!I=oaB}MlLc)CD#udJ5cVOv3oe$-X#n1Vjl)lg93GX%VSL@0kgT2YtlkIY z6B$cdD2$M%q;u{#3YgF(UoMX0giJ((6iZeu_YSq;1NLecpS3a1JikLk?AaY&IGs-& zKjKqRs;|Ozz#%&3zvJ=Fc;)U7kFDJwfU(P*P1N+*+RT6=w9%VIq?l4GuL5uq6L9UXKL zp*BuUO*gxmOQ(e)nrVpTqy$9`oqO`7xANd)EV?F$sIjD>(-lJ3b%`uoKS$#3v#<#2UM;ffLq-~6 z(X$iA3j$eFkIY4fd}V9hN8+);L0q8%l~ZQYXa~yjt`G7*U}Ph%@`rFNks#=DXXugF z0;4^#6%d2!Y7F%%t!-cfE>B;+=@(>n!Awk7UVf0qltZG49vu%)rlrT(YL2V6%!0P8 zZrDj_wSkxV21`by`75gP-lNu>Ow}f8ZVqTs7Zl3#!KdSUrLk$ob5xB{XqgDTS!sKN z>wg3`Y!_+8!cW{gWBdFPm7WSG+aq?u{+Rs6OG$gw zlmU)-o*TYUCi^JvNIXxaYAGb|62UwzsP>YH9H&tctf4)9*5Z+tR<^bW+`TcC0=ZYL zs4k5N9){)l--;TuMoSJ6Hdf&UMdVFLzT4?oz=QAt0@22QBvt_L!)20X&Sls3y}}nYltR#Z7S7-Q4fM9*|G^FE69&=bQvN` z6-GUpUdoEX?OXAmeodpc*3)AR4r&0kgqF|++cduz+iZkE=aoJBE;m+3BAL8q2A{NM zeKAwgcxJJmBa47>E(~ggKI6aNVg{f$d`a6syFdVgVbLlz!0s?=3?ct$o$=6Y$<9zL zV7nhqE|aTgB$1Na4)-bIG(hwuFk`*RXES!8Z=>lx@-o9(QI~W z507co=4o0L)ZGHWU-jerHftBub~Vch`|AaJpoB?arc3&;1?|&Ed{d_Zl!8}(;i=c7E7h>HXD?fIt;94Xbd(^=Bb}po7!vk3f5%qc;m|Nb)a_3%$Zs z0WiEKO2@XwnMh?0ytr`a?dwZpHvXQ>9`goxGJOOM`<&^t_YTMsDgFBNEgaB&tJC5X z&3iBJ%LGw?A|@;a*XGR`SB}PnCLD%ewAeo}khFLuU{ToFlet2pMd$SrQhwi6jUnfA z8m(JHzuR_qLo2beoI`R(%9TL;t?+y!Z3KN~r~Llz{@rfc!S+-^YvHCitQA6PC&p&j znF+0>-t*I~l$NoPjZmG``s1aADDq-VOzIrMf$jvZv@v?6)V$H3+3Ql)$~+%u|3iW? z<)!h|A5BFTeBMxtWZM+rU;+sI@*V8VcX&-gLh|tTd~V7F6Hj@=&&%|*6Or1T)w6g7 zJqOQ^v)qHw*D)Cejz~B`{Er=p!cGx{Fi+>d{R~ZKR&Gw>!5oe}#(}oSjEw{9cTu|H zTlKWXu=i)Y6~w2E!3wD5-_t?YfcC9bvk!OX@3|EspzE5*PX-dl_AN8^tUb@P2~HMh zrz_27qVWwcE5rD}Ji6oc7!ObMB~P!fcBtC8XRDE}6qEQlSEyHcU|wQ_-jY4^M_^zX z*or>+_#-T=v2E7G(y4F&Rh8(DU#*7lwCLry!Z z#Q!EaE5Wm@W~pe42qE2PD%EtM`FUB~os+(sk%7Bhh=Kgu7311&bXaUtL4U#jQJ!}} zr?@bBfvO_Fo9?Vflwxurv7@ifbwf*OESOxV5 zpZ-?>QWPrv`1s+ph6FM7iF!{Z1cPoSq^#h`!T6B{S=tut>F>T@$j)7%)ks6H-8Al0 z4i;3t9e>jP%W07ijb7&}cH(B>s!j%_E5|yJbEQTeKW$ge=Q&&adWa5KgOB|)xpnUF z?nTAFuQUERN@Dlot^)XS`hjv%-_YZkcl>lFM^LvIaB@a!_r@Qc?^nI6;R&e4V3;`k z_Dn7XW79UiGu)1!wKZDpyZ(4sk5zHkUEkJ?0P4DK{fsYj5gZKk8NtaarxDTgxcP!Y zO6cHeNFYq%Y`UEnBy&uy`_$kmq-_&%XL37W@S`Tvz%wff(+#tx(Qg{H)A%C+W$a@C$nua$ghb zrq6}{Tw+AsYXgWa>x;Wl9sB!DTky)DIo|1Q5kOV>z|v z2J9Tr17<^os_M^d>zL*VYw({2p+a}nTp7=w#Kztw^lv<=_TgI;4BJv^kW7!lY<~NF6<9QrrZL!>%m5rKY^&{qJU=dS&62 z`;RocIXr_S6uGJ(!~cr@vM=r*(%rp0w)XadQ`Ff9v)D+;IcOq_Wf}8Yhq}^yELD1< zx4|AkF1LmUIgX{qJ9_+8i$#&3tw1vP6o=lgw%NkL4Gl+!jx$$(?sU=4Ut;Y9EKTov zOU7tOqR_&9Efquq>Y|Z~EkjkNJ{3SFFRgqjX5^$%_>h41o)N!-QJk6~tW(L;$1EpQ zCD%K@mNd@)g_?<-6}mC~;U*v4+9(=|6(ECYU}6>_q(kS3E0@l}fW>Z>n$e~0V*+j< zGS@{gLb`CkaUrWPnh9;9l($zGl}1~-!Is=QXW zjCM;DBhNdGdd`xq@q&-g&_(j^YoGRRnpJaPbTOvP$zW$Py7O0iF+8ieM+7;m(b1f; zJ?P4V+{rJv)ev8QB*Hjwf@u5ooKz z$T+RY{pT+YEU>!BTX$71-Zu9!&|?1;{n2^4EDm*6Vn3x!IuP@h|NIsFix$V@@lQF* zzmeXB)e7o7s?Qr;bETAWn}Wc@HF&~ZX0w!>+V=$6yyLs^e*;9z8n-JfwtohF4@q5W zQ*57-$48oa(7CW84YN8w2es=(Q)$bHL5LVv>Xc7EuIjE$EM@cVacF~uWn&u{#>(Q} zV9T)m&ddT0?iik@|CuNEK$hIv#X+g`{MgZJ(NNPMD^SuodGf`K?e$buoai^IuL&}L zMQbh#gTKdCJussqGE>e&>cEu(NH4D#35k=Yv8B|=+knjPJ0h+`5O2-a9w{FrcyV$8^P_@?ZAvt)k|%+>zgHQPwD*&g=v@b>vE_1p(~s ze!G?hF%&mu$EOyA1Q{V?F#^C0CmQyziIGlW9R-~YKQ^km_T(ae>cm9sOm4)d)*OkJ zv@Y|t9}?C&DX9BKSoEd;vB(a}F?Y=ROws(F;GYQ-Mf~qXLehBPYH@V(^Z%Gcuq@cq zv+hXvQ~HU4u5z-KQJd9BU8Xt)T<8*Z0#>-klTU;q7Yu`bV>H(F)Ll-k(aeP67SKIZ zDdLvT+e+-{(bksgh2w8--SXi+Jqv#c@fIuUy=$4r?>qgjTV|3Qnw<^F^vkP-2=D1o zV`BhT{3qredHIYF$oGr_g39se0n-Qbx(s9xD7(c_Inq>O0quHP!ZcwGn>FSudI}SL zz$GpFcvMc8E>SegxEiWRf6m+mq~~a=M%=hH`b1apN=vn7OTpUFG*@QBUA|y7SSl^R zMwg~m^8LT+w~U{{RhJ%E?4NCDGI2%tv8^j@BDdzexhevU^e)F#?8rXv3dTb7)^wYR zFY%D5Hx2YI;Y6y@e)8HD=ae>%n!v03bNI=fg1w~vGKD7di^`XuY3TIoT1>t6#JU8^ zu^kK?akl`h`hC}o0X4W}Z=*OTTb70V{ zhQkF`pu1gBr6_+@2d_>H4WQ#14R4mlIbomk4Vj#!lw!IpxI1})q_#Q~?o~$ zNSycE@~b7I&%m7AHr?qaqUQv(zHL3zn6agGL~S8S8L3WVJlC&lxHDvqb)yukIbu>k z6FihoNxj9-I0t_wY8j{Zd;`F%G!E6hUbXClu!v5@{~YWu;%C1pOMb_XG3iI3#%%-c zgzBC?Y#pADh>I(&3`4+IoWT9nwItds2vsv3klvtXh^(el^C7@G%~?m>WC*ya#M|rJ6;&e~P`;0a z<_QAEFcYr(n)x;7H0YGmJ>fp*nDF7ij|)B}?THIcaEKM@5)8he4yP`THh|~-3z_j( zDta!U?P}A_<{Zeh(YGr+ z#SyqJQLe=Yswwi-xwn%|L`$2KNB3j$f1RYqRX<_xlHUhu`Pl^mXPj2e2e8mM-%W>xSQ+U0(m>dhcD z_S|-IBBDgAU*6pW5tkUhwt4-{@>Go}m*xuKEGZl|!~`d3QF&_E;XZ%*gB_R}e)YhhBWz#zlv zp_Y8?bxELp1578F8zb5PmrBPZJwK<;&ISs*-eJ(p1=7b9XmYk=s?{t^ZHxI@oP>Z| z4HS=5ow3Pv!@l#+zvUFF%}ug-Oq=`2Wg-3T?sgsn^q*-bjzPHQopqODA#JKL&Rw0m zRMhwQID?o_-Oyw&5)$NWX#7hy;b!+}PmxIJl@==L zx6O<#-gja$GP1dwskgdi6@X83YSYtCY0V@?vRxKwUM)#>oxfw4S!spVX*0^{tcd?S znL@#O`{+3Y6OzpC({%Dv{Id^@Kv;0rG3$$+J%@dU#027$7`(LoC`Q-RGGOZapVC-j{f7^8A@A*mIEu6aPJL^M+u2 z*2N@T6_5u(MjoFjz#E);@Ni=s4-nuxx%Z&4sxn zb)k(I-B{3cr!6mu8SEI$`e^xz6c`Kk!pcAg4DPt`6Uwd$RubN`V$ zAC?v{(u*@3kZ`wpkPg`o#6_W@Tf^E+AWkdOcyO$o{NKsFnAilA{NKyHToc76(}G9y z7OYd-g`=gVmCF&xT3r4I^(j(ev}Oaf=!JxYz>B%6>Q%cjXr6n$x z`onNPqazwdJRyt;7uOe-6j>p-1OHu8gw(ow0hGI_!iZ=`&vY#MDZ+}Oo1mr5Hz z&ZX)JlS}CUqKn(_>Zhm#%b%ip64ylqF`#^W#uDO_eiE493^CEcg z=8hurqpD>A=Qorp)&}>$Vi!4&;q8_e>p?bL&Xn)if(71bR`X?>KW4C{6^F<(R(Rm0 zwGi>-;$`U_fx!Nz9(kR)A9rs;$&-J)sgcIsl_V^#%4{05Kq<4w}(Q? zZ=5z)u4w^pT+)@uOr`w~NRbv!=h{b@%mYhnX@d=4gN*uU9 z4!He`yN5?-qtD5Dd&*!mo}eJ>9-Xo^``%(GmPYbpW;C9_z$v@-)k{w2Gh*bn6&}~y zCNvgyatsN_w^{`ZuSiAXbE6@w0S!WStEfTIg1SL8bmQ3dhcE3*vQg~Jigb0kUyXWx z=zb1>rq#`a)Px7ekIV-6*RwI2*cQ<%vu?C9?BSS-Btz6DFeitns zGvgqNii#@K=yj@N4S_o-mg#rzDY%LCd9_d>xF{nx^RatXb;Eb0IT4NCx$Pt zzjKji@@DjytG}CAY+tfuMp|utkR?qAV$do5 zM+*?Kj-$t1Q}Fi*r;+@Bk56;s?Yfve{wrh*!@f?QECrK}f8XlwkM|(5f7O-$^S3BR z0^7fYt^fRU`QIP9?K1m1AVDN;qqBBt#SkbGq%YS-5U9K$8nn{vj`w@y#vwrgnmnG%B z4A3XGp;y(|W0XA2Zuk_=E}%#e45)xnY7RnIv*L|VJsiC!zGntGeC(@QmpPk>a~i-O zE>YS!P>lXnyA2&*V_XEBm&^4i$tQ-&GY z-85p`;>9naER@yWJquo6?5Vchwu2npxnfAM(YDkJLvrS$-$Wrp#{TNkDThZoo%RxQRgO}#S>SUxG)-=D{Ez%>QC zAszg(yJ_GI*Y@^ySa|rzvBKX$3(U;Qa&&g?9~z>p5rOE_%}*Sgwgx$1J!6Uac%h(s z-Q=4RnfG!y4~jvI_{HSAbPHMnkH~nxXgGSBVQV#=1&)>7Iy0p5Ll}p3%5`{&Q@~F3 zZ1%-G^sye!b<$_CQ!aBZA+S0J`K<;_9!p>Koi|&Yd;Y}qNuR50fEv0(E)Gg7<0{a^ znonLfGhXtoVkAGeH@6rg1U5SD4+lwUfbt1Q&T*<4DN7d?$&i*s``?ZzkWdhSt-w1buP6U*hZ{uwC(qSbW6%xU}b7`0>t`JIp@v(BwQF zejE%xd2*@y&KODlG@KOa18eZk?M)4SQ8C=F$n3t29=zd*uew4Y(mF*vBH8Lc@PS#- zhYT{XLgy0-ig?YUa+A$+2Qs*)RKK>-W|t2bz1#(l;tTp_HkeO=e71-4c>>K;-k&$2 zd0EVUvG`_w77nUrWxzsN?lysT%NRG*X)r1cD9@4kYGJ911*=c#0Pe!|^hwRH5ySSE zyQjLE@fmhMMt64w-MlxO2;NkYwFK2+U?-FGd*q&UUn!pnRF>3gZhvg9B$TF-88vMm z4AbvT{QCK_Sgo;y&4_8rLcu+P@n3oD=z{O4Q;aE&4$kC9<=KldYgsWs>Ep+aP4!9v z*GQFM?%&l5xJ_21MA_%ke|}J*Is05*K4AnOK^2G46`qBU+z>vJ!jjq-ENJiOHGtdJ z$mRZQ=e}ROXVx_XNUve}{3?UWQPP2n8_f0{cpQGAWSFcDoH0Snc|ZCVWmL`aodaEn>88*rL(MKdYf4k(NKiZqt4hhJ87ZCtd^Hy{j24@jO~IUv zpFk=~W&?$KRR8(ru)y_)AECbsbIBEW;+S83f0@6OCyvYyFnSr`bd>oVZQ6C1pa?S_NcmGQWapdfQS;06ZkpCNeNgpuD;ye~~DS+jxLRau-X!?^ghFDSe z_!%^yRo#iKlcr*XgOK!*3|9V#8htku+Q9qs;2~ah663p@lCUO_Z;xQ;^OtPIx2Cuv zIo${9Nv$W=`uQD`07$QQ_?FGhp|lK`qc(F%R1;hAYKvuoHX>d=-`)8b5C)q(>D>#Q z-AdZlL3bQGrLcvw4~@Axu%Bh;>zX=d$@MeOc<(IvODHMO^_4Mq{QBfrk2r}$YM`4oL)mzTvK0} zom=c?G7S12_BZ1xe6;W1t^%q~-0XV}j2P?CzS})LDMLGpX2Xl`uZGko$2ON;)@Y>9 zx8~{0yX5ANbfpXi{CqyFeWP-d65L%Ba)Gna4ZY8ZGTJIjYZ<66QqK~KTAEHm%F5E4 zV8;U634GO@1BY*E3E*t`wyYyqw9tV}9H~Nr4a;nxt_gOc$5e+lm`})sw#J)4=d=e| zuq9id197c8OVjJwDAH`#3F-y^9Oc6iP6rYZh%&5A`a_k^5sZ4B-MMV92~7M- z&mMz`m}^*m4)1;r@ko<8psKA|&rGMzcytA!8iAXU=pveJ{~#^IYa}yk_x%9Es9p|- zp$0tsQjHFFQB0?6Hh<{oNt$xJnGiv?Tb9lPO;BY6^r+2S50B-szh#s{MJjcjeUqVi5Vi!N1iJ5en;PT;1SkwROwDbJ$ zt==A~VCJDWhf^BO9ORNa6XYE7+L8SKu=kchb#+^pZ~_4m++7j~5L^zf3GVLhesFgQ z7A&~C1$TE39^Ccd?k;^u^4#~mU46T&`{!5RABtU2oMNrL*PcV>n60El!`pHuwQWqk5rfg4LkFNzTy@ zYV#)LB4Qf_#G=6_6&*_F2Eq8?rBz}|#T<%H6ULqxPlkYME|_t{4Air0RhkD-VNW-5 zEFTF{Y;A=bPb8*@i}EF(RnA=Z=-=drULyg@wB;#d?Xyi7SQo_|xAN74O={?F8=28! zEL&6wx!&Z5`8Z?!l-{l7U0ZB~@>fJ;n@g@=FMz>WYQ|gO&a>engIen1{2E%JD;4cX z9W?Nvbh6804kS>uMOsxB8G}c+ID=tg!IUu-mEz(8|B;l;CyXWu{~08+uF=kZt}7Br zM|69(neTlFf`FwyFAxzIA1r_XFCqEAmQY?a6YPO`xmQ_vO%2@J*ZOHpxrS5doGf*$ z*@stF5*y^FrMr5fjYV9WC7t4;b)nrKTI{r}-m|Ab`CMYVk^~KNf(IReR-}Kyy73NR zw)PbKYFlYHtVbExWs`pJD3MSyJ_1EJ?cqpiIX^VgkeudA+e}r!8^ThguYe7VTV4^b ztLm&jQU<8^8ObwSplgy7egpx}VV%z!cclT3T|Qr9QhT55X6hX;VdEVUJNh2_&69KC zVW|}`zsCu=ZW$50JMB;0UY}!VHZy(TA^UDKgIo1!17d8Z)ONEIx3P)R&RJij7rhGW zxK#{xnxJE^E4~2>OWb}38iIxvd0RVh&yfsMKH}YG_ho1G0iFnsFdTZ}gTl^od@rWg z$$3YyISRK~e?`f`I8$!JwRmo*R#sWEd|?XRma()o8K5n?GckI*{Nl1t924|X^9n@$ z9xUx_o*;%TnaUAcAfKNkf#1Ra53VOF-_c;QGg>Y%Hex7$kBZ_mGrP+k!!+aBnTvgB zlQ8N$O3v9OvbH_Kj$5)C5(a)VSp2m+T46c#Hty*X`IUaBwmTj;Ej{>guHKQ}P_Y2V zA&(cgO;HI*XjAKTH&FG!(JFrFV zQ0IX4-e!Nb3RG1bU#8&GN;ghY_(610yGinAekrR5EAdgpQgcvkCaM-nX1+b}0N;=Vzn4qCwJ~ zjV7jCsS2NQ<7YJT>KY^dEp7e#|-QjKoDf-Gn>H1Aagn)(ydLC@s*q%J6 z$q>Jf1eb7Dn2h^Yj*3lVkBdr*ejt@Z5`r|PpvcL|i;n!}?y1en!}b%2gsglwicn^C zu^H=i<5Xz6=T{X?4ksiDL%niR0$1jd*0D7K5Sk(aug98g2H)ICF`76i@vWf>Lb(`54Rlt2_un3L^kj z)r+Aco64A)J~hOVD?KeC8*W#2{NKoSFXQPO6Ls>|o0p%jmK?$H z?biFR#EnbWXZ`S_B!y^nsi4O*s;Q((!O1!N5J2U_^?PW<#KYD`V;;bCI`P1vzDLsw-%v`oQ-iM zr;58{?T}SBvDG%|{54%(jLnnch-Db;zk4X>YX&P7M{}9e&vqAE@R7ncj9ks9xmAQY z#iJFuqB{<_>D%^qxZriEImU%;-`Cbc1Oqx3?lyxnmp(m=7o?DN}V0f4O4`EQlp?tr8=?V`G3AO@G7AYUc z_PjKDzVtR0d8~xBjW=Yy_lo_@Gq6v;Z2IpgX**uz$qv2b{!uhrk$i5f{o4ef=~tx# zk%m-BzTFq7-g|W%Z2E75Ei7maZH$e)y<@eSue!da=(RrFf$_LiY9C1;F$sywam%&D z5gHCoaCG#8RyQYn35~kd~9{su!R(t#fay(2ATOY^7lcL+!-;8jbE=zXh9v5uh z5U!-nB!AnAv`6$h3Nw%2rQTJBqcc{==Q3l|IV9DS8p=0zK*9&&f6_9>Ua(DSdb&nw zs4>R}Qr641v-93+ep}Zx#`nsBzz%-&U`dx=?wwM;&I+3m30Cjoxj?WGm|Ayi*h%>d z5 zB~5bVt_V~Syjn3L(%nh1DFw4(;iN+%h&cR%gbNfGo0eI6dJWC@^2MG962}-blGHyE z1}cJqw%=jv zZDHK#O&IK{-Jb4_8V84R4VJELQjC)Y3Dqf|dI=Lr56qy{+Cmu@UA_Oc?*bYK`}k0q zG=UIryLSZ)kD%%uC1TC)?>6BmM%+Fs@q@2X?a2ssbJ>dewhMEc_bjK7{xDLL;I`OA z*gLvX-MPdC!agORKJ9uY*tn{)Rk4D5#E=R!rI77-J}xl&1Gg+p-f;W@5$chZiEYk* zK*Wg*?Vg143#r>imCu^Py-(7;ud}rjPS>d1yG0`f?lA^evKubrB5R8&mXd_!Px-un z<)`nSzKTU=nFjU-Xwu_!}*~+h!j|^Kz#d!w`r)F+e z&&x~?b^SXR6V1}YLHxX{Qu5u-p8ZGHWvH9)+$OmJA>L`O$pU z@~d=jt#Ha-Npg2SgEMy?34ylEteTfkpIc#1`1CCWPp=4mm^yn~MMN?=)^%!tB)6|( zU65VB?HH4}EBv4)v^_r%B`!4|Q=eUv&BYfSeiegGbO!SdMgGTK#I)001ihK)FW;K5 zt>AEra3TF*mMrByz?`BLf#}OhfKM0>moz2_PF#Cn zu$;t*!0uG5E`%SFm^j?dO%=+egi# zZjRM0BYvas_To>3f?9gl!!4rpa7Dhd~eeYt;TiQk{0nO1KUtU-losau1IsRTwjaVy#&p?jB ztIY-3I;5;4a}R`g2+n6q3DrluHC9VoGZ%3^V<*rc!TbzPcXG#2YNaPGZ5mfJ!x`M? zf2w+hz7)AlcLrWJUqE7FJ^DxrS72@#uT~{|^B?{dZ2!z=B{uz9$fyaaImhkvYND>l z^jw#q_;q=nRvA)-7OU@=`UqMXq`l}O;>zIk_vE=5rph0DI(@_k$t(ef%0zmTJ=XSH zDoP)jGVCTG65JdzX6~^P*$v2Gta5!BQtLy!Y%j!Ir<2;pafFK&G=jujU7HfgeZDBN zab&~DJ7VOSUsIMjRkTf7durXo#IKLjQ=YBKl)rMM1jL9z>3qCu=W0#40?a%`!|6f> z*vrYwiHJ`4jeS-VgQY0g9( z-)tU=kSuA3UQ~4V_7IfiRRy_YO@A0NcyH$UigZ!4T-Jr*;(M@Ld7XlpweZ3IFsR{} ztN+XVQ7gJ5QTOrj2nD!@>=fD=5G9lVT4;dFjd&i&^d;C;x;(zNSDQ)sS(`gte+vYN zVOX~pl(RZKv!-V=0^q04d>Pp8OuSH-)TF!>Q4^?LeU} z-azEN`>-)sBKaCE@42`?Ow4UUftIWWDYPC@W^^?Uxp*hN?2Q|&J_gNMgWIGu80>;A zf#t?*wh-`uoN5yo>uE^^FtPxh4(=5%r~mA2n7S#_#=*B(G^ywe*X@AYIY?r-mROsN znoI7LwKs?10v>*v@*rBCU^xZyFEpFwyuhe2kbq2;(Xh#Mv1)CBiE7<8f%-gk@W%S6 zAES`eK3#>W0XfeJ)z^|-*rEs0f+ai54;9kA3E&C~vOvA_9aRlMPoe$h{rCHgN!b4- z7Z2*EIQ(C5@hbw@M^7U$h!~$NvU@qaOmPvG+H=A4i~c7rek*vNjinQ>&r)5~<7wnM zV+d~qx#uE@g-O+xu5aHeDRPz{u%p!l3FE+H0T-Wrc%#X+AGM$5Wh9Xdi(WGrm>Ww% zIMsA^NOUdH{C#T|)Lmj4VGi)50pM5fL zk7kQXtS^cMS90@RVEWd;Ejd)zy%N6|s2E~+qXUv|dVTf6gwNzbkz|7fd(Z7tA<`B< zw*{N5YA25HCi-OA6t=wJu1?yZ=Gv%uX=7%Gyb36uPdTJKEV2;ISr^Y1&DG^Mg&aAO378IS&<#o9moec`Z=_2(@N>~v?AuiQLj&pBw z7jsyy>h_V>{Wv{h41Cnw+EB>{<~}`Ok3VDdQoNM0mj=W;Hnt{x;RK1#p3TFPPc8%2 z@jDxg7fI|XJ*|SWE6ZKoge@j>eTn4=sW!5o&(gC^mX4)yOE~(&p_Nk7=KSMI?pJNi zxKrVbq}#Fe%FvFNBl|n-POi&Io=zn0?5)I&hefXtt~%if)>a%d&hMfgPVQ;uo3soC z)3@vo4%#bP{3vwyoEZ3-27Tul7cAfx$}V#^9uMJxbAGi-NBD^{?*=uh`8Noc2qA`lQ@mjmKclhTfuV7f>w7VP*yO9-b!vi-SNDk z4I4~p>Lqaa0N%W{$DwHpu z$uDh&UM)~S%eSO;csh|rvaZ?{UENl(`T3n16OF~XF8_Zkw8>gW1+_=VOA~-0a~9LV zHtB5PGY z!2>P&_!47zi504k=^Lw}+=i5Qy05W`zS`UcP;Cx287w1HhQ#GJgGl+hq5&)h1@c&) z->TxC6o%aKg8!%hyj_XOWMtHa|0MzB+3X!buIpK$HlB*_H6*OfdVVm!!|bb_f*8?i z{@GI%Vqy*>q-ZlQxgxod>P)DyFf7w_X@6W5V-77CZm2~Io!ftYCiaK__YznlVK{>5 z(2Po0a(SD)UP<^xu*FmzN4DdeT6DPe+PWYy%SEr|yMP6+O7|nRaAUWglWczMFl4C8RkKrR{P<1$gKPG!gklL$`@rLk6z@Q4{W*1kV@hVp{)wpw4Q5)Su*IxX%>4a3 z5|-|PmOAA1)T>?z>3eCJDdXv$`ys~D*t{wCky=;gK$lpDm#X$S3X6dKqBoSuRg5w+ z#1Ff?h+5ur|638nzY1jShoLbO>M=4dSM%aR3UU1?N#%kNGUv}op7!`1bdX}Y(Ad>r zCc3xxE*Qow7aA`N1;~dgWFc!%0AQ9CZ*)NUmk0o!-R%fYJBS^?2VR&;2`c5)mcdEo z7OuU~u_Yyd3O|NIy}3zu^t8ttOHHh~vSG@l>nXN%TU_jIuNu7+m%}WPuFHye-js-q z2%KJ z3XLi>1kZ;AB#pidWo!l~;Lrw*A4NJSS%=WpdQc0NnMmj~UiA*Z>hZV>VX~WARBs$S8Mt;0N-S?0cC`0WWv${Mr?tyy_O(#A8{=j z6uHAO^WI7MGx#~+VFXKN?~IMNn-Raf=&3&^FRD^_VErNdI=sOg!8w&D5F8v|1{p?{ z131{OxuCh-kyXs>P=XW=c!>bF=iJAgY0)Kt~ z%CZ|Q5c)+tOUb8qdfp&4js=%G3e}}hM2=X^qI`-=l{gT*?iiB!Q0KYZD81Ded7ocf z?OmqzWX`6bx&J4HK(qrZVlACP+lUeVN@2-gaAE--)$(z-d*| zuNV5D&{ekNBjd=Bxb@U?dCp-FirnoYC&^aSmez_e*KRq7Q&bxB z>~Dz9$Ztaxo4zA`8o)f-<=qOTZB;w8ht*8z;)lwWHzP-_e|>ZvD>uJ)7(SL^^QUK zQ}SXoUguWy5IwllkJ*cd0}bQzD2BDK5W2tu%`k=H2-bNOIa_q%is;%~&wr6X`AU zzOyUFYr_YIlS8DoGonvpT7@(WahfgLaA~SX_V*-|n7HRbf(_2e>~5)m#ut5q|11+0fC)zp2b?$PGht^s$~ z;LL1E0z{r+Y)r1?kq9ifap4NPBZ(snA}JYC=D!L;H+F#hu#59nCN&=I>fQ)X{imT* zg4#HY)5qH^wbzZ@ldFnlbmmH)62X0b0$`(u3?_-m9P|+)HeVNUI&vB1fEy7lnX|ni zwcT9!_5_-p{Ra}B-L6eG0q0*c$gJLk*>%MDZTw>&|F z>55%WMkuiJZ0pK(EKitY5qt7UpQ_?UcpwwG*WY;H-IP!EK#`Z_O%`i=|J?4?S#NHB zi1iYX1dRbqu`d`f1~}wDwn4`aF#iBm%v>D7x+Nju3`l#Ztv0?V2oVFZH=83{)*+VL zZ@nJk*^>ruEr~~{TBj2HMwNqcLuyn+=VsC`^C{W@R%_=;Xl~`}A>&>bW1b^Xb~ul6BhS9pFvQY>8IayKUxanX}DRCUyjAm zUUg&?b{&Mc-PZp&Yw%b~aE@{SV6IM_*r~ZCW&TkUu$jss)6kAGtqVk&eya(GAsTPM z=Oo#u7c~K%oRd%+U3YJb$)E^+oc-> z0CPPF?YS9RYZI^k$~Y9UeWrc^cz7D1(^!^M`5hmaNUQ_<5V4SukS6yQ!{ny+FR|gF z!KTF@%4N$`A^PCvoXIk6Ugi5%Jg?l}sj$oF|B&YY*G4`sp7_JCTrjn}hH=jE;x8|Y z`p1=b6QAf(2ZB3p4u5gvIWt)8hMIwY;pGDS0WNu1G%k@GauaU z-;MYAkN%2WmP!MR6Rg|Io7OTDVK~7WeRpjug!&t_2 z{rZY4b=$JLBj%v>wNsw`kI%Yz%+t5x6DB**w7J}OXAOrkat~g~4c4AGhXh(%%z7N* zVJE#63rcd&Q;b$@{OA+r^S=!GTky-;OojB2hBMp{knksO%V{*iYe7z@#p0zQPl*gb zN|{MoqBx~+XNBW|I_~*tdiNI2GXUCjF z0|VHfx2^S&L^y-wVFA%z>-gu-6)O}keO5mO-tmfaeAK`;!^1id4G-*wN zw-}GDT$#%kEGpNKy5zPHeSQoZ~iI>=Igkv3Bu&i7Elk zXxHonb)jA4=^>Ay`9oEBOnWO0%qei}tM8nx-ygMUl~YOD)ZZ^SKN9P3|F5Pb9;SqR zyUJsX*(|)1{~CTF_IuGeF*rWJ_^*ZZr#a>n4wL>z&Ar&ZstkbtfP=x1_q7NICf`@Y z)eraa#jBRlk)h^F@HGR8FP^)fy5u2#WyYa*zrgju;HZlI!G~8{o?j$z?olKu<8!`O z!7UF91F9>cKp!%5AakC3&T@4X2pNN=a)B~)wQtaGRx_OhodH|mHl z5@*xT5Gjkf)d8pH92!qHI4~2o6XA=ZP1R{15Lzg9bRzt+0fO%8^dwBF_xtzA_3yuZ zr2)I`&N>J4SvyXJ)~}?qG%us-Ip+2Bx5W~Tw97ZeICO>@hR!f&r&FX9w!SAafm1_# z7ur`uMj4e-_4^oOL!W5tm}O zTLbZ;d6GMxu;u$PNKWrrD@VD!*Z9rlevQK~jQfP{Zugz~^V)V!UXHD7n%Q$;a9rdF zeG!k@Bc42*BIG?}Cr)GL61~S$M~ul3oaiJYWclrR9|8LY(v%>vDNVS*I*axIA(A_v72g)cnL7XsO?Zk*?>zo}@hT zj&=A#d8yHH%OsBhJ_efj{~iNYxFE=Ie6EmOFDS7@$UCYO#0j}9U*4p?dzBm6icsIG zOq88h7x8l~I<)Gec?oH~(e6=xtcJdI9?P{>8iM_zOyK zY;LE-SfjLAB?Q=tJ*KQ4tdUOZF4jO+{=?~smQlG<9CY?Lmj>(@ve7{*-RjQcZ2t!o zhluWaxHnFsdXC#4EWQo8zQMT60~!iIQJG0{boz&21<(G%b0WpIeC|JMFlT>izt~`S zvByD4BR$Dxw4n~{TJ*gh^4Q_1XK-SrBiWF`4T!;esAWp{)bU9rCku%PmgI>y;lmD_@7!-7T=N$QFMRn6groX7PI90Z#$H}y%LK7T>!Hwac)LQsc;GWrdK2_p3G z*^;6b^jme{M>%Hb+`6+acQIvr_@=jX)_wzFmX$A8fm@zIaW1h10%U>oLxT!@!ag2{ zTayxVLv?@%$HyL$9!Soj~7evmROTtd?4TMtVyi6nNxl$uc&hm0FEaCdDZ~ zfBFl9t%Ocf&c)aVCAGa8U;U$sVT*xR;(LO3zY%xgMB9u>W4uEFtBXSz)s;LaEAKIu4B>Y7(7>9jo^%>W5-RMGe?zni~ckk|U5t z85I+RiD$tq9rrVnpg~V?!nDJE*X1h%O$&ugd$MbbvCSuz?Nh@41aS2Qw73Gi2ArSi z&+nLXo}-lL6_sLQBqdPlbe zQ>D3n9~*9}SklMs)0g|j-OT?J8*hurw9oek{<;|VP#m`uletz@d_N9&x|VWA#hAB} zxb4;^!yoO<#P%VAKiKZ|_E6vl!B+Q;!T5BD+6cH$`N4V%c? z*;X7^8n8W>iifQsb$;z+bQE(rVST!R6Gdn>k-BM+@S4cW$~NUT7JtOI-4(tCrF)A& z-(}_WnB2s_g~$+YWnE!s#cGui94ld;LjKgML{s0T&CElN*`VpeoGgZoAds>XOMnieP zQRx7Fo{*sg1EAF!QCzg6kwnGghVgn`FBoy@b4Cx;`oq4=60MtK4>H<7@V>w49P4++ zaLi8%w*|ji=)!28R=53v^VDrEsG680O^+VsD6->s_P1gvw?l5{&{Fz`j&rQHHrS~> z9#01@t3|+7T;6{xDk`iD(A21H4Hjz+?Ws!Nlal&RPF@IS(@eVms-n8}N*wyS#40+$ zySlN+K;5*G5HXM5U!OUVuD_IkLj6dkZ)5cTL6;jDRwwie76lbw7^Fq;o+P(>>=6dNpBP>GKc#6qN-~rB_!QWxOHc z(DaKO?c<3>Y;j$Dv)DCXORz=!#!J~6;<6`@-c@VXgdF3s8PwkIrQHsxczqKf(UJ8p zW1-GD9WEP=F!vj{ot>|j-9dDct?8FGHsKmtkw7734ww`nnTi3+CdZ>JcmI2pQ4TL zVepUP$a0qFT+!(nnDqbmi~XPa#XwfkxB7B$g>kf@*|DT?wf+XvvQR7KNMgrZnT00#k_C9aBi`d5LhIAjeKn_imPQLNjz>S!%T^*m3mTb1&hifn z{w@`*h(f60&!1%woDQax*j%Txj>jiV($R9kx8-*9pTY&4@V-dO(E#6KbhNrLm8`MI zO}K(aVmfEc>_o^-LH^ACZTj&k=O8q?yH{J!+)l zR^L^fW3)v?DEzbVO&!5b^KxWl+Y0ehuO)PWXO8|hyT(t7V4WZ%RT*`o{5KVkYFti8 z(w+Lo((_U``?7q!5OvV}iFKRwD6B`;0C&#p#p|)U$C-!R!Az;s`M+&r8dj~oK`^2k zE1dWXu>`wp=lEoF4LrU$1oKt1ze0fVH6I0l8~le(Z``Zb*-7$HXX`fKx6&lZ(5qX@ z_%vkGNy51I?NO9i)1NY(WqB+)dr?6`3fUBl!4eZKZV&lhzkOu#)@?$ybOhb4m&IzGtA79X~*IWkAQ5cIr#weTNZ<$K$@|V%?-mo7S z*qk`Pzj|o~yTu6!=YG?^NEbw*&zmK>8HH}^*wJ)r62PKl%k?qF-ut3WrIjgkfS+uv zpc;Xalh>CFp?iBrPAPzU-~=oJ64k_!wqazBc0a{9$><)=B?YI?ter&+vL!(4e5n|4 z_@Pqxi53y;GNzU4*Sq>uDr|EIm8Y1isW$pOU>V)Mysu*{k+_v60VQeV@zUe12C`sh zTR3a*G`2JnAruh}QWp<+CYaV__C zMtn0wPeBO#43qJ@!E4TyrRRbvZ6g|=s~}%OkeB)u$d6uX#X8sBC4LBx&v5K4#;IAr zcz)e>xF1o8%L(#e0Ow z24HjCVfKARmp*R(5zl+tE3!DqEX+GD%!?Wnaf&+afT}geSRCLA1z=q``Bkf#npm`zQ*N z$+fX47{x!Bci&>sYJJq>w_1$VsedFN+%Da`ft>i$<@IkcHWWHk^-3ty`@&i(U^@j$ zf~P$8@rcGm?SPb!*>++kJ&WW_fsJG3TTG36vt*c8&v;Hipe;imilr&ON(0f#u5bey zc!=v%IH1~rfCr(Vr&Inq2;n|l&W%^MJ78AXDa;>vomb=^1|jDE*usTWQ7 z;F1NjuypF`tdCCX{z_ax?6;`>6qNtVrY@eHke>f)>UthsP7Um{e|jeJ8Zk&UU{nnb zB1KjIi0Ye#Uc!wb4*a5+9hY8Mh%^N&CM#ZpTQjAlT@$M^em7ZK?T8!s=EFO^BGSsC zkCnqi#}NW%i63Il3a&wowwi~Db}QRyc1IfQ*MlDE6AVF>S8+O{!mGhWHnUSii?&_vhRO{$$_WtYSLu#d+yXy4OjlFR9d7Op~sU|V!Fhs;~E1I zJ)~)2fBBgssaV7x{e1BbGsWnBh$T`!YWh}{Qg|@TN~&r{6j8Z?fsnYD+N9{UQuXnt z-JCzT`FRTmrnMeb+$(a*5UNO=T|Z`fATpG;(B+EXk2gQp9Y{0tuJB_urJ$tZuJ0?R z!D6(Wyi4ofO`*1Dm*x=OI9)h#!m%PSILgr3Qz{X;g~d26oR20dH5=PaJ8>{4`$TnR zthzz3F%!71-iSWM`RuKpkIYq)YU99Y(*t%x|Y{H8{x3TvnUkiM~s z*g!MGH$|9H8xoq>5QhD?H5}qf>vGg+c&VkIzF63_M)O--m|8qQ6j)rv^MjdsQ4y0rF$B#x zmgQ8~3l^jklIb!KEKvn8$Vc+JpoTPDV#pCZ1{^<>{q6nHnH$5N$rUYVMg zLY&6&{K6$tnF*%~*DQ-(J*Hcvw)oDj+xH3Je8xZ)n93or;8d<>;I!mf0glCGARwj1 zw@FJI31MDs7J)!!2pcw*!y41cZi0!O?^uldWI$Nm_xY9h`u6VPXs>$ zdEa^Efqi-H9ftfnoSYF(eg13mv%ze5>^`z9hvXA)bynw3wb`TG{osL=qHbHitWI#n z5C|mW$Mg8|+@FHxeH9mwAqX+2vCsO4`#+FNgL}$c*x5HWwy;_{4#&VKtu?|Wo2>GK zDAFfu^O=ZnsG6CnK>f4>$KW=;J$s+M&e$fSb-h!1i%^ zUv;YTtzDl8ZhgVGeS3?#AakKt;txW_x-R)e?$a4edyJ9^d2Y#5R6H32siMT!Q^A!G zy5cjZt+s?E1MI7~OetS6LxS+tk?>ymM}_L!;mlT&ZE7r?m@)>53=&c=Fh8KcB$enBU8mV`+M?v^;qmRv9E0`hs8GD!QYdGh6W>?6s^Rt zg2#J^-{!r+G*%!R$ib=j!SGczn~B;&)o&gFcfxZIs0Ea5G`XGVng?sZ4?xQK&{WZ) zdZf3o&apiYB{{;3N1WypEYp;b`ep^l09{O3!|O5)*S zL$p{dWu{#0!6mY53!z^}JGj@>WV!iP-n+=gk@*Gpf9PKMkolXV z{(be;+57A7=GZ^F@A~V%AN3Fo8;+{g1r6gwM+xI4?)&7zx|443{Iza?OgjV}KI#!1g^|@$nx`gJ-c(2jh2*A}G91lY((GXvVv4NO+}65;Wo3SmL;B}$ z-KOBkV+m+^B(du^-ZTnV%Yk<$`(Gy#PN^M36WODYCD~mk25Oyj`*DQzJd#RJO;)7s z)v^8#(~c7aahB+?h#qhTPvVftThS|tPz+CwE^=)ul_D}wq}4XfqiT8eEOZ3iyDOqA zB=h+}d1M^V$*udlH+H=;7mR0GeE!Dk)eDa3!jEwKL4f9a5BqRm%q0smz5I2 zEj@9H*04E9zBjD0rV(IiO;Q<-zpC)M9q34>HF8^r7&$d`D{Y0JEE?F?(z=O z`w6{B$ZM#Rr0#Y31(N>W&9#Yo8KvRU;wg|dZVecN&xy>>^Z7|OjwU#JxxD}4$B}nU zHm`1UpbY2)RjC_;lp;XAX^wE;G!8Lq=z_w>EBh50S&mCwB@38aOMoaO_sE z_y?pVp4fbsSS9_bgcu#mjN=W3g%GVIaPZ)mrucDKf2QlhwQeJ!Wu~n?&{+i03LlR> z798pY$BH9E3SIX)EVxgnxQUqM+{a3~6(OS@nCg{h=I9l@hKC1AdRPggrN?KKtz5TQ zK2-;WVRGL*M9)~)RrFN#VDs#!bVY>Je%CGZxC6M)wfnH3#W6MuVrU#p)z9qpJR~Sc zJ<=zTEsxC3#b;WsY^L-B6n(&_B-h__#CZ&Rg1!3qBa6=$g{n6f+w3U$*>Qmw<0v2s(JfNvR^kmShZ}rb-Fu7=@!DbUY9n-AVZQz+qjG)d@g{X1|R(v>o zB2k%ecSXdjg+@rd}d z=5Q=s4m2z9+He9J;v55d5W*Rn5CKHb z_+w2W26Jm>>Q~uPA&74H2gi*B3WYW@cw>e}iNyfrB9fJ5AGZ*;3?cEnqq5AJ$7B?I zo+lXLE1|Q?`&3iKIxfU(cZgoDU0o8?qmu84cNuVQt6Eh9x^1hFc{$DHe_-nqT>coT_ zwH^oPD?IV^SH{J~gX4|H=8L7V*@HKh3NtEMg_HhiRw~x(D!#!P;95nC@So+TuMA3E z2%APb$2nbLhA%c#tXItx$_}6|IV#;`huX1s`N6yw2!rL)U+h^%%8%++&O@2f=;%~v z|5*~VvAD@77u(*%0d^ACE!tt8?MKDHxUF;~H4O*;uOH8pndJ_h;74Wo%OTF4tYYoe zUf+5MsRuBDpksmr=g=<5=Fo#eb3T6SvCYt{@b;FladtCwXA)Vv>`dXuj=%JYgw(b{ z=Ag?sJ8{HHK--}6{(CzZDET@w!2#tTLCRBU57vqyQrBN!heB9r{MDYLFLU*b%kQ(n_EU5lQ}>;(I%yrPDT zPI?+FFKb!;vzBi|ckxrk(^w{Ga9Rur_{|HR?}j=ILwHm$ zDH}U-o%1IH9&EAkSR=NXMEBcRSQx4jDhPiXOg9aiGq*y49(o8+G|xW zGIQyPke4scG5p%+c6-NksSlf-E>X4c*#VnNuSY!$WpoUIP%bVTSXQ*}0VGW~8eGi? z(&~h6z5Zt|VtAN@Y=b>9a4Eb^Nj!vN0P$?t_yimx&MrB*tuWbQ4(D(@(*li9RpB2~ zs^bvJW534i8}&2`Afs7@qHWJHXGV#1PmAhAWmvLQ38*GkHbl@DCOfLnJ+gl8yt`{8 zoie-CbvZ-Q3pr24*UOgH2VsdAf@uhFAt}c9mu%P`w)WFp1HMz;>D=a}$*rsNO-aGG zwL1?nQvc!Ha=Z|8X9$Z{r~N@XUFssmhPq`c;Ch)-*_l6|cQ^thRIy>Q)|D8RD12L} zFWzguV*Hqt`9@_Mb2?F*$*ZgIf3Wu!Kyh`^x?q41Bsd{B1Pku&1b26LcXyKD!Gb%D zySuwf6Wm=oxVuf0U+UG=eeczKH8Xdn=2mq>_pZ~YPw%srd~1DsEjpk3dnb-fX5!eI z3A1#Ao%w~{nFA^Mm+a_k9~aGA=K{T&4}8oP?+Y`kB3R;Y^TrUm``#rWV5qxWM0_vhg^#a}-ae?HP*YU++yaJaa$4Xb}^ z<9^!u=;O)6TwO`8hfku|a6LO{BsyHdwFQq>ZaM@&w`}jiAYAypEq}7;8>qR+m*MDbTw`-3iACmM zU;jCI%ireBacme&I~QWpA4?a5P);i=`+v&W$|7-kcrxG&j(}k?dj~l89Cduqf9W%d z%NmU+;VJMYMC_h$GxOJ2mg}6cR1ESyq-xb zDrDm@V6~bfZ{jb^Re%t4nH!|F>cZRep7U=g;*9Z9M>-Q&DM9-|aFO=kySQZ@@kZ1ZKTT$>pRchcp}_a0 zZXPkx@M7LGAE2OO{~h4V_$%MX=AveeA*TM37Egr=kDF#|_ek86vq;`Tld-}aZY$@$ zSpjz}3iV<^fyGN^V=+Smm#@HEncbTuQu(0f{n{SxZLvxycRCo?F@KPimF@F80H$-_ z3_^0d9%dR1M2^=gfbTjOT)yLWJI-}En7y&3;Q;1-wz)e_A(4e3toB`bQ10BaU@-sk_o6UAvJnSQ_WbMhwnVRMwU@l^y5ytpX z!L$qJEH}w-&YXxDKJcEnhL{l*bOsYBHBZVzf>HME+|Sp}@nG~CVm4YWs>bJ2K%5fX zzJKhO+AM1)I_t4o_KJF0{>D;7z09T?OM!Ae05@>u2f>hm3wj-eKN;}XQ-IrBBK-rK zU*GjY{q1YMz6n4<{`;#o0m}Aqr#NgJja~|zw_0eI<1JraNTG(-TylRTawE;gW4H6a zfDtlbEban+!LC!2wR`os#}dru-W8FTZidop^*QKIf5Glve%T(aFm&<9lVIhVHPBkCR5A~~Bj1#_bW9vM+8kl+lpXqHcfVIzi;fj=C>~W z(8Nfqs#D!iEP}|=v)*#-(&5I)J#}*Deq5d@oF;hdiZeb7u3%qxeZ!)-AXwhX$n5V#%oc&0~Oz+_DXw*uaz}g+I)> znC*C;{pAD}Y1wmHAtJZz_=i|3w6=%78m~l2@Z<)o->^lgd~tKt@wfLE?%-|I#ssNi z^Ch|*MThoh7Tuj>GRxO!;R$bUPosM<$Z^>MJ{QdS8*arCR>xwNqX_DiclfYO8<>*`OvuLm@H9G) zumq2+CHbzM3%%ys4iC*|svm^7B8iHw9MLB2P`Nu$8DI7WLu``Cxah$%G#dMtBy4)r zSPllGZd_XG;sTg#4 zOey{oTq;ihPH(>mq#OM<;Z0QngRIdghO z9n0BZN|kDV$6{z^FJIcN*Efm_L%kIDBlGxFv-pS*?6psb#&@y2hl;cCXniyFsQ3By3ZMoXmLZ> zm9jgPgN0!%7CRKok(xAEsT`e<>t$p}Ldde99N=DuO@m-OFo{|knEL=13{<6FZTonL0=5O%} zjFIZjW_V}!UVneiZY%3eI2V(P{z+#0!R{DZ-Qqi){BnDFEBw)z)P=|CfxBk|z7N`@ zj;Af&Crm#y{7b;QzFjn(=eP9z=D_Lb2>-5}FhN(a*bG%G79XG}SJo(-Ias{T4nD9Z#!x259FJOzp@MC$A+ zMg5K6awiHth0ey9!A_FizXq&&dVp841XbSeJ>3wpOWVlQo6d$|NcOB-qE;Bm^ybX& zhFQ?6kr}e914HF7I9P4Ow$dWJSuar7FA$B%M42p}iOwUqYMWtlQ1jHNzguaq2V1P6 zCl-kTP)A}YM>v&!hN)WF!UJutZ5AaKTV~Ae=Sv3-K%I+p#3U!Gg@O z-rhN?a^}i4_4~IRMkYE5v%Fecu4Q;S{cbtU{b(wAbeG;e-_Zxqq~E@BtIz*2#(~iy zhs(CL8A;qbv%C~Y>X4>h}+72UcM9X!)RJ3xw^-Am}sibd#Y@QSZS3c_7?RtW6M6R|7 zrnaju8ICm;jar+-CuRJ4w_2ZFIhP3IT?#Y6gFw1!FBK7XRXGTQq3Jc_a=C4p}d zWvm_^)qFCrXO90^4iSB6(0bf;ZL;mqZ`uPaO{u3jvyZxOZ%ZV?Bgqbc_1|NK2e1oK ze~0BYan)=k6E3E0B=*cVdhk>658cwXFOnFmHnpXW&~Hs2OpXigh(EF&R*b;nu|f}yv2(l{q}d;c*f^4S zfCqqg4u`u1vfrbRx|_kmK<3vxIKxw70%L1UuvlqMklc@{{UNEXs0T+#I^3NglCc;1 zK${yj?u+O1%ye<%N{f}Jof>rc+Ut)CGnZ%bDH=E`jlH9{^VkV7Om^XhGhI&0;!-Xr__SKW0KZ|A0=Og8(pP-9~ z%Ke(7Em9pp9*Ols(MmhnM#1&L!R-*B0*4;J-l789zoF?M+(URfsX;+Zz84G1wl<9I z?d_kbsd_9+f_(=*Yx&dkN=c1R@E-Th*`RQvy)w4e8`Y+6T&^bzUp)37WMc0Lf!3ou z!)o|iOu7$z2XhEyom>r-z{l)6TveAnFqNhU6@Z$Y7QuIbKs^BbT&}CJ|?yl&4YAsG@$Op?mFnzs&BSM6zh^7Jshd0f`RLmO9!=u z7F@>eUl}7vaOa$U3x2+%sB)qeqJ*KQiIWrvwW2gT2gWJST>ira0PJk0U-oB`D49iw z)mb(!Q3W`kt{PpSuw z>m*76Q(trZEjJJ4qkry1hKHod$wg&%weTg=I+<1zwV!T`-aUXAZ9po|%ZxGaY>PL! z@Rw*eQ&2n6I#8|DSNEs@tP~N=(&+hntEN{!kP98nVg`L&vP%W#CtX@A(!@#}ks9A2 zl4tc16A#SxfD25LZp~}It1p${RAcu}K_H&2h8d|J%`MB%B^MeW>v@kgKaI;SMy}nq zbYZk-pAf{}3s0t-1^A`Mn0jw3%hBX!lvmEz(+)>sWC-=R&%P5e>p!p9PWi15J3f@j zLX^f5!C;mG@x9h;rmKH{Ex#OHCM>?(TnVu{DVX3;YT#X7yRNG$6N5n1JNpc`O%h6JQ{>} z-g83pT_#P&2cdz<+5r;v_4V3KjyoAP{VfFYX2%@>@_)cBI45l7yffuSmF@8xTrRSq z=-|@SI32VC-Y@K4)poyMf)&xfDgPVjmwMlHao6tikfG&8_IEdrP3)S}qwa$Czw*qw zq{#2Xj~^*MjNj=NV5gl)V`|~SaU^OzpNEmF& zv2^2LlwP+g3-VYoP5nXhn~aY~I~LGla1{pr{wWCG)H*M+b zByT)i0Nnha8JnV494z?~M}o+y0S!K%GIR;6K|7o#;BV1=^N+9w71Z#^{Lhf~bc-45 zj=kp&%4*@}kM!Ya_=?ssb{Ja&+tt|rhmba@JN5b?g`T#jSoDMRNb5Sn(5U&Lz)~Ok zsIK2scXtAG4wFNFN5}c?7`5yJ z_;#58J7+C={twew|J~%XkjV>QkgUHi`6uF(>2T6n*S4-{St#|Zg1vgI|NrEkgUrsa zSxSPuu~20zcI(b4w?r2-SFqU|Q8mPn?2F&5v$bH-gFKh)`TS}isjS%d{aB(IK(sVJ zS_2>i{C=q9@SAQ#FTGK}4`y_E^r|gWi?6mlzOBa{Ic1ZK#1A1N1c$Ci5_%Qv=8Zj- z-8vU10F^^Rg%0j;)SExhG9LD)$tw)bDt53K_Ixb4wTw=tLL~q!Tgx|63yCoLB7vS` zg-T^S$3WRePfw+~@900IhH`oOtBYH6>kzDVq_EA%({z?8K$wEU(tHiGNS~a2nZV5? z6muL+sOEml8H4reO6=ZbB^3c34jvwF;oWY5H5ULGYb;UY~b?DzQGI zju^Xo#QgD*DgDL|edI(gXAW-tUyh{jxO9?R4{(r8nLQ348+nzU2TkqVeTtRK!|f6S z)7ZZf?T~-=!|OUu&F{t_!ETwW8L1{A31-g^kAP0u&kD!g9A~hF(9Hf$S}kAgxzkvE|3Z*g}s^$Pj_v(Y;|Sm zD@|44izSV2XLfivBHwW02;BZd0sl7*2i`roePq$^jC8~uDx;4wLj&>TA=|rGi1s1m z9>}NqJY7_@Zahi}|K<`j&*z7vK<*?>zcmzTs#lwl;__Gp8NTO`)_C~kXz{p@Jz)5} zuIMO6SlWBSvHD@3CWId-kt(pSTtfk7fm1TTR%liA>fTv#RD^ja{xDf~m}x|1x&BZm zhLDw4oU5lhFm41>)imiGsV7HHdj-#UAU3tU0-0F;UY++Bu1xS>w%;4Z-gjSj}n0kzmX9ixCH0?91M6yXZd!bTjhA z?pWLmk{Kvq`8Pl_Tpcu=$-fcBPv)w0lV5YWFb&nT@uyQ#<0z~{G94PT_TAs|eqkVl zr$ghs)oFLb?knw@sRSc+TCPKf%8mn9`J(w#fzc5RoVMm05Mx#A2m})pl-p!o-`s*osC$WnXZd zorc4Krb}3!EC7Wb`EM_Rpodu_LzO0MzG=mrml1&aqSMn^tQwe#VaZ}SIJtkUnW6Mm zHZfQ;$JgCHI&pOWMw5xO3g#fEyU5C|KoVveoF{I!QvLBIShYZ)tcqQuAi^J~gogI! z!_Z`Q4@AU$1sc2-`SOVSCjN9r7NLrXRfR82yZYo@&;lwCZ_ET=FxK2^;$)tW#p;XJ zbwLX9zH`+G_Cyg;yY5br{KR{}dU6^NOa;Hl-B{gf*f?QYm7sR5xnQl7}0#o z2ZC=t3mCuRKjN^K)3G5RBmeaJDZ{PpQKO@hLCWm;*j_Ghl=&_l%rzJ>`XrSKjf698 z>c<(^81G6=fIw+&Q&mSRVlkEu32$v(HZ&4@Wg!@nnEH=*w2@3J$DHqEFX^=?-C%r~ z;DS(=_k6(oo*wdXhE#MQ#>GslOCoyHbAplh7YHPv8lh!6suA%ism*B21_5I-JARQkjvR%(q!a#;YmUqTvP#_G@k#PqSG+v$` z6+AgQS=dcx8pXdMBazH5TD8BOYdpLb5nTft$c(ez172$5R#)L29UTY9#^_UQvNo^U?UeQtDW#Wv19^P7 zCY<`KE>&??y-Kt<5YwMo_#<)qVsZkJ&Dcx{c1j{?u`7H4S5`r2`srHgX1)`Th$YRJ zdk5niA>$#^Kv958P`r^Dx>^N&+hdsM;?0c3##FlRn4&s^EhAVi9TnM_pGQ`d4=?B< zO20kkJgy~DFL<337cELZ^EAcp37Of?AGv5wv*0uFbSCvjM;vfE6UBPR%{L`v#rb1= zlqAdSt&3y!0F67I$$A?7iY}_@&(UOEw!z4Ji7l&91BW4wlPI7HA-@-<)cV_i;Mq+F z#y~B!i)ghQT^Hv!dqbmx-R<5k-r8l~cz|WeBc4tb6iOT$yT$993#7-o-^>~tlPz*g zs|L3HDplSvyb2g8CxdLC7EcEU)Lu)mQ~Y~F!CEJO zWq35if0?Ht@|hK1p-4H9-_~bd`IgS>P&c*ro)eLStMD@r2?I{!craw}?(&ktGVH&Q z_y1Rsx4Xg$T(~6DlKKCAMD3-9s31h#kK>wjLs5cR`rv+lEOx7pMRi8tcB8fC6WPKK z?RbBe=E{iaXk!_x{%CZqXEHiv0erzC(|z(KtzWya4R-(N2=D!yF^?LNi~$W?B0Iuw zufyq2a+(Ks{QAgZb8Yyq6g5GLpTnHOD_y(XSDpVP2z-pYrE&gW#X^kSP3`2+Uo1bi z>)cM?cr?7CWp|!`L0Q4`F3TTSjTuKH2d1~bzJC4lPj>pR5gviR2^@ZkT?*Y+^Xu!! zB0KAL62D$)+OY_vesj@Oy2l*qYNof(kD!%IKWSTIx3rY;o$8IDVUP`BNWon2p@)ZT zGB`<&`41`lg#*!!R`%0b2chB^Uth)lfV#b# zQEA-RoKAUCpREdQW?iPzsB9_l8*`~q+kQ?Kn(`5E6^Y-Cm8uTrTY7)Z)o_mzP0tmt z^wGzF0)O}i#Tg4;Z+r<4H@>mmh9RQqisR6*bVN2BImqw9Rh!1H6Clafmo-sfhK8gX zh}ZgZ0R$FiB`F0`4rsi+amB3-+|^=lVS7r(bYx@7@1!yhBeXu0I(`+Mj- zx^~K>e=7z%M%EXmwVMCp{tneZ;G#@oQPQ$GVG5x}Fs~vvxu50iJ_c~ap^huIE%jRO z=FtTg@k$=pMZGS@l%?X<_D*52AA)m^GJoAaE%r}9-Gf;hWauh$KejA=8AwfP3;4Q5 zxKT@3`NK+tWan^g;Fra(lefacu_@8Li{_R~*m8A=drG*Kh>@eccX%F5 z+q!nJ)Au;Zqr1a1zus0fPdJsm-|#Araq!?K)bx|P$*AG9q7!D&HnvbVGu;U|bCP^F zhb)^vnb7W>;a*GevntzgWMg#2`KMB1g#+2MS-<;{q5d2_ho*kM>{%3}wx+0hFn!~+ zEoZ@GO=GPSX$r>59^VBEc>DD82h^43>cL-80N~!BwC*@}bH(26>bclx(y;MdzRzu7 zZQdx&Xe0w%V9FOI8+g6OepOHr5mThSPms-6*JK<43E+#`Q(@n{k$HL-FrTV5A6#^>xTg8aI4sN0%$VAFH=I0j!>x>EQu zA>5tTP)Tu)_U_FSrE0`;QlOYEl>Q!J|Mc0(M7^%caC6hvk}XZo5(TI0ry%dIk2y42 zXku*!v3m+D5LRM--Jg-O`Zvf*L#QR)k4u!m+1I{~1f$N}o1!D@h&DO$&pwmkPHXfg zdIVoFF!otz^3#wi_;eUyL=u?Hl!dgtZ zUyc0CNB>2yAi@QnmydrmSBMw( zf3dj#6ItA?m*qMw{osC8oc8N)V2}xDo;jU=qXZ)p?t)ua;c+?!KC86j@$ne<9o?D9vU+g?~!h;C44jS z6=Wm)4YIBDE0nh~*|JAQyF=df`MB&_x@<2cZmkj{6;8wyJy@CByqLZX#`XC!8*gN- zdHr6)WkhLn6qamuHsLp2#=5&8Z_0hsmS!15`J2zX$zLH8MY94{@ASm{Jfrq|MnAW3 zq%r@5cO~Pqhg<6G8NWhTd?kFJyFHIbsPSP*fb1SBx%0mQ$4VuYgJ1VTGc3_S%gQWG zaG25Pjd@398eGZigcwgg3T@-+eJNoUEb@XP{*&MiH`}N^*{h;J(A$zokk$Yuf7dRy zym*6)KJYi=+xG1$cu%!&T+HQ_*Za(=eSxE|J`NZ0FCA?yku}A@7mnxV*k0#}721zK zLLlHj61!GF)_1VltDq>%LF#DDMfPG9 z^V?4w2te*@&+=4;*qDpO8Y4dliF=>W(9l}DHD99;!o^!Z`PAo!YhN~-m)%sm;WAS( z9EljxBj#D=tD>6U=O>2u-j|;f+36k%EI&mCaHs=P8&s?n1$A{%9pD_6BBAf-7LIG#~KgbUcV**vo~=7F`OLZh3Td z5~Orj>3mlfU4^Ij#;8wp<@SF$nI}ZcPEF~N9n~roqQ**FPP#sCDwN&LEmb)9PQ<3E z^QT+d(CyUBnoV*NMNY>ZL5m7(xFHax4@;1lg1DX1KMQ*wDhH;_5<6v7OR5BK15d*-AP zF}3utWm_!|%@bGODDES?gZ&6l8cei|bu=5ojexmDrE8a(LkOQ`-cPp5)T|M3W$>q) z0rz?%r05LhgWc?nhgG{|6{R%i)cdz7wc5W?HyXq9o3LiegdHJ|hgz-%nFcB)*Lvg~ zqAc*sm>Nh@YpT3N3=E?Lu#FnbX0N@d)|ZLo5_Zi*A%h+~N;KG>!A${LBHkZAn{H`J zzx`CJ;;wX$j;!NMyQRtB3F@FRoalxg#rNPH%c)0lueT8T`a8*-f-2knVuWnl7-ZM} zu|u!tShY713b+9j(ebcdwr0YlHSRhj($=QkWX~71Ni+PoxQ9Ufy?9`C71}U{Sd&WwmNuP(lcCB+XgoNWh^C+r~5{Li0+@|dI zwrR@;?4#~B0+CoKO%zrmVkLGEH?(y6<@+ky#b3WXFk&tXuwEB(e8V~w-+>oo0Z(Fg z`bkG`;1$$|4!)wS6cvxx_^Jt6i8*9JQHbtDz`xIXi8eodTp%`=Ni!6p1H>90i|}x-L+9_rDOUa#I>x%>bfE)pXz6{^$A8}OrGnX2 z^s|+tlRBT#2js^KB42UtAYhrR{dYNvu(O_^^QUgSAEB9wmMW85IicYpZ-~WZWf&kYM_bKz8|-ex*;=47}>6s1n3AJsxo)${%AcM`i8dW@jomGcTJ5ZgT# zK-`$y8K)*A_u`GWV$J(vi6Gzm$PO_4ZRaDR@hP-+`b}~TNU?Heq-zuz+x=k6yJ;n` z^4l-2e7`GN=EMpTb}OQ_Hb>e-*dfCGf4BgA3cdXAv<3Ym*imcN+QPH|&k1QL0zWZg zJMjSreHy6WgO`IVVpzh^7LLQ_&v zWM)=29^x)P-|8ZlJp{e1-rKFFYQeu1=WfDWky>3Z4{kS;kzk}AK-xZbGvX{!Q+u|* zqmr0BVPc6Pm7ua~%5lGpK2hg=!S`&C%r)%$f$KL(XL{RzQe7|^?Z$jL)N^|_tV%jC zw-MJBdg*b44J=W;j=Guj2=_i$SWRtraM<0ndl~6u98u@H*TYLtb+}+em-EfQAo@z7 zdFc_`RY1FS-NO`8vKal%1CwF9&dR*j;^!dS0BJT`V(TT6n#g0~mQ{bO=X%8G;Umw< zHNWxJKHE3gYI2^woq@V+Q%f8~F5RIP14J0>K?xPcUKDuQWegyxr;@Ir=G;0PbWR*6UP*hM~-A9R`?>RW7spU zi^hQ=*1oh+Ybl*h1FQu{2Kc{SU*0Xc0Vz_SFTGf;LCudA7<-E^3XuR;M3{Qp@riWV z-2@96&gNCS@L4!ghx03T#fvtj!h|?sPtZUTZoqnVRqO5VgYcJ#z)H9sMw`<*yt!JO zq8X(1<(FOi`vbt~sl!m}+D-R_+{NHh><}VEfcnDioMET8@AiZozSG=5L?+Jqfx7po=vN%w{7SE<%-4o0=Dk#7C!XzH_r(*#kwCv zn_=m&dD8w|j2KvJiPa;L>Kep&zm*Bj@FSSnxAoTwM`YN{C>}bY*@UWEGsQ;YdIodweW-yj?ElIr_=m+ z-xo8qymIz7LpNGn@!-YiH@Dh^JEqzBq2G5J_h&p=4|_|+bMcsGV1GDv590t{4Y)+qMo%!a_wDIe zm@ZVB_xaH4GxY}UEu{Cw7`yZSv_-=VqxC!km)mix(8DvYr-ejJu8+tx#PanKlP&cL z*RaT27q7OyY26*2;Ol_zG4Im6){^mT^+_eTbF~_5Q+r6hD#>!1IO*3`Fuck@%ynhq zu9@SAh>Q5`N=5ThM<2d3(F<2$Yst^tr;+@1*m)2n$=^pd4w{o*Gp~NJ%Ot_bE0jnp9$v0OQLTwP5eb-WmG4O3t#!-8E7T_)^NfX6$Ze z>$%?T&1JkYsVrGL3-pzrunfl%qns{$PHGq$8_I*gGpYB-x*f3w8vF93+0CluIOM#A zjAPh}X6D?wgQfF2F;g|6HCXNp@}4|^BzS20@T0@vmkK?a(@G+ZX4?;yu!6IROr;{+ zx*AZ##{9RQ#wHuG$kqof-(=2M3%l!FTj7wyP`k6W7oVQZ>H!x-SCybf~oS?4^x0BPP<~+@_qbf z$L|#eA%?+tcA!!E9x_jAP`mkCg&luP0EV(-AA6?g-CH)8=_9x$Afud9R}UU{#}W^USaniu)PXD{n9$4#hzc_CP>pfn#A z_G78(wc5$q&Z8nl8c@v6w{N+WSnwM>soK~l#?LV!A#a3dKwoF0!*Q=L4g>}E;Q4&c zS@WM}DRKpfi;5ta%*J!{FT#js!+n1EB764|V|FKyN-X^m>cx_5b5{?3&+WF(^cOA3 z3*5DxbX_7{z6QjZ7^T9=OkPZ$Q%(WpPp4K9Xsk3LhWKz7GbSBL~W&RZyzNVlW&9V|Ri5jd>H%fO>cme-4j zAq`~wqdG|?6tP|p{a+oLBv9R;zIZRSBx!2Sdap$BIEk30 zsK}7g5e24{HQTQ>K>IaDtV{MkgNP%|f65Aaqs?fh3w9uXRA_Y|84*QXpJrnfmyrC- zS%(u5h1WUXy;gzAcDi-JK5=t}9T(K0Fx&2f4dP*r0yB80S`CD7*iOb;7W%?liWn_c z9+*$NjW}v;-Xpa-AW-Xa1_mG@GtxH}`Jm=hluD#qbx@R`p8I*k@{u>>i#qb064O=Rr=Y7xz)B9CqB*2#Zns8G29V9ddn|;ok%Q5bnAf^a@)Yb zfwRj1jBQhTGjKwQBj0lS#4aab5BX}n7DU`=cxzqlsK)U8O*FiDTbm$R0lrVq=>=mP z-Kl4eMki5Z_FNC^PTy@`;P$v6o}EAAZ|AW(5x0HpmWNMo5W6^GxR;F86Mk?T}I>C>eW&?ezC9B}UcL#4MbN zua@faRJRFdQhP;6&NVJ3C3=syO+t9@CClvqqmjlYD28Jp1s*Mia__Eq6L2sfg+JG2 z-5g=Yo<5_rFIUErCxRV;zi0i2wKr`=>$3l2BK=l~X3;cXE{xAwdYjOD5tu}JQx9by zoY~0bBAYlmgNYbK@0kkTu@tsEi>Z7To5e_9{$9nHmPmbPZdrzcN4&WmkJHUJ>GaX*H`h6W`RW$c(`eOr-ii>8jIg5Y^T{4S8K(s>!|Wj^uPT2y^i zYZ-VlZEGtz65mJvD(_y14sHel_y>`ezamm}N$8MIIi4zpxL50KXHOPQ>Dtm@8{ixH zD)5V8k|6J4TmVqt&|f{l}vRr2h{*`Zzai@G|6Qvz(^ja@nt4iu}LK?mR^NT1@1m ze6}Y@Q)(8A?C|Y2N}DLg85*KwY1@$c0iS=id}mXX5hLuFPK~8eD<<3WP)gXncLw8l zQ_Jh*Ln`4%|Htd4B3!6&w0z83ei`9Ivk#bMIy{CLJ-+6Xs+m0>5fW3lJoCAHI->|O zE+?_tm~xJwJRx?g$d2YMT0DK%PDytnNh~~NVyE+uHnyWm@5}7j-1D51TApu0rHtPybnLw2VKzbJ@9<>BKOk2sa#TTT zcV?(zlMAFWoe*<#-0gA^ml6MzH`|rQdn%<0&2CGZ^1wDnxE5YKBtcq`t5DNN$-|WQ z7Pi`Y`i-oOl7C#Tag0*Q#O)wNIPF^s!)|ntgK}6(E?F-sU?MyFa_Fc$HVtSkTXt5=V*+ndT9zF!O4w90SMQr7W_K#7qP~vMbp0IyIH-2 z1ympf>IKKZEiWDEg%1IS{dH1)RT`jkt?(zuOeQ0=Z@MED#(q)s=CQbnS|^l?B=_PD zenXLV^RZ29Zg+5r&&UMjKeAd2(;U5v4pC=OB>T}ggkp+UvuTb847(T*U~994s^ejA z$!Bz5n`h7y#9}?46zTRP@XY?i*{VRIsdEFjl$u`e+kdd^?ucvoc>o=t9g#1#HacK( z(&W5QufUJBnYJ;!Rw5!m+D@knXy}m_lUxrRg8x{pZdm!(5msNbx7l09<9<(%{FEo_M* z^I3t>_Ue9NJo_bfYoLL2u#2?ySn9QRHjX?9|HXc<McNdY#yOhI97b=;og|6>Jmywo#(WjMwczTiX@12}zV8VR zf36P9_bqIfr}PbeTPehR9|zp7su|zD>%{PGWe7fmCY)>mH}~WR!I|1*L^n9yKnmDD z4|r=G$@1M=(`=FZb>>;wg2LMYHNM<#izh4G(;aE-0AByv#l+Lyai=6^FG&B$&^!MJ znV3trzhLv6$V9%HADwNww6nBJbJ|>BEe0#+R%DHN3W`Xdr69J!uB{0^3A8IC(b@?XR`#L?f>EuEX= z4A}2ax1Q4zgYML_D0>@T?D0`IZqWeKMSKI&!_0#=m<@n`FnWn=DXD}-v}n>qBl0H zIZ?goWm*4j)m*hvHg{WWzjXindv#&eYcZbf6=4*f(+Pm_#R>WM+VI*jz$!S@pD7sV z%!CG+s!LQah#(>&f-+3(SyV-deKn&TC*k-Q6m}RvBD2xcPOGmF3;>DOF#X zbh{$E(id|UhN#hzvxIskS5;E~f|A5)I$w1AHlpLdaqx~;6;;pf)i-e~NMH|zm1{-z z6#IGR6TQ}Me=J!22n`9()F1QQw5lK%Um(xOyTH0Xl{Rca$d^mpHvz#_TTh_DGm|^o zj$~;8@o7GhU+Y(2NNO}$Lr<5heN3@w1%|pD{H*oFrj}d?j8gJ1Rj*EyZ<`txwX>;l z>0?qAoyoVoqJ@bp)rngChC!o+8t}PN2|U3e+r_zdF4V&LYGkY@VhI(`^P7ON95xbrqC%gid4etX_2y9HCm^-!GF$et zMW$W2bnDrPVxv952$fovqvd3Pxl-;yLDR*c@hCdk5QcF|y1tKawut#+XvoAGQDMI(5g%&390p@6vwbH^%aOZP<=lR1 zg2r9DRQ=1z_JZl_2g%JDQHbx)l-I$(Rh_O~Z* zh3v=zhi7qrVC(6sOfCYaf6&mGvK9Z=KJt!UFQ~<%^Ntn`5t9iq|O7cW{*GSDsYjIh|1h<#RpqSPL!an@GiEo1%x>#f>u9SDS9Ff4a%Vv$0&h56E<%9nk&(1v>PGyQw=rC4-{7`{2AmoPd z`6Xa#Pra&@8Z3ui{;$F1n0gZ7p=!ou4@D9tMa3a=Up|uJtDSVQme}gHCd1cQ)qvfr z)K0p-72m&qvj+6ZY<)kWYAEL$s6w9Th5^3f_kS|;;P4b>_@6U^Pul&*E&Q*c|CE^! zj(3B2lboDfs@IWmczAeDXVURADM@?>OaoIXQT0e9mRJmy2Jof-AGKU}P!nC(M?oF| z>Cqral^{(by+|`4l86wx^j<pNClp0`Rf$M1#?T2!5ilZzCJ2Og zd7t^dneWeU=6!c|c6RRWJ-a)5&bjCJJLldCfB~zvw<8z*1b_MRMIR2&58e8{WS0Q^ zY|XN1or3;;0|WvQ;Wz~cmPEQNFHfA)Phs#mmjpDf0CQ18(`y_uRs2Qd-TOCGbx)|o z-pDX(dwT&^UIp=Wx!vnKl(8#NXmx8}vgq37nwlEVse0eg^tZFB8}I3@T7rOcVSxWO zlKlO*o~o+q6Iec=@*SyItSK3ypR&t|x2&$$nzmGwCWVTLrVb&-hqNU?jv?O3PZA(xv@5{wXSL*!viUB(#Cnnu4 zGZA6P;~$FnWDYx=&ae*0eQ*R$SqXvO|C=wtEw=16b7kAJFr>FDtT#wynJ5tE`_reTXf+#Q&<+PlIA{ z)rHh-Hc#x`TD!-TaKf8}e+0w}!*r1azYh#}zs9WGf&O(`_vWqi_3k1h8Y9@O5{pO? zEmQx={jN|+W06*t=O}O+Tp^l4PVTBRiBF6d~`Un!!=bDoeWT`ZCHOS1vvt>+$9q-V?tC`n&Cc5>X7Z{7f*) z@sN<0Q5T`{0f|PI`b-fpQ&BmaEQzBRQhlYu=VtiVNzXh0SMk$2x<)peNmq}XkFN!o zPWQB18~p{c?q|FZmP750K){4yA4o~9gdOyunAzk>tq54y~Tx?fp$?%Hn5 z-L>%jVWSf#y|;32kTRU{V|CT6jFeMQ6^1=ibfbpxx6s1)t;_~eyGxa?_5!7&urx%3 zerTm{d7l`%mpTfRNN3$k0AHh{V>O5C-Z0}9$bk8a6aF}mzo!w|ilaymzTlOY#{2SI zoP&mGW`Oc4PhHXDU1Q6SeOMut1c6+|%?i91h|SRTQYyP`8z(Mq+xIauF!Nmn*Hv#b z=Y_>Op->8Q*+hlv&TD#5b>_g={Y1Er=?emyWB;~?T%eouL*54Awg83v`H0Pg*JnAL zJ8P`^t*v63@30BgnJ|2!$YrW}u>E~C%d~Bt+{^_~f0~@6@QoGX!pZ|5-j63Sy)Fn8cCv-)*n)G!+B;mBqlL?v6^l~BFsuK(B(IumESk1h@C&iW)eAF ziRrn6s>EK<>YHt}yTuN`;*PdbuFiPzjj2j_YGNOL5MNpG?5v+=0edKAcP;=WtQUshWm0$XjqIsa;3 z6)*n;(* zDV4wabfrvVhK@jU7Sv{DXzH_A`kjVBXKKo&(K{{AJ3HdZ0p0WJl4FCycvt@0>F1Gc zE_RYnb|T%5oINRzN`3Mw>2rri*YT-tiD@RaA#z|r^@zUic}L-WJx*ir>AOYhJ7Gq`VQVm&{-Nr1QUU4wG-a%OA8esa}VESt2M9PU0t zp09MJwMt7Wc^dQ)ctjq}o6GN`%qKb}vIUS0=vSY)*PKijBn6!mGeBD`ps)&W>FgjRvp*wmQH5t9K6=3<) z)+A4ytJGTY`F8QK+cZ5tn)P~+<~zK(<3#Hj(331AD!bBn#29I->wisGoDOMV7^In> zdi6-|$=NdvNsNYgi@1!ZGa(Co*{JrJUqONt7v-c^LxJoy| z&E?_Amwwii)$naNYgX)4`QS8uSvH(%Jqk|aIL9a<)9to1uPSY83KPGJK#3=eGmr4i zhQI+WUs~HM&C_->Axb5;JmAD{-d57=P4f{7j^t#J#NzB@av+%%5>t9_p2SW|2e3q5 zOBG$4fgDX} zkey(^SP6r8kH@E^q5X{mH-<982srQdJoPjZ_@D&9OTHd zC>uKV=21nU5m^mIr5R=>l2<(jV-IVp1v)8x$oN(7$UY6*5SkYuH%AX0Wpf9W~@lI1UR;@Y;W;{X5-#IRrV$}%o?d+OO z1UN8$BSC{1z7+T>@lhx3H}BSCx*HaQG)sko$H-zrfyU>GNZq$A? zD5a`erv;qndiZppGuKLE*-3_X{817mrA%#(;U2EWZwpk@+V9c0N474UL1vE{kvr2v zZ5+O85iJ1k`C>P7*fY3-%AJYK7Q^68{W}A`4`zHM#A7qmq_7Y3bxpWMgp@E@BoQmc zKwkMMTAai8N->ctxl>U`t3ICDVZF?vpx6X+-Y-HLgmP8WOcf^)Y{`(z(jTr^;ZkIs zFe?#Ok#+qgoLfxJzxUjCnZEpMjjMP0Ui=Ev15&tdmSYOmo3P;Wq7rQTehH%ot37-) zoqlEKF4`N{mV24|G@-5o<8cg4xe`7*2&TlEsUHTBBa5YO3udH;pqWGHa4=ycO z-p|RhdwWDj4lS1IJ0@b>NqCc%o8T(JO?k>=VUaA`L3-t`txbu)0tvF8{dc34hJR&j zUnLTqpU>4~v$@Zk-zl>%P~xX)#H6Hhhpx26)aHK8letrFTIqh7O?BQp3w% zQb#D)NvB%;A%wkMHhC-x_r7%}?mD^g0rO*AQ|b$ozc%)dysZL{gIkC575z^E%*OM? zyvUf+f?1DI9q+pV2R75=LUCs|_rrAA|43`3E#G(ekaeK-?fA5jAMK6o;;9dHQ2*6H zsOf&AQO5BGqS)3?MXPlL>tXQ{MpgM0MwPL+Bp2IsocTFpA@QP;zh;r!(qU#jFc2Su z^bv^3LxRHp$<|LX@6is{futbo2S>jK{;hQ(5s_F4)8b*ESbS6FW=btP4}g8_T7v4d zX5gHhoJl~Xc!TDY58iP{ANObbBKc@3yts<2t+#+Xr@n4)X!OE$^a{V~y(Kz#2S0UL zpG&9*UdK*3kweHq>nM3&oYlbN;P&_N9a#sKy*WlN<~JtNWfyuA^=HGJ3g`dcZeP>; zQkBskxuayLByFded|A+eFcYk4I0JqDeb}lkBXsFzAtT-9MXHI50ABeyySD~{0^SVW z94uM6#F{)XHKaJd`<3(X>jF~l*1FeJXMN@_0RDQ3Z=5<;rkl3d)(*z3h%5KIC_tc_ z1_ZKGd}DZ+wdFmP1}SB_IMvy$X^IDNE4mI9-bw11lF4|NqsW9Q<4$X2uzGv%e0wpy4$yh@7GS#KZ9`<~R+^bUJ!E$slFu#fg&d2NkyK705%nO}{%ZdokbqM(iK z_Cz2Om8+|HB>Tl0ex{?Jcolx{_b_IvMNj+@=QM*Ou7nT5YIKt8&HX^=N*E~tqjI>p z-dNdHFBO+AccqM(X`tG}c8CZcclV}FpG(=YeCxgik#KtWOD&d~J=lc*=PlSDokZ`+ zb6LSn%bg!0ntYfhAfFa1kFrYIFWrF;JoeEpw{-v&HfRgLIa5|wX zl5H6h)or&PO^AKXk)J~9&rrsg=j;DyXiI*)tnt25iv}|k*QGvHO|q%YaNHiTjo4tc zk61Tu?~!3Z+|4`UE^s%1Tmiw4>cPaI-L~yq6>N?W!|hSI`-2A&ZA$tN)`%*Q00yXm z%?%E5`zr*}*%Sg>R=osZw=SZo#Mab$wiRlNs@fwK|k-FToPS7e?Wqb`}_M#+cl?pk;*yGGSC`h&N4ohwy95QY;63u3BLd!=(pv( z=wiUk0U6>v=Qg*7w6G~DCgh?M8Q5M8g>uspHWsjqsJuM3wY7Cq#-oD+48CP+d+8yt zKGC`f5S^jZuG+}?PAZ5Q;rb`*y!%>mj$jA`vxJ01tumrDPF{H#?#aLtrJqvE zcXAX(1#eCf|3QeLuK#Cs&%cw~K;Qp%M=>u;URHqM2_6GbGw{5^$Zo@Ddd~#HR&b>N zsyt~sNX})$aB*?%>hk~7F!`+Ue~|Bgl#w~q+S>`Zxkzy0r2{tjO+(!(m}Bg}0M?rP A!vFvP literal 0 HcmV?d00001