From 98cd2e3a4dfd9523c8137b4920c7384eb171d359 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Apr 2025 14:35:27 +0200 Subject: [PATCH 001/128] added COLCON_IGNORE to every controller folder to not build it every time --> added gitignore, to not push it to github --> remove it after everything is done --- .gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000000..57aaf61f1e --- /dev/null +++ b/.gitignore @@ -0,0 +1 @@ +**/COLCON_IGNORE \ No newline at end of file From 783d129b3be106146b6777f2dc4d5d4562b5d1a9 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Apr 2025 14:59:21 +0200 Subject: [PATCH 002/128] added motion_primitive_forward_controller from https://github.com/mathias31415/ros2_motion_primitives_controller_pkg --- .../CMakeLists.txt | 112 +++++ motion_primitives_controller_pkg/LICENSE | 25 + motion_primitives_controller_pkg/README.md | 9 + .../execution_state.hpp | 13 + .../motion_primitives_forward_controller.hpp | 117 +++++ .../motion_type.hpp | 13 + ...imitives_forward_controller_parameters.hpp | 43 ++ .../visibility_control.h | 54 +++ ...on_primitives_controller_pkg.rolling.repos | 6 + ...ives_controller_pkg.rolling.upstream.repos | 6 + .../motion_primitives_controller_pkg.xml | 28 ++ motion_primitives_controller_pkg/package.xml | 35 ++ .../motion_primitives_forward_controller.cpp | 429 ++++++++++++++++++ .../motion_primitives_forward_controller.yaml | 52 +++ ..._primitives_forward_controller_params.yaml | 26 ++ ..._forward_controller_preceeding_params.yaml | 28 ++ ...d_motion_primitives_forward_controller.cpp | 44 ++ ...t_motion_primitives_forward_controller.cpp | 277 +++++++++++ ...t_motion_primitives_forward_controller.hpp | 274 +++++++++++ ...imitives_forward_controller_preceeding.cpp | 80 ++++ 20 files changed, 1671 insertions(+) create mode 100644 motion_primitives_controller_pkg/CMakeLists.txt create mode 100644 motion_primitives_controller_pkg/LICENSE create mode 100644 motion_primitives_controller_pkg/README.md create mode 100644 motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp create mode 100644 motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp create mode 100644 motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp create mode 100644 motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp create mode 100644 motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h create mode 100644 motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos create mode 100644 motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos create mode 100644 motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml create mode 100644 motion_primitives_controller_pkg/package.xml create mode 100644 motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp create mode 100644 motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml create mode 100644 motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml create mode 100644 motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml create mode 100644 motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp create mode 100644 motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp create mode 100644 motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp create mode 100644 motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp diff --git a/motion_primitives_controller_pkg/CMakeLists.txt b/motion_primitives_controller_pkg/CMakeLists.txt new file mode 100644 index 0000000000..4ac8f424c8 --- /dev/null +++ b/motion_primitives_controller_pkg/CMakeLists.txt @@ -0,0 +1,112 @@ +cmake_minimum_required(VERSION 3.8) +project(motion_primitives_controller_pkg) + +if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) +endif() + +# find dependencies +set(THIS_PACKAGE_INCLUDE_DEPENDS + control_msgs + controller_interface + hardware_interface + pluginlib + rclcpp + rclcpp_lifecycle + realtime_tools + std_srvs +) + +find_package(ament_cmake REQUIRED) +find_package(generate_parameter_library REQUIRED) +find_package(ament_cmake_gmock REQUIRED) +find_package(controller_manager REQUIRED) +find_package(hardware_interface REQUIRED) +find_package(ros2_control_test_assets REQUIRED) +find_package(industrial_robot_motion_interfaces REQUIRED) +foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) + find_package(${Dependency} REQUIRED) +endforeach() + +# Add motion_primitives_forward_controller library related compile commands +generate_parameter_library(motion_primitives_forward_controller_parameters + src/motion_primitives_forward_controller.yaml + include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp +) +add_library( + motion_primitives_forward_controller + SHARED + src/motion_primitives_forward_controller.cpp +) +target_include_directories(motion_primitives_forward_controller PUBLIC + "$" + "$") +target_link_libraries(motion_primitives_forward_controller motion_primitives_forward_controller_parameters) +ament_target_dependencies(motion_primitives_forward_controller + ${THIS_PACKAGE_INCLUDE_DEPENDS} + industrial_robot_motion_interfaces +) +target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") + +pluginlib_export_plugin_description_file( + controller_interface motion_primitives_controller_pkg.xml) + +install( + TARGETS + motion_primitives_forward_controller + RUNTIME DESTINATION bin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib +) + +# install( +# DIRECTORY include/ +# DESTINATION include/${PROJECT_NAME} +# ) + +install( + DIRECTORY include/ + DESTINATION include +) + +if(BUILD_TESTING) + + ament_add_gmock(test_load_motion_primitives_forward_controller test/test_load_motion_primitives_forward_controller.cpp) + target_include_directories(test_load_motion_primitives_forward_controller PRIVATE include) + ament_target_dependencies( + test_load_motion_primitives_forward_controller + controller_manager + hardware_interface + ros2_control_test_assets + ) + + # add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller test/test_motion_primitives_forward_controller.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml) + # target_include_directories(test_motion_primitives_forward_controller PRIVATE include) + # target_link_libraries(test_motion_primitives_forward_controller motion_primitives_forward_controller) + # ament_target_dependencies( + # test_motion_primitives_forward_controller + # controller_interface + # hardware_interface + # ) + + # add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller_preceeding test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml) + # target_include_directories(test_motion_primitives_forward_controller_preceeding PRIVATE include) + # target_link_libraries(test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller) + # ament_target_dependencies( + # test_motion_primitives_forward_controller_preceeding + # controller_interface + # hardware_interface + # ) +endif() + +ament_export_include_directories( + include +) +ament_export_dependencies( + ${THIS_PACKAGE_INCLUDE_DEPENDS} +) +ament_export_libraries( + motion_primitives_forward_controller +) + +ament_package() diff --git a/motion_primitives_controller_pkg/LICENSE b/motion_primitives_controller_pkg/LICENSE new file mode 100644 index 0000000000..574ef07902 --- /dev/null +++ b/motion_primitives_controller_pkg/LICENSE @@ -0,0 +1,25 @@ +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 the copyright holder 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 HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/motion_primitives_controller_pkg/README.md b/motion_primitives_controller_pkg/README.md new file mode 100644 index 0000000000..dd7e2ae218 --- /dev/null +++ b/motion_primitives_controller_pkg/README.md @@ -0,0 +1,9 @@ +motion_primitives_controller_pkg +========================================== + +Package to control robots using motion primitives like PTP, LIN and CIRC + +![Licence](https://img.shields.io/badge/License-BSD-3-Clause-blue.svg) + + + diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp new file mode 100644 index 0000000000..1d2c101f4c --- /dev/null +++ b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp @@ -0,0 +1,13 @@ +#ifndef EXECUTION_STATE_HPP +#define EXECUTION_STATE_HPP + + +namespace ExecutionState +{ + static constexpr uint8_t IDLE = 0; + static constexpr uint8_t EXECUTING = 1; + static constexpr uint8_t SUCCESS = 2; + static constexpr uint8_t ERROR = 3; +} + +#endif // EXECUTION_STATE_HPP diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp new file mode 100644 index 0000000000..273cec3f3c --- /dev/null +++ b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp @@ -0,0 +1,117 @@ +// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// +// Source of this file are templates in +// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// + +#ifndef MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#define MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ + +#include +#include +#include +#include + +#include "controller_interface/controller_interface.hpp" +#include +#include "motion_primitives_controller_pkg/visibility_control.h" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "realtime_tools/realtime_buffer.hpp" +#include "realtime_tools/realtime_publisher.hpp" + +#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "std_msgs/msg/int8.hpp" + + +namespace motion_primitives_controller_pkg +{ +// name constants for state interfaces +static constexpr size_t STATE_MY_ITFS = 0; + +// name constants for command interfaces +static constexpr size_t CMD_MY_ITFS = 0; + +class MotionPrimitivesForwardController : public controller_interface::ControllerInterface +{ +public: + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + MotionPrimitivesForwardController(); + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::CallbackReturn on_init() override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::CallbackReturn on_activate( + const rclcpp_lifecycle::State & previous_state) override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::CallbackReturn on_deactivate( + const rclcpp_lifecycle::State & previous_state) override; + + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC + controller_interface::return_type update( + const rclcpp::Time & time, const rclcpp::Duration & period) override; + + // state and command message types + using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; + using ControllerStateMsg = std_msgs::msg::Int8; + + +protected: + std::shared_ptr param_listener_; + motion_primitives_forward_controller::Params params_; + + // Command subscribers and Controller State publisher + rclcpp::Subscription::SharedPtr ref_subscriber_ = nullptr; + // realtime_tools::RealtimeBuffer> input_ref_; + + using ControllerStatePublisher = realtime_tools::RealtimePublisher; + + rclcpp::Publisher::SharedPtr s_publisher_; + std::unique_ptr state_publisher_; + +private: + // callback for topic interface + MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL + void reference_callback(const std::shared_ptr msg); // callback for reference message + // std::atomic new_msg_available_ = false; // flag to indicate if new message is available + void reset_command_interfaces(); // Reset all command interfaces to NaN() + bool set_command_interfaces(); // Set command interfaces from the message + + std::queue> msg_queue_; + size_t queue_size_ = 0; + + bool was_executing_{false}; // Flag to check if the robot was executing a motion command + bool was_stopped_{false}; // Flag to check if the robot was stopped + bool first_cmd_{true}; // Flag to check if the first command is sent + + bool print_error_once_ = true; // Flag to print error message only once if ExecutionState::ERROR +}; + +} // namespace motion_primitives_controller_pkg + +#endif // MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp new file mode 100644 index 0000000000..9a552043d0 --- /dev/null +++ b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp @@ -0,0 +1,13 @@ +#ifndef MOTION_TYPE_HPP +#define MOTION_TYPE_HPP + + +namespace MotionType +{ + static constexpr uint8_t LINEAR_JOINT = 10; // changed to 10 because 0 is default value + static constexpr uint8_t LINEAR_CARTESIAN = 50; + static constexpr uint8_t CIRCULAR_CARTESIAN = 51; + static constexpr uint8_t STOP_MOTION = 66; // added to stop motion +} + +#endif // MOTION_TYPE_HPP diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp new file mode 100644 index 0000000000..d9c55b99b9 --- /dev/null +++ b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp @@ -0,0 +1,43 @@ +// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// +// Source of this file are templates in +// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// + +#ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ + +#include + +#include "parameter_traits/parameter_traits.hpp" + +namespace parameter_traits +{ +Result forbidden_interface_name_prefix(rclcpp::Parameter const & parameter) +{ + auto const & interface_name = parameter.as_string(); + + if (interface_name.rfind("blup_", 0) == 0) + { + return ERROR("'interface_name' parameter can not start with 'blup_'"); + } + + return OK; +} + +} // namespace parameter_traits + +#endif // MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h new file mode 100644 index 0000000000..88afabcafa --- /dev/null +++ b/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h @@ -0,0 +1,54 @@ +// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// +// Source of this file are templates in +// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// + +#ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ +#ifdef __GNUC__ +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __attribute__((dllexport)) +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT __attribute__((dllimport)) +#else +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __declspec(dllexport) +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT __declspec(dllimport) +#endif +#ifdef MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_BUILDING_DLL +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT +#else +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT +#endif +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC_TYPE MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL +#else +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __attribute__((visibility("default"))) +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT +#if __GNUC__ >= 4 +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC __attribute__((visibility("default"))) +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL __attribute__((visibility("hidden"))) +#else +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL +#endif +#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC_TYPE +#endif + +#endif // MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos new file mode 100644 index 0000000000..1b3910e7e7 --- /dev/null +++ b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos @@ -0,0 +1,6 @@ +repositories: + ## EXAMPLE DEPENDENCY +# : +# type: git +# url: git@github.com:/.git +# version: master diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos new file mode 100644 index 0000000000..1b3910e7e7 --- /dev/null +++ b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos @@ -0,0 +1,6 @@ +repositories: + ## EXAMPLE DEPENDENCY +# : +# type: git +# url: git@github.com:/.git +# version: master diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml new file mode 100644 index 0000000000..a2abd194ae --- /dev/null +++ b/motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml @@ -0,0 +1,28 @@ + + + + + + MotionPrimitivesForwardController ros2_control controller. + + + diff --git a/motion_primitives_controller_pkg/package.xml b/motion_primitives_controller_pkg/package.xml new file mode 100644 index 0000000000..9f32bd1b7e --- /dev/null +++ b/motion_primitives_controller_pkg/package.xml @@ -0,0 +1,35 @@ + + + + motion_primitives_controller_pkg + 0.0.0 + Package to control robots using motion primitives like PTP, LIN and CIRC + mathias31415 + BSD-3-Clause + + ament_cmake + + generate_parameter_library + + control_msgs + + controller_interface + + hardware_interface + + pluginlib + + industrial_robot_motion_interfaces + + rclcpp + + rclcpp_lifecycle + + realtime_tools + + std_srvs + + + ament_cmake + + diff --git a/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp b/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp new file mode 100644 index 0000000000..a4d305a3b7 --- /dev/null +++ b/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp @@ -0,0 +1,429 @@ +// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// +// Source of this file are templates in +// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// + +#include "motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp" + +#include +#include +#include +#include + +#include "controller_interface/helpers.hpp" +#include "motion_primitives_controller_pkg/motion_type.hpp" +#include "motion_primitives_controller_pkg/execution_state.hpp" + + +namespace +{ // utility + +// TODO(destogl): remove this when merged upstream +// Changed services history QoS to keep all so we don't lose any client service calls +static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { + RMW_QOS_POLICY_HISTORY_KEEP_ALL, + 1, // message queue depth + RMW_QOS_POLICY_RELIABILITY_RELIABLE, + RMW_QOS_POLICY_DURABILITY_VOLATILE, + RMW_QOS_DEADLINE_DEFAULT, + RMW_QOS_LIFESPAN_DEFAULT, + RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, + RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, + false}; + +using ControllerReferenceMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerReferenceMsg; + +// reset the controller reference message to NaN +void reset_controller_reference_msg(std::shared_ptr & msg) +{ + msg->type = 0; + msg->blend_radius = std::numeric_limits::quiet_NaN(); + + for (auto & arg : msg->additional_arguments) { + arg.argument_name = ""; + arg.argument_value = std::numeric_limits::quiet_NaN(); + } + + for (auto & pose : msg->poses) { + pose.pose.position.x = std::numeric_limits::quiet_NaN(); + pose.pose.position.y = std::numeric_limits::quiet_NaN(); + pose.pose.position.z = std::numeric_limits::quiet_NaN(); + + pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); + } +} + +} // namespace + + +namespace motion_primitives_controller_pkg +{ +MotionPrimitivesForwardController::MotionPrimitivesForwardController() : controller_interface::ControllerInterface() {} + +controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init() +{ + RCLCPP_INFO(get_node()->get_logger(), "Initializing Motion Primitives Forward Controller"); + + try + { + param_listener_ = std::make_shared(get_node()); + } + catch (const std::exception & e) + { + fprintf(stderr, "Exception thrown during controller's init with message: %s \n", e.what()); + return controller_interface::CallbackReturn::ERROR; + } + + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn MotionPrimitivesForwardController::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + RCLCPP_INFO(get_node()->get_logger(), "Configuring Motion Primitives Forward Controller"); + + params_ = param_listener_->get_params(); + + // Check if the name is not empty + if (params_.name.empty()) { + RCLCPP_ERROR(get_node()->get_logger(), "Error: A name must be provided!"); + return controller_interface::CallbackReturn::ERROR; + } + + // Check if there are exactly 18 command interfaces + if (params_.command_interfaces.size() !=25) { // 1 status + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time + RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly 25 command interfaces must be provided!"); + return controller_interface::CallbackReturn::ERROR; + } + + // Check if there is exactly one state interface + if (params_.state_interfaces.size() != 1) { + RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly one state interface must be provided!"); + return controller_interface::CallbackReturn::ERROR; + } + + // topics QoS + auto subscribers_qos = rclcpp::SystemDefaultsQoS(); + subscribers_qos.keep_last(1); + subscribers_qos.best_effort(); + + // Reference Subscriber + ref_subscriber_ = get_node()->create_subscription( + "~/reference", subscribers_qos, + std::bind(&MotionPrimitivesForwardController::reference_callback, this, std::placeholders::_1)); + + std::shared_ptr msg = std::make_shared(); + reset_controller_reference_msg(msg); + + queue_size_ = params_.queue_size; + if (queue_size_ == 0) { + RCLCPP_ERROR(get_node()->get_logger(), "Error: Queue size must be greater than 0!"); + return controller_interface::CallbackReturn::ERROR; + } + + try + { + // State publisher + s_publisher_ = + get_node()->create_publisher("~/state", rclcpp::SystemDefaultsQoS()); + state_publisher_ = std::make_unique(s_publisher_); + } + catch (const std::exception & e) + { + fprintf( + stderr, "Exception thrown during publisher creation at configure stage with message : %s \n", + e.what()); + return controller_interface::CallbackReturn::ERROR; + } + + RCLCPP_INFO(get_node()->get_logger(), "configure successful"); + return controller_interface::CallbackReturn::SUCCESS; +} + +// Function gets called when a new message is received +void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr msg) +{ + // Check if the type is one of the allowed motion types + switch (msg->type) + { + case MotionType::STOP_MOTION: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); + reset_command_interfaces(); // Reset all command interfaces to NaN + // TODO(mathias31415): Use mutex? + (void)command_interfaces_[0].set_value(static_cast(msg->type)); // send stop command to the driver + while (!msg_queue_.empty()) { // clear the queue + msg_queue_.pop(); + } + was_stopped_ = true; + return; + + case MotionType::LINEAR_JOINT: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); + // Check if joint positions are provided + if (msg->joint_positions.empty()) { + RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_JOINT motion type without joint positions"); + return; + } + break; + + case MotionType::LINEAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_CARTESIAN (LIN)"); + // Check if poses are provided + if (msg->poses.empty()) { + RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_CARTESIAN motion type without poses"); + return; + } + break; + + case MotionType::CIRCULAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: CIRCULAR_CARTESIAN (CIRC)"); + // Check if poses are provided + if (msg->poses.size() != 2) { + RCLCPP_ERROR(get_node()->get_logger(), "Received CIRCULAR_CARTESIAN motion type without two poses"); + return; + } + break; + + case 33: // TODO(mathias31415): remove case 33 block with hardcoded motion sequence, only for testing + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: 33 (testing hardcoded motion sequence)"); + break; + + // Additional motion types can be added here + default: + RCLCPP_ERROR(get_node()->get_logger(), "Received unknown motion type: %u", msg->type); + return; + } + + // Check if the queue size is exceeded + if (msg_queue_.size() >= queue_size_) { + RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); + return; + } + + msg_queue_.push(msg); +} + + +controller_interface::InterfaceConfiguration MotionPrimitivesForwardController::command_interface_configuration() const +{ + controller_interface::InterfaceConfiguration command_interfaces_config; + command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + // Reserve memory for the command interfaces + command_interfaces_config.names.reserve(params_.command_interfaces.size()); + + // Iterate over all command interfaces from the config yaml file + for (const auto & interface_name : params_.command_interfaces) + { + // Combine the joint with the interface name and add it to the list + command_interfaces_config.names.push_back(params_.name + "/" + interface_name); + } + return command_interfaces_config; +} + +controller_interface::InterfaceConfiguration MotionPrimitivesForwardController::state_interface_configuration() const +{ + controller_interface::InterfaceConfiguration state_interfaces_config; + state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + // Reserve memory for the state interfaces + state_interfaces_config.names.reserve(params_.state_interfaces.size()); + + // Iterate over all state interfaces from the config yaml file + for (const auto & interface_name : params_.state_interfaces) + { + // Combine the joint with the interface name and add it to the list + state_interfaces_config.names.push_back(params_.name + "/" + interface_name); + } + return state_interfaces_config; +} + +controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + reset_command_interfaces(); // Reset all command interfaces to NaN + RCLCPP_INFO(get_node()->get_logger(), "Controller activated"); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn MotionPrimitivesForwardController::on_deactivate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + reset_command_interfaces(); // Reset all command interfaces to NaN + RCLCPP_INFO(get_node()->get_logger(), "Controller deactivated"); + return controller_interface::CallbackReturn::SUCCESS; +} + + +controller_interface::return_type MotionPrimitivesForwardController::update( + const rclcpp::Time & time, const rclcpp::Duration & /*period*/) +{ + // read the status from the state interface + // TODO(mathias31415) Is check needed if the value is .0? + uint8_t execution_status = static_cast(std::round(state_interfaces_[0].get_value())); + + // publish the state + state_publisher_->lock(); + state_publisher_->msg_.data = execution_status; + state_publisher_->unlockAndPublish(); + + if(!msg_queue_.empty()) + { + switch (execution_status) { + case ExecutionState::IDLE: // no motion primitive sent yet + print_error_once_ = true; + if(first_cmd_ || was_executing_ || was_stopped_){ + if(!set_command_interfaces()){ // Set the command interfaces with the current reference message + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; + } + first_cmd_ = false; + was_executing_ = false; + was_stopped_ = false; + } + return controller_interface::return_type::OK; + + case ExecutionState::EXECUTING: // executing + if(!was_executing_){ + was_executing_ = true; + } + return controller_interface::return_type::OK; + + case ExecutionState::SUCCESS: // success + print_error_once_ = true; + if(was_executing_){ + was_executing_ = false; + if(!set_command_interfaces()){ // Set the command interfaces with the current reference message + return controller_interface::return_type::ERROR; + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + } + } + return controller_interface::return_type::OK; + + case ExecutionState::ERROR: // error + if(print_error_once_){ + print_error_once_ = false; + RCLCPP_ERROR(get_node()->get_logger(), "Error: Can't send new command, execution status is ERROR"); + } + return controller_interface::return_type::OK; + + default: + RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); + return controller_interface::return_type::ERROR; + } + } + return controller_interface::return_type::OK; +} + +// Reset Command-Interfaces to nan +void MotionPrimitivesForwardController::reset_command_interfaces() +{ + for (size_t i = 0; i < command_interfaces_.size(); ++i) + { + if (!command_interfaces_[i].set_value(std::numeric_limits::quiet_NaN())) { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to reset command interface %ld", i); + } + } +} + +// Set command interfaces from the message, gets called in the update function +bool MotionPrimitivesForwardController::set_command_interfaces() +{ + // Get the oldest message from the queue + std::shared_ptr current_ref = msg_queue_.front(); + msg_queue_.pop(); + + // Check if the message is valid + if (!current_ref){ + RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); + return false; + } + + // Set the motion_type + (void)command_interfaces_[0].set_value(static_cast(current_ref->type)); + + // Process joint positions if available + if (!current_ref->joint_positions.empty()) + { + for (size_t i = 0; i < current_ref->joint_positions.size(); ++i) + { + (void)command_interfaces_[i + 1].set_value(current_ref->joint_positions[i]); // q1 to q6 + } + } + + // Process Cartesian poses if available + if (!current_ref->poses.empty()) + { + const auto & goal_pose = current_ref->poses[0].pose; // goal pose + (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x + (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y + (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z + (void)command_interfaces_[10].set_value(goal_pose.orientation.x); // pos_qx + (void)command_interfaces_[11].set_value(goal_pose.orientation.y); // pos_qy + (void)command_interfaces_[12].set_value(goal_pose.orientation.z); // pos_qz + (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw + + // Process via poses if available (only for circular motion) + if (current_ref->type == MotionType::CIRCULAR_CARTESIAN && current_ref->poses.size() == 2) + { + const auto & via_pose = current_ref->poses[1].pose; // via pose + (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x + (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y + (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z + (void)command_interfaces_[17].set_value(via_pose.orientation.x); // pos_via_qx + (void)command_interfaces_[18].set_value(via_pose.orientation.y); // pos_via_qy + (void)command_interfaces_[19].set_value(via_pose.orientation.z); // pos_via_qz + (void)command_interfaces_[20].set_value(via_pose.orientation.w); // pos_via_qw + } + } + + // Set blend_radius + (void)command_interfaces_[21].set_value(current_ref->blend_radius); // blend_radius + + // Read additional arguments + for (const auto &arg : current_ref->additional_arguments) + { + if (arg.argument_name == "velocity") + { + (void)command_interfaces_[22].set_value(arg.argument_value); + } + else if (arg.argument_name == "acceleration") + { + (void)command_interfaces_[23].set_value(arg.argument_value); + } + else if (arg.argument_name == "move_time") + { + (void)command_interfaces_[24].set_value(arg.argument_value); + } + else + { + RCLCPP_WARN(get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); + } + } + return true; +} + + +} // namespace motion_primitives_controller_pkg + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + motion_primitives_controller_pkg::MotionPrimitivesForwardController, controller_interface::ControllerInterface) diff --git a/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml b/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml new file mode 100644 index 0000000000..8c4ec46897 --- /dev/null +++ b/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml @@ -0,0 +1,52 @@ +# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# +# Source of this file are templates in +# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. + + +motion_primitives_forward_controller: + name: { + type: string, + default_value: "", + description: "Name for /", + read_only: true, + } + command_interfaces: { + type: string_array, + default_value: [], + description: "Names of the command interfaces used by the controller.", + read_only: true, + validation: { + unique<>: null, + not_empty<>: null, + } + } + state_interfaces: { + type: string_array, + default_value: [], + description: "Names of the state interfaces used by the controller.", + read_only: true, + validation: { + unique<>: null, + not_empty<>: null, + } + } + queue_size: { + type: int, + default_value: 10, + description: "Queue size to buffer incoming commands", + read_only: true, + } diff --git a/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml new file mode 100644 index 0000000000..6be68ba92e --- /dev/null +++ b/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml @@ -0,0 +1,26 @@ +# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# +# Source of this file are templates in +# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +# + +test_motion_primitives_forward_controller: + ros__parameters: + + joints: + - joint1 + + interface_name: acceleration diff --git a/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml new file mode 100644 index 0000000000..1bcadb0c65 --- /dev/null +++ b/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -0,0 +1,28 @@ +# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +# +# Source of this file are templates in +# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +# + +test_motion_primitives_forward_controller: + ros__parameters: + joints: + - joint1 + + interface_name: acceleration + + state_joints: + - joint1state diff --git a/motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp b/motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp new file mode 100644 index 0000000000..c660587acc --- /dev/null +++ b/motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp @@ -0,0 +1,44 @@ +// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// +// Source of this file are templates in +// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// + +#include +#include + +#include "controller_manager/controller_manager.hpp" +#include "hardware_interface/resource_manager.hpp" +#include "rclcpp/executor.hpp" +#include "rclcpp/executors/single_threaded_executor.hpp" +#include "rclcpp/utilities.hpp" +#include "ros2_control_test_assets/descriptions.hpp" + +TEST(TestLoadMotionPrimitivesForwardController, load_controller) +{ + rclcpp::init(0, nullptr); + + std::shared_ptr executor = + std::make_shared(); + + controller_manager::ControllerManager cm( + executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager"); + + ASSERT_NO_THROW( + cm.load_controller("test_motion_primitives_controller_pkg", "motion_primitives_controller_pkg/MotionPrimitivesForwardController")); + + rclcpp::shutdown(); +} diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp new file mode 100644 index 0000000000..de939ba81b --- /dev/null +++ b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp @@ -0,0 +1,277 @@ +// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// // +// // Licensed under the Apache License, Version 2.0 (the "License"); +// // you may not use this file except in compliance with the License. +// // You may obtain a copy of the License at +// // +// // http://www.apache.org/licenses/LICENSE-2.0 +// // +// // Unless required by applicable law or agreed to in writing, software +// // distributed under the License is distributed on an "AS IS" BASIS, +// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// // See the License for the specific language governing permissions and +// // limitations under the License. + +// // +// // Source of this file are templates in +// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// // + +// #include +// #include +// #include +// #include +// #include + +// #include "rclcpp/rclcpp.hpp" +// #include "test_motion_primitives_forward_controller.hpp" + +// using motion_primitives_controller_pkg::CMD_MY_ITFS; +// using motion_primitives_controller_pkg::control_mode_type; +// using motion_primitives_controller_pkg::STATE_MY_ITFS; + +// class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +// { +// }; + +// TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) +// { +// SetUpController(); + +// ASSERT_TRUE(controller_->params_.joints.empty()); +// ASSERT_TRUE(controller_->params_.state_joints.empty()); +// ASSERT_TRUE(controller_->params_.interface_name.empty()); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); +// ASSERT_TRUE(controller_->params_.state_joints.empty()); +// ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(joint_names_)); +// ASSERT_EQ(controller_->params_.interface_name, interface_name_); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// auto command_intefaces = controller_->command_interface_configuration(); +// ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); +// for (size_t i = 0; i < command_intefaces.names.size(); ++i) +// { +// EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); +// } + +// auto state_intefaces = controller_->state_interface_configuration(); +// ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); +// for (size_t i = 0; i < state_intefaces.names.size(); ++i) +// { +// EXPECT_EQ(state_intefaces.names[i], joint_names_[i] + "/" + interface_name_); +// } +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, activate_success) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// // check that the message is reset +// auto msg = controller_->input_ref_.readFromNonRT(); +// EXPECT_EQ((*msg)->displacements.size(), joint_names_.size()); +// for (const auto & cmd : (*msg)->displacements) +// { +// EXPECT_TRUE(std::isnan(cmd)); +// } +// EXPECT_EQ((*msg)->velocities.size(), joint_names_.size()); +// for (const auto & cmd : (*msg)->velocities) +// { +// EXPECT_TRUE(std::isnan(cmd)); +// } + +// ASSERT_TRUE(std::isnan((*msg)->duration)); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, update_success) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, deactivate_success) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->command_interfaces_[CMD_MY_ITFS].get_value(), 101.101); +// ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service) +// { +// SetUpController(); + +// rclcpp::executors::MultiThreadedExecutor executor; +// executor.add_node(controller_->get_node()->get_node_base_interface()); +// executor.add_node(service_caller_node_->get_node_base_interface()); + +// // initially set to false +// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// // should stay false +// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); + +// // set to true +// ASSERT_NO_THROW(call_service(true, executor)); +// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); + +// // set back to false +// ASSERT_NO_THROW(call_service(false, executor)); +// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_fast) +// { +// SetUpController(); +// rclcpp::executors::MultiThreadedExecutor executor; +// executor.add_node(controller_->get_node()->get_node_base_interface()); +// executor.add_node(service_caller_node_->get_node_base_interface()); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// // set command statically +// static constexpr double TEST_DISPLACEMENT = 23.24; +// std::shared_ptr msg = std::make_shared(); +// msg->joint_names = joint_names_; +// msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); +// msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); +// msg->duration = std::numeric_limits::quiet_NaN(); +// controller_->input_ref_.writeFromNonRT(msg); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); +// EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT); +// EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); +// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_slow) +// { +// SetUpController(); +// rclcpp::executors::MultiThreadedExecutor executor; +// executor.add_node(controller_->get_node()->get_node_base_interface()); +// executor.add_node(service_caller_node_->get_node_base_interface()); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// // set command statically +// static constexpr double TEST_DISPLACEMENT = 23.24; +// std::shared_ptr msg = std::make_shared(); +// // When slow mode is enabled command ends up being half of the value +// msg->joint_names = joint_names_; +// msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); +// msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); +// msg->duration = std::numeric_limits::quiet_NaN(); +// controller_->input_ref_.writeFromNonRT(msg); +// controller_->control_mode_.writeFromNonRT(control_mode_type::SLOW); + +// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); +// ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->displacements[0], TEST_DISPLACEMENT); +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT / 2); +// EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// ControllerStateMsg msg; +// subscribe_and_get_messages(msg); + +// ASSERT_EQ(msg.set_point, 101.101); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status) +// { +// SetUpController(); +// rclcpp::executors::MultiThreadedExecutor executor; +// executor.add_node(controller_->get_node()->get_node_base_interface()); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); +// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// ControllerStateMsg msg; +// subscribe_and_get_messages(msg); + +// ASSERT_EQ(msg.set_point, 101.101); + +// publish_commands(); +// ASSERT_TRUE(controller_->wait_for_commands(executor)); + +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// EXPECT_EQ(joint_command_values_[CMD_MY_ITFS], 0.45); + +// subscribe_and_get_messages(msg); + +// ASSERT_EQ(msg.set_point, 0.45); +// } + +// int main(int argc, char ** argv) +// { +// ::testing::InitGoogleTest(&argc, argv); +// rclcpp::init(argc, argv); +// int result = RUN_ALL_TESTS(); +// rclcpp::shutdown(); +// return result; +// } diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp new file mode 100644 index 0000000000..61b72494a1 --- /dev/null +++ b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp @@ -0,0 +1,274 @@ +// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// // +// // Licensed under the Apache License, Version 2.0 (the "License"); +// // you may not use this file except in compliance with the License. +// // You may obtain a copy of the License at +// // +// // http://www.apache.org/licenses/LICENSE-2.0 +// // +// // Unless required by applicable law or agreed to in writing, software +// // distributed under the License is distributed on an "AS IS" BASIS, +// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// // See the License for the specific language governing permissions and +// // limitations under the License. + +// // +// // Source of this file are templates in +// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// // + +// #ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +// #define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ + +// #include +// #include +// #include +// #include +// #include +// #include +// #include + +// #include "motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp" +// #include "gmock/gmock.h" +// #include "hardware_interface/loaned_command_interface.hpp" +// #include "hardware_interface/loaned_state_interface.hpp" +// #include "hardware_interface/types/hardware_interface_return_values.hpp" +// #include "rclcpp/executor.hpp" +// #include "rclcpp/parameter_value.hpp" +// #include "rclcpp/time.hpp" +// #include "rclcpp/utilities.hpp" +// #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" + +// // TODO(anyone): replace the state and command message types +// using ControllerStateMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerStateMsg; +// using ControllerReferenceMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerReferenceMsg; +// using ControllerModeSrvType = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerModeSrvType; + +// namespace +// { +// constexpr auto NODE_SUCCESS = controller_interface::CallbackReturn::SUCCESS; +// constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR; +// } // namespace + +// // subclassing and friending so we can access member variables +// class TestableMotionPrimitivesForwardController : public motion_primitives_controller_pkg::MotionPrimitivesForwardController +// { +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service); +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_fast); +// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_slow); + +// public: +// controller_interface::CallbackReturn on_configure( +// const rclcpp_lifecycle::State & previous_state) override +// { +// auto ret = motion_primitives_controller_pkg::MotionPrimitivesForwardController::on_configure(previous_state); +// // Only if on_configure is successful create subscription +// if (ret == CallbackReturn::SUCCESS) +// { +// ref_subscriber_wait_set_.add_subscription(ref_subscriber_); +// } +// return ret; +// } + +// /** +// * @brief wait_for_command blocks until a new ControllerReferenceMsg is received. +// * Requires that the executor is not spinned elsewhere between the +// * message publication and the call to this function. +// * +// * @return true if new ControllerReferenceMsg msg was received, false if timeout. +// */ +// bool wait_for_command( +// rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set, +// const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) +// { +// bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready; +// if (success) +// { +// executor.spin_some(); +// } +// return success; +// } + +// bool wait_for_commands( +// rclcpp::Executor & executor, +// const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) +// { +// return wait_for_command(executor, ref_subscriber_wait_set_, timeout); +// } + +// // TODO(anyone): add implementation of any methods of your controller is needed + +// private: +// rclcpp::WaitSet ref_subscriber_wait_set_; +// }; + +// // We are using template class here for easier reuse of Fixture in specializations of controllers +// template +// class MotionPrimitivesForwardControllerFixture : public ::testing::Test +// { +// public: +// static void SetUpTestCase() {} + +// void SetUp() +// { +// // initialize controller +// controller_ = std::make_unique(); + +// command_publisher_node_ = std::make_shared("command_publisher"); +// command_publisher_ = command_publisher_node_->create_publisher( +// "/test_motion_primitives_forward_controller/commands", rclcpp::SystemDefaultsQoS()); + +// service_caller_node_ = std::make_shared("service_caller"); +// slow_control_service_client_ = service_caller_node_->create_client( +// "/test_motion_primitives_forward_controller/set_slow_control_mode"); +// } + +// static void TearDownTestCase() {} + +// void TearDown() { controller_.reset(nullptr); } + +// protected: +// void SetUpController(const std::string controller_name = "test_motion_primitives_forward_controller") +// { +// ASSERT_EQ( +// controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()), +// controller_interface::return_type::OK); + +// std::vector command_ifs; +// command_itfs_.reserve(joint_command_values_.size()); +// command_ifs.reserve(joint_command_values_.size()); + +// for (size_t i = 0; i < joint_command_values_.size(); ++i) +// { +// command_itfs_.emplace_back(hardware_interface::CommandInterface( +// joint_names_[i], interface_name_, &joint_command_values_[i])); +// command_ifs.emplace_back(command_itfs_.back()); +// } +// // TODO(anyone): Add other command interfaces, if any + +// std::vector state_ifs; +// state_itfs_.reserve(joint_state_values_.size()); +// state_ifs.reserve(joint_state_values_.size()); + +// for (size_t i = 0; i < joint_state_values_.size(); ++i) +// { +// state_itfs_.emplace_back(hardware_interface::StateInterface( +// joint_names_[i], interface_name_, &joint_state_values_[i])); +// state_ifs.emplace_back(state_itfs_.back()); +// } +// // TODO(anyone): Add other state interfaces, if any + +// controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); +// } + +// void subscribe_and_get_messages(ControllerStateMsg & msg) +// { +// // create a new subscriber +// rclcpp::Node test_subscription_node("test_subscription_node"); +// auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {}; +// auto subscription = test_subscription_node.create_subscription( +// "/test_motion_primitives_forward_controller/state", 10, subs_callback); + +// // call update to publish the test value +// ASSERT_EQ( +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), +// controller_interface::return_type::OK); + +// // call update to publish the test value +// // since update doesn't guarantee a published message, republish until received +// int max_sub_check_loop_count = 5; // max number of tries for pub/sub loop +// rclcpp::WaitSet wait_set; // block used to wait on message +// wait_set.add_subscription(subscription); +// while (max_sub_check_loop_count--) +// { +// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); +// // check if message has been received +// if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready) +// { +// break; +// } +// } +// ASSERT_GE(max_sub_check_loop_count, 0) << "Test was unable to publish a message through " +// "controller/broadcaster update loop"; + +// // take message from subscription +// rclcpp::MessageInfo msg_info; +// ASSERT_TRUE(subscription->take(msg, msg_info)); +// } + +// // TODO(anyone): add/remove arguments as it suites your command message type +// void publish_commands( +// const std::vector & displacements = {0.45}, +// const std::vector & velocities = {0.0}, const double duration = 1.25) +// { +// auto wait_for_topic = [&](const auto topic_name) +// { +// size_t wait_count = 0; +// while (command_publisher_node_->count_subscribers(topic_name) == 0) +// { +// if (wait_count >= 5) +// { +// auto error_msg = +// std::string("publishing to ") + topic_name + " but no node subscribes to it"; +// throw std::runtime_error(error_msg); +// } +// std::this_thread::sleep_for(std::chrono::milliseconds(100)); +// ++wait_count; +// } +// }; + +// wait_for_topic(command_publisher_->get_topic_name()); + +// ControllerReferenceMsg msg; +// msg.joint_names = joint_names_; +// msg.displacements = displacements; +// msg.velocities = velocities; +// msg.duration = duration; + +// command_publisher_->publish(msg); +// } + +// std::shared_ptr call_service( +// const bool slow_control, rclcpp::Executor & executor) +// { +// auto request = std::make_shared(); +// request->data = slow_control; + +// bool wait_for_service_ret = +// slow_control_service_client_->wait_for_service(std::chrono::milliseconds(500)); +// EXPECT_TRUE(wait_for_service_ret); +// if (!wait_for_service_ret) +// { +// throw std::runtime_error("Services is not available!"); +// } +// auto result = slow_control_service_client_->async_send_request(request); +// EXPECT_EQ(executor.spin_until_future_complete(result), rclcpp::FutureReturnCode::SUCCESS); + +// return result.get(); +// } + +// protected: +// // TODO(anyone): adjust the members as needed + +// // Controller-related parameters +// std::vector joint_names_ = {"joint1"}; +// std::vector state_joint_names_ = {"joint1state"}; +// std::string interface_name_ = "acceleration"; +// std::array joint_state_values_ = {1.1}; +// std::array joint_command_values_ = {101.101}; + +// std::vector state_itfs_; +// std::vector command_itfs_; + +// // Test related parameters +// std::unique_ptr controller_; +// rclcpp::Node::SharedPtr command_publisher_node_; +// rclcpp::Publisher::SharedPtr command_publisher_; +// rclcpp::Node::SharedPtr service_caller_node_; +// rclcpp::Client::SharedPtr slow_control_service_client_; +// }; + +// #endif // TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp new file mode 100644 index 0000000000..2699961d58 --- /dev/null +++ b/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -0,0 +1,80 @@ +// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// // +// // Licensed under the Apache License, Version 2.0 (the "License"); +// // you may not use this file except in compliance with the License. +// // You may obtain a copy of the License at +// // +// // http://www.apache.org/licenses/LICENSE-2.0 +// // +// // Unless required by applicable law or agreed to in writing, software +// // distributed under the License is distributed on an "AS IS" BASIS, +// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// // See the License for the specific language governing permissions and +// // limitations under the License. + +// // +// // Source of this file are templates in +// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// // + +// #include "test_motion_primitives_forward_controller.hpp" + +// #include +// #include +// #include +// #include +// #include + +// using motion_primitives_controller_pkg::CMD_MY_ITFS; +// using motion_primitives_controller_pkg::control_mode_type; +// using motion_primitives_controller_pkg::STATE_MY_ITFS; + +// class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +// { +// }; + +// TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) +// { +// SetUpController(); + +// ASSERT_TRUE(controller_->params_.joints.empty()); +// ASSERT_TRUE(controller_->params_.state_joints.empty()); +// ASSERT_TRUE(controller_->params_.interface_name.empty()); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); +// ASSERT_THAT(controller_->params_.state_joints, testing::ElementsAreArray(state_joint_names_)); +// ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(state_joint_names_)); +// ASSERT_EQ(controller_->params_.interface_name, interface_name_); +// } + +// TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +// { +// SetUpController(); + +// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + +// auto command_intefaces = controller_->command_interface_configuration(); +// ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); +// for (size_t i = 0; i < command_intefaces.names.size(); ++i) +// { +// EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); +// } + +// auto state_intefaces = controller_->state_interface_configuration(); +// ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); +// for (size_t i = 0; i < state_intefaces.names.size(); ++i) +// { +// EXPECT_EQ(state_intefaces.names[i], state_joint_names_[i] + "/" + interface_name_); +// } +// } + +// int main(int argc, char ** argv) +// { +// ::testing::InitGoogleTest(&argc, argv); +// rclcpp::init(argc, argv); +// int result = RUN_ALL_TESTS(); +// rclcpp::shutdown(); +// return result; +// } From 6ed1181f75c1f7f4692ae707288213b8f2e7ae1e Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Apr 2025 15:25:01 +0200 Subject: [PATCH 003/128] renamed motion_primitives_controller_pkg to motion_primitives_forward_controller --- .../CMakeLists.txt | 6 +++--- .../LICENSE | 0 .../README.md | 2 +- .../execution_state.hpp | 0 .../motion_primitives_forward_controller.hpp | 14 +++++++------- .../motion_type.hpp | 0 ...on_primitives_forward_controller_parameters.hpp | 0 .../visibility_control.h | 0 ...rimitives_controller_pkg.rolling.upstream.repos | 0 ...ion_primitives_forward_controller.rolling.repos | 0 .../motion_primitives_forward_controller.xml | 4 ++-- .../package.xml | 2 +- .../src/motion_primitives_forward_controller.cpp | 14 +++++++------- .../src/motion_primitives_forward_controller.yaml | 0 ...otion_primitives_forward_controller_params.yaml | 0 ...tives_forward_controller_preceeding_params.yaml | 0 ...t_load_motion_primitives_forward_controller.cpp | 2 +- .../test_motion_primitives_forward_controller.cpp | 6 +++--- .../test_motion_primitives_forward_controller.hpp | 12 ++++++------ ...on_primitives_forward_controller_preceeding.cpp | 6 +++--- 20 files changed, 34 insertions(+), 34 deletions(-) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/CMakeLists.txt (94%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/LICENSE (100%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/README.md (83%) rename {motion_primitives_controller_pkg/include/motion_primitives_controller_pkg => motion_primitives_forward_controller/include/motion_primitives_forward_controller}/execution_state.hpp (100%) rename {motion_primitives_controller_pkg/include/motion_primitives_controller_pkg => motion_primitives_forward_controller/include/motion_primitives_forward_controller}/motion_primitives_forward_controller.hpp (89%) rename {motion_primitives_controller_pkg/include/motion_primitives_controller_pkg => motion_primitives_forward_controller/include/motion_primitives_forward_controller}/motion_type.hpp (100%) rename {motion_primitives_controller_pkg/include/motion_primitives_controller_pkg => motion_primitives_forward_controller/include/motion_primitives_forward_controller}/validate_motion_primitives_forward_controller_parameters.hpp (100%) rename {motion_primitives_controller_pkg/include/motion_primitives_controller_pkg => motion_primitives_forward_controller/include/motion_primitives_forward_controller}/visibility_control.h (100%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/motion_primitives_controller_pkg.rolling.upstream.repos (100%) rename motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos => motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos (100%) rename motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml => motion_primitives_forward_controller/motion_primitives_forward_controller.xml (79%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/package.xml (94%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/src/motion_primitives_forward_controller.cpp (96%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/src/motion_primitives_forward_controller.yaml (100%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/motion_primitives_forward_controller_params.yaml (100%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/motion_primitives_forward_controller_preceeding_params.yaml (100%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/test_load_motion_primitives_forward_controller.cpp (91%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/test_motion_primitives_forward_controller.cpp (98%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/test_motion_primitives_forward_controller.hpp (94%) rename {motion_primitives_controller_pkg => motion_primitives_forward_controller}/test/test_motion_primitives_forward_controller_preceeding.cpp (93%) diff --git a/motion_primitives_controller_pkg/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt similarity index 94% rename from motion_primitives_controller_pkg/CMakeLists.txt rename to motion_primitives_forward_controller/CMakeLists.txt index 4ac8f424c8..c73778c958 100644 --- a/motion_primitives_controller_pkg/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 3.8) -project(motion_primitives_controller_pkg) +project(motion_primitives_forward_controller) if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) @@ -31,7 +31,7 @@ endforeach() # Add motion_primitives_forward_controller library related compile commands generate_parameter_library(motion_primitives_forward_controller_parameters src/motion_primitives_forward_controller.yaml - include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp + include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp ) add_library( motion_primitives_forward_controller @@ -49,7 +49,7 @@ ament_target_dependencies(motion_primitives_forward_controller target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") pluginlib_export_plugin_description_file( - controller_interface motion_primitives_controller_pkg.xml) + controller_interface motion_primitives_forward_controller.xml) install( TARGETS diff --git a/motion_primitives_controller_pkg/LICENSE b/motion_primitives_forward_controller/LICENSE similarity index 100% rename from motion_primitives_controller_pkg/LICENSE rename to motion_primitives_forward_controller/LICENSE diff --git a/motion_primitives_controller_pkg/README.md b/motion_primitives_forward_controller/README.md similarity index 83% rename from motion_primitives_controller_pkg/README.md rename to motion_primitives_forward_controller/README.md index dd7e2ae218..2a7aba8649 100644 --- a/motion_primitives_controller_pkg/README.md +++ b/motion_primitives_forward_controller/README.md @@ -1,4 +1,4 @@ -motion_primitives_controller_pkg +motion_primitives_forward_controller ========================================== Package to control robots using motion primitives like PTP, LIN and CIRC diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp similarity index 100% rename from motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/execution_state.hpp rename to motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp similarity index 89% rename from motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp rename to motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 273cec3f3c..9924017d48 100644 --- a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -17,8 +17,8 @@ // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. // -#ifndef MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ -#define MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #include #include @@ -26,8 +26,8 @@ #include #include "controller_interface/controller_interface.hpp" -#include -#include "motion_primitives_controller_pkg/visibility_control.h" +#include +#include "motion_primitives_forward_controller/visibility_control.h" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" @@ -37,7 +37,7 @@ #include "std_msgs/msg/int8.hpp" -namespace motion_primitives_controller_pkg +namespace motion_primitives_forward_controller { // name constants for state interfaces static constexpr size_t STATE_MY_ITFS = 0; @@ -112,6 +112,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool print_error_once_ = true; // Flag to print error message only once if ExecutionState::ERROR }; -} // namespace motion_primitives_controller_pkg +} // namespace motion_primitives_forward_controller -#endif // MOTION_PRIMITIVES_CONTROLLER_PKG__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp similarity index 100% rename from motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/motion_type.hpp rename to motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp similarity index 100% rename from motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/validate_motion_primitives_forward_controller_parameters.hpp rename to motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp diff --git a/motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h similarity index 100% rename from motion_primitives_controller_pkg/include/motion_primitives_controller_pkg/visibility_control.h rename to motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos b/motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos similarity index 100% rename from motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.upstream.repos rename to motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos b/motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos similarity index 100% rename from motion_primitives_controller_pkg/motion_primitives_controller_pkg.rolling.repos rename to motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos diff --git a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml b/motion_primitives_forward_controller/motion_primitives_forward_controller.xml similarity index 79% rename from motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml rename to motion_primitives_forward_controller/motion_primitives_forward_controller.xml index a2abd194ae..1d9ac20e10 100644 --- a/motion_primitives_controller_pkg/motion_primitives_controller_pkg.xml +++ b/motion_primitives_forward_controller/motion_primitives_forward_controller.xml @@ -19,8 +19,8 @@ Source of this file are templates in --> - + MotionPrimitivesForwardController ros2_control controller. diff --git a/motion_primitives_controller_pkg/package.xml b/motion_primitives_forward_controller/package.xml similarity index 94% rename from motion_primitives_controller_pkg/package.xml rename to motion_primitives_forward_controller/package.xml index 9f32bd1b7e..1265dac284 100644 --- a/motion_primitives_controller_pkg/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -1,7 +1,7 @@ - motion_primitives_controller_pkg + motion_primitives_forward_controller 0.0.0 Package to control robots using motion primitives like PTP, LIN and CIRC mathias31415 diff --git a/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp similarity index 96% rename from motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp rename to motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index a4d305a3b7..4067fd88cc 100644 --- a/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -17,7 +17,7 @@ // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. // -#include "motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp" +#include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" #include #include @@ -25,8 +25,8 @@ #include #include "controller_interface/helpers.hpp" -#include "motion_primitives_controller_pkg/motion_type.hpp" -#include "motion_primitives_controller_pkg/execution_state.hpp" +#include "motion_primitives_forward_controller/motion_type.hpp" +#include "motion_primitives_forward_controller/execution_state.hpp" namespace @@ -45,7 +45,7 @@ static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, false}; -using ControllerReferenceMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerReferenceMsg; +using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; // reset the controller reference message to NaN void reset_controller_reference_msg(std::shared_ptr & msg) @@ -73,7 +73,7 @@ void reset_controller_reference_msg(std::shared_ptr & ms } // namespace -namespace motion_primitives_controller_pkg +namespace motion_primitives_forward_controller { MotionPrimitivesForwardController::MotionPrimitivesForwardController() : controller_interface::ControllerInterface() {} @@ -421,9 +421,9 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } -} // namespace motion_primitives_controller_pkg +} // namespace motion_primitives_forward_controller #include "pluginlib/class_list_macros.hpp" PLUGINLIB_EXPORT_CLASS( - motion_primitives_controller_pkg::MotionPrimitivesForwardController, controller_interface::ControllerInterface) + motion_primitives_forward_controller::MotionPrimitivesForwardController, controller_interface::ControllerInterface) diff --git a/motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml similarity index 100% rename from motion_primitives_controller_pkg/src/motion_primitives_forward_controller.yaml rename to motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml diff --git a/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml similarity index 100% rename from motion_primitives_controller_pkg/test/motion_primitives_forward_controller_params.yaml rename to motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml diff --git a/motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml similarity index 100% rename from motion_primitives_controller_pkg/test/motion_primitives_forward_controller_preceeding_params.yaml rename to motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml diff --git a/motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp similarity index 91% rename from motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp rename to motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp index c660587acc..2c7a6d38cc 100644 --- a/motion_primitives_controller_pkg/test/test_load_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp @@ -38,7 +38,7 @@ TEST(TestLoadMotionPrimitivesForwardController, load_controller) executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager"); ASSERT_NO_THROW( - cm.load_controller("test_motion_primitives_controller_pkg", "motion_primitives_controller_pkg/MotionPrimitivesForwardController")); + cm.load_controller("test_motion_primitives_forward_controller", "motion_primitives_forward_controller/MotionPrimitivesForwardController")); rclcpp::shutdown(); } diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp similarity index 98% rename from motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp rename to motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index de939ba81b..01e062623f 100644 --- a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -26,9 +26,9 @@ // #include "rclcpp/rclcpp.hpp" // #include "test_motion_primitives_forward_controller.hpp" -// using motion_primitives_controller_pkg::CMD_MY_ITFS; -// using motion_primitives_controller_pkg::control_mode_type; -// using motion_primitives_controller_pkg::STATE_MY_ITFS; +// using motion_primitives_forward_controller::CMD_MY_ITFS; +// using motion_primitives_forward_controller::control_mode_type; +// using motion_primitives_forward_controller::STATE_MY_ITFS; // class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture // { diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp similarity index 94% rename from motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp rename to motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index 61b72494a1..deb3122f0d 100644 --- a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -28,7 +28,7 @@ // #include // #include -// #include "motion_primitives_controller_pkg/motion_primitives_forward_controller.hpp" +// #include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" // #include "gmock/gmock.h" // #include "hardware_interface/loaned_command_interface.hpp" // #include "hardware_interface/loaned_state_interface.hpp" @@ -40,9 +40,9 @@ // #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" // // TODO(anyone): replace the state and command message types -// using ControllerStateMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerStateMsg; -// using ControllerReferenceMsg = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerReferenceMsg; -// using ControllerModeSrvType = motion_primitives_controller_pkg::MotionPrimitivesForwardController::ControllerModeSrvType; +// using ControllerStateMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerStateMsg; +// using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; +// using ControllerModeSrvType = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerModeSrvType; // namespace // { @@ -51,7 +51,7 @@ // } // namespace // // subclassing and friending so we can access member variables -// class TestableMotionPrimitivesForwardController : public motion_primitives_controller_pkg::MotionPrimitivesForwardController +// class TestableMotionPrimitivesForwardController : public motion_primitives_forward_controller::MotionPrimitivesForwardController // { // FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); // FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); @@ -64,7 +64,7 @@ // controller_interface::CallbackReturn on_configure( // const rclcpp_lifecycle::State & previous_state) override // { -// auto ret = motion_primitives_controller_pkg::MotionPrimitivesForwardController::on_configure(previous_state); +// auto ret = motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); // // Only if on_configure is successful create subscription // if (ret == CallbackReturn::SUCCESS) // { diff --git a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp similarity index 93% rename from motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp rename to motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index 2699961d58..0c0f13a949 100644 --- a/motion_primitives_controller_pkg/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -25,9 +25,9 @@ // #include // #include -// using motion_primitives_controller_pkg::CMD_MY_ITFS; -// using motion_primitives_controller_pkg::control_mode_type; -// using motion_primitives_controller_pkg::STATE_MY_ITFS; +// using motion_primitives_forward_controller::CMD_MY_ITFS; +// using motion_primitives_forward_controller::control_mode_type; +// using motion_primitives_forward_controller::STATE_MY_ITFS; // class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture // { From 9074829833d03d3ef12fa8a860f65ab49f614048 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Apr 2025 10:47:58 +0200 Subject: [PATCH 004/128] added functionallity to execute multiple primitives as a motion sequence --- .../motion_primitives_forward_controller/motion_type.hpp | 6 +++++- .../src/motion_primitives_forward_controller.cpp | 8 ++++++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp index 9a552043d0..ac1fda9b0b 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp @@ -3,11 +3,15 @@ namespace MotionType -{ +{ // Motion Primitives static constexpr uint8_t LINEAR_JOINT = 10; // changed to 10 because 0 is default value static constexpr uint8_t LINEAR_CARTESIAN = 50; static constexpr uint8_t CIRCULAR_CARTESIAN = 51; + + // Helper types static constexpr uint8_t STOP_MOTION = 66; // added to stop motion + static constexpr uint8_t MOTION_SEQUENCE_START = 100; // added to indicate motion sequence instead of executing single primitives + static constexpr uint8_t MOTION_SEQUENCE_END = 101; // added to indicate end of motion sequence } #endif // MOTION_TYPE_HPP diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 4067fd88cc..72c4a80b13 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -201,6 +201,14 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr } break; + case MotionType::MOTION_SEQUENCE_START: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_START"); + break; + + case MotionType::MOTION_SEQUENCE_END: + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_END"); + break; + case 33: // TODO(mathias31415): remove case 33 block with hardcoded motion sequence, only for testing RCLCPP_INFO(get_node()->get_logger(), "Received motion type: 33 (testing hardcoded motion sequence)"); break; From 2cf7b094bb5ce79345df317e5a4a690e3066ac85 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Apr 2025 13:27:24 +0200 Subject: [PATCH 005/128] =?UTF-8?q?Added=20new=20state=20interface=20ready?= =?UTF-8?q?=5Ffor=5Fnew=5Fprimitive=20to=20indicate=20whether=20the=20hard?= =?UTF-8?q?ware=20interface=20can=20receive=20a=20new=20motion=20primitive?= =?UTF-8?q?=20=E2=80=94=20replaces=20the=20previous,=20more=20complex=20ha?= =?UTF-8?q?ndling=20via=20execution=5Fstatus?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../motion_primitives_forward_controller.hpp | 6 +- .../ready_for_new_primitive.hpp | 11 +++ .../motion_primitives_forward_controller.cpp | 91 ++++++++++--------- 3 files changed, 59 insertions(+), 49 deletions(-) create mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 9924017d48..850aad7746 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -104,11 +104,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::queue> msg_queue_; size_t queue_size_ = 0; - - bool was_executing_{false}; // Flag to check if the robot was executing a motion command - bool was_stopped_{false}; // Flag to check if the robot was stopped - bool first_cmd_{true}; // Flag to check if the first command is sent - + bool print_error_once_ = true; // Flag to print error message only once if ExecutionState::ERROR }; diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp new file mode 100644 index 0000000000..26b0c01dbc --- /dev/null +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp @@ -0,0 +1,11 @@ +#ifndef READY_FOR_NEW_PRIMITIVE_HPP +#define READY_FOR_NEW_PRIMITIVE_HPP + + +namespace ReadyForNewPrimitive +{ + static constexpr uint8_t NOT_READY = 0; + static constexpr uint8_t READY = 1; +} + +#endif // READY_FOR_NEW_PRIMITIVE_HPP diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 72c4a80b13..524222b874 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -27,7 +27,7 @@ #include "controller_interface/helpers.hpp" #include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/execution_state.hpp" - +#include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" namespace { // utility @@ -107,14 +107,14 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi return controller_interface::CallbackReturn::ERROR; } - // Check if there are exactly 18 command interfaces - if (params_.command_interfaces.size() !=25) { // 1 status + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time + // Check if there are exactly 25 command interfaces + if (params_.command_interfaces.size() !=25) { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly 25 command interfaces must be provided!"); return controller_interface::CallbackReturn::ERROR; } - // Check if there is exactly one state interface - if (params_.state_interfaces.size() != 1) { + // Check if there are exactly 2 state interfaces + if (params_.state_interfaces.size() != 2) { // execution_status + ready_for_new_primitive RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly one state interface must be provided!"); return controller_interface::CallbackReturn::ERROR; } @@ -171,7 +171,6 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr while (!msg_queue_.empty()) { // clear the queue msg_queue_.pop(); } - was_stopped_ = true; return; case MotionType::LINEAR_JOINT: @@ -287,53 +286,57 @@ controller_interface::return_type MotionPrimitivesForwardController::update( // TODO(mathias31415) Is check needed if the value is .0? uint8_t execution_status = static_cast(std::round(state_interfaces_[0].get_value())); - // publish the state + switch (execution_status) { + case ExecutionState::IDLE: + // RCLCPP_INFO(get_node()->get_logger(), "Execution state: IDLE"); + print_error_once_ = true; + break; + case ExecutionState::EXECUTING: + // RCLCPP_INFO(get_node()->get_logger(), "Execution state: EXECUTING"); + print_error_once_ = true; + break; + + case ExecutionState::SUCCESS: + // RCLCPP_INFO(get_node()->get_logger(), "Execution state: SUCCESS"); + print_error_once_ = true; + break; + + case ExecutionState::ERROR: + if (print_error_once_) { + RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); + print_error_once_ = false; + } + break; + + default: + RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); + return controller_interface::return_type::ERROR; + } + + // publish the execution_status state_publisher_->lock(); state_publisher_->msg_.data = execution_status; state_publisher_->unlockAndPublish(); - if(!msg_queue_.empty()) - { - switch (execution_status) { - case ExecutionState::IDLE: // no motion primitive sent yet - print_error_once_ = true; - if(first_cmd_ || was_executing_ || was_stopped_){ - if(!set_command_interfaces()){ // Set the command interfaces with the current reference message - RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); - return controller_interface::return_type::ERROR; - } - first_cmd_ = false; - was_executing_ = false; - was_stopped_ = false; - } - return controller_interface::return_type::OK; - - case ExecutionState::EXECUTING: // executing - if(!was_executing_){ - was_executing_ = true; - } - return controller_interface::return_type::OK; + // TODO(mathias31415) Is check needed if the value is .0? + uint8_t ready_for_new_primitive = static_cast(std::round(state_interfaces_[1].get_value())); - case ExecutionState::SUCCESS: // success - print_error_once_ = true; - if(was_executing_){ - was_executing_ = false; - if(!set_command_interfaces()){ // Set the command interfaces with the current reference message - return controller_interface::return_type::ERROR; - RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); - } - } + // sending new command? + if(!msg_queue_.empty()) // check if new command is available + { + switch (ready_for_new_primitive) { + case ReadyForNewPrimitive::NOT_READY:{ // hw-interface is not ready for a new command return controller_interface::return_type::OK; - - case ExecutionState::ERROR: // error - if(print_error_once_){ - print_error_once_ = false; - RCLCPP_ERROR(get_node()->get_logger(), "Error: Can't send new command, execution status is ERROR"); + } + case ReadyForNewPrimitive::READY:{ // hw-interface is ready for a new command + if(!set_command_interfaces()){ // Set the command interfaces with next motion primitive + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; } return controller_interface::return_type::OK; - + } default: - RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); + RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown state for ready_for_new_primitive: %d", ready_for_new_primitive); return controller_interface::return_type::ERROR; } } From c09d1fdba73abaf8eec3d7afbe88338a7b6992a2 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Apr 2025 13:35:07 +0200 Subject: [PATCH 006/128] removed case 33 block with hardcoded motion sequence (was only for testing) --- .../src/motion_primitives_forward_controller.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 524222b874..211e8af363 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -208,10 +208,6 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_END"); break; - case 33: // TODO(mathias31415): remove case 33 block with hardcoded motion sequence, only for testing - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: 33 (testing hardcoded motion sequence)"); - break; - // Additional motion types can be added here default: RCLCPP_ERROR(get_node()->get_logger(), "Received unknown motion type: %u", msg->type); From f4abcbd897ed62264dcdc1cc50863cc176b05ef6 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 10 Apr 2025 13:32:45 +0200 Subject: [PATCH 007/128] removed mail --- motion_primitives_forward_controller/package.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 1265dac284..537b46911e 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -4,7 +4,8 @@ motion_primitives_forward_controller 0.0.0 Package to control robots using motion primitives like PTP, LIN and CIRC - mathias31415 + todo + Mathias Fuhrer BSD-3-Clause ament_cmake From 79e47bec8dde89eac4d55f13843343a4be5b317f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 10 Apr 2025 13:33:03 +0200 Subject: [PATCH 008/128] added command_mutex_ --- .../motion_primitives_forward_controller.hpp | 2 ++ .../src/motion_primitives_forward_controller.cpp | 6 ++++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 850aad7746..13f2c4e134 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -104,6 +104,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::queue> msg_queue_; size_t queue_size_ = 0; + + std::mutex command_mutex_; bool print_error_once_ = true; // Flag to print error message only once if ExecutionState::ERROR }; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 211e8af363..f08a0dcea6 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -163,15 +163,16 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr // Check if the type is one of the allowed motion types switch (msg->type) { - case MotionType::STOP_MOTION: + case MotionType::STOP_MOTION:{ RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); reset_command_interfaces(); // Reset all command interfaces to NaN - // TODO(mathias31415): Use mutex? + std::lock_guard guard(command_mutex_); (void)command_interfaces_[0].set_value(static_cast(msg->type)); // send stop command to the driver while (!msg_queue_.empty()) { // clear the queue msg_queue_.pop(); } return; + } case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); @@ -353,6 +354,7 @@ void MotionPrimitivesForwardController::reset_command_interfaces() // Set command interfaces from the message, gets called in the update function bool MotionPrimitivesForwardController::set_command_interfaces() { + std::lock_guard guard(command_mutex_); // Get the oldest message from the queue std::shared_ptr current_ref = msg_queue_.front(); msg_queue_.pop(); From 316ad5496389404c5af3d75fca9e17ea1a9523a6 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 10 Apr 2025 16:26:43 +0200 Subject: [PATCH 009/128] edited readme --- .../README.md | 42 +++++++++++++++++- ...s2_control_motion_primitives_ur.drawio.png | Bin 0 -> 458182 bytes 2 files changed, 41 insertions(+), 1 deletion(-) create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 2a7aba8649..28f64f47b0 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -1,9 +1,49 @@ motion_primitives_forward_controller ========================================== -Package to control robots using motion primitives like PTP, LIN and CIRC +Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ), LINEAR_CARTESIAN (LIN/ MOVEL) and CIRCULAR_CARTESIAN (CIRC/ MOVEC) ![Licence](https://img.shields.io/badge/License-BSD-3-Clause-blue.svg) +This project provides an interface for sending motion primitives to an industrial robot controller using the `MotionPrimitive.msg` message type from the [industrial_robot_motion_interfaces](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) package. A custom fork of this package is used, which includes additional helper types to enhance motion command flexibility and sequencing. +## Features + +- Support for basic motion primitives: + - `LINEAR_JOINT` + - `LINEAR_CARTESIAN` + - `CIRCULAR_CARTESIAN` +- Additional helper types: + - `STOP_MOTION`: Immediately stops the current robot motion and clears all pending primitives in the controller's queue. + - `MOTION_SEQUENCE_START` / `MOTION_SEQUENCE_END`: Define a motion sequence block. All primitives between these two markers will be executed as a single, continuous sequence. This allows seamless transitions (blending) between primitives. + +## Architecture Overview +The following diagram shows the architecture for a UR robot. +For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) is used. + +![UR Robot Architecture](doc/ros2_control_motion_primitives_ur.drawio.png) + + +1. **Command Reception** + Python scripts can publish motion primitives to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. + +2. **Command Handling Logic** + - If the received primitive is of type `STOP_MOTION`, it is directly forwarded to the hardware interface through the command interface, and all queued primitives in the controller are discarded. + - If the primitive is of any other type, it is appended to the internal motion primitive queue. The maximum queue size is configurable via a YAML configuration file. + +3. **Motion Execution Flow** + The `update()` method in the controller: + - Reads the current `execution_state` from the hardware interface via the state interface and publishes it to the `~/state` topic. + - Reads the `ready_for_new_primitive` state flag. If `true`, the next primitive from the queue is sent to the hardware interface for execution. + +4. **Sequencing Logic** + Sequencing logic for grouped execution (between `MOTION_SEQUENCE_START` and `MOTION_SEQUENCE_END`) is handled within the hardware interface layer. The controller itself only manages queueing and forwarding logic. + + +## Related Packages/ Repos +- [generate_parameter_library](https://github.com/PickNikRobotics/generate_parameter_library) +- [industrial_robot_motion_interfaces (with additional helper types for stop and motion sequence)](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) +- [motion_primitives_forward_controller from StoglRobotics-forks/ros2_controllers](https://github.com/StoglRobotics-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) +- [Universal_Robots_ROS2_Driver from StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) +- [Universal_Robots_Client_Library with movec from urfeex](https://github.com/urfeex/Universal_Robots_Client_Library/tree/movec_movep) \ No newline at end of file diff --git a/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png b/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png new file mode 100644 index 0000000000000000000000000000000000000000..a33053b6b206bfc0cba7726589a8d7c79e1c6c1c GIT binary patch literal 458182 zcmeFZ$?o%BwZZj#lZ{og>Cyco$#5FMI8W=KW z?Y#f*)Tt^cffz91m49y%H{08Luf3XQJ2WhnpVzy0t2+rRzoZ~sQUiO;|N?Z5gT z{`R;3@_+wt{%hFtKmSkv+yDBv|Kfk?7AaWTBd?n5Z+|C*Ki~d-!ODJK{!WO0zg(hW z_~*2WiYaR6f9|pccERze$hyByc=Tu0G|}HLGWpLK9QwBbj{lwD;hP(;-Ln4qu2b3=YO_D*TF~i#f@V?wtMt#l?fFV^U*s9Bjp}21 zk0JH%{^QpE(Pn!nQ#6#1KFu0vB0c^zf#VeUr_uEL*B%URf$maF|G3Xzw?#W%)%jP4 zaOmvsw6#jJ`LApL>{|N1S*qbb+?n)UmnDA<`(G_a)70<(;c0o_{PlEyoio6L{|Bw3 z9j_#6{?omFl`iFThy$74X+6j8~vUlnv$|wU<%hMgNK^>`SR~zQkSVm&-hR9*Y*pN z?F%+cRa-6926A!1@_yQ*DTQx;o!w*;{P?%?k`3?)%MD3>KJ_hp%*j*@3#=$4TJ!S# z$1E?|0RzsLOWVK%p(Q%QjX#;tH~j>Ay1s)B^Pmcv|7cg#R0UdZ35*-unBd`omI~yD z`|Chkr75}%zoW-{4N-y~eTUTo`=);F(hNx?EKL4iBn17);o1LM4j0s+-|xSA{C_fA zf9*nd&;GIa&}07RrRd+wl9KgpwoG3bmw#N2;p{*EwR-=tc{Ie-}$(DYR8Pc87# zJp55Ad3B&^;{Q4zrqL3CWc~Shk%zAM`$ecc-hA%ZT`77F{uwW~l-vToz0pre61Wh3 zQC`aZw})3!-f<<4(-ljA=RHc^hT{TXzhuqeIG)nr>OzH`7HU!8DEL2h;6HOf?NTlL zClf-lHWCA0Ilk5OCuW1h%R3k-nX~?W;fpQG&^4S8@Twm?;M(VZ9?Xdqk#S>4> zaoroi6*vB6*KV=|^A30Cc((?BhARDb@-sE>9ENMg-YL^;ep%N};e-St#v( zFK&jGl(hr@wF_?>qz^jE<@dkLKf2kcLQ?(g1(La*R}3J2gP&biI+0Q@YbvEX^` z*H2gGf`$_+`*$83D78NaB%TjEIKch&Jlt~UWCb1%8VEdIcyaJ3aHBi7!U5^eb2~2o z^3ehKsR-)`V#lFJE^U|3T<)&HFhhImC`g~*fx?#L6b``nqw}g>z+h-1coaAF+eGtAbvgh%pgM0}_}XwYKv<$efK`}%IADNCOEDV|UHaXT%sGK(*#Ud6(^5B?p_ z^zKC{%G^&@9(&DfALcQ99?A4c(4TO8WxJ3T{e{^)C?-vp;i8j}l4&9?e)-a$QR&{x z9oAXSSJhomv-)ek9qB&dpj;w51wR}^yBz>nh~wS}5`sZ?Pk<{|GTQ}H8Iyk|5 zw%TyGQiMEd>wNTd#_UK}JWBZQ?JepWoL64Zy=_+ejJ!XRHwz3aFJtB;x94;82hSGk z)hOU;4y(SJ72|zZmrZvM7GTIHoalb3&~Kk3Ja$#M!g>U=S4bx`YRxi}9`BqnIAQdJ z^1PjC`3%|)kK*2B%7LA|@`GOkxMOFLkGv;7Bz80kh5O&jL@@1!U-nY_%;ISo(c)iI z%$#vb>C9Az_C5Jj-lvl&B4as@gFW15z0wG?Ur8A-&ecZ9xZ&GsIq-$MXSpkKNw|&>|tz&eFNhfQpQEXQCcjGx4_LH|o zDu3@Y7+N`@kua(1B7hi#%q22{8pGW5xLz@0Zz;ln!%tE~XE6_J+a8zP+)eAan)S0k z%l*oUNnB@4P(g2Csxe)clW#SPx}jrrCt7wlf5epsUrShI+%6Do$j^wkJ7+k!-V?ap7r0<# zJI)8S1OvV`9|`6$hYnt>U}})2l+(b&VUmw<3wqqFXPVlt|>!=%r)v8Y$hjeR^a<*NwGq0b|+)?tfUr<#MN%>uv(hQlHcS0c&Qk=NygJ{n5_Ya zLvV!9!ACqUu_Vu9dw>8@?tb>-Lz>Qmsuu4UU*DJGPu_Y%^1hxH_P~@jurAHFcoX7D z&V)?`HlBOQ_4bGj0}b^fCWr}{l{z6$lEB`qrSZB-2I@7?kP z-H=015nOT*lu*n*5gT=A1YAox>MMD^ye=@LE$V3f{_e<}r?oeK*Ph(HbUBEx_zotC zhY$$~9a?Do;Bga~>*QSBk7s&Ii7Q3X^n9=D^LigxQwv2w#Zvisbi-(~B& zA2^-{j^`wx2~FrNFVaWlGTa@h%MX4-i>iA0M7DV&anp7ET>)5l*Q9SAlKL$0u~m-6 zr_hFncA?*keNy>E^=W4l#O;&kT=6;``F`@e@Kp^@6zRQtB1`@oRsv^&j zdrwwL8A{Dq8~e@&t$rW%V`!zX{}RyfDdGHH+vH&K8ONjZ_o70DEEe0d^(!R1q6);=c&QZZ|c-WtG>PRPWYF?96}%T zh!W>nR;@~TO@4k&?Y_?=#dO|Y#qm3G1o%+M2jf$%YVh(X(@Wk>xzc6FXpRd6yN@9&yA zmFavPF-jxZ4lQTOMcN`iuMtbmS2VeM>z?84KW?BdMXX?-4`E#)1Qbl>0p??OqRFSm zX~J@eN9&@H?<*GHU(0h$y+=QZV=6Ytw%?Tcxs|Y{n5!0Y3 zKYNQEo@0);`FaiGc;?cS{ettSJ@JIyZ))P*@!0JYT<&oN4K!>tjkG$_IgCRZi@|k+Nt0+zwyb)d8K#2OCV*v;a}fkz z4u0R0lWdq>5q4esIpjBx`=z4FBlaeo(RxF^9xQg__w_ysf`EO$*}G)iM_cly#^2{- z!5+aaPt&}D6wF2Lr$x^Qh$$sc=sg@3+c0Kb>m0iF^Pi*mh)HC$$>9ru@SkT8xNi%t z?_EqYp?->~0sk1eopBF8HTARm1%~2a+&b9jmC24wEL0c?ZqPMNxgUzDA0~YI^5=5h zEb?mQKTm+_=yiN&HA0SN@M|aPZ9G9|bfd&BUQwRdTX}xM-E_Kl^MKB$+wFt=_4SP& zrFetais3x84_eV2ps%+hQ=+D&K((w8>3|cT+@TkGVkl=^48yXH{iLP(r+hs%zyUlT zLOCNA-!Y!Idf!w*BBe2i@O zPcJHA$#5Hf=eRCkQ+#zK+%PitoY1twNm+LiE6d70KF8SFV7SBH`~=x4UM$cUC%#*N z*9UObo<-nUg42T*b2#0?Vo_FVcMWcf36@RWZ5+S~!$BOdi0*;72CzWZC zAs*{!q;}vW6x_>5GpPd=ANG8^Q_+B-pt5gpO?|X3m36~V_|Nk_gWs{_aM5c38R5Ox zBuU+xJS*1;dsCYaYI3Oe5+VRP^|E=8;}llA_2RB2$ZX zbfQ5jF3Yn08r618<{I@>s;hT+;h(iyQ( zEbt>BNF*i&YUoXY9v8rDaeWt`N0_7CdgU(p_#Xp@azft&<+sLa-eWCFuSfKRW z4|(p6o?(P<9xM%xUv#Z`VFcUuzCc)60u!+DF5u+4^#<6%LxO0T=CxFM>bwChw6Lx@7Pqz@@p>JNU@C9DZfiqry(Bl4i~8o$u#diyQhkByuCrcpvg;769;qw={E{Zr2wAecnLEB z0Vn$1kS{%VoVRNVUJY{|(=w$o#DJwC_qt`$cfdv_^~t4vP+hf$;({+~!|_f`tZ1M+ z$);`(=R;N*z0!RMZN3gp%B{Q8F=&4Cd@aBo;6JOMoBo%a=OFG~3yqkyY81?p*fE!z z)zx?dQ6L^}+l9`n04canKv@Cx^b|o8rWM5nkVnGL;2Mf*6m8%%$Z#F8XA^dMw`B;w zuZ~_+$(%3UM;5w^e=1aJLLYa9d3RRM#S5L`O-BS@QtB8=Ldl)|GjE&y>M-h~-i7h1 z-Kmk2HA}qOzEHR7J`V?>ed({iU#d%iRSjSp05yuRzI-coLt@MI`-@gflhVJi^AdJ^wm>hESlJ69fs56nr^it@+Y_mZlu^*BeJMfBHq! zn7QGnyt1yx+p!!D6q52@`nKLUGk-8>3bK6o(u446Bn@Ou(lbyOJo`c<@Pcq{Vb;$}Gc zT5mgk3y$^Xc{nSBon0=oW@hcI6uabCyNmvmf|3SrF76XNs%J}|8%Kk03y3LNqtf{t zJ`(0Wk)s^XdyYO~12^M~hKLd13D(Wf?uM)I*vjID?*Uc;fL&*)e58B1_dd8P?gr#v z-0uOwm^aZ$+82sxtj)n$kGQ-$fNJ^fnmbhTqS9;~%`*Jf;}EPZz?L-zk>wF|>L5HY z4hFVwKFnN20V%7cBJI%69+y5JtouM1?W+wn?-c5(6PIIF@!v~pE{a|BYhs6+!`b+ic}Ta}2TeK+AG~NjfROMTicc;H_G~wKX^EIYE(Pp5;DhDB zO7zvNX=m`t&oi5(5i10#YTUZSD49=p!aQ$CdHyc?qy2*T-9m-|b`m!Tiy>KXgU9H} zoKfEDI!0)1N?`Aj%u%JR#MZ)vJ^0n-^jvqH9z+1Km)$ z3V`LQ2mAQtv1*d=3YU?A=R~@asZ5+My>uKXMgTw9x0R-!zTw$OoqKwiX_WR1pTrZP1l~h2} z$yL!ymP4=?%NrZFhX5_yh%3uOk5sM{Tv~UDh0IthzFa4eAL-XYHu$-d!V!5@K&A&T6ZeY?ak=7vC4~p*u>>4* zB*npQX) zyziO70W>a(TmziqCf+B6SW*B zxjT8+2J3oB&;zHlo6r|s@tz(>0kCh}m(BhV!mHtIa7F;zz2zXRw;OSB@vwnJ1u66) zIFGVJ^dBFs_$-Q<@E5tNsuAGV`m2rd7T#}a@em+xnIA`4hI zuoC$qD1&bqKcbE3M>>98mIa^zACACDum$gw{HC4y=$h28RYuXR8GsR#_k(jDpc#4z zvU!DARD40D_eLNzR^E|j{44agfzrpX{W%k?jv%YF^BBrvV{OhN&0f3LmjwP#LSvai@b+x)^^=B zHUQ4~euTIf=Yca-h|K^30#B6EIr%dcUkPBX{vn2!vd!}R`Oe{H>=cY8`T78q?^cTQ zeF^dD#1FR_zi+NJZ#5o)&$?T%=J@>FGYde#4m-R0qINIyw6XHGZCjj`Az^|M1H8T4 z4r*LC{ZpI)5Kh3ii6;3%FV!?i8{kq^Y!#kS zg=zjs3I<{Y-gtKk!S}fCLlclwX0pc04{&#Ad29ntn3JWNy;=lJ zNKOG$y4<)uF?VIZc(li1kb$sx3R`0TNXP&+0c-%&Nf=d@1!kRmZ>HR`wt0TaO2VEb zZw#AEE&g=LXvQ6RI#3uc%UVQ_<-<8ReEpf$OIn}buV6r)L6zf)!0{1Q3y)p)OURgt zm{xmeTXd&AItTXaz~g#c^SsAIK=%r>8=??Y6W9ZeqyfjY8J8Q?cuHcV5Ul#5dy@>- z*~S)KAOL-Z9^dE<{)dfbh>2~lkXcYi$WsG~^K4digy>Atn-T8^NQHR9+Rvh=W~hj@5#s4>2b6C=y^%~Rz~HE$S%%LF_Qj@Z7m`Cg!qxd`06S6$J$UUXp@OjY z)-#&cx!d2Q(GY6Q*U%MJ^rDXkv$Xj@#u1V3g*@cuy?W1ss4hq&ryagYY2?$9ff*-m z`}HAxrNSdoyk3IO_3o-9uhVpE^!k-$Yd<&=Y2KISCK0m7x&m5b zH^IKVVQ_q50L;R3qCsDOiJ9=L%<1vEdoP7&@{YB>-e^6I2R>7^iB`7#t-$Xzh8V_Q zC|n2z0e%BHV6)FA&%@?jmvp5Q;caQDA*YYRnQQ;7B^%FZZGe3-*oN_av z2}ZW^O?7@~E}#e9NKqc^q(n$S{56{_dz>fcZ+D+ifExf;tFs;0lw{{ybavnF{UnXU zvt7GhO>j$`0iC6YfS_z&9SxyQ$7^2l?L@sA7l{@^0I!Q&g{D z1!XM>It@tZ23QE3aYfDxY={>tn9P^#Q z0n_$zb4Be+FHhuQ#s)Z4ek(MjZ)=bT4^&!S%KV%K8onKhdRRaL`p|qdh0CSi*!$smgb{siZaZt^@nI!xsh2h@5bb8xC@!C z#CvhT(_#HEk7)w;7K;gcl#1aA+Pi)RdkcuFdL_H%TozL}ffznwQV6!@4tWSK)PebU&pf5p%KKq#kD?NWH1@EwJI4eY4zX1LWhetcwxt zS06s*vaa{r*gne_G2-1zz+P1*HVw}DER?Va+C;mzK4-4xqyx#f2@$cKCLderP*n-8|Wh zDWG!^0cd(Yz%6ndsPC16(K;aYs154{hN&4KG7GMg+!~Mvdkdk{^U}!sl`b9r7*>7-Q4hi5N`E?+-^iD;9F)6Jp z@mIjtzzYR6#V2iV#D!rbB$*qerWx83XnSzrhGc6s@U>PcGi(7tG=Vb;PsU#@Imj>Y z?RF&2c^nWEun_gE_rAqK$>Ld}e@Epd@lXGu$YAr<799Nvnwv;UQB1ER6jE_C3@QdX zV9f%HPJ3^z?nX7BTYGi@$?#iF`dW~-7F=ugQETa#C-+1X(^?pUT(}wtl zV6tbr9rGb!IP$aA>ct2VZ7c)cWKXGL8u!5833bqFmK+whTaxVYQ@el021Cvg0w$2c zzWw>+w~0~#+C&`Y2T8rgJ=Uui{k;d3et0?#3@yMJ7!z_?v2iS>9r#zOP}SC*kl5#t z4k)Z261Ry5c!XqpeF%G0X<$CU`9bj*@ldLeXU3gL&He>JJur$&jJd|h_R23<^59zg zo8dx@Mjm@4co(6=g=3=<+6w*;>qP)g$XRLz4~3@B)0rQcK4X&LIpFlPSHdR&o~MNC zS%#4JM$8**nPMTFWDa;!{x=E%$!maPto)dLNWzMATaN8kAGp-Z765Q)mHsxl1`uT3 z!6eBnOe9(=-Z#2I%FRnI&qRLpo9r(BaXY~p^Ec$IQsDWAv;5d|x*oZrUZ`7}O=r8r zOk_?t8j1|O(SkGs1@aIoP({^}Q+wS!6D+EI$R;3Z6u~9CW-vMzx`!YaavAgq2>KQR zXQzhDXVP4$GHQZ+Ivo-MQdu4hYv7&WwwBM{eI=HZjJwnWptVRnKX(T29C2G-;!71S1jbAfZ51B&zt?^B+G&v3)~y{Tp#r#jjhHj0;I(z;J>pJ zRdpA_o?01)3atB;VDREm5z0c+pRgX9dy-lX_JvmIhbgZUFnxDZtfK}^G{AH_gW=M* zV;UcKVNZpvfZu_#gZsrW#UR5DKqKL@F5d%=J5=>~Z9|M=OB9!uV9-uTNZ%wXF;(!H zfrb^za2!(Dco6|FSJ4j}+`Qh82Aq5%glZ+N49T-fdt^% z%&m5r=r4Ajk9Xa7{fg_KOVx}UhVKRV&h}ljyCF!&s2D_m`i-2;eL%;6PNf9Wjb&D1ZtZe%Eb7!;Cv5-5+Fu*i&`gv>f zW;uYW0fmHO+YfkVR`~q;PA|83|kLE2A*isSLHasUdT7SN$5c{q77(? zS%ay-e+zQ`)Z7+$KPAr7)4>ElMw)C5@mFl1hBnAog+$Z_CaeK-bstdf^$N~0STgY;}*6b=ErqBOjr~03G*PEQJ#uP$=n&gE0ffgC4JKf)4Pt~rw%}OynHy? zLA4ReP9}!Da8e1+@wr#)JzP5BDL-SNqdDvfPr5Fv^Z-!(qcS&0%kk7oFWv2Rx}Y`W z0HP!&|6wS749Sbt*OLdtL|+l|g=}LJ%4z!~Q(a};U3r8;%i|>vATI=9%$3O@eCHED z#bEz86mN0zOaQOy{qMZ+2SnyVU*Dj1=@LITEZZ*3yJUZw=7N1XJb{d^XFUZ{_N&EW zA3Z`F#P?>TizHV~8R7VGI;k(ld`?dw93>7}?#3PucW@1XR|*#@aT2En=z-1a@Ue9H zMl_$dd%Xz%K2J)%zZV1Gml2hgq8bOJiP0P*cfd@=f&B)gg6bZAIz(E#U>a+^>OXuO z!-H82?xi_!K%XH(Y)d5N5aFWyN5fvCON2AC+-_q5wFhr-r|&#>3h8cicEt}kDpI}Jxx}ThsYoJ`|#w<5)zu42GNmMD)z*DTl)*aO)DT& z#;Bf_Q?WHLtcn@AVc0{HufYr0bZkDA5U|MG^R%P4L$?qhL;cY;9j5_yyRdf2voNiJ z-JH+3Jx2=}BS5GW_@GuFmOAhbqa~O~`iYUk*&^MD*m$TOYR}G#_r;UUI5DhCFu`4 zlR*dwd3+HYJspk9xPsR}TzizMhfTP-Q5PV@Dg^`r=r`4+T;dQg;3NjN@;Y@JW)b$6@a@_y}9{~L^P!aG2ve%7y!d=JX1ktdH2V|+_B~}QC$11RoB~%h{cYgnI)hh82wGfOF=i8b1HNj62 zv)0EqD0d9$4WfG}5Q8?oF)T&Dg#scNFB8q%n>JoQcGwIxy*&fgjPJhH7Go)5(ydn4 zw!7jE`ctE({wb@AjABf09SfZUE=%-vYsCM~qY7h|D?;zyvqay%!X`m53z>1qKMJuI zS+BMEvAW;}d0Ydmv`xf{iJBdJTC}=gQxMkiXR9WC`;@~1ydA_uzNWv}sD-Z&YuD>W&aC7x??F z9&=*xu*%&4pozV`uwH{K0||ck_${upEHOwG(vY`}m*e~WVz}^%{mZr%v}qD;(0H#G z`L4~B#O=t=ru{;0vqEkL)FfVv)Bo`PzNwEZlu6M~+KIfEZafMDtc;A`lMVcK_P59jPR+ssq4Rw-kC~_g7fXn*7?uMD^^>oyGpN-_ zN-ZFcxe#jckY~q6$(Dc^wd0uRMq)}b5PN+fV2YqBY~$lLSnwkYf%GMPfZQ?QPaMx6 zQWA&MsLnT-E*YNp1?USf&M&_1)KC+JvN$^AV8>x(>-fIa!*MO1KL#_qy)W`o4n43; zdaU?JANZ^PupJ!Q>T@V5-VD%hzBfU%^*IbDzD+Je973gQ@O05#2PAgoL#jI$=?+Rs;r-#$9LH~sA9taOTyA9B< zz{ubBML^XyKuk8fX3HQTj z6+tOraI5)Q#vLFiB@DoOzQM8)cGck{O*BzK%g3qgR|UA#OR!&@)^{yN6`>2PZM;i? zUZ~9vu8gnroy7PH%~FOZ47lr<5L2ii9jF~6*uHfn%3ejs9{@v?d{v<^7&80}(_c?1 zd7c;)D#O)uns5Rvo+}-KRz^N}510$e5~0sof!fh=U{4@X*ieBj)=ic}f$Ez=wS zwMWpe9lLr%PnC&L4u&zX7St_2U6-1GB&u!3Y;4PE_*PxRdjRfG1*h=WOsm00a_80m z<1O%bm*m^Fc+Thg?HOx?yiLet=FLk1#JHVU(F$a|o08r7U;$Zv+!>0DHtBKbPK;6zmO!La16F)igJfGB_$cN~9lGSP+1fAr8)6f~t&i zdZoGs?KF z&q!C_ka*LGBfim1J~270r|4m49t{bv!-@S~X!{wXnLe>bR3&9b!oxcrTPy4n2v zHZ&^%W+vQ+Kxk`k@^1nwLuGj}#Xt#61*Xew#F_W`Z#?nUYhXH*)-b!)O^# z%&|(0!Lr}psUDTtN9HM_bUqYOyANTS=qswfu!-er4lJxB6oFZwYJum+Pi=ph9w?2H z#l!beKt{f6nqNw0>OJam?-JXyRtSC-Bb9~(-Urev3-@7*tlrahK04r0UuIHpEO!Bo z{?LK9V_ol1ZHH<(6Nuvx`Tna!C(S7x6ksn0b}`GO`FsXHAOYq9dWt{3V;>BU+zCqx zj|npjRi8UktKY}2a8TRWdb$U-D!ZC~k?Hb^lf1GH3Pz!*SMdQ5*2=~wQ!4F0_YIgI zUj4Q_0Uu9?QlD`i&O5vVV*pM^EYHjlCHeY+w8?SyPyv6-Xs`k0Loce4>uI`~?-h-` z2&l5Z5T6gT-P{xh>Z2Uhx_lS}O&)x~T~$=yCj!BFe%4HWob|TtK=H)er#15e#G8h? z0b}g2$*2RLnnRWjMN`}y;Xt}X#>rBl@@Brt(k$0tc|!SWaU?JC5Rt;b$d{Gvgol=M zH=L*7l?bZ=ai-`%N$EwpwCD{4H5Aqb_*0KEvaSIQ@*#E4AHa9}La#Wj=mED@2jI|r zZU8XA9ditb^ic#ozdO!JX@I$0cAwi-U`7QS)UNT9ZxSrz#CRSx4VAU`#=(IE+FvKQ z{*Z^HiNw1%@=*A$17o4$o;$K}cpVU~3wADt%8_3U!uAM=%h4lmdjMLxN$u)8*LQd_ zX}_|jl^1&&zksVUg%tp3<&aD1s@o!Sf6~cA4`9IqtS&KfFi*9Y+Zww-UKd`C0=`rW zj`|m5T`GUoDnQ^YVKe}TaHl#42Ao#_LM>5}vj8lk=v|O% zS#lpDbV>$i391NA8qhKM$J_h{YaL-6AKrO4vgqubpEopy)`|R@<6UdJp4VH+Y|n3OK8teGmbW zHvwoEuK}G3!-+v~DAPcbr?yCoo?%~5ct?K#fpKEmEiOOS2P2{;Dc!W7+UEv5b?bRR zE`x7@HO85S66l! zCN(N>0I(pg<4r*nPwsfwkejXNZ671!I)ZS)TRT)hPrx$xVf!F(Zr~*is{BqUsk8lz zgpxO&?xJtx>7&?C^s@i;ZWY8Xf+V>;kmUzBq<0|oBSxkJ?>6~UEia2uWB*X3x{a&d zmLbk6P__m$w%EKFrAKWZ>RV<()g;@wc@0z~Xp^`SCZt9vMq)vB2n*s*C(mne3Vkc+K8Mf{KDAK`lUoF6b%5{+;FsvpBhaz; z=TSB@0T*4N9%cA)@C})C2~vfZQqi>w2dt$1qkY5nwdHSugG^RoW(;-HWq28vf=R$m zf;v+!9bfwfZ@{2r%Ks23OWBjy_5|3L%ba8l3=gN7;BhItbcN_7{61L(>Tfxrv`qipQR#&)+FSu=QYi~c-&J^;x#LL5f|_>9H=ZTTRCVyF}(a_X>k>- z9L}Ef0}6e-lO@c~S%2?ELY@y))$>LT@8x++kjQ(#fmba$z%u5i{8qaM#b^2f>Zz4T zYk{7`95br=^IAAo0#fuAIc>X{n982cN%DJB(EPpBljYADBZ zw|4B>1!vde4e=OM4L%>`cg{fV@fKv0Azw15>w-L7Q6#1Iu6Qr%g~y^yYCy)wVorwC zA*yZjbFMSr9u#fYYXX?paR4T$Dv(WtG{u$zh{xxsk_LPX83JvYMJWl`e$_i$m_Q9b z^@fpptT*j|m+_$YXjKVdZVFIqIVf%PMk5nX^D)mNztaU;QRM?~Ie6dH*9^X~YQ1n! zYvn;wk|lqXddc%cVkUZunZS&HP~ z@;rFME#Pr!zsYEvO=&8l^@q5Cc&tS+Tvp$Ydd1&mS!F(eOY|fTYQ; zKzw;$Xrtz%4W1n0;tFsY)B>mcA4Hwmx}r$et#1hs5Dw`P0YL zP9m$RGWXD=^lyv99IiMqe{h&1_LaQ^+s>Xbd~*Ef+Zh3EhcXla$uyBvXX zKt(81*LkBa$D{X1Xc<6BQYE(Ik<{x!7UTRYpsW1XRz?>F=68Ahou0pm)UaQ2%9)dxPnhkH8Osls`qU)f3xv# zUiE|)8rv(5FM6;MT%CM`be0gK8sSn&gd>H8A89Ocxf*+$M;aG=Il zp4pQ?+#c$-gG}dmRuuRMp6YIQy+6oT6VE*~X1=D*_Y37gf%~)G>rvYDthB_``-JY) zEw1(vb{$0FdoXg~su?t>d5(WG6jX2@D!NAE-Fb@o`&&L_b;nD4^rOfk@^JGVue$LR zJJK+0S00+6Jl?E)DzzrAJ_n2XDsNS`qfMH9P8H!F3F59!Sm-l}wO^|!^qn4H5|Zx3 zGG0tLStA*(8&{A%XVSR{+0v_KqK|kEIW8LT#{S(?9^poO)Jx;()im?e+FQVTiO+!| zqccxl@p?G?-7Cg^`o-x0)$ZL>Wmxx2^IC>4v(t&&(&rUZUBsR#?%mh1TYBxIpfS#Y zqdtU-?EWz1L&p_rfV5TENJ+Cz%LZqkWDx34jsPjvh*oVDMWSo>U5gboeSTRSmS)(I z@kl_~#=)*E?t3%Yui(QRcicy6>(0yft1e!j=<|s*BwIf;A|8bWUGMJa^TMAF$08TY z{j5knnX~|Mh5r?N3UIx>(2|Y!NyndMPbh6Vu4b6JP0}O4UqJYvorzK|_m$h@4G`6g zZaK#sBscygfVO(eP8(b7W@?A^n*7^>VOZ9J_iV&#gM#OIHekJjF45)h^;?DSgcXV; z=Qs95<`uob7@6wx39mgl?50XMooeW7YT^!Lg|Ff;d<3(DNt7=7v_5xIS9}gU#yj_Y9qBlIMU$#fu|m$P{&WX_h_s&botw5UIY>S7XdQFG z2Kf>9mwxI+xD#>(rFolLURTopIrK^0$8FCtDYI$RMQec*`e21W9A}~kSRYr2l*k3RI8(M0BK#Mhypruu zW=~Q@_IBJO*E?l`s`FQ7U9!vb8opNfW->Jmq)(pguSo)09a-bAsIsqDmobe?@FU-) zg2Py8Fpu*`^cWAD^9BVx0aNPB^WJnqAC{A_RlMQ`Z-2L&N?SASE#Hl#|M6V}3^NXO zXhkK>!=fdw#(Gie>#TS82F+E(fIIhdNc@*Gd-uuo<|NBt{MwEFF z!uaCw1TFPBO%Qzk1`a^S#q~VklZQe*7)GE{?k8&o)Ccia{A5%F8I6gEoj@o*;hX)b zRt?H_IsA{ajl(m=PkaKOVgh^*UKf~d=;lwT)P!M2r{60VciFu*;Jd1~g$5L zLeA1?1^~{SMEg!`ffz$o$Y9%%?gVjdn~u$T1l_JGz2mpfDzZ%rD--to~Cv9pgQnyq^b!TIAe zZM8mY-vO8BaZEn|hY21Y9PQlt19O=V@8t|eG*KZD@8|nS+`Tw$mnW8=@X`lZPi0bT zoQY-^hyh?U$5DX`#Bt$P1#3i-r%jnWg_qJcuz!MqLJGiTVR}g-uv+aZ7li# z4LoGres^JSlB=F6-`Ft%eNVl^?K9v1&RUp}9t;k~R5EtUJ>ewi>Cb9-{v{i0Ngq$-?(d=I=468t*680hxFcg<{?|M!kTt5T&;n z9EvNdO;BVA6XG8`hG-~~Z#-WA)Rkm9n%0oar0AynPAP-BQO0a+BeRc`DW1fWj#F*oJ02TZv4A)PsE8-F;9x^f1id0B;ufv{p2gsjKOD5AWa$e#d)rLmh4w*Q3q;4 zW#eG&Keuq~zz@9wk_xSuD_0Ab{6>S4^kSpQ82Mb9015u6zkUqauRhvb-}}cP@KZ{q zdbrSNc}V2n4Ndo@{eB<~v@6KT)T{}U2B&n=NdrJ4ul`%cWd}{3dS}9m{_IcHJ*)<} zc0y~)aXI|WuciU?qcFj}6D;IeUW*m<$rJ9(S5i|G)l$5LK7&=*<6V(enj9Z-XOeYg z130q%9`oQG;$VQ>1WBne_QlPOYyjcCH+Rr-Ur!M^2DQigk9W^Kror|3b$wqi86gFc zdnSU>Yu#W*?LFu1zHPJC!ByfOm}0iH$_O{ZD_{O=kCsf39xI$PKZo~#btfA?{dnpQ zo4fzu!uevjy(c@5Mea9zFgxfPiGEM^(32JQqZ}xIH54At`*>s11S$m&UhC2^3+G!Ol#Sq#ymuY=37=2B-oM zA``X~Xs`x|e;72|-~T@w?p2%@imD__eM#0oh^+C?K=2lSxHbIw--rJAZzIP4eF0ak z6fU-u>K)&*>hS1@ivaxZPX}>02a$6gy|tA4D*2zVtiJ5YfI&aiXvy8=)I6S3^?A?J zOOFytPjVG-8a2flivRoL28QcdkTb$4GfBb!96}ubN!2iI3t6^>WtxJ{Ug4om12I+u z4pzB8!VL>O{3^V%@8RKz4_Kzkde%!dzQjE?=$CC*!Dmx_A0n`BjH?dgmv*kaH3-$jJ5$Bd3Bk|5J+?KPp@Dc1)AP0}U%1oI$qm;&?Ychh{HN7m z*E-L+*3aQrTvlZdnp%u+Rgv%a_aX0j9cs#_RmthLRv7baQwWe|k=P!J|a^yhqPqJEwuQ8ol`S`r2tcZYxVhY)}S3vk9K_5lZ9KdX;M2z7N7o zC`pzvESkhP{F(pi;k?E#G&k_*9?)t@ujsghIZfJ(Ee1^b(>O=#ko8r;YO(*up8&g4 z+UOr2a`WoP7#>yq*lk9#bq!eKZ|tQJmhMM<(Bw%adL0lw|Jv^xG^ZkL7&)E`NqyL> zUT4hBgGy@FbJ#F`71LGVkiO>Q6Ce+L?BzbqZ=RoN$xG$szmrLpV(1cYgxiGe@b7Gc z^AjxCdP?f=J7!yCiPAB|)9zGp;7)2n-3)MfxgU<{pK6@TnV;($>TT4E9`2GIjv8e&_S(+Q!{@ffS4f`=JPnkOE>fRpY z*?~4x`R&3ZS;nvUON2%2o*KK;NPmnHJpko37hS|RPNBsKKk?$G(Rlnq8`>TJP6j}Y z$n_t=ycJq1V;ze4RBt9s?Z%U-t-VQD#@ID6GQP|)u{W4d9>^^rvXMPf5Wn@qhLhM9 z7$^rpqG5^!htHVWyD}4vBVH?3RBOtrciBw|xdTpmO1gg%z1Cbh!dW-9mE8a2`J)AU z)sY%^ze%LfgqHDRpH9_&mHjyUp2j!y8}Lh=_8ELyGf`gNF4sXg8?>UQ( z8%yR+*}uK^Gsv03S65f1#7BV(s($XsRAf(+6&oKy^_L8A`Ju;mo}QnX)?F;?(Q%B) zizG~sE+?OtT?s`@TOt<>Ex-{ESNC$r0@L5!D7P0V;}hlfy?Sh?@=t4)J`O*taRx~3 z)Yld2vi$V;@GP)ROpzavsZ@m$Ts$DlpkJ~%la4vrl7!{k6t(Pz_BxpT7$mtYe>6-O zerl|hGP**L-w|7uzJ1(9U!eLPRQI_(d_fiSkQd+1vkDOJfo@*QKLLrjkUMDediI*u z?`c38D)$ESqZzBY{V)TD9@1nB)uvg;P(K!$JD02ec#d`KQ|%dRG^OZ!i0cpgv{ zI|~Rczi;`D?ER?<#6|hQ$+29%kHk=1oif!jcW$H_N+0Oa=eRTc`McjZTE^;q28|gU zRev>Kp$wif88GB2|Tl(j@J6=PfK3A zH(rw!Lr~C@1`-ea3LmgGY_wU#j(B|XtRAlc9?2{2@}H>or(_;Lx#L`RCZEXs>EB() zWcfFN7U&|HJ`i$*WR>@VCw^VT;CxO~l6ICb;M^AAj zXC$)Wt1qJM-QTaDVC>19C$08L;McVz;9) zIC&m_=|!OP?3Z6S74*gkpQ^~9JpWCr$H#T8zK2s^V=dRU=bLOUCq&wO+U$on>N@ix z{zMF>;(j{0m|N8yTB48m^q_7{7=OGdL-TN&5^_tOv=YDeMp}9)I?aXUoxyu0jALB# z=#SXKvZfFE;FRR2nJlG~NyFH=967!Gr#XU`h}=_T!K5+Ou0JR_-Dd_&?dm($8yBc` zvvhP8JWK1E;xXD*`AWeWCG-Xthk`rtIy^$!23{oNp!8H8n>PUGC`0$!wG7P7G^`9~ zAhbIv%bgc#WbiHX-O4|{Ao6W80ZtJgNgux*8hPYNRdppFFCSVOX0Q$X3?c@6)!W2d zs*tsxJlq>$sOcVS%QNs^=6R@A7G^ow0R3EE(1r2$Wf-C(_gcx( z5g$C%sDFVN_`P`d;FJ=+R2^`Ps$MX_=^!K7-ygsIFRw7AW3=stmqTAUjH8Jrn{u%r zUy+07T806rVLVBa@Pmd-Ouy=%2RX&AUVW!;`moo_ySTuQ2>pNQemQ?1-uWGI_TfAJ zp}T(X{G`*<2B$M&Xo5p#L(hdr=3)Bhk%@K)%>wBz*YKk2%>%Bbl;a~178(ry$&}@C zz-XLY$wD$EKU2eHP6Ar+YekrsDO6mf6XSJ!zr!CQIb%m1appr(3Fw1T&J*pC+JW{j z4aA4g**7bFGZg-`)iy|g&*LF6mtJ+3hxB{IpW$x#-2+^PM?m*lGF`T+K)6qLd`@f% zb8u@6y_55UL3Ud7%Hbt*(^pG?S?Q~|e3J6%Z;b$+Gx|LG>t14dL8JS8sez4#+GOuG z3tm$A00}=$fV}Jcd39@0!ZH|i#279Yud8r^*Zt4g46x|Sn}#QO#3o_dTp`8(sxdvL zWL4`wwqu34a_!(@^V`6PqwH&Jh&}`PqFnG9aF71w6ZDTGI4#D195cw)^Xj~AJ9lMO z2ObULw7R15N%FVxzLV?wRnw*An2^j=4(+!Vcfs4@OunEzi{ApRwGUcNg?3qm{D2D6 zX_75=ZiH)sjS@GMETrZu7|1aS^90=?&-s+O+3$=hW;v;K;88T#jleu6`%XOlnnXyCr#B6*6bUXl17ubG;qYKhFc|8q)Ii1+zJhE}WZ$Sbkti{Kr1BgEzo?-0s(dw# zllj6n43(?cgQW6~l5clOb8_EKolZ-3m*lJ!+_=N|YUAg)cP^y5BRnyD3c6)zG5KoR z%FY&lvloL9L%;nZ7wS1^6eviq5K!I{yQj`UVwbEC(Y>uphY+zDnCJla-qqgiUICDy zTzbcAaDL})e(|{leo^?T2!XMHRgvZ=bhYp!`&&2GqgN*~sz3{EKd3qYy)RNk;{B#H zguD+*5=E`ANB?iS#|ikV0vTLrqCm7u^g(V%cLTIkz}du2qHj1n?X26!cq>o=sslti z-#n_h;*C2lYKUKbOJ8n}0i2G?alv5u5~&ktO84&(j>-g}-mOuv24jk`U6Lm~W@$=Q3$d+P)Kb1X(vT8EvU+tg^h zU&R+%?x%IR&xI-9eW4F z0rR=tUF=w-1*2Ab)u}B6abZAeykyj=@`d zN3j3$V?aGdi6M{Gs5hK<)@&_%PYQ-JjzIYJ7dTqHZ% z5~`JqHQ@i%*OE7wXnx*7k>mKs&q>m~aLxcTt$^fPQ|Fn9pM}hQ$AZJ9Bcq)S3goFm zo;?y+uiMhlV%ty+eek~S0LqZ^E-y_+UI8(iSW#cWooKES)HI;SLz(^=^ zIziqAjt08O6=cOFDoc{aHyYE`{%shr3WQQnz0O;3Nb$lWW)nnOl61A+5kJ(_1iq}E zGfczV0#-v=0Wa!y!FN1eH>=A&-G!96WO~q><_$? zCV3>*WkZ=;?+HB=9c~vXo3~%4m9h=9?~Jqf$kGeZ03+gk-$USqs;ZrN!|gtA4X9*5 z97wFlitr9-gY3Q<;JZWF)g-x-lIxt2DAJyeUYDMGgHP*9ON<2fz5oK_4f{Q~{h_Bh()9Zq{Bm*|$(yPq&; z($rl((3(&ay169x-F3BlGH7P=A)C`IP; zbyIaK6#ZlPbMLE%yC&Qk#@0azg<}HJ9TZ=@XmofyH}`R!Q5g11DM|c*Fv7a?)!j$rMsuxE5y4?va}Xl1sUXq9*f0ThJ!-D z9!;+DZHqtM&PMh)m5&t7E0b6J^@YtnRy9@$B1uTs$mB>8-*)=6fW3n*^*KdI8`o|B zgK*h~c%dGqMql}O{H5=}h4~GP7`s+*^xae7n*;uxyqY*W1usV|OZ;FOZtaytn2Gy( zL-e9v!ztn>iXl56DKno(Qo^WL^0~V!d1sHL;n}^g@0SoYGw*0KbH}$TpREvZibV>Y z7q$3i_wGnB+>fYR-9>vLsR3OY2|VB(j6%0!$6Y@MGEI|_8-pC)5)(@$V^9cz6Y^8V}WezG%_In zbiZ3RrFrn3mfO4WogSxj>+L)uQR>6n8Myc!oa3>)lSj}#f6plxXWFK~0mE$e9wFY*2&MTy5@WQ}ivn;l#aGlWLu`HvJt==lNt+o##9nGVNmj*d%|dqU{~+MTPie$Wc$P`jCBKba6CW;oTwC zj#p~TCZ69L)+vIW7;M%uOLx?hgC5@Frr&0WeNEJRaE0a9zZeAf<~(t<&>2HYB_)Lb z>ON!2U(16{x~6yi>W`?^z}0CojxtP9W7o zP8P`}J=ijPgdndP@t!s|DI;AMcL3dH=Y7a0r_?umHI|PUy8_eX%#l6lzDMvv7iaN4 zokQm9vf0NI?vK}yTrPc#A)1BOQ6TQ+I8F!{G4t&Gv`; z++VW`2I}-#+G7YcYoTQ^FY4M9RTyN@>anA}TbtiRI=1=(OO2sW?5*PqP=`L{wWvm| z@+SC)@qD)OFG&`Q4%f_5Ix%19#p@& zSz3Xmj#M08X;svt%Z9eo>SH&OO)g1z-$dUsO>(i9%0656a{U6ji5zc8gAx3AR_#6$T>#l@+~KSA9QW>{0-mtFHpZSgl5(*0 z1}KD(&~uY7=gfkdhQTT8c}B^1?-FghhDU6|n7xv-9d#?OHF*at{)UGK+2L32M53MV zO@H6ru0uS)(v{`+Kmd0EpF*6+Sk~hzNrC|K5!3ah_q`BWa|_BXfA2pRSG3a@==Bc< zq_!fRVnKe{N9%Iyb*$>}G@268yprd>uJZ$_6pHcNYtWv_@9qs#T2zeMfOHf~L$`{CcNrlU1!K!K=*f`BqDbtZU2}U!<@Llq{o~XZ z_XDiQcuxOZPH8HKbu8~xKmU;yN&Sl+T4Odl#Ie>S32OfbjOvXMFQu6LvTcW}4H4K= zhy)^{HNTV6n9S2ix|ZId9@51fdC_$ERZW&?Av`iK&;!sRj2*an{7dia+OH~r>BoNc z1BEEH!X}X6dt|yw>Wj$V+KWL}&vQgrr^+gg5j+EcMt$?-+P=8^^!m zZxj>N!i#Pz6u&bR(`|9w-Qn{9OH2MRu!1U5j@HxT2mL{sqqPl_`w`|q;;ns)q`R7h zpIC5_nO2j02i!OM=gMuN4Qrv)Dn1&P&SQkRWW>pi{7d#1nU;56t147@+UH zUk94ckgl*J4wnM;o374iKQ0@g1K|DEvxGBZiLA^Rk>d3u`MwC=DMxn|rxVhSq`T;L`esFC;X=`0D^A9_ zS#j?sj>^;pz)-(Q_A@aLQGvfduy^#oIVh3N$kX=mbQff;TD&2IS&0gO_*EH@1+2-$ zK?=b&3GbA2F>K|+^uK9ApF9xND=plA$4HlnPYgVboTSx!K2Kc6$?`!@=;e82Welm* z{;vEjKn)A>(=s-hDlEoRk#mapL(U=S3d%kzUj8Z{Noh7Rm|C#xk&kvse^3Yk4>73K zgv8H2E)fqQk1bY1`On*UZjqz_#X-COU12@`VGOvK2dD|y+*-pY7&;lTwcgx(%_Ec+ zh$oBWvo3?zVb#>~1+|6lV&?(KByl7XO=FM+s09Y1iobVH-g{b#{J17ks7y5RvmO=X zbO;hK)oj|-TErwNLgm6sy1U$noA0#VuC~=G0lLO3%JA%0K~B||=@ZEh#dc>fDqGK@ zPPMR$T>Av1v;vxzpMw2k=ho*6wj!2S;Hiha_yYQPK; z{m=)xOu&NOiJ9K5eM#+RR#Kry=`O^#AitcKCYp68 zaS#4L-oyLjyU(b1tNVyommP;?`X@pNA6Zj{E~14n z)gW=9_9$R&yYvvXA%5z7yqR#GfvYFqli$zWxB}B;qtla7 z`cdQn5 z>(Y1qIsC|d!V}lza@(Kel4k>gI0Z>Uyit3cz{kd%^0HTN0Q6YBDS^n#pe1FR@7L#N zD=FH_f61_&wa4ng@m9L(OG6I%!N`{pAN}_2NrLspy3jLMc^J$t@8@>PRLzE4%V{nF zoFT-s_xTH)_WrQV!sLj2&GX0~c$!FpF?eZiZnyo;dz%Yt2BKaf9r{1=B{{1TW+#nK zDJ|gIMR$u*+X}Rd?e&ScBOVN{0o-v>vVZNBp1dBO4A%%`0vOW$(W%eauVzqdvd6R9 ztxm0>iwPk-xzl?E{G{h+Zyv9)k$;jsZYI3PBf92CRmn=!vuR>njibC`mXbcm`_@x9 z2_9^3@yGy_{5<0P1AQW?M}-*`KLzJ3*3Ra6F8`|S@3=>>8Jai)+mO@vt{M;hzDwr~5Z2bD=yVqt(ICrfqKsoL(UI2$l4V<}tlX z6>_4OQuq*Uh@o}TS0`=)u?LXiGQ7@JY4Re9t#kuy&+PVk@uWP<1d{XuF< z?kjxGxx2OYALm;n&x>TCY{($0g3HP3zKrD-vWY;G*h7I}YdcUh*-~;?Zl6};Ro}n9 zFi;(ACuFt@h4zQ>dMge1O$v;P+64j67(GC_aJ`n1XMm2cHit1cVD4rv$M&0(`s-t# z(N`rk({mQ%H+PMMW5<{BTnOxaNgl3?R_YXSp2ikCNznlA*j)PzCX+y zdbpsw1&IS41YxZZWf@~!_GF$@Kzb0Pf5+#C0Eg-8qvVUDyCRXtw5s!%a=tH`!9nZ~?({Uu?hLKDKSDonK!>*xtWJdFDM}=D;d^ z!v~)AUKG8uHto^_`LYUg{CU58-zWwN6C@!COUXW{Z36~y{8hz~CqcCQMCI2tt!$Olk~}5|Xuaco zEgg4ZHm16tk#7O3)>;uO#r-0nQDA)10~;ZSYQ0`GDeCS><~;kQ@#XK@2e|_FQwpUs zxaVgWbu=_Y93w9L}p~;9U67 z$M3HUvGE-Kl-#6j`Hf-Bv!-w&j&`yJS|^#@6V8572-EV383}?9;$sT1 zV99axeiU?&UGSO)$IE(=O{$$Nir(G^LUv?Ssq4j(e^34#NCBaR;LJDx2f7_Iid+vk zhu=sQM!aObCm8SB+wdER*4mv5slk;2A016mhU#y@hWg?tT;ldoDqt-`nJ(Zv;AQxG zSQR+}Pbtm9f=ddMpm#=`z1$xtJy@=&GvL%@VLrmq6Ei}!J;HDK723jM{J5ea&!5VJ zU2LY)jX8c6w)Z}}9sf4J);qM}1;tZw22q3tj7O?(?FRx5>d)6w)QWs)gHT!C8cD&q zT%b{crjGKLYX-RYyc&KXm=8=;F#8(G!~VJWg|kdcM|J@10~R{q`urr!`R0fL zOj0F~ZkL3P(de>U+_$I8#l($2ZqXj0YFI*cp?(VWI^(nkTDzg|ckUB31^9r`Lyim!D;o= zi^VsU%Zh`m08FiTbxtAfLD}A)H`0tNH~#c_&p#+Ugs-7@!MlA`BY-D?tZ2;j9%69( zN0_aCA-MyvE8+?u9}_#`8|ZrniEfnU(8tL1MUpnUQ}(-HsXjVH?T>$aR9MV0gU6l4 z+%-KtJ~8u>ubG_^w#@ww=u3^X-=_;5cMotMecvB;hbF7VZtOnHklImx^37v$ULVH@ zv+tlfKzZQ5rJePXU#KrlZjv&+st}=*)Wu_P@eaSEca2HK*^m?{^lHcOmyMwFWlvci z`?z^gcQ3UM%p+T11H9vO`8}$K9j;RZ$CG~Fgk6m-q~Ua4ehACEhB!1)_X^(uG)957 zD+Z_tt_l4}@@;Jx^hXO-#NYmb|2VH7a(u{@<#2~_*$AEDKua@Bb4u+*FOnY?q9&=|V0T><_xMCxFY!?^E{$R5OR z+EH7?V>bu^8VlPeTJHxD=Ma#0&`mvB&QVu>*`q8yge`;SNt{1N24l#G?Y~seb{#ST z$WsTgQT)*Fr8XF)`l>B)O^&+-V!%ftT-A(s3^bdUV1Rh4F_W2@!MeUE3dQ%ulP>alMZ zg0emZASo-yszxT+dadc%B-oj|ngoKq0T%}*$RPIOp+O?v{~B;wq!g|mUmd`!Ll`9hJa-=q(r)i>9CaX6-Bnb24XkY{p|_G* zWtw!?_pqCq3VA>?4f6WAJ}dbi!S z9fpv1)??YRNMT8?&O(;37;nl;eClT~atj4H6eKn5Z<-)Q53Yn7UP9EKHr#dn9-nfY z-mpzyB=~S2q)#bat71N_YJ=X#s6bU&#b|%@*%rSJ$WqLjpJ!U=Wb67M1+;qfoWD!s zEYXt3DSU7@lBbrTX7tLZP;48wm$6r1V#+M$soU)_%jaIeO{-7`>EsB@&d(3(ia)jD zR6!vl3F1>yeEEeFkCo{`>f>1$R074RE!D7)qN}S6cAclZX!ip}uw}*ZP9dTrkLO0VxyA}K+Nr4j~0wjjGTxWb9l+*dUd#~Kv z_;^ZL`*?h}8~(-wZNNg(259mMe+1DGnZx>v?Vua9dWD<@h{xv7i3eYp0{ia)Lhr8W zva7cDb3&ml)JfdCXNkkwiKK=K-4m20vix^08nbT?qhnuDYx`-17k(~DNj2cIFqxdO z7ksAoKZYkM9iUGT9|m@-wZpU;4(tdUeqDdhvI_eD@CuJ3GA59D(Z{XbzQ?x~6%uWq zxi%9)8b5}_Plcp;cpP@$6@HHmH_zWhvDukL36+bo$C+97e&_^oANxh_Xqz4mPvl@D zgS5g^z!yZx%zsjK0n9alQz7c2^RG~L<=H^Nf?f9zN|8YgPzF>;S(J;okq;ECtB_CE zjBzjmQmKo3r>xeIEvW*_Y2i{i+ZIo=F8-?q}48wNQ}4 zxo)LO0+o90k71KucykTIA+kGk(>cMM&r5cIKWNTihQen@M^qDT#P!<384`Bo!|oxe z^`WiN;T%LBnWpqWu0}AnzAgQWkfkLZ2BsmW89b`ncu!;_s7AEGAKZueVCuM0jp#9ufA=`Q%$h!Cnu zlv(_gH73MyW6IM)7Q8$)c&UkGa8+g<%p`NwcxtPkRZn-KZUX9Xd64FsXd+ZwYc zmVuu6ax0|5$HzeaI5i{D_-zrW{fLg4)LoUq&3{->v!s(-Kpm#fjUAt7;&}n^U z2opIF))anelYJDRM#RIfoJ+YKvL~HpPW{5XMgkplC&)V_3!>;!at8^6msWZ9ET-~_ zo9zLvQ?Sv(5ZlNQuAox~5e+uRFfl7$!L2cqL#qbD#uXXAniU3{+q^-6MyK!cNmP$q zOyp3DiDgv(rSMs)^~WoqO^|=sS03&)GOLCw;B-583hD~#&=;lk`9+de^_WcT4Opn< z${?}M^7Pqf(pVQh#Md8mG;Smv50>^PaacjdP3x?FVQai|vc9RG3B(ZM1qIv;~A1h~EDIL#sr`Mu6%TI^s z20H4=q^RvXZJ}`Y10{nIy znHSC&g_R$q)<;8!9B)bO*3=iy2c!Z1SMRlmm(anZkfLf_7=t!pYiU`3$QphI0wQMl zyhJ~u;By?`8jZ=Qi}$`EtFQnXbZ36Qx01YQ_JRowL-T(RY)f+C8Cd%(kdX5a3iLzs zy$+>@S*aahPbigrJMTt(86i%{5k{J?GgxqXHRyyp=4T!hX@Kk_$-Ia3R3rTW9M+{D zqLgh?oWQ8?I?XXCr{L1E?9i1YQ4W7V568H(+)J{%#a0zW_MZ*|I|cc@{E{(dQyFkH z$UTe?w!)D;Fm<%rXW@bn@NkCl0r4kjy?Lgil82{aDqQMM-oLt?1%3E-rX^$yDhKx6 z;1Jj*y%#n|_=iwQQ5XMlBqz;C8tNnegB6|vxZ7S~Y#XZJr1204Kz(!o(-$&u&L%q- zK1L+Y;ZTT~!P$t9yPLl70H4gd<~vP$Yet&$9>JT}ky?$qYg^lUal#1+hA4Zs74T4o%poSc zKQi&a5p?KQRn<$r>HGd?A4>>hN*lw6d?9ljGGY8p>WhBu@u1F~>J@r2vhBGejDnm{AdZjslmHh6I)z!I@|= zB6)(fJL3EUb0^7hQf}XRaieJQlb<*Yj^65(znk>$jigxo-2bpCDdYERF4V2_ao^q8 z?(Wy)cOHL88e8Dq3+q6f9NMkDeS4LgisvC9B&~}b!(aVP`$>xD ztHyDr#aPx!43rD}^ys^chMInt<;+m>%Qar&4ZXvKFmD)@(CwG$8eNI1p0MpekRZe< zHYb_uH=4rGQcu(aI1#AzN8a4PA2ZFV9k0*ND+(89I-HnqqlL|yx5XPiXs&4bJ2c4J z+!ofX9i*gsz*l8S#F^@zPMk18eelJs6+iN8pPiXGSiW^ULK||&&^I14XP|g>Bo`UY z4Dj4`YP=7!9m8S9tsJ0a2Rm%O5tlglr(YFjV6sHq$zc~CWik5!JfzdDs&~j{3>$<5 z?S#8LILN&$E@bKzAfxNzb(vj-8-9+i+@WxJwDlt#IN!d43VjSwNXRmkGjDj++LZPz z5E%~OK??RvUB7%&r_7jvk@XXM0VPI~x?yMQW)QnbOuAxp1eG3(P zE0B&+6;$0>3@_404m%sx{B@VWa#G-gjax zeVE_(6EPrfF(h;)7W~JZkfA%7wfzGyUF@fuG+-|r%fAWbAG7lGr>9=R;zeb3dx-Ad z%&Q5agWg)wBD-v$50S8|l+z#1Ec~1<$hMBt*zbH)TE2aJSK%+LgJ{sI72dyRRKxh= zpkIteF8m)R`X6qtCN{|((GjP^{+59UpVY${!6A(n1j+63I~ELQ;a}RdKO^5b|K1gF zfl{mZo>M zKG~h~I^Xu2aTdyHui80VA~o*-eIw>h!JNN8w*ukc{eX1e!o@%Mu_giv@Td)tl0})E zX8!J8Z#=_*mj@QI6bJ>dT_cjeO-^`C{r)1T_;fN-hq)(46fd#iyEla4VAFu20!ByG zM@Y1ro{<@0%SvpMpKzk4FY7s+wqMb=GaZ)=s1S9U3(++qN`C5sM{|0yZTN#8Yni0l zBIiSfg-^ zv{N2jv$lQC_&@vvp8rca!~?>IY9moV@bH>16)c@{AzZ23A*e=3kU+Jo`bT&Vw8t?~ zAIB3?`z~{tjwk8hNucYn{PWB!pSJrFKIP0`B01dNVLRqd|uh=D# ziGE^H{E;6_jtO`$u6Lc7#H`s~)!$^=wTz|N2jOds%i)A5jdh!^oQfV1QkBTLlsVDN z&AjareEp99>nqO{6fUzB#~l`!XPQDQ@u24>g{tY{^qscFx7Wmd)F2>plF|KeU2GnpH^nCd+i^y4wlq&C(;Uikqo45x8k&@HMY zDGm8s%3%8(iZ;qtem(W%Iyb}&?QWCPSLuTF=v%l$@q%n?STc^o>4f z4(W}(;b^uaQ!c{nl}?I%#gCgCNtMh$oe}<+2A3h7t?;S1w_8y$KX^P6q{e03^#I~N zVF4N{p)axb5_R8;+LP|bdY=7=2gK!)C-LWbr%-P^AN0OA=3{et2hK4TKIWUF`)}>s zVfU&c9zDnYMf6k=j)CDg`0wzIZ1khQTq5Og%`^=D4k;cWJkO!xT7wtGqTR4__6k&- z7X{mpxf8r-13Xj;RwcZf4vIMZ2hS4L(O9?>*e`dR5Lp$s`Mu_8PvIZoWzeY>ceShh3lr zLzIHiiod;<3ow_MhCGF`DKqAoDx~@2Di}BqTc(CLJWRcJu#U>j@8c8C-T&k1ytWn9 zx-I-lDiXXTC&@wKP6PpwtO7p$>2uZoPiyX7RZEuvVTLh!|2lFQH0hXtrht!lLlU)0 z3XEMrd4n9?&HC+wG(rXzk|NTN(4fKbAR;kZg`z6Kz#X#}ul^x@1EtXApj`|WjZ@Nb zqVFhqpC?kHfa2x$m(qiN7tzuSj*7YvNDTNZ3VLJ_f*X3ZvBXalyC=)m-#`YdBkb4I zt&)IK5F8Ls^eLO3tAHJvS|#3Q_!Hse|K*+T!E7?>BTaG;c4BsF#xFw6k(NOY+;{!w zKD^@}3Q-2pR1G&;zZ$RHyXnSkJX)bVn%swD4`1;bRJ9)g_nmw(Ga9bKjRx4}Hh1n0 z$4d6PcU7L{<{2|k*Wh*EjyDLayz?%<_6{lU=_7>lZG@H$YZ@g3F=H;7!faE#hhv*B;fBQ|+oSWL25I|ZNiw)0qTIFndy zn1=oKJsI0}an9kbhtkkP4T#0wy_uh|%cC;tNt*mns~YP7rGw}LK9P923M~B<4(XGB z-!e}a^V{!pgy#PmSR>ED{7x97gz4U9jbY(8VfXoNr7WKt!~$3O{)0r!t3unpacIsR z2UszOM`=~(8=@jOm_v~I(SLb;xqT~a!19=<#-gf1q@j>l2-f{=h=5LuRDT=K?*0TP zNu>V>D%i7NFl>0I~+eqNhs=f1_UsU#LDrc!10Av ze|n84KBVq0L*{)i{bQP_gjt{cLVZsm-sb%gRrNrZ-Lr{yjwg-i3p6X2s&~zOe3M^G zDl(AWsGsw{-7ReDKdTTokoWLn%XxTG47Jy$EO`2!$aokfuK@Vg9dr+ytP41GR8Rq7 zmZ@id;jS2`Kc0FQQZXJuk{Y5-DfhQq^E@AUUQkxJIS}qTm2v;Zs@8Ah?c?tXO^G;e z{!92a15gvrUcK3Sq*?D#-@wiZ4sTGq@F6v%+;UH~r{LZ~W%P!*!w0-4MW05=SX4%T z7vfF({`OZqnuC-6o89RCtQVOvA`a$Yxw&~}IXd{ur;uBOyP<}EA-g~T<-qRnf|AS* zlyFoYWD7eK0?nhH%irQT@?69K;@-}`lzsDH$kdL)VU&lU#4*C@3p5EJXX$`IB+kU6tE`^M~{#w8%Bix(X@bn?c*siuuzFEg?kIXopGi`;}O9`tKsL%#^ z8b7D7h?reE0Sq!5rF9k+zyuu3Z3^*`WOfZw>v+jKj}}Ka}Nr?fg8TOPrF~Hpt@sGb3yvtEJVc* zv}?buWRt>bdm$|=JK#0Fhq~W0L`(J(1DY5Y-KX?29^Lecp+&@NVg41+Wht7@6Jf1+ z;uj%|&vss`?=SCj6kodcwf-V;VA+uogsWWc$dh(r;>HIkyB=VF{IR%54j|B6+AWAf zj(_P8jR>#}VVOP&bjF5|BeD9$NsIGR#M`mBT(3LQ*+0AV!7_&y<$$SWUe}DjmBNVU zf>c4jLk)+BQsg8er>Ef6Baipnq8Cg%HOr}a@p7L09Xb-!vIbBEbAX~@(%pad^(U3M zikgsN(m4&+-uLakUf;BJdH*D&jwC*bOne!wUPM++m`*Ve9MS)+$zpC+86w4dcf#pC!$I)#|TO6SY?cLmROIu>9cRSNB|EKR&{os7L zaC5;;JY%ScY3T7Nsz!Vq@ISybK}ABniu(%)+^{IFzal^o;g8*?TCyi=v&XxhS3Vd* zj8O(Hy|q41#fH=#ks6nnUWwugblOMkQf}CB^Ipz_4Qv9Raq>IaW6qKJIu4o}Y}hPc zg*%Geny}9%!#&fQ%d+HzK54+fA}+D94zDZ9=%&$>DHI1AO-pD8k|Tf{%NCCLH||KL z$#Bbt9&As)_QP&uQSnk>Ef`P`Jzv;EbA#g@^<4CxU%%T+S#+LU2GpOuN&Bbb`%}@| zH{W1U%!*nPdoUhm`pR?EAOAK4IY{a&QIF0;^q_eRKMJd$0cJuUk34W>V0KQ=TonN+ z1mA6yA8%lM@D(W&ggD@Uhgkh3DA4(%5ySl#Yd)tOdqvgH-fy?L=gS?RN}%o;yoZD( zO4QQrkDN-HbfwZ>0>u)n8N%B6e=_U|-@5;UZLe*;9+_Gs^-Pmq+h1f3($})$flXk2 z-gK5?yU(fGmNiusn!K&ok1Ptvx(KvE%qag(D#8pk>F$M!Ja{T>P0qN(-x4T-qc{5px8CvUx;|6G)2{jh?TyEWaV<2v9>5WswVF4@$Vygn2iFZ*QX zUkech%oI@e!=4Y88SGl{PQw0^-RXz(}bcG{v?iZSrl>UTD193|C)tt;xnvx#wjdY4=C#N65o7X9v=w*}QY*o2 zJS4RCfC~2Iy_hR!)=kj#4zO|d@%^cc3mtgfP;lIDr~ZBXz% z5t|350DFX0JV8*po*AjC2ix~-Tw^&RzE}HWkwM0tu3s*tzF&*9WF4fG?0`emQC96W zB!yNCFVCL<76s-2j=43G{e=HuorHa&*~>uJliAocp%MM~!2pEkfVjB%_WjM@A*~0R zoCZ3+&$-{-T;xCdFX;fn&?T^p_qgY`3ETRh*l*U2@fRu8%r)zk0L86R&|a2?rW zQJ6lSm)Y9l=aan%D)L*BzK)js}7sE6HFixphcA zhA4`NLt<_&H$3M2#mM~XMY8rGE1~evpay!lM0+cOs@xZzf6aVSr)Q;UI$a6%>mPly z#Jb$a&ddzH)h--lxj786KEwv$@tHwwi!R%1Hua}1#{v5y;RHZ?AoKxWy}d8r^?zKa zMr?u|#aH4TvEEmmTwb{SvHzA0Ny&&=KIKoc>ndDozo%O_fZb3MOXZ0k3j)}H=eR9JV)*1pQ!<8H@w}IRe$QKn7d($3~Q)hk=ko{l?>%Y&l5t$1dLI9 z)S6RJk}@av(zQqgpQ{Cej)`>a;ML@p8MIbd+oOku-5{#BPcLdd5&C&{>q{c+ zu1E&1_SxwF*aC&|r3a)GJDBtCce5hf)_JQgY5Psq^z@=M&>hrhdY>^XVH-HronxL+ z)8^#I8R8pIct1b~HwGLXcWkHDCxV_-LnJjK_zor95Z{Rr%xg=e+XBLKHVrLBUOp@jv$Ph8ReC>elck$yOTD54|3hcrjzq zF?=7H5e6wR;b$;?%?@@s@6uf7A5I25Q^e}mff{14xIT~bO`EKgC9XY;GPtG)PHp? ztRX}_4JP|iO8ru>NE-vcSB3LWxKHUx{hS`(2Odtb_6{GfL;4YFI-q8~>UFq~8Vov2 zj=aP-n|5J%jyP++V0(8@-`UMY+ zcSFewLwf#O_kQ0P-tbcjlmG4g@7sFQXi+(zlm9*D{Z9W|oyU!6B2CPh0yp*q@>~t4I_(bqe)k5A@$$<*;N#5Sc9mz47 ze4J^DRgvJD6a0ntECy&tQQEk{hzi2&4Rb-uyT#^4If*h3iMlexGg!3yg)yI ze|Ilq^l81IiD3uNOY7aj|ANzOLN7-hd{cdTJ2U_>DCZ`gHTLdq@vL=pB7UU4#1mg4 z$*u!r|M@|F#9J4M1${=wvx0<`5|VbXZ*OD<$W((I+^&dind3=ks~`vDFN0i7f7Gv? zain<&0Jy^kz~LJ-r?1O{$-WI)HYVGRdm`yUn0}l9p2WlOINy%?=sI?PZm{ic0(8jx zXiEgC4r|*>oF#kVE-D#B;oqd*2jc$>2hec96(Q#$R{kXaqk}L+6*gdLws6%c{@Xb= zf*W)wm67NMu;pd1+(>T4$Mw$)-=uX<{D%7<@JDB1?+Z+6?!MapQq9Ojo_gj+vK~JV z*5_6I^E$XwgXMNdT=MmElf=v8w^`)E5i|fZ@n$q~I1mYopGf5L{IFj{_qk9+BZq;0 z)pNa@rXSLH=3{{ZMn*2)Q~pBYN_Hjr66Cajr)R!GXZXDF!H#)zl=dZ@rXAJ%(6#x0 zj@-dIL~)yESQH5IrmDwZx$AU<;AjUg6_9mVIp=N&HhB+F-A8+!G3MezK_^~4e+uH}l?MrAipg240hQNtu?jww&3%X#v(~qz3q@?)uXZ=1f zbOgygxP5ndmpaA!Qx8nu^hmq8 z8Oe$S?hu+DP4Px48cwqCHu>n{O314dQg`!z?ZZY>nLac?F+%tHwlZ>vnfMo14D5jS z=XR?Q09PC$u_H_Q=fFf*t;rtv=y$MAsok@vMtH{GENaSA^n<;OrLOH~>72vufZy03 z{N`58k^-N@K){)`kb4%HV@ zAGb+L0amSuXn|Byhr4xd-tB@j@n5$IC`s?o^GAbmG>eYR`REYYUdo#bt zZ0S-I<`lFdo4yo8s060_V`*O=hy)T3A;j%k!zf}z=EnvK>^a+AQCahz`i9V);hpMU zbIf-eo{2gfQ3~zSzvOUKNR~IeF+P$^$sXg`n+~{A*rQ!!+x!**3(bt>BVH4CqWVtM zG}5qeMSAuNEabbGOtRhak-6Ss|EUm=vJ^P?@I!O;*T}3-=DZ0b!lVFS6~MK)0Y*P+ zz`;c-x!SB>duy=%=z&=8hQ|h{QwZIF^%MAK$F#QI^np=(ZTnC^6zE*E6Sr-y?Oy$4 zX!;-B7fqA%35gveGolHXsn-u#tHg~CIb5^PB59JZKlJ>(KUO$#Nnox_momkfo6k!1 z*o80N>jTt^WBX+{(`g5tiF76@;kb|z+LwU{{6kV`ezYl@z^!4~rLaSU%JEW#qdUqj1 z5H?_SJzvjTRrF$pz8F02i}6eAGxnrX{ZBc&uH$~z2HuG}M}U!R(jWAhJsiNF&h{`vp6N3+%pv}ry!09o%? za6NZqnBQ0450Y{I=9BXosihaE6JjoyL0Gk1@K7 zS@39N$L)#@y#%{g4V@Kn~vmZAfrEM~8LY%=j=vWDqO8{~FYzbQ!f$+R;F2OicB1l^Z4m-SczCxa3 z@+KO>XSF~qgJ*Kf-*19K)A^@q{xhigFZy7UrbKpuH*F1n7ldqCLlD@z5^E@7&9)A) z67Sh6BO2Q8XD9J`E0d$q(+LW;U@o7D5=Ogqk@)9T!IND+QOsQ&>%bSK+Q8A_i*2%! zB`c@?5D?}0z|2EaS3}u3y5+~ZPNsGr^l&wxyLm@4t2xwlRIulDTJd*4pgUeLuJf2; ziu;7Wdw=zlU$o98zwCGD@-CPC=c}kE3l+}e@|XR-`uXE)mA`1(mikgj_V`f^Ij$_H zs;o~7F_-uGn#&`rDu9&(1gBX1OY2{L6`)^KUWR1eX2<)=ige4N4>ewxlE6tTE%fCB z4k8pnpP6{J7_ESOSIQ1qs|K84VUJQ@)m1LsuxkJb7vt~yFJXA$QU5MeEX+AJBSX`5 zoqOg5moVg>W+f~9sI=NEwhmbKU-~^!FAyE*AN^|~+YA$ZJgi5);U18k|F|0aKcxqC zp*t2?l8W2sp3)9YGwtw-599#qP7Nfh!q-MZdI{KN9+Ed+9k+*H7TTO3!F&^+{!ASw z9BT zz?~$)A9eOhH9K0Rp-6?nLs{-MK7CgkZO4C0NCI^c4aW2_nPO;230z*fk-pAe&o|Fk z$A9ZKOzlGRjTBUX;godO%&2J#WX4cx?9K^t}l@tmwPm9rlF0I&eZ7q-`t{=3sjl&a**loZ&$v_BR?dEI-&_5xJNf$^DQqZ91N$HZv z^RS0Ne3AjVBxn~Y@K(2{FDP;f3M#igeKQ&%EyAH8B*Y71L+)3S`AJf;d`RYD=3qGHWYe| zbID?~=g2wrs#OMO;DskwXhKSCqXwuG{im}nP?XT6JZtm)7jsq(4gar8??|hnHB(cUS7C!=x84lcTn_)C)TKoQ#!eVW%?H#F&c=;KN2mz zR(F3+!TgbpQrG5J7vW7KA`Ac5EZH)%kxre{79rxzeQVJOH6~t5knq1;q&iF?>4Y|i z5bQsH%ex#RYST^LY7_o>Pu@8iBPd}pZrxSb_qLJ$ywJSeel%V6_!d1kC}k~J$F||Z zAF53ut1#44P^Z|U=3>-wG>f3-=s0IABRl`Y);N~PuPK~z0%MMct@9qRG%VfL$#rX`fnbc}bOTm~PBe4+7p<840(8j9>N zNZ(nQF^K-`^g$uyd&S=6Svn)CPTwp~aONlExAH9z<2zzMpbY`_ZLc?SwY$>Kb!YMi zPkkVO@@(?=YV6SZ0f@+_D?v zrN6(UNl#7n}`VbZC!MUeIUy2Pea%J+6U#I350I%_r1Jvim}cD2P_a zg3aWqj`Q`)8}$a3FFP$q5JS^WfCbA5rx&%XG^tt&MiANOT3x-& z|CH9f4y&i=j^I;D;CSPL+BqGArD~+C0B7E;wa@BS~Fk6U~^H^=|+s>zw_Gv_P0rk)3JQDAYGPX376`Y4qs zF{sc7XWW9ZRe|lHk2O<<{Q17$s$QiAuwe#LFh;&ip>oT^N?&I#?%()J^gCmA?PKB?)vAN21D92;`y zR0ngafF!Rc)~Yc=00nyFFw84@V&fSV+62Slz-ShY%Fmsg-KO=;+ts1%|4)1%VH0z(j>x2Oz#x_TY`5NNdr5>;fnHn|<6@8;lRDFxD|2$R%8 z`w`ZLEkMc)8iKdJUw7;|Wy#m^poaU-$6G<|&2_H^-nQZL_QjswjHa{ttJzWK%NvyN zW_zBWlb<^R*~KcyGc^Yf%S>nvG2w?E4+!<=L_YG?_^pO5{m(lx>NURDOL=VWZ^Qtu zyBbSwO&9D5hzNdvDK4+~uGb}3r0(QG!Hv$SuB=1$ILpr;d%gQ>-wY{@@G{?^%Mvw*IN>|3D;|tr#4!uD3S=rC) z2VU+ak^rDM%bfU~m>FUm$3EQKkQ*BHrG}iG{OW#vu`TH9tHJbB7=#;oV9XsI`rKh` z?z7Ejvh97gSU&8x?PN1e;-S2$*Z>l~~&F6*aS5#Xf zm{dPWKh?=E43HbjihhW+&dO}vP{d|urMqT~U-?5%^T~hp9=+J)JSr-={i*QfH*J1L zZ;3M}c{Sp=+n;GnAWD~Ds+`1B{1{mA;(Pu_t63fs`QZJ2)iV~+9I<)4Ij%bas{3GV z^7a-KHUF19M!toAx6YlR#KFBA*f8HrZx!Lk}J09^#=219Cq(Aa_Xn11b2iI=k%m@b&^1^v% zte4ooI|ZBp0#BH5XfH7J)GfN1Khw=!vf6JsCs|kH`SAg{R^SMEVmZ>z$A8T!K_^%3 zLIwofIE?iO^1VFe=KQ$g@A<|?#&3r6rXrIXZX5Yi4N0+Up@5s0z-}lV&`JU4R6gp_ ztTD1u;%)#ms^Ga}4o$H6&^Z5T?%`8dcvRpR=+bX4nZzUxFG4(Zs0C2 z!3v-{HV8Ag`LylO>KUzwyv&xy{B6FCWg;GQssZ9O?8Q;7umV=l_%x_$vp_YBCVLhdrv z6xD21F|OqbR`0zBg!Y8PEZE{G9Hn3Ig2FCXXbwkjHl-M_Mq?7!LWlqQJWT?x0BoaPXg)U>93+#sg(Qw1Bf$ABeL42UiG zOTXFSL8vGTRl|kHqV5EXJxs~_-V>sMu=sD8oFt+-V6QE>MQ$bW{&TGh2p|`-EWqtV z>X6Tx)K+l=Q~L1`;Z(ujQBu(~XGMM#sYUa*8}mazN=?3;k|?Ig2eBUPpYec0>0iGL zsSdUIH)p4lgo1-|PZjH8ME3D}{A+k=w&q};uwx)6;9n&uL4W=7;9v3#=In=(nR3rl zK$Y?spZ%NAr5@7`hpgcNQN%QLsLx_}qL%DF8+6TPuP{r4F@kMKs|%oa$wKRJ!Kgs% z0TVu?HFiw;VmijtxVc%l+dEwGuv$P)+-O4N24rbU&Eez_sw7gDd^p@YE5tDoGPbJ` zn9C&w+aZE&3aIMu8qRtE8+h(MBrSY*y9Ym~-!P-V_+8+oyprjftnPkGh5vK>wu72b z@&z<Loa^TF#)ho=kXTRHE;1NpG_d@#Qnw!Q%ELYf0P+m|k_&eI`3X{QwOPP*n2X z;gm5EvZWsTK$io=DGCTv;HS!@(%04iAt&AO8KC$@Qps}0npsT)hZ*;osQk0(obi`x$2q4nGHmT#tCnv$y^W=5op*5}gO3iva=1_pS z7{19(TgC5K`bp_$I2B8Kt<_YRM!t9cPTPMc0Sqq%_>~ zU@&UhdSSwlV$Pv{-+9U~Ter6}p|1Da{{g(k-F(?sDDYfudssQqFAo}7^VH0ffad-# zq+fP8eaU6#I4*Z5Iu)gol;j1u8iu3W%Rq<;euf8-_+zDR5C8ol0HI%uVVE&K0*;54 ztu(iF&TnG)>G}3zyb$zE@!iYc&o__AQIm%X_|IVlAl_&KY%wF`7S#jl=)M_NdjKF| zi>EMVb_RV5n$N-DYyZ-OWNbLT?0lG-ia)*YlL}INtCRTvXO(cO-nHcC#Tcd2vn~+{1Z<6HKk;CY zVTxiM&$CCag$a?s^p6uG)B0#|BJ&(<8wSwz0@L0iA(rC$qCFc{NRHvLrtkZmMGmtg z-Ahxq=JUkF@Mq%?$VID9Tl=@< z$v@G%o26uIqxnDAWTNlJ*gj_?+n+UttL?VNq3)l?NBBgWMiAK?=^Pb z@NUI^${m~&nY3WRiZAMCcutPxmbEaXXZv9Ec%31u zGGxNu-R9lb{ox(N{zdT`@FkC^PaM_wbJ=OH>st2C@qKS9Y*O#MWq)rw`|fwyw=44J zost9UfQ8jAdv@4)O3;lQog4vu*-;O#e;!|zpOr`ammoWZ)tIb>Kr-z^{w`Ib?3T5w zFHp6+-Avt*x<}3z(PfX$K!xOKfvEVI=QHcYL8q>Be~3Q$`vXS)}))rUt7+favXdc z_lhGdOyAS16J@n*F#gu@q2xi^u5?-~4=v;aeXghWpqJ13PEE1v-%TObN=Ola&Gv@r zs_}6>)ltuIn0momr6q(GdXBE8x1#wcdr0YVIcxqfxl2WRarjGQ4BjQ0oc zO+v!8wPtj9u?pJZ5Z5upu@}+w`N^)~3 zNbZo?;jE2IQ~R@F&~lbwCL%+AK`$?+?(mfeSkXf!YW)TIk#B;daOCGwINw-5-Z^!A z>`FRD1LA1QV)A{Uy%U|fVT(&=TFnF(%9XDxZ&sCnUSCq zX=&75qw>~Gu%3iHQZl-Eoqnn4o1vFRT`g&Lu-Eho=75-dhqx79_|>L;Q2yjeWi0Ni z$jOZ!%yM}y4*k&(LJ267M-Gf-$=nh9N(g_?%V2qE$m6HnPtm`cX*{Uj9IOs*!giis zb6fvW(8d8E(Hmz$*e*=@%bZ`9kAy-3IM1PcB!6O)?k}wR;04LlM|Uas)E})FRddr7 zIVpZ%aN9K3KT60wUpyT!k`(1MvC&^!coUCebRn2Ep}I)O6$SFrM1T?XEM9N3Is>N> zUWUS#PvhZvS4tg?zcI5vyD~+5B6Y3`gw2SB2P^rb?{|{HpUJlQ?;GzfeFJLXl@X@-Vk%uwrlm_gayk=(5(m&TfwEdd+ouOJd+t@4GNiili#l z&-?I^CpjpKZbrJlh3sXDCk%^^Y46IZ`;A2$QsqN8|(Wm zDOvY!d@1_gveEk=dS}ci@7e=U@+52lwGDho@hp$)> zFMQusqw$^@E6S$G;EX;!C`V$~o1&cLv2dlD9V!fSX+ zy{8sn=QF2C&xH;vrxO#$7o}~XgcAIScVk9_m(pf#{^Q9er8zOTGlbL9k5i2Pz_(6> z4wo5c}EK+>)Dk$RmIzGA33Of-MiUH>*{a}p)YG0rzL1um=1FOWUNLWU8#!n>D z4-6ZMDTV1T)?ulNK!qZ7*RPn4S&?F9I|G-{Z8ZrJLbHEPqIX>=X>?6vSImS z5WM;MEN=SC|3DRwmGsv@@9zh8xq4a<_qLS*;@rDbkWbVPuru~lqJ>sD@A&hEdqtnA z0UzC=>20`%!h7w}^!c8ah)js%q=a->KvwkV-&cmO)ew=E%fib3daS*K(9DHQSxRXl{#rEwl&F63SwZN8~H?Z23mk8>^KDG^m zt4fKt_*M9US%EmZ_*3IL`s~89zZ(OEjw3(Bn(>GiRCTzNdg^n%r_srMpYB*L{s!)~ zD}fV=jXL{GWCVOK?DO{hXx?)w(-h#cKx}2+GQ&<((==x8BWPG6r<5ORD+`yK&d7i^(ty>SE+6z?U`It7!yYfIr0{RD;qXPBfCFl_kjIxG1ljkQo=B}LWWn=!Ok+fm z)wKjFUw?Vov`hA*{-`Y{)JOm=rQ}c_e-t}2iGuJf;`@9rns~oFqm_O3_1z-NDVNO4 zh)}rpKO-nO<~^VaRBUT9)<=MDk5=2g(=&VcoNF*6k?q1S9@K9um#Nh#eQ!uWBiELd zkJ0)&e(vo}T+KqK!#3SlD|?hVMpn&;g4%xprf2FAhkEb@KaNG?lmm6B@|s&PQ>eAx z{>t9Y5&0@ujFti!DC8p;o^cR7_d)D+xi}oi76d&x`y^HNn&MwVmHWPM4yKT++x!cz~{m^+W~=?RRL9!;*k=lKy}56+##a*S@LRV2!H~xnnb+df(TMAgtri~>w5F+-_E`nV6%p}cLS(#Fhu$_b7DpuIe*QG-@ zFO@tMB1R2o-xi0i(R^(fN(&`9a7ZRbm4i9IRb(yJ@aA)Cs3x|F&1?5v@3G?LgD!dc zibJDJag0+=Sy9h(H&&PHLDd(i(fE#~H*$}2gmb<|e%w?oV?4le{=B(zU7Ab@=ewubPw%1ri2I%$@^ zT*9*@`2I@)f_s!snS43|C(=!t0jqhp^U5o-0u(v!E##-FSH6Ia&v|(q+xa(f(K%Xj zOp}8Eo6H0X57@fC-w=|kOd|Qar+-IPik4G-Dkt&l*S)tNM5&ac!@k-BK@(kRteu}h zkO1b0Hs+SxR3TLSaLPTv1N>i)cr&4>0&>hm005!-G@hl6{4TujBm$-288@nfEL@_8fK=u8E;0=Fd6K#>7ed;awzC#E$o%3P!4SfAjYQFZR z#x7(h%6U85%pYV_z@(^n@D{1zHm=7|9sD9$w3mUiUv~7mImYcpHXecp`w!9 zSmjI~w#U$68;(4p%Gl=u93a&Nbtq&<_jWv%PZ_7xFTTkxz}=qKzHib{?tyEH;dDP- zPT_7hk!jkygUhr-`73pUz`G0TSRqd46CcOYgvc$y$p)d)~0jw8mJ- zsxbxbh;TXk=~FQ489iCG2}l&DcS$s$@}5@@?Ek*_&uJ06kUYDWE=KfSPmSLNhUKb- zCHQyGT~-5poaM42 z`?~&sq1ieZJ0DlxyilrYVdIhjO892Eo|d)7F+oMRC^LIj{z&Y2iXZ}!n%y4cG$J0U z6!IICtY&w3CB1sEgxJ1l@T$H~HL{69(nwX}4dsB`>CXyCt99XwS01P$788h~>s^$X z$LKbeVQ?%tK|;PGBrQc80X|#AlykijO&;&u^Sgai?!r{*vJu$acMLpMt`4sQ)=$s7 zal{dfc=P4Qb@ z&VpS7A1G|2IK@V>-6UN*^}YEzHEN@Wn&SJK5gNrv;<(#Drh75w zj(vy?Sx?ONU>;{gQs0K2@v`0yoWry$a!*xxR0=qSB5$*P@fLkeVhDKM$g)LBzDl(t zg2UMVQb%gAZ}=S}*p@9VkyjO~^5J?ft`UbIhd~@GRHq_zoRd?|i<}Qg&-Hhkr37ET zd$ivb+j&>=GKeC)4tu@^B+7`dsPcR_F~c`S{(~cYUY;fxTxjJkKV?$s;s!Xf>5)ys z?S4eg`<}700)bHt{oD<;Cyxee@`@KldGz>rBZBnQ4mbYC{rt~*1MKbfcI(_4n-*TP!JMxbN;8|`~p=6;3D zjUSv`yQEE`Odql7M#N<<*b$Jy&fbFhruuE()hfdvIKG2%xfYDg7@HX$R&;`B}WEv-Q9j* z_MCr1z90w5h6f>m(qX!@{O7K!F2tgTeX@VjD6Klp4%e|zGK;mWl`K2GQ9i(QGRnL_mzTQ^?29L8abiY+I~m^int(|{8SJdDYcPD zz=R>~5`Pj@qE_{zP_TA=(`Fe>V;ps&93CqwM1&syDBYr0iI=|D7m&eLCsKiEm)3`m zG;aEGIq_<CIU zU;Y=``sK3x;8?+YynA}~^!ciQhCGD9)v}9HA)fPv)+lS8cHDZavvG;|~!XMpep65Te_5N$A>?$HsJhF&Az_DFUW1w;jWLPy{rcL zk~9C|0)T&ae@{+G7+mQRm7FSNF4jW5CqB66yazdUVb5xEzqk9}a3^edoO957&rTqd z#f)JG5oL_GL;MnMELukKr6~H=N1DvW&E*~bbToQy2F0ZHh*kgW9K2o%W^6QP3O3d?z7OBo4NmI$NfykH0;$J+UMONj_=FXq=PG4K)*a}n z{1qf29|-*#n}?fif3XLP!l2%75~JC}?#FZw@-#@$R^k7S`z7?C+nMDZncbNVVnAQ8 z=0s8qe-3Bw*-l)msP9#_6BMuIi}g85{9CvM5xKab#qb$YQd$sB%I7@xfm8RnLoB6u zK6GN9Y*kN{Pp*D-K-+X&uA!^nP%c#5mp47IDZPo`t4Hs5z)u2BBIYeGxQ2K+-7fH) zZzww>&$4ujIHZ|ig?aIl1~H+zD5$LctpOj~Fu$=@5h0tr<~Zf9=}H{5Wcf9cUaB&L z7Qq+qXNg|H>MJTg@bdefp?Amz{C%gx=}G#Aw=Vo*38oaO`lx|pjL6FVZGUj;D4WW& zEV2?ER|j{vxxfMT*K{tQ`)BCFk$=O{llwDznUeRs`FTW1x%@1@xMEhaN}bsG?l?Ga zl#s;MX}bi94k3rGmMnV!cZ2C1Kmi{GNiNrL%?gskzcAv|6F;J$qSh3qX3HYqU3Q*b z^5-hXk3%0IA5z{%exue%F?PXDCR;E^U~k4ChlKC_QRySnKi+E$vWU@oyG)-YFoO|L z{PGK%KhiX;DnM~!E;it(IkjxWrl8xw|KsB%pWct@#F&$HKde{{+ho-2OWR_Rp}ii+ znyZef!PCVBXdn3ZgT$Rq!(@Iey*#=l|5lLI$niU+T+lj}^gG6VD=bmJqJDRtR>hmx zg?Tw1C&-wsYQK{gUqrla@lB8JPp`a}c8cZm+uj6@4PzhOsd0ber3<8k+w~mW5RSNN z(=X81Fq=<`*`T>Aj1K$-iG*f!WS|Q7c5gU(Kvy_0*0g**HJi7~T#Vx?Ir zZw%gWI*3VH;UW!om(kv-%l5Wsfb?9Dt{&y5Le)*lUNHF6a!M;o)Q3wKTsWS)#Z}=Zj@?t8dta5 zzE@xNO&F!VEA_GimaAffuuz3ymXF zBjUcfAYYqvT?Zrpuf$uNr{IF>_$!hJ)W1HCuGkmOU#F{`zl?Le%mgiiJjQHgeRX;x z2o=wRqqc$9l^n`(Z;cgJbs*_R{9fYSG*fPfLpn2kZV&zGG2vXxN3r(+&aAF;_&aM= zAvG{(XyCh9=?1n5-iYqG`@|$;pBy-L@yr&gbVN|}`((LZFEYg3g;TPsqM*&Qe}paV zSE|}3^iw_}?(Qkxo!)O4Nz;Lv_q{LNu`(4a=E=oV9=YlLxlLzL`(c$GqHxcZMwZVP zuSL%&67TU?yjn`jm<@jK=K6a7)R!Nj2lV zA${lhu;4N2a{wh_VMANYoBS2i!2Hu(Cov|; z+$`@`z2F19e;m&`z#MmHvxD=_H=}2efH)yGLc`JTtp2v<-g^ze<5a=X^19Gs^GEt7 zlWE6h5g=sT7!NJjP{-q`I{a{cauS^UCx435=S4qI$pxhM=-?*&T~is zEVs+U?`Ezy!^2pJT{(h;8~wD~YJdxh?_{ob8D+N1kx~uxDHhBLr5E5eGawzJBn6?Y zCi@#WJ8QyN{J<^&puJ`9vcz*lT^3K*?zG)@m%`su*C-fK$hl|REn%Lu+df~ub!Qv0 z>`xA-IjoMEW|39jPn|y6WT;ku49G+kXvLZBFMbSi+>(oV;u1v*Tr=H9_1_^#9zqe7 z6gD%VJV9TPLYRV9oD|(ZZ9SSgbeGu)(-}~Wb&k?h0RQ~@*6uZJ@cX6MGr1hrmA2v| zGdoUIHsSklb#C|E9-Xn?Z_4LY&}4>w)pf|I9GZXvTUp6(F(%GSJk*YA{>6sZ_Z_+c zoah!)p;9m8T|~|5`Q!7OVr>X4{;{}n{;_DT`6Xw{X82gh_qjjo$8WLpo;icgvP zCBOuI6*F1~?46u$lrKgHQfot_55ISkBijE;Lxnax+J2-8&>m7d&S-z8^%^dA9N(|R zb!AB|R>tnjBBLctpgqq&Gh*gZoL|ex`&63z^pmw4H0Jw>PuBK&OGmDcEwd{n%W(SL z^KyS8ydygciK5)UU|7Ep_k!fmUjt=}Y3#6F7;}eva-Uot<@_8=FeQ`@`Qj=v^9yGR z@?HF?OUf8J6N+!S(6J7YC<>N z6+=WuO$yh+0G>mMe3ZkLG3Az>J*V0M>AaS(^HGm)EH96N-8x)9*z=%^=cm^07=H1> z2aKs5e@EY+r@zY1Z0;4&l`EQQvS=l}uL#W%Kcw9p)Mkm*;}=r2xxnL{n;j=B=Y8?j|A1d98CM` zfVW~n8R#?Kc%vTkc$wsvFCU!`b2RU>?G9)R?_!7N+nH)#$#wtc;zrUB80E;k@~EHe zI2l;4C@vJKAj!IeWk23|6Ri&kD-Dw5icYAFCyKb zx}+`QGOZtw+3;HraD;jN!TTZc^%OvZNJG)WI#={OBo0&4^e zxl#lED%>L!DuJ(;=`uPS3F{B?^b&WS0Hqp?yY<^`TOGuQM<^$;siG=i%->&x0v)^W zgf2I;&7Pj-d0X>P2v3p&6BBV=Ub?+9!2rwuB87yqSr_j|D<)d`0 zLZATv^c^5kHm3f5@BO}nhFTP1KR*FZfwM^f`AZCVisRC~EeI#&6AC4SyVJM zy~g{*qDE>dA(Gm9V{%1LVP}Ac%(F<1thpjWnJ<)vy`+bWgV0IfQ$RVlsLIVuRgdi4 zU3qm6K(B!(xxR4j^t=H-<2u6I_OU}U8xxl{b7{9q%U|EMGDEeI1l-`|seJRO-wWcE zDI{tnI%PF-gl3eGEq&X;VggVNUgWrkU{k>{T#@Pk%#-&1oi{c2{J_!}stoHF(C
    0D{9bUbWV94L)!$jK?)Dhx|#24J)WeoN#-4QLI3cVlMTi+p*vk9rtr zt?rwF*kP>_-$#!qw>TTBnuV^W!$8qcdm^CHqz3rDH~0<$bQHHwD8h1runqcWXa(}U z2OSPBtp`1E*%?ZU^qglZ3t^lJ3<}}Ezu7fm6YprIFLrr607j;<02^(8Lv6W7O@Qh+ z&_86Kz!r@8ZsE7)Wy|$f%w>2d8P`03>(0E1C0&c1$6^< z$G!*En7Lu7JktZoK!vk8pt2D_ELS;B}_> zcCKD62Zi)Vf$urM4g}DW1|$!I4?GK@KPus|GLtn%?Ld`qLJ=*Db zw*d0>(NALz?do7(f=h@}s} zoJ1M%!$rJ906O0ez?<^1rpmxDYwCIj>r2K`msmXkew_(yCGzbF?*PFIkxmKlJ>d00 zS7pJB1HkE%axtz!SpnLEzdkK~8rEWp0dde7!hlfU4AeIU+SHJ$VQFIV+@M2$2OLZB z=DS9IKtf0FF8m!!FMS>WfCd20W^jD&JHu-ah+T>V>8kk{AtT|1e3Daq#e7Jw0>KDG z)()|A3@8nNM)ijcc&A)U#`E%eS0Ug9+%E9+suz%u}3 zsT&~UlHpiZ(S_Jl8iS8d==gZ{RshBgf4mC5gq9=lW})H_T=Cc`ZxOD`r|jC_kUGCW zEwa*ZR;Z@fxqZxKRn!2(au(uqL2xUs&tM+G8Jw);NAgwC8#F)%M%x4NJ#;eVBT$7k zrF=_O>jHM>Vo;u0LjN3jk&fyk+JwV&Jpm_nd|_gKxE_o2W#gbcgsB3w0f3VRYw>i* z7uC#r9YV3LKM&S9w8R`A?|d*{1lNbTE5s599W9(XS5O!0KFajzDj7tVp~8#JRSv?o z%t6SWz$hgLd;z5j_wIQ>wngLf&@F=O@7zja3VId9?g5lE9V|A;ID#LRg_aJ#iU&C{ ze5l4%#b=h9Ew3Mtk;?_lk%dC+2Om!i_hf=N6pGp~yNW+$Mvk~P$5*8T2Wa`4$mR7q z5YUGiuX{_w^8zR&f4)PxUYo4m;xKd$ivz@VnF%t4*4Y9y5p^NS1j1dYu5LLWVW{x}~pu zgW=nb@9)<@yP_BW`*(+`5v6Jc9-s0L_x#+Az_Qo3i{*bmlnXF+bvr;wje+Aro!Z}V z3Z^2u_%Loj)c5h2;@3Nd(w&cAAy1Gt@1_pQ)6b(q-%Rx@M(4%h+5fzc)->(sU>*bh z2|)aya|YAcz<$800Jr^dNW21*DSXC$qG1F2?fJtNAa#RHpBs+oNq_uO!`t}bAoMFb z>if2z4?~;2A6Eup3<qY;WfMWK6hzWKH%J+JAK$(h*kQl1TU@_>*l8I1rig#*DrnsO6eJQ(-?TxL zjpzxG=xcs^RlgzSLo@YI>i+Tie)~Nmft-_H0km406` zzfGoJ&6_?hgE5O`n<`1m<&IQI(h+1nvL-tUJBZM>4O%=eh}*+ z4PGB2g7*E>atGj^NRWPf_XLatW%dRUJ4T?=Vvtw?sj@5z%ERY|Dto=qB>h2374C(jz`b+Wq8$ogy`VWr$r}FhzYEhB|E&A85KlWMc+U0-#!&acnBs;hzW( zye#Nyg+D)><4YVyqYD+tCPNm-=M?)KJ|Ym z{x;fO7vbia4J5i2!fn$H&fp89G1AXPjk!LfwYHp3*q1 zY#)RFPEQ`3fq$6N%!eg_>;(|8=+lb$8^J(a7nuk!HL;IBKMpZ(w8^&a8AQ~+od9Oc zw{v{k_U%GHSYK%4m-hZRCveY-aFSnZ|8LX%YxMUO$qyRl`)cwJ%gYbzSTl`fR)dA| zAuFIve!Z-~jfo$B;KqKrocwGvz5C#m!P@opWj>dpui+!~bVi?QuSO>1_fvftKxh&C zQk>Na$F=ECbv!OjUkpFB5p4bC;{1!%_uF&*QRVy-Yv*f{{RMu)uce&<=FqP{zvT}6 z8%q9{Zu~u+^Yu>t|HTZgvmj{y^^*0eY#Ht+V7mFV&%f3<@HLqq|NFG9eh@|$`w8kk zzs-mr7rh_H|BbXS{b~69pcH?e=>JKF6CM8LZvO0i{_Ht|C;HuS{Dsksez^uCSmMY| zgFD2~ss4$X_8<2xKac$IH$Oc_q%T%OUx9ngw8h{1Y1lvUre1{UK!YWrKWLB`Cbr zzr)~vfn^0h5H!Mm^V9!>HY3XgLq^Bnlc35<&?@Ngs;L{e3~HbMahKsEpo4b65d7%p zrto`kcI^ruv3kQ4?-;cpx%JAoY=U)r^cQ4`F zEdQDr@R)y?@C4F^A2vVC-yaP3e=zEQ`6|D^NHCpan9HADAezQ)lhxx#Seh38Mx&5A z(g}YY8U3?%_Sd5R`R>2PeZC$1SG%Nt$9}@`&-LX`hamrq2aMzho)shquIOpOFJJ3L zlOzK~RX-FqICy^$oc}rxilF?QXZZa)_%8_k)1S}i2RjRi)%{O~{*l!DXF~sQ_@A}J z(06TeQEqA!C!I=rfC2Q_xo)4)Ftp$|NL3L&h_)$`ZCwJuN2j%!vnU*r;GDv zXWB3C_K&ZC^9UIcy{Lcf3LkUy+r#)XU;J}Qe@`_2{xSar3V`_&`Hyb_#$Qhh6q@<7 z)8fBD<3rmQ{uBGFqymptZ}bv>@Pu)a`HB7(ru+8y=M(tRE5_N+mxiyhtO4@&*Z!2G5+|CJQhj|Sz>=H!pYBwEMG z6NCN(k@)lG#}CHENBZmI_s@j~Io7|_!oMMIkklW|KT^!U9hmtp_J2Xh?@LMHKm90G z82$OaeiS`|{_-;a?WOHAR`i3keVa)?2-QDHJp7AK{4dN${2UHrJ_GUSjUY^^U+Dm( z)zQ!|-ojVH;@@e`e;NzF_ZFZKBx?thQT&5x{SRruUn+%PgwB6C>wnH`{KLFwuz<(e zALe}-Cn(?XYp3H|ssc^%uUr6}^m`r?%>OZfY{Qpf_lHye+w1$|&_44e#(%*)|6wBk zmi&B;{TqqT*DCgV;?n~`K{$ce_ebLMS4az(ZCH#F*I%o||GCogsf)hyJO2ZP=TmL| zp78wd&^Rv+!vMJM{~{UsDtP%HC_}KwqILH7WN7RG=>Gjt#PkQ^^jBygCcvCegp+lJ*&}`aOyIN=}a-1y}za>skN-2?CX|eo58$5{qBk zLEj7Z{!b92kI4D|P&tD91iJGd+?oHzz~{e`g8q*tYX9{h=WqDae>TAL$Hm9Yr#t+| zaZiM3hF;D8h`8r(L=rjrC!QpD7Fq>Z>{DHRd8Qmk{KR1d#qc;u!-r4z?gdTCmIc4R{iV1K^saCmXfm0G7q!a8$&@6aE!P7aF4A1M|Sj)6D^t zesklGA;3s_^$gNTVpYq<_L|=T&Jp^bl<0Kfy(=5V=b*UQt_~oY<=h=5gWSDZd;>kv zjH5;==dP9g1@)x+_f`WyqmG!L!ll)?cXIMwEt8x3vpYuQ^`XC$OMQ7MCuQ^7^Q5nj z=(_5t+m7$m*dK`GO6CUZ&p||3*GgKbeSnQg5Hlp+U)_O!>{oXhX`y&SWrOgNR_AEf zN?u9SazER`Ge2IAdI2yV02CoLj2hUje80vEQ8mW;|pH!@URBMN> z4Pa?Z;s=449P--p`dbm4?wX+8Iu+<3Hqy7ITbf!l^iK<8Cs=@BW{p6rAg>@VM|IeE z1&a_qq;#54qc!xyJ5)@(CqTSFqu+k!k(37g?#6zK*d+kp_F4E;3^PR%pI1GHhB{f+ zu(S0LUyQrmvOtDuD_!rfFBy5RIMR}9U^@9uIivz$Tq>{A@wOR(D&8lSjm6poT#75K zZi1o0?3b?a|A=ltn7fFTW*!fYH_M|ZH9LpZrMq+agLkMUBb9P#InRK_Pl&?!<#1HZ zF~?@NQuokP!|oOLEKIr+NjUXsr7WB)s+a%Nj_u9rRp}U61INumQrO%0NVHVuQiQ?%@kmxSs zwykFO#f3qT0jZCmr!kP^Ya^fbFl*Y;C#H$L3;RiB?DZP**9ASFeAfZyL%pw>8fl3J zY#LLbk@q|2$tKX?VHA#@Ec)Mrv(k%jJzlT|IAzESJ7-QMVf7s$W^~V#LthX8{Dc$c zUKh-`+BfpGBdL?`H=H^~M*qm*HxNK60cekH_ZCLjlZCOkl*?YG+0-491dp*tl{PQI z)k&;ozZ*yq7{JT~2g9de1R8m3+`6YPa$~qF0tH1ZQa|R`s<_-O5DEYbuc8DnEA0jN zv0)?pP#(b!eDY2~7Xlp4i8kg#kjPARLo5`)phv zM-db$fEGvsF!l_}1--gdJ==K=n*X=}-a8Bcu{;H53)p<&iPNhuTJG{({n^!>NOO~S z4;`vc`Fg3l?E)bzfoLvjrE2?Gs|4IVS&G=4b|Ijxi|dxhJJ37DYe8v-3z%%@qYBi* z^{wxv(u){fbS!f5G`yLM;VJS-TfTwWjc)w5x0^|o7w-g!FqQ{Mu|gR?lI4{10ko8N zej!?rSA+`|!46n#TeXwCYX#GD9JLgh@;B0>&Wt4ljtEGHHz&fHl@0q5-EY)#;6Oc|;$yWFB?ZwziZn zM^zyO*{XPPYZ~CbA z)(NSRpkid_=B9_+%6nAEDPX3-uqUrT?)^+H06c4@ig2GYo4E<*EVKzs9d8SsjXL{nZdKN`8%p}Z<-Rl|vNa!VIzu0J-=k4csC2s-(6b(~(>;!d zX^iNOaWjcz={=9*bH9}UV@r3J9ly%ACFM5t^1@FM)%E1de>pMx?gf#PX3FES-R7yB zB;OTqrshE>vW5a=Q4X*!GJZ#CI$78Lc~r5)xX8;g$Vbd1Pa56!q}}fLv0yZ*!79a_eV1@2_9$G8BGu##~-<^0`iY_ z@vZu1`_gAr6LprZGcA;bKv<^W2 zn5a3mIP9+JA3`zeE!!aQ4dwPm(um_|#es4LLA}yXN4ny7Whc(~O1?N^c><(sR#kEV zYn2Qj@%_Mn$%xbRm^o`YhgO(ouY1RUqXG|g>KLeyP7*9gjP%d4OKrQ#+7X4y`8g*lAo$ZtSUB6ew8^i2<^;+tY zb6V!S0gCvgO$QOo{`6KiCC**)zMT`lq`Or*(17eS%R?WypcqY$cMb^wCdmElgX>`I zTvs7{!>UinJbmFuJ>XdE(zYL3`U?CQcXt0UOgv;}fQKL?(;=heNUEM`endWDku*T$ z&@`U)G=K{lFx*xJxYGw%k|$5DAUPcm5#*@J^Id-M?8#+tnS6nh2GIKHR@GX?8q)>$ zW`3douv+U(@uZyh>|u)2&A#>vzcmrSHa+OAKe?fl0lU+X&?(@4s#Kkc$pxc_TEz$E zqvXD?YMNurgX!@ zp_A5Ya+T2!y#+rOpwzt@fHaFl9Dx)SmSA79r%Tnt@c{5t6APumI=Vao@+LGk8Ca|U zIH_|0#|Mz7E04SPfCNgl{lEjpd%IZ*`zk}h6V7#np1o@BfXC}b#1$41c=5!gI)~+) zUD_@ZZEmr{^NkZiA*_x0sJBlFFj6DHY`;ul4?v1NU`ucA18GS>r+35W>153%eF#o3 z=j3A8HpJkFI{k&CW2QKR+y*=g%z zcGxQbx;q03^N8=ja1Azz%XJ4o-x1*1FcQRbONd#rQl5RyrEPeOJ zHvHa8GW1}r+yk?{apq?~>NjI6pXq5EfiNX7t#`>p#3^H=hdTiGl>?~Dquc2)sV5ol zvKt;e^*#W^Z4War$vy@Tz)9C__x%_WLcJK9bjx0_Zp~r;1kUjOWZS*n1+bt>A@E3{ zt6z#o$k-FCjStt1M-l^~}%tWyKxnjA6NbJ`MO={I+M!Aet z;Z*ocl5W_IKJ`Ity@EVKvJhWvz|fXj)>~Apw8dcZ=Iqu=FE>+}n^~OI7J`~^dg&mH zSNSyBd0GYq5aP+;tx4BDY>%P(Hjh4*Cxh`}D0LGloozK|+HLX$Z9Klcr^1+FM*uCx zOkFm(F6+O|NdwnF5SWH(_gD42M$N78)fVu_&N7 zg8@IwxWT(5L5U$pue@YCFZ@!pX$X|mYWu|LHj$1=s3Dg#w2h%<0~W|Z0k{bmBJDYA zl>T*I9al9>z@;fAix>IBm47-|1U5g@Brq|y;+>ULWL!C}Xf!xRmOwY~j(>}v$v(6- zSawDx(3E28X#;3#a4qd32Jw}?0>9@}L@NH|&|5S-n|>1@Hqv7SOkR@$PWWLHJXZ>I zVqE&Ltn*x~fqRfY@}zNheery4=#R+4YbgS?1f>0>xq!y1_}E`f2bZ~bZ@G>K5Vf7A zb_BrV*96|ZrlUPiz%2#SHkr%)oz<YI)?Ts~w2+A%=DYnLRD_E8vc zfa@xdXpMJQq1CZ%*DJZG5s1^WwZ)z9pl9f1ian#HO@KlVpD$g?h_L z*ss5q*R8E7NlV^V-+PbpY+uKHL@S?@jMMD7-AV+&B=-iGzE=msw`0?p*aM(!5a#2P zEwA7~+5C$nsclhtn_}#<-U|hJd~nJ%_N|zx9ZTCw90*r`FF>Z!Q8~u%5K!Xm9D}fd zZm(llN>^e!f<^um@)_u{PU~AAXRy@>B^OMGICFV$i;#kH6}i6MGj4~tqB^B#M_Y6` zE{N#f^dfW2&0AO*j%TJy$2l}s0Q5K9_b&Fi_`OX?DS1J zbULl(z&LiVl9qT*BVO6^MaO{f>3-K|g%=<`)Nn`R1oUOFa!R>ykyB7x zs2`7=5#6;7x?z6Yj`A=!gmogp5BFnlP)}~s=5$Fgo?8IbH~{=JN6JfN(*qWfg%tw0 zgg05?QsZ!TprNE+)x<=)nW@<&X~=iCL(IBw%+r)nZB(hp2kE#knE9mt-6V z$of}*;vTgm>m2zq9@Ro!FPsxAP4>D4s?K@DGa>jsO^V(;N{XhRw2TAiLhAWjl`DJb zNbIRMkzCuyZm1ZW4$8R*Ps_la$}0e!YrQbpcm;=uF_nruOES?sPm(42Si%6W$la%p z?{g8)6+S=GYg8r3pI-1pSU%%PR2NDIrtio3~9r|j);{Zqp z;8AQyH9y|K*l++d9IaO|d6Q)qa9vf+_i0P1)H*#?VwGp|vDGRJC!Z(zG&k9Sy=M$f z(tx!FBu{mLEH`6d%AN}W);$h~qjfDIWKQ01x^%^=`whr#jf8c;5GiEqO{o#?yCUyM zf<**39rCbFzMRaP2n;hNf9HYQ@)FN*Kc4IiG6R!B$W+Rx-vIDWC6~wokAqST9t(Pw zG1Is|(z|*x*5_ncw>!ITb*`qj5Nv#Rf1l{_#XuKn2g9gZqJ#mINo) zQZY*7Lvy~jf)-R9_|_P4hpD&NOXos<;xIf;v#ZoV-{-h+ox@>8@0W&Xi}?m~n3gDj ztF-tN{d_AhH|qO&0}RaFcpVP-n}U=G6AAlrcH;xb0PcO>CA*D;uu2>gC=-&91+ooY z&o7Kr%Ry8P$#llMi*}Y3-zFJ{h@g+LUQxpn?hvs3b8#gzjl}V z;+D7J=DlNvm?;yK@2$Hl0kD}6H+u(q4|MZQ{2mpSO7V%a6yt`Xw z2OMD18Wu0D7o${c^6*NlvpK}68e8LKKZb#B=F)QPZma)1W7Ff=n*9q!tSd}8Ke5ST z9nXg>*?sk=a(Sy6(5uSjQ~ z2q;H_0%8Y>?G+##^rV%ZE#Qq8O|^BY)fxi*P*KN+Ous07Wx6Le%<-E{TKrMx*Aq9H z-f-UiQ~G>?k0}h%^=cuvW%dp`kM1j^5}=fU+=WVvryXbV(LmSJmKR|F!+Qx=7j`c- zDG$rM^GksMqD~V5&`io#-s&E-5j_Woa3QWO34nS7yZa~%7q5BsWF>=YxO2u|(-1KJ z$8&#DG?d5?R@)tN6aqR+U_1(?cJi(*htungLhB%?CkgpgX^;7SZZm%Jv65F7Xh3v! zAk0G1$wnG^WMUnPgrnRJC3%s-qHP_k*5m2@Nc4AjKnY}lH_`|o|A|H}8%{t5*zE!m z1pzDwZ;v@SM65ANpc>*8)VX)?h3#Ppp}Gq@&`~9@KQg=?r;FlkRTM$Sbs1?=7CP)j z6Qd50@N78G7;@nv)j*0`3(=b+6qP`hlM}k!MQ6{s6(wF)&~dOmBVbp&?p++=Bg8u3 z9?jPq0TD_|7hFtql<@KtnA|WVvnzZL$=m&rP8}MSV=g~AeVboQ;3KF#YXiXgyuO_7 zo$`{#@C0(JRM=?U-x5a=qltvL0s? zX{DTVck%Dz?X|C7ap0Onl(h$NujnlGq`X1#!P8YPKx7Nm6dkZ0F7L?@Ijv1GRy}VX z=T8E;4BHBj`$tcfRdWavu4v(Yl30Ea853sO5j#J}4+m~GAv`R2>~UXrPE|u>P$av* zETgbMSciS3(LR!iv>69Q1O7cFghfw&zRNB+2N~y9a_)j&z48;*y?RHnBY@l;u#~Hc zo&-;-VLx1cFxl_Lnh-$r2RCwlEHB_mf=`kcL-3DG!vs>k5CG-?!CTf>1w4nJm`5vcGK$=r%o3u9W5dSo|S7I!5Sl{)Cly34<5~`4RADucL~BYioOojwL#4Mc(@i&ri1&t zZEkEv#p?>5?y2?abJ4{+3sph6m~mQZP!JPwh(YQaUPt29${cacvNBC2s0#?`ZNF0w z9ja)GYHy`j2LsG7fkHcG99DL`vGxKry|R!emF23$`2i1;CqcgNEFM}lM5)e8>pt3! zHwhrG7OguML?IwD-=1_>vCvG}FdWE?Hw42ZaW+Tu zwNp?wVRVy zd_n_J#dJwmkq~K!I>rh#?%Kh5d}%A?cY;IW{Jr2;dVVUaoWtU)xLqo1NBq&M-s>gK ziweJ<;A9rp?z!w34T5PA-~jz3l3;^vo7uY`Ug8TG6Vf~j?R+h84V*s+YUaRwxMOen z^7djVU`y3Q(p zzTtfLmUB_v;|;!~)STZS^MWL#p@FZDhj@X!gwwx*3CL)(hgrN+Ox4vudFsuALytmhpL()X z+eIhZXBN@75)x&~n1bVJ`@*9$n+#(ERJKEeYzs&` zv*a1EcX9pHZ|>a%HU+PL(B3lO``usH>T-O;Y6s;Y%Dq`~Sr%b(kk*v0so4+jFTOSLtv$zxz>!SXK1ix#)$8)^4YUiYQkaFr%rrpl6u z`vfLkaJMh&GAe?j2J%QeLm|QZJ59wkes11;G&-U%>N}8H$HYd_iA@6EDOs-yDu{n7f6BBxXW%=B-^gO2E^jTsI=M4Z}K`$lN;eopi6?Ja^6?t631K;fVZG zysyg3uTHeZL>G*kPmah5z^PXe&6pS)kX}lr+>hehQ~lD(gf|KiS+j9C6$6?}a-YAb zaEuq%d4&rPNq>lJ%}ttMiEes{vJ3DMr0QT~gx5e$=oPIMhQ-dnH#SjH{zBFiK-_Tt zTHCnUS#*BIF=oK06+;35KSHeUImHoWRRjG`p&uamz{AvOV^CCYa-r#b1yZ?j0FGwZ z9cvd#t$<3nX4yLrJW`ixNA??oTigIQJR%}ZK?&r+o^SnAG1(W(TCtAZd#NL``b_|f z%Gsvb5$>OgS7 z%MsFd0xUo$wlxkMa#;eX62#D2JSr_Sl5qDVK=8m4vOQni3_iG=*kFl5^cO!~k3e6-3x;=bYRx&J z(0jft3$S#A-7-VkoLvAj<;?Ts0Zoqj-fM%!?^UT{L&?tY>X9(P&hL)o6yYK? zgF5=GI_D&<>LokQur24EAiE9>4l(~(qTUHq83-ktBkLO;pL9Oo%>MWypz0y+CECZE z!_afEa8VW%iM}!J?)1EdGwEgRB6E0jsaJ`YgRNCF4Sd=T{|0BGq<}TW!NdiB+YHl$ zFAunP;NmA^HkR$SUU&1!aWSRwY&`O--Ih+nV(D5HWw;_h6p2UcIs9;pN(V)Tf}{7* z1SVwo@P1P;Gvq4K2S1d!UN2_?M;UmoO08+7g~n00EsJ--q=hA zGg%Y(=oJM`;o3HLb{wW!@-p;!E|C15i-D(SXP6hNlzdfv3-i?E+da747^bsU+0Uk) z-X~KN=361&=kwc_v_sF8RNY2kJtmL*u1sicnN2?~-NnfgaVc-qjV86nQGT&LfnC$; z@zh@~)RE90@197v*;-x(>e$wBA~?1z>}9Y4XBr70HEQ z>3X>9h9t5qT_A5iA7m|K&fpb5qT?AtsO7vur4I|W6sNFF>Us|5$@DyHOPu{Tj6Db$Lev`*qSPo?5rbS9u~-Y9jb{T-^C z`t!lF)@-%?aJDC&g@S(04->x*-+qZ7$sTy?O(9&z_0m&%>JE{YkUms7s3Dt?Kzj&RiDZZA znH9uWFp{B2NNtq%923`A(2ln@DIiZjh$B=%OcQ-pdh^nHD8>QA%Vmh2^%I&|he9Sn zpd>NqBtd~{r0VoU(Lmz?)$4-9-Si9cZpahS3eJI3k_#KHbk|rgIMPN7BzFFb!xK}q zyrT@|EHf)TBml!|GyCItPIEN!z`o)%KspuDkbZMimjCclyrkRR%JWFwke`Qo1ULK<=IBQ2|raWm&V^Lcm%B`&~Ar z7LId&+L5}U7?tPqp@7FN?bZ6C)#~-6?_KnO7ecBJ(9B3Bh2tGAR;QYx-c=^L(oK02 zCSA+nNeh-}lFDem?l`1ZdwzD$2DzSTpb%7}vwxb{P_xLkQ=H&B-S1SMT4BD3V(_ps z4^OlalB`cLQr-^nct6i?Cg1zHBp$~Di7GiG4VXTKI8GbTOOnnR7^ooWNM2(gosZXr z)Q~w1ir@u+6j)`9IENwzo=NtFm`HN^#49a`^TzRV5k)WraTbbaZU8ON-8|q9qdiLV z>|~@Ryf}-uY3WFroEwW)ueeu2i~Hc51Jk5auusarbZX8;|7ec8A`NMAaazKyPqu18xm|&@_ObdOQQ~6`MGQuWkEP&bM#-ESP5nV&WAZBzNeu_EvqH)p~f zE(zAA=lZ5WP8uYD)pwx%6;_%lk;xOy5ym*je8g3~%TxERDXyVD8 zqf0^q@fMtfI>YzR{F3G6OqrqR!*^n*h#59eplJ0;amOB)%bL-P(m+8G0ncrP5RcVz zr)IUyQyOYUsPS>^j^NchW|K65<@tth7i&*lxlX|*pn!kN?3ryapyqZ5a%~)WCey~b zZ8|1Lo@Ce?^c&>y<{ln3YnWoAi{z?dzH6apFl2$@DpB0uQIzuu9NLgR5i7Up-Y3de z2%R8-!HtvMlaqM&Dn;xJLPJ6VEhGGufv1t4U+%3J436RCW9f*)74OD@3hHgbAUem| zFJ@}qaiw=YX(-CIz3MRqaxUe!{!se2!3dw7VnB&7!wsbi)i0;F*QY05+b|Rq+(Dv) zBNCu{rUrs_J-((_>D7sYLACGL8u-~RTRnQ?^K@b%Y5I`D4lEfgI6cVj#j%8Z+#a>* z@ZkkN6%)Y(?{+5!AXAqo^a#kYq~H0`df!~{_9oy>!OgMw`}V-%{TxFi-?TG*#2fDp z)uHi9zg4Yd)#x3!m^Z(`qkBYTK&%4qTyApYMuG>FLlh3cLP&?K|VGF!uxhoFu|4PWMN>FR&#ku0N zKtyM7iqqN_)!R=;&Sxr!QF=UePK=QYQ^MOV!<4(907A}y3 z_KY?53v`TeBYv@fQ#7JiEIMXsM_PA>aXd*jf_uyAZ=g&gFZC*6CiZR}zrklnCl|T} z9folVaZ$00wQL)kv*{1>E`#%W3?Yo*zl=$JJ^WsTStjjo|AYtYxzF@g#Np1bwkeUT zicKC+$EkCXU4YWQGNlwkBer>NDhM1a{RtWX57@BMhmz54=a?GgNy{Nu>||0#cD1j~ zGlY*NDP)wPh{4>H9*jF>eE~G0J*ZQm-hnUKVb(m%Whfa6E04yr6H+&q26G^i>nV+| zIp=2vYFH>{Z^3!ufFtF!$flfO?;*LsI{-n0lUw-ugyn>Z9S3_6@FL}P;6!$or;7=; zArNm4fz+-KI6rhZu7jB8Z4HgFlxP<{lsW^zk%5a zy+LRpSm}Yr(@??PfGgDHo;uf64y6jwau>> zvUOImdf%WQ4h&KptcHPTz#QajX#n!Iu?~@QkIU+F*ag#`?^~)!u3hNJC0s(_l3Ou( zY{>D(_C6RlXkl`oklAJ+czMMIU2dCGmA?*W4~I>Z%?Yy)JqYIN0kLwSG^U-Vp}+S# zvXpS4Qd1r}#F9w_w?Q&y=B%cVdf|?c7L>Mk3q@`u$y0oGj-jilpjGkmh76Xy_kvs4 z;hb{R*#kfG#1`wGXeW9wR1&&O9v9*iC4C@_r)big>Ut1jr?;ahM}dIyB@wQ}bmr9= zCDnd3hU`8*O7%M-e%l6g&8ah5ZD`XNd0vptuvago4 zCRowL6D1`4ZOsiG3V)5sRKRc->b6nVbsq$&%}yujlGPME3SoFJtu6pR@mod zY4)QsC`t#)`QnPK0r(l-&~D2MU5o9`p0dqRB>J9v69-64QKF4MRs=OK0q^P2DCmxW zRuPF`V%{)mWM;^wpN|9G$&)Nh0u+6yT8yqH?WxU@BUw8)U)8~g5^%FXE=_rbNEv=D z?Tyi$*XcIHLr&gT;GN7IdLBux-huP=u;P^Z*fuG6<2#gtsG;Ry_1sV#!yFAoCQ19| zHcWOPazA9Bi|W!hv`!G(GurMHjhqLn4r!k%2Iy!$Bn2MOIH_)@nw@t&O4#=TLG+wC zPM4FIcyGq_I_3dgvJ?1`!T~=>?Y(eItBy_(I3XbRNQT@0$KG`SG<84!R#9=IC~gI} ztzhO$VsT`WKu930gtlsS0@;HkSQp~JZT0_C>#SO>{ry@+t*f?f)K;rjTUYC()>##; zRz>~aOWuPp1Zq*Sg<2&qFL}xP-uLcvcb~iCyOPM!t_*6lUN3YD(-XyXhEl1AJh6@| zjyCWViZqyp%2lz`AQCDkGm~VA3BVK=dw4E8FO>>Zd=raJVZ$IwF@tYZnW-5nwgHkn z0-=K*7oAK?k|InxQ|nSAE`FxR1oNe$;}M!lE0D+7v=Swa<>7h6Cbm8e=m`YG3Mp7B zPo=dY@l?LZY;?0!LR&J0V}yR4OcLEljArS$DkeEyD$EeV0Gk9INi5Sxy9r#FKCh4v z5>Stsl_0iiShjdIkRmuKgcP|#Aa*4}7Kos6!kkO4l5FH~EKp)hg%TNhv{EN>nR#lC zDlHWlkG*Vxg=L9%!~jnVtN=C6BA3O-ThlBKnEOdi z=RsMTImW_frAE;OZmm5oRg8kJOfxFT%&2$=bcrLMSwZyaz;|#W45S>5@>Bg)Ar+R6)T%%@qTlpP0fj=oM;Pn%iS!*)1$NBPE&x z87x+`%M;^ew-OjOD$~N?r9cU(JS9#W14S`3lUlD3lY!x{f^o%WC(jWTr$yWj5lU)c z3GAL|uEh}_XU-I;guG~Of&i)m`3Z_7PpZ(xho}sJL4h)AK20m2YEq*FN~M%2bXZcO zysXy*K+Z^pi@{THNbw1#453~W!;vSaCq#1%6s^dm7twTPnb36mAqN*(hI~(XJ5{1Dg=Yqy#q1Fp(l~rPA zie00XA*hqWh2v2+L7FF1$Tb?pDnkk*kz%uDa1~~jQX88VOOT3mDK^yh@nX}#KUK$a zsAAa8Jf?}EC#0K%(W!DP;GB$fxjBh$v_s)PI4rCL9K*DLgY~q5uIy|r)9crpsdWG)mSupECuD6)8i?rBE2wK>Qr0I zi3w4O8Fm*zD^6iVOF3Hjbb7jitaK~&^61oP4&BO1u?cO`SV4TcgGDm2sR|X7lI-TH zzB#iNMTGtk=_gNUfWmf5Pxo#KCu^DAUwJk;qOI31c%^ z9!(;TtVv+n__1oGna?81lVD7|f~axC^C100%YgCh6JH6UAi1F3A_}J!QWAAQ@RcQm8V9h7z~MaF0>Oyy(uM4>y|qZvpiWOr5n=e zI(cF=KbDdr(m>@DgjPf(5#n~~%$ZhtI!xY%H%p<}5EAH9xkVvO(n9+HU^O!fR)b`im0Tw)ks?*tHA0S%5kn{2^{zyPn*lXjR#_C>PoA9? z3!gTb>!C++(m?REJV6Sdo(LfpONvyIo~e}qsTpWODIU35W{b`gB$yy2OCd^Na4Uon z6zn)^yuiW(u4HlwNd_p{Aa=p)gc4aCNI%P(>Pm$IOCkVFtEHs5i4KCg_Man zlb{nrW)m0%=0p~BKmc-`I!UIFw<+wbWR(MqK`MvNNtUE}Ea39SK#5s8Pi9n-33Mfj zG%XGTmt_|x!Yp4f!VEDdjUZ1G$qNo*4}2H`8yQVcS3Dmh-Ql%-}uvyj9Li^>omZ*sFUm{t-+mMkY_u+*ai_xiLoP41?&8iS2NM%T-&BEcPsbNUD%xTPI z@uf^of`cOCgJ+ViC)$-JraFNNcFhFp$P0RmQ2QcGNu`lu#a4zi!$h~I(vz%8nS%ne zrHxXGG1DxSi781MHn5iDI>^WJ8B{5esGvF2TCR|Tnw{7*0g`B^a0xnzimc*^RL(Sx z0T{X&NGeTlRcqs2&U8ks#EQgP5TMZNp>&j-?q1EC{A2@j5;dKtV!WAWyw*ALOn4# zhG0iTIs~#WhIp>Ut^i)WElCjXaT1fHzyPvS8D7!R3DQ)VB8x#S6Br22XtIqLrFY8} zu>{1zC&kkE7DKAboZwQ$^HW_kI&iQoQ5tb73Q&@H1SrKoC=8}ENkw!esI4?grh^2@ z_CyroyA+8!I*dqHOH)lmy)y%hrzzc#szFtVK`kV>-RVr=D8rdzh9O2&IeY=sKRAhJbB972t?P>nn=^D(j{8(E%0a%QFhw>FJ#P6x?SW>AHxF>yM* zmMGP$CBPeJXCx{_DH*A;P|TBvUP6&>Fh>c+@;HXWVoiuoaag?|%atr5vg528hm~M8 zxD!+Do+PzLYqjv>l+p|p%j4uGVsc`Kl<8=~8{1)&%ii znKK-IV?@=D%wdS3un$7#k|kDlkUtqCLrSIn~!xtR&{6s0#V zu7PSEXS&R2S4vXE5N_hp6>^(UsyFj2TB(x_oiIF7D?t~d$W(GP-nvhKtZr?(CDSUT z+mp;n5`1eKWUUysbaHaMnC+sbCRnWsGmXm?agD5a5tNWv;T&Fu%fXPuB2GSy4YUSL zv_^oq@e&mopi6O)Kq?qP$iKt zP$kNe5#92{C_9w8X)TKAv^ZdV$y5T=`Siq6L@{z3%i!QB7((Fx8`b6%gp|av0#lok z$W2!0O*Ut26hjPEg$RYlGdrX_Bi}64O8HWXTM-@afTCf9E~R?8@(7K|<#C)qK{2HO z?OEj1smV#KBooV?zz~oSC{t~O#*^i7$axN{mo)FOOXW5>At6@7bSLsDTDl;a;Fc*|Xc9#j zOCd+ak!TVqyO#=6EUsj3g3$t#%QAo=Z{gBB?nLN?Vo4;~=}fM~st`gYCQqPDiAhUP z&^Rm`Uy{a`M5O{Q5PG6%iE%~`%NE6g&76iPZ7GU)ml>K|*ql%vY7kQtvCyH$B+_Y( zv597Dn zU`dMRDF`I7nySeJG{&+fp?B9P5O7pRQ6eXn?C|Bh(vWC6L=c5M9>LDFBB=Br9z(no zV)M@Q6b3YQaJy+*Ljn+7sc90U0N#Ygj|H8>VoP;wiabd#fKUL@DKZ1ql93^Ea~*7( z$($SwmxD?^n7K;x$lP99t&yXl8KW(74r+%rsq91>iYp9Oo0?>yI=Bj=+McK;&`~8Q zaO+~6CNw0?i-m8?;Uw6o@h)I>zzgDuY%YVWLad?;gCLEsQkyJEay!#4PJ`8g;yi|l zA5V94s1_tWHq(~MN{Kd$(B-Blr}8*DU4l@;P0{N)VwEIQ#7(lPWoo-4ipq*3b0|)^ z2wZ2h2!JEG6$5*W|*B+qA5{CN)*YH=)g*Ma-0gARtaC<7)6$)F|9}(U!#Doc8o+awCu6z zs7WH|9+N8N*(BcNS-P0chHMv4t%F7!ycn9qf;zPqan!+|Pp`8?4Zh#8DR3}3l?X>Hn*hx|~RUOOVKz}li$PI=;LSWOiBCCkR zR14#!u1pHqW!DQ8g0wVH$I$m8ijVde@lc&HA~gf@LK$pSP90KP0^~)^IyTf~E4Umx zi;p;r0u9R=ooS1Sf=$4pM90Oy$mRGrkxg^!jXw2C0d=x~GNL;g^h5uL8F(}X0Z zSZ@)q=^Uvufx(~>!4=U`p&~hkrl*pX0);5X;W7}NHnu{TngStOeiT9#0bQ0LhpKOl ziRtCsCnT^1qG*rCE>uHP4)lJafYW72Wu>`OX>LA8A~d)K@yygDMpC?lL{~-Glq!zM zV~>+$B)C%)P7RkWOQz|fDBi6tiBC}}c!`X}bWIE$-Y65*?3Hfu1HrB#|WnyJA z3F(;v#Ab`q#Il9fOamv@ofM^!Fce6JRhDT@6F7w6%&}DV#P|eCazd0t4xfYPwlkUN z28KT(YKAshr2&EBrN={~N+vTQDOoIup|YWG9gG5lCd|I}vHrs$0Be9rCzKgORPnf_ z;x?s4^O;Blyi+NSM2Ub@Y|#&VO!N|1qgS-UtM7nc({?(+cgTP02!0Hz6TI{AYQUf& zv^vLox8%?!%=f8$2mE>^mu$seN#FJolSQgLF4sE~sO%t+s(08f?p+KG^h*vd!KS{I znC|Pll;3m`IsyIfWyuqP$iQa<;mv|+@VUJ!;U_~RG8I3~UyR7)nmE6f21){zq;ds^ z2zT~x%nn3fUgg<==x9JGh%&mG#d8Aj2gReG(esLCKmRpJ_3!774_!rPSjlY;Xvz#T zTFD%R!K_SA)ahY*wC@RQy0iDIRPS`>5|WKRC_A^hczeK%k_wb&<*mJO9p>v^?b8^~ z7y^YU#aGta8&&C*jplp-v)gExb?|HN3=0CBJA%a^H<^H3Ucp8|SLd&2*piB@SQd-N z|JLk@Z7;xB6JWeIg;Zp#QQoAVu_n@R3HDR8MY9e3)hrR8Cs>orHMXbxWGg{!gLVkD zLIqP1VMMPNSG^FS0uR(*j2L9>!0RYR_!jUJBWRQ9op21K&@{EuVYY!UPVk>;{!H6m zb5vGY0ErrEY^JprVtOC@jh!rI7t0xn;al|=>|c=a`Lji6u$-YiL^7p3G>ETd4boC{ zd;?bCRQ#0zEUz9t!i~qk;4|J?rIRam5 zOFUElD~F0W5ULz1;xhcopkh^G1H};nY-USQcz_5~U`m+>I)xEY3_&2|?j&EM!|q_dH7GM55xeMvw{!gTchXrKp2273Yt`WCtm>Erh{QZZIhoZ>p?;c z00mg6wlCq4B37pveOdVI!y&rJ{i^ zKhs7+-y4052Q>Wr0Mr2b8N6~feAyjdzCTx_)k}|8t;V6gSip@CL89W9!%Sj0w#+uQ z0lFGxV6iI9(BRw3KcH5zAo@1*Gq-d&5sQoASH~XW7cy%!b~VTrDtMJUnfPVkOr!f1 z?i5J+l-emgvkk_HgIE)QajADeIs$(E$D_V-HbGUbUUf#5%b-36v1|@ z{bj!@Lir+8F{NBZi0hx?03a9CBX$(>i%ydYT7CF5Wbrvdv)O_jOjA1?&;b-x*BrSM z8nTv9s%T&kjrXBS@NWhQs}JT?ppr|33I7Q&4~t1u0p?)}=#{~|SG6xNELILgf&3Z{ zA*utjR0dOu(2L)7QIk*;p-VYhy2?-mQ$%I7^^1TiL^9ge1HFqlSb*Qrhc5@J5V5Oa z7cb>#yq-V>LtB1Q`C_aDW-*F=dN3tLDWURbv3jkHH+6(!Ri8`#T#2NrT8Jtpk}yM3 z90))^TGayqRmDG*d;N4Q4_LW5z_aH6I&*;CAwP3~M_&^hatF|-2!M*@Dy7`+P}|Bt zs^YDHE^*CB7L|-Fk>GRrxu@ksUcLJ9B?nbW1eEoPDrWzX{p%A{Et^&>BO3THbbM+o zYX9`mliwSPDDv328!s#2oV^^=TSMs^G)zLP(K<6Q{fj|W zBCSFmQ&qMm9$70J4yO`J1;FX#k^yi`o#Gqt1w`Z#*!u{L4)fuObUMUwN& zPI=MOr9RN>8mc-vwyr8>9mGw>zmtor!~HOm_=-}OhcQUE`_PZlGW5;W3MZgf#- zI)Xqz(3b+tk)iN7f=HjezA)anJ_)<<(qe$I$@KR>rxfIPFmS|C9**Y~(s z!IW@~UYT0JgrFML0(fEmww=g$scHfD)p5K1LVyGjb#+UANd`6I9|RdN@KdWA{8R(3 z3w(wisSGlB;Y4Xuj{^q+aJEWm2*zJl5T!uL%YhNqp6Vr%O6m&|;YI3;Qqcn_fh?6+ zdlCAARz_by%=#atFR&%_%Y5LBI+Z>H{JdgCg0t}qdXqXFkDPkRdMHT--Bj?(Qj9%d zGocNE35jN#6{;CYgmTjSY#Ro%BygvOvk5MXuC4JOEg{WnWdwsAKrQ zIwR$!iB2RUl;~jlsS3H6Qai5(5S?&3ub;r6z$gJDS{9R-xWz~R<92U}$O%Bdr&)@kvx5!b3A&{HG+77h>_H^vMgbf-(xGiAmns79_%3__CKN%C(!nzl zf%K1ZhOvZyO>iQ7i7hnJ{Aw6EH7ou1QrrfdC;P8-8%XprYNaT`_Sf8oXS*ilT!TQv zyt==3jlbxcV3k#`uF#KxG5KCRL{CG@QilR*&Y=bh=RXgkm(>K%z~eYM_hr<^zFIs^ z1@8)VurSv)oLGvt_BtYR2uS+AREZr^%8mR>Az?pP&kJQs^~ z3YA19VA6p{?9qr2fHo49h7bWbB6Knp*G@QieD(2MZ-Yy8wJTbFEv!GveD_<~aL5u> z&`j+mIOjwdvl;;tCkP0UM5Z7FO36wzSU_q7@NZ}cNH~#7q+om1Zvg?!!;m5pLZ#5i zbcD*llhghSNP=?^SbrLs0#=$p!=n#1X$5fwTtUm3=iR{JM7XU`(V{mPaKbngNIcgT zF4uY#i(hH$QI$Yw`PB*G#0WYAA&?j(3Kir7`k`Ta7u(v@2m%!$(TF63hS11FGPd#k z1%nQxH8KI>xpXpxLL_6aFCiBZbRvmPCr}A=I!x&GX{?$g6y@QdYSQZAW%`WPe3>8s z^@KzqFlZDY!xM-UGG~{sj#dh3W-$G0zjyS4ud2SSZ*pTJf4Q|+vi^E3`U-Ukf}77(~fBZ|9xK4fMZap z2JLgaz^bApRT~U?iyb;hR8}!rrn0S+-lq{6YM63`mc~5`x>W%plrJ_#vRMs=p!5<0 zzm7ttKq?-kB6|^hnI$fJN=;g13|YRMMb^;Zzj78Cl)Uf9`<#EzrJ`p*FlvMVppiUS z=rTY6%S7TzAH@kMG$&EXG|(UjcANdg2i^ft9|9ejh!li~Ab8};Uw)o-PE8UZ%$!vu zK+g>ks|^jj2q%vQ&4R!Iprf7uG^@a3V7LI#fR9gv@-!G)1z?Yij!#7~lD`0yw)&Wi z_zM831Qw*Bw8at$?;7Cc;dzs46M#~dp$Z;B6%@mZ5C9-)&>1v36`>LVsN=zoA_1Tw z5oCl;hn~qaIt2&%{_Br`2A}~h1k^|a4MBaD0jbeWKIAyO5?O7_@3)vFdNnzSFJkp+ zj0jkDSU^DaBu43K9N4N6L=p*{I0PgBsS4{?8x5g`N?V2pWS76(BG!2=qHpaJlXAi;Dhh}feIzNwgs^jm94(9lS9v;h&ocnIs`P}hI4ArJsh zLJuquEbrggRcg|5x<>Ma>NZyr~vjwM*N+Qu1K$=AV_NlR&wD?ts z#`(N4FCMIlt$hKx6$Sx`fFZ8n4$&cL#wb-4N~BRBj|y|5@E`0p`|VU%OB%#isj!cs z6&#v~^{vF~rkODnRnbsh^5j%f5Y+u$SP-5(UmXf zoSL);s}K>ZzE%A@&ep3~Z_Kv>1prBNXeS3L5+W6X=)TW_X>0UZ$fQ#szy=z*Jcbl{ z29Zi*5U30Y&(MjOkK(TYo^eV|k`&x$tuAEdXR3WHs+tPb=zzURbjW&9Aw7bWL26Xg zJP;so4)Wm>3_mqdB|BZ?eJ~7vRHXWAfT5;C1`=hb0hNtF#|Z&NkctYfF4%Bzl)diq z^DPyT5^;)c7U3QyRq%4g|3bCJBgLgfWTBou6; zd1VU0%S13~!{=W4=`zSNQOXO3Vfw8GsWLq4@|@-O=1K3_F*SRu@U!e>QSFdYhq zfao~rl3KQ;HuY&0uQnxfIp}|=DlIFWn8EY4gz!<2pJ8pWGb`<(0m|NYnZI8uk6UFz z=^SfuL%Q-rv?^JARI!3kl+%z3i1#p=8E;1gVF=&1!8Q@3XG*Ex=k5)Ke}os?@(Y3} zCBFd7x9}bKYgP65r!CX*2fFH)yaJF`G1vXCUEwd*?N{)Ds1Txk_6kzaSE9%nm!0SC zhw`dh2LQX!_f1|0t@z@#ThSbVa7f8QWfa!@UxtFx2n6QWVF!x4rj(clP;P5q-~BDe z&8|j`i59GS1@d*(n0WjJ(~;1#4^sg64y)CXrF10Z`LVFtE7Fm`BlpQ1Zr7lo#CHH+ zv)5QFV&9}{0UUyVXa+2UFVdnwV=h|M-^7o=LRB2E(G*Q*N1aZa**h|^{8c^g!#k7E*0WWrUQIGa- zI4x*5dan_LMqx6q4TP9FY6Gj#I4r_9=>oNn*h?#GjQ=`!G%T;5f9Yd?0|?*+Se3g@ zcpT+51p*YjVHdtVA(vN8M&;RPA0d>sWVo%xE!lIUk5`ZHG3WC|sE3lRIR9ZS1^xS% z7Z2I4dWaC!lP_h*=7EGFP^yQg`1TFRj(2AL#gO{c!N6V5_sRy z`v_GO=%d#Zq`nkOgy*mSF_x&bQFtMis3gUd1U-97Zraz^65*<<97}|zT}v=e@X=1_ z6XAA!CS*vx!=ES?*oSBYrPSyr+(;?l7jKXSXVVl1W8nRjW}{JV0!l!UT`D@?@0jny z;IW!gj2KjyYvM48iWSi__j?)R^a6@#p#BJ03D7-~K_n9>P2|A4y zbz;SV*GsigMtUYq;dT?qN>+5N-GU?|3Qst0#w(z{ze36j5L*y}oZ(GQR6;dym{DYh zN;l4DKuI#*A2|LzycYb{R3l#sTGXIpmc6k*9E}%E6!HT(c*@Nm;NZtnel#9crmz%U+epw~L zQysE`$g!U0Rgx8z-lkS!)U&%E@3=iL9#3~Kn~2tFsA zQ7-qGh_^7Vbjx85Ts3aFGVOQEOw;oZc~phk^6b18l~_b(!8aW=dWDfK)wJ)PePx7- z?QQ(JFdC-hMPG+FX1SaF1!mAuf(;$DdPM{q=sSQtF6Nk`NeuM1zQ*~7B4RE29lQ@@ zRWkYLjj28!P1V%^=A2ib8h}>ZzU_eR5BMlJ?X0}$RrRX@`pZ!RI1#x>4M0=F((326 z)dW~(y*jb*Yj47fQM-3XHrugSvt2@6bZv&&ufbY@aB+y@zhweO0UtYfp9>8M7v#YHoXH=&$fP(opj+2mFGw2%aVK&o|>iTwHYh9e4CScs(lqSXkJK4fKIZ&osKdr;!MH zXmIfCzy@9?=O=_^mKq;&QL-KfE$pcJ{jPqR2#HuqH9)_`vg=TkZSh|R27??yp%fQb zW4OE~ElU-0EydXr)WTJgt}BuLud>tNEwUhvSINZ;!)t9Q-VQ=|cPa`Zh*Q z5~%Vj5=${l{&mT_7cWm3K7%g(Q2y=rg9TLmgb8iY4r4hfWV8n`LNBlHGo0f07Vs-3 zqBTj(urF4TIr+De-(H%u0h_E3Ge={HNr3oCQwn_-x^V-W2 zZ&Cxn8D8V(Cvb5PW$|^9Ev4I@9o~6H6U-uZ-3trul;)$94L-bhiE;a4DKI~aK!mRG zROtK+O`!2{9)21M&s6w3hBYw!Q%;Fhvf5zwy5ZiEiYi6?YDEI3GnFqAcz_DHxe6g$BocR=x4t$dWDIY45bM|lwONw0naLdPP|HCsT6IG%pm1Fx(0cDf_r z$pbiw6>xj8M$scU?ycUA#bzP+S8o^9Y(J}MUX|Y+|4bHGv|>P1^ogLkdpLfh(L^m2 zCmH3Cp@Z}o!6>(B^`>xdDJ}XO!Q$)ahd-e(I~Q1@DztXnMC{C!^wujnrlB;Rc-a~Q;;{gJiPb@!wP;N#0puo zTJfkAkMhOic_iasu6juXD})}N=f(jEvlh<(^W8ox(BW#uqgLaVuW<<$vwf($Rze_v zRWh*gFE=ZGkPVd(PpyR1N{AVo(BhlaQc6NHYbB&sLMoIHYpt2_w&yJ|=&07r;DIC5 z%vfvfOs$AGE7l^lhNf0TDiIM^Ef%T8A{A-8HySPImlr{S_x@mWP$sp8X$ zF;FGv6&b=x&a3KmYqvzL)_k_s#AO^p!sR9WUrXu>^jv^BO*XkokCO0eBcQeMt!G3) zGm5GJYK5d$NS+}ia-~uYBZlR^3Zhy;sTGuG2#V31p&shc8*4e1wSeon0TNNF%Tq3c;?J+X=#Xrb+grmDS3kSH_#*`;S}m-3R|Zl`pN@Ih+Xf@x|TJ z=yd2g?iCcgyAc(u^YW805-|cFERC1OpiSs-QLRBDhIgEGYCqw)~6Ej`n#k2Y-Xt2L)%f3IcO&|)c&Bm@Rf)oA%Z}G7Hjwq)Zt@I zXz*HV5+#B`C~n3;DZfVz0~1<*@kE<&;m2!`h*I&niNzx&xo)-6>GQjw)Tp+mvfOH0 z-@#|pR8q=XP9lXC;olaLQC=qy%t-o+4L(Egm55BaGbiwp(2A5=k+pQ%3?7zEu1r^> zT$V~ST(QwayH08hdJ7+v0{XkRt7K6_5i-Z7*XqzWM0>C5m2!hnu238No-gVcQi<*= zIHMsuFn6MD>?P#J=T`i+f?PbfT%)NR zco8CeSTFwsEl!6J1wnvLkki0iRfv%jG&Z!wG9gJ44iXKrjDNFdqy?VgrNZG74pb=& zi?!RSWbajVqm;ssHDX(M8(2YP4oXRIsU{E=D3-#&C6Pf_Dk)U}mqiM?l-w1KipF$G z>HfS`$Bz}a#jeQAgYQE3_gxqStg#>NyFl|V3Khqa@bBy4%9JaLWn278)N&Oh%?TQ` zVF1CThJ?3&hlKK#P&qB#D|1?3a;T+DH}{tzNvHw?|FuX|$k^>J5+oSLRs3wZf`r?9 zf0c$Gt2r92th4b?(P$ctoGd55G>zuHk@auuvR26#~$`pMol$3l~8|;3@ynaR1P8u;tFZ@$Jx317=EU zMQmI9Pp~Z4iu_%vCE)$4aK(tc$k{Zg?MKa6(H1GKPoH~6Y%!{cL&uZAHL&K7L1%10;<5l`M-Uxj|z+oo3hg@ISU~b}!CUjSii-q}7hB(B3Cn zv~GMTtJC7I|M&R8^{?Mnw5ivMS#Rdj(B6}l-raEbllyCpmww$Sa?3ZlPK9KgUvTrg zjqAwwFZF!7U_p2I|5|+4tkI#Nfq``@`e#C?I*WFF!IOkB2L}ZO1iV?%KRxnS_a0OE zJBHO^J?T7t>RU-ID|tWW;C(}nRCq=2r)kCxi0=Ae{{K#&e{12xYmOZggi zIWnVGE@=64@{f*_R>D#rew@4UgSqJ-&Z5@M`~|LyuA{?|=5>tASa=CwHd*3GQ4=$#jTd8oDKinVD$doQn-_PR7j{0ePh=O6TXm2CE>|D7aBnUvKwa`w3iSMTf@_g){v2a}dg z{Uzkm-P2#yZM{|Sbi|&|41%7c!gj8S;hBzhSrl=7eBZDKU7F>at!sAd*)gz3y-RO3 z{p0N0j!YV_Q{U)FW#6S+hMc7*t~5KgMEoSo`h9rJ(@~%N@yqdt_QiF+eZ>E6Md<#a z8?CFx*LThnHSGW8@hkVcHC3%zjSERopE^Bq3e~jEk~JSDZT|A%9oE9oasQQ`WmCR9 ztT!(o+-ljiX^91Gnos_%?u|8~r_}tqoEf+C&$K%B{kUHYgRVAM(8?Xyzh}N#HSr>G zS60J*kB99)Hgv)2;Q90kvs!)fMXP#5ckk0Z6BiE}(&m8sk?4oT6S{nx6>?$SFW2SF zfd!I?JSt8#1 zq4?H-QP=uO2Zg$4k6aymHit8P^y#+2BSg{T+RwT5@axo-SNgY`FjcxJ?0(TkoIpkI z%7}!G0p~jh@dx)jIY|1secF>q;Y!k&o3{ubED6|fW@hx0E!6*;v8_i;PO#G&wtwn` zU!;#cwqdN18-5(cm=rx|;Cst^xA``T^kDd=%Q4n3qCVwjSR-7YuKn@HK`Rfu#iiRwD~zhzM} zKio#2eynkR`E)$(bJ-hJ}T?=)>S zM6hD3@QqQ*8?WA7B)Z?=8}lbm&wO&!+W*I9`ExpN z8c*Nj=5(zmc*1)qT+~6(Y18kdg%d~d&V1siL*9Bb^tTZa&U3v(HWB5$40VljRs?@_ zm$%^R2>ZD$1!E>lm;BJoy{g@zVIvhSEV-g#jb&5j)X(j>ZA}5Ki>#xyUuUy>+VvkA zlFn`GKks0`U1OF=UH5_YrfA`l!>cBXzIN_h*E;OUW$sV*pHDSk=#H?w|Iw32%q3Iu zC(K!#vw!cpr=JI(Z@Di$M|AUAwwB#}(e-6_o#RzERt#e2Noc3q6i!_;T4CkWCoglR zejGgOH?8v{{rlR1Ez|1#eCxAMR|bdC>Acv@Qun+KE6pE0x;^*fr)|UPhlR<4wvNg< z(&@jPr4xFZA9f!SroEDVW@+7Htq;ZD{o(F_FIKKT`u#rD!unTcuL%A_!<=fe76v^Y zyz@%5W#r{%#H+U=ySH1YJbHD}cKhL&y9-DoR|MZM$HdRrHtcBlt+-RS>Mzv2yXKLs zSLEQ8SF*pj-C=}zvS|J75&i28&*r6Wvy2$HK-+1^Z|?eI!#aPqAY{job(Z|)6T>rx z?&wVUso`nf`?p&D+M76{`vO<`ngRTy_am1kq%1@(Q@Fj5Za4nibpCFg`T4CLEo>TF z5Ophh?6K=BgBN{%IXr6X*`IQ(O)mTvu<-CGLpaft+l#kgT7H2rk94Ztj!TCJxtq}g zCXCqr-x-;EuI<)}E)9Eo>XOFCI)#0(d&YLHgC5)K+X;_%)NQkM@v%Oe7EU}gdFsmM zM|nX5gD6u@pFs9~5tlWBH6eFh;D$+CPF&SS9kljFM8-PBIa=Nx z*_cDSyRPUGw*GD9IM22>&)ENPEN%YzPdT1Idb_n_hj;BXG*oa{@0gX_{L!xW#vS5Q zh@!$vrxkC_9`V*?hI+~VW`Ei@KbiiZd;jm}cKVq{-=E!S`#@3~_TneUuB;k8 zWTtEr@n9t32Tz+j0}42EX9csy++NHGwAZ^dz2~&A5*A*+dDydZ>in$GQSFAWS$(3R zp;^|#H@aNX&%BqbyOdl{e~2w_Blzm{eb=$4L87_?R;>!Q5BMo|N}qe~wx(~cgxm{D zT^LA>D>=hk2U=Q<`L%6vx45}J2GspOqDx0qh&$X zR!*Zyg;Ouhi=@5RX>OA{tR?pMuM$L~n&&oPrXL@(r$OUK=axxl+*u#2%6j+fn}-J# z?mh46J4F`SZO84C*S`zvK;K~4`qA9oECS(UXUjzm<_-R8-S%c7`&uI{3Syo}M)q83 zs1tg*UVcC8rQYOh5 z-N=pmhfa)p=YP!}3=a92O}nZJ`L^e%Z@=R$n5nzk=8HoUx~8o8<3z?vYtu(aT(9f1 zTYR;8@K3qKwtd$(ztJk%FnsW!vAwAyPXE03!k2SI>*@~8KH3;*w{zw;(GAwUpqx3E zTNPgTg8J~CeQns^_YXf1HhkgEF9!!IhiAb>hpu@iJg#4!=AGr=sU8pFbgM%=MBmr5 z&cokZZR@nQ<5r_0m^C~ubo#kLU;WW0sP(-+b{rpeXL$dg&3Q9*#sJy4_WkCi-+CvY z|KorTb=o!PquTq9c2?Fwa)517X6W5EhUQzYCYrtob8vet3|$d)dc&5f{mwNfD)_gy zf9_F^ZD?-Q@WI>2i4lt~X%;ui6zNYz{MoO=7wgv@z3s}oEH}}v-i-a=oJHAQ#v$Ka zn=|mzmKk|F3bs7ix%C4Qr^THGO|I697`ALb-MMMzwganrzpXelX2GKK$i2Cqq1{LH zJ+=A&VxL?(zUZs-A^NZ8KWfLG*We<*Mc)Iz&fD0*eA#m6Ab;OkzN72Un>Y;F&3MyK zI>VZi^JjeQh#nan5Z$WI?ISHu(jcV1 zdv@52mVHxKy`A5@-(A++t>m1I*S6n3_eZWscrLU-OoK19l7aMFCqF;)@y>yVH{^ZQ zMlz1>8rJ;0eqS5DlYNXWVND7(w2bT7Gbd>O`nt1tA;CSrnSVNWZ{dgAcu}FLJL(s_ z*)?EwZ)}^bVXn~sgu0p%8$B3H>)W_)aMbKa21(w%Iuy?ExmP>hwNoB*;+zuZ`! zv+BQ(4d3jVHtgNDZRo9sO|(B88#Z^>6>j(ZeuuL1&#M}5Q3Zd0*K;@UQJ$vmkO})j z7aq7Y<@C;t-Pr9; z!){Yn4%>UFOaJ|Ccb}NFcguhc@upLa4yAoV+vz?{1&GHp{xX_vhyB zSkbogK3>-_FfUQ!Cn0wi{E)WxahH>ZC6DK_mmGEf+5Y3F%hnmrDGoj8B$;(E^oxr_ zkT$tV<0awb3qE8$VRdbrHIv&lIEprA zv})&=bK&~HhCR3RrMDILe{h{T3Kfb#Cru)`M|?#tioO!C}F7mbM*udhh>DHN}}u?RSqDJa_GmF3-51TK( zzxP6eg@b=^t{vd)7B*^g^RLE4Z3qj!{f74Zq`{fDBPVJC#Dmwh)i6aP{`~yY{X-v) zZMbe{haY3#VTY`d1}L+iaJR7zXa@KFWAeDdFQ?aKe>!jKTU%S@{@49W*S;HK+t&GN z^_0VBkKPmxB6fECOy>7u&#k|faZXHl@LkVF9byB+njY?QF}CqZ);kT%q=0MV-tBN& z_2%;4oiERxM`-Sz+g=71P5$ld< zuhl&iwRp-JDQ!L>=#%w1v73f{b)pHGlsszt{QrE@bS7t%GniID3+b?fymRWDyKScN zyA2aRKA1-tF?Vx=Oy-GBm)hp#ZCyQR9W(l!+y`TWChb1Qf4X#W*o-F~?L5PR1$k|T z582%?0HJMfdYXSmGo&SI!RY-9HZJ*X_L!c7E>9mY4fIMn5ciM;>DQ z>U6V~_x6WhZ@uB`v?VvB%3t*XA$S{p*+M z!z~jdyW8j=Zo5b9*K=XsvT5~JGrl#2DEm?l{!UmPk>BRy#-WXaLeky6+vm0!A{;GS zA9jyL=(uXn@`n8`H0w{iO^zbm{&d&aFGBa79j0z{|A56g%z9`hC7|HIZZ2|2F3+vH)HqL0sCtTTnv*-0Z z*5h{KxaDj14V@Ml{PvF_!Ky7<7Y{llhGu=l=p1=IX{1daR!SDR=%}@81(m1mp zbP^BPdTs9Iv7aA_9e$_Yg*F2o^Lj<@y>8p`e+~O3Pi%jbcP~#c@w1M16V_+y?wePR z`{e6e?LS*wf2OhDe+;&9I|rL`kBt6h`I!w344{cld^~IXtzP2m({3MLJAKUjZ%=pL z6f|J=DiCzO`Qiw@`QDm0cR%GxZ+$c}yVEBJm8*uX&+nHRGyHJG^)J?L-pk8rG4b*K zF{9Sp=-GYTFDVBu&ELFti0;(nVQ-&)+{IWhr|GAe{pU4hM`RuDmLH(t%icY-;BMEJ z1#|X%9@ch$hbEW53f!W9xZ=jV7+n)PX~mL#Ll;drzU}q}^Y-!f>7YmMP!d7s=9&?{McvQ$G8H`QHdTF?PJ^ zVZC!id*Fy;_{HtVrZ#PY^lRtZd?+Y?LxXj(Px?>o=U&=D5#H9d^~k}wZKf5r?$Gg6 zefE}*V%v!34LjO+xJZ9@_q~1UZ^$RFb~Gfi&a{&++7+2KGJ96`(Y&0ab3<-yZM<4G zzmRG-Cp1GQt!W*ozQB2ZIqZq=wjRsgxOCe2otoR%`H`a*K9u&gzdgL!heL<|p8f9n z8`ENmy}Gp_%%M-wWyuBL07emVGcvJ-jesep1YWYqu{i z3Fr3hu}5=a)@K%ZmnX}JlRdtTk-{B{;{V#tgJXVwN$GZu&+d9wdEdMk21ER=Dg@0$IaEjNaZoSxh~w{`vh zo*UQNb850W*naq@|L%X-{&d3P;i0CmG0Lz}H)aK{5bf?Z@a?>%16=-|BDEpJpe z(VfM*-`+o=o?pm4JMYlxtfOyqaGUHcS8geIzkB}b(_er5&GhU-=T&9yfzJ&Ev~Bl( z{#-P3!#m3Q#vNM^pDAoUF3F2b%**??X!sz#W9tR`9!MR`-&+JUYC2}m$Wb4f-xm$< z^vTA_QJw><_OXU9QuPHTyQk@!PkEhIK8kAH<*EH*bZ2|lO@|xHB>T?(MrkQr(qdh2 zN8JV={@`wVAznM}j{WPf4Re>D-?4M~YyoL9U+M00Y;n%f$(H|}y!S)nkv$tT+72Hc z)^EGzk5y-lHIpZI)%A>a9}qyB=tzRsLN-~I);zWXV1OP{Ak>VOG8J6{kpyN zj%8!p&M{@JOrR}1U^P1$O2QYk3VASpMVBdy+Kmx%j^Db)T6|z8e`P`L<#YTs^Rv6I z-?Z1wTXQ(;gTOP^wY!!bJGyOtx5q(-8T`kNtR;aVk3Jo+?c=dQI(>g;_Tho&Op%XR zi97ySsrw`7kT&=~J97&6JZisnhP?lIwRCR&P1V9tgn0+L?r|^eKXcoL8y%Lf-g9w9 z_nF&rkM&C}XwzX@6y*Zv32VFj> z_mk@b9}hk~;`89Wd)r-Gqwm-wZ&_>kt{uAxzfCmVx-@IYlo^BbcC}Vayu~++wDi08 zLx@6RYt-vl+jG1pd5UiCj8AX>FuUoY=<7Y4D$&jl#*#?pB_rJp*t47e(6D*t&Ww)1 zo7(N1Gd1AWZk~Nhy&swk=n}FiZ)#!e(QT(MHlB0wef`#ZhOBvKw;!LvIKOXb?v9U* zYl0uVd)WT%;5%LJPB>c6usuwa-CjxBkn@e;Y@;)AO9m}ndAaok%F~>TGu+O|gP13m z*M|3X_ilVhyRMg{-(0rf$%-qs`uB6Cmy)^6C%jX?FIc{P;5_<{nY&vzrJbDuvC_m| z0LmHqeLUs*FiuvYSlnz84z+iS*tpjoO6S#|U3p|N!iy~Qt}ozhCO;9&>k# zZ!od(yHdwF{ek?27e9dyZ(DylXx2=3H+ILlZMHEBKROt2b;oz#HTn49=@Y#gywwKO zex1c}O?cOBC*|RWn~NzUthaW)IbhuEM)!I*&FX)B+xeas`))nZc;u}W-hdXxUug<9(J@1R3`poS}>!-fpTF0LRO0dI$6G(^Q?`&9> zFu&F8-^_qW|5HenM<0%jY=31evPu`6j4|zsR7;q0=3LLd0S^8P)*oQ@kmy61?CA)kMDzKY{WiAk|FXY*Oj}E%-A-gn_)=k zjwodRQMZv9G`Fp1%y-TI3^tKW{01iY=wXUK7a#8K4(WDmVQj#MId4yj>SB$YI@mVv zVC&P3502c?YA*X5Zp-vTs|M~k%Uw2M_wjL4$hn#CUOhDax<<~P7e)>WL4qRA^EdPN z4ShFd=dTTN#?5Jz^;^^3k-Oj7nQKNlzJgYO#uB;|LI7gDT@BTI9Xau# zynnmX4dT@kTuY{g{S-tVnYxE@ZdnI?`^i&7FIq14IDX>e75A<_J@RJcgH<#RAhnb(uIox2I%OIV#Nu0T5_xWRy9?m!=_nUk(bH=urSF>ZE)Sn&`dFaes%fkVZ zuRpvNFs4q_u;1&CO8fATYmxZD!7GdEj2f@%4JLU)gF2bZdhePu|B-xM>i!L5hm1-3 z0t`~$(6FP|m+|{9eY3vu+xRZs`YyQjklKAx)47jXb-(%T)3?q{-mo%cvM3}fu(5D! zTUq2pw&sZ3KervzU4G%$4VR~nzm;=u-t4fS z6+hkUdx73>vNUq5bl*qZ&%y>Y`mm52wPUIv^2`VB`4{Rnd-L1;W4p8&QLI&(M5+09tPwsiWx6@9^K?Q6F6odZ1^cIbF4xaHZP z9e3*mzI&B>R@%CEn<1^wjh@hK`RK(LC*oXyKB{`Tvs?6h;NEg%kgmhnrkuKyR}C9; zJx}>gY7VdY{`qT~U+%s0yO_(P){__I%y=vC585ArQQvN!xy`htWyB!MPGw+Wi#5N_ zjqIP-_2-TUdt{Gqc)!Ke@QEQq?IW08>z}yT)os+3UYAKbm$n+AGK?lrI?tYw9Apc6 zk1wCO?Q)=TpMA|8je%tS#FIh)nm!xw=gql?>t>6(UT?l>eAiKZ$Q!=9JK}22!Te+6 zTCh5=u{P?Ny-2RinfuL@ajq-7$9KvYpP^W=et+2Yf&Wj}TSrCtu5JH{ASERw-CY9G z4N?Mw(n<*kNJ}>(4HAQdS=z}XR|7UKdj0|#+ z8|5h77T?Wd;2kI5wop1f?zw$rwle(m8Ia=1yevPJ_?-UwXC_CB52%%pj$knbfcUQj zw^O}^>%K~lElFubh9HE}xi?j_s@#{4#46(<X+>f5&8IV|W!&<1K`*w7?0dcmEgRjbIm0r)p428!}N;VzM0BWudb> z&=b`DJ?87|#;wDc^ht!CyVMm&hF`E&e7`B@P!PpLe_RaUQH5w|VpW&a-0XY;Pn)%i zMT_@{yLtp~zLm z8;U0o!QL_u6dFSzIi@bLX8i2uC3TsQ>3pHk5-+YIQpt|VOQ``ROS_~iyFH`j;?%Ya zzDJuyh}oDOSF2Jr16J*X1?QH2n#?VuhCAMKCjK6oVSYQ!s2YRXbQ2&LVujDfNnzX7 z_TNr(^-K<}0nBpZFMA0&do)DnyI9klL%#eoqOEK9`jO^Rkvh^6Sf$L=6N4x?M7>>q zch`bt4&nhDTAZ8(Iksw5UDOa0)!x_|q4@%|WUn@U6WYeSh>0Dj4U!$k8aCc4Pf1z5 zOE$e-ZU{*^|3PJ;@bU21m{uVGPFDEyK0Yxqaj|i+$WHTUnGTbING{ueVfFg9p4n&J zwA^$#!Q?H*Um<@PR>3ID+DCF$)1453ft#73&S+pS_oo5-`U~?kmh;%*DbcpCfsm!Tx{akY4Aa#pHc7Y{oBD=&2zcT3^v=_ZB_V(cA%h^jblC+fW$;0v<$xe&bH z-V$5em(AS8ofGu#dy*8%k|5V&H^OgS#`PJNys@;3{tjQP{oSj67j4#lUrEI2(R*ZoHVH#;O=`R{t6vJxM#=R^u0p>gIJ@$ri)NB|`JAR=3!;;neCcr7 z*rs($Qe-)bbsX=b_h+zaz(hmK0j4x0=Fv($CjJsaYdi>RSt zdxUi^`vO;@!ADeUGzQ^5ne^p0Rlr3?__32r%UEQga>FA@wt0ifg8c80M5#2mbE{z% zfg;icS`=9K6U>0W7aV7Jaq@BO4@yqh@Cjq8wzPu=m_35)YC+WD|9W?Wn6`RmHUeWE zR(Hj>2$Ycv&W`hL8{M(qsVSvha~U6O_5+{56$c$uMj`Ny$!AmqIica)Y#yHt z5Ampc)|g3dhg!$yu*yK6S~kVgyL--;q;o>RTmDb6a#RlSMA|kIaTy{FL zTU;H!?9YVT@=%;T3}wPAt|Z_^UihfJT?oC^rqfm7tYXr)xs3&9_{>dwdt=YmIUUFW7j)J zCiq?`&jgEd&8-bEPO~)v2-#nvZ(Dw%B`$2y_e$)uNoa1*WTH?EZ@+(N+n&>00S*l} z<2N+w6iuWCmqYyFmkK9aZfOzpZ|w@Y#}%rkIS*j++m23!NKUeyD_NkZ-X{w zCs$-yO(CmMz{m(-4JRr)1coKoPV=}^w)^M|zuXjRv6A9C!7h=__h)cuDu~#T8AYy|d{b zp)HJZbApK<-W)B^-jM)wR4s(VzEzG!B$*F2x^L7g5C@6L!F_(Hi%2VgX2joXHIQ`IUO(7XEZMdD?J2mWg8Zt zAKIlzoKG7hJD~8@xMY+4o0Ph#uQ$o;P(hIFJ9_#}r+3-hV<>1bP=$zIPsBMp^4(a} zr;#WqV=IKdoJ%FQoPLPKn?@WRM~f}OLgV*=lY5%SZZWf_v=)&;?VzcxY0!z)y?MRQ z)8M5H>dVFQN$mjenMG2l>yFNcT66C=rA?Q0La1WsdKU{8p`C4;tZVQ(9|SXzHm>WR zj7j?y&a^5#OqVE@)Nv`tJYb|VGGdWvq9c%{w4@Ji8~d~?Y|oSa_lEup|N8O>4I3_F z@+$bWli4Jng%PEVQFLaujyGPAnV46{QVw%&fz&rlv|QqzJequx+t**;5~vCI&BCPu zI%78nc8TbwybytlO^(Y|k;zu#Z$iH%d9GZpYHN>5JAFKjieTa$|7NN72E0(T#{v*x zW@X*dDf-cLG`9gT@PDuvdnn5yN5IY_vWWLWY0?T!HqUQcAiQ&@X1{!&f<1j^_hbO} zu%3o28JqdKR_}THd=SUf!PW8nmc!()by7G(=9vti9|W)rcZtt_OO!l(9{h;5eM{<0 zv*4#shRN@vwAwhxt(@`kzn0a10ZIdz&>m~Fc>VZ2)+&#wFO!K=$Y-pxKbl@Hes*nI zD6;x67_+Xs6^32xH{zvRXPdE5%dhWX2+kAc8PQAsf#~X~bAZ~+12cW?KD34@E7L$G z;~?1B*kX8;LdH(A*9T}vOO>@#VV4J5F0QVvNu2u2XGfYqpow&WdCv28z@`(x!-IB= zBr8t#8C;TM6eTSVmTRX|qsT`~&i*8n`?;>MJbZ9}&0eij)yzTr`Z3uYDWu8~l^5dpwRLL*O`E z^2o4I72f|B102Xi5!h%~wZPo%UC#f)NUGvQHKC1eR{s0$7K%IXGj%%GHEjYptpS>MXCDNOOo#VhBx z7(4q9Y6m(p@!t$*B}-)Z#`i42q8=Sl0uic8*-jqiUS!ULOZBH2bf0&qEWevKwFI{v zuz(l(+&tYx3igH~BPUtEexF=cxJcG;Z|YdkunYawn@;<9schO}@-o%fTN!ab7Tma;mw2 z;eO2pBfr~PL0T_FkC-CP9MSE|49I)R$W7eG5LnUg3^q_%dJDIaG|P8{zp?(l1bDQP z6La8S#7#0C?D~`cgAVw{S96t*a-cF+b*=pwy!B;2l==Rd2nr0s5A5Q5_e1c<5JOj_ zO$|%;NKU_L#TEv=&*?Dn(i9UNPgnAdwEqCP_z12MPNnGE!nb{D>Wf*~<-W{+u2{eb zyfTrLU^!CSA_@&gv?dO@O^gQNBO^I*_Sq07VAnF8 zE<=|QHIAuk$(~yME+0+;;^_Ceb;1^D$?#gm7e?U0{#_9{)yv9n>7yj*jihQ)7NyD! zcZ@aR(80HJIQck=1(XxUpKL zcgc~IO%SCMJ&1pcnvl)7?PW?N1Qhiu7{ytERwgqco<`7WkL9OSY@; z^x%KC3^gB7J|;&0M*H}oSD@{t&vxqc@FW>v$sW1MXObF+u6$6#^_GL|Rf|nR_CXwk zu#PY)?6ku$#m>NfW_*tZeEK5fWmr2xl}!@pttN3Rd!aXhtsrK=ws=misTV;gzvx#s z2@V{~feFoJ<;$!d4VphSJHs>6XtZIM42+%J(*z$+MBYfo8IA3|(qL;*<^P#D9S7xR zKcii5n|13v7ty)*rlqZ{-w)xpdmt!2fN{1 zwTB=IezzPY!p&rF@#QaD+q+J04$HLZz{r_M@zsv|RKUXowpL1&6lFsulW+}_H(&<4 z-2O`*c)~r`I8M{OiT<=P7m1td3q}Pf@FpWYvPVD@doto0Q;~IrWrT6M?wwIY8SJ=~ z-%e9L6cUd;Fr1Q`KdO4tArbj5>wzJ2kOQ zP7RD8MZZHj{9BA81QZvP9Nlxv=Wb$W9|$G~iZpl2udi9$QmQ;Bi*f)L6ma&s@heo< zxBT|{JfqOPlgwwjN7Z z_;$rq*AQhwE=b|x8$AB^0^k=;OZGzd6SM?-T#nv<^qcq40n=`sKP{Ro#fJSq>jS{A z&1GIB2W1`1^zEw6eb{E4`+Uf(jCmV(&Q!#aIsgfY#g3 zuX8qg*z*}f%r-9b*bw5q-Rod}2ba)}C!>-QTwH=VA8cbvh3ux6n>yF zTn|!Ifw7!f@$uJ;V(AF*s{s40EMP{8IN~T7pi=bK#uJJpzjq(5JQBW^vThe=gL%TI zuu01yu+Eic4@W-5wjv=r2g7O?%g`9AnSw;kqKdoAwLFNUFCx;LjTP^9@pRYfK#$i{ zi>1Ik$yg(eCZW<{XnVr-0S;~~^f^ow>C1E-&ldV_Ze!|s@&{OZd)Vc`YiTH}q z%_!df-F@N61N@8ldXg**Q9#?b|H&6Q0f?jD?Rye51o{u_0T(!op*h=jJ%_OJyRso>=x@m|H>(k#SBn zQn;RjqYs;O+;MqvNb7waH8xffLgU>MLr8GMlf_u^aRT}vnd6%$H*@X6bO7Pvg^;ileINt%Zqx;fiaq>^r9ybtY~%>8+Y3f& zsc_~>_ZKaH@D?y&FRJ?RFhx*?(#90DR6S?E*lCEk|9$(`+%XL*O}VR&_`8d2nk1@0@}gA>%|`fs*wfo=#jd zJN^A`8#H?%f9}MXEn2ut$jq&{oKIy=H~M^OX5l_GqnAvW7ks$V%uu0Zs_-516ZpN{ z@I3`p9tQ#3>;MIj0~?%woKh3!Mib5X_u_6d$1OYhpb&~{Qh2Q)?S<)=cD=7s3=*I1 z;2i0xb19DEismx=7*ZlSbUjLf9uqUes(;82Sw6ADmEQkivo!N7h*?HI$<3`YOvHE$ z%v8IbQ+Z^{){Nodc;8h-Cs-&ymYN`k6xgl|)RZw(xAZe7jy+3;4)>y4#LfSaJ6Rsw z#mPndyKCCS4BRrj=a^6RUZXX*+ls_4dD~`{v48zcJ8kaM#UBk+u`s$ENGZxfb$cA3 z&1Y<32n`jLVVk9V4A)V~Gmb3l*(;iXgPF48l=SqCQiI09Sm%Uozju{ylI-t|wZ@1I zjUq6suWavsT4%Y=x{h5rEUuSR{%LLwP&Ja0Sn41pzuJdQZk}n>DxZ2L8+qU3oJU8& z-Nd%)Q9Y>F?tp$<<7qswQcvP5LTFYj)E}kl#&##F#wHZcOH93&|70CEJYc)p>MuW> z*n#dh??pgP2yD%aAO@h_BTwEv_jYa(b#eKVNdE*qRnnzh^i0P^eZoDn*7* zb!L2OGw~&E`<{2x>GjJ2#hw>|4Gj&2RC;Ia{9I z7Va07(0TF7cK)r-yT}&)Vs7LM-BYcDpTxNISgd3n+gOmJ+XFq|;J`YuIW9;B-8?aL z1zGR9KemYx5Q8>*ifQpIjL={B*3Q_aU72iUb!43=@ME}Smm4YG3$YaiTXQV^EyVOTf?;e<*Mm3BcG!mAh-u>}toz4Wn1ucT58F<~jIG&O zG2)Kl^ZaKECT>b@l)Vae!>4+y$=1(`4)Q(Z@b8u#6^+^LBJtGJFVg zG%w#P$MT4~n`?0{DO{Wj0)MIU&4E8n=R$QclSq5ioH{Aybz$XbspQn;E^ZxDyz`Hk z*Km3Z!YhJ|jvvm`8hn+@9;Rl*BRmAX&lVCjFwi^cw0_jl+Y@=v8Lu`1{0C<+gy$HK z@{IbdSjGe_G_tY0fpdf*28E;c+hO1QjS@X@{d;&PJh0A*x9Kj_*qTX;f#}y3!iD2% zWVQCsU&ab3t-T-4O+v!-Rt2w~nA7@pDUqSj7@$HD|6BW8rhld(B;06GvpXgws@mHn zcUza_nV)YiEUqs;f6=PicX@&|s2rF|t}C&WIo7UUx;-VBUGXEQnl?ifGXS}dBrP!X zO_FDwWZm+9IPx4;K5aKW;Ckw_nVD{A>$DWRW8!xEyD!t9xUccPN-Nx0bR(ba$s0Od z)`UNJh(9M&8@}rrcl#CJ^L#E2ae;AcdurrK6K3>-w9A_*V0WrlgBv{dW2UYs+>DQb z{neS@=(vXA?|UCumgqMcdMR=0WvA(Hmb&UGSR1z`*w90c>L31Zi{1!r$9q?qEvI!S zEKJc%AyR}(lzLXR3e>Uk2sIvHHc}BS zW*ye(0%RZv%18@t-=zLe}-@`k(vG2avSBz z)7gm&(nv>ywr2z4e3aPfUdYcVzCl*SeR>>wnw-*&^69xFMn>sED6iM~r%c&eLfB<8 z%QutiH$G#BFdjV@xM^U22m8*$cD4fMfvb-BWoJECoE>&w; zG{e;lq~jL*pVZh787xlqgerexnLWaG>@=_V{)gwSrnVCdwNTGq-z#i^0u(6U@wP0B zapJ3*#a1Mco5Zd52z3OWD(um0@-;mPz@oL7>Om=LXrr{w`&4SYNo*MT^PZw5!YU27 zTvJ&SWC5{BO5LhinDoZHV@Tw)d{&>=h8x)7t7qz_&Wym0*ZN|uW>7dMvComt ztjfV_I^mnJ17Z(TG#O!e`Vc~ehViUt*hBOiRw7vMH#{I$`Tdia7gQ7MTK}^;({b0Z zib6joR6d#eWN7_I?hx)9crfQ?_WNtLo1MjeWM)o6$MfP$M+@9rv3V)s+@*@%y2VYt zZdP%{`}W})nL>=EK}rYjiY_J7io5U8)!a(#Z0XgBsd&OIZ+D#>>nH`LkGTlv0N%3n zlXQFKUbl=g`ypVfNfI=dDnRtk_c;Pow zOIT~kJPq@k(I=0nN?dbN$#coiXj@(Q<|i44dcTlFOQ3lj3u?1Tv_-u6s6HVB*}-6< zm6eR{9H&ZE^G?^Coj8b%+2H4w36Os)`9Ow>&+apooGW(Q&+pFt58Dhu6j$50;IwPr z(pZ$8H9Gfc22)}hYH{@|FxgaO1KDSaWnw61Mag>@JgJfP>FD>sj8%DC;lR@5gXVUc zop0t;?nxC3uD12)kXNC6&!8Be^yTU}>g$Wh`d;11oVQIgv3U8B4{VP@JS2D|cypPS z>-KK{93NI@U3!E^GJVxFqAZJQvzjTFA z;I8>!Mcr!jL+38u9*g@C{`s^v8>77uld$rbl&ffy50||~>Ga0Z?CUIT6d9^JkLPgO zd4v0!v>WeJ?3s!{W*)UhPl7NCz>+-k5Oh90T{U}$7D&lyN_D|}Pk?JoRv04tHR3A? zi>V3$Q``sc_|vyRtDzzCqG$uW88v6{ez>IXlgh84tSy5n~L(wX+X@#_XCd zg(s(_ugHcKg_4iX_GyNxH_}E_p-pr~cx^dw^n|fjVD*O}gd*@+ zK%80c%0eazM~QN5UIsaS`Sv6SqWsMgMfxU;nprdKs{1xz zCGTjzsx~db3BIVT66hwo_ekWKcr~0qa{uD)wC|fnuS}C}DLA2k))yY*ykp`QD&|it zP;Jl;t=4n^_O?K*W|2MeWKZOtAz|CL90e(1Ub6&cn&t5cw_)>txoCbLP!jKjpy zFfmG48%Oj}LFHK|zHFP8{zBGO`{Xw{;_{Cn7_620BWHFhzE~eJ)xhnfG}x@bGcOkE zuNqhJS@$w<#TS^F*zi_49Gi7$ti|WhNm~UjaZFiy%=MCzA<%S6&_u* zTHL5Tg#6LMW!(VutphH91a0LD+vuqj zFKbR(g%TdmVAi)khFXI$E=_d4%5*R5=qb4^Sb$=>vRQe&agiZ39Z!f|NHl?Yg7#l4 zRL3>g4hh7EIi4RH{}Q&+er{iZabbOk_WCfJ@Y0RSuy@Zlg2$YWJMZdbx~75O_N?0xhJ zru@%AHta9Z$;yUoPtLqj3u&3D1ZG$>-B1I&NM-M-ubwHCy{vS`ZE}`JXC*ek-?Vxx zLPATC*)8GS@<_@t=xjJp47NGxLr3ysuzSUw6Vo}cP@P)ea=S*gNJjm|;-~Xoye;?z zzn$6pFtRME{0v<#!sn7p`*WKxN^V^n0CE$rN0;{%P)BXS+Z<-FwQ z)-<}@|5;XpYGVB$7db7hF(?{or4*23haOD7W{<6i)bd!^+>@2(KRXUZdo9%4x#RGW;!OssAnQ6W4J-t6mIUw6tfeZ`mRJb2AG0sAje=-0gOL1}%vWY_&Uo&?Tjmdj5jNfKiTzGjZ&?yD=m|HfyP=QlhF_rvq{FOdlbWNn3c`Do0l4b zime(bq^w8cV5>ko6ei;;<`hJh-J9uhv4{7@R9@PU;0zfInA)>8$)*$QCrV>DMl*GY z2b)yQ%TeX2tv>rsUTkC^{m%3d_lhRyxfGu6*jtOJ^kq~jYhmYl{mB~~?I?zd)mU0C zMb=5qJu)<9q_D0`|2X!PI6WY4Ga7rBbTd1l)T(Rpm}_c`hd`K>3Hy#P@*aye+gmGHDc(L_2((o_;m)-^4i+>^hvQ6TC z&~)smY$IKlro!Rihk&sodm&{8x)33lJF5<52$?l=W@(vSm*Wbj5f7OOMusB%Z!*(A zv^`u6(TqWEzM0Z_!|`Uocb1pM7oTXZ)^ayDwdSkI9O3OJ=S7BP6mvO7x3E+KsoVX> z_$Ij9qa3a?9DR7dO!8)a3_y6S@yP^lCARLIlQ0Pm7a^+EKkRzd(?&kPABmM(Ojb`O z^A(A&AJ}BoIL?}d$3e_=6;SpyjPR8G;W*Fl?0V+c8b8~+Cs173AlWndN6#N=R;=Fi zVZ3|O5_<~kI{$G>;Pu;OlYCwOHKFKpBGKn}=%1MQyqHGW)5*sUx|JB&XkMd84CP!C zGJ?$ll7BQbiq;@2Kd(Rab(wE>PYOS7s+`6=X>*Y`w*l>68(HcWOSV1!uDZ>eMd>}s zn$$Q{&g*gJ=RU+i2J>9rPf{)Plz!Ux=<=|HE?S7sd9l{jcS-jNJOgo8K1nrK>DgRU zArk1Q2Q`K&J z_}S;a;BMfO~)`((rXs4RNC))nmDa~itkJM=@{-3D(RwL zzsV{02;EQm;nz>0=jth=l5gLn?UdJSu7PCD;vv1w1ncAk0xb<=OEk8=yYo-=`b}$r3SEd@;Uy3+l6g zfOfJAHyC`ClJ&edEss1@_cslPxSWiUYgsi}9%cjCUv zI0y-{ppec60TU!RsIa2dEk{`cmP1J>v*0YqR-(>{YdQPfWHf5*cH5-0H<59ny=`ev z`2-l;t0Bm#U)E$dv>l_&W89MMJ69V*XzR-aH3YudKv48q1DpMi#C}BS|B4sF031M zLe+6(4QrmXfBDwW7>cdYU0-BIp-F(#58~UQdoF!$O+d3n|Ct*3NJ*3TWUot7iQeK$ zjdw|Oc&69wZ1J?+F({aO(@E4J5sDG`geW2^%D2gkbd2%5G!Bx>@W0FH-(%tb14wl< zRlHO)Lw)#s~xPrP^M=|&qr6Q00{IG$oHNnDsZNZ*};ul(Vr`KDIa0V_j? zx!=d6FJ|Bfi)s7IH<~?Q37w)tZqh8HH{eB_E_OXrW751?MX{Ri>FL+B_fV z3WYBZs~@D^j!O!hEKp49gqAD&97w@xPQDt9zO!Z)p$@>h@t2`9mU2!hN{NGnn-Z(V z{J##>qkn@=X1Tdf{`$^N*>y3@-R`+l>s5S0Kq`Myvg}TzzQm)#saX9*y)AaSa(w*$ zGd8#PuuZNLjY$T4FYjU%emQ!X%@dwkFA$x?f~&n&{Gg*}5b!;?$=1-Z3|2Pw)-vF3 zTHA9LU$-d$HLvrLFT*cABY52634+x*P7QwPRxfhp1+$Mq{S;?ywdw!oPmx4Zn>j2xic*`}bh5Adc$^_%(RTA| zba*epjxR-~&`Qrr&(B=T9588BI#Y8p$EZbM;Uz(3((B`IWPt_)(DyPWiI4Bs zN6QUVj}U%F$G<+f6ZnDpXLvY~ozl*&KlpUvJstt~<`SkWQAe!Ny1L;;6rNW-$#>S9 z;fN#OZ}qcPikUhLz&wXDrVSquo1?*oZDv*|LP}u4(3az$QRV-&J-tK|MWZ3y(WZZn z9{UMB7w?u3r{wpr`q-EZ;P+IeD`+HARdr(QTcdf;8)VyUuI>1NyFGK%M-q=kHcN(6#Q^H2S3$ zr!{KYT)un1;Of;iEdmG1L+T^1a2%UFVv2Vs zGy6G6r^-BN5M0M^&PU2j)FOAh`DX{vI5J7$a;VT6`n!SG|GBpWn#Vlit7!V|cKgkG z`_u8!ZcG$tXmrU_$4H*hS=rk1X!$-6DN$xHD~rR1MZ);6`R&2=9f+q}S!Je&1 zfxEOgeVX218~UK0uJ(TJ1|+_ z58IVWLzmmZqGI))K~6Rc36!SzY7!J6Go6e z)`0i&nPi>k|5SO?mlnRH??QxXu?u?d0q0j45`Ef*e%}_BYr}zS98&%zO;>NJf=y4Y z^3FGzR;--bHutEhuL5s6T&;XwI2U{-T4;aPnW^61 zpz$y~hASCNe(ZB=OektZXwWncbaQk({?k<;tp(a8>?gP#8d{`nT3p;-^D?7u%7CYNhvYd7^^m4O8NW!6Fid-g@Oa1@Nl~s`jXjw)Crq5iyhx z|Hs?exbWdun&hR+af)7Fv4cluvq$lbt8b6-+q|C(u&(k(raT4JGTunkfdUWJtVP(w zp$MMHQZ`Gne;<1G&oP>E^dx8jkV2Ou_<56wo9?9e$Oom+=}pa*fu$Dl`^%(rWD7?z z)t0$jb_nC!xU&E?c64R8%5w!I<*M5a##o3`i!LzrSnd8!)2WsvN~f41*s%Vx5Q2zx zs=~%yQ$or!%iO2f^4rK8<>66qvS|BWF5qd`w=KL}+gTdlmOw?|mBSkXO7wnl=1}VR zvRES`UGz)C(pf z#P6%Yh9bt4+D}~)=-&nr8np24_(7B}+2s^}fVMVAfm#7NX`DIBCvW0KEqi(KErtScbSdh0NVhtPn&T;yzcRg!%DYrxQ~ybJTh~R z^B56Br8B7Exd|xNns1&ZVlCI&F+DUi{z~{puZQF@&4ksvgnevH+*?C+DwS_6|78>9 z#$rz9xc*Zq<@3wT+N*_$j_q|a`L>lFNQQAep)FR2m$p?4hF{++}na%^1hQSG!5Mx#1EFP6Ef6?w4H zvXX?q`4auCH^q)g1P4v=Yx{ciVIN{pyNI5ymY<2K@{O&np4>KvHz__EDswh#ynR$- zUsQ}h?zB0T(YiBU>nV4QGG9si1+AkgZD=_e)h+^AKa${a<50ob-M~_ zqYk7`aUP=YXfN+|qtjo1)BB3Gc~eD446A?iIO+F)QA(nTSk$_0>z=J;6h0qHSuu&5 zyt_}9_KN-Xn3LkNm&XtRwZ13PNfgPypQqQja$oUTNbB{@tdzpD7WubrZD9JPV>f-S zUabJTS^I(at+pF0LUwhZ$JUM_@2)IaY+bxu{aQSA9m}AR)FwrAnN+TiHL!oAyWaP5rDq^sM~k<;_Q3%l%I;i(2oT`kjyoy`WOR%L41m^0$=} zWvS;gKoU+!Kp_p(^*951u;kVkoDjC;GPbUg)#`XTm|u28X*AO`a<<3RmMSehacACm z+*3#^2}gY$do1&KYBt`+hGVg~_A~3jJTEzu{8VL}PJ~LNlH%iaXDS`0zS#;PB-|Ax z4TbHrJYtJ$-J=TCd*0aYEYj@+EaxVziwOCI6g%JHIa}-f+J#OZa9?`HP_`{UDc2dg z99kG%Y*9^;xqS9uTDo{6%x$=@L2+HMlXBoRa=%xqzYz;<(@1JWP(IXTwjxRl>(5U_ z^VE#83Zir_iJRf%Gj`c^_$^EI`D^30W2EFh&4^d?lQmkT53wuOx7$BB4o2X2nwrx# z+Byj?ThqsyZG-n!0Zg?!agTWkc(u?akqzV_2p+BeEwlg9$dJ&Yokgk|@&OUGi2|gY zv=?#17?9#bFH_nxyP>jW-|03NU0w6iUd&~|>%x;Hr=w@?v&;85rGGj$Pn&8DUG&Qr z@(0#N+VH6A*bbKyQh!_EJH>!NrW@yXKMv=U#7xPbj+t#pwHN_^Y+Q!U$cKCOx{BOr z6Z1TOO5=@u~o5W&X4;?w(7fYUqFzf{7-bD(+z$07Dp5{7V;d+tMr_3~WM0$D4g2>%c)b#$W>4mW0k(hgKY!$KR#J~NIeqAvXaG{xDZx2Ux4PC&iqvg4QuH3N+*fyA z-f|uQJ-MXh+#&BEeLMq;$W@jN_x4fihvxPfXa0?%|NowstQq~Ps>+)c{>>!K!OyVG zuLysiONi4I0cY)-t>Db`)YPK7gRa4W5rV5@V=<@L5BKNR`;~osoY63)#2q=*1LJ9% z<~r|RGddE>sPOf)D(ddOp}~$kv#XUjpIG)4Bxi>rs0RfEk|eX|w6HY)>Hlua6eff9;$6)Jfk-Oml6XX%o?PaVh#e8wNrYYbR^hZ|;cI z<2BaYqZaQJifcMY`mK$Cti`u3kL||x<|^yKJ}AmjFB;*|>p3o2&OQL0E}2N!dAL_@ zv>Guy`Gq1aO+KTw{0uh=IG*<(YrMJs+sf;`vK$+$y=4HNpBpvm6S6-?Z$T2EWY+Wi zt^d}clSre{mW%9!%}Pf_O*)a{{8$$3EuNavxzDYCk{ozGsx;`Gs zC~rNQxZJQmS<~Q`HgV)y!{RpCaaz0HTuI5Y9fo_`4knRbi`kuIE~^$_VZ5pJ*QG-c zTvS8L-q}tU7VGTg2|$rwhLexPJ?6;{s;$)1jn*by0b+bQyWwi^Yf2**al9w-nthX27$8q_WGc^e~; zJgld@b@;A8ElGT}-a*2nc&YeON4~ZRwYIGXJvq(Jo%W&iS-R##LDVMojwK7(8+hj; z7BriuKm8A897m=rBZ#jK2h?G`-qp|7rP5to5WefrpSNOjvyvwN!vd%lTpiBWS`^8M zTx%Pjfz<4`3RcaC3~Iy=3`kE}g%3k{$q{09R*iDx839+v%gyn+mn&~*WQ>R*D-Wh4 z6o~i1Ngo8YXxw#D{kx>^9o-H*Xgs>%ExZo%*({rdR9LR{U5BUQ@y3`k|f+*Z&hidYCm>R6@b@&(P3|KwPX}Zv2q%aIMv8uk($C;wX z$8w%87bW9~l{z;AV&7XLFZ0AXSMuBtOD*JWN6X1Yex$`kHwz=wb!X!$HaK!tu_;f9&qOQ3U_l{mcEyHKF5%y>Egb8~3Hb z?;F+ub~_`uGrhob%RJqoWW5BBlK{$;PD|}Sp!fY3hN`(zcx`)sQ!`E=T@e6$lx=(%;N7=iggY z$<||?BUa>Su0}4#{|J&kIQ{v{U~X31ogge@YcT$+?C;H!+*=@xPz4ZFUFWc@rKCHN z&chZv(e0G$o8%7%hfH2X5sPT*bC7Z#!#{3z^MM>^1ojQ4fJo`;CGS>1O9hHPkw9T6 zqU~JwX+v=EO_!&|hozg78r4~XR?kX~;r8lg&j-uiDJ9FnBjfn{UWe)GA-3zMQbJE=Rv z-fN|r)+yE+h^rD#g>WOErwlLMxS<+1AIpCGg#A^-dl8-RYn{>XZ z^xN~Ped692$N7B4l4%+Vcfz6eZ>0YBg__U3m0`x`CB}9C+jdt)^3XH_D{T<@%B#l7xz zujifSpePxhtGAlTtt2170B*emWDA=LWItPXN^Q+-=9;TY<%KkhV&A}?frP!&TxLo6 z4z2U*ki~48#lKEZ9VTRx64HVpSNB@Z60HvRQ|t*^zCMTq24(TGOQic$uRw{g;dT^t zUcqghwfofM^JE*%y{Tuo*32Hk;=yFHhqk-w@uOa3(}tv1tU{Hs{b0 zwp1tl1Ck@_t+IYWiJA5(M>B264*ceVa$R2pRw2=k-`b#Dp-9QAYCv)E&Hx)1LYTjl zBOQyhnkg-Ghvtk#LJ%kWnkS_#UKj3M!X^8=r^saeoAl5O3UJZ|86gw+_b|s6?Ei#H zcb8((id5d6hYAEw-Jq`<4!3C`3!I4uQJ4zlq$dJ8T^m5~wV`ZOjBMWsH^A3$E{N#Y zl1_;Tvx&OZXys$ZSZz)C@I0!(KDEwsU)<-Sdk z(gpi#AR3!&T%evh)swG3Z}owNs}l^L#(;?t4G)toG)#C;bUbBcDo(gy6en6jYHFm3go_|2Xy=={jdH$;Cd zdfBT?X`XuK@?f-Rf9+CMDfO(ox6^XjWk91vS+M9Pdo?3E!y2S;Me}?6=dhTPh!anG z&)9d!M1fN2`<>ABc{iPlf^u;thJHwqn!GejP`wMSmH#mkj_$hB)HC-sYQi8u+Xj1%?J@~2jB zL^IhKGUOI&*I;wxdq4~K+2CoVP)z?bjw>%Y2o3Ydt%v-&=(ooEQuW{YW1Y1MA{9zU z`Rc=*Q&~AoO0tUI`cqQB6Z_68~-Ez{u{| zodAgDbaJ4x_YBxTYE&7C1n$4vxM&f!M(0Xua)7_1Zl&hUK4(yd@EqMnRA^I|M`if} z6t=`pUrRSN$_sFW7oOY|KqmkT_uqrfvO3t4@cwIJ%CY}E(`)EA`U6!{vdT#Z+omQ% ztP6x!Q%lr0lU=05-P^e&iala`3oS`S*j{pp;bQ0u1ZR_pOaqqd6j4?^p$_C zR`o8MkC)e|Fc?zDM#sU&_I1%|)=!iq{r;s9%L zfQjkImeozyP0vqT>h2ZRPER-PEmyn1S_A^tfXqsdO;1M|k`e&Ln=%h&ZN*E)cj| z=?Zz-9#&S@H9$$FdDP_uc}jqQRQ3ZEto`7w=q>3 zd$af$)+9Itd+2ZcuVZ z30Wg_by#JX%-TjP$~O_ATa8-!h`kNB5_Mix@@#VJ-l8UNr)j;g1LVorCV|aw+lW5K z!>W=eCsO&V&R=!Ynof+5G-l0s)npXytG6ST=wg3+FR?Hyug`9xn6cMd5wSn<@yww+ z!#$c-vj!>(+o$9d4OyDK^q)UhgX+hzLt`Hknl&`czE9J)=AcUJm!o=&yU$MLOMFTu z6RC$vdt1k&)?Aa&Zg_Gn6vuhab?ZY)jA!byKz~abcX*U4Lb!de!=NlDU+f1C**C@V znCwuelYl3zG3*Dg`Yc?A`w$yr@DGh97z+3q#yIUbmO@;sh}!lQ4E5{uI`Z|IFEz`K z(h{My;$GKXiv{l@SEo0vmtA+q?rA(8fnQ%W@n$GpK{f;3-yAzq1$>`I+zy$g^l`pD z=V9A&-Dp#)r)ddA|B+$m3Mc0c_2CYjJ&z_`xNzN_lTfX_2T^MM{*dvy)hZ{yEZutE zXKylpDnj4v!_8uWODN~1rtLiVZS7(0z;&eQl_vL;0NN#v;ISK<7K^def9Ux?{LPq^pV`B`YhTm$%#R#VF z-9&4?DE;3<{Ck!pEvTPXE1r$5%W|!pY#O>F1gXX+ct?re5Lh3UW;GTt)L4EZc)Z+7 z+>CpxpVC|W)%}M6YP*qEP^T>!S$=xJKk)A+Ujz$szr@wnyiu&G=ZZZFvTu;W5OE6X z9M2BvghgwkE-~NZZ)xW7CM39SqbB0vewWYt9+!$AP$GbBa$g2>wb;h|+6-pp*w`H) zs+zdYhT24BX5wy;BgdQF?5+|#ArR#Xck~#QR$|HZA#A_uz5p#crZ+Hx62CxB@mduu}J}=ey4VUh}PAm zBK1R#M1$ABUSQTzlj>?yw-s`EqDld#6^FA}{&5P)Q;{P-a_us=>MJeNnptO2R1{<6 zGw*_r-=JfGYl;!wUAnTkVz*6$hDu((Sp4csf#=t0qB_^j_3Rw_fzoA1d$R#o@d~_R zhE8Yz+n>AhPbe>Mr?wvn@oV~#BD7FKAm03y|3%>6!z;{@RDx@zwHDjF@q>5}aCBpC z2pxk3zs+?fvg+x7$BpM5H{oPu-Q_1EW3q6)Fd0uxv&rQoJ$#jli$chy>x#NI)RHN4 zN(k%9pz+4q*kv{RvW~Ax+3Q9lf-K;AQ)Wk`E0D2}2Iv26XMnfedk*psXani!ubh|U z$r7IIrX?mCVn*$3E|{aWNhGcHPqA-2n(0Mtp2hh2QFv6^4a@05DoiZl z?pTfec}a-dl64t1cJsx##dtg&&k#(roA>n#@!hy5 zAsLlMq-f2?#cc!$JRxk-(Mi@wc#fm-h2kW8>VO=3!+a70BR`V@ z4p#GA0#__>>0MdMa9fmEz2W4@z-hSh6{6)-woM87tkJas%XnG$aYAb9g>7+-PL4f; zk6LCXJYm|2nuDMRe}9Z!h;@vF4Ii}-asV~Cj>f`XBHSYTSyUnbgDzxRlxW*nz+a0_ z*64TkGkkfS1n(oC81cQ1hjkwG^x%6Z-mGi!jiiZh(ID46gwFm9*%xWEnw~Yt33w4b zOSb^U5Z~tU+}|22ZAyC~i^(oTXJzQ)`-|?|UgR7R(w_EJmpZA+oTbv{zhT@__%!Bv zLFk|zchol{G1y{kX&Uv0>Q^uX_cs-jFL&YYl!Doknrh6qf}z{Pjg=>~A;nS3(?oGL zq8lv^THsp~xlI0=S2%FDZOwKMB$Zr5qB+av20l;0?U$ySEb8d2dtC0@se7?C>`(q5 zFrFb#`X0*9|Edu1D>Die6B|7B=_fURe^4ixrfE8p%(!LZ@15|Z&Wrqf8ONH+w!zh3 zQo-S_TiS`kj9h|LXB#iQC2WYb=NlzQ#SPN8+q;}0zK>2$> z@f5M%&&pBf{U9~h3foZ$l=lYEbXL|rrj@9q)>>bbhI3L)96cOU(=Ceu{)73MQjOkc zof`5I^p_S#Q@k6yIVYjR%ku{xYdu@TH%;{Ad{<#5*xVK$Wrcrz<72!Q`<}Hei;Q9? z&pPnem&*Hex(SS-rH)$0Ro{-!DhP`T;S379X)QWdpxTM2(Sv&_b;wUo60fr!b%O3@ zv7!P9;>U1I7nM^qrZC z7d4g|`aT&opj+q|40PkZ2n^5^=UhA!DF{GNG!{Ht6X2k=(vO-L%-p#JRa zjk6YaAHt`On=8bNnhQD#pK%f}_+5#OlXB02X<^%h#x3RS_&PNF|d5ggPhxlc&ULnW>7b z&3aIDDe0WmkbC0pV5iG**dpQE0-SfEo~1OBUgJKq-W4*{4#q8Nk_+$zGI#q+{?H0$g-1H??pOKx#~|xqcWA(G zDZWA63w$uj=Em#Cr2|q@fj!}7YCf9+RQhxp)&i~#qiY8^a*+fgq+l)(c5OK*zQL$z zWmdq@_wr{DuB|Bzf8As7Rg^X5((#N;yUBoOm>XQJQdtp&SWWG{)2W}nU-wtgqFYlrAy%JplWs2eUMAjN$Exi2V}vcF2pEPztK|O3=X_Lq_vccg53T=a zAim9^iyW0K4)}_;BBtTI*%SyvIt;{l^a$F2wIb7;WaZLuX>S;=#o)u9oJ=7h?tCCi zT%|R*U;lXJ9=+VagYopz>y@FAK$s%yJ00iL4>9Q|WmQWik)|s>o@IWVD_k51jei=# zS_0LQ4Y-yi19Y1X1nQ-4Ts4cd`woX@phE;TZqC!il1{?ULU~!mwQN&)ScS2VzW66BxEUhd2et8!^}SYfGhhYaicN zcI9j6zI!|`+SRBY$Bc=I%|C$rUQ?_h_k_=s3Zbjr$LmSt2ai`kzXX}d3DfEMEEJWj zwU(ucUcE~+3|^mnFNZnNT|(-$;P%sOKK_> z1@~39E7I^yMf_*yhm2?8-@a=L*yXruH*x;M#1wGcU9Ga)t{rD1pl zAymxs=|~UMKb;Q8GFbLI?OWY)DMGW<$ct&BKiPRF1n$%H+h*&8qJHhw|AeC11}9x1 zN)LgAHlzOU1UuFJpn)z;cKBeviJ9^KgUuZxVPR1)O>wJukc(u zc0X|rlw4K6j}q-E#=dZ&sMggC3iR7gGadNC3NH=M`6==(`FZQ7u`qyKaBgHn73hg; zPL1S$dL1H`Fk5$s?v`NpU7sW;(|UHRHW&7h?4ZnWPWTwnuIB)%~)cis=_qTu~8!f%C<)Qw$l6NC#@{^4q|_~F=no%71#IWum=LahZ0wLvjH zI{^X+&LdG6sw7LHVkA6&*bphVAfdhm3UX^#QP}KSO1lSZmlq5aec}n zTL~&Y_$n2ER{l@R9)aPn#ui2*%>D&hEK(Q+&&OY| zn!l*JY&fVW_42xXEI5?HVFL?H>WJW0L-1cexs;apEX(|L&f$IC$PsO!-sJW_4#^p- zb`JB326#YWG%p1VH>v&l=>IU1`8yO}qUrE&LWCXg`nK!m6bh?{z%H??@FOuEWob`) z!S|ax(qWeax>Nq&_+8p-G;AK3HQkR)IifO(5`=Oh_JdJJhS5lhfwRHWux&~Gpas9| zAea*#`}tPSy$Sp)fNQa<7m1QK*ABgi%=3}TXqTwqo*R&%>F`%J+28&61gUf_h?hApViJo?Gh;04wyino$HOr+`;G%+lU+dpqIZmBp-qcbc+KNY zu|0mMst@h|fS>C(X^yc65RJSz-Osq-+k66Kxc~JqnL7{d%`wfJHX7-n51G6=0_sJ( zgvV*mr7Q;Fe8q>yUDEX^Y!WayMjlZ(Ci5Vkm9Q|iPNBUfi$$02z?`i2@X$C{o zB*^z*i%dllw%G@_8y5Bw1@2vgAT{3iP1Gk96%Gc+5z%V=Cu4yt_Fo_?u3JI5!mY@D zH<}-J-Jja_*bq=xc|^+nk>^(&vV)WPP`_or=#Dy_|vuqG>}QtDhF~e!lK7v!UKQ_LkZ!Wj(YVx%Z9* zT9m?A17Hg4*yQnco-q~AA=mCGva-#j;0<%@fX*|uGm&ANP%uKiu*D@X_c$?{l)M#b z;9Fro9I_^$;NS=8Q7x*mie*xyihy3g!{7UV`-XotRic%#S|O{@NRJOzxTa{^|6e-& z+rCPQ0o_z_L9Bd9c1 zoZGw>eXkgJX+NmD7d3E*3qny`g)LHmW&|6&QWEOu59h5`S}qeu#sAX+*m-X+O-;Lt zMs4AGOKj!{FYuRJPv*c@C{Gh?Pt@Gd&-(Ztx}m3UP3g((7hYWumr+mF`bb7E8riM4 z-yS*5u@yayL_JvM6!f`E%JmY`{R(wZsq5_~ef<{J|8C`YUwPcMQ6)pbe?xg$kim=gr#Ch?Ul#WH0vfoOu?a>yvS_X^L#&sWC2YUk!V(O>&^qjv z=I+@IkYIT?_JN+5FIVb}n{SEERi)ppdAQkx1l)Zk_e-0Cr=Ugnx2I)2{^!p9ou+GQqNf%$VT7iw69WVHzK5_S2VW2Lp5vt#6G$Qh;^0!3}2Vx;FzD9PG z!QOgV=eROPq?tlo9@&+{#uyenYJEU*yyV#j(}{mNeuOT6z?B|sxl@$#wbG?R*W`Ua z(d|nwj8|*|D=u&1c4yx?G`Z?ul@z=UIL~T{NzU+o(NwvoY{4)%Ui+NSz@f@X>z(!? zW;o(^>q@O>QjJjiQ5`iY(cma8q93F1pOu+{rnTv84ad&{{Rhhi)VVDkoo)HW1@z5n zM4~_P0_~4eyUv%X3nkk;dX46upe_*|1x&4^kGE1#(AkXX9AnR%VwQbd?IV`^RFe;{ zsR@YlDfl8nmG%gvarGw}wHp&jNXcJ1J($FMY?BzhmMf{JmwMJq3oadkU*0$MCqcS* z54LLme`hB0aAx^sbZr9sc}5p!mv48VThLayL^Ii>mfkzMt00L#YsB$C9~Z308Vb}2 zf2((U`n_~8v#bcm+Cq!S+V>ejkBI_GkYR)z-iz}s<2=$Xy#r~3HsxcPJ`QV~tU1ly zTo-^%P$@){&U9@xp2zgBq_CCpU8x8Qvj|C%)ff~Qxk`jMcP152wH%jjGH_u`bL#q$ zVS`+)Cu^o+6`PdP`b%064RtH9<3K~0h{inA7GGRljcRV`a_OvWWjt=y9glLMt2vQ6 z5m7>1{0q95aGe7GH9&hhfX3z_Y5GD?kr!-15VyI1Q!!#2aUg7%4Njr1hn-lb%R?Yo7g?Kdqu&7nIozd=9^E ze*_gCO2~d7d3L|SKH2L1b`813w^H)L&&T7P-u?v~K?%CD(TH9Z5y+Yh0Oh*aLeUd~ z>J2$FN9=w(epjjHZ$>yKzfwV8+&jXn_xekf%IwqvsO8+#OHlB?a`#a6PRbsU>krjC zTe^Hfl>GegnL&hsHAry>jfpE8MaB(H(1CiK2;`6GHB!MfvNint`k=k17rqr;-|Sa5 znML(Mc2vZq->~x85n9Zov!5+UVYLqrrC(Th;B$vGDcz67ShFuG7v>={V~)mU?B79% z8=N=6%9)>9*FWJV7`@QzC%<)Zb_^4ue4O1(l@T4lUTL>Y*2~4*JkvSQM59BeH&7$V zg7_nf%C2&T%d%SGf4^?>p^hl^O81O8mXjVR)_58oA2cxVZ_lFzV*eu|xwSF8eS8ws z;0R)B)vM7u;CoMLO^)N&Ioo00N$g_va4#|40w>amr(mGPO&RxsflQb`)L(DP8n4~{@mVSc#=*f$G z`TglJ)fzEzdzAy0V5Pf~s-hQI03Ur+oWAPNsey`?E# z&<7kNy;YOUe)|+f9uzx?&aJ2%^7Sir z;ba~8LF&DasE$P3M=+yp5gvv->aCdDUg6Lh)O6B|=46tIm1k_Q@Au~q>!xKHJ_26t z91OJL4dCv?K17OzfZ)&jzZ^HNK07e* zb1CDF9{CSIeW`c^!P>tV1U&F(YhaqS(P5rM`>R*DnTP+pS5A0qa&Vk14g7S;u#x3rCtC~l= zuTRdj+%}$}Y+#NtnBLu&`mVUf$D?3&s7d*de8JL7;#6dL?W(%?RqFP_bZty;iE+Xa z?1$mY_u|_AYngzvtyM;JyA$ApBaXNB`o@9gBHbE2wEbTzsjU5Fd2EF`p`zz}d;)5q|V%JjCOi(BSUAB5t9P^eZcsfkE}>-;;*)MK*x*4Z)$ z{l2K6i~EfJcF5{bgh+pROTWTM6lGy}s0EXq1h%n&{D#lRoG3UTTw`}^`T;A%39Cp9L( z#fcteIo!0-;a>q7yT0T7B(97vVlL0lY!ITB2*`3v{mMxI2Vpny&?^HR=~ADfNHB>G zduh}0%AbPQ^k63Z&r9#eXm=|XfeSJMfJswH+`GpACWlPe-^T3dF%Zw^?`W6jG}t>f z?wqO~FX;PaNpvhsI@`Ay$TiL;z1Fk`4~MSoZUwy~)CxS%d`u;;6qw$a7|}bahaw#W zVPeXsu%*$6rxR#0Za?8D5G&SHPUbswf)SLE3mi&(nLN+%1yN+qUtCoiR&#PRhv;bQ zrqu6Em!>&g38+t(2wB(e=lU)NAUnur}g^}BeL-Q?3-}?S;5t)X4Tpknh z?TjKWnBlw`vWbFeQQr{wLczlUQ%T07+US0|(=OCOh7FVPOrjT(|TV1ip(E>1-Lf>Z8$ zSu?~<`7J)U7A*XHXCI{D=5~o06&00NTY(*IzJsgR?0$?6%I&4Nm5qPTTS0Bc@5*`WN z`7BPO=7fR&1S$N#IoOXGOP;3sm)Cci_fB`^ONTz5+3kHzvfE?^Vj1EdJND-WUCF;T zt$F`J?2DKk|H#VeG1JNXZpIxoRiPo0aZ^%9C7Q9&3{s@h0FOW^_v`m3@5)oW;s*zf zszz4PM8x{oJ`Y`Vis;lFeI3EQ6Z)scG5k-9W9?T4@}r}PjITmZHRQ_rP< z)d~YU<@Nw$z#hH;9pNfYnzO8tB4D>nXqU&PUI?#yRu++;sag2 zW#7_Yt8hC5plqu-Fz=P28-#z<_(J=8xfnXP8H1?QGhIblFIyuc+*PkFNeV6jzaJ8B zZ-Z0dK90h-Svgnkv)(K!sjGIdD1xTNCZC)R{|NyBtug~%o)XcW)dl2rZ3Inq<4M!2E|+Rh`EcR0#axqh%Wc3HH3+J^dn&5HTO6>u&Q$ z>pT}yi7K-vMO^P!Py!Qwy&;c>DX}5OnFcTy5IXu`$E!Ab1i}4K_^z|+`_DMkGWbkM z3Es%5wfqZ7#KOyjPt390L5H69@ z*YUW-_H>3GuMJhYxDpat(BJB};w-o!>hF#Nn+}-2QOq`Rn4WS%E4M#SJG>sBhz|?? zg2iKTTPcHeX&)UN|F}n0 z6&1Cp$Gou6mqj%hik-OB50bWv&8&~&ug*@w5pAwR9qiBgL_Q~m4hcFEoDrfP>h0W8 z^IyXUn&4%K?H%Cs|e z@`X?p4{6}db@iAw z@FufMla$?Xz7`>2{-SA-+jr)_o3iAr&X`yTgGfgMfKaWaqbJIGXc<~dI66T~X;zs0 zuRB3#3zZ$X39EKStV5^&X2^$0sE=9nJg(~QkGf9rH^-Kv=p-^s_Mexe+#S~&Ux|se zpw@X8MNrqi31lF?d3zIf*KU65@F%eaWw`sLq?i6+w=vm=hwlvv5feDK_~i8UX&v(S zZf0Uw3Y=f*x_y+!2JM#fHxZ@K(H@Zm7fvp}P&>%edXg?2U*v znnYQx#o;)Ujfitgz4t^bo)@j9RYf8Tnp*DqJ@bOJ2F4xL*-%iNka4aj?_Ov*s8M7)iRl z!9(sN!0*Y;SrE+h{r!g!Ky#85pxi5Z+Js!Vo<1JHrFe;b)Z6{0~K@3KGrNmI1Gh@q{~i-Nk}?a=R; zvRl$OHTx8IY}wxeb51GAwdxZKzb53R2cyp=RB8UN;rG&N8p_;U8VRk>uLWi!`{b zfc*mi$?=Uh~tUj_LlnVdx zsJ8>u**mL{l%?G!9c};_Ay-B%7>-2o)h3WjylSEsB4r}A*E=d_cmQ%Q=ae!8&6}K& z2cB6Yfi^Kui9b-MvG=^On%kPINy4-JpCc+iV1*gsdYDqJ-AjLD&{qfUR;dD8-Y%! z+lHm#XH(y;PLS3ow$BVG9|l)X!aCs_Cq@mB7u4h2yl(4HR0g4hMLjZ=BEp2?y~`DE zp6caQ(Y58yA93%uiB`6iel|bF>0-)z`_B4=A7bn%vBYNh9oH*V!;_59+bmJ|)GxIR+TjmF(Q6X9nS<;1-}#f1-zMh}ch#JJ6iqs- zy=@I+{o>na_-v0Pg9WfdM$4<8>_!OPSM?edWG0!kqCm=>`jjit4rJqumX-H_umGsP z_-A5*u;5)eJRsKQzKZ4l%$wJ=86DiP$jqSU<3S<$^~R#p(0OQhWdn#LluMbME`2dVr zKa*AlAA+#Q1lkVvZE!yjSy@v$%)i0dpEPk_q}%HJ7c|A~P>9aHJ-ke7iW)xVQ+cqg zDLk0N)-39+R0mq}y&hMhgwIUVtR>f~i)!er$p~Zrc=EJF#9xJnkMvuK$J^QToL|!8 z;C=MH2=tfqgdvcZpHm3je&B-%++g@G9RXz82cJ<QTZH%aE_$BHU75X^uRDcyIcl}6w2H*HO}*yWM>p_x-^g%Jg>c1%s;y#y&bZg& zJvk#c*9(lT&kKw$7b9KIrZ4RX(6$sGowB>3ET>>ZKUHfZzH#hH5k@8Zm~z_zvI!o5 zYw5~wfm3M#*?6tTVTPjT8L)$c99KMho;CgC*`qux=Xk=4;ym}(o5b6%I%#KxKloSd z${HX4TCeH=sSl4`7mvr<9XnC@zyeUfgPN3EQb0A`YNb$} z#Jp~gU9EVL_9gfkdnZ(iB&FapkTOu&4Krcw7zS=e1V932$YW1TY7_lUbscp?*wN)n zS6hdQ{cb&Uj*{-Yfi{8)WaWk`}LEv>kNe17KIkz-1 zy4+=SZuL@-`pKCT8p+WGYGqiMZmx5t(|MbS^igR&ov4y(TA^dPAKU(QN(@2Id)XBq zAvM>1%IHG7h{fFexP7n-eVn~P>g@X^X?^IOaf#$%N4o!~rk?T3J-(oV45c3!gI90O zpP#6IR*u#v&HZ}4YStahHbsIn!GsfeTQ0vC^R#_(ns80lw-7!u)bkc!dj_7cmBdHg zEKnN5Z?k}N#0jNq(pLAgY{MX7j3^XQhT0&a<9Omp^}F~`?--#=bDSRK1sJa zS=KDdCsC;K2&Qv36r9*5b#>aZP200(0{ zt^FO$`l|PpL3BlE;M{k@M>48s;SEIGHW-W;vW6)2Bze&=&E_yyLK^K?N7Dl4)I1Gn z?^C`7x}!t*j*mxC0fXYb13oC2zS=-Jh8CfK*WY)MrO%KBi%<#UFg?JuSz;C`YDDm# z2P3&UUv83B#2oI<9zxe*jIs=;%W9n;UvJ8fAo}>{ge0E>S90|5<>nOKkAVLWUQnZR zbydy3FzgYpJEv?B>9uo0S4JJb!(=ZX`9w#=B9EZFMSq2P{{14#2Tc>g`Qs2aM`W;f z9;WgkPz|8kK$HMRgtjeqm>~w>_0KYvF+M#9WTS;z-)>&ta`dDOC>TEs&n2ZFxM&vb zi=ms(TQHc3g8!WxEbvqG)+6o)vb^J}#0*oEf_DQRBxaZpTjf!Z-UO z76n^nq<{)LA!Dd`sMI3hGGrs8MUA@O7u%C2p4#p?Q2m6-Z?$Pqa{G(DC5HdNl8!) zevzth{fwa#=U2mVX{N~#0g?DPl*?^{3R zJk(p23S4Z1Bg4k^H+td90c1KEVOXyoT3@op4Nrlr@)g*W*DpSkfxG=Dts8E@vWcF> z0-<=gh{DVOmkH@-q;=Ny$-9`J*%Ia0V0|{WY-RmeSU(|>6Ph_YRTnF&V~OPt9#L=hLItZS-UVS^LpGN&MY-t)@QqoP)OOhgz5xaqzVl z^5^6T>w3K+ngs;TUHS2l*C+pA*30}O`0sZ69*?6YQCkB*!qmK*3_v?9eEx3RX>s#(# zT*K=|+o*jI1}+}bR*$1$IF;!bSfp_4QO}yruZ>|s3uV1E9l94d)zX5yb(m-E9!o!k zRb{XYD<^Tvnw=gHWo(V7x4&J1Z+p%iU5Gz^SLPT9>64?Yv7@Jk3**XjX_wE=HBTKR`AqkELZFTo|im z(o`+Os3Y|CQ)T1uEh+C0tI42IG3GC!)oMEraA@kSFuJnwTTPX$sghDjz ziZZn|ndML^y-k*@-&H3bl_DeX-T$YTFdt5nN{R=H#vi?GW}eX*3E=UsONTs;0YOgJ z!?0LdwQXj`O{hCUqL)H-G2|(GCrEmZHA;<^WEA68zscHvfeOkcqLeIrIw_l>=#x#f zzws=b2C0gEn1byiCC%uHr`3PqdW4chQS~;Ok*q}o2d$`b~oF zo@qIg9u7#rH?*#(UOfl6qM5e)<6Gb%4hA zuQe)>Hc=|~?P6iZs;G%cNpF+AOu9>WXxoQueKwwC=Le&JEjR;e@O;TEuR$0yg)DNr z-<-c^D@x116nLi&Lpj0f>}{(qy(uNU%@fDl#?c@jNvLtKS8o>b{Mf2i6Ujoj9hp_? zzgm%XppFv>V0oM+gp^*Lzc2g?Lig+T*B6T2@R{$f5ymEfccb|b@h3(aBdoY}yZ!h4 zQ2_=^$xll1n3s)hZQ=fW*4wU` z*U#dk36g#H{Qjz!YGlYNf$wME>!8&f@z#^O)ZqFW(%7u%SP;T$XMYQ!5CRZCfcYs8 z*Z|OSFir7ct8^w>-^%v6nON{r|Os$fFK$6<4&X> zEbMB}rB)eY^cYA?zYjyTj>f@-WJI!|LajsOg7V^k{z z*3S*Ooa~4v|wP8rVRuv2BYiENCBSi>UPxXfs|?zQ%}X` zTH57I7$6!<BDjn)T3=x*_ zm{-1ZO4**Ml73D*ckgy+%CR7!cX>HhJ^!_DwAT=@qR5})?f;l^&2J+BafuIh@$sa5 zh;@*D#xqP|aR4DL2@|44Z?3NR!lR;W&8@8VXDW?4t%AiQ zMhd7g7@x|$t*)yj1aA+g?FVoFG=VL*(DK5A> z_xS+4(oy}5?fq`sl1XV9FYfcE)(f+Lw{9$?fm%AR@}qY&32;eh{Lj^jVWnCr>IT6! z5PET56s^S3+TPxC0sECUdlz)Q7EhNvEFzj&x1&X&LZ6$93XK~^W@fwya;|cw<;%UP z64f&i-?1NGHJSTA1pQ!;6|btUR?srztQu+$#5#m6HJPbFeDD6a9?o~0j|()_Rhx}m zL`6pOWr%v55MW_pMSf=8S=>7V9xh6LG33Fo{9}N!4~?lBX_h}^$s|Bfy5Cvu`itq{ z|7069L>I+!svN@SB>ik8CioVUv9n+C#MhyyBmT+fsYy3)0 z!>ZkE6qW2&wpaoFaxv&irNlPpJ9Q`*HT&0}pLoHiXy6++i|O6zNUQjN3W2rdoMAUR zEcIKbC18Lga{2A)Iv$SamniwdGj~ zFz>NO!}{?sn+6bJuUTkT8+573O~i1zR9{Lez@kVsPt|g!{H|EH-nPPA`PaO-Az9^N zm2vN)n3!06bZAgeT)ccxi0M z4;_KK;>vAQRbwoEJ8nMp0WNN~nktT$tjf#Fle1q^BBB+qk&~0-sjI6~I+`p}GfxwC zSw;fp=7TnS7{4fAy}N`$bgNB=x&{)s5`@6WW?mEYiQ9NKjc{siL&?P7zkiF0iY{(k zLctZ%>opb=OlQESkaDXDo3HmorWX|z$(ScOP?qt=-TxD@KM>s#{EXNPu#*S>rD(k*t& zW_d&FkjjSEa++|#tpmiN8)jOohxrZ?&cZM+{_6U?w>ZK#ZLX)Q>rIZ)#Lu?`$u;

    DUJx13NuF$NJ$R z^;oe+$@`#OA=9%hOfb$r#OS~Wp7WwNI|dB@{Q1+uy>DUR&!6|~fbw?W)9U}j)>lVG z`E}tE0}LSD-Q6M~Akqp*cQ+ypO2?4Wr8J7PbcY}?v~-EIboY=03~*n5-|zeGT6f() zSk6M$yyrdV?7g4o+57Bse0jL=wF<}vzVRd!78X_nmkg~oa^ZI^6+T&SaF}UfJmFQV zZv3!2$-!sZTHSZ2>5qW@YMO}d0?n)>rKj74kP>!^z8cPdmB39P=|@RHF`)5X-+$yO z8#s2U#|`X87k!fULGGI?@@nnLY6RWV^Y>e^s3^AL8fvlK9|k_LG)zo0u9j7`x1=p= zC9S#yrmP17R6w2hkqZ3DOXM_r{}eHj=D1iA#;L9j7e8uS8d0MYU(rGBlcCa2%8!1# z%Jc(!C`aS7u9`5=Y>X4?{?N3tpu!EGmO2b^c|376VlNI&2w$}hykeTkGScU8nr^Hx z)37-EXtN}Zcl>-!$6K>ytZ!7Z{ry$oRng78??TVivl$upYm)@Yb0A}Y_p?J_N9kXI z{KraGb-seUlUdiWW0O zq*aH5F2*qL3DbM8l8p*>TYb(-KYLZ}z>L%vFa!isYhwg}ENq>pATFJx;}zoiOjEyr z_fxIw)zM$0`>t^8N=pVY9r!|<-&Oza@9!e?>9>bX%S-jOwV#sM_(Nuup4mR!-^p$d zXK3NgumiU)&#MeBvVh|$hBn<0>Vr>5?QiKTlgwSycun&9f5Owu0%5F3DjA*RR$?~y zpJ=Dh+v4*%m?*}6PJ-fSXlT}<@U<8WaLVD>S8+X#s@R>@?07(U(~P8hEQ}5Km*j-L z{I#oP+{;1=&`ujRADZx7Dd`m#eY;45U#!{Pn@^khsk3D`Tt@^pnogbw%i0Xzr*K?m zpDgU{>b&x~$S8WH3s=4q7rHp0Aw={9BHk{4xwYIY$7qgwe!aemb9Fqg+a#U8C2e&1 z^+iU5ld)s@#N6kIgGy70L)Sfcr+rnvY0A-r*Gb&9vIuYxqb#=`2+Hi@y>45t{+Gzu zdb^ENfCr$PId)WBqSaLp7G3AxPhF1(&CF1erKP2}>P=CK&fgy`Hk(dNOr!$y8yIF# z^R7&{qEvCN3M}ms(-PT;0SY7dk$F5<_q`NspyNc>7fV4T6VStLNDym}eP3$GGA_ZU zmR;|IfY)5?&s6c82z5UZbYz+9G^?+OEIgP$xSU&By64G89h<2#J7%#xw4LGQLdd5Z z(+TDkrk7Al@n_zY8#Prj&MS%LnDl7z@l|<;K$EY<-){|5m0AT}{q^$r{rh)ZG2gu9 zkNhGVY|CpYD?tQL`CEapZlI!OUcIB^WvHDj%GY=xsrCKzbfxzVaQ=9C>?QRie7qg% zpclS6jx4-YGOXxLN85#Nx75-l>>KXs&jP*ICv64`M$@mhRsL|$EwNaB{e>+@KDn7~**XTsK^+n9kt$ikj|a!3@JtC?*jrD33;_5jarb&Gagc zvalStoC{utWvJss&F?2dS(k!#zEY7$gXldt5&>Cqh*JozpJEi`m_dNVpc&um2Dk6DM$UcJ-~)Nx$s}rh(WKpw;wp`SsA#&qRiQJZSJK z2%PVJMOWO4UG30us5WmOtEd7sBy(+^ZG8+7x)%K$8IR1$I{t-y!uvs21|>WkAUVpY znIqS2c5YOkb0Dm9xckXA?AgH1t80{1CC9)^d2UB$+n<|nW6J|R2-upsmDpYzG7-YyOG8p~dkIQg#xA;H4yT&_~SVp57> zPyqn}1#1^6BbkgMu#X^regm&f^(UR+h=^D2x(gU#)2SeZT_M6-)3Jd|X&SgPMGcL( zXYA-Hn@|$+v_O==+76o1<|uv2N7{ z`R7=u^k7dZ@o%(VX%))>8i(-@&xSGYHPMd`j@wU`Y6A_JP+GnFY51)GQI2S~kZWVS zNhF{nF$wu4qLo?QW9j8Xy4Lm8^W_Gnm}gg<*#wP^mzY3T1nyAUm#)vAK27B@IJ;_} zrfJ!_dD&XDKmPr)B@B9Pu>DvrjF|g$8Gz1-*yc^X-G2Mzs2eL17_vNE87;c{Bw^Aa z0*iRn=Epf>34J=fuEp4HG66$$=~yAJR0VI}@cuigIR_XFR>Y(b>m3rFJb7kc74z$Y z{9bANq5c*QTTdBMKmrwO1tV8CK4U(KF>?%R@B3ciVQ=;26Bwc>a$ZrE`dChe zjz^0?T0J)MU;3fJAp9r9Wdj*8!1isiXr^;H@OI?$7X6Rd@M9SPt!2w!@ic$H(LY;S z+8Oqv4zSv7Fd*;fdK~R<+Hz9yo}qV}Ikj@0kUwGz{l`_Vm;{(`8DD~FD{(&_LdBbk z&1uWTLQYBP(*V*5hPe8cZm~y?`COBeI#Gcp(>06>Pq_Ip1F!oFLb(Zo^a@l0MZTVY zKKTe8FSV~y)7|!U^-OWoFt|Eymj20SRr^Y!Kag+l?s?{9@Uwhv%R||LfL>&9eqx zBi>v?oa4x-&(NO+RT^iaDwfac8?VEm5GP{eBDJIsIwnl*}h{XdwxrA!Dl~;jyo5E(fKB zhK7funQQQ{JX1g_n&K)ul(n`lsC{{p!Fh;cSZ{|650_&C8RJZR{*!=}{Pl$&X&`(R z0}KYM&#Ri-GMaDYx%*S9UF5(Go19hVKAwz-EF;N?Zgvx6*t&BRQjp#w9byB{Q z?dC-+$>k`wt}^f*WK~DXqSY(8Ev?Pl3LLEJw8A`%#oR$??SW3g=db8D2f( z@9xq+rh8~#_)6&AbvXdw4Hx*S%U`oOM zsjN+QugM@5R&@k2K0G)eJh>(g*yty~3z^?3@k5>23Cn0x6P@?4;S%$Nbg^2%C6wkGc zwk)?0Q6BEygST#pP9=?7-gOjfP`#Cm{L#Px^X}%t@1v{ANAr^QV!=-IR?wW;!7@Pj z)IpZI;IB$VqSE68j3}T#Z44dmyOV{{OG`@x;J8?hZd_!oXwJm`%xmTBulh9YjJ6pD zgPZP{$WK~h#bTe%Xj`D()9fA}9|uWw7i$(Oxh(k|x8V=&Y4ME8)r0}`xX^L?ksT8w zN0lC;zFBOvg zLO6@cZbz3{kQ6V`{bYdkfb@K1fSsw^mz#@y5lUf4a^!6XQ0~Mn>B)7$6b5pxyD`cH zz-N3g?k5-5T8UBPBG7&&XXbq?C$!a~G9-#)qMh@;7hAWITiRW?N_$weJoR=a2GTee zi(I@3F7x#zGUnzv`J9M9-y2pP6ny-%f7o+L0{trLe^Ngl%LQOm8Nh<`{(O5Y!i@$T zz#34*lsTKP?B>6nX~i54K0SG0##f1d{R2yHg^FK5K;@;!A~wv?`{Rd?R8Oa1?VUnjkas$sZq5m?-7O;FIhVEw+)mLQFsZC(S%LzKWiyZ-|88eP$iU3{@(1< zW-;YnV(v1dOz7*tI*%e2G{O2?q>_a{*hsX>*C1{8RXR=i^CsHi_$#`A4>4QAxc6Ja ztd&|F$^&g2ye)62@dQKWp1CN7LJOFDqq|O4yHieF_NOb9z_DhO?1v0sxiyxJK{k-h zFrlb+IMiE}gNKU!rw1T)4tgdlMw<~n>pJ-R(L1VzE@aRFM9xu`TpNpNXW5rasLObu z*)>$24Nadb8D1(p(66shk5`^6OV)^?{WHjIMPUBc1obX%E^5#RY(5DGtEL$IViX;{ zc|yiurz$Wh#_=;F=$XwVAvekP_ho@P+7oPCn=L+?2wWOXTanMCF{C`2GKRzB+P3SO zMSPul+(_u@HQz8H^86JoyaL#n=E8?@#TaqQR_d+9L@yMaijn9@*0e?tEO*6pHur=b zMWOTR5dUnB85szXH*3xt^Ne`ol`0|0H*??JTa$hX6F7%-R@LoALj(~c3d!YO6J%a+ zL%pcl4-LDWm3>n_!ns$J{)b*&XPw!OY^-Y8{zTu*&>Ckf;91|#7ymio8%&rFY&^oc zKdtIK>_9uZuj1?blx1n7F1g_)DYEAjaN3)eN(9u+# zk@&XJSm`XguQHlSw?n`XO!{@3{ooHJ{3vflhRy5q9nFWQ11hl~6YtMPmLU%&1i^Zg zw#*+(NXccqN!V?73E_o8>NUb3%Ta*udi908*07_&=k7Aosj{qbC6GCwH+1j>^7{gK zv=Vj+>J^`UIDu zd7uM;JrpN^-}QP-idr*B3*%Y!#cIq;B_5*MMsxmRFxgS)&>Qvy4rqgkQ-acP5h3y! zn<_1nl0-W?adAP-cHK$X2$lytqSmA|QUfXV%PMfl09~{>f3P_rkZ_}PDNfdjsahu4 z^>Cgl*1&^(na*;=x~Ywg-kTr`gtx}`kD$oL71|10z{{cx7gPVy(AO$}UAoo=Z52D@ z%)vwy=Gn{oHtgb)UG*6oY3LiID*bJISQOZOiPqa7#G8=cjsma-;@;f0m6L1HcWOY7 zlO3&@jh{R1DrKD>ea}kNK9ip8sM2fij2pP&y)-QHKg&lrPlvcLVSt@@zou#51vVb+ zoCxfY=eaxnTO9CiLIGwzB7FVa*Y4ar_fNPWp<0z;^fu3eOeB5K+B6P3WcN#fy#bYc z*OJw#$z}XQQx4p^e*AovAxdOkR{{$&b++EV418LQRdbw>5>Z@5-!%31Kj8H*J<4~R z!DPj~@m$&B9ptFMq{4Br&X2Xh1HY5#E5%Oqgnqx_-V03|xLt=2x>)o8XIN-yX{!Vl z1S5}Lnd^8iw+HC3*OBGUc9&;BH@-#%4bnZgC6%vq6TB+`p^%g z9}w?PsdP{j2P0XAK(&$d{9Lr~UMZ3=dC@m1zh)lH!yfBqU$EhT`6scZQ%nuMF;k2HXlGuD8DpUiY(k0XRrW&G_{B=uuAj!lETJpQ*ny zhoA@MQgj44+fBQz@3p1IQ>l>@mGO^gjZOuzg{Ab*_s=k5*f^ai+@q6jtfYAhP0*wbYfJEv1@G?ntDv0Q zc{0vGNm>C0vbPwxL#wZ*IF9us&5^FSn7Z==WkfqMeHJDsw{GWYORC_5!)Uw`DG8W2+xQ2?Zo?~!z|uq zKD+5%LknbdJYb=Trb|$nAhis&J3L`Uk2Rc1ZPzQ}W;ShMSx~i#rKbN+wU$SeBcwtM zzf8=z%ZPt(Sx2mYfWlJsdLWsipAm8RLWy}B$<4CHX0V;eJGK)w5HF68dT*nyTU}ZK z>gx4PzR*cNA(PHn2Rc!3MN$k~dolFsP_ObC;yoj*^S}%vl!%Rt>=!;G>uh<-lpI7a zZBS!Q`IX9AT&lggGy@8Hf=T^pn@8F}LL_-S6^UJ1Go;W?I&WC1F!ZU>gsm)Q;KV#C zKA7`(jFQfVk|>fjQaJ3{ib$DiED9TCa*y4rGFq z^xwcP4j0HyVn7{yLRe_`np;)rZm|YugN%NbNuu+3gGah-XKB+?)tU2??Gwuz``olX z9cC?@LH@Jv2N5jbH%PO@f{-?WGrdZ_45)Rmtmm_IMdzqX3f2vw_-*GWH*aD(46Bx; zcQ2x_Jfo{N*BpNCrMdc&RA+YP9Lib^_p=@E+&+BBb#$x6CU7|?r~79Q?1ZDBn|?6l zdp67i29!IfJarB&2T-+;AeZP*C*2_06+nNub&t(~0Dh9K6hahMxB&7ozZ% z4Z{6w5vr`|Ra&(Moa}X1f(NlcWm8^mDJ|eq7oB7YnFWR(IV|hXvz=4SZnCo6pnpe~ zOsV)T%!v4U9=8V6Z4G@Ro*+G`7t{Xt{9y&D|4?Z|DIH%(WmCG30eZ~YYs{&&!Ud6j z7qV5ofYXLv=!qUTeni^E_X&v&@z}I<3{3+1KLP@0f|xHC{WScBF}2EE22KC+FFx>`{D&!(-H_eXkh4RV-@g3~ZcFZ2Y~l`^$);7b)_ItaRX=Lm|HqR)7icgH%m;_rPwna5$yc~2T8a${5_0ja6} zN)gzp@zpe9$0N#=uB4yxUB3O>&-+n%TcK-YR(T@LnSbwpmy>rdE5Pri)Q+0Gndrm@ z8P#sKU2aZ;M(I#GCms+R!z+kvxy1w^{$Q0OvA$x*rd}CyL!*twfG0fqngVmQDLtS> z?8cB}CKYgc>26$3+9qOzL$j})(Fdl}GlPx8pkIG-IrA8^ux%yz0IGhK8QOksTLJ3+ zGj-5|hg9Gf%Bv&x56urRFGo?iqsy?nWslol>){i~b%umQ&RU6F68c>=^*YC9nk&AE zWd-ubgnq|pe#g<47`@TNNw}PC_uG!-we;2Df9E`p&Wy>t-a7jn+hp8b4tsS?QHSu6 z9=V^HKZP}un&Ml0=}!-Q(RA`DrO?+i+yUJ-^bUipcg>+3PE}tHKi6Z5$xHEw)A2Et zfa!JewH9#RTWZqcQyHtr_U zw`}3do3V&HF-(l{=J(q|#yB8Cw$t01d0A*&Zl+9c@f+fuaVyNWfEvpU#|+2H6G$^5 zWL5d27~C)3>?X+jp7677NWT-(z}em^4JJ_P5`Zf?Oh`bXh^X*QJ7w|jmc!%8$&|8z zC~DyMz4+)59KugZ96I3)LbGTc|D09eZG0!G`BE+j+#eql0zprr`4R0$>ttOZezi;$ zdCwCbF5f8DVu*foBWCkSB}VLIDp}3mRZlmsu~B#TFVo3Y8$B1-F_+zbZt>v+Oiqdx zGZD^}P}X&rUchtjY+82I%Kf?`G)w&K2)@}xBr2}aYbJq_@4LQEUbmls)g+DUK62Sk zDZ3~Uy&iAEE;c~uu>F0BYpWvj&&!|Dc<7BhUHb@5>?mjmnB#t*ljnYL=(J{{mwnN4 zqq;R#dCJZFoDP1wClmI8SFY)_-6UjZ2c6z-KUnPmHP)Q8K_zzd^LD?P#Ik0zww0 zO#!}1Ha{AKWXwqm7+UqWIEHHzLgr5!EPNeT;;*^ig?ph%)%)VMrp`7v=w%CmAdE_g zhlM7Wk!q74WovgpE;^$l5VP;-dHp)F#`BcBTI{@fs}ATqLAkr>s-L<}04C9Oj4pop zH?hF$86ekpMI-j1qe0q_Ec@4U1$x;$X)XNo7=etUatIx~#|#nDiEPhQER>T9(UP7Z zlQ%y{>TVba@{7_3ymh zxdL?gIwocemrn1TbelIGe*61sFFR|xq#^xh^@+cGbjy*#>m}i{g*EK;@1$+EKJnB! zOM87J4J}N4q{|3TMGbwQ(FqOv7FD4bQffh*>ef^u&zi?R5-#%%%-dKCcIZ ziE#1~P3`Q8UqrT3(BDgvU@8rCmNMSgYCzdK~Eqr1Ib&2))yNuwt54zN zR8$TqX6$w$g^EwSC7^G6&4~S1D?g%m^9`seEC2o_JU)q@7e5se8v6A_^+~H1BR@Ys z@{36gM6YmXv^>p`usWTHvoX28i@x@sG+hSgIo}4@p^2LqbGbGtY?=mvO=$xb`c0ct+hDjg5 z6!C*KQJC+QJ_tUcep-H!lLTB#&3CSsHixuTS0ZU_C)0)Jhq_7!RkS>fZ4@`At4q|NM-TrDT?$ zRcYjO>vPwkBZ{cw)rqOc&t|hS55XpDNm@}2@19&%EzWaicxXx6+N-!mSp|}1Q@HE| zkwkWnna|&pPgG=4&`(wzp33Z*A+POmNbxuvwKHbp2H-tJY^wVCXz0<*>`OTvsClZf zq8d<95*-4_#4%~U{lr+>#eND*Q+M_Sv((1*X&#*`P>itQ7Ri_pMFN2$EnrkKU%5Bp zF(y!`CQ`w!fGip*P@z>Bmx{Ndao1WqkQ0t82NSU%(hAARjPb%QH~HC!e3SJ6Ur)Hw zhmoP_oG1pyIt9};VlXEOTD}MzT96FFFOOT}qs5-+O*))!0BUVP7c8$4;llfQ{loLO zEBX)jw=R61j^*$eGiT|^wwVU|KZ7K18CU{T(bo8)kw$X!W{vPT11Ew8Ru*&YW#k=l zvDJMB7>e)8t@ju}@d{$3MtXd*Ka7TBDtghh+4 z@nz36efIsO$2Vm!MM-&>>J8@$${Ie~9=mt|sQC>diXEnpAFyxrfzMDu zPEL+o+PWDV{+bP_mb>9;$Bo*s4^ffBA@=M{dtUMsu!*jyZSZe0xGtGgUNll z``{NbEk=~QXlRW_QVXuo*YH!Ffsp~-hvmp6jQBWZ2#YJ>M(tE8Dn;Y{ zKSY13ny|JX>%Ea13zT=;Od!xh*xZHIvB=#$*<~W`PIVMoD)-Z7)-M zK|OMHY&k4h@SS33Z+Dx=q~`KXf}~k)o8CK){;`MzM*CjMoHx-%)i@G*TFPaH1I)dL zW`^5QT=z;25>vbciOk5^aIOJ#n{m=8=+mH4oit!-Sya~e^u*O#?$|%WV+wRD3^#$> z2*tHxGid~EhpEoX6|%yBq9+k4Z1igRNF<}I*i+pn78VxhK&|P8+^Y9ntxazEVJQFF zF`1b^4Bg3HAC_T;sOY!M^EV4|q?>(?LnkRg-IpEpD|ES<#`_6bm;ajn0tOl(#I1xn zH&6Z}i}vtMj1C6p&3!xj+yyy{am?|<JbQO+-X4!|2CEcMD|W=sB2kzh$~8Yk~oKnmJv%OkY_p z9=u}-L^n&wq>l_Vx@?`?U#f%!AzF<`o@1w(kUzIjDEWhgRR`rU+JTKNbD_q@s?@5Q zU@pA1vFcXt_dl8<*jHq_y*!wBdvZtO(D*SL`)79OlHGShUd8WK5p+aNI6e{yKy)xB zq5NF%xF0w^O~q@2`|IFbDVW%H#QEoc{`~nVy;imklws>$E|A#->ucO3Q!QYC&@VB3 zS1=BP2Nvj+8j<|n-cJl7hnu~9yFC>}#Ma)m?s>GhiNikCH5ulj69onC@vIBwlcp}OsCX%j(nVgK)h|1?eCkOUazn^`f6C_n-px%hyoPf9 z%WMs2F+65y1+9TqyLDt=bKv84!n1cz#w@I{6wsF=Zd~-SNdDQ=mW1>$J*9mGU;#Qb z>z*>v$HV=+mm68Xwp{qM-h69o;-ZAtyO~{QOEiud5itgkJ;hB7)@vHJNJWH5?;8bjO>&nZGrlnEz>#m6)Zs_vS0jhj*vL zXnZgvLP*(?Df9i{!AyeKRuEDYlv=8Yw}(w?&Befz`92z&mVEFA-~dTZ{{F4g6Zx-b z7#MOGuv*f|apV>^04B>~&dhK0SZ9e!+pcR@67&f$1s@P&P?SdoV}pLI@!@(OY|PEr^67uX z^iUq+Q{MJ*grB9Q!h5XyKECTC*AZ{?OL&9=>b ze^?RlN~<(BvY1?=p?WB9_WIR#^Vb(Ami(p1k%MD$&vNMmU=^&@AaurlC6u(N5WJ3`F`IKfERbK>Kb?G>7x?#(>cE}H}vcQ~= za0?l5V!$fv#sDu7Txe^fAf*lSTB@H=!9ALr2Vp!(b&iFYFKox8R^fC$Ktvoujw|-b z_DRXe1f9sOY?-z4Cw*vwhstE>@1reyt8dceogtORlkjD?^M58+0!wtnc(j|xA?GD#SXsVZJQP3~uMXJ_v zz!Xvhe|HXN0w%)s%MN?WW>+FoO$5nQIs0?@lM z)xW+_tKL7ScTNk{ExP>`WsTdawC~hseseW8L-uzn+tB6wL@w{V?T$%r(FEB(pg2ei z>4_wGYiY%lZ*0hQ_s@(u1Z|qbTpYa6z4n$wRww6(QkyDGs^=PEYA>|}V}@zlFkX}_ zkF%lmT4?kv*H2li;OG0bC&UPd2nY?8Z?2^#C&4tfM~1*g)<51Im&lG}V&tJwd=Kw2 zQ+3mNOHH%_7^<!`FF@t&+y@YIeKfJnPSXMhB7@+dQl|S$l-wrpr^eo=KJ>Sx!QEA)JvUfaFJb}TBL2GvE_$fd ziE-d;`qPf?@+3PzbInidQpoHd_whF%Hk5-hYIt@h{%)Zl;&BiEvY6?Fj4= zcE^5iAMM2&1zmH?uOkixd~$S+DyO&-Aw_j#5m2AxEq02v{qP+A9bJ~;$Fr0Et! zr;bqJ^65gNrIMDX0$)C7p?|GKk0KYOj6#jTNlk`xeTnX7X&t-0!DWPmvY+ZT#z?hs z@docjL)S))smGQ}Z?OEx?dzS^DVvC1U3vpX<8bPSiLC@r{hE?{zcCT8E>gu9yVUCM z?0&t7sds|Zm|72~^4%}pJ-MgxBO@lZ^Y#^qy1a0p*r%J7TzXk;68({NOhA?uSg{QA z@2bxMpU3wqr-Taj7^`VT#FV{JsQpif1Npn?6xXUw%C+}ib3{WopEm}v4J&8+KS|Kw zM9XAV2GE`y*!4sty~ix7d}=!`ar@u+*bxqondpQi>gFQR(s-+O*vE<{L5*e}OqJEf za&jKV1!_`|W$Bh(+G&52yzn?yU_R_w=OlvU=QDb2t5Qs?P27n$U}2pKb!<2FFLv!| zsl1)p0FDYy0k0Kf)r^XALN`Pvk%qF@( z1oTmkp{$d!^0ea|ln0#JrlDG47ETmYsj0wSgaKF5Tghq^*r1`Mg!KbJ=tK8JW|;}M zbN0ftk0)Ho=Kx4WhX69}Jvu<>3WWfQtz=$ekU@~x2=|M*?m4jdwBpH;JUvdPA4&mo z?u?>Givg}?{9d`4_~pRykj>?#lcrXcXoj(y27%U?1|+tn#ZW_EoAvldbkB0@qOlN! z@3zw*BSS0zBkspc#Z^vITtFsdd}@+2-uFzYDinG<4lMuOPqYu-{*-2&eneZiq!jF5PbiQd-#-+Hl9M^5ASZx4EO-I9DV<(+{ur-i{MC!%0rh<4 z@znrdkDT_9%qo!RJ1ihPzRp0xP}EaIq)bx&4~M?iLc9PCtiI z5^&vDB36wOikp)9u+tEi9fN(W2`@;|97H{(+%-c6E-*BV%AF3C&4@lKdn7Qxnp!}+ z{ywZ7M3Cn{PJl!IN^n+{mZ#2HJaUlk3@M}nAmkb>l>(0z|k7`9&CO- z^;N*lE&_gaJX|zv=`=BY4i6o zCcKUzed5g!m-^&5*V6h3y2?7q1@!feuDYh8KIdqgQy&6$89O$hIu_P{0*n)rTZl^# zWi1+N0u;a^&5CGi%Va#U6*|_8wO}37ceUC3LXQY(uLrJ`N?M@fO0Dl>lZ!(1uBY*) zPn-WLf+Exj^>wa%KHgH${j2U&cewZd!H^R?-_C**|&T3h;jOBDCm zKl8qL>F1*NtohwK`Xd`!HqwTXEwuPte7P=aD3buJ-|h+~+Y+3aX;{-7zR4yYk@*hT zkC^-0*AUVF)&eZ%^O=55A+6U*e`+gr22dhncPYoO(2W^v)QI>P9~k$r`EJ*{k?imn zwL>EV6SZEYDU-SHtI`Cwc;cm!u2-@vaD;>!qK_1qPYHij+&nKnT5U6;VrJ{5@;aJ$ zfJF-#`49}58Y@qSL_QBk}nqc7Aa+V%n`a`p&TRxCb zh1{f9y4YENaXQxLA_<%M)rS5g=5wzCxlpz8%Ei#zztHTuok;*%mk{PDQxS&Kq3CP?Ox*AyTSCru&C)!oj|K{d_zkr0$I2BN>i1}?J0`*QI ziV0y43sUvLQsUrq^gbgboanfg+IziXTa!<~-^DOaqX$!qL#)d{4dbQ;=`3 z6*iyB=yjd5>AfAL;qyJs2zOoAVg2FqeA-=6%Id9)#R&0L% zv-^9YzsG|AQv473%lpGlJ{Cal%OJwnLG&VrsswkAOVaq7KNWO}L~`yTKizV}Yu_IY z9pV&xKcu#Rmo2`vH9=ojifKvgc#>-}I;87F%(~z?)BU7rLv40g%C1FH@)CF^W2c4bCBb14>-KPB?dx+2a(Gqs3Bu)`*m6 zASdc9l_n`BYI35SU7bH6l!LZ6fanl!GIqV z>tMO_#MH#ZWTi7xS2mtx{+qx+hWk5wk(y%MFALCV&-901UC7U?UUw$GuHLNkH@;Kt=Q~pwgwkUn|$Y#Sn+j zwOeP-okV80vbUOs4C?6G91!IP#wqo=5zv;McWQ;$3NVS ze1#*91NbdYsnWPD%NpP4lK_&5d*sj1fDn6Rl7PTv=}oa4(iagga`LMF?h_ugoa~@p zFibsR(Z|X}0p>#ne`UpmKME>S9vX`a_$!5#l7(nY_5^s0s*z*1nW0l^M^yK%W2LFs z2)gu1_UO>iA27g9$Sy90(3SZA2QK8|!0b$b?@MvhNwHI9zUQ2<9Ng9ZXLK0=qW))e zBx`(zFY1G%J@MFEENexE!3hK%x&B(O%*+j}O@9@9ffVk+K1D+k>s6-j|W1pgUX z2&uGZ74RM6ms9W2K*_HVg_{+T9U&R(l!pt=CGTuLyoMJB!1T9Nt;?jd;y+|&*1x23y7TV z(OGAsoY9Cslasus#m6a=Kr?5#h|E!PYQSRHdH!pS$eRDN##9qP?qh*6keuHETVTKi zt@*jzw{9D4?(T=G0>n%M3-Xd2JaErO1pgN93;t5s`bND5ux*gW!<*p4?e^#$X8w9sVFt)Qv8r)M8YOhc;O2MYGuE6 z)$Go(ssbPgssW>)BuMmv>Foyn4vP%RdlY6h^y2$efdAkJUXbJ?Aq|t@W1>V}ZLMm! zF|XC*&01A!MdX**@0n{Z*9JKlF3QE^86PD(cB$2Vlir+#M0cI(w72uDZd=FylKD%3 z%$Sq@xOIj-@->K%M*+JUdhWiL2)H@i$IlFodrBW3zuyK>gLnL1D~-rEWK67q%@U2t;-UWeni;2Em&IeHfbphZ@N@qiU ze~1eD@i_1_>aRc~3}VCwzK=jxG5i;h=)vNXRB3wzVw3m9i9un#W~e(oc$}Q&g15&|Yfg(chTRqX6P(Xh9iZX(#tNxkSj1u3?D9X)gvCc_rq_f09Yh`Tj?E z%qaMRus&4f97BL{bSx3SjV2_8xPjU0r^9YOxk&Jy2r4YOAEK7y226(HWVV znD?5ClvGe|Xeg?mcq>*psfq@E@c6j;<8jrzmoC*gR=xf-b(10=GqHt0oLS_m!&^OK zBUqy{FW2Co>Kaxi$T+d4FfAKivjM9`PxPpw0H(*vrTmo;x%Y7pYZVl6>A)aXfjQuk z;1bhB2WB`0`2)%Rr%=4?N&3C5wY4=X2L}i4xV{pVURGD2dxjT3>bpoN`w!2cXiKhC zxng#tp_UUrBIw6XiIj_=VhFH>!~T(`2qED{SYpxOVhO;#=>%fqBQfSoJ?@yjO&tWF zB$NSX^N$5rRzkl&!`GL}*Dt{j9t5{05>m?Ak>xwC-UK(J=uBhIjHl)aX@C86Z5sZ{ zK#oZnQ$$D^l$?cx0SN^x;)qACjtPbE@m+etMU|CH6~)Cn@U`BULN}u( zZ|uU3w{E~=gLlWrqk^PRGF{~WYa)o1>}bjjB=$}{$8!zmRY&lIMGND*6fUz|NCCU0 z7$o|-MQN?7I7a3d5dao|Cr0y1sAPeQ!T(BA^pwbgqKkN((H;7L zjz(C48ATVTF>sih_evlY12|!}ge~;?{~AtI-)qpuBT9C!20sG709d=X9f|p0xyv6h~q>$8?wfwur!#L!~PeEQ-SG>t*|cS zVaV`HDjMG2XK*p+@uPl;HUStZL)o=9E8oYFSHiN0Y0guq9K<^C~KjPd{Q z^_F2#c75L{-3ZcxbW681D4?W-w6t_fBaI-9pmc|HcMl;TCEXp;-7&zs=DM$YKhJyY zeQZDZWtch7wbs9Wu@J%(C1Tg?jU?fnZlJO(y~%&H?I^Ih2~)5l)4_f=r2_AcyCfTL z*#DOS$gS?5$0tJks_-0wLnk?so-_D0KjG8u`QFX6!LNKF*K>kG(Pb*aunYU>4nBx0 zw-JS?G?@fQbkq-aQnD;%1pM-hcvtE;$Oo<>BLdM6u5r2IC8+~XHz^)-EDM&?dN z0!a>xegLeZ!>a!LMJNPBi?z0VL40^*MrFjFWs(;@owC7UV(s0ZIP>Q?gPW99zO^C5 z)#fr$*0Q3${z(n08!Bq>d~#@Xe6Nvyr1{bPT4px6y-O4H`HiV$Dx zWWoe8crLK#-)F$-h#8)9%!v{F;5EmH&dBWVMRSl5&~sn7NZsU|_bxv^3XWB&Bvxu^3Jd9c4fIjjQo zTIV=#q}9T-9&bQ=hv*(h5}0p)AW(PcM8v<=V-UX-^de6mZfN}6b0G3*rzW&e z@XplZr-e5B#MB?^i~jq1)E~CkGdEu1=Gj+=wtL>b58mS^`iQ~Zt7o&?+Pl-`skJqQ zMj7Loj%t_kUX3!!qasq|$Bk-lN*E*e=d0gjbX;kc%#yy?y>S+KYWUv-C;QwRdaR-J zqF)itK2+tmJ$u||Z316cjE9H(YfK3qWkQ4l!)y}MaAb~|QCG<+WLsvhtmFi&4F-|U zd~O&5=pg-{cHmQOA}H{b9T3(+AdP~vyJzM~7GA(4?%GT)O>?RXc zloL%C&1f?vq!5W(SR}8WGs#5>@x#NFpj=^4UTq3&MCMbE+T6e}krWQ8h~--SDj;4k zykV32=}ScLDIi za10!4L_8c8H;pm)W>OlHelG!s?T)&~z#*bs$Malu|jF(mUc7yW*@hjoF8!OwX zW1rhc%)5G&ya$%2&(Q-@(q2~8ub#-`xUyp=AK-sluVQh>1TdsbuqJIrVy3C@5+Pl? z$>$@J9G7^Gv@LIr4bPz;8+5eZh=B{qwN{Mpl53CkQ!e$mX1Ua6MQq4ZKb>6Mx!ET} zZ@U5*>}d_O^YZAPJtHCg`%*|SKZ4}(B8S4e%`>|9+-AAvY`g+B3hI9CW+hJmpR?H#D^ zWO0(_Xc78f!O{93WSYH}rZn_8wtvlnR#VWP>!8I++R%?<++Rh)i$g<&`EN-^gemWh z2ailgRdg-vG6)A5@5S-lxpg*T%_|}N+_Te6#Fb>u&;1v9CXAE-pq8#aPm&KB9S`i; zn$EW$EhcaEsIM0e$P$KRE{`Vi^Qx`aLI-f7EBk&0pWDn|{y8Wv3+`diX0P32Ff%u` zc+=*if+#(B_-Ynulp7h8UM#RS96E_LvQ>#TP;17 zjVbkcC&p;rg1sHW`2~oJ^RzxZ+tvP z%_4(ly=((=Kf^UuZy5Af@<3IHOq1z_G-xOX?={|pBM$lg-7@=l9`^-C$2Q_1k-+sT z+k}YVGe+z{G$s-FC$VL**Tu)pUl;%nk{T@cfQ)JKJN-5hzYqC=lOSTccmK^Dao$LgSIDfqu|p;@z>WCu8<4_ zS9T^h@F}jYjs`yX>ef}1zN;oGe_V1s4+|}1KKfJgCX2eqRbNmi0*>zV1q`osUYjSeST3qzE6z*&i*^?8%Sz%r6sL(k`yktz%l_s8fm2do_`w z>G`*N8C(rFGnB-gost%)*59MYs5I$%_Pg^8Hobo7>Tt#0Cwr3TYb)s9pw~+wdo9B9 zuq*Lv-yj8t!g{ujmSei>>$&sLA2w0oGfAKLycxG?V6mE-fvKzl+KNGPUsGZGm0dKW zWY!t3bkO}LjeqO^2NGXb={SUukdXlH(eds*H1f3-9c)G^WrgAK zcFoh^H#|qXkOmda46OMiBTsva^gbMfX#06H7tdaqH#*6R(D2c#0|ug!wd_|6K202I zKhl3o{Mz>S(;zPz3~djC%*_cQ|EXOpY9YGuxY%U5AcZm-%X|^%-=Cg@fNMuRGzR#| z^(hysYx_2yVU{VR;eR30Y{8o;FoR4?eC)Eu$*xOD(v7d&&^epOaq)S)x#M5_j1#co zJb&~j^<|Caan@pFf4%>Kq117o3F?BmPxHA(0>@piygc+^zOQ_J{c9GV@7?F=%Cgqm z-ZPHQvQq1`fK8>tU-tMNVGu(D$A7T3n`jW3qaSb7-t3jndabMR!DcS>bf4 z(KOBe=B+Kkx1)t78#`Oml=Xx4f##G_?h|6^rPPHFk*CJuI+9rX6ffI*IaV&pXcIUL z$zpMRrJq%6ktHdqqJbV)lUha&93&|}8edBskSa56kVa5Ra#*w;1$D1y;dc=WPS+44 z&{x1vm5W54cS6-b#8ekI8I%^>peTMZ8!+Y^;#UJ>Nj}*@zC^1pYudeaHXCFtF`KAy zmZH$PY~@kd-K~Tb=W~;&DtE|yRAmQ<^M|{CC0!n&E|x4%h-QwNJx*$qN4z)o_Y9Bb z#0UiYl|lXcU=eol_+P)SZacnS@}35tU3Pht9D8nhUO%bOU6EeU(8#5KxD}|NJf;>M zq7q@SR=a7duCAIOo8o_Vu(FZrMZM8&m%{ zm{!TOtO~?EoR_bMiqUceI5JW`h`DtViuje%vps}yn@N8Drmy({_WXx)qrcU^!AU<9 ztz?h?2=&{==a^7l7avkH&P-wq86GxIEudPpu3`?vY_`U?uzO(PuW_b#~@4vzXF^71rR zLDYG2dySH->0;&r*#1%}0u^MjaYqF8*pi+%RrGGm$>1>D`Br-AsT zDKD?QDT%Egco{x>dyH0lk&WT`ijrT*0MO8M5#x@d@|o{)-r8n-q;-gku!RY!|x3sG2YWE^Yo4-+%efU&)pw9>Leg>Cf1!!bc*hHGJsZ{uz ztD}j|4OhcGt&es_7wFK)??;P`D!OC;9Q&Gw^QJY}#LICyN~SCTHgo8Z&S%DlpQKjC z%$v*n*t9L`hHYgjVPLo@{erp|4H++u0N=TnC4a@=J0z!78n5h~=5Sk#MKygYgE(H7?l~ zX>%W<8(q9Uk-4cQuD@f8(_bs}WJ4kQA23hPCSj}}pS@j=lmX&*&3?<3wrmMP=;rof z!aB1eR8P~AAqn>@C4&lSZGkcidsClB=6l43#4W5W39H+Bz>uG;DG_U&hx2#y#fFp0 zhml0&QsLGz*gQ^sp*AO`mQ^#;RbzbV?U;&FrZ;3G|dOt`ks9srRhEyrM*$_ZnsMTCAfL zn0bJT*rNJd6uBH2O(?yl{myOBZt|%X6jnlRM}pgYw|hzyljS$SK9X!O{c%00Qf;$k zlk#jhd~0g{db%HuKa`y8M%Z+!b3o0^`!V2g#>jiVzR~;s6S?CrgOK-!Xio?Dd<`I5 z7F!hF1MXBu^AFKo0kil`yw()gR=um?#Fg)4Lm=Dc&oB7L+*f0lDYRy1elWnxbTkLm zufr*jy4_1o5LxTqwS-CSo1nVQ{z>L7`J8`vPf@y5A^asHs309e!u9-=*GIsY%m%4G zDDL8o29(fr(Ad^kNcMjfCZH381ygP$&d&H+_4ej-9f@u!>#M9P^qG&?h`mAREBo>& zpU^2-hOpT7I#eH}B=pe%^)L>Qj`h4qiJyMsfieEw_r$LsE;YybKHB)Sb{CKtk|LhS zopQWRT&O4>9E;m~cS$MoqOMBg7oqRC>UTb2RQ~Ohl(bTEuage3h>3%#CY9-g;jVpZ zt_8=pe!+ciNf~V!e;d(hlE`karS0at*JxPa#Jx{Pj*B^TFJ!_4bGD8SU9W5sPquwR zPTCJkZ&MPJOl=lipkMMe@ms9JLy_eJ+w`EHz2CkAm-aj?*$G77CJFODXgi%iEy=YZ zhORzeFYPKHU2hxMr47?mVy?-~&oc5Mq+;++Y@9alS$z@eyFLTE_IuCw0ujkeEmsqT z$?Rn<%@v%Di;3k;F0yi7_P1Mk_dn4Wz>G(UWU9KmySi5t6`PE>%Hqc0ry$i*n@`qs zagMz~V)$*Brll^|8c+b-Z28mNrZUquorI5x*a0Sqq_X|lc^~2%f^ATHiAE1sqc8V| zciSdU9g-81**5yzjlM3Ob6fQ`@{`>PzS8!rZa2~(ZmkXr%4-X5LW~B&ywW)~&XUee6CoUp>$;6)ax-&4I6R4>W zu=(cLWEf({9O>lid#RHrYbTo9E`8p_py07G+-l!T7;YTayB@z8{chIUvDHbr%tJcD zR*?bNw)``S`vN@mtP=78OXT-WEg|m4_HYz+e_R&uxy5`&B7N@WNRj78@$;4w$h34Y^wND|df8;hGPwHXI@~sze4+Jk z9A>_V^Tqj@)wE+Y2Rpk4;vI6z!ou@XcF|i=o!SS;whlO!Bx%AW_FtC(sd(xS*W_rQ zARh~({9bo8qwDp;HM3LMQ0n74&vRYrvyrhe=EMK8TmCF@)keL!zmCA6bneO!aVYq^ z8&7hx+gMAQ)8o9m#ApMfDA_MJ*zlLUyYuN`$kQHz>a;z3>D77GUPrF>?f%b@@13Rf z9s#f2)Ec&y2SJc{n|*Y4b5@MwlM-2YvKyBE#O|eE&e;q9BDsB{Xrxr2tt^uDTY7x& zv}ien@j8<|Vxsh84bG~{60-WkN!!ocN*leX+N=_-9X+1zERqEG)`^w z-3sojIx@d&^E{bgz{mSzMCKyeYWy`S@tWk|*>$%;L_iw2haNFac281CMPL-=gB1{FSpn4?LHN#N!*v~@Pow`&kpD?VK`YU zO4j9gud_F|co0}ia`LhL9R z2AB6Gw~W!`1qrdK79X^-6WJ5Awf5~a3)1=VfZxqpeJ`|A`XA(!p&2D4Rm*uIH1O}2amK_%1{m`K#n_?YxP}?s{JlZ&}4OH5= z*??gqI0HN=p^%Gdpv36m-FIuG)os0IZM$U7WnGKgfM?|IA$CHs!xFBH%F? zq8$JmIehOuxz;VZg@oMX*Tcr=>^-M=R$p>S^IQQCivJ&MJgiOD0xIQ43maR$tbr9{ z3{m^|?svC;g?_%CoG>d1jN;LWI?RY{V`BU+t1Xt;_t`tc5+M}unaHlr2gD4zjRH9T zqlB;oD3GSk$3i_CDrAJjR0Tb~Rx*-9N`n@6#|nZbAnT$*z; zqaDKvB7s2N4=n_SYs5H=c1Qu<{aZPxG)u^6U{g(-#{mt8QE8p7+O=jR^V^V*VPepf zG6~Gs0`JH1)}oH@zR$$r7GI7f7v0C+?L0cC6#@jBhg^uxEv;OH+~QN2sVufqrPGbF3!B zFBkS}OnY4%u88gy=chi4d7rjdW>Qg>tCKVYR{!o5SQ)Ajl)UmzMqNvofzgYo5K;kd zoPa+#f&TOx7TC=6T`@Y;;CB?FHFVmD$eDd1!qv>`|7^@hP^>7|6G8bf()MbqdwG7o zxhyM-+FFHr??m|#043m`_xbkIxtN8GOkr(j$+dFU0<{b&33&9kI#AQ61RGn$dd<#L zoeK-x!>w(a!BJ)UF$il})cD}&tiWpDW8~b`Vi@~P-MZDX4!mSEML5u8`BT19|AHn% zOpWZkBHRxeVal)1~xWDVP4+%S2L9+ z)9|RFkc^{H5CE43FY6LkY37xg_Sd*L`7+g;U``&Ls*+zKqFy`|CB3PIZiJwS= zt8wq!G*v!yzgM}H~?=NSU-1MF=J=IFos_SWpCB~@mdIg zdk6iy(kV~mlq2?!&<_DtE=fo^1Jaljf*2+~X`b%KC#h!mepkI*jz{=BKK3K%j_AwZGb!Iu;3OQpenFjWH5_We8d zgdh}YBs$4V3SMJu!taGy_lQK=p1T-4j1kaMc)lM;h6dNqN~za^EHg=a0r?HvJcNO5axjqbXF>);ITVT4C=8i?ocBww zA09Oz`4eWn?4sIBz~UvMpnU5%0`S16Wg`5FYvt|gfMi5PBLsNAIAGhvnX_3kfNcY# zGyT&8CjQn*izX_Ch*D_I}U}@1WWKYjQ0XY&S3pFK7Qm90GKrsIV>7Laxrcnw*DX1 zg9pt-b~b*4<2s6r&sf6iPPUJ7_EtBx(ByR_;?9m{%}84s(aM_C<`TQVSB#%E!gYpVo=7Yoa7RwCtOZYkl4hu@?vK80iq0& z`73E4OZK;yB$OTmWRN9I{mym3Yot=H^2Yslc_i@Gj*^#s3aZWi#3!^6|gQxnE!WV)P{$Tx#0`&gTf zKI|sO#>tbu+cTd**{I`vdn{QW6K$~Y`(#`nNNfIv$;A-*@`0(3_4EnTS+|RdO4eL{ zH03$o+PXqG0KgX($XYPl+>gE_H#HS3zCCxh422k6SWL2?|B0MqFFQN|GhR=A%N}R~ z9{Ec?jbJ|}no_3i7uNMu;s)4qmBD#tmQEmzzPf~%fK`tsOOrV87A~90U)|p zJtmL~oVzI+!wpu9pElgJr1Yh9A(NzTj5n_|>y){upZhrc3NfgukWhI^`XY)F+13a` zMRStST>Cvd9c5_DJfK3_`lQuy?49)(lMm;e0IJfJ)Ylbraxv>*4EM zu#-w#_)K%+@c#vF_g}hTU-Gj%8_q|ardPjKb*CExY%9Euw~@H;b|6F!V4EXv0}&Up z7M(U$%&%oDwKwuX@yc8+a5?5&pEM}M-&VvEGM#6ygd?{iaV3$;FVCATPWcy~kY_ou6vff9V8nPGakJ2rA?opU$+=iAr6gF;gBB zW+3~r!f_Ev5`ndpb`#Tx5KvK8rmuh8jr!TTslg0WUX29s{*y(D49=<pGql+|j%ZBB7{nWu`K?bm?R~PowYb=9mP9 z5ZUk?()D;otapv0BSR8bGx@u>x3^j?Uuo3e-~R-7rYFtK&7CrN$)nNo(f%hpGp~}_ zx`2%Sg$Ag*n|HS|o2-2wxp1LxJdE0IaS!g=r=Df|h}Ubq<#_Q?Va1~%C{2JO0*wOu zX$KP=YRw^TrR6Yl7P$9}(AQUAq<*OfqJdIlF?o2i*=k;fhWttnl{xlWS4+A5RLoJJ@Xmekv+;s4=5Cv=Hsztsb5*MrGd)V0j-c?zzn6=*`W zi$sgU$Rs+Zi*nc8XE(T+FxIVYW}Y&vw<9^!%O`hiiLO|XnUGW{W%BybCAq|PzTW0 zB4HT+P%-h~8|?iB)S%@u&tL^>a_>BLEire?b+_WqxO!v{g?S_gD^*Pn4Da-s*^%E; z1stj1rR7K7^Uy5o;jH~{ zb5|8qSG!L$bsmwLuRfGm0ywX!hrvvn;)1Ma=-TWg@D|&d6v%?`yD^Bq{LQi;=u5vN#dpJos=4Bl{Hm;Hy)$=@#rT0wDu|a2|Afz=vDQeV#16e$^nmMPf*>X9X zL*9Z}bVMpD@W6yY`^~1sl+}T3%XY(;io)X9pZ(mL;)tf&a)avC9$OZkv(<Qzf&4`ocWZxIDaku3uk%g*#FJmMy`~Jn$ti8k^h1Ia5`i^ zG%ivx-2u`X=0@h{Q`)&*m!TPCSBI-Kv#@G5=+#eRKV?H0P(vkWoI^M`E9 ztNNJol8f_mr?jktXv*=6rS6tmz#+I`r`eA|1R6`kr;hX?A)>cl7luGA?sl_-eXv-j z_wLHjnwwxJiXQE^B8o-;UJ=GeYQRWFT~TnjsFCklfpz5Tw{0DWJf#=(06 zO%{A#eEjuDYGa+Q!3CNeJJIs%0s#&-2g<}`?T-x&Q;Jx=Udxq6Cd>7SUyhd+Q`m8t zOU1mGV#6QrJeOEfMs_)#&gS@hNB;h+iF!e<6p4t}gY; z?A2V9@(^6@lrkQ<(q@czfBuAPF&D}X(z}r$0~F6e5bDc>33^G z+3Acr7F&t*dxY9QpFDqg+?bG%AoAwbz)kG$`pu z&PYYw4wIhfeGBc@>nq_C`fE~gAcU0%LfAhBEvNg(js}o!M~+0ntkJf#M_w1yO1pJn zB{<8}ua`0{#HRPM6j3V0s$$I^kb2Dg>eo5doQfmJqO-3m&mO*|m(6z0`xInlIsQ2~ zzG_B3DfoR>?_?Nwh&yR1{I4U-vonF?ez)pJRGQsjv;T^pNHgxDe`-)mQN1adZFtP1 z5=H_t(KALR0|(Q&1*(>TFwNj|1f%;Y^=am6BK>sky*uLTRHi}g827~}04LTQB}Z&s zSuE$u+f3+&4@N{cMW)BFIJ*s4|yD}TTP4k zjb9n&H57y-@p-t9ue@$1JK+JfuA*XTXZaSA9)-9IJA=$-T>mcv0#8Rr@K|m1W?{{17j{=EJHpcT5<1<`{Q5Y z#={)~a@&VvKaOWQmv>ehiu73A95%yJMvs9Nl=Rq$d|QOvXQc=I9+9y@Slz$$P8es$9->nk_$+65*a z_(lcVr>CRvQW738j)teuZe%}bn_Bd97}nv?7k)7Z;jYfoiN(sIK0O3;eDXhKF7i1} z#a7XTtjHIZM_N2LU*q;T?ojJkYN^m{-d7vE2r-zZkg|n=OzQ(poAs2t(1)`t+omgu zbHl#|08qkh_E;>hO|xqJcuv8&M(*odQo--jpK8ss_4xbFxJAWw+{nYDF}asRbU_U? zYv2k`kH4MFIAD9MYwvvpcdi~ji3ri-vpPZO8pjZ#r2nJQKnD$h$fi;X8nUbfmN#I!!|3~+>dmU}fq zwC;^oBREk0MG~Wr`BW0CtvM}b++X?*(MF)yZCLSV%kn(_-mZ_?w6yF)!O{O|+v~ce zL_WE3+-9q&CH$rTW#w8qj8gSexctfK8?+p_g}fx|jD{JD@cUl-eVDn%?=T21+rtB} zJLrHOXwW~zFL%jry|b>cUC$Vrz5i7g_|V~lZSy7oySI5o9!Kf8To{t}rDBa^pygkh zl-KtIR0xv$8Fwec_1e82j64qn_mdvlBdJfI2roagVzjf7O+JU~ta$3RQz4C)-W_ns zJ`HHO1ALCV(V&`cgwZ2Du%Tk-C4)Ux%FrJ6&fMG2X~onBA_C3LM|)Mk98n!7?^pMx z6z<+VUq*1^V`e-$e|`COS^TpyFw*29k}z7%PaOBj0px%(^AUYC#27A z*X_v;*B!luZ(O{foHYzAQW(an`cTsx8`NkL%G3LI*6wR8zDazR4a1dz!eprT(5;>F z;CCTr+Cnb{84X&_PQPV79J^>h55{sHbJX|Tf{rt~+Iqqu+1ziU4w5II>D227y7jUz zhXMQ?H)0iRQj7_@R)uX1{a=_`l3=mUdz0TGVV4w{_71hv2Pa-Fc?cZiQ5-k zXRTHLVp0Ws$H@AcvV8U7CEfY<=6s`_Ah#Pc;E8h5Q1j)T&=q@Y<@ms-2#OK&5wNiy zTWzDmjPbvr0*O^_F>o2GtY-!S5eFFw0-zY4yu(~pGKxMD)GoBB|!tCM0kcYH84gQ2XH@ifv{ZT78$n}7Z zxYlIFy~DF#N58I)YIJWVC^om>v)t^LhR_D|gq9}|`vNDcKHy~K(q=HM=WIE4ev_eh z1^utkwNK|&1*<5TAK|Y?UxQ|${Qq(RN~w_IP7ydBPyQO#=>d!Dbk( z?AyBufj&uVYZcxf^&UUkRN5Eu>^vv?ZpI#Bv8!+L@j%FBoh8g+lMu z=OdMqku1c!WlI%X7BJQ=(QwLc(84A=bO*XETfMZx)pc8E?*zl!0;V(x9&IIU`^NYF zBZc!w=7|L2Pu711vd*y91bvwfLii(F8W8QZWfby=eoy1e6#Zx7Mz8*PR-!~6O zmsbN1*Q`xRkq;kpK4`~Zv?fbY3X#z`o@l<`d^v5OA8i|ev#_2+K@mb4XGQ*Yje~J7 zvTq!kNh&e)#S{4j*;Ce1ctZq%nj{Gh{Uzj*Z$Ik_zsvaP>WZ#=reQB>xI_W3y?bAK zls7LE2`9W;op)51N|W9bq<|_MVLJMMz!sRrZ^}F^{4=O~xLLHj&S!yod3{2>qvOzp4mhM=JDxfV7uB zx*D>qEVOQAPA6i8U;Hp-!@CA^)h!N;%EsB*IZ#?$51tVt_4H72-u@u=)!sv`kwwF9 zJiOkVbV>=Q=BS?sgJ6s`KiEm;QuWyXM$vl1hI~DLgOF{-CHTymh1&Ln_>L$@kivHd ziav1ix@|vFzj5mwdFj?4>xfaRHVJsJTw;214p%C3mL2RD-Wjw0Ry zil1o-+el}wx072s4!1R9R>&I1gBbr=&9joiER`D9`563fNOlrm|4<>>i#ddwo^AF2 zbkTUkn=o@gHo!9EZfG=!whHTgsB_&SH@Zv*h7@b%*`*|rn*TyR!{QzQ?`L`c7PRPp z_)#z_BeT{@om$XHm=bq&$zNb}#F&0bTPX+pG7!0frr(u$KC7iMS4eSL{_}_Z-Prfs%LbUxQDW);YHha=98ac(Vi)7}PgRN5mva%lxkXqSuK_2z+>i%={=le<`K5t@PJ4N)A^Z{KGo4 z1Qbo!;78y<%rS=04@O46o=hn9G&eWjc`oYfR^M#ig*Aog+Bv=aA&tx45=ppjUVuHt zTh!H%Q6Vab2+2vl1W9Wk$n%1%+h)NVDzf+bGte`U;l>JYZEjk`{j<&{_|>ct*>)op zmJ|M;e7e-RK-sufxgB)3ss2Ur#*rggpxb(D6LP=HXYro&W-#cQ1;gpNI7XG?t`0UE z`-}GjgM%Y~GkSq}Q!<5cLvf5hV7iv2`z)1KG>8UVVzE4|IRa@gF-?buAZta2eO}}$ zedPMPZ;bY9_WzOun=yA@M8VGs^#!&Jo+e8$9t!gXwZ1;)DOA$CWWc z*QJjg;-^nlHAJ8a5#$f0{&ejLHC!I=xNAk!aSNHL*_u$7R3JQY0Wx>TNsGZ3@?f>& z^lne_8BY@GUIoEghS?qo@s)UG6}b3d9L}Ymlh1(4l*A(ffph8QPi3I3uII9BwG*UAy;yh4-Z(foS=_M$Hqr$q{;*yoB;T3MV8d6_YX2e(DOn{rV*TDGE3z|uWo!<6MQzp`25WCf7(%Jnns&&=lLZ@~S z&uXeDjg<20&-G1p?y9b;5HRNlsj~Pp{2BV~@L)JyY%_d0DChIjG)3h$oOI$yn^HL*iU&{LQ>D;+ zzKU9>LDx?%Lke>47Wb@dlY=wAYL0s&n=ffYpWiAIUWao$>v?j>jZ{ZFq+1tBCU#gV z3`zrE4MM2sr2u^|nYabj=E~d%&%sPkbF&oRY?EW{d;o{ozN)@{-oeJ$aZ+TO9y>j! zbGtsZUX?49u<^}Yfs^G`K~as#v8K94Kx7~@RS*K!gB-Q$y+!AW{k@iXl6l`s`Cu&b zt{?6Pa}DQUU8ZQ2xLsH2XDB1Vb4@B2_(CW|xFTqqzBH$a(K4=X)_GeK4f&&Ny>R!M zRiv01x}?`+H<}Ui;qM2|(P@_(pOcUjM4*{J+b~qLE`ke$;1Pa2*36bFfmf4oBKQU_ zc|89~D{XYiM_2sSIx0Q2?Rh+oGDljbeaa6c|09lBa+^<<+bVRj>XxeC6 zJoUozGCNLl{!2p?h812s9fq&R9;#H8euzg)AAka^!dV=TiJcS_+$}iozPqJ}H+&vA z)b>mUZ{52t!}oZ+F8dK=oAlaJO^jrU7sig>H2Ep|42M;pZYaXG6Lu{J0(E_ z93JjB8a{>PFOG?yHXgkro!af3{hl5&l_qFETe)hoq)>$M@G3{cU#TnOXMS?)$IB4W2`eqo-jnYkYRdXK%!6P~sY1d6v7`)RgdOL&@_mh&Jd zA}GL5s`+&oOzPstkvt8AxYS`CgF2B=yj(?5_4w_60fha1OcsesPl!fesk@D$xY29> zSPjQR)!Wcq8yR+^rl*IcSYa)5q|CoAJ2Kn(R&$s$KA6?vVCb(3Z7UJ3*t5~;nW8W6 z8roN?aU)Ntz-zB^w7-`M*{e98AUH!Ns#{<(aXLhXUobdxY8Yksjjih~IbTdKy^!3( zdZ?@-wsp7~=Xw2M-%hsIa&6D6ial(%rPXc^Uh)e!OPHDj$%E4U$FlZ^z_{CdKe&gf z&LGWuwfLb#=5_*QOymjRUeaMuJEK=C{uag8+Q2D`hlZJq#_0%CbW1i`t?)FaAr=Kq z9+kKVt_iN?m_Vk(Nw3gTx%(jV?f%IRtJg&g@8JXR3uvgHr}sLBtQ=QejUQ}~7MVYv zS(bADP#*DGb;Dl6GkxhN?Uf#zocE!(=;IzsEJLThrZ@6?_y=HQ_!;|0cE-j*g~n7Q;h~Eu)NVb2Y*8?bMEK#3NkmViM~o zmr$pWsrfNy_Fxq3+))NXtXj5y2s)$q#ub(gdUwI$%C5p$+p7{rp`b9iW@6wNEa~m!3iw%})*UvKbaKB)Igxqaz;(Fy(jw4%@^JsDn8LO7N%xd{ z@;M*AV(xcNy$ooH ztOvg0c{O3rQ$+NhyfB-C&Jht#2E|V5A&iB5L3fYu>cHlFf=k)p+wa#O3ZFcvW)riY zwjTszr)%e7?~1+_-TnA%;a1!fB@g6E2z4;>Uqu zmR5QBftn}#OGF=3RZE0_{r;i*(WuuF6Mn_G%2O*f?azH`#?UholKAJM#Len6z8X#w zKSaLIBw91v3w@22l0T)}6wA0fSaq~l2u<*!v!*TvA-=yT(X7t=Sd(WuZYT`w{%@+_ zk$)0|@u^{g-%@&J8i0)0&K_&O!UboqRuu9(h`!4x>nX-^)B~|-w3H*0VgW)KO@JnE zA?a=4BgY(#G0AMjk!mSBPeWiR{dC9AMt>Z7pJv;`0v7%l1()NixkA(@Nul)EsgZ${ zBNXeUOuHX!`2CWZ+gHk^?!m(|J+*Ep7hH5}AYS&Qt zY%42gV3D@?t0I#3cczY%y1L7=cjjz@LWe^*YkY4cXU$Go*`%+)C8>3T!vo`FFKrgm zvT_(02Br|L*-8-pdOm z`6;zUmi86<(lY;NY1mI&y>?`9&RKj`jo7n&jHcTI^=4jPt3~GRDiIQ|gg~Xa`P&p- zzQd6OmseDjm-BuJG3Z_Gov5600RjtdY z_at2i43FzIrn0fqx~tZ}HD8Q4s=^~C?q}IlYJB#Qa5x4MMp6%R%9EuQPDwrpxBaRs z=vZ%AZC{a)TVWdR%khnj=@m~b4Y!XlYjJe2DLnoZlUlVm(hqfY{+Mc_?^#(US*iA^ zStE_&{AihyAHT#R1fdAd*P43gh5U6M^`q33=)BkczoIjWFP}NvtOBSA{51)ct*_-NWrS4tTwGkFe_*qa=1PF(rZ0)d{FH{4 zHhR1U#1t)E@DYpe(>5=#9;Ot;BSn)tmaP(q42Teq5!%J_UOcbF)Cxm*8CIZ2Kv~pg zoGy^L1s4?d_y6$qmSItLZQDNs0#YK4v`C78(nyI?f|R7xfFRvS#}E?IsDz{vg0yrG zA>AO|-7xe3!|-3+&vU=;`|1D5ZM#0`HRrj`wf1%Fzx_C76-s?EMAnt=OT75>tZA40 z?0!P7_xyUx>&?XtisP5gB27&A4_rDtl~4LaC5ot0GwKUsbc|OPbE9Yk6|;CJ%fUqW z1anKvu$6biFaER7=KVkWEFs!@K(Flk?TRaT{NoJaK3QtQ8*-06oY<+*G8Xf8p6VzV z%}VnWd3BV@hb)jzX)xD_!$X7d;-iOP#5e-wlQWcP@lNB{8}$@kU6l+;yIS`HBL`mI zl9TSQ?46%gEWupwvy*o9S4$hGr>DJOu){HER-B^H+2UR)$0{bK?~O)Xm~?b>u&zGv zRW`6l5wdfxcUlQ~m8+7*aJCD=aFK$~O9XKFk@~+$U+^+HK*svQEg;U2kLvsCQAHkv zckz31$Yl=Yw8T3OJ{0Fvd=@$Hh1u~)CusH z>`CY&J*$3kEIjp+3L_>UFoov#GBwl*eL(0e_dEkbfSAXDA`r!YiYySd={9dAH^y(c zmFu=TdD&o1hC?aA0qI;n-u`1X5RQX`lVfgfF58O5wv*ZbCOHr+_!&_h$6cn5v_dhU zE-uF}6{GXwzkj#VG%}iR{`)r@31*1a7w6`(qXLY!U5<$e2nZ^*iw(Avyb>C3&{zIp zvw_$Ifn{Z7gi@EASq1m*-OKSGazB`_w4SRw{W{(7p((u;%B6>?t9yt>l$!YqVkt6@ zZH9N2x>;%;Qg>_fXo?GEXN29wLCDCytek!v)_`3q`;xsG!!tYGYqSoX2eZd6#+e=SwHUk}z+;S;ad;^ak?F zpADQ3C2S?dG=otsP(dScp_6H~7d%LPtqNN^LS6NZSW5JW-Ok{=*A92f-c<~v)VO|= zk0%+%;xp5ZS^RtV*2&yCt#wP9p~0?COyz0r!5|886@>R8*o)*(sp1M$e;eg{Fgz8> zTzIs=1H(Ce}^YjvM_(`579%YXkIx8ML%bI2_>rALj{k3MSBfYB`wy zBLsVNF~2W{^5HaJYNp?wgsS@E$G!OfLeHh<&wf5fDs@v30UvxZIXU@p&4*b~C~^RZ z=Vvf06(N|$Z=v$Fp+VfYdGuB2z1qvGE2(pD9*xsb!ZpUE7A>}P9?Pq)XS7{on{ z=@}T%VNX06)M0MyDyfdSRh(pOZxonlsUiU4Cc3e@O1-_g`E7+R2$xvJ(b@U2D44X= zztk2gF`TeVu6R2WO~PfpkJie{st$gAmVz7A`zD&9Jd#qzCnW5ns`OpFT6Z4@Nb&p3 z%*;YrJH{@rw$#N+e&$ak!F&7r>4Iimv1T6mm};=|IroQ@l$5~_A3o%~^MOuLQSoD* z@;c!BS8}4X$JLMoBGajlnLqO9$!S|gHBSEluW&j>Qyl01-U|vxss!3H7Bh|DY6Vjo z8L@m;O-Mz-5hP(^{b#-?*jw-mpb@5O*hr;uQJbe9E=AwH*3fZB)~A2`p2uRhT{e^c z@d&=-jIlfW2BHo&vJc*YK(!2+Vc$ViQ}Q%?`}r^k-lL`^dkJpTvXq$&gjtdeH-`wS zW^gY!VjY~BfWodBnBOOI>r)yS7!iZ`)gZXUS7;?bLe3ccyzyAHU@|W`uhbP-P{I}pSy0)RoYB=-TzyO?U=KHzjgit zhlr-3c?TOC+v|>-@+?SMn4~qgK~G{N9rrzt*A3V9$nQ3-+gMpSZEbB~n5I5KP+?rm zIKYWo#3A{6dwWVO{qCT>B}9a(BlMXDsiG3b&emuy!IL|mBw!G=v%Q%K4k;-pF$3J} zG*-Hbc%T(=K9Zwke$uoq?v4r!1;)ZCri+8UO@^XiC-7X9Bk`z&`&^WjKUG`H^3boeju)^T`oS)a zIz2vCq8D*A=4E+%P}HM7egg{F-lQE;c0f4j+k}I z91waI?)$UP^s4O*nKA^TLg96Fb!-17=ymxKl*E7txVR%|I>aljFXeCb8j*-QhtUKM zB>omv%mwTW82Un4k!{Oh&IimyK0b-yZMusaMlWdn&raqFe5ykU#)T%G(exS|n6+;N zmQwOIN-SHebCeQ=!&H#Ze!BH8ybJ0N4P2Taaq5p5otO{?xs=z$ zIaA}-cVKbf29xu#wOB+~A{@UlF!4HgH)E;$&+}_ylWfuG?OGZA)Lb$p?8P?`VIEkA zXp;#4Ze6Hh3vO9R&dUwyM`XKGi zine`%U;WbBmQxy^tBFWZ^m0P{w zcl8{y%H%%-TF1}6yt0`n{!VIJDksDJ!|~m_?+F|zJ0Mg#ybl`P8TUMqQ()fa>d#l9 z%nv9#^^Abb!Hl78=ZmWFksrZShAbXh%D$ku&~x>s4{noCm=m=UT~ z*LWt+DX{%A5d0zT&!9(Jkiv)e9~z8;Dx)%mX8FnkaQ`)SC4wC`-L0pMZW3ADBzW~1 zOM4B+?BcKM-gJBxujz$J@ef=LP0v1C+fyZovOk<5$|r*%JTjoVYSMZ4ps~s!hEd=? z?>IR+AwJ=4-^(DX>E}qJ%Y{sqeu_o$1k|eEu{gqAiy{YM5M+_s(raxIwS~I=%%>Vpm&5ju3 zE#AjpwKX-XUvrCNI8bZX0mH(K5?q9^Zj}~v-*!evb}sxj6hWnfMyzA6 zVwaN3_-j}}55*ZCg~x~1a&P`Il%;*K#7+@&NY`LrZoMP%LU{lS)|Wt0x7uypZ+sOEW$?eCqw?m3vCMfBFw+YXC1ZBaM!Gk`<0od6F zgG7FX$%66<#S0GYB+UFD{>YuP)lxyR$b4{a9F3 zS6?Wc*1cFmZ>@wD9(GI>Yn)qzr=Ys&TAbW6ToEvZwT+EHV? zv_K@TaQsXr$aD=3cucGS&UTq4UbHseZr$e2PU1U#{f#zwLLo(~Wk!>K=u=xVj(~SO zjBAR1HJ{CB56Qb1SX!WxJrm>OLNPH63FEgyh|8);VE#?=S3y~Bs+LSlCges2>`aDF zY*TtLM;jYvg`S9QE`B_ND|7L7Rpa?3i%n!~W+pS=Ooi2dSpY+m8C({hl}9iwYIJMR zM95GejmU{>}l`*6l05PDXQ^{|CpA|!&~IF zCn@~hAB1?3Z$ zaU#vqihfm`(EabyCBHEHjKVNNCpbZ4FXSx+N~`{JDWstAzY_AkKdX;MNdDsya7SOJ z3T%P4I}BYS(4Fi)1&{TF9zA*$`oo%Rl9cJegNC|%(9IVg<}lx2)!?+!fl)~Kgi$V% zI++qxy4{zOGF}R@fve-RYiqnit28MHyU3a{odeXij4;H z6cb~GP9ZQPL+~>yUI2<&t~Z3$Jsg;y33U|ZwECZ0fNEvH&}pD$hhfv6|kKyaeU??n8rm6>uf^L*Gg5P>DI@G9{JvU z-n`DdPLB~c5d{Ni9%6+=);b?eN;A6p!`o$pKW?NA5YQVME{Q!e`%;))Qv>-T*E=GQ z!x~XlR=IZYzTnK~wnEm0`;tA*${;i90jem@XV;jM{C+c(bNcstG9Yc7w8#b6aA55O zoOtMw_7FrU9d=QO`Nvl}Ciyg+QFj&m>1T1f<<%8Q4S$_Wy+%;6gFqGkWW9R{?Zsho zGdx1v`51?gI`(diL4#5J9+uG~r64tbb!(U~Gc$8Uj2E^-`g7NO49r$W4=|!U-M@*A zjjjEg2>0iK4I(jYMTA?5e1`OXQCvbCUxpqI zQ{!iPJH2_XHA(Vx2In=beGI-Y$BX-xVqo`<|2;-ChQFY^RuOa>q{*oEH+3YU*@0}} zXEpJ}i{9?B)i{m%`&TpMzJ9^yzlx^>CWrG2Z>=z$&?!lUZwgg7pgjAF%EquB|KA;S zv0hd46->$8_0#p)&$-M&T2qSq@U{Jk|i5?2eTr9`Pi zxZ!?l+rq>`GUWr8v91twCL&5ro#W%+eAk*t&;%c78-*AqpEkH2=NBOSrBbf@&81LubCv7p6xdkF&G|)eyV<>doou?FkW>QxKsJ5<|@Qc|0-&Utm$>ZRuS#Q z8=Q|sj9Z`qrsuYGtJ|xZIKepEXjidVK-{*KYv`qy|2;Tf z*+`~-fcV#-fk)eTO91@WH}9K2SYz@)Rg75_ZI3BDKvBSF!5h7?_|b}(_-;<2_lzI; z6EpQ;T}j>D*WVXQQ2BozjVVJ!#bJkQLBv|RLKq0llT3`qLccvy-$+5I)$g}QY(SVZ z-YTmJM``*rAhYlKrhV%8eE;DKHC@0Ts{c<~@ebfv>G!xKn->QqMd8 zoqb$Bv7-sW7^rf6j)}*fNQLHsKJTQLJErQmKGlzk$^6XSbp>6e2F)0&ON*36f4$HEz?=)bm^2=_5}f(9Kw z{*vnms=?Y2hNzJ@%KZ_`%llL7aT1^8A02#~ljqqBf*$_LNT`R3xc3}(LF;ab=5B7S-MR%$#UVh%PkMPv@-c%=(sZdVWKb6f-T*sN%clj z!}X=uNlP14o_!*cJ?1NjIqf;qrOoj%vPxFSF`BPaViySS&N9yDr!lDogu>f8-_+H( z%&e>FxDN^lpUXY45!#C`1nx~|?Z@gLDvk;s?~RO#(NQ*uvy~MU8Px}~D`!&j_mEe( zg34tTWt=r$7Y1#p27^~e(oMj33>X#3I#o$j94w9bj$gOJ~It;-E1p znXRd`F>5A+Z+P%+9~g7{2d>ijoO~9Qu-7>hZ;HGxLtL7viT%lr0Z9hgG$K7_@INO& za%LGzJo?>(sV>g3EUbC|kN^SNdJalVuWhX8?mHAG=9*41ad!3=BM-qvL>^-@9Accq z<2~m(08E`daE8Qg?v%jSH+h&p2mZl%6JSl=ocOJa_(z#612RG%JtOE!Z}|3YUbRD1 zsODlK6_ZeL*bd*>!>JeFoC^G={?ywHLVTL;d>0@MfgkvtXxa9@2>oLuiB`oMXIK>r zuk~yHXk1PC2p~bE*VoevJYlWS!0by2X3UVbvOs1z;wJ^bi)6kF8p9Ov`xz^gnw zhm4F$$97k7XuNCycrBGs2K4q0?YFlwC-YSlpI4qnr`uuSJp#9uIb zAS0aaF-Y$Bv>r?l6q`VY5>*-D!o^cfX>h?{siWdHs+$e~l#UG#bKe+u?2>)W^*QpN zD0+^J*qpJ$9oS{$-jd%9RI?bjX3;#?%29=0uo-}jf)E4OBPC*Ys zSXfwxot<62`p1vOG4E7OU zS>#5kmD-QRTzvR&2MR_a5sZ^F^mUc>&$up1$b7;6Td+vwONKgi@mo5eon*d#*D9)% zl{wSyr?S@V(0Ho-1gp8S9MAgd2`JZVrnW5Le+FW|Mn@N`8{d)zWhk(-;-4|$!+5Ai z>|#Iq7R8lVR5*VbdF8ldTC5yu|3~TuJ;6B@jjpbIin=yC8%ZL$o_23?TWjd-<{}oJ z5*5L--^ma@4*Jo*qf-gGP{qs{dJ`*B1j9kIY@+E3zYkpMKf+AO$QWo&Y{{OEbWLU_ zRl9)7ZqGC?F$|aR0ez)eJC4DEW`a8#p}p_PV)~2MKT<>CDm?as=vt2(RTEw#jK%2w zMjVZgg{NoNad2Tghq$)31v$y63_5Yw71osI?ZpH63|E0dj`X z$L%I@tXG_JAbnVi+W*)N;y)u~Clc9Qx^adeUzseSZYV!-FZyv_C0&PvIW8dIz zK4atzSLH%%a~t!G*I{ab-iCa%l8a^JNUSz|%!7wvcSvvp+Jm5}Ihbgnd-n16w&oht zjE$Y2A;#}kb>LP1*GTj);v|G|I&lh{b=}84>8Ts~h|TexS01z~u(GB@VZVs5T;^k5 zc~`fUlQwVQUmeh=l>EATVODIGZN_)5?D!cct@0b?g3H$Go+jC)1J#12LxblBqdbg# zNymfri~|j!SoQLEPP`M+-@9$OZBsU@sUww!%D7v4JEZJqYYSY?{j4(CcZS)1KxePT z?oruGTz@Yl?8ye7?pbf!Lah=^M8u~r#pkU_iz9LZ{AXWWBKYMVvA*N^Kcx>HS1WDq z4hy806rQLfbVF&+CYV5ey0%l5MrCh6k6M#{zK|Z%5M{Y=F~B=>?@*dDF!3kUXI4T? zwi$ZT>3!#>>3p?nXq_a`_~&>FPur2R3*n#!E~>_; z5^F@nqfd(^zk>}QHi$mJNRV?owadasxC7hE<_FVtY9R|NsMh$GwjvV0d~^QRpb2R# z;}I}~DEjvr!g(C=UJQdS?X)ia+0YFH5U^3Tuizd%jj4}*u{wH3uRCh|8boh2#x%uV z)ESYZ-wNca$dvAgcns`|c$_(+g6c!&X6{7pPZkXpjnTTdux(Qy#eQ(HI@LRkx!y=k z_?=q4(N<&rz#>ZqZK9sCB)I4kVlOeUS}G~L*2eYt5DX{dgv{rX<8ePv{6GLl=wHKS z_t;d@X)d->9o{3m7SvbRp-GjN6b=z=B87TLuJ>a=hd8OvhKInp;AsbdEZB{HC9hm3 za5FQeb0g~2Y<{$f4zi3gUDS&F6XRQ?)CsmC52fj(g_5bdYMmPx_e0$aRfx=ohonkh z!~a7sCGrUXbniiazCs3&nAP`tLf~dwKa}yLP+jvay0dqQ2noY~=bMcW#XXWwClNNs z%;QI(fS;MrmFpE1^Rks2nqPCx5a;dF5=>?M^l=I2F4O%j8)_1g;e-zKOD$#?KOf)6 zDu;!AIVe6g6&2Oau-)>-{QUd_->b9uUU*?gzTzg+|Lb9%NFnsh%(B}-FCyQDhK3Pf zXGi|EuzvS=k(XyNT4QbRjXH{3=`rtU84^0DHpBP0>5dqt;0 zm;@P-2$lm&trr|DaCnDKJ*dkEqU~54MYJ$e4Y-3=p&!q%oXhF zn=EZ>+Rx{c+ar^Nc?JwGR|MaA-w%e1peq@;>lf-C?2&p(Sgj07@f;hKzkjV?rar0a zh94+~QxJ|aEVmjQh@SJ(39&gg-J0UbI|!<;rhinz>QL(H$Pq`0K8k~noE0b_XWWPG zhNI?CimL|}8c^b^vZm4%b^hPnPeC}jpc#r$hbF=(MsCJsj&6(ofcqI#oB|~wm zj|)u-9PWWHp2FQw4EL)`VhQ&FQY7?h=0N*KPsbhJQ`Y}ZAN$rm#gs8KSp%+O-Fasnnt(?hH$XCTXrM4#7aU3X3$g){BSDP-JPV4M8c@ zkWQ*Yu42mq1(&u5I~$wcb5YR`WSfoh)t@Bcp2xqQc@AEJ#Idl)UggAoh2?Ods*z3> zg$1J8>*6sp42bJt9*yaiWm^X07D&WBl%|~3z!tUZnn8&822FI-#*<|2wB{0gWP~&X zgWYIh$4t#5f;B*+1LW725E7$KqWkY*Z@BmF^rd@ylstA<6md*t6HZ=NGyFZ^6-Ld$iMQ zuT8we>jGQ6iIH~YU%p*#z0{3gDc{dj4wUbg)Vzg8yT!Y7S93A?_YiTJp0!icU**pB zsAXf-Cn>?r>%TWh1->U7B+9cP3FK5;N1vC>Zr>x-3Q5Qm20TM0jYT1R{Z-wr6iFka zohA`lapc>C*Qjdm+y?BzM0nD>xh$yq&mweipl4)jWW+*OT|HnwwVf-5kVeQTRtfXD z&r?s$2>7|3!^p2!I*J0wg{D~7gFk26w=m##rO~N*#qBowuO|?WxR|T3(zu)PufMPF z3G82L+H{Wjpt@e{dzVoprV>ssQ zb%HO3o{W^Vj{{Sz2sqn;GMHwx%Z@wa+%vaMxrW9lvln+IuvIZ_?kW<#cR?adRHdY( zS`H2m4-+=4fsLtpd47=b(tBvHBZ~GOD%xtU&XrkuE%Ko0iszH059O^byM;VlDSjju zS)+PJ6g-xul-vc?l};6P>G)1cLzA48L@w+wk9s{(Y=~X`w&-1X$1!kmgu-3`H#Z$y zHUX}NU4IvVp2vQf{ze65p8nNz86K*TT+iPGWS4uc1L6%~U4fF8+EuF9ZwKT{G zBMnBQvaUDcHd`Oi96#L$i_byFYgyvtQyp&ri*Tvi;J~<8^6#NXZhQxZ)zSL%ti_l% zKaTLfsV|prZYCDK#Wo%Ph*ZKGDeN9MF0Bj}qH=F|mRrD;@yc>=Vx{IQ)p6}ach(u% zGlt49LjE;fP`c3)CEXI;GQZ}P+6c~o>6#nTyw9!B3hC_4{13;|Z4y0=aqi*2zk90B zHtJrb?ml^>$_vk}zXzQK6K`2+%$K-%`}(-?ldElMg?(oA-KSl*(Qn9siZ5YaD#7i4 zD7oL1R+MI1^|ipp{B7&29Sf`9=Acb%Fc5r|jOuXejQnQkJAw8Z0)nFoy*naN+>f6O zWyz$jb@I&5EN`w}zEv9^k1Cj>^f@$1JUZgDV^0hjwB6lxK4_nJ?i%bBWceS`zH_); znH8&+WzYMpZuj;{)tm2z>D^jThs=*eAHCx~`N>gu4GebQwJLic$kx`Hkjn(oU&@>S zKC*r{+X;BJqQV}C#U2%ioYeJ+28$?}I28>|54S;$8iMQtFk9(lb)D~&*8nZQf3()C z4Q59ht@8GgRII1~i=SUqwDt!$v}XYgC1QYFF)+JsCMjIG+u2$lY z78&H5Ri84PL#yO zS9`*Vd3hY{lP`yix_?TTsi2#m7wJ_h(f~7@i~)^_+}_?!P`~43Wp2*a5L^2nM|AHB zr=n!eaxe)O8(YE-EbH*}^mzgxk6&Lw380z{7waj)Ru1|)?mWQijuy^3e<Obj)g;5qvY57P8@~Zd`mH?RWt@y&`MX(gPYLf+=`WNcE?OsiwFycj;V^{wZ2!j zA_tt+`FEPfnio#~avWO_tLl3u=dzq`4KLX%Kha?!N@_InzNP+(g0n|y;t)iR6ch5U zTAL9DJQCMXTD9T-7%*e`c>|t1T&Q+@47Xo7;#HG%eNnVS6az|S@sl;oJQX(*lcP>4 z?hIrs8efZW598pQL8`XDN*vU@4$nrTLgd)up+XTsa1or(ZGK2MY0J0EuXX}a;=b}0 z)sf?NVk~{B=hv?De3*OpB`(p~CPh4{5?i0UM!p{>(9=q;_p>-5bQ1h1@L&ty&n{kz z;pVm$!3*&e-*_0?ytmfgT%kpPewb^C;tf7=)H-UK*Z>UX?2vTw7<98xp*tjSU^q11 zng5#k*$?|TE6?uu13}Z>h=_Wdl(g?Awsxi|GYzg+$OllKa5i5}KAo6C7*=89NBq0M z{5J4-Ele||_nQzEYd2X~DR8^yjaaP~9nSaXM8nfpclY*0g@vmXo38+u;w0gHMs79- ztWE`@yLaz5YeOl^FMr5mdfI)OVf= zv#u?O%lXh^eoBpriTUBsN9*#EHdW)x2Cw(c*LB{qZ6QECl%v6drENJfnXa&M&$oW3 ztD7fiF_8Ln@&(h&B!BB?4S`lfL6%U7+`LRKu%^^ET^16ChFyT zjh0HbLFY%SEW9=L2jlnoN-o68ztj?m@z=&85{PdmVe4Ui^rcuv>c;KDEa{w={Bv~aHFl~k+Rw4b1B_8oCEeoT$s^@kyRYe$8lD?Ok82a#w zbz1w&ldZtJvvc+CE?`qxJ3Cn5#VGL4E@+d$G*a`SH-XNRjNmfs zu5ybwu->iCvhb_azn@Dd((q3B8zbB`>IF&=z+%a1kuy5oxl0z^!2KF_}K zoWa$*@u>JI<4n}e*2-X<*wmmGe%<%W?o( z(#J9*r>!X=x?n*7cut-B=ja z%owvt`~;;NK9Y5Zig!w>kz9m+S7*B(q3z z;?l|*%}TfYOG4OJP>%X&zr`Q&-h`HEYv%7nVfMK1#!p-O-AI}Jc7ls6zZ}VT64qUd z4ib8{LR#Me^{vBJtGhD&_V%PvR0@O_Xcui0cw;jxA2l*zQeu<*0dQqto-Rl^;kH>P ztlX`0ilP;!^dC!2O;toH4S&VF3I>!{i0{d;{B)_0i0k%0LCikZ+tUNN4170{@NggC z2kxB*`oWM(xM1=+arz-$bju(A#xR-=T_K10zPRegKhm0;AS6wteoW10U-qzM1Mn}g z)o^szuhz2C5_zEmjR5)#6v8EDSoJ#HZeJ|6JAB`So4Ivw_S>H- zQXSLd{WtbUiQR#2jh94GXurMjo@^^pVsoPWTY9@nItg=`!Wfd|+x=e_0Fk&y7=P=? z9QHB;76-LUz%gB-L33op3vvc@tAhvFy#hA?2FVPAq(S^4_J?AiXy+-r#4F7m;9lwo znt`wm>h6Q(94HAM!nM@a0sLlu1CYCvVaYj`2$5aLB+F1Dj&!Lplm4g4=H_N`b*_*U zVFwzA*_vk&$k9R4}<)t z2Tr4Glg^FPDUD@4R9OTyvNmsP;i?<>Mmy6s%~4uX2O_!BGd~A%0dkba3!(K7zpadi z^Stq8qy(^nyFUw3DS^nh`}kXyg6uwEw=wInS!9Fuux#&R7?Ti1wb@w5rZ+gTKl z+M1f#GnujxEP5q9pB%r=dVYI)v0L~g?c^W3mylaD>pCUn zjU3CLTb8_;=d&le%=d@attwbZj-3l^KBmGT|2$~ijS-8Vho47K!N3@H2cTndg&!M6okFDCec`msS`Cbqi!y+e;2t3=gL5#a1*}F`;?Miy*^Y!cIbUbY zGm3N8W<2wJ%l;)tCP4%lajbQ#B&j;ThE}m^ZOqOZU>%7(`T6IUT173>3{w!iZ2x|g z9WP)O83kfX5$f~?~e}zY;apPg&YGW>*d^IA9T1nBTAs0Wd9&D5{ zGaj5d`C#BiKM;_n*Zsd5vH)nvC|UI5i>IFko;q?V&ih+Z7ch<)VE` zVt7%Suba$OF|k~f_m%xu1f{4TX*zu$dERf#n)mJTPqnqAMFpL3LJ|rw4@a@$%FzQ>;t_A9WX0E0E zQW^j4+g;Fe4Tr^dB`cBhb0U*hEikp7-JH!h1S**K5xw5znAUts3=~b{O?UOgq|ykN$9UDAHe%C$8;b_S><EFd7;f{1#QD-wlIqr#R=J9i~+fpU& z)0xo!wXC*Xv2b8Jr$^=8w+UM7Oi*mFE>kj)(0HMID*==#^P7miwm>hmfsdB&3QERJ67A7%d2fB>ZLi``?e=q+#@iuW_*QnXO4jJw=(lj|nK!s$Zy;b0y8jVVon)g`s$WV5` zyQ1s)z4Z|M;|3zPg@*TWprrW!_k$0)qF2rI^z?kwrC?1NU$PsQO?nr3gW#uoje-5= zA8vm?GWzxv>m-|)=4U?mYqIB$$Zw#z<#&nxYIMHR`ky#O0zw&*0v;fCSYC@E2*tES z^#1Aq8<}O~{~_NZ|1bFleu@{DHpNBn{0(`Lz)lIz?JN4ZUGSwp2)qADY<^A`;qjI` zi;H)@|937rwBKPn)z9|!_UGR?PU?WALL${MD0L$aBCMJzuyj&~kkyTi9lXJS`EqDd zN(vQ_V4Q!n3bdy(k9!9O#=$T1qfXD|eZ@;lL&JRZP7Qgik}RBe}9xdu0{mRaiUcJ(@oO<`joG1Tlb$+ zQ;M-_yx5}vIGA7>c>C6Mjw6IAK(jpl(*?D1i$Mx$fyL!rIQnSn3YykaQpXOWr6x9y z2G*Azp57bM!+SvCR+TS?d0&=K*do7m!sf%t6;}Q^g-H7IPsE8vI=3R6YF0M$*O z>#*G3~ld?ZES7nDj>HN#?|(tXsE(XorIxa#!Z`Sp1 z7|D5KLjyiBortl#|33&N#ho0D-;7-IXG@#IS@(qPXB{m;;c~e-04w7^k%H*c((>}& z9EG(Rk&R?Qo4}z1082Z_$jRxYK6mXAWoPeHlb6p;on9ki5Ep@*k;q5W{Soy+mgWMT zAO7c$(^jMRd7%^GdX4XuTlMOynM)v-9=OAZ-oksOm6h@AKNq;T27zk?XTbq=^7xw9 zx>(VsKxSilQXs7_XCA^G(7$V+w=CSAAP=LSuz6fzi<={K=Ho3o$8Nh{j0bP;rjmkB zHW940lx#m?keu}^fyI}DHN7A86JLm!O~6Z6eDZT&W|E(Lw!@d%@~`_Z;sfDMPEI(t zr8%Ys*hYVfyR5$cRn9vALt*H6HIn|z`SmNA`F+wk(D2J_o}QkUcl65f8YETUys2Oj z`^$qRo;Vtbe%sQjepD%7U$?j7J`ENM9d>Oa|%51(8 z;^KVso*QXbJL5&iH7*;`+|y(gO|4jS{{H^Cd()LlhV^cC_t%$qcT=_0)P5u;B$zL+ zuP0o9qQ=6?3uBxUzKdl1E)Tc?`?1N?X zZsUML|L0MH45tY(3%j_$=D${NTg&osC*ZP%>xt~FXdgPA-%crG z7)d;TZthcwWV;Z>o7WGTQ|_dqplDh>zv<6cz6yNRTK?A)4eSA7UA}{_%`2hA9=Vdf zwudNBPb?Ru0#vCv30}s)JFl_!vBsn5JTQJ$2Ib-bYyKq_V=v{o>OUGF0Yd`FC)sMp zGEw**p{IcRA@K$ZGw_4T7qOd&-_j}LMYgQsP!F<|bI_nt3|-^2Q9LkrmGgQ3Gl}nv zYpwHEA^ZBq3RTifiOXhJEQr}Gq&+|07AAmOrXv>9>3u(E+8u0u69p*1Fra}jZAub* z&Lb?Y(3KV`3oG)UwFi4MY~JbWtp!(Genm{}=IGEH&N>!#;cNWR11Hi4S{c^c17j^A zcuF#F{0lg4^mcyoWtkv!)^pUbQ*bArBh_4UAKQ}P#mtE0BfbW8mWZ={yGN=_s-q+6@fT7@ws)6I|0m-(mTUkAzTzK~?chBuZGA)jrGF>=KSDaoyB27Gqz<*n&e^IW zbWUAd-i|W@ofG(dc2jh)k_Gxv8$*(b3&JHf`+)QW$Y9z5=$YfvyckD3GNM70!26vn z?t7el-TuTitZMI{Awp`adxhm%dQOk9&m+Nny3TN;Uix9bhGIBDL

    I)Vn`fsiWxR6bEhT(^v1@(5XK~*?g>FWe8m#Cr<;gxBI z>hFD0yGJ}T+^i;kU+uZ-6Q@${lT23;xzd{2o5V9dNUMmNrg5{|6Yfax_wao8`wa2t zYgVhiTy~Cx@B32cDHP>vJf|u~AHIzY_uT%5&U1bzkCNLOF`E&6@?@21wFftM8r4LJ zQK^*oc2Z1ErSg1wTcX>v=<@|ooX#*t#-%NB*?E6CK+<6BdXk2_Q(1y}d6!Ou&4+i$-uwrJ}$G@$vsvQ0w= zVa(FbwaL+0uIvNlwGS-9@|LZYgmhNT_svF!+FLkh6b66v5a0hkFs+L7hR#Xw$&)8K zZ!^kTp^{6qvWr4sSkzOw6CTfNwyzrpro%2;7FUS1M5qw9KZ~R3Pf=@Gc8B5^&!QygjFT`9C?tCl4yX`RZbUw2JeTh(t+gD#vMHy_$jXXB z21s=)JL&Q=ILOGp9^Iz5MqI{0>an9V+CM7j|E9Ot6&TuP6v9SD1O!f=y{KZjW^F9S zM5Ok%pw@YJH4 zc-Uv=sEn^zHTRb<2|d^BO_$%E*e&v+FnRV6-D3Dk9a(>vyS7izgepyesf}hEhVsza z{y1H5Ut4`Zr!wF2^BO0nK{2i}@y^WxJCV)BIa(@+9(1dShBm-oQ6HVzGtO?zr|GNg zR5Rp#8ZRqcTqCe}B6oK1l$Nk5afr$I)vmdOl3VW53HX|egyKKpx z-xE7;xE?LJGQ#Xt+VI=H86{q**cx-NJUO?i&Np)we^>FrF23NuJtoXs7EAavwc;cJ zZWI@cbf>Oa%av^piw)bTQH&}M2{Ji=36jUs7r(tNSe!b82>Jb26915HUYv3!%67(w z#ylgGFHUjBXyjeBPiE@aH)hPAQY9@9Ox-2@t)<0W8`@MiFBH}08)*nY4bo6B!VL z6S9WYGM{Mwu(GyHNGvO1*a3bcd!lm=+R21jnh=h zCkp{D<6IT0!L%b%?08(a>!qiAcCFQhUh|h$y-oZgY_k*QAC2szTc$SUX^Uh~TQC%u z>FOTQwEGXxYe{1%Zt|Ip6$tkeP&~WPFgi{wM%!#Az2^13c>Q83jI=aL?&Hz#0=$`F zKw-+OdTgL{2oj-G>4Rb`I8~Bfme9rBcCH%+(fuNscRH$cC|O2ExLDQHyi~Q2uf_BR zd#)ef`Mm`PIFCu={#?`6$4%Q^%IXjXSpe{kj`Bv-B?8YYsHOVg{=O*E$vN{B4J$@( zkBV@>{@cE-SO5Lpn8b>4&mx^26O{oX{%B}jwZ?dD=@|$m0vg1?;mCRv_#!3zUmTh0 z?l7u2+8AX>`Z7GEkr}YJ@u9v62)=otzH)CT@3tnO;BlBM+i}qxp7?evSI)PfYq3Oe zPf#d{=Ju{E1KF8gZ~3u&{ZHL2yT-m57u#P-w$%cHN^1^g$90MxliOxkd{1k0HHEA` zB37>EuOua)bnldX-Z{N)ra%A#>G+ur)eK3&+g!2l_36aQGYiQ~3S-x$*5Jg$R1u_- zdinDcFOCNL#3%2V!&XUnKn4A%Z!C95&|w}*)%g?Jypg}iJJ1%iBOQb@XEm0uCB*Cw z1AkG62gn&W2x6gvAc>Ih+rqy?_`aa@$7hU{4gZrMP3l>7R6w)gp@Dxg>ao%h1wnBB zI>wWfdHYh7>xe_>myGL!kx6@nOB>~9bz{EZu|i~jWcC4DUg;mC zn@aSkhEgD#_gT$o?hS!tmPF661ygrgDJ4w-I38T9E5g3SpY6(Zu&p(42W~zSN4YvX zdAlt;&t|li#4wH&wM~t7`f3;5n7U8QgT$PgS~T6H)%pI;E8L2$A;Gha1>$sOMx#cd zhxRK)wze(<3qD8no1!Z8Qf3lXW(O^je$p{#88u!QB}xP^*?>ID1?hdZ6(uFbkM9{1 z3)^hOQMVn|{?l8D%6<@jhTSNny((x`QHYQ3=r9o8T41&Pl;WLL@o3|{dls(;r@Pgf z*mIV`52%AH6?zJB9g>Tk)!k&L<(@YB%niE9BF~tl9d-K#nBxYeB$f%b`rIU8RAfZf zN|~@Czu)*T^zFK!vx%93Y-z(^$V4p$F3iq0+^;@cqLi$wEJ-4Dn$6x=9MjneMy*%; zr=!NxI>Og7*1j0{&p~?teA2hi{y)mTGak;b?RF5o_aI1=5H%r)=+TKFYP1m{M33lo zBD#o9LWmZte3Eup;c>9aad`NNo8WTz&-UPkq<(>}Pn4tl4pdkVlnt?@ zwe_E9wAB$10e=z)( zH%4e%6dsB4GTB-^uy5GtOXL^JB$Zt805yLS%b`>k*)+&$yeee!P8ULRz&ozQah3ne zh8?>pu8dtDx!UulW(#LD1C390iM4nWQ;&^zIvA>kha;it(>O1Gb|*d?=}_HKx8 zx0>6Nh}6$`PJA>H>MiOY7YuKmAbJ8MqYI5bziZUHqBOs}D5m4cGzm=7q-7llKDUwT zpKs$nb;Q0CPlK)^aHdD|NQ{5JoL9Pr$IS7Jb$L3Qyr|N2Hkx<}E;-*2UrK3=%JAZ7 zxHDhCgCtbLIklR;2Hlv%(N@J4a>4!b6dY_#! zja1&2(Y>wLP4G$TKFgGgmBBV8Ardk>GZhZs3ATM0^d(9EjTq;tV(ZVLF$~d(B{b|N+(e|Leq7!uY$WIv{e`z5)$8tyI{@iyNr?jn zjOU|~7n^owfNNf8XlQmMlSEnCdvWX8D!U}Wxuef_r~jZ3%d)E8wd$tAynK9v6o{l? z_-#_-D-SKdgt3F)zut7+KhkW3b%xwpFCm{Sfga#*65=g@FSE(90-s0FELbrjb;B8O zqB?H-{=GgAs_7$=?1prKVznBZA%39wDaiO&pcJ3r|JId`?SQVkiTR_yzdTaHD=gid zU3ph2%R`wm@sP=9CwV4vA${&DO$lC->!Hmhx;3Z|C$NFlk!#!woLd|RVl=0;Cb2YV zS2pedMf1SYbNw;hUeB{$7cEoSKlrQMg+5oBhpN%=N@731#fFK~f~|v--4QpXlcOKL z^}|K+i?HwCZQDMGFkN?EQK^QZ0@dVp2dol>3~%V4pKhKT2~-yh%$BO5tLUr%r?4{Y zSl8K7SNbdvu}(bq=eNy6!(F{$>7+9v7gki}4%vjxvSGuVON~>TG!GQ(#)q=g(xjOe z9KflhzT$JRDJw&H)bv}?yc;+M7;R~m(JNqbUwRy;Fy(!#6RX6OG)@{Lv92p6YbNAgvmO8Dp zB)Nsf&lzsNh4-erOMJ2*1fAcZs|!kw>H}`<-Q_f*Bq|PfBovIuBze-iHxkym^6v9 z)cageVDpI7k6eZbZ?4Jb>K112&(;NJ6mMV%GR-B7h4cv}W~OhA%jop9Xt-&~y}J(& z@b#!s9eZC816VKxXMxKdP_WVZu-U8&f1cv_Z_u?Lf!2&Y;6`*Ci76}VY_KxyV$3>KGv_YT2b;OOgn7Bv>!~MBqQlmbe>My8lLHJGS&s#?zrg zg-W?x525kfn_np`^nXv5Ue*cFQB(V(iPyScXY$y3$5XjHG^t zSF7ii-_cgSCo`>~9X{=et<^YmB&q`>y1ejW%w1 zG5^s5NEPXiZYGyly3$J=rW`~0kjxY~<*ih?FG1$4qvZptV9)sVrJ@v*2}xgi5My{g zh&gAH8KbB(eso9r^ms@Lu26ju&-}!(`Ade){6#x(l<7FY!X)D^*>)ck^UpRY;}K{FZ}W#US}bvQo8OrC+|M;|#Lm(`52dVj<&F>Vsi!hNJ2?{bb=oJ0RIu&XF_*yFvV z_xqr5FL}kcOR5%AVj&8&e@>8O7B5oa=`L#*edy;ph5%%<7nA;1HQ=AaT<Xr)Axac|n?IxuN z5@1SHZqs&xY7qZ4yk10!!jc^=D;GF%vs)a!wa_8B;p^o-m(1LL+@*GBpj_FMFFihO9Q`|f z0Mn1;y_@P%<@5X+d4AO|YlZt{-pU)Ym0X()swHbL?bHy}!~o&yLS^f)P{!b%cSN36 z&h9&v(|elzi2{5;n$zbezgLm zu$XAQ#R=U*9@pN_(@IPxuOKQMk$a14%b)63`%3iACdP(Xyw2!QN_S9!KU)E*hI8lA zCeZ;X;A!|x9Eol5f~stPKd@hKaL63sMXLtnKSzeQ@Ealn7uQb;x;Lh4Yx1u-8lhef{ zTO5KLg^_5x+!2Ke#B6tYIeO^oJcB{fY+`h@%oK$@bX%?@RK@kL3T@4~_hWwJ)}fO- zkfu3}d{UL*4LjCnd8 zFaS<2mB)VDt$1U(?&HZR@V4Y_f6~A+#+xen7afYAhFi}a+D0+vqjdav8`oP5A4kn& zWmrP{zl+A&<399$;oI10PWxIO-Eh(EWK4~cU*%;#CXiRKni75T^y&Jr2jb(GKX%My zYqLN!=L|Clny-ma_i0pMnQAWsfSsPQpOPA){F zFE`f-6<8{3ePbmCj6z(*?2Zy-iqz1g2S@h!%D}VYafvw` z7_L*GV~P^~vBvtcN;S{#C#KAFy|4 z%`%o&)AYX@6c-essb2+r5@5@CAU&K;$m0gDD_+*4dHRNWx;sMO@RswNA(KQ-a&oc_ z%xe0cY|xyHd5I%HE0Dp!c-eRF@&*yhZEs|sJ##AXhu@|+XbbNW-|YAU>;}FbO#N!3 z?U|w%w*7jsJ1xlij-p8i*Uw`rT=Gzco1MLbXoA9p*iRXb^SJ8I<2}8F$7}k+u6SC~ zu{WdLBq@5B82zjjJG#0$SNHy@M)PPdq0fcZBm=S@)V%K+k=}?F z^%(EmG3kBC*Y|XHy1eTjW2X1CdO#o-YXFSbc>4~w$8@R1|Kn5(Qv-JQ{{|i7OC95g zJPS}oNQh5VNx|wH>(A&P?%s^gYJ43s zT6u_*f1C2%lSyeMl?&RPub+JI=+TIOa|zSOQGuf+UQi8gql6jzw%%BbQeI5Vq^Wh_ zhML1(H<*B4(9Cd*M2|k)rXkP~@J;KaSWt5H#;ynhlaxW2hi;?;aW`T74C9)Gj?o9t z@$Qo%HCIY?U|o2pudlCid-UvM3)BKNT`DP0ZF=Bmt8Nv8c?z`>k zk$v@jp&K*&j~oZbkNR!~jvIi4IQ+#y>P51^=%K48bmfR6B;}&LI$PfNsn>%TT)4LH zV$FohM9#t4*rW*OyZPedMh9IxNe44)t{O3;3P2z(C#wYJaQsK7vrUEOdh^U>oJ0Kc z1M64d>SK<@iHWMm5lt9|H!U_uYRcOM{YI~n|6n}^WqD!h68MJMf#0dyp3wXCQ#>FJ z6^DdLriIB_wpLqnn|(XYjfLb7Y6oV@Mk$fF5+W4z#zfg=pmX@Fs^-5GnxT@_GWD)| zD-XIpvK!}oz0JUos39LHx#6$;;07bdfspGe0~jVdF&?Xx&H#SG)TVP<7{IH7mD@vQqt0UfcQv z>d^U*{tq=#!Re|xvy^#Ca&i&(9veOG;~wC>6~FfM`AqREv257rO$~92q5zG5)9V*h zZ9iX@Ln>H%>t@n#%c1`9vY|FT&Na^G+wAt^st(}7e@3iU2Go=(q++bCFm7keOejo311C5`$TGyRsGgCm(WvK5Ab zwXYy2XMX6DAvNU+Oba((fkHMDvxMguzOXR_?kqB?Rad@q0rU%>Ai*gqDdl)e+Zd9^ z7mVEu`VQc>o)&(S2CJo&l^A8n6yEj4)m6^(uMh9ZOksYuZ6#Rw^QXuvga5vI>YYz) z^}VASNxnc#ko&(g1~*%$C6G6b$$>q4+&n!_^tto8^*!h_nS! z_5uI~p|dtpsY2}B=YORpo+k?ziThZk$|acK=Khc^#m;OXbBR&}1qghbRNu?3AV^o- zEq7vyTWxP`0BP`Gyg*ON70k*0p_2n|?dRo^;?G2W#uSfG;}YDj=V8kZ`VLb3snn*} zcQU}E2it1bsKqWj)abobB{v5@hwchH=@*k-!or{hJu~5&P^Rqm61Jr72-E=iBd7G0tqau2wI+D4!;V5 zJ2V_Bj01z)`$VAKDR!p!V}^Go`rt3Rq&Q)}W_J6qi&^o+eHi#t8E?^{>)6bY1zx(X zbr@}nr3=0$;@r&yPvkIy;3U(zj>-4ipnHspPGun>A@-u8qJp4f`)$B%Euzaa1$ZS; z5Nm!i(*MXng+%^|{F{yYZ0$fc&6erm3!(f6+ON;=Cfb}3Hw3({kK(8=@5#j7H2lJq zR`N9CwzA9;Py4r*bbx-A7zKIHx25pm^iem%#fI@2v!qn`0dN zVfJc`$S$M&R%-lmNtyadK@c2Jw)~h^cyrV`}rYJ-Zl>Yvf+rsC^A z8$LcIvwN=DR!Y#r>ujm>xEdDnj^zs0~UeN3_g$8y$pLKN{7? z(7kI;6$QR;;(j6f@C9<6RL5?V1581LDbnT|!)1F>>Lq4c7$Nu4i;o&G_{TC2={Q^B zeArJXnf67Q{E+?=>Q4HPO|U-Q3;0BOQ;acT-l%4l!aPUPE-@|gYBMvkScXMdltnM7 z4A9IGY|tfvTgK(DhwjcwZni9fj6yff+%6QbSXbR7J9shh2g@a>25{iQ9PEw=1{Fq) z%Dk+knP*J=w)1i(?qbXZ5i<~Ivb}$l^haJaOjO^ma~I-=ReBZ$gU1ESKDM2D2yuEx zdI(ye?)^$XVM}@Q@yFUT%WslqDg-lg?n_JD%?J^sSF@lgHh6Mrbqsv;wouvDF_E8L z-6P%S;lSoLjL5I(iSZon&6<$@C_N>9_a43Uy9O0fxrElq^Usk_vFR_(>h!e;^N(!m z{o@ctPVY3IaJ`gsKS4;{FfO0A}#l=Cx$3z{*cMZ}fo*Qg;=|^nR%&J)U07QUB4VuzUcT1EXr(4_643 z`1I7$O5cIF;1`wxDeWV?!y*0g)HWq2Ad_p8HUk|H+d>tiytW5q0fTdg=|80!&Dy4{tJ5%XoCH1!$Dqx>dQ)?dNf zeEGWam%Xy4MldMEl&X1Ww>87mOolwKqHNe`fjZi_$Z33Rd%Qqb>{YJg_gSlr9qc3H zoe!3aYDyXFnJ?`5|L#>UssPzq4uw2b>QAMGB7-ztyDMqs=@lUS(!-F1pU-_5y6@lo zjVeVy&U*TIV@R>B>LYA-WY)fZj}u3jz%SZpKQmG?|JJ4|{%jd&Fe~>19aTC@SKJ)2 zvX2i+;An%78R2gpj2H^D4@kVf+N)-ci(Ow48c5(ZRMCK9htu$ShF(4)v+cvRYDVat z-x5TPM};hx?APMgXw#IO_-42jGZ3<<{z*WFtUe6VIF3WB2u+XzZA@8!ebc1#q?)ycW}ltql$UBa4; ztDlP9cRpWug`J#ooOF!ED=#1fGZH7i8fno_b5-1aWY&)1r*N9|ol@jH^X8X#R1%{Y zL1K}%s5Xy(Re-_aeVka9KEmI&I6S3jf_<}as=&XK_3~q^e;Ne;GXFI73HV|u=36R6 z^?)pS(sSPY4xLzkix$uP5T3It$Yr*M{NqQ3Y;o8ljrDmf8B@^crryKt5mLx7XKCzL zb)DbUlWk^nXiqPSJDw^3+P8w_T1CK0y=EtjeJ6+_j*W0F?_cyqH)&rY6%ClBJUN%q znty0NGbR3FZ=hZtFULI7miC8ZxG%3oj(=zs@yoT2m83(@n6tK;(vw_Y(c*};sS;sf zquw2Bz)n7u@He={H#I>r4D0E!o7}=UQBUrRoAHlOE+=QA)<;BsjFraXuPnKj z2G?J+^AeJc&r+z;vV1d)$^R67A{bN4cv$uZwoR4q8qlO4^R$PdkjM05$?i3Br^tz< z@e9}{I;UySfUGjg%32!w9kB-d>&^c9u6k8eJw#RN4r%N}EIU~3Zl;;+&F~l=S;nj6 zjYn44FJhnRm~FLQP&-DBWSI!mqy3(a{OssjU@Ge%uC4w!>5B7^6ZY4#?6`5R5cEB4{D|=@!N1?St`dfQEJ0 zjnrkESVLHhw()G6&B1096WV&6KYD7MN9B!Z!953CcdXRo)M_jgvGk~pMXN|TgQX$T zu*5`yoGuU5zvHKB2={HQal)?UEdnZ^qTd2kUS`N0l(En2)=dK~DR=Io4Mr@zM%39D zbuYD#u*J(j%g%`1e(=;+{oHsC*lb7!7_A9f;~Qnu#lON=&x;kzjh{5*<@u23y&6T` zW>0L?>tl_8>{r3on&ZyuzlRW~r=15hBaIP^76YdE6x%DOqVeJ<{pI{m0YAc69MEs-qwq z?^?)_P!~px_ZgD{Mcl8E5DAPlos{=}-vhX>5#YWbg1v&T0YZu-(6>8=_|0x>b8F}{ z*?-h~$l}u&>WO{w{AbcLYE5`=jIz|y0O@5V;Ys`ku99)z>8BFqg<-YIm<&yW&q}ri zxt(9S6HPp~BJZmuxhLO=^y9sgCH=J-3Uvin5EyU2UoGM9;yfv_Kr%E)6eoT4s~H*D z5wfkj+WAK4_uJaf4L(?{kx^}}Zt?uPpgA&EqF305ZnoBa?tg)nrRt#7tbxwY0=y)AgS^fzPeb zS|Y!pucv9q8W?rxbgz3!uo#>J;oU?pGJ5Im`)yPd#5wAARGUb$yyQ zjz+ggBo8GEmak{N`H^zo%=*XPow(HcVg)HyU%d^2J9iX3Olb}{P4{Z~UrTWZ!Dkdf ztW5p2E`=1rQm9L3*3;Q|tM2QZ6z~LZ1*>WEf1_dzo55ns(a=%6G|B2B+wy|tGp3g` zXmiIlq^m#J7STE3e;GBZX#6~BQQ)V?*^Hja#ZV03M0W6FdWiq5qi?3GxTz`#{#9b_ zBiTtk7q}qi7UVlTjCYyewJYzub7Ond{u@O!`Uz)0f#XvJD@ zv6TDOT5pNCR1+geE3h|;^*`R_1mF@c<2dS)0DzPU0HM&+%QQDQg$ldEmZ@s=IhlkR zO?Ky~P-R}i%c52B>xR_)w_{0XW&!?z-fvi>JN>< zSDS2Z?=sQ!CmW-hFpM4e4GP;YUJ;6T%R+yu#}=DgtnDmRnMBTuRVThhGVB_!9KOO> zqynd0vafgLkDCu1uWJoKsF-3G>NKYeU&>(|uWdeM?u{MxyQ z@s0aU@EP^rYrrvIw>b+0e&q!rznkhxfWv)}S>*vb^wW3M-zD^d(bpfUHpQumjR=;S{7kd(5{{PQ@h9PL2%(2BIazT%dt?DdSoqpq^#qZ8`|I~S?6fv{q|UQ z&rKXP6>w^7Fb;IEaP9=&=eHdVcbZaz+D;3qexSyJ9~}NHly-jrbN8xzloCjwgqU3C zZmmpUxMCsX*hyvYe#OATQ%*)k#J-xg1uaeysoKs z_cS~g%8n}1W8G`t*XmmtYUizQAA#S0k&cxt0LJt9CaH5F#TQBQQ;M^71nn#ySv4D} zUhTlWX0^h*Hx+Ywr0;?)4#1vZNl zZ4ihH8>Rd9?F7;Q1qQ!4c|s9sK^KQ7OoUhlVX`oF>uYT+7e)Kp?OnoQ+B1^1+PjM9liUIA1Ljve5~D=ykYS+o9%G3h!)bZPYZ}*@LSEjs#9 zn`W~0?;emwY;__kb~9kqKrm=@3kroOTZpPjH3QC}r6Yq`jwskEtK=ntOHB2}$tpH+ z5yUxMGd|O69Np8a+DlEb7NaG<7(UP;Cuh4sBZO*nTyysQf);WYV4UeE0n1)l5Aa@t z!hpm>$KYDc5cy%TJtn8u0aPZ?O3x|vCGI(7#T7?Bt5lzPC+(DaUqY%aq$oUsiu zpE9)9x=p-G#`KEXJUo|f=}4a?_v}==zKL$qp*syH97E7XzCUr`WXx-@`Gtk5tZfCm zAVWJCFo#h0ZvgyPiIHBm^gKv7Jq}S#KHyD z3f$d5wOdWSzWw8>VG08;<^Qs%lt3@cc#(Z0a8LOCLElt>?$IDo_;2C-y79Wf9Sq4a z1Vk`nndY*v8aS=R1`#52zLf5bh0@K`U@RD>W%qR|Pa!NHCbb&PP32)t<9V&D`o=Ft zu|iI;$B4%LLlz8;=xNeRlnmTP+RRFZKMczUH5%CcDq-Z@K7U)33q2{q_B(u{_%~?# zQD&oYt$_W}YR_7>`j4h4-P$M4dfTVHV8vyD)dNKPxM({n%t5%ZOtPgzp<`6& z$7v1^^6m0idTG~q#*6ZW?pf16g}^d1B1{f%pN5Cew?Mz3$73gIhi*1Hu^>2KC;&#O z@ul|Q;4iHHL3;zdNWg+Gkrn2e%kBXSz6*?O)&a95k-F3f1G%A~DW8>F=5BKgGk+7G z%R-(!8U`83g(Z09abbi__>-}Nb>tS^l#b_<&XAF%`V#vD8yQ4QyCiys$sWu_v2xFV z-nUU;H*n}ts-S^$rte6!7&3h0$>n73*r0V6h(q}QjKlwp;^mxGqa^Wf#`WbQ^1Ei^ zaq9!)T`q(ynQ>1-52UuZ(J?mD;?07t)H;ovvjSu5_w$ur+^21h@zIVR-pl_o1#2pG zlddSJYrbz*|55abg;aEu+P5s;kG{Gb?_^IL>?Z$AVZjzHv@y1q6L;-KA}-~-QkVD@ z|9WyaHkOowHSRI069g}21^L7Rysssdv2D@x01|mKZH2I={~XK(2;OA|Gkb3j?w=*R z)d(2?Wh6to5|dswr~CbVUKGtxj>(4|1tTV}f_;G%z`}|1Sm^cn-0v(+Qq}~L^71f| z)#mfS;x>=Je_8PamF*^lLZaQKU-}#wo|@sBr*T=tBaK$LS45k*^`9@aBiK5Rvp%Kg zLY*#a0zr;4;kv=W8 zF@xPHeJ5Q}RPW!dEw`-;aE4j!-IggZ-Otza0E3pk%{Mx^HC#E@QuFAZNmuw*C=d=l%7@N!Z!GWt%pgU|Y5O&Dw~00b}ne^xy(v>@kobI+)6LL6oY z6O)5rA(?(|gF@dP$S)iTO?hbLe(q=0wT=I%$HutCq%U9%9ARp9XVBqLxMWe$+nOz? zfNR)b6p_*KVnHpOAD>~k-a%Z;V-T5azj#g=`KDy1E2Qi_wp?LO?whso!>c;sFshR53tK0EFS&T{Q>qXkFjI!$-U-2obs(Y zN$taXDgS|1CXOJz=64f#&Ih*E`wT_D`XkW?<0??KtJ1;rPgmi9D?0Ezq+lPKEd0H+ zRP$L+FOmC)lc;z6ay+2bw7^tdp9NUTf!$^84H@SR@u>2Si6ewyEd7@jsAyw8#@ua* zftX@7HEG2~$q1>-{aSfS_k87@(LdR{L}TgXr>2mTfj|bCv98TwSYBBKRuk8rz?cuD znDtSzfO4`}RDijMkP%~Zlr_dUp#sNRIwMPD{8jd(MJ90B6$W+7^K@|am**WRa1&cS zP+XPfFRhsVlbQkAD^V_W$sv@2{T5duLg&Ut*LE@WyffWvzgDr(u=)kfTYR6`x0dl$ zcN$GNRy@yST~jkt)`e|N&uRPyuTQgC4)GJ|h2QbB}#af$JM+h`?tVgMrY%RL$^#i$lgam z&7@1HL9}V8J+2VcRQk1)C1V`wkF{&IFR$g|1xct0KQ49e0!e}A4rT#vn zUMQ-}&1ZFu9C=e3=(w>5)`8q*D~Zf2gzhy&2lA#~{<8Hg#;^`flge<>!b_MF+q>A; z2l9mHMk%Yr2Dn$m6o5YvnZgGd+4ww2`}jiR5Y^HjG0i|>v~Fd(u?3WR+ktq&R#eTM zQ!iJeCE-2w2>pZ`%_7aUdtsx{0I4?qWiHbSGqJl$;EZ=aJO4S`6dD>KzmJ)B zvOQdL+<98SrCn&W*S#yxkmHqPFtOGj!nC*TwpeYc*P{;qdu@1xd1g*Yv!rw62(rc- zvMua-DDMeatk%}p57--NLWvY>!o#1y*%#Ienv*u&O744Qj`GHvKV_qBN;VG{xM2x>gBnkF3@+giD%_0^YK|bUz=~TFNWEy2CVi3~NQK z&F|Fd&R0{W@k@RQ^!apWp0H+bpM*oMGB>tjO`#5XXeDzctZkugVMSufvE?rK8Bj&A4a_EZ*}1L=k8j`nZEJ+%tQ zTV|?WtlS>|dxgY-*;@I}g@BX*l@I%~>;Ou81c}^wgZ9<&moC3s(~p6Io64ldaXAoJ zv<_sR&Md3_;xz|>7H(JC#y0wn;%`-(oI6RC&fRZsanzw~9-lg-1@mDUAy2R&I492? zB_iefv%)_2Tb1x3h!wIPO6QkB;#e^5>@xaOZ-rMrh^=_7wjWc0vD&RX18KwPBzIxh z%y@AW^!LL@*r4Z*IkF%}BSc~d;8a=Bqe*shPy{J&B|ZV~xu7I^i$;g?m{i15voT1` z%}?UPvV+0i!T#i{uqhv|H!F8sFsmEuUE7_N3M9K3QGpii-Q-wLQ$$@d5QyL|KJV2Y zXYbsBK=A0c*|5xI2Ou+{zt7ITtj3c_ro99dgd47VGlA;F0FN)Bk7B%E-c2b+y8$_Y zoPj}-I^$tS`p;%yyuF6qqiKztiQ>v|#c;$>Tw`-M-SU#|;sq{3uzVhXCjF9^8SiXj zM!ufzO~37P@IaX%tzvhYPz-kMn9u(_X>#P0yQYvTvK62{kJYUy}BS(x~Uqa^Oj-1huZ+8{t z*w?AaAHH~E{IcwMwio>gc4Et)4#d~~4;mJc?rZ<5()&FsW!~`gw?Dl6t+(OjVQ{c( zXjoX&*$E-6xOz=E z32Ff3FoxOL*F4knyH?oE(kLI+1i(OQ?;;Wnas#<_dXP+)(6&K8 zSoSa%wb7yZzKYZ%eX!~lOe*w4kIQN7kwHx>r|~s0@$n^Ivz`*J2XiI{_sO+E@S-TAM^Q2u=qca*SZX|vn=KhdbBuYDuE&C3cHtcmgGqoSoFX*DWy6%I z;JM4s#o}+Hfvpi}ff?i3%y3(SHcj?jI2q@rA*?gr?hb-F^vfJ|KR!Y;sL|5+xavw6 zhr5Tt`?YKR*;K5;6WTU<_8ixSS}U^`8(c1~_uJc5&_h7aWHuh%$X*2%*V38=mZoHf}eH{{AAU5dwEr`ttS+tjdO#r>|vT z6BtNBpGQnQ5_9o0f%0-gG(WWrPU>p661aZ$Lh=_i&@=VChs~#b4{lm3a2M;PL_RulC7!2QkEK%yG?mVlI_oEaD@jXDTkL?l?e*O}bs zy#z>k3^tBTL&v(2WW+xOU6g>*R~K+WR===#dtw1_^yXHG<85}hqXUCBPl4k^UgH~B zyLtuG-@> zgFD839)kOsh{`7`-8dS(lWbmIf#MjNLOH436mU$rub0qA6+0mx5gVg9-| z$O2w~8Tm;lp{)c{8bH%F<7gtz4&Kc$$mIB$2@^55PU69bU~z)nC4LqM3}5mVt9?uUSQNlH^Q2JG4V-fHkzK^W&UazUSe{rD@8iHDrcb-mSS=T1iTpbp8pZ>IM5pwV%Dj1Bc9s}&7 z>;jV@rSxh9GFmZJwABD$ZUF^`equMr!A<54<`&1~15-3L;wGmyQKhw}&Hn8Vw#S)b zgHk4J6m}Fg65CzwgkRj-VyWN`{%{qhjyD<6(BhB0)Zbsj<|6ORhljj&V`gH#2PlNu zcbC(l$}`^cPO7XkChtDb{MB{Azpg75ldZ2uBtmT@CHO zfy^fSLGbm#7%2m=6oT`?3^o%?$%Bb=oyJea@X*>I2K`Fvv? zaMfU94ISv~)VpPXA=V5{<}kjA?sW725iL7`R^Iqvlus0HLIo9=_@;d|vY*Yv3QOe*T zmt&>INr!jzMH#C=xtUqXTDX+sb9N{C1zFhNogqzQ`U?43TT@VGoh3^p0aK!%|8FLD6#IkaKd+LL z`ky&5z-j~6c6(3_!{D&SQg;|GuPxKdTpA~1yj;S1oaSec*A3)yV+ZQm(OD7U9@wjF z4xrXz1#QR+Ixo|-;;#O%QDW<=AY>i7IVG9VE-Znpm;PSlQD{4&``$w32ag832lOy& z)Di&3gj%ojeY0uB7c>!1U9+`6?yzh;t6d2OsnV|SRJjB=o_z3yQP`;1CG(4;wGNIS z-YhFCQ8vH7S&U@JTf-zi>S7{uc@P=Ut;-*){ee$yCXiC&6Q}UrSAyqlwsh!A8SVX; zn+z!v9K^G>*y;f{2XQ($h)r_`-(0Ft9c% z9~5}^ls(|3cko3n2kYtOYvb!Ouk^-qUo?T+HOh7pcvVAZd@AO~o!ChM!882e>>=12 z>#lCwBCps7N`E*doNkX(Mo0G=rPkS$%6|fvcZV^GIcoI~|75s6DPM_ZIk^_dAGdq7 zh4^-BAMs8>Xb2}T^48zNxErDV6Hs))1Gcp2ph@3jYk)PSe}c!Bq)5*KfMX)f1p|%w zayuGR4mT5`&q82@H9mhYjc_9KbB#`$L8FzC+yOoBuzuBevyi(Wan!!uM{3+ckO7_;qk`$Zz`XAlsWfh$UmAd%Jr$p6jv}v~pGogdt#-;PVk*^V*HXO0X5wVv#tE9HxFU-rGev|A2vklg=F%vVi}VsB4E69Ljvlwx4((81U* z$Ij83=UeOZZHv1)Yq&2(!4D?L3-&OzR0vxR&H4tK|!6os)=SzKOMS{KsO!}-TkL$|9PU5$;F~^^ zQC_8ym`oH+J+ZgsilnKBX_=axzR53gvMLlA#67*#C0)qR{4gN5Xdq-+%M5!d)S%O9 zAUaBuB%Be(DI*R~$TznC5x7vq5b||KndRxWFgg5z%IXkypG`-g8Fxoun2r2;!fzI_ zdc{a4YQ@jD-#0T({ghL?fC5jW8E^&3Tnl1y`wtBg4Mh5Osm?-E(eR^mPL)M*l}aw1 z;bBv>@yS`*%E6jset7N+O_vxMskXm*T$-AiE1yUu$wcOzwNig+eXqYwd5K&VT$Fy|U|NX$Q{?eXaOXtrN!|TYpS58P`SZ+bng&+j7=+P5I3xo(#rR8Ebe5kN}fyrCvk%losziv<9 zOPrZ2gd$j)yR8id1lv+RR!3Mrc+1lpSc1MQ739v*e=X$JZ;-Cm(x^K<4x|okijVJ} z;w{gRxn52?BP3DBN;h74#&;K87sGp!*dubUin|4fEN_Fx{1;y=YX<;)k%9*e{*A5h z0tUyw6tRO-AA0xSL5Og^&_h)Zbo=;0N=t!NwbxnYC!}N(q9Q5f^Bg`-89VuP;_eD+ zH|<;;CT?A!XdT)ws$?qnwD5NNd;zhuA^je;7*;EuFxbt?byoe+$Y0T z7Q`Qh^9wy6czqrr99a4ygYHnZKO9sZ+Mzj{d7l3aeZ}3>Ox=P9axLX_IsUbqwfZua z?9$To@w=Rd_}B$2OJyp^*Q;|!9iy>f*&x$6eu=BR6(tcXqT8}P7pYzVPALq(#Cphq z3tbo!Gx#%0_$t?(=kJ4+<}5R;sa&wJ28|o7iA-4L*_vOv*_>yye!3s^HY~D5P0HJQ zCJvd|zK?96O8J6UTU!=*bg~rX?$4C$BxVb3r8M>?8Dv<41VFhQ?1NJ=(7rYXd0mv$ zPo#<7$8B(BSlqvJRE|JaUPok$D$Wt$Yc6_{lmxsWFX;Sh`l7hkFn}yHrP%BN zwr>ldnV#9bL0G${6JnW_`>WibK+$n?>c~Lp z;{8_-bbSq&Fgo;AxHRsj&VXSf~`01K@iz&#q?=vsawX9@}}&RJtVQ z6@)779EZ@>rg(z}(9}%By%q8eb8|-7$BPTQ11+&~iS@WHG&zpp6QwuDUkTI173-#- zQa!Wv1)WY<_9h>DM4)#*n-KNP7Y%nD(jgdzK3z5mFmNWWyOcm$5gkv;S5gm`l77Tj zrIbnZnjd|Wbo}I{#+TMWH{Rk)p5svBmW3Fv?DyIeehzv!;ftkt93Zt-07$XUqFGdx z4_$h~^24W5eR!K}_UElUGNd@P&vE_Fr{1pF4EOEQ z4>CjgXDP@(r5cTS15NTS5B@Uq?1)&4EG;%IO(MG-UgBCFqVR8TeqB&1HMBTXn@cx^ zg&g-Wn1E49s*_*yzIlf1{AHip|L-NbSP8;pe#cip6V<&XFPNG_TC4T37oAP1%SJ$( zhD=`5RzKsEr6Z7{teSw= zO%~u0zVQU)KB{qjHIP#NrLA6`fg{BMRv)LZ!H*QGLw?U29M&3SIN#3w9E4FNyNE=U- zat-^I8oHG;R_zunq%zxEU=UjIWbM0zbJ**~^^Ygf(aMYP!AUEyzV-xK|EWSOTBQZP z?ksKZy+Lt#>pu)*YLuCKF$cXDL4^xOzPU^S=;MXX#D((4?es!D#j{l|HCP*p!Yi;9 z0bLlefcHJsGdIs#9WF{7t9p>g2b>&=fmMlRqhDEl$Z3_9zCJxLFrx;R+Nu@oWj!^n zBRU|ws8I<~YioNMS2`QD&MMsMSox%C!(`7vYDw63!u;8ifF{hncBSO8wBSeXz?*{C zI^fj_x0{-QEGH=F%&A)oerL>3KNdOa(VP9pR;l5qY7D8i6doAB=_5zlG21kJauw@% zD?~=gYfkwI7_PW9M~sXmz%S)c{Th7}^MAALSqdc-b0t2t-~6lT=SLJ?z^t&j?5S7~ zX>*nH##cl00<4;ag6vU)Ud-PG)$ubyr*O&uhqs^qQ?UrXS^qhAJd7H;DOP#5g3ym8 zx=)~r({zryI~BLWJ!yxczSc|D08`FkmL8=`jLG6a0bJ+GZ!o2qWCA!V-}Bj-QLvd4 zeY4YSI{#Vb^|}CgpMxz&hrK!p*BT2THOUC~&@5nt3KP?v@WHX1e+* z3(YaJz?T?O=WHFJcP=Z3bE$SNPn`#fCD(hLu>q??A5)1q>mJ+GNt9c3-ME-;o84)7 zX?1jbPl=~ME?6pPBkNF`LG*Qs$N0CuquH~kPW*SU%oEIjmWhvhZh=?O;0I_yrA~+p zhx5?aC~h7eRQL0E<%d3LJ61=h@9rG$mJQwT2l$3|oBS<*8qCGt6s7OLiqTF!K?DTY{rLe`|J@zGf2Ti@I*4TFU4 z*({$^c!J1G;SQK*v8quQ(sM~$tUYV)eZfcyx=+DCo%~B5hh>sGSv%>!-r_La zrG#ev6YCcTT1Hr)d8yF3Z-8dd8?hhj6&A4lrdmFYf5y|zr@@{pydD;^_H%Pg|B}?^1IwGxQy4&lYIuVW`mM$QtbDu28+)a zVbSh0O$|=_5Ox(y$vnpafDn0n57i8^Ok{a7>vB ztcq5HfoL^Y9dAHQXs85m0(x#MAvc$ ztitgW7h4EgWtyx(1xym7#`G`$TVk!_pal3q7hSDS*6gesjfv5aSs6 zaMDerN7n(N^8y$EmSyj9iM`-Cj{(f31mGr> z01rFWFfB3FzPZQnYzmw)&R!ttK0RvzMxPCA$e^#3hD@WBqAe$dPWy;OFYiwl75OLV z4$30@r|V(h74oE3iinFF1-*#kV^Bxu%REtCrxdeTJ5A(Ub{#3v)?P8MuoEU_5D`*5 zUA!vpw`tkaHD=36zo8#-o^Oiwzg8Qf^6v0f&=t=aRmH%>&Ky8I$a~wuU~JZYJu!|f zz#rW6B7t5+0Q~=~ghLzUrHb_iMBZ9ydBmWgqDV}YXS0>hA($H~IDL<{R3hZWD`I_M z56IxjreYq{%uxtUjl37Syx0jJNty4Y+hn)Lqc-k*hDMc;cmMZ}p|Hi#dE2C@McC5m z?iQeWc-Aem@^RKLqHZ!=q}uQw5{j~gdNW@X3MSK^j4;`(%HPX|ycM+x>o40JcZyb&_KMi)_!LX{NwTBzN_xk)bPbyr@{RjM%k3&^NLaXJ| zXy1AG>qZPJ^)^Qn6^@tu9|=Yz=NIZn&ODH>Fs#+k9mDSwb8j9xlz$6#TCA5l=M9I5nvQNzf=T&`&LUo?bHGCrqf_wY3E1bqeqj zZLBlmwPu3SvLnL@*=IcUUyjM>u1*%brce9$;lN;mAN`Ol?Tc2^a{oRhI#)dg^vLo_QO32B2Hyq($sSR0gFM%Q0jk*xWprvF^yUPA-Y0kP> zsM~I)P=k!Ct3%Y?6wPpd&TmqmjWAbl;QB%L;H)I_?gTcEvxjA7QM2Jgf^i;#m;fay( zk9_l@G<}B~GbJl)CcF#1S)aZ3KFA(Y(sjedoXYPYoUOm-pVjkszBxZl zv10X<3=yL^B7zXS#b$yGVumnN?}XL#zZ6&FXh&HC3){hpZx|40 zhI3!!dVJHK3my}H69R@jIpR~8V1kks#D3m8pb@3G$G2gohX{pD%vwPVSQV~`U^JltF zq*6&5$&6O1S0Yo)h*QWMibNT_(@Y+I95&xh!0#YJvm!v+Dhlz^8q+;=Nd7@rqpuWn}Ae(X48W$ zsCDS-iAF&X>iqKM`2A?d2ihxcfxdnpQ|=j-+7yj8>>j8@3?1nwV@9e%A(m?Rd_t^# z+f)33tw-C_)>W>`?ZULRTOEDUvqBnv3wqzBXG6Hg@o0suOyw^Qe$zDJy*9f;d^JGI z2LdI72h0=jTQLq&4HY1|;$35$nZcCx$oCJ>hH?SuH~5je3Xfs-ZsMSi(K7>)qTXJP zll8sVST%#XfB1EpO)}?#Mg)xDJFpw$5hHDU4#gt`!1Fhs zHBL~&akn`JtTt8#C3FOm`MN?~UJemUvO z&z?A--fZ(qN}9nsWc;=CiCPoCd&$Vj+=q-vO#OH%<0%sb8AQ{>7Ll}y_O}8b5n-Mb zGV>t>a_CmJnrY(tuQm4|HYuv{wwy-2E;HUh>pS~XZoeDOWQ75PPhhoj1IOTF#9g0z zw@#wjnBIpRyp3Z^-|n7Y2q6GcQcf(mAU`ui^6f~OdZI&p7hF47vEL@E@y?Ic>)bPB z#~!sy^KL5)yrLr}B9PfbwThgxK+Z`$Lz~%X0$6UBw)FEok|Hx#=o97S^q!vYX!M;; zVqr2d&@KC0XjlD8%dP?G6^*R)fg~j+Ccc0$bMjI@A+b;BHl+1OGkDP(WoxYx#K(WP z-au7kb1F7}u|m}1zu`E;A5#GK&VK-Eis1S28*G6^>#vVrWl&vdsjOtJ2ac8j!1TGZ z(xKzlO62?d0p*ro9MeZ219?3o>mzuW(UB$rVkcIypXJSth1WR=k zL45RXvugs=hSNh~A>q5%XiD0c+gMJ>7!$kgTK&}5+L0Evkl zA{is=L}F}4Z7(NNud8tf(~KE(Gye?^Vf317g_0bALc$C;oqPe*9`7i}p6lF~KN`DF zGez+bysDS|mqxzXR;-o&jAr`XZ=0XI%?B-aS1?vLjwyRht=2HXz{&ED)J6h{Y)W2{9?gy9QMo&XhyLm9Qt$AuGGNI!*uaDIEir)rO0|j(oRvPHA z8bm5VE2-xm-H>=ogWgDtBKp-Ng zdX=yPeO_VH!0ER+c0F(*C`T8Vi#&#glVjHw9|FP=ImTW6_sL|RslELc#TBA}qpvLb zuNKLvh!H}6(wq1-3_e@ec}SjB3Z^_r+wzO$b$SImKnf+M-}fk@V8Sk&0aK!e7e{oG zJ8s)F9;}?C*WURq-Z*}`o&y|6b^uK9G5=A%w4fKxLqzX2aVX@qut=!wYC)>T)lOoc zTcma)9YJKt(|Yjf0ye{u^{!P(O&{@Zb~V3QP`SH<6>Rn>Ia1BG3OgmgFhJ%-5TmHM zG_~r`cwc)7*h=A{hnb6$WCP-0LmyF8t%zVABEh)hDL1fU2R|(K-Zcjume6V>X*nf< zJ?%w;DSV`XZD*bXuY)9n{gx%=6;@f(yRRg8C@~u9Uw8-P9z}3F=7Xzgl1Q$g z&MQ9`Y)@?|qq4Ve$>qb+^wO%uXZfB3_2;%o#F82xL+kcSLpzR&zA{+7Ez7ejcy^ET zeL&N=;VM-0!_F_;_A)hf=#RH}P{s*tp+uHxHAnM)p4d;QOcSNIZtjx_{ zl3hzSCoRw{)6&&?(cQ-e<^mex!Lg4IbqmFrBtiF5sL(0+aGfW@x}lYezNf*S7csd7 zWLw;;07ZS_GtTNibzS3UZ|fM#Nn+U1)+FyC-hh=l83b4=}d1myxozIC?i zkySN#_{j-{uM<{Zsp&AwCFPp?>{5HDi#yv)ke+qkG(u=7be_cyf}9pRlHVl{fO&ueNSQx7ugx{td2+zD9Z% zuRGdAJx*bn1X?8;K&PP|iTt9K5EK2V(jOr$QfNJYOy)Ta2H~yk0;fCO79`p&=D1uG zq<=J8+|KVI*WL+prp#ZE&DyEcbB#05rlfe~(r$tE3st~i!%kc#0KENpF5v-lI8-RIywX>Bmk`@)&vZnNCX5x1vQyy{ZJp-S zNQkegxkd7wb0J%Zo?AEW>~KSOs5?aoThDi|>V3e%Gv4=FaPCvpJu#;*go6rC7NQr` zrYhh{{IBvxZDvA`ZTVf8&Rk|&n*TfmxEkz;E?#~#m#ik8tOMShM~+;fLo@i(+L-b~ z1{BO>3d-=-G(sp##rBkJn1uR0z1 zG{XH)eOwnml=i>aD(OTy=BD>zSPkah$w;2M=C+t#x60`YFp>nqBxLQEMEy zVQ7bdi7$=-GBF;$2{BYhw$np9an~Wpj_iB%BWW144b3Y6RU;mV9uf=`Pt_9^l9Q4$ zT1AAeIR%q&KaA4r1ei59n#}8BCU{4?lD@JYbUux5-P{xsy999KGce%VwVxoY)wB69 zYYbGh$}pK<{s8SQ1Pw-2PZ7wlHwmz6w)jFLdq2d|F+&t?cZEqp{R#`==ekyUOQ%+6 zrnJ#`zGLUMSM4pz!6C)=D}@MTyy=z!-B5ErDW}bfgRX5dRt?@Y5ttm7Z(Yw5xL^Hx zN{d}>oX&3=0;5~PY<-?y|nh|J%WF2)V=~Ym;2Z2@~q|@ zNuUG9@*{UZ*O{OlN3OadJ#N`v$M?-yq2TT0!$WYUDy;5Wi=Muc-9rgMIvF)9c59x0 z|GsF=?=51?UprLn^kR}rQhK6}Xfh5{lP?mqFL_hiVC6@#2JsIyZ_NbxO--Ztn?1av zrj9B%_a%q?xN4iVhprc)Gz zz?^n+@k8x6{pW1{rEh;VLNT5sOI=w^LYVoZQ7n~iPV%*5;PLUpo3}b9lcfvw{CryI zc#pO<_TI^Nu7)J{4+x+WcOMgmpATlV7_B0>jhUFgwZ8WwU_)+{H@=U47$F2~M^iVU z@^td>GOPTl;E2~B=D%#>htC3-(dkikDZ5?Bu0~J$-?Tey)c&)fb+~SlQ**@oz{KSB}Vk`*9HaPt@0{-PgwQd%>pqr|D#ApY*^=kO=!ITe>}z;~ccQ8;?}4^ny9T?9^IddjWB{Iz4FQoz0X{{6ewmcu>RPbz;| z#u+De=5Gc94<-N{Zejs_$IgzBS=?R=2hAPrAn#;u_ z{Yk7bO#}Ibuaol$1V`O{`ZSjpXO^$K-q45(rnoc0*!mFduc)_6kGds2Xc2Jfn%NGP zNS2a)3JfhGR!{NXwTrNCha;?%%`yOwx=kb72`WP2!8Qi(!pWTBr_E3iZ(bDz&Kq# zKn8C@1VGV|t?{d|E28BaV_)8l)wsNP1VHV2zpb1!QfSXP0(7)t~snQ$L$$~qd7Cfjd zVe{bvz>o_Nn&LghL{sR9pMpc`k$Q zs@s*W%y&;d^Y{RAStkQL(mEdp;5Qn6J33o;eUD(qNGXe0i8YVpM4 z4S)d~!^$C*pevnO7!5VrssBr{3s_G&?n4yRb@5HMHILE`u8{(YF#_rWM2+c2sjof3 z7-7dBNlXi1Ug_{P=;Jg~suVm75SExTAA{+T^uV|^cG3FETnH8u$luHORO3&@#Qrfr zO0zigmZF0ZeTZSSCSg6{lqPV-?w2< z9c*QmCBjPQyl5i$hfwSl3BveRv+hhQyp*`&-fp-^mH^E=Mb+9g$4`|v)ttmI=q^LO z_X*wbsVze5>TOeKTEV-7r0Nr8U&@iUrvBsB68U+&;3e#x0>jVab{=7bT;)ac@9?$|13s&t7);W>kuG%XOy7(5-7Rm8%Oj6XHOBn3U9y7+gG z3$1?tt^iuc4Qw+0RjhzQxTx(n?zz91UcriZP||8cEMk%Iv7Jx(BpwlP=Sv$XN~rFU zXujVD!(laWY)4=S$`N+HCC#71m_=Hd04a_!Qv+yrQL$}J%JUy96sjO`ztg%7MKd6d z!N>`^`(4lJxb7@mSj|Lg&F!?D>*IPjk)4QPNKyQl20Lg!#4pvroH6~n%=1Sq(C}zou)*m!e0{885dLb$*=H? z%WO=wNs})BA(~OQuFgqb&H$GwY=vAKL-KwL&duGa510@6^|YetSa(+CxJ@&L3`cgx zbvL)A3V$9JkJSrtH|<*f;@&X!f6p-VS^6uc$w_(8 z{J5!H@I-JdQZqdFaB`dg>-eG44%bvi6cHf=Amy8<=a~Hg-9+f)El^h>jwLWpmxe1H z)Ox}kz(Bx-Nl#=ZrzaRyDy(q;`_+POC!@h=C_%d7X$Uc$mWUd_CwdO4j}gY7=y-Yz zFrr?rg-8N2b@T6GE_?rTY z8(=gji^BF>{Z@sBJFL~b67X<2G}UjMxMm^=+w9D>q7Bg+OJ1)S{WWafjC)B}NrerZ zto3quamFuDoGFd6(@_xBJCHe7bcds;zmOROV?4iKD$!cXLH7LKkk-rP3CM>Z*Rxq@ zVi#hr(7a!W>iB7z*mwp8aJDOIZ7FRYE}XQt;-s?DeMATKMbimLhBkc-@D}xSTXN{o zao_+-no81aCH^eMN3ITBaWd7P0Ki<9dpb>okCJx4 zFm=8N3y3|pV^o*OoTv~zdJNE2c?3x;l{u^!)4uV6v{$4B_#}CArS8g<69{RVilujk z0v>MzTYJ2iX4P#bY`Z?}*)r8y?#q{aP`6(sMnBN|Kx;92HsMzBO#8)+XW)Nt6OLi} z<#x0byAing1GQwB%>HL_`(KERjckjC2pbZ5a&3H`DEMc!NWCptqTAfzTCKp|?#V@F zEQQ^JMv;!muL0YJsB^~m4>jj2hW8nICT9vsC#zbR_sg|X^xjP52+*{C;tEF=b=k+! zYSW>Q3rcHLuRO8sKuc@IwIw(JKh=tbjN_T&6UVdrti8MzvMu2|<>`PrgG#S(BES^= z%ld}9p*B&(t&KiH>lWfl1qNv5qfyoQKZfz@>PJm3TWl(tMyDAGNEb^B zyJw@;B?I17Q|JBJ5cl>-+AIS3`Q^LAxv#e~oIfo%-=Y79RQUyuB0Q61mgCk&-HA%hXIGum>tr)%92F^jDoWZ zvvf1~u9rphBk3=;h92G!3R$15SNpbQ}e~Ya*Oyvh62kP`4hmw7qe#ek-*PvggD}ptnBc;t_S|CR>KvIVG#nbAnFgG@nkNLDZD_aA()+_P@&BK+xBZj+ z9zV(=o$TAWqg97910VD~fXgG3bG|c^-M?Kp*jFxzRuh+E0gbi&K0mLDF9%M!&R(?7ntW<*S!RKR)ogZKHW)1K@g;oE)OyMc9dH~}|+2Pg2pFF5}a2h8X_ z7~z4&qBvw52$~5B(;W^WT32=)5svB*27Y7pZ)}E)2u8$t8xcD#ZWM?U0j{&EO|puX zUycjxm7NP_X@fszLb#hH!}U+9xZ22P4uS+ANJuNBjjuASb^5x;#RBVI9Hj2FeGf{2 za8@*H8V80SAYhudE?-75VF}Sf0phgVf2>swNlGBb#J^O;ROLzzZNevO=R8A$ws}h` z1L`x^<4ma=8WA{so4h@T*<$rvH(XTe$EWOQISlKc&$hV_bg`wNK0Hes-D=$Yt|;=4 zTLaO||K`?kGtA$E@1kehVR{|;Lg@l~yz?;RQe)5AWX2r`*ghc%$lr}`k>%>15s_l8WIVTf2S~xj7q=obn`%#p6k3A3<}WXRhCva~NCi4e zrB)b>+Klh=t?cN4?ymFk>&3o*kQ4+7F6E_4%ys2Q;C~-5(nvR1#GXV6*rUTN?hBt- zN9RY)dfqGvH`&rTbSaT6erRO7x{ilVocCnR!&$@%W(jFA4t{o@r75Brz_$2IN{fH_ z(!joV{NL>x=AY$RJ2l2d_$$>PTsEJKeslhzU=s&E=3*Fa%!-pZbovEGBF)uqzcVKf z`lvlk8R+ey5a5MU8c&d?h2hgxRqxNf{G>HxM_KZ1W1_^@=#t=*=u~gfy`=sD)G1>` zmw6lf^T5j)CiL#9&o|%!mcn`F)$kthBG_rK4C#Why3iVBYELRqRz4V z7?O8xdKYtLHTnKmY!3G(O{k3utp6tu&b$LYzWvszXLto@R6A1AGFYPLMK49Zz>aY4 zosOP=zEWCAQ5{X|2+=7aY?*QP{*Od z2gMA55Q?Qpd`T1X(luSz-vc8QgEhBDMhMHRO|AxDIJp{a%!j4pHgBoqlL=DkgOrT? zfKpx<3w(=1uoRHo6?kxB3K_y3pU?8<*R&ceyV9gZvgMyfIlT5`{A z0q^|16OfW6ZxhztCxGF+1v8hidne?W(Y<)!p_2YWLtWj6i*n>uMysnP73!t_ePH=L zL#TE3&mUvH;I`_dy(~;{lDuv( z)Rph5GzNHv1;8^(^|?f)rs%vlF=hW4&4zwPRjzGUIE!HPK3_~<$j+)hn<-Jq6o1m6 zI{)s7Z*p_Gmg|F>)uD>ciQG~%N}%N>Ry__I6({;G+N-|fuE76#hJOi&=n`~%DMAm& zm%jKRbFc%K9+mffP_-zR6xXL;hqn)H0NL>m7&IlU980|CAnsrehqo}^J|{I zYb`R|YhZbQ`B&-b>X`G20=m1NwO8tMmgsY2b@1mf35-IBJ^W8u*~U?Fia~eC&I|U3 z8tRJ!7uKg(xr#q8vD40n)GAYN_uavCQr#9C84-$#1{?)kITZ+CJyTa&JE{R6Tm@H$ z(h3~p7X79HxI9)d*X}JL7zG|+guOE2{Au|H`pphBEE9`-v9@wfekJH;?LBp~mXX0# zU&3!k)>nPgrJKHtZ`KXf-v|61Vgm4K|6==5xQAl4$?>R8dcw7F7mz<)j%WPK^JQF^ z?O2wxC}+YN_5=q~Jb622caS+&ew)STseDFt@)w(KPYEem8t&9x2OcSwP$Vt`-J#hB zPPx7~xgO5W>Rc0V;`E+9Mz!|vd8sjtR zV+E|>QfC}@=syCL9le$RQS0TgUr8bz*WIF>2bXZ}O=YJYHoThw&wvY(E72s;m{KcY zyN3p_(4iK#QtbB2l^%%0iP->VH#@gJ@U9vLHRE_aFB-i)-Qe<(+|8VuHX&zdqz&DP{j*9NKvpJ#oq4Rdd@+fqjFNQ4W@7(G^A}hID8xPA(5>uRMhqHqlvxn<7{h;z_5*L!}1U9nJbU^q#X!gpAi2TlaMbu%zXi-#)4GaXjC4iGVl@3 z!WHN^7ljvbwv??=|F))PlyM500@&KEA~1>sc!2P(4WLnBNXEAOG!TEkK{-ZEdJ1`o zOfDuy9`S`9{1vQ*g~CsfC@>)!U!*YE$8l$6A@zSdor_nCd= z=#tOzW@xX%?)R(7_wV1A+YO6Z4y4#DNMzB}{aBz11Jc*zkB!1v2f#}8`z$1vq6}1| zax!-%hx$yRZbZfeRAyP94x*&7$bV_FhChsAc)i5HHzfOTCNG7P8s}b80&1B(Wdn&I zl>m67BQx5-^3=OMkafNsd`}b!u~ESEGU!s2S+<0n-dK-fE8M7M2{}Fwi98_^%KHIK zmz&5_ao?bcymF&k;6yHSnLo;ADP!O_Wsj+WTWN>&CESOAeV$<{{PRIAixVo@m496zAb@zAsJPNMKZ4FmR#82 zwd*pnD|(Pu+QkR8#JIk8v(ew9p98+6me6r$s9K@7gva?uM^D_0*>N0HWXC>dtRzN|WY=pf`M>(^`@}hx?Du z68Id-77{N#$=1EtMquU7FV*1lB%3=pZ>8J#Fxm59+bJbnY_$WiH3IeejuSy7SdrN` z+5>pt5>tlY?ovovlo-AcyMRe&?%ZEf>cgL-lqzHKRBRG?qx3Xr)Z1Wg+_`<*xYFg~ z)(TJh8tH0KLS(DvUszF1`#S*95Tu9`r)mV)M1O0u$|!i*F%nSEP6?aK{JjR>;;YtTn8(tQP5hEW1PifC;2_; zNn@0NwNms<7?GRC+AT4leg1?y2)&abAiuhJ`9a|Pu(vw)LM8Td`>=zs*%VJ?)k|01 zl5HWH47)bxVpf`OTjCr#k|VUJ{rD1h zeY&BhAcAMJsSy3=>Y7URqXIH4YN53sa%Lr|_4hv1aba+?z8G;14%C_TZI4s?_6<>&~mULGfdp0GaECs zG+H;|wG;&+QLL)*a2wIg) z%xBS~n?d^8Y=OuT2#u^IwcpuD;7!%q=8d|!b7#w*{W^m|+7H4;S};gMcTLq&*9$lI zfru{^H{j;?`-&=}23)8_={L4Lbs)gtz+EM>U(>krWQf~Url-Q}HZG@zsX+rDNFk6} z_}8#Xo9)VNu{?A3f4>^51n#RjT*wtS1khp3ZdgC%rQc+PAj01zT(a;D7+w{<1>B0+t>&uFZ)y5?NS7dk8eUX>exxDU@2kKYxNof0l0-+G1(UjD|Am&eB#P>K zKoE&@)A?HnmkC#_3d<}!4*KS}$Ey@N`{6$7>W|>1EL=YycPP(HrdyB6f5x?!=j>gM zH&USaO3D>{h~J_hP*v3(DvpC0+SI}W8bvxPMKVjs7a;*sP5~+P(=g>zd;6-`OOMk-f4}P7ym5t;f?OT2c^ zw#!)Q7Mpl0mDga%OU&VHVeiS!(+wm+<$5>s9zzxBZ*s>_@lgzx zgfO78-$Til#!+HehpX&P^9edg;pO)}&Qmwvga-tkly@6HXj7^b2mg`)_b*|Ib465D z#!8tzX=`MkmGjlcXS6F$BFG!>woK~Y_m*x;L_~e)U#z$sh5sn%fnN$E%V8Uo6V}0?;xD{jABuxe@xnNi|-T_4s6Jd;G`I z;Hyem2~lKH6MNym#7H7rSx{yD}`pI)@rf#l%oZY?TVgXNOc@26aT)0KqBbsQ~ zf_A>m<>Y$ao!jip@!1*f@(&ZQ@JnfO@DR(aI^762iL~$S&)jw1lYYQKxG)YD)MQG7 zLYsq;&4FH;IBhyHH+qnOo?e@UWU>Agv6{JgkRb+=g* zrV_Q!HyOO%y68D5eB0n9b)^ujO&>ec;>)#_t9Ev$tIUet7i4Xzo438EN^C3E+S1s= ztBW3vhlG+b@P|F={BTkI1(6t*Yc{tOW?K+cXuA?UfIKI;9QcA;@lI;6;tOOMk!aW7 z4UrhzJCh71gA4_|#E+=G1}ScYU-;X0pP)e3ro@)T(^pD!P8^2AKn;o0kKHE3Q?HHJ zDs*4RGctCm$+5f6fFBy*fcNNr83w!8C1&ANO&pcjv`a8R zj86=s7yZ_ogM@nL?cQR9-XzACJDvQj_WK9RXqmu0&XQlRH2bXB@gD+7v`|7##I)Q( z2N$PqzAa7N9g)5B-;17!vay$qW+=M>&k)beX!q>?f&s77y_hR83DL7XG&HV9nk}y$ z%u6LfxaN4kOFg7XrQeM0fs={oKw=i(G~nZ(y6v*(Yi1`gUqZf>1_;=xbKE@i&2Hif zymh;r$?3dMd4klN78XN(c#73|JCt=@GKFbZ$5vX1unrEw6_x7T$U zswnv)M)fLP~EQ-!mhq1FOb&KKbEw{zFqepPZ%kGL^3m9A#c5fVlsIr zXj&5X_-L3sASVeIUxaX>klqrXJ*IWBA_cMJ@c{qY;$7@sCx|Ckp-z3~MyhgZ6&wiv zN2)QH4uO%DmKp_(-+1|kByGr z^6}M#8k9^ZA3^shQzH;6i406_npwsdvq68v58`j~;T134P$umvCX6lZBnTFvyweBX zy_5=g_qjr}aXrKVcu=`?BoZU@DSo^mj*bFpi`3Sg=0xKK)m1b)u0`%e#Wf=rVk~0W z4UZdqe@|Sqos?R2%))dwWa=)iK0P1pyDRtHrXYj=DSeBPr(YU)jyW}4G`LnZNVjSKhfN|C@^MlrO$2r2?SCTMVntttC`AFa7ZL6Wwto%W zn>>z1nz~FZdOA+{Z89ru=ep$naYtV6{q6qpZsu{xjd0%Z^T6*|r2kUTezO6MYV}e; zu}8SqY<}t}xxmq{w410tz2JdMl(jg>r6F9Y65u)Xn8M5zb9>-|70)m3KOLlnMPh1C zC=Jfx{PK9=9FQKOcabi5YcF$bM$#KuS7jDi{(Q&^M{MFPvUA`$IN`!r!EE}mg)EWF zbRs5e?-(!0R{MFo*JJSc_D}JzQ4mRBc!KD50tNfx!7nKz>}n@IVZ;SCiwev1m4%HigXaQFI0Ql#T5UvRMt1Zb&m+%l$Q*HfQ6 zM%*YjqE3C{vngrTn2;KdxPreaaBA<}Ex*aF z^!R$|ZCdafw4gBhONxhk(gbclKT5#-)Hq)Dz)Q`#%*BQMJtl30N)1nn&XRN4!F=Ma zcfM}s^aHPM9+yR*BzKN1iuxer>OP^cdqrg9l}MY;Ugz!U#%vLXpFhw~oeh?RXxN@O zjJDVAKVA9xv3%OTPB-%J1AG`MI4pRsw_n_i?U`-0wHEyKOGQQO)Ga1+j*$@>if<@Z zR({p%!*B7`i-iL3ZbfA*RD!DV)8dz$r`E%>K+2PPUpclst;qC}ff>mMiBt8eR9j@c z8l&?kI_U+~2^B6GVFkaUtVQ)2I~SEa?*7zO_c*JwV>P_rF_D=j?P)V`*PEhlL+X*= zTqkN~2FgTKw!HJ~?;VL0mcxfdzHV5dCx?4WgCHzpUH~s~w?pPyd6{404;#%XI0MSL z^ZB{#^}rshUH%rpC2%9WIfC=pAsXB&Vy8b*L|pc^_=@iaIgoR|QfHl;J$Kj{X5_5E8UDx%~o6R$-WHY9s}UO zx2STA^}xAoRQ9AkQIAaKMS8YaacyUV&?$chgo1%D)n~83?G_rd$yyNA4ua2&TlWx= z80`J|U~-8kX3;5O@E5BdR{WH;XgVaw{oP|V?At4+I>CnzC^bO zbzk?hpZDGS!`}NF@>7pmYtAvp9BYnGU41+ydzMCq1kP`iUo%#h{&Dp@k)P%9SQfhm zSTqvcQk!G@7eTZ^5)M`DQ%a$;_a|*CrQB0k=TR-l?0(;+b-gsu|2er<f@7}4@k3A}*70su+_aoyyV z+DCA}8d_g=;}m28JE#aH$m3HypcBMp5G3RH4%`5zx}m`N1C4@GSgAc_7;3;s$q4E{(h_9N|W z{z$TkmE~VI)BP{>sV3veg*kSEJMF0=L)}{7o@Rm>VAtXF#6NIyvCuf;{={5yoGTm< z>xG4?=#js=8zoaOhfk4+Uw(}wL&zTBg<JJp#Woh}&)1KZt4^U$8B1I^7(XtHX6G(hCdn}6c zf@1qtMLaUbYz^_OuY=WjQvz^` zg-^$wXoLX#yOGQMZVk4njK;(w7GuUe@v>1`Bt3l6SWg_h8D!}rT?z~?0S_GvA{(Wf zj?|m7M#MDwhO2l(Msm0x5ydIyfvZ$h_>dJ?TS_wI;8xB%EdX`~KZMy;_|Am zP2q_ReHxDD{0|QZ4k$#a_QP?V2*eRaw)tOgB|d9vllz8kVPqKcS5kUrMZ51ww=h{! zOtt@$`j|1e%sk)snNypp(L7{^KZP>wgU|qJDCkmxdn;*vl+lx)5~QMKDsvOUN-x=! zI3%FdE*tf4{%ysgL^Wp^e)lNCjE5k#88I_!$2V*@_4t{%cbHjG!WW#+Q!;c~+TJp- zI%#nikw=0hH@l9%UuU|9avbEdnNGZ!Dl< zUf{&Iult?*{h;jC9{~!S#(hMmBB|Jf!$IUD=do*9gL;8;4f2knW7w|~>jMwu29xVx zV{rGc`|fs>UGQHfAFgW4WR`*`K?HBYF}#uhS#+02^t2bpkP5t)mNv;V64uVQ{|D*~ zM_I>CKn;kkmA$D%h7ku7E%ML``G606hPF^RO^1q*4(941ls6Q0S9!2zgg({q#7joY zQZy!RmuV=k+JlXqv2kSMmg!5q#JP>=aEY?B4nio*eQ@Y#YAp7!0op!iq~O}uIMT!r zdQ=5_{R1x!$oV){;JXq293$&?#r!m9bnvA=eyRO4_fS7Q2u0f9UxY};1BgkCT9ezw zzj1$_k^}9lEk^+x-H*sCbkAii2dYrd^wKG8-?ywho!biEWgp4sf zX4A(s{O=OF`!7G5EW{OkDKX%H5G2Y+ZmRP5UiP{y_CCsaT>IyTL;X-BGy#{# zkOqP9HExL0Z(Gx(Rmu-73YLmZ|(D?o%$z0?Oc_33!y`V3> z9`#Z5%`CsLIN|JH5v1JsM0!v?HxyZzz~0SgnvlE){vf6ZlEx`7{Ot{_-qyK0+QE3O z4W}^>QjP%9WUz`H3H5)!nDq0@-AKZ!B^d#=)*82;wOF#Hrg@A#GF0EW~ zeP~WBNyEIL1>pkX>#)m{a8K9yg6lEP4^>Lz#Xfw^ue-;>uuoPrCo1`w3^JO>SGZ=y z*o(ErZtAQo!Q#h<7C+|w4rNB1b?h0pF5;IWO6_SlVg*$o>2Tk4jix#F2J)jR;W%ZX z*T29K>|Y~W)yyVL$n#IARZCjZbLL=)LVMMDr1Em+b8)s1N(Wlv{fId{j!ThWobT#p zeJm&89WiLHI54o~GZ}(qF{;3(1ob{tcQ-~;)Y)Qy$N_>lx7n(QS6bK_t@y>JqUq(4 z1kYg5>M{AZpXuTy{T}G%rl%v+M6I~Hbj35DNcSkgzrG-N-sZ!VOCP7r(sWHnh)rS# z)`uLb>DlrMlK0cbEq2rWxQr!m6;V}J~GF=%26(3oCv!(#C{Tv%1)1I|E z{YEnSK-6=+E=iQlT!|;6jY?~}Z0%^Y;w2o7JD38nrRC+qFzsu8@7$s*Ycp`3X%B3FCsu`81F{9zT|o#dv?6 z@3+)T_yDNhpI#j0#Km2&kSLIvo3{9QX;Kf2%T@@SJAT1j(xwC;Lp^(m>5C7svjGdt z?p0iExv{ZBoy@2R=XJUaUE!AUU(tKPVeeVvpVsb+Ej&5!@1Nfoy1#Xxa9f9;j=lZj z#b9*|ltv(!31yP=DJZ3cSg^zVz3ir5cQxvF;R#+=IjIGh*ti%dt9x)}xE2%ktfsR9(s{>!EW7H5HusSHwA|gj!?L z5FpE}SyVx%2A4wj5A^kp2_7R2wnDr4r3?bA#lcWIhSY~RsXUs;s%6#)SG%e4>^8<_ zhLOi+S=;tVj)N3U`=(g4yYytwrkF0tjoSINj$m$cb_dztUdtHD!#@7!dsRW#x&OfB zI}Qd4T8H|Li&@$odm9JGmp0#UXNU$IYo}@~9e=$+jM%1hZ(k6qNtL^P zee~o0K+)d*2i^O{h8O;4->lm{Gz4Di=L6&~{f^6M<;c+$R^94W#mcdv@Sa$`Ui*gnq`P7DObL-&T9J97P*@jOwPo^_C;(jTu1ij zkaFM2yLk{VN@P#T1HXcjEL^ZMf$;@ulList-!l|L_6#&ATtQGHpJ-4LkJ$njBQzDT zMB9vH`9M6Delm14^CW!7<~a0!vq;;M*{VsvSVftPh}WCZvNwj6}z+5qn!s2bs3Iixs6#!#pVd9lhMFv5_cSW82{Ae8!DAkLy zadIiBHVSKa&tBSFR^sJER<}GyH&VLrzbhqRsOqQwMdm3Qiy$4Yi98XS;ZSq-ZCco) z$Q1r}BOQQzNuPN$EP@l^BM4G+8ARbL(XPNPh@5oR{TVnbiLzciWBYg-y8XCFsRH7m|i(1oe+if{5hu- zw0?5cOe4B6Pe@k$3KhYpHn_{g8b-OECxHMF-<4s3OzHItowp~>OxUCZ@(J}7$R-o6 z@US?1XE&i^@Wr}$aV$tW_(%pd5Q--i(IjVlP>#KW8r2n&rhcd8$lR`_81~nRnEqI=Gz`8<5fjZ4#p?q-q zfu5a=AODr%-@WPMwCd)9@gSMq6E6cUQ|+L=@>7H6z5YG)4H09}l7U|}&S5-&=@{r3 zGDs5+bU&&>$NEm_6{F!T*ydn0IOnr7Gg!ZhoK>}1TJnYxhA~KR$K0(m63iA5pEkg> zyzC9?wDsjlcb}Nx2N)opzq}8q02id-=g;SOw3q7QaZZ1!`p*~dk#r$yX|>EuCL2uc zzh0hYJ8*#~%8{ta;J;DYZ*bMf?udnAp6$QDEVD$?=O>OKF+@Pk$?doN<<wl-oiV*v?U3%<;GT z(F5tC^EJm3S`wGHzl{HSKn#=x8n}Or;BF0ykY|9doqvX6}XKys;!{X9#`4k32_2C&e=lWo^-`mJ!`G^q0RS?^?iCA-9&a zq7Q>d5@0~>mNVS{e4EX$o1szG7*`<><6LCG)puxe$}X|opMH9=C@f(+vWZ^Y(bD8I zTJ8KaZ}xB4C4NEQd=xRA3gI_J&(_y}olb_>Z-mf(Bnh<1F_GKOTv0!uP<=P=u$}Gm84kMeX>)XF-RJWXAD8( zN%*Gof2#@68c4+76?e$wDkS04np<6mvMAjz=kzETls5)ZT<0EZoC*9l$5rHnHclKA z$FG8ed)mT4!O|t%AuoV-BL~q?7IPJP>OX)bHaR}$y`aLNr4{Vae2q)H*-!6#K(-9z zWDK%&6F!eViCzWA6F1t;w50uxI5cLJ25tw_CFZx&anrg^Zd;nPGXl=b2Fxm75FLAs zn{W0l382NuK()&=ge@Z+5p;Uq@>l|MHtfu)V_af-e%e_$;X@(4SkUp{~x}Hih>2Y^VqYS zPs(M8dSL;pYo<#Bt3NLJ+r)@lMr_~aP?~sBr9^hPt==Q|_j+8thbcF%QX8)xG%)1B z^0!NySHJ>p$FcjTSin_ccte8YeK2lUs73QQu|YMqV9pQeN@7X}V0`-tlzA^%k+`5| z1^5nx+<_292#P!k6eeGk*jrX4iHDv=+yIvFMZv)p^|^?9O>-y8g@5P>7V=f#K@D3u zxHfM!Y)nxlTs`6~Nj)yOFa|F4fAz^73Q?j$!1czf9m(7Fm?ESd+DYw(${7*YP`bKt zLI}Lf2^cS7*xApd5RC*2R z!5zCD(8L+kC9gq8osA4gc)Q>5&t?7yus;f>V3Y^1$kSbilO* zaSYB9EP}BD3Tc-_iGdHidr`hW z3AQg_V2#$?QXLRbgvcmaP-yHhTZfLXlQp)ida-@ZI1y%w*RN5oYDMaLPRTp^G&;aI zr_5fWsemi4WK}RY>O7~s`=6Wz74IZ7;40KJn?qH^5JOH_iMhHifF>IWo=UcMLDKXG zluE2WM504^MULUFucWULCgB&Z*#pn!@R5A_7P%*=-U&1qoMtsx+ome=?V3qn;(xGd zpMsCLh=xkQL=mZO-A(ua2O|6T82=^viN`aVY%q$UtLPh(#zld>-VCMWIfbOlm;a?P z)qbUdNS~V1u-_LG{DD+PzjU}eV#SsAAod%-oP86i__Zq|^-+jHBDwy}O{!VKdXezI z#4z6%Z@*EuVa@+$FnDNiEIUlmRb~#nQ?xnx_P?(dloA!nu3N^7#{FI%j5}((E5`&M zLrdtwv6~b`g5Xu~UN*(O1K5}sAX@jB?UT!qHDK6Xeuk$BpcRG&H>yy-F;`*1iOwcm zL+@h1t;nG1nOG^9^32+9c$AQ{M}2YsPpk->bgTd92=-%G)z&nrLw1p)o!&3f->L0JNUaq1*HHN-7_lMXp8}Pl8puK#D1KimeM8yRXl2WVf`*R=C``28>$P2x>RIpjBlT|M|JVJ}KfRj=AjHmNJ%y*TE9qQO`fh2Yd{!8`_^pUh@t>WkD@`5^fRD zuEmjqmS(5o>I36D;6ARax&HTEOs=iTx-;(Y5jx}dMNU_@BwmH&M*-ws>0mBDrQ}`y zCyV)tykU6GOWChOb`=*i2SM}$l><;>e5@;2iBex}M1G`(66kBve-mg=%}OZ+Y7sMd z7h?u*mcZH%Nd|Gp^~vy(2PNt*xU;g;a?c`m@JT!!d1gM6swiT-wC9ptk)uO(CnQIR zCS>xzv6S9+{X#RXRW^o*5DLGz=Vi06@dzaq2R=}$UUZ8;YyNo?1Ra4?1Gud=me*ID z^dhlyCg#Tnc9C}P@?LBGF@NzeG1}F zU^>lZOfetrgc{v9AquUsvNfSWl}i~WgQsyNdE*yI8=-)f!dr>p-p^U@T*aKjKH5MJ zw*ZCF1w-2mR%Qn9(7fh2P-s9vp#f3!!=vghSeH}wHDdZ;6QiIZ78OOx%4@4D+A)P3 z6=iWgQ_BHw-7TLB82f?UsD$Tl8>9K<{Vr{R05{WwfE!r_Cj(l}P#;s{8|3 z0Rt@qUCfoCjAv*-6IyCt#})x$sKg*8I~;yRc#w}r!*QUWK$BZ4Xsn1$%|R%0)eD~= z6$j+)rOIUd62rT?wD39EZBT1~mI~sr3>KRA`{w)NcoPuMBxAws5nLGdUo8N*kVP5q zP#mdBD0F$*|NHV2u~*l@?X=k_S41tXuI%OF(6g%Wqb(Ok-9b+FwJ{Ux_zCG|m9W&z zs`6C&DUa03voqP9$!Ve~E?6)G6(y!6!1nTQc=4vQQE2cwIw0}Pzf5}wl$Jx9Y9$4g z7$6GcK=J=Y8aFpeib^nAh#vS*g-pw%o>}`{cWPRA6odBB|wLiK%Bi93j@huAX-u;3eBp-58REv*9^qz%H-nT8>K2~ov? z&2Wu^i=%bnj!H-m?dWJIdn(=!?E>WxI@n6O=+<;$5YmE((Hpr8z)mMJfx9svR+t+9b2q9kc+h`po+_OhEG80XW_pYA!@V# zD?ggI0zi24ElssiwT{nA{NJxVkHT&dV7f_)pZn%}v~Y7pOed*gz)(EAT-tKMdIYmy zlRa*nYw{Nz_`XYAQvPy%mvtyz{QY4jj4r<~f%9}=LwJLZR>a*YAYpION8u7exta04 zU$+)9tJE?d`>OLo(Z_qDu ziPd~HV#UhuC)Xe7mE&lSZFGOGe!z5t)lZ88HVX~nRMFk^d^Nol+Fg*lUTEUaP^tXV z8N!_HL9DV5w=Zn;+7tmEln=}Bjshs&*4iyWFa8RKCEX>hUeHNUq{5*Iy_Lctkqo5=0)(=r}S02L)q;IwCr4AKl@8cSa-s3f`T?Fn6 zX*7g=pN?-%&IT|S^{;i+tDK?Nq>0>|A z^#hM7o!8FHc`|p%YF1!q`*60r;|2T*Qx%YYNp~cxT~7$>F0` zK{`Nb^F=j`+?OX$%cs&sr=6 z{aZbXjwhuFqIoMp>lY%DU7j+36aC{_zqIuDf{4Q1uy}cgc3N&)G=3+8(`Rmz+B-8f z?pn9)Hs`FME~=Wtpkl*~$%Q;mH5wLAH%-mks|40@$@3=7*`>$l7ub@^ta`EiW1Oaq zp7A1Ej|4T+voAM~9z?KfP#BcB-gfM#`(JH_H;oU?O4NI_Ut8zhp$0;M^{9`>6lR z-IuWE7ur!@Rg;vwMaq~KaL=P%C$W&<5yZa2R7-<<1tLO1Uy|7neBpCnod*^lOUAyk zJ{Yex`0R>)%71SBHitL=Cra)rUVwFh4aOukJS&uDM`_w26{DpuOj{`*3!r4U>dY_- ztJP%x<44JEjE^h+u;lc-pZJG4y67AwlJi>@b2ec2$@6d$cm|;(;(tX6uXz+fx19l~ zP{t%Id)0|+ciM!+fhcNY=y9Qr=UdIMnlwME7KYAlQyv=c+YFs(d~z~rd$bW&G0(F# zv)RCsyWJ7!FZW!uV4}*x@b8bJrTD?_JiRaKt#ptI;Hv9qUYpXm%d4KW57U2Q-NgO8 z9OfQWK1&s>xHfx2adP0HCE|Gfd(f5b*5L%E;2PNlc=8mehwy_Zb{8GJ5MRJ&qWr~E zFyqpyvd*Nz{m$(Bq&{=uj;6p%Z~L38^ATXAloy6g{A9e${Db?-&j*=9D`Xfy6WbV` z>>=Eh54@2Da<^b`R++-z#w7BBKGAPB==N#VV%v^TB*EYU^+pRafU1GG&)hjd)XM$y zuhf|5_fbXjv$VE1+$3hY(Gp_P)XG5tKoA@n#OoRGVmLz{YgZ#F%TM>ebXB=9a+s@j zTbG25A87+RzNF=6K7cGRGj-mHAuSjASL4Nw_p1>@l*MsPp0O*-nM(kM4>U#9?mzw- zO)UWq&Z)-n@=wm){K1UTYU`%M=K_Y)tuOb7CoWHS^5*?F=2&Ph9cHju+pesvEWvP- z2d1SXeGb2Bv_u?kkbPJh&&@n3>)&Eo&Qt5}T)IjZet4j}a@pX%+EDT8cyJQ*Ue?DF z_iXcyRG)0}7S-7)rq>?;q+VzO|4_6Zgm$0uyJt zmh#aSlpHWVC$z!!Wb}ODEeyO0WBzVI4)8XLLvD93H)bo8Xf&-_Qw;#%ggQa%a@x$T zm2gHG$xC-!pv+TgBYV*wzrSuMGKKy0zG%LM4SsQ{8$b@T1jX^Kapch|Z*0WSRa$ zts(01(nuDXMu7)vDh297T;>PHt%dV2y&&bQ-W*ZaIYdlgE@42+c-8Hkq#fe6I(%SI zd3I;BE|;;+lZx&i+h3ac|%ccasd1zEun%v|4Z;J{B)A@tfw8)7|+Gz~zfm z?Y`BI6pcX{Xi6D0()@0sgwIa$G@}|BEb}qUj7><^iK&b1vU^^P9Of_IkK$%M@JX*R z@Um7iNI@ZdMwG_NA%!d6b#S)cP5yb6O)L$4@An%poiWdWjk}y$)WsxcCaiuW#KX?6 z;8_LJ#xaZN=ka_E>h+a@?|u4n?c7=O)+=mZSz#Wd_6&Xrf1}mS&+$jv17vSrUfn?^ zAQ3bE2_|rHCW3o`PxwToHft*ZwaL5yisBvC<#9xS!j0SpY9cY8l}?r+l@)yqR|=83 zKG7mJsDbL*$J%pK8W1ycE|Jv-M|K+TD&ktN^S&9XQ5`?d#O&v=sH;3P@AU(#n- zPsvPj^e+~dg+&OUbc91HLGz%`&$_p$A|QF)Jj3W8y%pCco3YG^Cc$h(xBa1wsLKg5 zqL&5TEzyc0$hh_RtH3g6wvGIqB5f{5h-S;3_Bbg0d|p(m+`U?CbgrDygKtA-D&}gV zNYWucPuH?FDO={tWm&LxmGV%#eE2<>C2V`?c2a3xG*;j-#w9WnM~Z`m0Yp1MKhdBz zww)(n-LDdXPo7d~JH$fm@zc z;Ob0aZ=`^Ei|5Ag2T+TtvPs@4R0#9!G#IH>2&T%pJH4S)_?8eN)AJgehz4#ml)?Su zVQyqH+8&oqPPh=5EQ3qg?tp&3o$@J(ADA2|QV1r~JOwmdULvd7lgrcH4{`L5dD5l) z^?Uh&lb1k6oUm$a0|tVc49VNtEbD#5pq$NeUF~?QMe*LyKXGUu#_=G&9ZDi>2&8NO z2WbZXJ=F8fZ-_L~IJiPVAo&tBF@b(w!bCD@tbq+%-PB$QeWlBm}E04@|Mm7 ztQpwy-&EMS+{gxIx|p{prOS`5mMK+O)H!eXEJerrt&ZIXqr7M4To*Q*nxx0})O6JFj`O_kas%+CyhMd2heBK#)MD7!c1UPwMZ7ue6mD_!9oKI zOBS+Z*UCtK^Ck&QSz?pjyuZ3+BB;QJ82b2;Lj024ZE;u9_do@_Wj9sr-N`Ctwz%xP zO-Fef_qL#GAlq#v-Lb(tnr^Ob5Id>cL1Zarp_Z zlh%wnz00;&e>+QNn|zp)c;fXepDm*C3nmA|_bd?{?SUfvi0tH5kTe6J=jKXv4LJ}g zNbC^V0;u%E?;_+Dy#1|}?H!n$^iP{rN~+!jz$tOi0Ho4COy>G}fw`ZiyL*xt= z@5Eh)iU{Thk>3mshm`zyRuJ%VZbSorv|t0J<;-ODBP+g*!JPwq7|*5D?lAdft=&}R z_FTO5?U4R)=YrvFhL%^cQBy~Vy@!6*O_(v(z|sk~gS5O~ug{0x?N4N%xW9K1&(l49 z(SK_G+kU*z|BBuG)`CTM<&PMs@^LVreaEC*WA`g(Nxg|)t0JD=AE1|IpvQ*0xLH#oJ?b2 zXzXf$hF;Jn#-$24L8(~(*idU=QnGr;d`M+gkJu7s>P@f)AH#JWjEoBUg^eZuA}P@m zaW$azcX5AN6Nz{o=AGY0@QKd0Pp8ETTU>=kQa^Ce9Cg3`UtxzSMzi{jLv(Y=S6Nx7 zPc;vIYm+np0SGsvf%!r`Dwa4UC@|jFS`uP8sa}#7#d&>kw)*=?*mdJJax}{r5g|z= z5WSfwk@TI9n*E>F(k)a#!d|WFP@=X$CH=GA&c8i8GtF+y9yOo5;!=vVm#=^bL0}+N zyhPy0U%6S-#Xd6#oac-ltqM$H0~RoGXs9M_I?-J$9_JiEqm6u47~~JA-2T=rr>%y> zu%2TV>Rsb)$J0r}Gjl13^uFB*Wb;r#gz2)!SsOPvy|9ltT@SZE1no?!HmTXllL3e7 zxhhBFg#CGq+Y-I$@2i&0>{R+LK1X{uXlti$zdqU|Z&B%}SmNi_@*K6%mFDdnU=kHz^UXtd8aGpg-zu*R(RQ%%n?6{`K&9 zYf?95)k07~rszCc$jhoe5mGoZJrnq{i_S-vz+^LtEeMsRr2P0%*=q2$X&rYQ1XTR zmIs^Xch@K7ml#)2YeuJqS?#@))WxW3k@Ra@m7lFG5?wp>;`l%K*wJE?SV>?sQHZ}|M4dps{Nb#a2j!s$AjU_%y-1EL8`(o;x1)oH7Kk!K6^QDKz()&Wm^sB4Kj|iT;T_-+10c7QX=Z zR~eOk98GP`hj_g3E7b~9(av1o-3srE7%PDm#{w>1mHuZc0JwcnjzwjK&t6T@Ig3yL zJpvzE3OE#EuEvdx-SwX{0$==qlHxxHTUr%A`9rc+7=s1p0XfDJvMhV#!`8I?`Is>Pn?0`pd zsDQI#MWT8OwBRt--k;x`f(Libi?|Q4`XbTkuyAC9;6-w3c1+G;3|`joK$JpG&*AT* zC!AR9W7*fR1pN2(Rg}Fs5+H))XnBbU&<)EmHYt{}{rpY|v<3fZff4pbC$7>|gYxqS z(skJEN^(C-23iFA=p*=TR|nCaOOa*=TK(hr7|!67IkMQ)z#EAmEp(l4t;E1Y5?4oV z%>&5aXY~zHs%Wzh=CW-IbWu#UfytB~Dy?J*DR-$B9ex)i{LYq-Qh5112BnhruL*3NQvGPnOAwvn9N&wGsCV~q5+7@=sW z(+O=1^s;dm{W2)PomUx;n7qwDR{4?NQNa;1N$bfl(VwIk8S~*AfW0b%(}W$_gk5GP ztk3MQrOaHD@)!nXWuhV?)}KiKE;XHg^%I!gs^;uvJm*21W`KcVtG->nj7#T>iY=kr zJlQxYSQ+rPj?h@GReOkQ@c>fpuLco;5~pbA(M+!Og)C0A&h;f-`C$xrRoODsPL$$8 z0|OHQ4>ICV~#|kn!||styQ!CB@Yz{W~>B?|eUA>nu25o3GJ+LHT@Uiv~5O=C9E$ zu{2z|a106lL&rN-Y({jwzzBdkL^rH3YQ+z03W^Kecg=Y|T$n@p0gss35P82L8>C?@= zhsaLXxxt$VCEi?WlC&v|5XW3$E`dl=t=UGeB+~C|__>vIMu7l68||P`b~;6ZrMvkx zx(foV+Aj{qwZ@~zqBIzxT@v{fuh!3g@W0}|S%mG!HR|}qEmrdQ+?ZVFs1DzMPAtAF z+}YT^Z}1WWmFO~w#&6RG*UH&Y&t93P;dKo5T?ge?%l~mD5PxGOrAz)%ewqq7tr5fc>9sMCt9cc(H4He=HIWL4T4QWQ z|3@59vzynGAc*DyHEX8f`?!ErwqV9^QoIQjOP3C8EIuz%ekbQoo?4j0K!c;fO}a(I zAHxs)x>pmc!<*5C{1P;Zw&}yYlGrrvsOlZP&2cYle)+6!1!h2OpYQ}=w8Q7UTq=jq zxZ6SLKZ{Wlo4*S!InIX*b=lWJ4mogxBiip@2jfICH&MD%g1=V$S(vcPFYsdh>&VYk zK|-%^=OeRyuL2+^pn4H@14%1!$UqOvv&ArQ;vT%M-hVRrYTvZw`={oN``~Rnpr#Eb zDyuKr;EFbw#qOTX%AS^)#9buMdk zJPZz(^4duLEF80?SF#mSl~<&l9s0v*5$t`V3lKn%6Th(%$tb(m&{_Bia@Vlw0~RW^ z5Uh~nq}<7?CmL1?VKHMi*P%ZZdrKSPY2MACF6k<^IErmRwR{b1Dslk@*4Hik?mMOR z-LIaSsNT}hiqQT)R|F=qtS-8lQkF~&TY*&c-v(W2F^lkos*BPHYJ3(8Bu(%#xapV% zXMS_Z;dT0p9bZH_%<6i_azWROWbNNVJtPSA;EDp33~IA1w}Xcci3u)2n3KdX@Wvv{ zx5krbwRssXUjL0C&jq8N=PT92QgFt2MBe-YR$_gVje`W&GEZemnm202{s6sSH^Iy5 zLX}F~A<66NAC5&}Ec?j*(s$E4J*AI2KMv29n70L0Qn>vz$`-vhiC$5{?wCz$U`K8F zxH4BiG>@BwmO&>3 z2!KR_y*0IKz~g3%rAHH3g4X>a56_C}^SA4gE&A+_UEFtOVnEmCDLvG}q4%ImAl;(| zPkce>NB0r>Jt~wG0xymdmT|))OR1Q*icA_R)h4o>@tFj{ylaP<`U=m@6p!>*@GpoN zGO9Wy^cZSUO*EZv+)iu)jil5zyOq)JZ;#M>kMSawd z#9jGm9SdoquF!ET;Jr2j&=LsZcik5wMl3fX>jtp8w?V(0K@Sp;>-}Bnpg_HaN=n%N z>MuxnUk61*OwtJeT8-olc)R{^okw#Skc7j{WnkM=H6Bk;zRZIW`~6R`2Dc!azeheh z#c8ZD`&1%MA60JTymJCCPo5rcs9f=jz-wtAdBS&Q8kY9oque25SufD}f)pQh~43>X*cG8%>u@?1;R&0p5o~}#dr4->MH1sCKzD9 z^qt=vg5Jc)uP@5~Fv5_{gt@a7AS~=ExJW<`7@ULUjD%j$CU`-78rkT9$zj9fr7ERg z{}xHncki;f@3StbKNgLd+GZj*pR=^1#{4_O@4ERPmx z(ed1E&KT6CMehwnKtPxsN-Gr)d*ZcYJ1r}+w{)rX$GrlF44-39g zAq#8z)a?>JqyaUZF+rqEL)$xhrqu2N1q=$u|7$DHMN?+tegv>_{p-2Dd5AHCT9B!aK@zy7hQf>F<^FmI*YNP-31!4 zn2IU<2gerH)xKz@PY)GJSw|SQ8kn@6VohbDYWw=p<85EVA&`20F8ld9O7b3cA(e z9PLgME_jsf(nzJ?)hy=h4;luhMV4p}AW;-G|9Or*^Txfw`=4>dLOrH5Z3lo-;NJhO z)NoS1ksBq;HG6^p?u*k;hG)pwgaT!sI#`n`P{T7I<2FH`^hsdFvi#D0vhuA}{%wuY z&tXn19X$C=IRDyoUD*#c;>kWRuH8G;w|E<;k_b^s3u+tn!Ec0zU`Tv%c5YaTr&4n} z{WYUn9hN=2azY$G3-iJ95B79P-=`N~)_5+fS_)#CAvB>dwpOkd4Jjp%m7u5a`Q?AL z0E)3O=H_;XF9$)%a2l;y@gqXW1#lU7?f9L#sgTe_RM1)!VQzO_K!0hd3{Dz5_594r zsOwYs8v2a8$df<8Os8NVMmS4}p(w)Z3n9rjKdgWC2P=bOIgi2iv&oKILPP}d@2HG3 z-A?~R2LA4qy?z(!CruUFRKtfhe5>hI^^XWz_xjxe0Ij!>q~x}IH33?2r#KUFSC}E< zphMifWhAV?V4(9+!}yg3{t_5;otG}*!^TKAlp)1A01Wj+Ee$@$2gyEvR0XVR5TCjk z#C;%KGSdSH*8+I;}hJg{S0)<--4-F;QDx>+$;muRUHY8;=4u9+N zTQxrNG4eB0am#!Q{Tbne{$^S!mP-76O#5qGTwDRhVs3$``Z-|PlB#}EJMdXt_X3RV z4;-nhv(!8Ojw~bY@cL5&#Gh0VP_`>2FCunKyu$1Yle1ssS$3P6Tlv~hljEk?%P9oQ zzQ!lC5Io@)-Y63a?%q_X0Dqiwn3CaH5la0g5(tlGWT0&Ep%V*Z|p(x5h1LP zcGZ*aV?4moV}5$~JLH)rhV`a<>`@Oc`M(w z&=!4r3`A8prB$U6D&+9|7Zn;NATs^aW19K73lu~BsAGq)H?Fw2LR z>NjlWU?xP^l5=~N6$W(JYZ*TTgnu-E857zN!+@=?<&nj|bBD6D6faWN7FcVy^dV$P znjov#>?8Cy&({ufI8p@xTb%~=4QAQikoFA7G`@2(geSwTU%jsYJhYYlNUmzWmj@>0 zTpR4x$^*?e?wska(GZ++w#DB^yvyL@r>n7yunI6jPHMKbH;$GQR9KvS{O}IQ@9am7 z`{}^xCP10RH=QFLE?W5&c6q3KVBCoIB7(W`%9Z+DzA7VYH^WPmDl?cIs5WYaxMdYN?4Qgel)$fY7m^SN#|Ni?gj@MdAqsW{(7wrnDW!=f9o-Xy({)cy;gOaD?bk<~whND`*!7=gSwAV&l z+Km&CSutBk9GrGW-~$`4DolMM-e!V5I?X8!JdfB)7;-JMJB?_~)9$@lpNdEQ$N&_~0N{?zq=f zJzG97xr=?B>_T0X;FJ8&0)Jl&yzs%!84F5_`Mvr(n{xufQ9E}*F(Bcpa+QPnwD{PG zBwXj3(SRLT61{j9^)pJH^Y;qf;p)@_ia$P%SL*W=latN$Z>}1Pq=huZCYw43^czMk365;09y`Pr>W|~ zgvb&X12AUF=V3NGzI`}0PLhc!lJJ%z45c$!0y(-rf<-|{iKtcV1=P^G9DtGu zo5}wO?x2wJKa%-&-~SN@S+x3puN^)a_|mir9ny%LwavG@{k_}9A-%E9$lb43?DzT2 zw4#IiaV)vz7Z6tTV=JAP9&CEwoiYHbpy)f>bj}lAHqRfCVITg#tAZpp15O9Gt7|y# zueey*a%FGYIjX8u z5|~tT@s9KSRyq&ao|q>Uaj82keLtG91xzi!L?7O@+a@dKDXQB`_@qS{|}Vq-F2BMoWzJCWEf zO5J*mC@NCUhQBZ(B0?2DI$Q--rr8euBLu??zb(lKJW!^#W-7}$Mufrl7g5Da`pPeV zCx`=IID4Ot6&bKHJ!$4)PI#9|^3T!Ujcl}pE9YN1J&Z8xjK->%BXOEqm)XWwP1cw1 z#Df4kW38Dfoo*U?3Ji{9GK6{8RXRt2!s~-77wyMl z8ik*T8^!zOl=At-7t!RH+xpa>Kk9VIBOd>QU>Yn7^xx47Ehi@pjyPJoH~Tp-wCbP` zMJ!lwbQ`2gPJW5WAX-?I#0IqbxbnjD8eOPktUurU{HZd{rhc)H8 zQOq+?-LR0fKSv`o>bc9V`I}W#F=~zphM9nuV{}ie>$7&uVCvgY_cybt)u?#Qj7uU~ zbO|`eZDz85y7#mG@&Om2q&Mvs>$IbNY}{ z7K7p&*QnY~M~6wUYJ~7p)Dg0swXwl7R5}`29YoUbOhu5_`p_ol^jzbilW+6WyeCTW zb3YCRm|#+|3DU}yyvDU$pEI}+3Wo`|6_T$OWXuv|)da-G)~h&Z`=*?_E0(^;+g>b2 z^FACMC^YsYn5uhfVq!7~nlSfT0ULY2@t0Q}@aX&+`{qdJi;|v#1os>QCx56^`AFRV zeQVjB$4={2r+=g9gX$w(^z$yyS2LqW&cw6xBHg~}6?sP@g9jb0`NK`H`Lc`GUwS49 za0U|H$cLY^Hj;jfp%}Beky}JjU_xlFturlM;E0zSsqPGcr9FOv^+;P+e65s?w>pTi z52efUE!pRvI-Iw`yyjMijh6q4x_#wu>mDB8Rp!~*lS}!6>zk+^g7Z#R6XUyaK|IekD`l>Y;D*M$yen!vO#`$dw|EFJP*np zQ&s%q*BlpEKKafuT*ge4$YP_K5IZc{I0Ad-FW*7D^U~^@?~SEqPY9GDc!M9#hj=bK z@$!b^GVg=g2zO)D;U2Rh=Q!#}E2s}NRsE@(r*+?7v2smMq1-i&RLRY3JWDQHSxCN8 z{8RY+B*bN6CM=GpQhU9s>`u$=$f*DNLsM*fcmv*K1TaB#mXIRc(}uUfAE4l>i@L@o zMsB}{kolddQQPm<8|)YdSPBH0tg(k*6s+#E%}#g1rL(9t>wrZyTH-!wY=auS-%n;O zp)I3VrANB#7h%@BBk@Emk1#CWgmy~ODx(8(B>yZ87kaY{U8a~D6E+`%djP%EF`P>+ z#N`p$G(hjDBrPma9$~#LnrAaCBbQX=-L_QrXsbYzYL9E7?na~Z*fXgDL&Y9GsE|CL z@8&Ki069O8Ycjo|AIN;%#!;QN-n2p>)!~-X%1QTfwxF%LCz`xX0qM2^gvU{f^(iR& z32pc|hkuY~?psjh{g>&NshW2w&X*FJW&aTy*)(UJUbkzVckpVAkj+|)}M>?-})ubGBQLYcC ziVh?eMehS}8_AWVG}S)tFLk*)5Egl*r8coFXHVtnL^kTaT077abmler|1frzK~=@? zzTbP(-QC?FARrx*0@96icSwVq?p9J71SAFN+DJD@Np~Y1(wxPA?zwZ%+&AYHGYkU^ zYw?S3e4df?mN?D?&o-l{=Z?pUs>qq;Cx8+P^veKUpf_P3nD3@mrkXFsL!rl>OrpF3 zgumW7!yY|(YO!mvfXRyO8n`$arNoOFzs+WXrj)7ORqyyJ18pTcQm)2(j+`u+wO#O3RFX&;WkCh%7UZFfyFYlkq79dhx0G{H# zcYi#E3flRLZn#@2v4ld)L^W~GBSJ$%6DyYcULrvUyY4dQAwo>C@gNSDxH(YuZ6il(|Ke4p-nov&`_Bz` zltT;c@eYe9c#N7nlZOnqnRS3D!Y-x4wMDZ}Y11%-sLb1SF{hy->Y=T24W4hG7W)7s z#p8qM8O_?aYRvoHqR`DMcen@yF&2TjUvC0DbBo;HZ}=tV{4IsJy{MLPC1g2Kdikut za^f7|wuk?nDnhb>t8V-hnY@Tvm3q{UKMaD4uyj4af7~SYnq&)PCm?AX<8GG-gd1t; zNHbbfzFgZAj3h@-w^Hg-R0~`}xeGGW`&M%-7+d2-Y|)S&2e+zQOXu4}Kf~S=B?2q~ z<5hAox;4y~KrZywHQ7}*&Fb7VtlRmIz(Acx$}Jj6Si3M@v{Dwov*)Ijijj>H4>pqm z;zr}P0hCok?Dq2~f@sU5`@|fl|C>6bKWYL>sy>8V=~^Gx+cF3w;jsezE^Dok+IQ4` z?UIPUB&!bL3>xk3mAZ&lRaPeoJTtC=>9(V_PW^-XhI^ygUZ6&dkMMxbM|=O7XEfPj zq>KoK2lWfd_Q&O?r+eop|E;)tl)+Pc@I^OB(+qp!u;93?^GV`R((@00)Y!>@_ouF=-ho3w98fZ$Lhabc z>7QUd{#_X11d|SK`eF{MiT(S*;!)~Z*FF+~WO>2C+ILI8KyDHv$|X%gzXS|KYxH99 zWy}!H|HxlUCdPgYu@zTn%9|jdH?oM+mqbQ8PpkFxnh2C4&2n{v00^s z)7isoRrIeaa3^ENg8-FPOXz9wZOI zHLjkhw}B}=34I_2n7qErZn`f3FaSny$UzSOKhlu$$z)3lya!4*dQmx%akHbxyR+tU$6X5-jC+&FKsp}Q^nr%^Tq7=+OsrKy;Sh$k{=uw8!F-dSkYwDVtrSlB^&t`2R-^8QkyLg?yfrDKWSVdXh=F> zwQ(3U$V-pWPp!(JGgrw96%XzNnHNp5{N5Z4C&Cw9Veb!ac$K)!Jcj5-TFuSP-C}Mw z#{8L5m;0m1bVRaw1LPY0Hwj{dk#+MXChtR8kjssDE{#$+ z!u`qs9qoBzHIjZ##A!HC7O&P*$pB@c^QIHqt;>X&9ZPpo=ADGlKVMFYRM`z0Pp+ki zD=pRmA;k}E>NemIi;|O=L;dr#*Ac_XJ8t}w;xMK8-)T{=$AbRa>i{Yyl!h(8uSWB` zx`4v5Jl6%07j?|%kcZwD2|UcA1Fdtotv#f3RBgIXy_ey?`{ahGsLRiK?Hf)>YO@=Y z(Qc7+LaTh)Eo4L3SB`h&lDU8?ehPs-{3K=g?c29Ne8}Gv^We*%u`#v%x>&}8N6Q<4 zE_k!BJwXh1e(CRNI-4v!_X<4udh|p@4U#E-%FTZ6wH9t1*U6hmX$m!m<&DOE|Kce8 z(d3YafHgP0@#B<~NBB|9xJSHRt%)atWam@!-+ygyjsGqd*bX=NiQhel-#oMbcBz1l zmk7;PEU$Ie39@N>w-ldraQ`^Jr0OUqz|lMZ`@0+If!jcW3c@RB9cp5vD7j^IrcUzgyVT<_K7=bmv}$w_k< z>jhDQDn4xjeSaD$j{#RA6=TFFZh09tLVvthg%T7z{6nn5OEc{OVPgQBgXlt<@O5pj9xG`r7L0GF&~piai>M z(Ndqxcf9a$bmW3SRjZ}FrUN;>&iX{*v1_z4besu|T_ zYT?e`SbtmdM1+dG@z~I9NEs$f?eorkpUw~SXe}A{ZOH<_m~HRpb6)E%ywkF$%&50H zQdha(xBy!DGM%YgT$b+?irmvH(n$zWLYazCB=kv1YVGsu*`niVz7pwGN>j=w#$oGK z`|gGWhHAp~1%)()8p1au-O9A2yXEtF@u(%upkf$H&PrXcrRW&BX6DDt<+&>+7%-8b z)licWx=)h!(NHM9HIyiQ`wns;$G#vY;RGk(5l$uqY`GBo#4g!T-Z42Cvk6kWm1uXf z@BEOozQP2uCz3rHED2z0Ol_zpap9*2uUyMIhniTP>-;{bjNLH16!Z*pdi{-$^#&m9 zB+)45^3`&(qQ)nQ`62^r8||gX48rPOyDx=a#pQf@PM!O|$x)&15p^bn)g|DITBS-s zUmtW4Q9F_>^T)4ZnL$iEP#MNoIMrD4_W$_TlL#_9gCDer{0mFyIn`(y{%Wf7ggRwX zKmkF9=4)cl)6FJUb2^!4fjoIY_;S!C{GBv9P?dW6Dz-X_y>CDfw!2rn#A0)ei}HcO zK9C>Z95FUXY|n2Ed2lYPu)sZxIh8hX)MmbR`wYl)EHg?q^IUz6cOuLwY_<%p3nhL_ z@kQ#%sauZCN6qc56luVI?|y^oaCGY!_v?zcU(=!-n~-Ue8}4y~)cqe-S?MVsp*u1+ zOsQQPKF7EGzvQ35^n!JXKUp7}h6wpHhw+7|FQePPJ;!tfBnDy|{}rF|)baZD`uB>Y zBS0VpYf|%_3EV2W2{+ZyyD;VI zkE5kxqYKBce}G)}&es><+Qp29It#|qDa5DJ*}%ixk#QCaYdr4ZyvRH0h}aavmjHKlw4UkknIodMs!O z-iu#vqZ?V%^Vi0*yj6}z>7BrS3mD^;3TTekJZ9`VRfas-=7NNGf3DZXvAzj;91PT= zCF+1|0TE{Nt1~TP56TB4$9zHSEw0mV1#(gFm7ZeMYcC_b%@Z6eX`I?CjFUKGH^F9r z0pVlwGyrlxtRd9@*#HhUh%S*NISH9S5j}YJh!*yH_>^%H_sQ^5tqf5Alq2Q+i^k*$ zwu+N>xPaA-ck+hg9WF}##5acEGepr!7j}^c*KbCm^GJW?__<8AzC`w8-=TZU({CZ% zRS2>aVN2*vS{oZ-S5a#Kv10$Oj4imkX*#F|?k3RgbyLl6ru~S=jz>>0K{WWVg}24E z^K@7ZlMTF-!4Zi*c|FSVE)iyfg<)~tHL&z;yxULOC0AyhzwjzDCT6(V^Jw7*U`kpd z3dW!t4^?zX(;t)I!|*POl=dJ4krLNjV>I96fPc?aOjlf-0OyOH(Xj7%+x37>{}*BY zy?1J0ECRuZ2%;2mW>=k4FSc+1OcY*F`49@pm_3-o2L@DN4m8QmvJWU(+#AtH#B)Zs z%?}c4{NP9lO#5x`E)a}#)|z9ucZ*qkG@hMR%}KcX{UHQ63gFc0XF{NU@7@cCj7uT` z+y5p6EwuRM94P~I^44j01z$lJUy?UvUeXr(yowv1k5;%m!>?QYc0CsmXJ}iB3eBcn z7vmpC!dBRSz9x?h!~Vf=8>6IZ(RPp&MvXv&W(okv^#hq@`pV1QCERF-@fSL&<BE&RD^8*CFLp0rX6*~{ z-jb0!!~GwkLv_I5s(?{!T#m52emxX+cRiG51ofgao_yg9kb@19VV98=|B119iAwqg z=OOr@kbsBUcnrPd$*5Ziii+7bh_VB3;MUQD36IVML?7X+z4tsPP4I#erRPsh7UMQcfDXCewgXsv|d^at> zM=IwX2qzBRvXUKf;U7?z7!#T$B?w85xd`e(kc{(?6t;M;@y+ixU9FGrPKJ=j><_7> zC?oE`$|v&>W+MImgF~qbGM6H`nr|xNkFPVT+)&M2fyvfqme}p5!CU)-HC$xP6UTrm z`Sujp@vz^JWfAslaSa$*+-_LmAgc_Bq;sTN^`=lLOJZn2;DSCxi`*8{-X+l;61`kd z!RIJrIsTn-^&hsHzZ~~Xu+=&(*Xs(sL=c%5h)OciqW{eR>5kwk}N#?mFbI}n|iNtyJ5=(eahP_PPI9*#0Fh6=fI!Ph!Nk1I@?EjP#2-Z)^P8(EsUQd%HY{?SY)kAF2J!iykSo+74FIaz@)tnyY_|q8QB=I7y^YTsU#jJr z@R%@nWxej=O0R08nkK_yrHqpq+li0QKuru#d<^&t7ch(Owq#$>CMJsKL>aIF7v)hY zV`>o^J&-LDfaZ2OL!~8_W+d26YD`*ZmAA$2qgIkUkP-sJa}Ss%X_YZ#yHfH5^xjfK zg+K05%gD(Iw+{VP+eui;11>ZF%xp+xMu)WZrU zmD50lXsJ*ROD|V9@$}#|QuM2zHWgGtJiR%tR;I|l0p z^T*#gm+#cFWIC(}ISrW|=WAuU?s4x%imF);ow_By6egMh1!8IVtR<`!w1KC-yBJz% zlR_XFSd&?aaXQ~;xyD?sxrsKm&LMx9)w=m@Fgy=OQ-+j&eU!QFZh~20Q7>x(+L3J= z^z13n0iI{v)p0{~9*FTWO@yzMoM)T$v;mIsExBQ1B*kWAK}aWtJEBn}*i|YV@x&3| zpr|X#h=qLDOcYIHefZ(^tX}<2HQ67K0ER03-s586iXwGD+UJlPzOOX)9@1tk5=ja% zf;9JkC`iz39y=qq?m)3J z2OJI=6&2TKv$^n)I(XA206&nSge$XJx5YU?n<$-_Cn1bIu<%!J1dgO;;*dd|DG7uq zC`+)J{T{D}d(_)Y1LB+UkP3%t){J76h{WE^TQ$+oD!mRT{))CQz_P3cIH zIvln~>=#5u8)?R$GD3S~V3Byz)UT$7*ATx)Ru~`Y4&3xEgjoD*0LO%n3d>_0YNZ`7 zw{VVT3ceMBvPIP0tD~@Jq>`)u5o-Kqpp!5)m!bObE+?cBb?o=tpV?|-EN+9V9trr6 zM|^^nlL>y-{2a!JK3UK0^j4tHQfD7*6YzAqYkB?=m_zP%{bof2NUuaGRRR72aytBn zeZYAc+~Rs7Y#9ae?9Kk8>wOUu5s2Jq32kh95~v|({$_LUSE@Ce2_F3o|1*jEIAyX^gk!N=wpiPeq(g9!{t zd~dRZY67qEMsGinZB>n^GizU&@G89!#A)sApLn}XLR2bxYlEmF0pPFl@xd;~nZOHm z&%zz$y%dGz^(8-KDcJDe@E26nAr*pkULii`x>hvKMioKG6Oe2XgUh`JGKDJZ+hZhP z`02^hp;4=9Bs_W?Z1TAewnRW#$?{Y?`>%QWT9GF_uL3OTLZat46`a z;~~_ATExNWRES2-0ol*tjGBRsURTMdCvm@BFr!S;(|Y&^w=t4IYCU*(d`)~w6&!bX z?%hCNq<{Z3l_G9m6>Ka=m6*Y+sY<|uB_$DX2;doZ8M<+a0G?$1MP++;=y8Ugr)T4V z&t1m+{=q?6wVjpq%G1@!X1mKELmKfmr~PJr1SL)w+~bXbIpkf0V2Rmq%A2fqaRUjipFXRvJXa#< zh2ev3$mqQ+M5cF}f-4@D0k4C*Sy)0;Lpg7omsVrrr?DCAY{`9mdCxSCsV>^^hYekB z;WvxX2j3q)zju|1XXhU z$=7dIY7^jH^zQ~fD~OGiXdw-KmcDo$8| zU)-A|YJe$dtB57EZ}6l)w#Lrm{bbV#Ul||CXhe#QAY5 zAQ@CQI)^-mOm7K)&hUWn0J2jZls$h`mhJ)Tmy)OnKxA3$z(GJ6l5mvwO;f@{9E`IQ zC9mvLmxT730nqS?J4o>jWSvg^^TF#w&pI|<;D;X`a8SA0xHWCRHG=-1-&sF*fUTNS zj3wC;maeHPJP~#vYv~DVkU%m~-#RtXDSl9Vm*a&m=RfY)jP&sHJDIDPWh8OU^bqB* z{25{`j{IiX?tML#Rat3^54K)^=W50P=hkejceX^uxrUK=GqH!0=-rQ9u0$QlSEwe_ zdMFnU1Yg75RaZ8+<0?aRsfZJY?+<{M;%oQt>;d3GZkmt;Bfx_ifTop|c$iRWUpE0~ zH1Y(0DoU31@e;cL{E9%Qe)4n83b?J}tqHe;7MhD5R~hKBL?zd0Oqq(AUb@Hk*JEZY zSDUpiSFED5Y2UReaGykcw+Z~lb)#7^0u}pYD35Oh!gf2YX9aQ=df;6~+#Q&ifh0cv zknbI-JfZjNJOf?@-#HBl|DE4I0$jR{&pH@0h>5DzgQ`W+#=|V#Op&$j)Y#-w{7O+ zN4Qs7rYv3`>XID|(BZstiCW(A|FPw++Y}3pfztmF<~^ltz?u^`fx|I;H-u(h$N8gC z(76VEZ5U&f)r74it;O8JwMn2mq4l~~k z0?M$}KR1Dmz=lhtV>N*))8!zp9Jaj*{ra+?3i6W1x>g!C)-~X29;!SiyK0LjaTFhM zw==oxf^aI+uKLs+$ezbBL=_}nyjn^XV#;sSPoJp))&AG~16yKd@J1mWks2A20a%;6I*ma*)EN*}pc3!F|6mED-w}d5wJd7f+yl{Fl9@LQ_}HFQ zg{OZoQV5>R7A0XJ>s&KTs_gAM(Eb*)bP;($L*i!t*)J-?NUD)z*{#9ui;vl!;V_sUYM z#fbf(IShYbFFR%9iL;(L#PPg}>L&Gsw09&)|4G=WVMdaIo3c-4`&05YQHqEDKMsy( zHae#1l@7-4jHe|`>%}s3cP4DFkkFrrL%oeHjzVd4ChN{UAcLE)!-wPi&UA@NFY8E# zRrhtTY^N;sZ=3<0Q=NP&7fhAkpH;*J4f4|lIzg0RK?!3CY=yzV;D?+1#J}%&%E(j^ zu@MprVok-V35bUrH_F_;i3+^JK+tc_Hl$(fFR&~65O3bb%+&lSrVdWrm?=B`ys7#a zesTC!z&VHRDN*f+7atR@MlI$p2)5Lhuz`pDUN}&rGqbNxlyU)~sqCcOk4g;od^-*u zd0I1n6CZbDE(ro5PP%reD*S!@bnFURslf$ruzV?|tm)ZIy?}7Z#gp4E#HNySg|t=iZKu)vQtzlAKbNey&Vx^=I1x)CAF&ew@Rm4#bZ<|<&3_{bjxRy;iPm( z_9^?@5P<#7r>xF3mic0M&<|ExvHyX`m~94EN^G1h8n->(-zqKn-w91Kas6Vu@#3Eg z0sC2p7(*LfI-@0m?PKKRm<(E?l7>~+ehNit79;i9f7~0lhO%Nzm@%aOhk;-?B}lEj zYvlURUw>%AKu@>{G_@FL@Q8C!q-k>1->4KPwQenZ#OS(yEnBQA%}+b+^7vpXT^YCy zKNFn}KZ7M+S#~%u4ashZ4{_ACZw){bcq6pk?CMUBGoWwirZUcZJgt{ikVc;6+E%Yx z6ITH(VUPrj2BjN|34;wbJ2+N5z`HR(2%mP|={gp^EJzBtK}EqZ)U!a(Ob7H*RLw3w zJnRT5Jcb>g-E3tT;M+3r%wILwohZ# z)VMAv@H^y7q}A1MsUW2!)P7LKOipmq`aiNNk=w1$vhxSM)w;j@fY5(}s)3yPlUr+> zK2u(vbbXXopf73beV^bB4lcTOO$4_57mP$c?rg>-$W1MO;Et}&E2_F*3p9kKm1j{q zeE1_-Aw5RS1%gcd8(cB!m$L@We2y;c66u?__dsTlzoTgy0b*9O-h1BNf4{``fZ>Fj zYl8dhcIYGPrkGqx>+1oLd>fsCVS6XxFxAsEA!ev85^{7L#7>V>YV88O?g|10k3tqk zT$$}yDo9rR=6FxN>(;oiNr~gksIbTMArIV zMx7m8jEh6tDVa`M;R@te8FEW3gL;5f(SRZMifr0bawS1x@q^i|IwrD``1FO&L!rSG z)g9A?TBy*avPdQrae7E5ivK(#E9#wI-X~YJ`m_`@qD6~rP6Tu~Z$X%U@yXglpk=dn zgSLY>f7JF{j@#H$mRt(qo)xn=kz?rfy!GOcPc)F5H7WP+`%)x&CbJ9zVGL!XoAZGCe2onlf^xHZYKZ$%3|GI@KazsNPpkE$oPZ{;i!)Yp9TP%6F0QC$DnzPq)u;gW94# z8&OYeYSk#Mf<1Z&7#hobz;QjMz0m~moy?o2Xf{2hAU^i{=>!sFC1DA(hv=HOy0A~} z85cJ8y_<_-+Bb(aw^=iRuukn+5*f*AGGw@+s|~p~H)xT&1@JlTh9EEm4pDVXy{*&u z0KBOd6*Dy1R?<5@Yr0~ako@)ZUyk4L{zw+u8gFrrZc1Kcu}X#BEDArbZjGucoO=?; zlIIY${*^@2D`x0h4t_PCllJv+GD1akEY?f-$!NQO0?pJv48;0l-aW)44MdxH1~FUz zgEQYYdrNlvAkIE8Eb^d$I>xUHj!1|q$3=OO|>{oxz z1z8hY+sSndXQ%vcvq}RY3ltIQE2Z4zn(}L0Nv`EyXAiyiL|7)(VZzM1Y$ED8pO31L zk?7KT&x;)MFr!xGK}3o^Z!y(ZH>7W$C$So7Ghxr1WDNw*rMd#Wg1b?y@88*3lt;LP z+?wwgS?|OMk3QRSdh1;|vrpw@^>6V#q>P(zt|a#G3FDaJ$_#a_(r2PC5|9Ng#RrDL znkh^dJK_T4B#dOKb=IoMPI=zsah{^T>B2(NGN{Gs?8CB_sO;i5$s{XXCmQ}FP}+kC z{(u5t&8)5e>HN6sR3)8CqyMkr$?Z_pOV4GQ++-`nJ4|j~?#=wTizxn03CwO!y_26@ z*Q$jvf6rhbJ3`;E0_=?NmWF*?bus7O|Olk9tdlKApcgi~n$&%A%u)&l(xmH zYimxU!LMk`_^=UunB49fvigg^1; zPE8i}lSR0Kt@odWX(wlPz}s9`mY9kP?W_gws^H0Y`0B%uk)Uc%ld1RqW~RxUdGpNB zGqKq>^k$X5wuOnmR?Qh0z2A|cVYAeDpSjiS{OvpoT;=rtD;HUB@L_nV@pByf$4`n* zx6ien)`O|t7vE1lr(_TH<6kWHlV8F7-CBR%MLf>l(Nr-ruKpr?lFh;cc0=dE1h7Ot7%4^6(Kh!ZbirVlFD3Atg`ZKpG-`$t|n07Qq*e09@V^B!){y zDQM07gS4z#Li-DBgT=OQywCBbaY^bp^%Ox75|8n%XPfyNoT9Zo)xBjEn15e)6Smejnp?18m?U%Zxl5;wV5MO{Qv zxYYizQ(5eb+$#Dh2uAPsxfL9}ei9Q9R+dr^MTORcVaLR5pZgfI5%XVURzzqjU^f}z z_YrVBDEG8ZX^?e)o6Qc&q+g;FTuo|B3w17w|Etgb)u?@|Y;^+Jx=$l*%b7l?a3nRZ zJgd~y(2W5if zOf1-6ky9@e$|d}Dh5S(?lD$}*DzeTu3sk9Mtam$MN(BY5W2r(4jXeJe65jazLLf@# z|DlM?r<0Y-%_uKwA09%gqc!(%WTY4yw|J?SE8zjUL1D^TV>fD>i~aCR-~!8n=@-!j z3cU6`#?I%*9;BvGnJ9RCG$Ilnj>ixG28u5+s@pXt*grb7Rw7_* z=&9q;Z_ihjSv)zmRUaq$Pj!rhsX@(gZA^-`&o*%Ph&5KX9)NhpR})6Po;AJ9Q1*;^ zX^b}+)$bm#_G%WNKC9a^c$0w99PJGD{8-KKn1+^DE_2rUK_qN(a91X}^FUc07V6)p zgWdr9F|=xPk{bGVx2(2Pi2c8_0CYnJ?H=@`Z5SStU$=U3f+$KqsXfcqLT%XZi3Y4@ zVfbwx3dsLCjtpTuuYN9Cwypi9?UcB289-a47*+jLb@wTk_v$;vPQkA5N!#Y3u7RM> zf0Tyino|Lvw5p?wIEk*8PjtPtBdf#tfg@jld=n0X&@LN?c3~o{A)3(HYSM>sT;Z32 zUpIfFoESd3ZL3n44*WR%Z2;@z=BlvU)k-oJ3 zj$Uf`8%aBIIr^b)T$dE&H2**!3MWemeKdxO&MS%&C?1#S~KC5r5#zq#2Y@Q#!W z>C3#Kw8>LOAVooFB?N4;5mX1;%tF?rYO~jXd7PMG)VUHfyD*y8)9th27y1qyJsVo-5X;&l>X-PQBv-Y9J@3yC3&w7KlerjF=4aN+ViHb^%z^OFW0VUj|suh zHK6h(M(QJ9syOC&(zsF;GBj4uW%LU`aI& zb`JbtlBrLoYMgJ&Y;1Dy8?gZ^f4ZpC@WF`=ER*L3RBS205ZV2*U9@=OYIB-(nP2GC zS;AgU^3^7HO3*h%sHR%4BZP7xt{a8#3`JrI)IV1!bRefBxx^ zIpUZo(yvad?#h$}_uv*pPk0}(bp9-J{Iw6n>78GuQPrYPcOR>icNa_K^=8=W*u5vG z*B`0on~5}a^}2Ji+;8BrkW0NNN){w7oA;`FwHNlF*>GY@!Rfqu7P{TI;<5Tr67g7g zF(jUJkVbbZ2gzC{;eppq?;zh8`T$O+h;gg+nu{pFx8Y%yVKbVz=?o zyX!s7y?G;n;oI1o8p~(-{$;_NeA`CM7U%B(X(fOxD3~}X^p|may-^U2onj}=fpG;k zJ_u0Jd(qMhZ6I&N!P?u-F3H>rr+|b~S|CK1pAcfFwQlS}MU2%sd$s+>K|rTce|vyq z1Sg;U2+Y7Thp4K$c20T*35O{AVCtE9&Z@0%N+bN3GpYFQzB{BL9h@ z_%fwA&7gNQy|ntV8enzOHW>ZnzIE4=#BQ*HBo*T!!Rp zn?Py*QX#%GaC%<#uApD)W;`={)HwORMn2VCH14uh@pLBoHT%dOQ}CrwH&ty6Yg(v9 zVp93fc1{HRh;j9L(HfkAD`b4Dn^w2^lW)Er_P=5JaSMxBmgGv!A3NhNgggbgIUKw1 zlDWk0_fUWoaycQoI+xI44=>@!*QvbQ8pm1BqZN0{eI859r`ON-q(6(HzYE+_?1cN3 zZ$BwrW!7VyHgC2lwkVN5s~H^R%x%^YFes*t>0aMYMr$xZCwchl=kjYl@A%LCP`D8N z#OU*{ih||Y$MTJ~q2SQd=N!WQ6Q9ESgyDy4fektQNA^6%E2x z=BWj~cSJoDL^$NwH*X$WXG8CkMArz}Ri(h=(&{Ln)ao22a@q(XfZwGyIw+}7Sbtp% zviVCjO&gNF^6CDlgPqdnIZyKgFPicLRle$&EzB#CIU|#l{inRDWr!wf)xNrY zr$V=;i@ClAdGH;lZco;3VwUq`3*R}Nw{(M0Wf8JK)7otMZ?vaea z#86&6m}svRwT6GmAA-QMIU0IqNEq=G?k_LPR(k9qnREG_Kk~B}ztrSN6$@V1zsaB( zSBdB0i>igLy>=cb2G(=6Y~no?k#h5Na*-naDYG#>ES+e<{l%8B`|QC4CxK^!vw?(E zFX|l3Me_uwmsg0`84a3n>{e&}6K7xw8DAD)7tnV+ROq!ASd70{MtlW^Qr&G4>8yVI z=awC7O!TDNU|b!arc-9<@h8hzAa=(is2qc`_4$}rzd_KcK5%h71{rJeym1l9^Wi3> zQRuRL?fg~+cFDL}p0$~&dBDZa>^{atw(<@qylA`dxAU}5Ko2iPRfp@uLris(l`<`% z#Ph{_VUIC^sjo(UQ+awJ5n@-0vt_{e;zrIO}64ce}!`fxS94YW1$8B(~}sO$=@S9CD1net6*BzR{1_R;5s8@ zmnSb%7gEz*$*Wb$Yjk$>+8#c^B&_!mEm0IGVqeIA4K(EW3g<59bhY3yw&Vr!F#Z(nsJK5%RfhK5B(P|3=wf{JRh%|Jn1MAKKD5$d-z>Q#ueUVKp z4RtMziuEALrCtO|_m1q>HP+3u)$+ntHT?Z^Rbu!4xF>XUtMr4$lfINvd}~we)Nyca z$Jd3%iyyq#$D?CUA2Jwm4#c0%uvQ)C;F4eD1KBJx;2P<*zmPMJOfLcn!+Em9CU^oU zo3!RDla1#) z*Z^hM)4Us@bgZh-D<5khxzPF4DJWE5>M3(~{DEQh!Q@fk-gC_-tMQy8c{65fV1$YlC+JTN^H2sEh|3Y~NlhK^GeASjl;)?O@dI#6 z%Ko}4B0A!006k(w*ZSk}lHlK7$iF2w%vmBLaNuy!zbr|eunWR%u|d`Xw875#jYP`iJ` zwz=igMu{eInzr3Xusf2Ul10ifJ^RM@AEvd1kg-_vvR><2V7C{D(^r4S`Lb!dg!JWU zbD%*lrpy`w>Tx1@A-6bB8-9l#bKi!)h!*jq|LSLcsQgf}GF$yg_sR71>0)eeX*Vr* zXNHQ~Zba7sKiJg8<&hs_2vfv+P2ym~1IfsGHD+97;WDg*N=PfcdmWgJl2I|qglM2UoHCHSLH&l8#a3{oR0Jjkdiu3SU}&i+gF!$8 zSLMC;b*}rEAR{I|{`b;c2C{(ZDbTA{k3*~JQV9*MtvfZd`!LuD+&deuE^(ou!&u&h z<}`M_4UoR|NV;iX?7Ot)5-Rc-hLF2MS$noO5|>d|Z~p>GRvBvmEdks_hLwU_{7%~c z+^}pWjI_`lgRIv$*0i}KKpWjGy>FF~J@|f;+rxdkI+!V+QS|Ny;2&(V+42UzWU1MJ zf60XuY#!i)5Ci=y<_~IM4Wkqcdqi;rq3GardKY{yP%6CpjwW6MH>eJCl{;ljwey7>%t`)-D>X^n@MP``G;`cqxqw;>zRm=4}33Sv~C$| z161vogTB~lC)_T!8jgv7W@u9VsQ?O7ujimFbt7#e)w=V~%DBCe-xBk$4H8tf$Hm-VxxH9v+u-E~+ zI=)G+9euQt?X~9;E;rtvwEPEsy}wv{r-O;nZE)Z} zF3QeN@36j$Xz|xWo0M`kS;)UPiAD@Y#+kiY9#{C_A)dOsi}>_D^qEV%RxEkc-?VfA z0EK+i5-idGZ1(>5mn>}JuMyug{s~>It{#yCU55yaRqGb72HCt`)VdH`K{Tt`B&YeFi02a_m)YmcY8--tN zoP=b8MAv$CnYR`WiV6I6^AWCU1q2e5;h_J=+>D)iqHa@@leJoP>-t@u!8LF$%i3hjZYM2h`RZd*qF?4K zz!DEHN>`+HU5y0j6ygVcy0tDul=G=1LVlQw{(%{Zv$+-wu~$5jS#m9LoF%Q^mqFS< zk&r{EoW*fmsB?8{T1UjQ*L;8Z+4IF{FBF;eVLE0`EWCX!_m$`x$;>tdW)z%)=8^mm zVcmoS#7xla^Qm9kt~+0|w*+{X43xKL~$08{!;x2%Ihf* znssvHcIj}yfN)hL_Ip1<2m8+392yT4R3SQ!h9fjIOI3Am$5O>HUm|jCinyU@ z90y8L4%_0)HW8@;vkc}ybpMMDX1?qFLKTvoxiR!YqfmD91i8IwExiJ;jVwH zVElZp-OV`q?^4`2xok9N<>MY6*Za1Ivaj0B_xUIrc7G~i+vO)|uIqvhw;LA;<*U9| zVUO`A(~k3dD%Pg~qdI~=pwOfX0PbhM?=1f378a44;XiZbbs8{8_+kuW<3y4?v2JNa zBBR44gEyuNiEfa{H*wO-5{bSQvhtZ{6O5rLwE-Rbx54`CbUz3qH9-ZXVrmqJvc?L> z2-N7;xWycO63^{7GaV1-!((5aJ8aji>o&r7oQUHlHS>3NMw4A+Hjpn7OUscsB(4B3 zC6*s*JWea-RDub1r8zvSy}DTA!rU^mITPp7b(EXVE}p!o4Yt>}9rhmFZ`k%B{3JwW zmYw3M82`oCTSrA1e*dB~Lzgs2BOTIGl8S(Ul+r^y6UDDk!BNEa`hqQ=* zboY73@9%f+Id`3N*IoYMTHtc6d7pWoz4xcK?}!bfl)>NGszYWS7_>JE!F#NH|745N zC1qxIlvdDc`wR7LRnTo&jsHqRe>^+Qg~}q3+e<@3vdisiv)tK1h1XYl`ysg#a|W!e z;^6rzTY8Zz$Q;KsqYn@*T7!01|FK7P#p`-LjT#~{1B)vyEE4l(bKB^iQE`26O}6%? zzgUv?Tg>WgJY88~Q-%YA9n4dt$0#M& z@YU(m5#PzHyG@yUfd~pO22fIQmT##NCPk@{!BOd5p%akVfq#Rqlgm|Zk?mBX&WW2B z&K}Z=ROtOcjxN&;TJBB_Kn}OB*oU6^4J#?!5r!4<0s*Vs27`DTa~>oKA^ zZx#fWEj01^=^AF6X8tm*H?-92=HgJioXsfS13N+jIwaZkk&O@8r9^Ln8n|UQMrwrITi>&c>)j|e(8^wMMvY;hwe`sTUb+EC@D8xe@-m(e!Jyk{7$RqO zzjCs*)Ve&dfzaJ eOOm2l$FZ++Jbj3@&E!W(tJGxq0*odbNWmhnWdQaeBMNiF{Q zq8OTCoNHEiGFaJq8K%)UT?rMv9lsMTKbxqmuxHlL_(zc_+OcVn$twMTp4=MHfZAcE zY2Cx>F!B>HeYW=+j(b^<3%FF+zIVUEXkjIDWHcvf@vdUyWFXt7j51p)(*4rrOj#C{yK69zi8m^S?GMi111c04)RiSQeu$fox~@-y@mn1f$}j+h(_4 z3zA4=tzkmzpsXFg4+3w(I)CWKY>4Nid~hSX^b6Dbq<68i`JVBa2S8Y9Fggk;5d*BV z`ztiIbMJk-Gu_EbIrEef(O)TLkiLq&$0l?*8sfFa)gZ@v2bV z8}6*Y(Y^@VPc3>*oi+`-zc*RKm?XcLw;Q)MPj{ZLu4MWWQL0ncSvRO8mArWVT?mg$ zt2`rDMTOCA+x&caF>s{3irQhZwdHSalpH5Hm$tI=Y_;wDsn?AoSh_1Pd38miQateQ zwR0%qR-f8oI&XOX&}2A!rO6SxtdPT~fCPq+YtT7mZi+eN04)K$MTQ<~_xNGwktnXt z3R5*{mHs?7ukp%0(6X~?&Y7Uu=@`f=LAy(yK^yc%M4;Zv=ZfRf{E((N=92# zfdE}_O$Mn(Y}gYF22)vnkk?3tI2#r1PK+K}Qw`1K*@Cki#ABXm2{$90weP4k*s2L4 z&aZ|SbjzECKGpOeAv=paa4u42)E9kXOb1-0CY89G2SvyHuG$3;_;q&~vf?)tsTVgL zO44t{--vV&j;nMvyBPHYbd<&>H5Z@3#SUQ4DB$uT2#S~7Dh)wk*w!r6%woR?|5qEH zIQ;bgR-ljYH=~S1$zF~WVdc}}mgS#;oVJ5xr`*PJ0EVse+%-U3(Hj18K*-7(-Uadm ziH7)tW3}9GXq?-L$B!vNAE||3UmgvLk2K6kb8l8~nDWZYnvicPLd97o#9dqvLT~+P z#J&EwjO(tri#1eSx8Gm%VT}y(jV9J4P#iStIUSn-yvJ949C-Nb?#594u4QWOLxnG; zXOQl{pB3rF*T#UDaGFtRWF?nhczQ2|HlLlInF+Q@XmfF$rQBrFeG>Ac!PS2}qpWM1qNIGxM&E}73{uN??Owu)9w73`6< zHA^yR|8U${Qj%O{ywQF(Z!f-51+lssisk&vI9;x94srv$Yp)gngV58iK&CMOz`K2A z3fW=1Bph{NZopY4X~x8T{f6R>ULgI3G@FO!3^PGbyZQFlYz57P~7zjN?cx~w1*;;=$`_}kAJYkxdS>0N(KtN@V|U(9RVB& zihhKD2RQ`Ug9I8LB5}cE*t6@N7pC$qB^H(!XQiT*63z8M1_-05|K)a>{7B1Y+)sjq zw(VNiFt%_W&3k$>?{-zt%G`KhQjfe#?me*QK!PdUz@?)CdM-Ykj^I1P>9J_Pd64MG z6!Dkrd+RgVgV*q`ofn*~eShVA{$gOdJ4xEXYrDgnSJC{>=4MIn^g{_~e!oiL|H@(@ z$2sWgy^`l&Sdu21<`_0D=ZZ($OR1aK7;Z3$n?^-AhIsoe)XK2LX{+f>z`!K`G;Ce- z7V-{`tPfalY!U|~KL~Kc37X9{Fr86nn}Dv?dLlEAMe-fTfe8k`s4)YUZKK$SeoQNg3(c-L-5(YJJ`Y(5Y2MgpW|H>i238zyO?` z#BFv8DGv%bU56ANiRz}v1wH%zluFkN5wD7f`g9SE?oyNV^W?rzUCy%ZKy-Spzqn5y zaFwh9`ihTz3jzAejBB*p*3trF7G2ue!ttlQ`hWiB!wC1Uezm> zV|jiwJNDY@vx7%(0coG#ES9t9xED89X-l*;3l)Iv(Bjj8wl@_5BgU_>3{bQDy7UVE zAq)ewPx>*17w4zWzz%HfvHG%0h_~n8*&nh-s?Fzr@?)*aG{ZTOaRCmv3msS6p--#0 z%;88$tejq4xHjkD;VhGBB8-7=2i6HO1LqI%ZGH<%7A9496Kkku^epjnZrRW&hBj4> z03@-+h{|evhCRUSD9i-_F^E(tgFgE187O?#Nu*A$GuHv><)m}a-jftJsHs$ z3|wchaM`YvDgzNvE%4e%m}V^`fy6NN-gp%5t?OyU1Hm|_7-!=XUg4RLgQgSW37o&( zXYkGs+%k8~v*PzRG%v!3Ht-VuTMMB7mBV>3fs@Ix5ZC4LBU4iBl-0=!=<)?_TfA4x zf_c05y#iVsw@!h0=2Iy~$C-rIFOVc~+X;cou=8`WuU{aLNSs&XNWDAV@c!5%|0_R?lyItH$)Q;r3|#|HHuk8jUqurKbv zqcFJ)Jic~*Xo%W9sPlr`T{0l1km0E`#@8d`IRPM~9aV9F>eDCHn17#DN5u*=RIpbf8y_F{ygWS!&&YO(v0shkra`vwal5Dw{lkXZxO#Fr3v%!F+W@ls(Fx0osT)bc2iZ(V3=QK-!uOTxC1#291@d zavvB8Ja)fcDr*Z!AIJsyWQB&2(EGQJqe9!Ml$ZugN;bn6%s}W^pw2n7NM%DsmCw9tb4j8&EwLmzt z^!z!9sJGe3#SXzx+_g-o`aBOg40%%jQIpR8u_kshhvua153}@c|1jD*T~lYBxZ0I& z`yudpz{P46Q)`9B}VX4cu+h-v4hn(#&y~}1=bim>Y0D#Zw1)5~nRroq4yA2$bNr(V+ z1duO1pZpMl2(hWX#h(J4U_ZDX`6Yi3#Z5UXbr8J_ch2E$ni-0(a9G(#3^MmGGLgsO zno{MOD7Vv+e(3;4a<^;Z@Po!dkpn=5e)@N)}U&sC+`ltfhqy)BZ9-9p+u+@CCxs6fXaj z@+f23Hn(FeJeMn(yeOZn$hkZ5_ApqNE}zTwGF>EGm_|0y9ZfwvQ`geDel}#js`Klt zFvz^d410rS*gjVB=%Z3xm@*AftXV6tzF1)^GA+6J_OOp(1d#9k^*ugAXAnTtx9;P5eoJkas9eS_tCsl`mKt05nSC7u4;d z2qvFbME-+PBWXJ0PNGq&yhtt3Ff)W)tf% zGJEDgcklH&6TVm3V#C_NrN>RkLz{;b|HB^(HVw(O=#H_DCL zbYMT9f!j|rrpll=V+&^OdJVMFQC==8Ej)-q_a5?w7+5W`86ZZ|Uzn}p9_(khj|kve zg^VCOR-QwF z&;YP#5sB5}6LDG>G1YRqrT9a;y%Zbkq508=z>*DnQ&u9eNwJRl7mp{4lTuc{Mv^4C zg4H!ONb!CXp9;H!x~+n$U(XF*-b`v%4~xNffTCW&P|jJ-4r@W_7~BEthy?K6aa#)9 zcic2lzaO-nXjK&Sp6psiuY?CrCWIietlaY^x9Lj6<>~!=o^n~Uc0PWUsJhEw_5C<`bq?+>K>3b0W za?SkEx!^${Y$5}&M}JLy>R~7HD_=TC%y3*hhrTZ-hoJE8H1ElDAc)Z<;8YvU4Cv4_r|+>I()-s7^}#P)5g&2mi)=12$;kH#6~Bocry)EQxpr^$u&eABNpv%d@>f+H2 z)|@iV6C=vmQrz!tBOJDHcaVgvA;-lvkc}k9tPtfA2q5WbQj7g7C8PGU6d>69#F`8Q z&>fCcG%eXBl;`4>>N;TLk;f=1;S&{(B409^C%K7C=r@$6-bC{-o>7!!x<6l%3yX*> z>`_;sq8qt;^qS!z9tDM6P|ktQGoI^k0{#r&6WxH!Ibec)&lZ@k+KY2=23E)qdEzHy zzG9fL))OJ&MbN6^@Jvl)bMn$E5YRMPO2QV+-|l|;?g(&0R=b~N2_qkDlVauY+JAJ% zrxNTQg1Y>8_*$2bET?|@l>99t@a@dn=+*&lj+(>ziVa8L37yj3uf9GWk=@lkntj!H zn-zOkx2EB9Wx6uDcr^RGu|adbMe8i~!Q|IFFzosb{^qpY4NxewFW=17BArEDzm~WK z7i7op8@gBWgHrB&0MTwENGwLFpD)Y+m^}dcXqXRg?rcJV5sY%8f}ho^l9gjWl&cOF zF6fd>lY}F1|2*lZ$tq)2CKKYeKV0)&BTwf7RpphuqQQALM8r|nh}DDs(23$YSiMkM zX(ED}1AkVoMu~*)#t+C5HAk|#JYf9|M4@B=_VEc>lM##p0$mW2wMRa*+n0Z2 zxbt#ubsE;Z2gsTNPw&YeC(J8@6-DY6*L{f0C$*)lsysXw;C(2&cbUK z)F|2A(s0nU!W$qVNCRj7rv)MVFL!v$gCJqflwjj_EwC9#kMW@n2^7 z&TR8|1c1a=FGDVF)kIXOS9%m6|HW`gK3X6`uzOCOuiev7-PoD)f`;ykQOqi2MU0JY zj&S(DyD8N(42NrL=1)k}JdQM-FLFS6D|jI|AqZSwxD755JPIj}q+%qv289^wE5B;@ zE0eIFu20-tV3oDA{Dko|l3ay2MOO=CL{khul(A_Yr-H%f3L5btv!bE!gVuzBIyfo_ybgJMN z$rKk7Ok6ip;+iX8&M;uF{ex0Te@FO6C5yiu!qvF#=1FSBh1cYOesXCMh9aLn_#NEv z!i4iAQ5>gm+i|))^%(H#)BH)dq;V62dX!BQaeUyEbs6d3ncS4z!=t>ATX&ZPVotC; zL@CMI4PRl$g!^*L0FCzo1?2P?*q7poYOa6@toGxYB-_8{DO2@=VzZrc@*7aTh3kOu zhsrN4yM9NsfFN*S-E9nTWk7$`v^YpAaIs`EgK0yc8Le1Xq=T2@Y;pHhq6cNxz-=@w z{@tr@L-%30yq&?=eCs$#+to$_EuBZt7N~1PvRxxDC*+)2=&qT}248S!6s808a>-7Pd z-(@u)OpVsbqw;19vX~z~wRECNblpb=13niv6BD=K!8O zogi|bc1E+~*Cp9^S?RG_}LNn>+@cuz^q1nJkO3!%B(WS{W4|YmjfNb)e%y3 z*fJ%?f$KDcsZn2PEgxke5l6{d=NpXbh+n<~YLDu>7mj|Y>!+U#ynLWrD`V}}CIO2g z_{df&pO1VYfa7wKM)a7Kb@B4{d}pJ1TmgJz{p@gHza(J%j=IJ-W%Y@T#`IjXz%Zo? z9;FRN;Jk?`dkzr>XI3RlQJXjaA%-N7On|{J=6`WO8)0lYP{|_eydqKaQkIAP*B!zssJ{CNkIMZWvlDD0vb;$ z9wL0|i8QdgOAt1`HTa_h4#!n+^p(w7B*26R-+IwP?4joezW9gT-e!E*+i zFg%=-_vhH|B$6?pcgq5PXAXEl9gj(%sH7PCnP;f4FU>@k%k@5Q9L4;>A%mQX)UTAS z%Jq@>P47bmt_umCPZh2?<7G!5>EtC@XYbExY|9m2#xC1f*Wj+$5D%PR^V~$=Xah+1 zf@9cap!_TtP)RNU|0~pcb1CL0pbLKi5Ei?OZC*vspLoG;xL*iiY->}_&c8OL@zJeD ze7l3~>)iZ?U|OeHI7d@=@M^Rq94btqzYS#Tt2jbG$qU73ek%lPopK~3cA~WdfAs^g^nAFc5pL zt3OokHRmC2RPVFmeV?8ij^*qDx(LRdiqGKDNkvQiKgCf1s1>(6qg({ z&ttJbSD5Qm8!>(@AYWuA<0*GL%OFdNP5LrXo7i*iqI+_& zdb#^F>!5giWb>!m&B-@vKFM2`;>5xG5@P_M`sT4C`qOP8=NgeN;Aoavvybq(dH*dd z+q-9~sr;%>N|f&WZlTKSY1zI!5Y-|wA25^bew(jlP1Ui{S*j8v5z zv+Kk`P)6DSj61O19L(33rZd~sB~Yt*8}E8tg)d|mZ#O?mA%MCfr?LZpxa5f=!W`u_ zcRfj~zdLJox?7zJ3pX@_l#u&Ya3l?e)<|N&^@h0Vg*xAY&1Qrp;tEXamC#%xt9R~0 z-kbl?GRB6|gHI!Km>~5_WLk!vSsi#K#^RhvQkqxG)az@=dmu$+4rw_*Bb;;Up+=Qn zi8CT6g=^=06IkP)qw0k}$@~5kj4aBQHJR)si?tu>TGpemUX|+oe*nrMy!RIN-yn+X z5>v_|^tVa1Zb-AalWc@8YZVQ36=6nD`f_~R_WFI~nkYBUqU$Ig?jD1md)Tk@g~|Bt zPiur>ZNc67(%XxCHQ7V-K2QGjcs9@rzbBOWQpwS>^ol5hN8(^0A29bv-c8v}E(LO| zn+_DBIc3b$42Ij<(o84&AI>SN>vg#4H%MT~JlUOocFr?p+xn-RbX1SuS?&GrzDE6p z2EWlnK+7q9F>$kRKa_R{?3LCo-K7=XxE7eQpO%)rm8fhh7z6}W4TXE*Qfg4m+IL$~ zmI%HIF^?m5o;PnI>8K@aN5TlwpNtNK?&S|<9a?VeREf1Qc*$ii74P#!r!~$tx?S#* z7pY#B`|Qr2Hu31USC3Q&bx5xU4`Nng$lh-xcn0V`h8mc6r`CgfbxR;Lhc9^)2 zsp_6ME|u=4xyB=|%Re4~pbqG`W`I0n8IQM_k(9iI0Yu5=f^3wzW9+9{E;}J8^3pmq znARy8QUjN8qq`J6#EwXWfL=!izW^~!6X1rzJ)LILv8T9@gdeeQFkd%1%#8y{nfKH> zw<>h)LGa|y1Hby?Sq0|S^N4sJDZlv(5wa-%0#QiEwJ7Hl7yM%a({wS}0IU$D@hKw@YH zmn|)C%&s&X>Mo`Nxk|^)e%}blDwwPjR1Q6aS95rRbLfAd?Vk((<(x!_ zCSB$lG0MouPCa0vsIH9Ft^;E&x)%4 zDX+dZ{&)BkeLsW8 z-+6PtyrNp8Z%4W~3|wc6YxVa@Ji5G!ouOHoX;}!X)1y+Si$Na~-?N&cQK`$7FO(*( zi(bIMs&xA+-z%nV|Fbo_iN`G+H^~&=LQJ%*AWE7o5Q`RKLlKJ4enl0 zD$}q`KR?`AD(P9)uddL{kCi`6<*lwLfCrYy)Bst)v@lKW?}sOSqrXagwVtu{_xqmw zd8^e~DvgO*mI!0xn{WqJ_eD`L+by$qv*nb^PEJ@#R$%Z#6s%Q*9cX_x(U{(9K(&Ua zSSj*<`9yT*lxvDlV4YT+3Wa)aqeL7WrU|MY?^5xuFiv#Z2qc}u^_iXt*T{R|HBSM2 zqpay#P9p)WI<$}8uUyj}tvR(1*czU4?2`K|u`lga>@U}-$n}&NJs@cp=y0;+srqV^ z?!F2A{GQey^V=1Ff!^Q%RYV-zB{d)H(22c^kUWd1pel}_Jx_N4QcOM(*oWI}xPIXm z)4&17UiNDE$6^qy@B8!&CCHQ2Z~cB1i^1QN9C0}GJdWNTXl}v*i?Gs6#cooxtkVld znXYB>pvRw~e(j0lmIL&!X+l?+wJxD;Y8@3Ox7CJDG;dT7Ky8|3!vpSl*cWys7{FCwi zdO%P`LcTxZ9BAy--E#z{%yJ!QGEsM=zz?$Ba?`}W=SU*&0!O?P-iXNMS{1$-7wGnk>J} zlkLr$%b^6(sT?)UUi==-h9`5#IInd3p8V4!b`eA@Kqa5Z8Lec_4$eqU&vonjNZ zlIi@tHxid4iyMBMx^748eamS<;5P~3}7G4zdIm>hX>M?2j?AE=l zu`*yQX*hjAJ-f+Yt787N*+W8cYpi@AvCV6bqr-IWY(^!K*PcW&;QuY{PyQwRzexLK zIzDv7Soi0JSdK`aHgo^Fffh0-g6vh-C~)s0c;p>xipA31rDTp4U4feFl0S1i?<)ei z6h@_5z=mI$vNe5oUkE5?Wwne2?0T+l7mvVpg>~AAVT9HZxSnk-J;w3Qt3kl}^fcLC zO9=U;5lfosoccI1%tW%9Z~D%ic7=GO__<<}$>VAwZ70+)4(NL4K11s>fjzwfnm3*7 z5#z0EyMy~GD>mlRXEwuAjq4z?An71BVAw!B+*#CD4q=)LH&p3m^w&jpf*ly?DFs`iDWK!yV1zvTsSg z(dLX0W&(1Vrp$W0Y)sPC18oPJ;svfpyLUca0%*kv%T?!2gW<+H5y+uD>Wx0XKle4N z%CFQeURv6Fo6z_p0TG}sb64IY!&h>>4PEd3#IdVY1J~mgAoUBvzp8wJ7h}13ehu9P&ik6vVZ>Mx9V-u;dM`2a^7Y>LrErhoFnhH zYv#pJwlC34iRQO%25cHmdZ(4aS+P*nNJW?QV}`VD_&V$;!w(2%o0Fa-?zLHU28@pQ z06Ie>H}>}t5bP-d*|6{q`mV#nKNR-M)h0@=H`%YoLEi+Qw$C1__W~b}R?h8%CtSK` zHu~>3CbWMi>D(!SI>|Ryz)3=XG=39-)F`4(a#k_@_$9^{fNUPUxN91APT(?{uXyF& zT3_k0H9c&*!5(ls2nBlh<%#>73AIciKi`R5^>(qtqcW$p=RTf4&|MpLrk9VV&Ig-! zIQ|d1def$j7SQJfk;g#|{3!`@cr)#faJCLehk4l>%Yt0zdp*eCukQ2cX3jVc6sSXG z4rULOw*1Ztq>pFsGpBdT1My6*M#Gl9rCTa&m_HFR6OrCby)gbsKgx6dRbJ{X*cD{p zl-4+3Y?LI41M&N#6$yP0b z{ZKA4(l(-x7S}lCHYJ3D%wV^WPqBx&PlszOXZc|DX&i16{X3`lCp-ox_FH*0zm8gz z-45q#4<+Td6F(gedzI?kPP4!w(E~l&oj_3ri6nTcagOzvT|mERU{mcD{h)Z=4geK|fL#M=pSWPknPd_nDNp*DkZWfHd ze^4FL>bBk+J$F|p%WFy>&w=^B*Gpd8`FQCvo(hqclRZ9>R`)@m!2GV z-3w|sKgWKsC#snixCyNF)N!g==BRr6V{_1YYC`f$756RHLo=V;{-K8qWBfuwa;A=~ zaKCE|5el#IiNT2NbFw+zxeID*ADZLb3&)io0d`kEzv@XQ@U%UL?YsjgOKdm?W?#|} z3Sd1Mx1RiNj4bQ&_3gfZ714&-QF*6hY-<|(?c*IJHo$hllsIG`d~v-Y+_o~!*w1A2 zl36NOJ$|ccuLt)2Zt`ml{D@WRViqCz^gBrxAc}#jYTN=|t<)UNc`Fo%?XLjiBLnFQ zw+5(Zt*_G9Kl=PK7Wq}^S52{lc*)gyO4OS4YUH-5az)ATODXsEs2D3HLj%<;my7hE0Lr zhO_-IZ<}j3xM)ePv5M8tr*Cz5?>l_4G%p$*mtE!h#|wp~EA+MZ$~d!yH~mLrymuyq zuCLA)<;DH`Jd#gXT^E#!PYiyRC`CG!>F|~v3=e%#jj^3%At=KQL9l$3*qmJF&AZPI zXjr-3ZrFZE!yETIbD?aahsj^!WGnetxg^NriEeQpHId|2Ti0u_(?*koR~ehWlib9QK{K}wfEd?QfE<9m z-9zOQ?FVdD1V6ACB?R8$T|fcHR!Ml%E=sBf#EP>)V9Vl_MZW#+CQU4@F^<$1keoBZ z_rILmL-G?%r(9ITK`Ie1$Up~rb0cn|o#Gw*hUT`xxE`6Ar+}Z=ZrH%1$;ji@@%ZOTvNzZx+t=b{nNoJN zV|V*hyHcqW|)UTot=CllYGQe z*k&6hVJ5TEV%jUfxRcnmJUFuDdPTTA>~ykHy~%Fuddefd_uF@Ct}jjc{MY;9#(nQ# zmY#HSK~CfH+d5R=uY&6P>qee(lWJghqmkr2kiXn!uF?KjW9_r-G(RanS=xa991?p- zfOWKOjmfX~jCT~+FY%QV5-^DOvW%lIkvOFV3R^aq6TwDbeDrA_R%0sW|8PUVRENBL zUZLpkx1vWqQTZ>zBuKZN-a z62N(ZUMJIJ%CTuN3^LVhFO3ruT|&og0GH$Lfjdg;wJo1q*SsI=4sQ98{L&FpICt=} zh|jF7#(cismOR!|=I(do`9 zPj-^kal7K0ZDkRpiw8}NQT;K1O*sn%3In^h`_XS8xNu#R>2l6<@#(EcRqYM1Xvn;sdH*!RQ@WP^72)og;s+DL!oVp~0k zEh3>jh`6FaKJZqx(437%JUPZb=q(nTd`M0-K?yqnwB|zwBa!GHPZi@hT>3uXkOC~& zue@qN8IO7+yBWZ*E`ySQ3Z9T|>BkCWv5g;OI`m=0F!050dfSvGO@8f*;ge2y0Z7E? zb%T|@2X9*e518Jn0Hh6!*=rUC7f{%AD_umiY(0u6T6L}$HaiD`l{QfiRm%6oC5V_L zd!cls(QzRP;hd+ORM_?C5aRUsQ+1kb3(1iv*Ze@Ot((|NnZ!Ph3whalEln1_gaDBK zK(^idx3HQR+0%Jtt=!XsQ7m){^T};S12^k6ndY-|kk7JNFwv9QFL-wO_dJ^KHF_ zun!-8h?oIGEFii%z{dYf5r$!~F(}VHccK!y91ji@xSw%o(H%S%m3$JseDFtBs&iQIHXEqmASOir=8{1>#w3Z&Zw`4_;7HQ6c%D*t@Yhu1dqp z2&zKm%I3tXB%uY8pAFRh>uG@|w*N47si?e;3Yo8GMML@}`|OJ=k^v_C4| z2RQ(5k=2h(M6)yDc`7=K&rz;^;_tIp9sVYXu%?pk_n=D9yK>sFII11u>8w;R1J2gZ z0BvWpHLRDIjGINm@+o3KvuO>UYeg}#A`nGB$iqYTLP~P}4ehyuwde-?L^K9`+9B;< zp0z$TK`u}YP#_o?beA97AR0t(eFY4KH}D~K9w3=k^{Ai>&|ww#I9%H?6IlaH?=Zkf zDEBE)z9ebpGA=$$OUE3h7Chl(RQqnWS~c@>-Zz95;`+@5Nfq(hDRWc`4-Ckyl|Fc` z$ojyO>Cj7(C=fact=GTWFXrwpZ-H$DT#)?-AF&SJetCcHd5~=XKScLnBfzA?H zpr37=_*ogHi;$18wuskw<733?&=3O}eHRr3N*EF6o$MfiakWRhvGr(+REa4v?dis# zE;)ud+iap2l^pS;$yz7Lj^HF^=XLfP;Z5TTkH20 zZvQ=6cF66oCoGEjE~k|LL03xxYvLGjXe~1w>KQ6buaU8|4vZY?-$S{?H7!e?Sgbnd z<)y06_uF3pyR$TSi^Pt+%}GK5Hi;#JY=ITX{Ea}#(_6^j$n1_}JpD3IX(VxQe4-We zU+VP3lX_JAKT-~TEfkRr{_PQwGQTNNkX5 zVnuNKv4;oF8VNDIdYcI{h@6}Y3%c0|tjO-5> zKU1bUetPMLkc2R5Qdxgp*SPBdy&x+@>z6kX>-4pnF670UNj!*%Jav+xad#xb$c2 z=r|4-_2A!e29OBO{73S@juSr?AGqPmf3QNh zXBRD*aSWLTG;9Hb&5IX;3=JsewIAqj87eFnv}xepDAco^xV~=z)f%~@lR$zr>vgJ( zrJyaTG-x^(;m^q!`rh#;>`K=usJet-BkA-Eb zm&Lo-I3=r5o~1!|fDe)v+%AqU(WCjjd870*lu3B7^^s6Kf$87HE_h&GGsa}8nXo~I z*4IHjVSSoDh@vf@G4{Y=JzfH)({EM~8^tyPT0tFtV-Z?l(vA0rW?wJA=jmi%!+X;u z*o1`F-V^uammw1F_&+I5k7Iz0E5P$J_@c)rDg@z*IY#fqtl`b%QjVWk0Ks+Oi{I1} z=r#x)gnMB==sg2pV>!u3=)4pw=2CJpS!+JA!Sb1v(b@)-^^Y_#z5qZTvGoLC!>*s* z)pJ14dx0{*yg;=CxNfM&1GfMPo*JvZK%P+ela&G?eeDpm7CHvK{!SN0wOw?L2rDbA zOPIBO*O3%2d%e`_3O|d?7tuJ8Xjk;OAZ`bACm~*k2OJAc&Xn3h{7;2fVH6i1gDSZ` z#)^PEWA!&v4h40zuU~K4oDWJZXE5+b_h4dR)5fw_`wi9i8_WWlznHl?YoMe3D4I4Z z0w@`&_@RpmIWCGw0ta0sj)SnSP0pmQUHM~+H`igBNB%isp#v{7F=~Y$Oh(VV*HahQ z$^t&Nu{Dv!albfltujIL*TqbNtCcZv7$e8R3LcU-sisYj2yX z^vP7t^edgy&ztd*w3J_P*8#YHgz1XrT^^1_02BA!uPVHwLT@^GR!7(`rgAFntH@BHeqfDno)4^O707T1F;ce+wtZTFr zRQwl)$ZiDW(xg&W?WRY|2BWTkU^Kh*I@Fa?ip_$5C&)z>4HH1VEy*Lom*;D0LmSdS z+Kmfn=dh7H<&ykm2m?&(j-S(nbsGkesq=8&Fy_!%b$Qg%uLXM2K8})4ut*ReEQ}zZu8BWn1_tGr^CvH z+|leC5x#!_H9up@n%Z-(h#RSjm^Vw}qaTCUx$QGE$G@7;;svcon%B}f0#`g0&=}8A zl<&qy%krYUdxrRxj`OH^(NX448W(u8-GgKsd>U`!J;DBSPn2}Z5BRcdel!_0*ogxx zV84@_VuR3q1+8E}bQNL2J8tRseU;%`VoARJAfZK9%oVQc*eA|U1Ao)aj(R_o=o2h@ zF(U4cqo<7_yuZF~!{#L3@Ssf7;b1VsBlwsynR6 zUp_Q*pr#rMFTYut`lMZ0Sa0ad%(rmgS!r3{8n~Ezqitqp>qz?C;>nmn3YUB4)Cg!Z z058a#@a=1QAbzFW7WkB$x)r+#(XxBMJ-z%hyv%V5^(n=fh=gvY3XCMp){&T>&^*cc zjDKF#LAFR%7t%{Kz?*+e^5VicPt5snD+uorQ?PM8CSCvo z`+ulXc0$Xa2AcADaKM5j-*?1FWjzB0aO+k&Tz$aRbCg@NofxeFelJ6lll~#B6#cg_ zuIurbDB#FLU!HCN-luBf@7LIq$-Fm@q0?a<>!{2**LQf=VapclpVx#_X_b~=-W4fy zumm!Le{$9WMXc`wS*RT9t{Mci4WXiNy8LKaMwA$<5Y_2xd_rX^WW5_#N}Ux2dBYR8 z7X~YCVb7H_pL#^y+X_B=b%g=@HUN5vRd5O=^A@sd>e9{4CQRHUF4i%{9(qNg4&5!7 z=OL03xm0ydns1 zh5hLPKGn`6?~s;%g>@O2iEn;aoAbRxjl^TBEp*k!+1eveC`E|b@Gw_gSNMhs>25gpa=-iC`#Zn$`^FyMIA@IY z$1_~`tmnR;dC$1!HRmKiHnyEAZEsRtpOhnQNPe0saDsix6@*x#r7XJje)^$EtP|Tf z2%Zv&tY@o->QORuR`nHgK_wO@LO*x2f$}UY95tT$Ly85BR}>LtJ1t`WSwYtB{#$A7 zq71?2fsbI<`dTpetK~anB4@K-+dg}?U$mIvD)hne}Iq#l*!7Gd>s8AKn-zy;?@lZWu^XD#;-d1W*E1BPRh zWGCdjSK+4hzA0jI`t+4p&!S4yl=bxRiiVmthIUvtG6vehh=v!WdhxB`vIVW+HV0~h zkgm3CTRan2+#%JAHJ_j|o+XI=aiH+$_!$GtmhixfP~#-$WB&2InO#=J-qmUN$cAyg ztXv|0f>8-+ipr<}Q8l$%U>=BOK=IS&eVH4bJ-6vSg{V#JyJymQ84BG|8OE=^+R$i? zmpB7(ejd^yGMG@JMIU5kE7E1G8d`H9DD zJRq>w7c?hEp*tu|ng39Z2k#?aZ=6d&^t5s$N$Jy6H#)9Wf_mQ(P6&zUFY)5A1jyFb zR>tZsKAJz}J*!dgj^V?t)3w~UKYj;tJ$Taf^}zszkjZaGWCS>z94`1s=hZ^mOo~i3 zyXR()=i9Fn!`9>(1rZA~-U!?x_+4l{;uvehKCGI(ki1dZWyOA9WQh1q<3^#;N4le` z>^Ope#pX?iQbIzx@e+2y$le@#21zs5Z;~V-3Ou$m$HA;c&lWjqQC6khIQQnTj&Ra) z_o#%|KXP)E3tV+>XH^TyEjZVi6gfDnyy(sKUh;lrzQ63Ci+tp{Q<`f0du^j(WO%6H zcD%Vn`f7Bs=2f50bbXX_jWqeB%6%2Blg`MSed65QJp2R=b>Sp7m+?>0^wbLHd$ZG) zXDu<2b5Np#>dcTaHW$p$jOw0n2^VJ<(JLwZvLb~Ma`4iaN~WWvkl^XUi1F z+GE#ybiuJO>5=nr0r4_;s@a~ak@b9c2Ia7-lu(*@Me-&F!C4*+zFX!Sn#&eL!4uj- z%qa~@he&dM6oLlTgg1?FtVUm#hB)KirJ~i@vf~f&CWGdh{n&E#?8&G)brdn zx1;sJ4dnyy>iEQN);c&o;ZrKp{&{zDHCiKe1>U{}-qD1gkoLKek&tO?tKE%FOhgJx zET?XGut(lJq(>RxXZQKtiwy}RA8c*ia5SvX*1`SZe14{DF72~&0vEt;#DR}t@Mi>+h5Zj&YND)&y}v?-E)F2VH9X?gQKGivn2S?p6=$Va}S2{X^0XupzmEB{;M@R!(6 z)@Q;R_t{SC+&iF&H*-2mHD^1M)&fRHo2k1(-ch`^qHR7K5^!+YPnC0*i)w24?cRu@ zI-ZxJmiqsWZ|Xo4rgIhXI0?i>Hi@Jbi)ECuAAEv~qLHeufgS;$9v#$Ujly+ZC3b=z z;7>WhveMPTh4VqDiD|u8HMTUJOGaD(xpE}2AV951*8z|?RSr>nqxhgg4$FvbdKx}( zL3{*ldXL1@iBWyUq!HCEKX=iFk`LxF7r5iQFl;npHgvqvr z1b#-DYBeuO53vBeB+?Hk>r`Qp+mlD7Ymbq}- zwKLj?a9}%={dl1L6vcIyh>*ml%Hue-A*Jq8*2%u8n&q1?>N{e%lJ*6LvWK{S55RWe z;{Y{@6v2*!nu83d^PBGaWtKruozo__l)ege-7T{`IaCDHoDHt9L>=F}eM5MgaL;=K~2FgRl zv+tH;d62KaM@F(=L%+yiKcrTqxwV;Td+rvW7B_L}L|?GMs_WD#s(&Jr0Y;ATR@AxK zKN)YDJh|-3DrX~5QS)p~uPJh}w8j)HooR1q#n6zht%;epzv{9n!06IQlKtU$;8?MB zy=h=6?03<#zVmx%^xUU=7g-QHb$)*K5|T?d-{@X2|Erl#8JcRKC@+C7GEI}Ws82c% zEJaUUL=z>>1HYd%;LI{u7_s0ed%(9mC!8$QtGtfeg^w*SKEbx0knf3tI~!pX)K~mE zoWwI7kPOZE_GXUfhydd5v&qn=H+DPhyTR~M>{0u|^||c?9{0QH3TJdA3nJO`M>{v% z?A!xkHSx81C$}OZ1$8>mDDx5zj5*?&G2Xm#BJJ9S=fZA?Bg^j5GTJG&%! zOone;Z8G=syIOR=*6Mm=Ve@=ujh_>IV{!zW&ordwqx9*BAs> zVN>-Y*OCq_LDUeabzD(hG_l*kOidm!qzu%J>Xjci`dntX_kJ2xZbindCT)L4`Rxmk zRtBSYOSr&c`1A3tM`c^$)irmtySj@1`im*!)?e9h zyP8LzFY@;@g(qIvkkJ7#N(+mjok6M;spT#p82f&z>4b~dYqvL*1%SLCUWGXIwq`L zY$rnr`-6Pxjz-dZh2WgVVpsSi%!gb33wddKH~3lKaR?w9(C0=0<@|V!W$v8=dDL~z zr+p{R7NmpI4Yv(_1~P_i2^2QsVne86H!9_U&AK=b;QsMx#MP$|B~>?ERq$}hs8B}F zoJzObIpB3gC1unyCwtxeKJ`STP4D@)JPEZx=-Lb7>@-tdv)SP&^rHnFt&sXr_1iN8#J6ti3g}agdmKQ8Gozc?` zwpgO&qEZN4lPC@j^@GC+frus4#EaeBEl!9bqMxymKm)`!vbgu^Z>q-6WcD=Jy zJ;I4SH(MQEo}UYgCI$xSwTt=!C3G@IILd7BI1qd$eKx|smraG*`%RUFse~&;H)*)L zaQN$5`SEHL-0;>|>bR1Kt%l=5v@X@1tfUswl>{(^oj4GcMXLuaAAEfuwCQb&y*>V{ z4Hq5{VSKaVK>F4LqFC2zH zmHo1oDNgt_Hgd4}@m8R=0>k18Ww@XrQ&01^&Qr76)+!B*xZWqz(@4bO=X#e{`pMq26L|X z=hAG#+gc7ico`+W>(-k!wZoVP@ZE|)rImuw889>V=hNvg<|43VqdCQ*uR1;~peQTp zY<_R7sUY`DL%is%2)>s=2n^SK7agJEE}9F zA>#YH#V(8&Z19L;Vhr$+<-F%Z5}Fz2yL4mb_uKUe<4d$Fv*~Iwn#XdX+pq4uTfS~a zifI2r+maPac#0RD*n!J*n6yDt*h3rAq>)xr+gxqnbvE2n6$ ztVMC)=X=Z=5dll;2?c#t@<#L?4#Y&^UE_-Q4Rf4mo8BdhQZE*~ ziY$;dul9wVe5QgAE$8pj9v5u>9($gXTcC4NGoI~s_X5OBqK7xct+*Xn8f7=F{_ro- z((2y#(GHnPGU6zE!H%ow=L4Xk#L&TYwr@Zoc)X0qI3hW_aJ$BGR;f8Dq9e9A-Vm)W z;n+7VG2=Apm9ZzMsO;+pSvG_4T~~*TDl1g@Hx|+m+GUjUC!_G!~G%7E-K34%ZHefZ&GkI!N5j_JI35tEC5xd|ef{@X6fok3nYhBC>; zHfE}F05Le^K7a4&9s(8WKsk)tfcxN1Nht^R+vF9l5l}Y=p+F29r4i5mawHz0K4XNV zyZME|Kk>OygcZTeXp4wU_80%FA~ISc+~p#~LA(YG;5k1e`jBcODUwYNY#ZyCb^=HR85KEZOoY9Hsttl z!AQquVvco4xLm}MZ*=hhz7)iwY6N)f$UqnVn`-#W(cySp{7q3OGlmSlBbY|QMnn7i zATNZu<}gur7kK^%`lvQ}Q5F>F823LKtjvphNk3j(T)>hWksy_bBPS=vj>Dk)7TC&P z4+SCkcCT6uaU$Zu76c8YKLzpv58iv;1Mv?*e?9*Lcv)$E3CIF)MTzt z&*M5Q@UtL+--z|T^YdS7Ym;uAjpn|6WogNv z(cr<&&cmZ>i3cPdleJARTldx;3sD3}Iw2!Wxg-D`sItDZ_)3#m1_(2eEEVLE}jrY|lQ1 zvDXemYwzsjmisR`SOSS^Z zRxQw6?N1R*%kq9^_mG>LyVPkzkpnagcns36qhn*Qq@)mYRSTXFi~0x=b6b9WD52>t z*{OAdiH4@pQ=d8Ut^4@RawPBszF?7wiyguaN_~8@A=tqouwMKWd`*~4Qo%w51}cYY zM0iR{DaxqEJ=xK%`;eD-w-8?9L4!JhiT~qDG7K(yD7}B0+zc$ekVQ zBQOm%8f0c8K{d6L1^JgRUphf&$e^mKbNXdFcO%eza>@Uq2XR5b<+r_2NpiD1QCLvW zlJ%MuK+$ZCffMMm)WU+3g9uJ3BOJqLL^zy9OmML3(U2a(!Qn)pfa{}gVf^6r$)a+l zPvn)~?Psw|Tn*MLAv?z(c#3~?kQwB$p4boIu$ksM>f>GLY(kvErkcFmUS5`HX>F~k zuO}xbpOvClN?mPR0Pt2c1|drXAPL~Asj1nT+3V`g2ei&i_Up2;vMMquDk{O;w zM$v(vojg~e`4^o!R|i1|39oH$P{Yn*b))xnl+#9kBuMQ!6kTe<%p7qb)Jvzj7z2^P z??KywtZy(Cc-r@p50+W&B;X{0HeMA6Do!ZJND;g(D)^qQ?JnATAF-m!^7Ss?h=b}a zXQ9}I#frgd3fEg#8Y}ab1*DU8$>9Pm-cnGQPb|-RO@+8@r>u+vn$_~SAFpH5UzE;O z^4iWW(vb?fGR3(rfyoq9fK0aHdRRJ&)e&A+c5tUw>%7%cVYbYK>nBHXLC190=yO}! z!am6-e`AtML%?#g!0*E(j8x{fHJojHu-IH0K$ZE3>Mj=J@p93ZapKQ#aMCc<^e6+7 z1gwUJ7F@q^+(ZFd4i9E>q=}XgQJ-hdiRP~!L z-9dw68dIPx`C;Zp18sCD&F3#`AK%56`erLGYCQ^sg7SF$1a7NwltVQ=y|l6fe1pS@ zrY2wK-RT%Ei{Xz_GBObRfL&74Eo#Ly5d~)#mmYkGhVEkUua_@hF19U1K9z|AQzGn- zf%My)9^9C*wdoDD1ggRw@V~`k8J;~G%(1gR@=|V^>=BRtFtyJ>A?u@?I?a0gfh?SY z-~5<{GgI;P>vYZC+N+uZZQ)_lUX5g9Q`<|$!Rq2~zD)lC82jiy1Y;#-d~Wr3?Vwz` zwTsvNYkjy5%fkzm3Zzc76-c*Yz5`&ZkN5?OF+spTjCOF-TsC~$fe6%fJ!O;B)EI5- z>R{f}0&BwJ@@xb$N>%fSu#?kQnxZ>br!)=^ld{mHw*}AK))}^=bLclcu-J%o zhd8t^j2CD*JtsLjKJEfEgI8esN>>b{TJ>Dt^z`&9_)hyyukv`JrRBp6T5s?{zg{e~ zDuZ2pUOx~T^(kp1pitr_hADp&2_F5GSWNpu`PVw`hM8#;qH$jL*XjqlM#}oi86inB zs;cWNPx4~>?2g%(+wC0>l5tml^w&Q{-SZ_U7m34NVct#T%dV?BmmMio*}jd*`gr9~ zBC~sn`A~0HG`6@S$M2Phm8ivuSXF1>T%WpDI9AI3#Nar~%Noxg{fAGNuo4qBKY3;@ zyJ=|5G(2)!O6Dgn5H;N-^Z_n;mK^WGcBu7E+K=q{0`KKXDnVS_kd3P7qC}P(m)m9^ zf0-;jsN-v10fv_96H@HGg*>vx>$F&pitYNKFla-AE7>i)!>*VojxtO!;Zw;LKZ3mi z)IYD_=2sK!6;L;|O>&l3vXuO+mz-|n_QKr7c{dy+T+Tlt5HWuGK?nMq_IZF^gv;!n z9wQ^;o<3LO?j63`&FRSrjp*$OZk*f1-X z2spyCU!ULKF5G)NE^0{|?abBym!vxH4f`}mI(*@4mc@xc`!8Uq-_74(s93{)1w;Rj z0BGXik57#$d@Uw=>N#b0P^wpQJ`3Ib6qJ7eP_K)B0HB*x1s_U1XG}*<^Wp@;A0{TQ ziaL)zbwJ>stTNgN*;sj^6feSPI(*;P$h=AM7XZ3Lid1Uee&z3t5~jaZB=UTq^lt3; zTziGmSsByZ0`K1RLf4Otw+=S2{l$arFYTLR+`l8@1T+}B)7i{(a_UaZ*E=jqGh(U9 zF)r(2f-SWUw)F%5MdP*FG@w6rT$-*Ae~?1*rK=XbY*-&gYQuH~vclMjnMWX$rGkWatp zrZmJh`#`R85YNsJh1{;HZKjs(;1W1^zV)Ra6t6d2VaaM<$vmr)Bt}B~ngBdFlQ0%9 zkbwIK`lU<*PcW+P>PRez7#34xZel@V{92s>4bm(ITj)ID{B51%n(QzX0@3IVWq%LC z2)i0TfH04^V3fh|QLtRA88N5)945``>g>HQeBR~xXYhv;rICG5nf}>Xz1mR9h7XjG z!n(|^Z)Qqqo9%SpZP|I)2N>t(r^fXsx7AoHSbx;3>%G+qxE)H6lKDhpt5NlHYb@)S zpr)qCs`%X8b}`wPm7eBH+L<1U!Ry-^?_ zE@m+!JNsUj|2D_Pef)AD8h7=IS(wfBUN%J2;Yt#~LaN{pnLTfPgAP#`?}o>#Po-av>?R0uKahT*KX<5^x&N5u5 z#sxp&pTzuIlD{DSeEVZEoz|L=jgiqjg&IL-D&5hdJkbXn27RoZyBIhdBw~sAW!3>~ zolh5el-oq6AAFf$FO?AkIzBgx9r%Bju;sl9LLz4F-zQ$x$Nn3u-NG-R*iCPzCw@I&M)Nf2K15wT_7tTQ^=qHfm<`3vOH3Mb+$EfcJz{ZXHeX$vAvr|$?yBrBv z;LpI?V^6%uhNi(Xl@4(fJH|GZc9$bJ9g9VEGlD#j^83zDl9s=JQ?zh6ltZ=NwWXTg zNy_NOL!A|dgN#tNk(5ZcMry2zRzLOd(x7*Q{}*Ial*QKi`fp$pJgTtVqI3E!KhNmM5x}Z>zDPfTfFT`PIU3O?4o^=FF|{a3W&CVfasRO+JkO zTe#-J-F+~LWTn&l#|lfz+S>W!{Ud@kkrlVcC>GBv22urV=ZYg;2;@|#a3DzhzBYic zF5q@tr!}r!Xd_fA68A(>duEUv@!|z=`WL9-J%Q8z^D77j7}`U-z_k?p;76VYSw>u2 zjV;M-k)b-s=$m|C$x^)*Zm)ljF&f(0DaHFHL_|P%dlT}qRZQBr52@^XMPPVHNpHW;&$sHzIj`$%=d>9a zlk(Z48yk9$P~~co&-NxQOHJ1#CS;stiV_nA3|fxAE=F8<8>EkSgiCSZ2SVor`A#z| zD8BS0nKea35)v?J#nI$4gBZdKAOUd$Lw+{Ejfw$quwC}kUofvW3RhjS4qXIm!14Fg z@KsmtH2y=@vqHV*_bqi0$n`GoaFL#9mvHXKR1m5fgK27QAY1?zUOa+%I zfoo@H$6@sAVX4cuYANU|GhAh-M;*dX!;v2>0H8rakO*ba42VZYyntoaT)wFo)%E67 zZ!f73Vt>cBQtftLfxi{{*uEf}faw3h7aqW)d1B2Ua>2uu!jP^rd3I`mob;j+4M(bD z3A&oB32G7s@n5M=`xNBV_{fF#ozFoHOLL0dEe@+%u+ZmWMhWiYMc(2z$-2KUAMiH1 zC2#QQC6+5bT`-cfmaF;zoe?AY>i`G%m!#mjLsdqsWH3Okpe(4BXdGMb_S8g-=C zwDYHoL}d)F_qsKXpPaYHL(6UF65o4xMD-={;tC53!*GOOUkr#DQKxF0=o2_h(24mS zY1lb9s6EeimRxtxe|T5BY!hsa=HfayJJYzjx~>A`q7C?6=5`hhf2 zdSTBq8qxb3&h$&PAp7Zn)m38_q>tYQ5yZP9s3b*t9hO>dPqw@;kA`V z$G`~k_eZFbBsxb99zg5e<1paZj0YpDXDf=Ek7MG{v6Uspi)zkgAkaqq2~WqW5wep1`r-8~s+7C7!dENo0tM#4hqcW zqTWbDF`PwK7*2u@5!QKfniaAlvwex4ocm&bA$_bRzMS5)P0ny(YHuOL7;aZjp5f_vk=Tt1GDk@{ zs9vIBV)`PVDwM#-&mWnSlY_ln6c&bshKWgASXf9yPya*yFfORmT7EpXqNlTyGK7Gc z+Rx8#Hf#Z(QPtiE1qB5{b61M6Ap67nnfIcWmzNOz6SuwDgqza|J<{+`7=(_7_Q&ge zK}AKZ7GPKk{aNYJn3`TBFt|>JoVZyiSfri1@}}^mxw+3Ls(i^4Tcu1~JGE5^sSbH7 ze{QJyUJ9U3Jv*}HLOQ^JWzD~egAi3ugemZCN9IFEM_tPxOS$OpeR_X_#tPwSKi{9Y z;E?}jd~gTM_CJ8(XYhWzqn&=VpE;JQmwcMt^)=0a_B<=B_$jXgU4c$gy02#q5}HLKmth; zz&EfX@c{8%yf4z}ElNjH#)j)NWku(# z<^uRC91ej{>P!hq9A$ZMqVYLxi=P0XmuY6Pm>i4e?r5!xgsP7c*3*#XxBh4u) z`_gB#li=9W=c}4LQoOcb?R><-+yX$lPSC8oZ}+Q-1@1>|uRQd_xa`kFZ2C>~bs@xY zWo83WKDSp67UYwKhOTU+V5r5`Fzs-r4EEk&4fOslNs@@1yuZT0-A|)mkM5{ca(8mc zRUXy!ISn{}GFaq7oomR2zdw{?Q{$fF)zChHA+I!G=h2CIh=7MnNe!;4KS*%?eavto zIN<;fZuicl&R0W2d>fB=3QwXVGVh`X>*dJE$O_^@G`&(3P?h$A)}XP9rpfX?5SALr z^>|Ds?4p8#T^aXJ#8$CaerOdM8uAeOSvWfaf_sdh#ilAScGI!3couqfbwwi}keDnA zN&WJKJ9uVmdv{l1zR|m9m#FaV4=jV4k5*$pX)~3BMZVNyd$p$LWpto31JPiJ18z$9 zTF4)OTn?5lyEJkI56+L<DE~feH|TDK%sU=k*yU*zImooeN}mN@XfIq4%nRsF*<7FJu;cm1zz^b`02cEth5~Dw?hI}!+kxEx){K`7{7@up z%3c(>F`B`TwcatRp^wk62lL8*K5x^**Omizhi%gyM#X_iYzZ6q$$yVwb0WaLqCZN9 z13w{(mY;5lCc<#<+gO>+t%Uw|jqdJyR+jyx%kIuj^;fiKDl))N7%TZD52XAC<{T{? z`niB>(0u2DkxcXi8Mx8*uyY~g%SM6tF3y+A2|z;L%KoZK6* zatVdzYmjniPtQYd^wk$Zef9`;7d-iDaF+u#*j@1caTn}V1~MN$Z1`YB-?bZ)8i)p# zzN+h>z)OiAe1}zFW)BS`W5{g1d-Ue^b~MO{L_L4|9p~-aw`c*YI{2c_pcUD1u?ddD=jQ$L?rxu5 zKvpr3x(#7xjLhF%F5qfFHEjp ze)BDf^QS{vz{Pt1AEMKZ{~#VSQQ+M1!qH5oK00Uw2Uy$#GMAI_Bp0eSYg? zray%W@Om!UsUe;Nl7ot!iI&|*ap6q0lAzo=nhIbz)^J7IjKymqJ?ap|aA*JDH}4IN6=mOPrSwp1D*^z`~APp)pk6Mp9lHj81Y z2onhoqqR9XyhF8l9@ViM97tX;*E&cLEegUQ(2+NL<0rOO6#D85tI`I|o}uD?;z2C7 z?|hQp3gNjs3p10emhmwXg{fhm8aas3}tcdb@?yUcIdC7}mE)ai9HRJ4tKMj}K#H#cNFSXX8DlXkvq{^$3?euYz}Z9V4j_4TLafV0I_X%khm zzxk;Zo&;-mVMneUyJ^1l)5ed+zCK)&^kN`oeW5PU9G;C~o3<9P_S6Xa}{@J@~n8_*T z!aCnypifOr{g_<>e4LJea%_{(=%}b8s$EGi7v&>Ox zC%T2>eoR;kpKctTSF0^@Kg7>gd%Wrxm@#>&bL+u>$jebxa$c3MWl^I)&P9RpBNjW? z-cz0Od#UGwBI!~oE7Ryy)j~uTE!3`|Y2M00hu8N`h$#%3O8hhZa)Bb=&2GlJ*5~xi zMx^*#P~;qDnESJh!QWfZweh`3;o--vGDEuC1?w{z`$8$1&m=zF8LZbQxEkePT4*DJ zOjbC_e8{m>99m+tE;0rO4=m;4Wb=Kbr_^hm$XXUZQNmMpi`ypE|ir5JNg zKb3y2y0QsXvwF;Z^c3HR`BmsZM*XY#h)-OPKGxL<(l@EPK9aeqC@rN1*422v-aWaA zL7QCYeG{2xTw2-yTJ`zf+*4v=;;icG3*1As_oQ@q7#lac!`T=$z$fK*-63+Yw_kLm zuCG=*6D3T)*QEH~qxhg0i4CNqlQqfG8vY*~>b; zX}7|}vb@3V`n&5nmSXD@q9hT~gs%j@e%V*>k|tgY{P;Cq{IpJIR`Bbcj@0rd zPt`DqBIL|c=VkwNR%V{oGogsMJcR`r?6=!!Z3~df{1Q~O)Ipok>Rbm-2?9Mcn+~Ka zcN$&35&Jz>h?LS3&YW{Q64$-$>9T!X*CH)JnT0PWC|77*8d|c)5tI7Ph;aOmfmN2d zh=+NocZdgz&+mzv;DPx_ctj*6v+TMy_(p2`US#3|+Tw~}_ss>fpub!(s{*&~klRAc zNpdsR3K0+tKr7Kd2_Il0A`2=i(0A#dpLIe+uPY0Ny`?sD|R>4m=b~Ob)ec*bSeU0jR zml&UD)}ejF1+}3_8=ouGdsVL9U@|b@uj5@N8`7NJ;Z!ri53uB6$%gP?$X=S$!UR`;p7>E1%;G>_G-=%bQ;9^|K27ua%%(362I zz;WcBOMDV;zBIdjSNVqj18oK2t(e$63|$d~kEa0dr4aUB)NbNQ!Sxy9B!U9r>(65u zf z?5uDc@*m|FJ;MUUUkR-PSaIz&=2t-9{D|smJ`RHxMBAHEbh*gLgoLgjsI}U`bVc%b zR}%bT9B;ZW6*#euunjJ6^#8o56MA+ZW!m(C6U$-uklERZS((uPE(^i3Emq0i z>QNCQ>^dnEgO~c;F-3K$CcW-d{jc4hc!e{eFuhxHS`@)gVx@qoJ*xMexXp z-*7{3yU*tW>L5(#!^vp6%zK|5jWfmr*k2+*{Chfbn&<#Yi{UAt<##I^QNt+uR85LT zb+UQLN&R2f4|K#h#gl3ISBczTkw*z-$k=hyPPfHv;!0-FMyVV{0D!3eiG5R z<8y$fnCxAdczbzyq1Hj|7DQS=g$jqqiMb;{`IOr9mK*@DIA8CFVoG&6CZJ-_fQZh(6q|+4ZZ66mGHA2F?`R|hOUV9ttBJz+B z4W~fWMCUFUUn)>B-SsE&Pi+-pLhJ12i7ObFW}i!X#OuiTVT;OB%s38&L6ceM`={}Q z+`m|Xa;0^dW!t;4;>c4ihaCwmP^AI`dfY+0w2@f6FYBYVT znpx*Lfoqj(R%8i+v3#a>c)@ozpe1uwadAY?To0BZBY;@kmsxx2Jb^#TqJlue%F7$a zCny-5oJENFqG^JQHej$iDXfIu;W^zTRKpUr z+0PCKBB~pFLCka-M+d|9BObwO3QSh7Q2qz$m?6K?4+zWhy-ca?G+AFgUp5W3UVr%& zzOz5kU11Yky@ekiINK|0N25@Y<*@!cv+qQ#7TzG~-*Pd+kTc^H1Mm7986<_EIv?7u z&ApVQQ>5olu>$sgin{N7n?H%DMS!v-t^r``H7OayvnZd)h!iJ+7wqa$*n@QxumVO9 zF?QpN(t+z7Quxo#lUn8DHuBgGNeaE$so6i<7hrTDKpS$ZanP!;lpY=#=>l*=*Y){+ z`(sFEMn<*dqIs&g?FNhBmr%0xU$R@}*!a6Q4FGB7MP>xNPi+A-)%ebtN*k@Cy*WV+ z<4&BtgPN6&a3{l4(5Og+^y1f!@5S}uo3;V{TqqYifS`Q8{IQV6&%mTCPs^*`G+XrI z7i69McXP9~x;0-1l`n934X!7x3=ZRN>p~@OsY3I2?;B#g`X;B^nQd-GQItx~7aH9& z_YBqSKK^hEPwK$hciWkRs4ufZZEBx=e`SsZUk}JaaaHMl20;6%h(EwiRS_q4f_bKX zVypsY)xx>28tJJa3@2r#sudSK4>d{*k>U)~tE=NrwnhR#y`94rN!!$A&sFIelM*X# z1Zbk61m^rnx3sjh5kL|YpPF~wj;dk4L zTr#3xAZ)_TQqhOE_f$%Ihlv@woP}W)Iu)kRiIMkXX$bAw#o3B*_yjvk%ToqgK3eyp z-#NgpjDRJ9ySxH}gIstpl;5>8tgp)2Wz%o3@%A3y&EhYmo+U5Oydd3kS7(RH8Y{B5$z{&Ul>@xJv=ce2)e0w6pFGWch|tgUBO4>L@* zjW+K2`gVEdh_8XcFY_yzI$koOqd~`jJ`~1vAsk2=;`%+PTSuQj?6SF_Ire+#rp|V^ z{*7tBmPZX>(qLN<0j371rj%UJG0?d!Ckm3ROiZG=O^2)EG{_BJwbrTRPK+ghR26Dj@I!zvf7X?exnXNpVQzk^ z$adaqVWj!_wydi{l{v+Y>$Y7LQ$gWXp9H90B?D)@9s}(m(4atJ{rTjg1=8L%QhhQe z?xL*f3NZVIjch(t-#nki!!M<4zl90X6|@x&M7|WT0QM*w6AdqI)7z5yg-ZD?9{d4=>8w8Yzap`(GGfMuyy19}HLFy&tZAEDzoUYp z=^QKw)IIzQw5p<71F#|SKT6&1hV|sP?u@?v1pNJ~pD&Hb!DBW8w;$s$Zr=*;%&$oX zakAvgefCTt4%Xk8(qBIVSjds>3;50*`_fT8{OSU6%${~#QMATjsO#))Hvt4ctn>rP z!$Y-Z1k_`IY8itB<-ZZ)ckG&|@pT#mkhm)<5^hvXoBQ=5*)k&0VQDXk=FfS5#~cij z-$DE%x3}^)4Vgy zmxp_av_P@;-No+9lR!e@>RpjBkMK83=XCCj#rAC821?sIM{NryC(f`$;}P)AyB0Xr zDRJRJwc%FSQAO_~08<7@5+TBH4;ok{gM|Gi04KlUz(hnUUY`aKlT98q`J0(UwpW9n z7oz$mvpcDjXGVNhpSh38P(vY6v=$7_zX$WL0y8t8Drx%@55r;(X7LkXrj!YQBM?Iy zbpU{sZ%p92ga!Q2yF{?fF<7F>C~zuNO-I5H(_MrL6w6Dsu{+FDl(uglqf(t{reEYS zG`(wA3WWZAY;l1GurC8;G1VtP&wI6J-X-Nfzwd@*@$f@PQu&(uMH_uOYSR zmDs1V1MTn_7L>L%t58p%=dx0yEq;^gZ;p`#YQO5up`ra>;@fkM+AIR|5n*B-ET-1a zb)x3+hUsh&2h#rHGZt95ER6aeg-l=zxcT;Aa}23~mB`@&kMs|Ck@A27c3u4h6uc}C zs^Duo1H2VR^kG#(Kqv!?HkJT4kY_W*fjvI0FN%_MDCrIWOC#99|KmXZiP{PhWh#g- zVC+3HZrD0P`C8?0lvQA0Blpn($-khfJK)KxA*q2H0{n*p+Tb3~qQQo)=@6ao&lPU1 zEa42os*GCci^!FAm6nK6y;8x~`B>nG|Ng)p6&Z-K{@@Y^IG*56S_n$yKh#Lb7H6_w zKbblfEa?WpMbBG`C(7WvT9HCuO}6O zC3cVq!Q1%jNqsLuxB)nDfaYg-g@ykzrV^}kda#B4?+3%dfsv~sUq4rp1W-Dkvx@up zV(G5z6``mo$3#)|8G}<3e(~+|%s~Iy(CQ*0g{fSf{twCc4Ed zhfh&#QjJYVpEEGL%hOR4t%}K$nf}5b5)In&FQ82m65vIwiQZ4ra2ST`j7Q5i+|;{i zf;zJW0lvzYX-|ZBb8F<1)Rqg=Qpu9M9X7@>qZfF0r#I&2_Frw?dDm;X)%kD_8Mdd* zoby^t@2F_-LnuT&l)bx@IFnL@UFwHIHU^x7LxMDQ{5|+>X51PHOU+FlSClAg*9C_J zzqGT9BmbH^HJf(NCuDvx8SsIfh%>G7?Dj6Z{%*3=Ob=G&87wF=?eCifq)t{A>lVn; z*AKvg#!!E;hpBrHu!D4zl@PX!%V8M_J&L>amuunyc*;=-DBPbrO?-EdAbdhN2{l7-jc27JM-8h z9hI|}=PxG2;W7sXbn4fmXpAzkK?#qT_TfadVjBZG>N|Wt6KCp@`^V}kzYNIR>A|6F z52q3WvK)ctha=Fv1JDXwRd>DMoKL^&tD?@4C2rQd1NA9kCGU@vO%BgN6u@1tU4TIR zdtbtbU%+v;{2kmGi5lzHg?rsY0}0EU&|aIJTQHJOlO>+JucJA4O_E`jT=nh!KFU!Q zu1xg~28PSoE-#Hm*S;2O@fnQFYHn_h*P%D?aBOh&1_zVCsNtVnfT6h=o}@xh)a-6N zI7)M$o=F~r`+H+biF<~-3N5+#&2>$wP%}$34W znoP-{O|MOn4oGb`;!|W`U6tX1q!u9LspRQKyr=iXoh#`cPV;&8hrl{WR{DrO>aNme z`Kw^>K+pC~P4xINVG;i-1>04o*{Nrhou%9UB3Hg&$<}f7D+>c_od0hvKXaU~NQz*4 zT4=?k%c&@UB`?g-e`O1Lc)tZ|5wiGxSQN%q?|BT7n`s*6UR__eEIy|XCEj!pSP#6- zzz0Y-86UOI8&4Umo$*6}kJp(%ZpiLthHDB&DCQ=x1>bwbd5;hj(URc;0Ot+-;~?nX z-d+|cnv3cW@&WlgKfptYUR_-+b_MkzS)Y)Hfudx@6g~k|No8t~3MPalsFYu8gA_74 zZ8>a1kp6`FuiuVNnokTr$ICK!HYZbjJkd5PB)D$)yKwm20^R=);WmH1)XZ+9uu&ts zeQ|gY#LfvX?O5oVU&SdY3hC zt`N$b=q>7Pjm=tH=ZZO}(=$EW=w6}9%DRzWiKQ5hB}GqexbLla6DsVQGylD!hpb5F z6_;nq@y{2pUk}NoJ!g=cCFszt6s(a6FumQHRlS`rMS2xFiAATJ1 z@}|8I$D$+?B8{l6t^M-F3uG(g!zya^YF1bV>&=p+8PM`;R5%hkeiwN{hj?AMAoXk@ z@f7?kKIPxQ)93G>LbQJO2ad?}ShC_km`SE?JXd@BZnI||p6yOvE?-vv!hq;NiWe3i zZS958`KJndXAmaE*S1f#2^Bee{_my#u{lBi4IB0)Ltv@@>NJ-PTYgTC`Yt%H$_mT{ z%To(sc8xaM(>xt*+?F%4I%^zp69nJ2DL- z?B|M7y)hB-5p*!l^EQA~{M2|WxNkgs3$>aUV#VP$HAjIjg*jNUTkW;h()|30t<@X>MRkr-jq`4JXpGs|2ArI0H@j^o+O7Jv`=OeS zuZda_iV~WKyi|A2DNDBv*W;Y|_YB7lwT&_|`>UZd*ePGzluqE_EMU3bSjsCkbg>RKhkN&` zSVZ@ZE2XXP^qy3RmZ%6+L`(L3M#!Pm;^m<-2`Ncv518w*Td04%KiO?L2s7qck08e& zjkrIbo}f1#-QiJ(orb9;bnm$_x!J1V6aT+xdk>(fx@}vyyU966$%u&L3`#N(m7E#` z8$^Pl1d$xN$w&@@A{jwZkR&-ZL4pLqKn6*YBsD>3plROfbKW`czwg~!|9$n>UuAvO zepdDFz4uyk%{j)HW7co#%)in-653@6*3jT29L@#NZ6Iw2(!qjmLN^BCj}dDq{mCUl z+I0aWO=9yNfJ>hL1Y)H%nT*nPCbX)2@QR@#N&f#Spxtqw+k1DM)PeA=_kE0aIZvUA z{`vF#cKWsdhJcm~_5TD@c+@4<_a0nJS+{>Odd>Gt!2jq_TmtPr(Ky`fJSV*T98JJj z{Wn(3O|SDfjAd-;<*N8p-o0~R4_3jPS(a|()B+=A?GH4qhiaws-GPdCc=~HXO1~|9 zEHW(WX%mS+%Z}U;w=%EOW>R)o72#SaiBuE9T z=~pr;eMS?s827XBB@=W8>!YWaF2k?`3=rFd?q5qY49te-XKrpKZN7^wH1$eij|< zpRgiiz|>pUwIG&-*t{g=0A4Wzo3ysA%M5%2Z8^01#u_6QxKfb3|dOY{=|IW&3Nuc z@^IWpyb*2qt7qvnwndOH`gr+Fl_<|0QvgR;o5aK;?Nf58euQ}NpH*So{XdQ5V z_O+-aG?X_|fCiT!U!XVqMoBprhx;P`Khci3D}m-K!0QaZ*X^ZmylUT=L_@uSW+Mm! zHOvX>AoC*WBsjQ>*hs2`V!r%*x?K8)MKO&szUlSJZw4Qmw<`uAj6?Ze`WS=DG9Nfs zQkF9}P{aBS!3GQJMi{=-I$PuSAT2DfG5)8D-ez6d>)+^=@z(dT^1s_A{R1Bh>$I=Y zms|mlo*-#phy(Wws_ZIeV&;PmCV>QIY0H)JJ=Ui$GCxvcqjp5E&_4hvA^QVxEj~U* z0??reGy9TYz?~%1_r?Fc&>uPd*9u5S$0tWxKMzyu{?U#D{64%jw<^qm!qwLoE&N|z z5!6CZI$M7rMv~mQQK&${>?4o2AdqoLuMFD)iFL*Qh1L!)fzjE1uR!ieLuL}QnyWW&XFM)jtTm^32*NbVB= zl8N2$zu;V22A|_tIte}m{v53A-Mrw#F%#82D;R&Y<-&Za^ntIsOw8E(nx>I{{F$+_ zsi~m2bqycTcnT7@^-|u-+oXiACZ(4q248JLfC`xHBbdNf=K&~y?RNM}aImA58=ty75tS-0&n5Nr{GiKK=9+xLcP@p>axR&zB35nU*IWGy zgf3%~dN*6O6QZo5i>MtA6WA?Z5dMk@K*Pfu6x!gy_Jh~LHW2n-T}jbF?EUp`H468m zXm(6r-r>BLB=^u}iRoG-G8J;Fj{%)j3!Lva~|9RT*M z%24#(?Yj>5174lAk5N@Amz3F@Zc@L8h&}S(D?>HVG~AT=L>ZHp$9ue#q<(8F)`t?1 z(*H9k-8tYaf;89>x(EJ&p0#uY?!dXm+J;?N@@_IWjUfoE%np4I7G1%parYqUHcsqHz4ywC9d~B=c?Q?0mI9D-O z-o|gS&paHnP~D=&@1E-9RqS}>01=P=%^I^aK53O9?hHN_PtC{ERB@mhPI|H{KUMUULaH3GIHjcIJbi9T7&Kxm>C8TDr-T zqTigC2B@!8pdQgxp}o2nha#Voy)tS?a>ilv{*IIqctSyh*G}g<2m*tVJYgr(I1dV3 zB18z-O|R#K_u)+L4g8-z8(aQL%wu>8PaWf_spf7|eJCzE=}H-luG&jArX0q-XS=h> zB5{X2QN%xwqHFl}Y=!M!?$k0--RGX_rq6tCzXG+bk7xNgIXQoW-h^9*6^q#&jD}H( z=7h{Ly`bk7*kdZfMzxFX48*4y^Sjfiwgh22k%uLaW#FKl^Zx=fEIw58ny}N!N={Fzx`yQSCrd#;`1eX0T66wvN z4~X`=Bu0_jz$Wm<#H$bADaa|5o1V#BI+Ov1K4YoB5axFHg3M3hB3gpVN?X=8+4=HPtorr!K*^jHiMD zSN~kxe{A}GJkN7_O{Hq)!`rSwDU?!6{2!jwg+z6RwyVyz5i}3XE(lXds9XDHMp4V+hc!nznZ2lW=TlXGg{TanS!F z?QzHQAu-7HpBEPw+u>AB3I#gqzd!D1e=6L*$ZH@vO(EOndd;@l_iuD9f0buz&)d|s zPZeK)X8bu?{j?bd9wkuOmVz_#O2CA@I>6RA2%ZSRAfKj@wA|2$T5e88BqnkxCKMAb z^(U0Re1>bWjgsP*$7@|W(q8*dz%_Ta{r>`78!@D1`6sxB+ZmbsKLNE*Qh6ZVeLOxR zkR1Eff7Km#T3<;MxBArse$<=l^RLcC6Du$crr}kSS6kM^*UrvA$5SJiADv!-&C{pF z#lPgIg4Z^EgqX9BkSgNcPU2CSE@;?~Wdo zLwLi~1=^wD98(9^iIiE1ZSH%0kA_GN)P z(DwY*0Asz70xK}h`AT?F%8*xWkHHyNC8LpV1LHrC0NU?VL-HW4KKtm9DjYie;ori) z=;7%z#ZHoow(FTpvp~(}!vjTzSk7$U8$oB4xz@5U26F&=t7xnfpH_UH(72DB8; zd6d1pkn0NnmX&rQ#(6gt{cbh=Z++>`@87Cj`C3QXbq^izK3I9V`{ec1)lC~Pxc)!7 zaIWC{^u35yiG!5+?Qu2dPbuR5(7E=~rn>&9>8LC$ykEPoD05T3wkFmYd9CfZ?xX88 z!Fr%(KDnv-^IRWM^B+TQ#WFUgqUO^>^q<8siL|$MeGY$iqT~m%gn&$ve6d35o5o!N zK@Awb_a(sqYmviv+%<#o*YJNv7(aY(bd4b*JAkTT&akZ0w(DsuMr`i|^5+N56r5 zA81L93Oz@jBZzNdb2}u%?P&;`)Qpj!J@UoZ{<>qv_5Z5s>Y&x5N;1Ipwmp>fY2VcD zuCo7_V)knEU!Cq^t)2gMqdR$hmYkDERv(f55b|D?bm4G&J9V9?^6A5j?Mz@?3Mz5d z>N?Qjf7V?8w=wnEuf6lNne*Xa{wPiFXZC(BVdOr>%nZyOH%yJI1SjrRDt^Al_(p5L zm(c;1adC|OuH2)?aK=D3(FxI*2`UR_%}PE2o#WN!fT1R<3DU>c(gwSluKmp#5Ibsh z{>mXXTEAuxHeYc?^oDnhIW!DC)g(izCJ}}v4S|jvEQ`>8rlQBCze|ONlwa%<84&u@ zA*&%JCPj{abR;i}qH|XsPV)cNv(K8_<;Uvw_^D0|YD?9}LxfeXI=){Pw@@$q_$y-A z3d|XpsC%-Oo2qs>|95Tyo#|WUWLObIgwGUe8-Z@DeIbC8mlaJ8!T0Q^lZcCxxY|nl zH%}eTYt(wI?TYdz8c4XGK3i<_F^saLecfhu_zGvWnI@X{o-peD2xCm#!nLBEhB-UNgz*ye3>}l`S#EiE~ zLSDD2kc9a`6FLyvba9T3j?y7_^eSONXD9NdCdHIQx0I0hmX@m3jn#sJf->Yez6>}# zJ;vjX^^U|{-8eXS;TMvu#c*czbj4)pH%a6*5^3C7@%ADQD`4e8E|Gp}1N+XQ@ZZ#p z^5;Qx=jM*5_@@sNTFPGJF6{1qDO*Od;{%5$KrhOxq@<+pPmD;m%rp{I1uZWXy}54b z<+%NmTttJ?!MG70*kVngZj7VnSzeU_AKg-mRbENDMy89GP+M zIb->;v>`xcs_lG+M=->Y?=3@klYjK~)Z(v?NBLf+&XS2LPd$9UcnY4>V_YZkCz4(- zwROs`s$Jm3XuiApmvfGGG5}lo!ID@k#lKR)3!Sl5?*6N?-*sURStsv4z5ZjawtC+E z^sW5VuLf3Ig9C^7Hv4pyM>>W(l{W)RTW5UqFQ=9;8G6X64e4RTx2JITgJ zpKEC_M}JiVPfC~|9)fwSzKzDWEPgkd)>V?%eew-zTN*juvKZ5pnSWVtE@*iUaNOyi zzggS1bMJYwW@M}<@v2tRUTf$jIU70_d?0+(d}=nj;q>RT`;3Jo!YJwJrAcMJ;3eG6PyFywWRnD(sVgxS7?y64;f#RDo+)WBrMC4*lhf$#eTYk+8~x=M^%<8zDG-)5`qL(C+0rLlU_P)Z3%@AUy3@ z%e)-S1jRgJ4Q}QtiN(|Mli%aY1D)^iNtJB z>=^WSMD?z1ZnvsLzabe%x|rksRC9s*;AfFfZ(^Cnb0s7cqWj+dxRkJ~;w3Q1FTLAn zt`!ian{vN9m780%mySnSfifgwv{7oicSd5O+P?M|?pdK{l3Mt%LGE#{=9j|<9SHcb z!Kr8bG|(!1XuWf%vRcCC_miBHgdNiJYE0PkOkE52^S2-GyUks;ef#*BEqeG@SgE*P z5z0UmM4_*H>k2qcE?!52s7J%KW&GGvGD|!5VW>*QawEgA`hH8^s>sxvL@7q^UQ+tX zm#YLpeD;OJBR(z_7}@7Nl~iZqsMlZjCB(Ck{C@0gWCDrIbOIdvZd%@vY>m=L8BH+NqeCBXD^}nLg(hf&FRo$xV$j`{Gs#uA1;~e z;{VbDZ23MOtM;q2SIlLQS(%@2S8$uTyzguJMz-+ls0AU4s3FNpKeEYdfWZhSr6AtD z)9BTc@GKB6=Zg^&BCK24e{4dd*(h{VVC^Fc+^8+o{6eD~=x}7=E=?a+%;gM6V}=N= zi$1_k@^EG70`wv*{&iLsRV5qWU(i1*#?K!r|9HX(_1PmGgFg%O+54?)QT;&IXYn%y zR0q}xYg;tCi4Hj<_N7ZzLoV0aKY4OSfwzXkrGS^A&)JE$y$!)w;B<*jCHh$9IfiYC zgp0JY-EYB{-NEze)03ZX-@JJP@qtzv8+>1_AV+??Y9}^xRV4%mA0gsn-GcNN+M+z; z&7ZoB-2WWI0K<^fkp2W7u?NnnL z4*I)Dwibl_fnFa52f`9`zDN&^4sv@&*=J)+{BWy&j?(Jhce%b4MYR)~B}zNG&gU6X zi#lag9G{waG6qK{!))7*6LX#i45X%>C+ritCV`JaPb`~c`EJJ#$WsLLTHAP#%@a8F z@4)`mo%x_VUT+=nCYs)WHxY(z@~Zu=qYGVT84Ar59hMDweQR}3(xow-N6AbOUmZpn7BA5v2PHX z?3^4c;6y-zOe>rwgQs#Ud1$yWjoIr6tP$fNMlMq|?;$qS=ya*YehTuqf7{^WPK!qIC)59O9y<{2)GBl4U-Uy^j& z7u!1If2Uw{Br!~@a=MR8`>b@bKTg-(BNS4IjDM&wT-osC%f5cD@Sd2K3d?la@LV{{ zc0g{o%TD3#*aTdwgv#)I69h^83=_m`_ z-y{{mK87HTjuZBcoIx+|T>Fscf~wfb6z7IY4J5fuWFCqu%P&e^v4_u8kaqTaW3dYn zzL{+3qI{=O+bV~fWdB~gEA3XoGROEdW$x*&O4zE8ibJr`xod8hQRX|Cio=ry*%gvu zIB&y9L$6m`Loodj8Dsz$Dv)=)w$qFaCPDA){Ay)7%=-D$4Em~5m1br}hg2tg6a%2g zh+y)H;$XZUnP!%>L)47I=QBUh4_9{kr34JV4LTi(8oFKAFLoj{TsA8pwW#+X=3$8q zx)m0X>|P{gskA+pIuV=FmGn{Fp1?36VmpyX^-4Pe;-X<$lW=Bo^;J&IG}*dZ{sQno zQC}bZpyDY)6`8%FN+<2Xe*{z9O-*vIiQD?yiWU^{?qf1s#c4mZM3K@(}1v+!2D`iNl=JYvpQWj?Gj^f$2CMuPNzSSe=w&W3qgS1wu(!6PFh!B>1H5R^RGp!9!srzpY=Z`e8IG zpM`6(wu^~X+c89y9L8dCn#6tx1foNaN{S@I0gxd#f*ltm%NaFj;VTO<(q-RAXcILN zP0w^8@{kUtCb3R#P4QC*_gDquoZ=2}h#}AC(ryL@An#e&N*FOm+`LkSQ7|Q#5$uoF zKDBxss!J(PEn?L~h3Et8GKU)%WI4!Bi`fWuKQI?+4@E$w*!HN~FH?YMxcmAg+ja3C zl6*>!heP|MxzKCHY2--LV=_oID!)x-DUSLK@zRA!s!3qjqZcwFqO8F1xO13Hpu_TX zLh=AbMOH)C7qGEp_z=6%HAkk?;~&`mbx4KiUL1z47nzHRmu*Ltvh!+OgNXM8t~*SR zusC#>Mh2)1FIZ(X3TVjpLrbE99}`uwx?O_6v-ab?!x9@V&-#(tkdA2O3E-9`Bjt&y z$y$1XcD0Gxk>a^S{@X+QO-W}3bHj3rXvIt%|L|SB2gMVeM?aI!FQC}0iC#IV(W)dZ zaO7J@pdaGopG6Ys+xU)9TrK2sfk-s!#oiSCb@4;lP46|{B}fcP zsO%Zzf}{7v&C@ z4XXHZ8)S=nJ=%G$IWTW*%#3;><(zSwAN&6Pu)3_Ms2^Ej(GFpik9^B7JqfWI!RbK5 z2|2sdLPe5g_g58iu5B_FJ))=tHEA`M6_!ZKQe&6D-~DM#g%chYxG-g8MECqdoK1k65b|1(}8*?zA`5{)y#%w4`=;-BGE z7)RDlhjoaE6wj9_d%zNkzVD$3kL~Ea#2EH@;Z7%KIom=PlF6I21DCPU>mSx}nKDIYh6 zrcD4E0Hw0?q`GYpUr#+eLXS@g_oH3mFx1}Jr6#{}Lcb!ZE(G~A1%hg&7NqGFk%pvL z9Q5vPCi`RBrRYe>dBu}xM`=7w2@QMBXW7C^SX*b4zx1%Fe-z1Ix!kHl8Tmz&c&Iu( zM<236N?kYMWDnVOk(myrAqed(plBQ1%_K)w-6QhvVQ2D>BGMn^;NzTU&*#eMf-AZZ zxvm7Ntcv15b|D{r4aR`4a~(IRysViTfkqX2sG=Nx6?XITur3rZ@F>`;r#l~0)sujA zd*q-p6Bb!sh+(sP)&XPxw2$y;J71C`$yb=KdzN)MjT_f})K#RL7GWxYLbHdj4OrS@ z<3e^@iC-n2$@B4PpxS^vsOkmPfEtfIqP9>~6_p787>aY!i&3tLz)*|Iq1W}IXJVdt z@-CfzIG6v@o8ek5s0w)(&+!75&cRbC5^=#C5DBN2_jDC<3AM?w-PNJ7nl zf7B(zbB)VdKx92V=yr5c_($v6rP?=XRNEB$a;pBg5tY3ek!*VN%b6^flP6nh)wj3) z6_4kDPZm|LV+usmK8LDds@ieDP&?D{z34wyrhrY9Icv}iKa_aMrBVQ6sq!aYa8xNV zJ_2$>DWpsc=k4Xi!u^aqKB$^Dv4A#jbxd1%KR0`B|m||G%_U1!<)pl z82K=L-m%_FHxgpvS1$|%aOuz9@g=(QX5=|n=?|`lKfHg4sV6$8hOk`9@`F{SJ4@$h ztz9AVV6?KrQXNr@kYgA%PL;rQYRTsu?-*Auve?37@*IXB1=6%u#uU;DW#Z31H>8BD za##!#`H`xS;vz>C#e!1kzwl_ky8hGdIkhEoegt}t+C`!hp(!7xDXH-+FjsTH!2xd_ zgyQQ&G)!Vwm)NB)m8CI(l*r+iwjZgS_J@AiF$~YJH3hP2d|@HgWjXG8oD>^|@idVf z+5Pmp8}DZ_Gv(TXD>!lU4=?5qp{&&oy@@PhuEj@w43`}?{V9+OoG`biMW-5Q3|TyN ze%#pwVPlU+Bo+f6+7ZzSUC~R7%WNXilYSF1$fbjB&>a{_77UI$)$bq7MeW;^5(Fd} z`cmG}2Y+QjRfsK!G^RK*IGL2m-A+2gBtt1A?qiY{dlD{`nH1|ifR?Skq~78PXls{K z1*^#j4iG-d+nOZ0P!kO@LUKzLoWyh0Lp}KwuW`x6Y)yXB=Euf)&X>rch3PWM$;Y1$XmjlMs60&bcj| zd_J#RK)38TDh7k5q_Tt441}X&Yxu*gH4yNCSZLetj=9+6Pj~HT)X#7@VnwA1--Xvu^*Ck`fz4>YiAYn5 z%G}5}65VlfV0!;_I=P+~`E%n3-M1|w8{YPF@qE#lYrtiga+`U6S`{sZtjfDd1?OM- zNjzWvz(|>zbDnw(tpkkpI=kdAYTV0iLRBmSzc`AJ3{X{zHE@MR${Xag|KS|#Q}Tx? z-cV8%XsSyd(>$3Ye)?PF0Vc0&i`qc<#ix?VFqW+&Dp?Ve*kWN7CrLcl(D(AZ`=HaG zwcHT5-4)DIep4mCJ)BMN!-I*mEJo$Nov2V1KG&A1bp!q<7Z|-qasXqqI$3DoU($y*UO(hfE@GcoVZMDduj^ z5q;H#OwG?eGd|`(00+uGsqjE@cnJTWYdGqq9!h+e5K-H*JdPv=RV-T;V5k39UxK%? z&L4u*WP=o@OEy8bqRfTMZrF2Q=|pg?Yb!r&|Dbc>Lnne*&TF1S%}rCis<1f>7lrm< zf}VGQJ($l?24_&AO=en#L@bQlqsA-bqP2{!UTh)7Mb$wTQYqX7?Fy*sDItxhzRD0% zyPaOyve;b?h-$lxScLSY5iB3z9fehj@AasB}I7>kYPKFosV`a zUj@?Aa*Izp_Xg>?zeBl3gE5rK!fD&e$%fnwqh2)V`(^Vu{@&&p_ha7~U&G@MVuE=7 zfq)||OgD|M5H>3`HH2^og?tnqiely?F|!1@(w`|~eZq+pLh_6hf1@At$A1#FEUyIa zbkb~WY|sxdshD2pZj^gNN)L@}(0ON)U}5RfJCzAOp4rG^Dn6O~wbsC+2y-)Hyc!a3 zQyFnnN}-)xgGt&Wg&fH+$17U_bimO*Ld{g=`o~rAA*OO z{F>(o{d$O@mWrOgE5#ccp;osimB~^Q1}Ot?@=ExY!H@^P^i*EFZZ;qheo7dH4v zUBlzZxFqR6=6w2ui{z=~B+YE;m9>-St6!r7%Om_akT-iL1hVe&KD5ogfR?wj+Jqiy z%8$*`56%g^3sRG>O19T^>tMuB*ZTXkpxLk6!sD>0K*uqee)VHEcs`YYs}zW z<`6K-Qwz4nSh_kmbkV1C;=Q5PyF6uY>=;OI+heyPN!+_*=Z(&5Dbr}Bi1{d8?_-nW z6B1Yw#k&|?0VGG+fj9_lTOG_4yp_;fWeahIdjdG9Bhs#znvX_Q0{h|f?n8L>vM{b2 zZa+zu4;%Ra_ODc(3JUGQn(V6}L6R%$7u78yrVO=A;qtrpd|SOO38IvWu}o1gi$qse zM;h8;dt1NC4o<6QGYzX_so>Ybo#6+u7WLo3WoGGb(YCp3&NcEzi!>;s5ck%OqMRXj zh;6!DtthTW;`**#3azUh zYW}*)1@M|LM1We2V*3%jPGag~5;>ZuF19rW&|5=McMI;1<+M4DJ&BSQq(!CcSJV&M z>rSsyB1PxjN%c59Fp7p2L}N{pP`w5LBbIxGxnIZX>*^%3GBY0z1_yP?SQ^vh7hht6kx%jS z35j9BVX~itj7tddFgC9tW+rBxam;{f(+(o*hzA?F}*R8oEg4k%Qdp z7)xZi&}#~j{0&Na+~{AHqTMuDk%j^Ii#g^*<9DE;;V{?jbNuN}S#aRO!D|cQhTIY` z`33|huA7*mwqS<2&6{E9-(ZfB<25|+H>`g6gFaf!J&hRWJ+Inv7FK9vFwS?;M%6A6 zBNFGovW(sL`Bw55X9j^D=uvYiCG*d72$^V@Y3L>sA!f-HVyKY|+aP2FyLDYcu+{S*W;Doj+A@Jv$!waN{%=iSS1>(QjbicqnHUu>+zUE;Izbtp`n z(`>`^OXHukR_!-mhLUN^IB2AgSopA6r>{-o8uL-axS`0g5(*POLlzCArf0be+Schd zFUG^wANf;^wQczSYL~@{udW?J)dm-cf`KPi*^Nj_YB#25BF85ulp!Mw@!!9GH4wZx z+}HkePuOtgUCY(=cX=WA0V?GP3@e@dP^24Q23|^j0#=bSz(v*jHQvycM1vL<;=R(y zG@KySnv~E!jK$e-Q_H`lp={5?DMsR8R^K%I*i6KQByh3C*|XgM7wspdX3w`4G`lUz zVq`bm_rsG3H)QJn-jk3*+yE(rUQDrrW}fPEaj6o+XeSoYtHOh4US}NK7u0B8GWW57 z-LMiH|5L{ekQ<8iEG$zuA=3UHCfqU4>%7a=>T}P&O-v}obv5p!v#Zw(ek3NVJAd$l zJ;=MWR}v)|gpU=8LH9A>frqgsxsp{GT$;b{!8tyr;@vgf9~eb7wOoHcKPg~rqydRF2`7sHsPTu~I;a_1bFp+s@|9I(Rlm-WXP!69IA2lm@+S^Qv;W2F8y?Bmv|BSuq% zhQAxRDqQ)K`LcNpLc=!awiXFxb!QIRAwx|yvx;QV>`KNj^`I+eE zvFmR|i{)sLUi@nx%60UYE&|q5oRAe{NYc|Jf%x##L_>5zQYZS#w--JCk)i$U2NCX2 z=Pok?21w-@M*g-O*T+MSm)XXObeR-@Cr@#6n*2B@SUv$L{S%-9r0(9mdp$hons4<& zS2PuC=u|fK<@qcH$?)s(`c!TzXN@DJeo@2ba4f8I0eZ_oBnJ6P9LK_Y={d~{z(bL5 zz5-LGLh#4VJ^&u)pAh6pOyItjFb=)1@C}>s{oF=atZDDnu7z7gW}-;^N{eeb0|q^E%tO>FL{n??boSOhd}Y>FCwrJXw_y*lz=UeMc}@ ziRpyJ_Lg0?3-4(jupI`?mKjDo)_nFVAg_NQYEec%BR%uK*s|zdK2#@rw^@l1KY{zm zJejx8X=(dygSA1My zJ$qIwmWMXvQI*R3yMOD*w3pU0=vbg5cA9~cMbud4eTX3X+I95TxZe)Ac_M=^at*$x zS_{#Ko%A=It{8t``TKq#$#YKoIdh*PNev_Z!_~lt*wRPWPD~6r@qfOzkc0m``UW30 z%V)318}xe3xJA5MJ=r-2_?@c18{?lq)3Gez$PT;c)TK7b2qYOW7|f=}FlDK*mzLirkik zc&#(Du?a&qlSJaqUo8K+{u~&Xtc1ZZ6p6L%UQc%4{dQd+W)?{^4YtZ#(AA^( zPxfY}R6SBFV`2^Z@+)Ur9Lvb7@E9(kb5q|XoDezfSzM?IYmeq1Yme8f*>3;D{N%+I z+e1gKlfX2d(3^rSEf;{NxoQ<$%K6c3^pS&J0w-J01MJ%K`p>n0rrutUD~XY%l`x;Z zzahWZ>TXpsa(X*u^>!Y)x>2#;bCZgCUKMor+dEbZc&Fd_+rLhIp7>}_k|vyOTfwd0 z_Rh4KA7Jp@qj&U&Wa^@FCx5T~-m}Quu=|&GqQ>QibU+8 zX!YX7Md$Al_z(-4Qs4OCgZv2Jn|XJ0Yg_U#fuu`b!d(N1Ccn0@z=W$u3R|iaZ@7w0 z*S5tK6w9>)%Lkm-{ji~wY{PjzX78R9lig&|2~DDOp(e2Lw<Ovup?=`PLfB|BWpYiL?N8{_u?2<H)Crwg*$aoE8=q!bYW@eO?9A(wKXm*D{3j zcHG~tK;!RMRaL?GI#w~_l%m(XnK}^OEJY^)C&=r$-Ysa0B?{t9!i(-+2w%!zuWpA^P3xGnXBc;$>2le(AYMmz%w|Mal$T9fZby-j4>~tXbO!yZ-d-6`ln=p zWmKCJ-`W3!pie;cq&R8Vaye(jE6tTz$#y)YO}@bD1))KGbLfd@DD=N6+MWdjB~-3Z ztn9NjqlGoOvW=AH;LH4j0edRmWK2$sr-8r?ZT1*}y0P!Bd= zR=$m7kzhQ$xVclvBKpSx*~Me}-b4th<)9uWB$3+O+zd%@>_Eg5onC@4YrJ^Y$z?wp zuMEZnTVVYFVI5C)#FQ_C%ZSCWjSW_kM@>`0A#rMpUSa6elgr;N4KQp?^97k@a*uvq z?(j~jaZm&ckAb4w&!&PydQZAp!ho8^Kj zt~sSmLS)#}6W|Q+^WmSt?!czM90wdVtzP@D9XER1ppK6RT9r8cc|%LBwyqQh2%~kY z;jNzMP89(Oh!1FMUhB0V-zwHKO&8LUrw+4;b==L}&$ph&{i5~VnGtK<_xOEv^+WlW z>iLQT_G;{x8zFl}QW@;Z4T0fH_NS$|lhf+ioTj5VbKe#)tFLzLdw;X3p5D_?7Ua(K zig~?#`NRC}iITR3%lV#IDh*{I>W6a8ld>B@6;BBw0JqPca_lH(3x~b3v7%Wu9U@~* zv6@@hZ-9A+W&k60^4?5oo^QTx1}~$@kx(W(A+k8D_MbEt6oO#y1fI3)tF8b^hbPpm zFAN>~C)`tyte!xu(eOdMAl|obH-HkAk`;~Ws4NRN&m;HpEaO}vy%R-?x>o5EZh-kj zp+k$zp{1qmRQah-j2tyj{5b(ozcAke9c!47tWs=$?G4PDJG)eMv2m?`F!rCT9r9pa z_bZ5T-Qltg-Vhu~aykIf(%3N+!VGp##Bw0-FeplV#O^#5#ZpfQDV4p-8sm{YoXUaD zf)ua!=Zy|RxdSn{ljYuK|IxaZv2E!h6OM^Z!Umg`_rUm5cKH($4FiUIydiJxS!TkV z_mj5t=hcy;`*Rm==KSJR+eO_73AXyyE)quS@jf;EFp(pR%}j@BhF0Q74 zcr@GP^=KI7CdY}i@jq5wGVCeyh$fb*F!WU0mx`?zECefsJ!rCUGEqKxf_ z#@?}m4{RGhTAn<1n9HDuO+;8U>bss-pW>(ap9I~lX|DGBTgP=E8$m1N2yDEPPr-+~+ub9~(Dw+dad? zN1isEKTvt`?iS_mW*BEQ8lV@ud4;IM1gu2DHw12*Lkkxsc7 zj-&y~7ZoX)h!m7!;-gQr>3Sy|6xgo^nXLRuL=7tnmFG>oL{x1@W8d-ae-CG!qeLjN zL#dXYosSKOj{9tM^WbYMzeYw%h3r%bcLl=?VDnIhumb-1X;9ITAZj6>?|UdU>~}c( z`Mm%f>eT{j11CG)Fe-8eg(X=ljO8ZTDchl75g24lg<*H&onIs!YXx|}8XLcO*swj) zlo>xYJx#TAJ++t)cV*xo=kSK>X3pXf(Mc$XWm6|ER`Rn<^!SEncVjFq?Xg_W6m-#szzE-@9{E61BEM15+laaRW;f_CW#bYfWW zTJ1OQV~5@r@lv{Q;vZcfF+YRr{4<(;L;-qmRp#wY=A4FiFOO!CKHTbjr7h%0?kg4{ zP3OPmi3{*ze>X=y?{rQwrH33pncV)WdfGkaB|a^m3azr;KltrJnq6ot&)H6S%jlLjI;U&4s9MC9@Y9u;OOxy-e4?b-|{Hbn3T9 zgr)|X?YVrPq)?tT2kqJ%#dryeu8`umN8ac=z!{FV&zINpLNbxMna9RfCVYx4;P55+ z8F>n2zytjN>m!|13|kxDvem~gVBx@BzBDzmof%&tLPE9dbE2LB_t&v{_c=q2Tbx(( z@AzOWjf2fX(Q9n&P!DeHMj{xD_%cjM;148Dj*c#AxLg@`K@nBCLiC_xVwY1lLhaAJ zqJM@i(GMtsvU~Sfgam27PByNLs++jG@CXW>hBz&Bv7w}|VX4Hc)FEmx&Lw+xu}DpH zi&6*5l+vRBLS+Hp>GYMf(dDz_I3bk^^R5s}7U?vG2oZY_Jtkq+OeH}|J8jx}XcOIb zAO>c~)ND5h>Sd2f)RE^25k4MTv9Ql>(T}w%(qU)>J z<0T==osKgW9`@&+?9UL4uc3tUdKoz_*`b6TE~pUzg$_{Xn-Cfw&daQv-jz7jE%(2Z z>+kt)k-O|3?NmEugXVIqzxd!ZUm%E%KhDc7gs z3g(r#^gBxW&r~)wo(DH8Ozup!eWT&?n<+xj(Q@I@?3$|rR&KxNbG?tYX4a(7j?g~d zn><){i!aZImp&S5so!&Oe3BDd4V3vW$Nt{6iB;LaaPI_Gn#~nnqwrqX8BXhID7U#< z(dK(|E~`{=i_X+B#4MV*PnvT10|-ojYglDuy#q+DA|a0WGm35G48osn&uF_BAIprz*_bkh)0uA|&B z2Lxx8^YeC4uC8L(p=CBJWP;?@;X#DwLbNIgU78(3eDpow^vswqZ6neCF;py>qF&mA zF4UCKFFDdKXCe-g3G$}{CQ#LGK6K&5)a#~Q>O@0JlEEn&G7o*vP{bHWsTM6HnW{2? zco7;Hvpn#Us{O)Jp8>CbFxVTAS@Lp+n z5k)c^{;K^MDLv6#K12y3hRLBYf+Am&+mU%h*tu7>q^UHOeI?PuSaSa@DVL#K6UCWp z5nU-&2Z8+eT2g9&dYUAbx?Wn)!J3ZV*tq zyK4bTcXxMpFW@}Oy?=Y}cfb2R-+Qj_I)9R*-mbV$=vF^?GuZX!t98ZmR@(cfY_&^2yAAbrZ6TqjhxhMK0o>U|v{0Qw9ajeCKAVv>hv;=N? zfbQ`P`7ObL1E6R7SnAe-QSkSie^TXNSiO8UHtK{<{q3Xm8(nm?kHkvCJk+6Sqg$_h zpj)(}r+7+lMIgMs7ciT0n3CPCqBIm}$BscJ_EQfI-^<5H0vegCd9Rn>3#kb&;lw=Y zM|Y|g62NXe76~EFIe-83=mC3!(Z+^j@pBy(Hb?ol5Rfm~##JqJ^IPwP%&Cs#E8Kao ztMp%}FyZu8Sw24Wx|{nNX|%u3qd&rTi1_Hg*4^vcN91-{e)ii4oP*2Nv1>w*Vsl|CzLhGb zO&O}b>TP3tLi5c!BBDMznlHR+S+l+sk=7dJb(dAQ3tigkrA1_zYunycGUH_R zgwV>DJJmYTSbs6+witTa&q~!ojE$3`VUTVVhfAYOKRH-p16v5!OIr|8P3qqB=-KsQ zAX47$^&KQS-(bDiS&8@5j53$OhxtYCmy@+u?@pHFOm+W$K)2l@G&hzre_?sRgvJyX z7q5SM2AQH=I}08%=!)^QzSt>X==vrT{?^SlHh+3>Ey&Wkt6aiB48a}_q=dMzY+=KC zN#3E{u7!k*1iB&FowTuj>HoG+1Y2dVhF2Orq^kCia(a@|7h8Pd*UCisOBR%9_=h~y zV*eK8Ybb{LG!6ijNr)tLHNX9mt4n`1#Uy7+pg#Q!ejBZ7_<)NL0Gc7}fZ5yzNBzN= z2Q@%WjW$jS6bCCCTNnV7hYLP<{y0*q-VIza#c8r>wrN&Bx^X^Rn*6@*Z{>Lk7*gRJ z4^sgN=V9pp8=Pzr1}_Zpf!Z)()4oOB0G*>f*{hv2-OifxNGVM~>THPp9qLLp_)P6v zecHF=0gR6+ai6w#-}W3s<hoAad)y6LGB)TQx{8#Ezt-!;)SSCq43&h4yi746|?Z4QsAY~Uj zG!iNg7d>%CT5~7V2ZuC~)5yOx9BWu#g;A)ypgnl!J;j^SiYCKq%P~{?rtX$M+QK>U z_nu+BQ7|F9u2!wxCs56!2PV6;KzZ!9e$z8Bhzam102TwEhHL@`97M#9X9Ir=Hvuj(7>o={!t6 z;Yv;%o`38V@0Rm8=*il?jJ~NP0s;Ut6u7Glv+umS~J&e$IAF?db)~X zAcsmtZMzxVA_vB(RLn%SWA;+?C(&jayO$v%u_RWVd1e|r(~6+3z^gKkB}}$NXu$5# zQWD^CfJ)MfD3n{mx!Ud|W^dve>}M|CgqmJVPNcoIi%^LeJ^Nk($NjLd@MhRD84D4P z!dT%CJUSEemY4?T&eUpy;)Vu3cn%03AK$+)ZLTNf>~VvdcmlizG&=_@Av;p~793n3 z1-mu6waPrx`~=26Q;`)K%$asYl#SLa0IwL2CaQH=&(UVr*2KFsPlOg;&W6EoKvf zM{mGShP`h5V@TKoPjpBxJG&l9!{LLb=iNF|T5RewMVaqH@Fny%1kE~;CXl~RkCwhR zYbtQ3OT_!gI5S_Ay7{}VD&Mh1&(O%Iy)PMW21#M)J`!7l(E}tT2JdgMby>c!$V_4VD z8N~!X6oKMaqo9Auly?vyKwpNTW-_9IM?4kLopkgzyJ&S5tV2p9M+|0-R{23ulTP zE>8&Bl{^&6r<80*mT(#xE#(T85M=nRxArR z62<5~WY)NFb_$Fap5!il(e{c~%B3|imi}VYb__Ixsx+TuiJtl)K9%K#?JAu7SQ|Y4 z_yd}06v!L1!8Kg(mP`Yj(=i7mh!b*}F{T73=LfdPv1i~73=;K|^UHyQTvU0h5_aEa zAsw%&il`r5KYP#{TBUHO6v6e&2c{(}_xr=I{+-hL{^LA!gKLwXb$z8T8rzmkO37S@ zA0b_tYcgcT8k;6Na7+p?a+NB%qsQd|NygKjZ6i0P@D+LxJdG^}9?ZQZrv={t2lxhD zqdwcX02{E;V)k+BkBQ9y7_axX&~#lCf=%E7v*QYvmyu4gEq5MSkAMKfeK%9IgPsCw zRpV>!wbP4RmFhRwQ?=Fdv)`T0V@{==dV0`sKVH8Vj0f3b`O}FtA&A5noYPtKgbM!+J}m9WLv7XfZm!qVI9>2_VkL zz^H!E0LF^!kFpH*MC}p(_}qmu$F{r&l^eZiV^B{|kRD=_SHy&0ha4oT0CEi8n&7=5 zg&o<^!Mv{68Xsj-FnVc~?WE(b*RNRBxkL$ZX~Np!qM_%V<2(w#Fu_u>`y=>=*=vb{ znGck2Lu~MJ>`-IL1z%)I+-MxJ9#+(|9Px|r)W`{kb4(pHHqx5v_ee)sfAsqntfYQe z{mpKT#4!{kExjyes^u~`vLhU5fb7?e`3ehygOH#A_F=6&D;aL7_TjXcb3z5ozYbmC zbMV>mFlCLeHR4{xO^toL0I!bok@|3KQ^NIDMu=R`GOBZ%+71Q zOVFGcma@{g<7J+nT2*F;)h@hI!k_Bu@aU^R9fR;O{4~e{lR=1^Qu_)l3NIiyK$0aS zNwQPHN0b!PxF4p2Y!=-m;3^}j*yXYSwu~?PB0$OyZZuv6R9+qRE7MI8L=V#-Jv zbYx@K6A@RDbzT^s&ni{!CuO0dqjOkpLpMzK*?ttwlNIO;?mN#L9!*FI(mW)JO<{}s zr*yIT+!v!etD8#adk2tL!hKh(0o>>NGo@lOGMqFP8fQYG{DP_eA;gX%HfqE23c-ew z&(>X>?)JL+mq-bEdwO2e%I7=T6ilJ-g<>W@Gf|maOj6~i;7jUFy44$XudA&7Ef7Ta zJ?5&fr>j;}9JtF9gUhc(T%1PT3w9`nE5EwdX>bAr*xgTwKU*@M!)uwPeR4;WCpeVzhRmqiLQ$}ua9@XKTY}bqO3x6My zr^%>y*Mr@}{nVyv!Q`fF@GwxT77edDCA^wNNiNxVpOl+%6>;BtcH`q`-o_d>2AN#7x;97Mx0_jN{(u$l9IYawOgpZY8AXS4Su*otY4nL-= zr2{|8MSz*d1wAavNYz=fxyX^5=LkVT3Q$xUIo|iN3I`H82j1E!AkfV{&96l(Vvvhr zFD};4fngY_h-054XsTKYY}W5gmg91q+rPNG46*-1$`R19VN&pLP84oD!>ZpQ2 z&2Leu3%s8Hn!jeQLgOgX$&kqzGSD$hhjMN{dBfJyUH8t-Z3ZU@$u@J$-AN#GB-^@K z#6L9INdmXhEb$>j>WjWN)r$5(1>+s(jRrs8?=uM{Gr7Njy^UU?6mOXGIDp|NvKS1@ zdi*bw)hI5srA~i^99cq%A%keQQ%>Tg7+$%M*)I1$Jf?U%7Va~M8p6E%e8$r%Q`H8& zoit?1dZMeDqx{vI6;M^(wl3`-3$;6RLpmq4-?NxR9}88zQEGpGDvAKiW^Cd80=RxxW(?BC5dRYo>H^=Sn@+w#j0VM~-WdWCRj!Ya zlaY_>B^#c|S}-Ut5b;;eqgtEIHoX^`Fu|~fKxOodYA_dkxGwHtcmlmDtT8~GajV( zV<_)fF;2)h)(WW)M>m3$Z+jbD5Ym%t2&+ilGGyqP-YNu0nn4)mOw_<5sj|?Z1D&-0q34#=;r)T*iWELrZ5$1q{b`1nlhetLE;L z(v;;hVW%W=oD^fO3~-(9jAofpw!gMLx-gX>=rx`AtJ_8tlBZ0{BRYKEPagzbUE2vH z-a8P-?$kLq(B7W!&s9#=ua7*eN~nmg6zBKcG9J_>aj%Omr#apl*i0lsQ&%?(+zrC- z42jlUdM~3n`MmK?>8=kT9kYAfmP19z$QXAzJutQAzGEY)LzDR&qm>;Yvj-%An7IXa zY5@T_x)QYB5v;@(THk|d zHF>ASs@5$@8MCsOH8n0QNjWWvZLO>Z%)%d=*qH7-t9cO#z?Jo`nVctZ+scS^gnRoU zp&8nvQ1_}&gra5sU($uilw6{4zn{z&ZBk3*#W=T$y#&VJqxa#F_@HyUZPpD|W7qXH z_U^IZS;Vf17*}hyqed)}N{49qhRFGsYWZ{3o@FWxZA`Wj_XcavsszS%ji(QFx>YR) zrx(FouM9`h5Y2VXQFb+aSTw1ivf(QUX=(pDHVzxB^M~!f&QvZ>&kgE$?DqpA6~r@A zsDiDvYV5S#?+Ou~u&x#HGO0Q51`3@u;|Nzq_(LHP5t37E4!b9y20utZuyUVxqHLFd zQhe&=E}x4@V$GUp#OuGf07A_&2dX*VvY+JN!s(HAT*eu22h2w8#76dydqLp4P^7IL zz9l6-OfJ$esIcoM|ATWsi=`jQiL`%TDEM}%ketv~1uJ6H-tZyO_0qHHbH;c)M$I@- zXb^$Nl+5?CFRMg>vnC%->Lt0s=v!6#u?8>VAj0iXxJVSic`%|_Zqof;`B^H_!%glN zFb0i6H{A)py2NyW{RyAz{s!DnckQ_h8aL_=Ut;~6hgN5a^RF6YBv>16-$=cYtNeI2 z(lrxNkyBD)ohiY7K9Qh(s_ULm6>PCH&GK&Wu$vay5oO+!Cp{Pvsqm|Z)%#*+^$=0c)R-6mHvJy z%OoD@ghgwj$_^KDlPH`b3nqY#)N~Gdt^O4WtfEO!!dG$~o@m_GY_t24`rg&WdH%*| z{P2EhSJ1)uPuP*|n8<9hOq?siSgZukLAZSmksU7mS& zOnYZZzr55sHUh*ctSmb&wi{Jl9Yr}W;Jss%dWGG)(~XX@v(8Qk{Q>F!e;J`%RCvSq z(a*>(w()PA&u$w9g=ZtbM{ekVb0NfK$v&H`Av0a8=y>;_D0=X7R|MiDPz|w#=>MYz zHz8cf=5)y|c#ed%0YU9I$hc-w%*IOOcjw+7$%*v$7oJ_KK>SUdqq{0KFQbGfRj0bjV7mkP%8A>tX*)5W&F6>8)uz{_YKR^^5TCZD*42vM z+JmIGFR1^N^~5lgDs0WXrHXklLr09sBda@KD0Svq39-BX2>)h=mYbl{h64FKzYel4 z9J&d;tH{$kZ)z_Vmv$qCxU*ax64IHOEz(rdUrcA%-{8l-=;wB8ci+KS<9DE(#+?<* zM)eFpy5f9O@2PS+xSU0Ndz6S$MLE4DTO%5J7F^fu15HiQ!5G0w;q_3}RCZTlOXW_# z2V7%`ac^aKNK6+i#DtsyV#9ZC%pODCNI%6^V-R82N!T<$iV+V!R0pnWgN`KzAg^G= z!NHLa3Ti+<6Ujy4>>qnH_wx2a#VGzDQKJohnNL8JvWX&qkf`5RHjLZv+*(bJScw;cCK2aNP9^2e}7y=%;w(QsO=uW7q%n(7)xcWkN^3O zThH2ef2)uC9EpoJbr<8gS^|bQeQC&e#Ct}qSk(;0wq=D8bzEZL@Mv!932Vo1~?>;f~kRd``ucVf{W83`qiMLp>(**J8hPHpUv}lUjEqde ziu2Qz<_*i}n9oovox!p8vR}TgRT2d&?+&X;nSS=hdXwC6nS0i5TdhdrC@_RP&CY+T zs7(P@arDd1NDeP>l)DtZ@WYQBu)*X=HcAL&bA&9EzZA(kUS~;_fuILL9w1|IsIxn| z=z#YU*s}!tt@)z0t!H;z2C0{0!Ouw#=IM5!98L4%=R2Ee()XHz-PC8;nVCBSc^$j( z@tYmaLi!zvxuLTlym;7Tm?vEL$7jjuWN@41YgnSEXBY;ScRfpB_4}(NbfnG z=j4trjeMQ2F3@iLLAuYB@$p^v2u>_1YM8oYDZS@ad6(g-*_@pY-o~{>@C>$pkEc2^6Ye11);*xa#A);B&FGisvowT zTB`TsDBUX^9&5P#GuHU~3jXVl0Uofv|HnpCn@tA)hM|LyRIXE=qo{%Cs!j4c3s0`- z;F3=T9rnNWnF_CC=@9LIO(UPLTAHS}deKbLF5Dbi%uRsnlU-r1THt7Cm{~$EON$1` zY>rc*dNXG`6N*vi&#Gb$sWm4mupT7JlkvGO%{W0=o`1QF?@se zb}f#$+k@TWDI;lrC2@~PeT3JuKdj59DQ-Dw5|HiDuom~3Eh%}^`w2+8W2$5x@i`a} z`HX#ahX;2vrSDGr4*Qn^>D4O?5^K3>c#vs}bl@^qbUKna34SJKq<{U>?+*^x{mFm- z`SAymv`3A?`z)D9Acc%fb*1vEz~1W6&aDGrhi(X`_7@L4Pwfp%wEua{Kko3Sza7BS z+wsH>I0Y0l`St(UCA7cWB{cLvxSRhsF$eI5!dnsF!nG+_&U3i)NeYh`|JmZ?%|-U# zTb!^SU!jV-$LhkiR?+;@3YyQYzshIK8*ze$h|UeVBOVUmwKB{E>EI|$ba!g3Zz_>Y zgQjuCv4OMf zYp5+(UZ1o-iTC6OHPmg`t*Hcp8b~2(j;`J#x0tAtF3G_yr99Vq2Rj?*JY#32?!Pw+$k7cP zOBuQp;4J0QSv}*%G=0&V#obKB*XqYE%&e0_aa0ca4aTV zl2Za}*r5d0a4q-y$Wu6K5)XG_&EFZnA%ojJmG|IooXM9NY^QK6=g;+Sh2VP*Z^Dv_ctVn& zYNZ$q*IQZ$zFyFpLPGXGJ)2U!#1E=GZm#k{b#yI@2w@fm?ZJAAXK8x+%Ww6({h@YN zsBHQqa$c6a_WD1KO_&D! zn=w%4ki?@71XF1}{cA1YBo6q7e*%E*c=33Op$zIq9by+qS1>+ep_C_w;>P{raY@oi zk`ws1Oa6AHKOA)Wr4C78p!sNwN{!};E=88W^w-P&L(2cYcpD{PeNUaNO-#Yfnn2n| z=-)r__Ya04K7_x?jn;8Yc_=gax?0^!3`eQ;=nvVRr~(0Ly6G)x5L7BoFd51inta1CoabXS7*?9 zgMXi>f$-?6zLpJMNCgsMvrb*nU;ZWxAFWWU$9C1Gey27)B_&DoP{uD?@O(}6?Afzj zr_PBb*H3iwt3Szw_kyq4*jZSfwW%umVctBQHKIQb%|00Y1S3;(9-EcyXc?AD-N|CVf}3)u^SRxs=k1CoSP_WN4uE zG9w|+XlKJZl7g>(t5MmZ_dgWHT>USLVm#-G{;epcN7g}8_cE#q@(oJHIU523qpCCS@E^96)F_(Y#cC90{UmCSS(k()HUwZwDKIGKaD&TmNmxyoUXmF3}8z=(3 zcX7wvtJmY95dD(joJ_UdLNfKFu%M%7&KwxT@h19g0fH)eYBxvB21n;2I;cAADR({W zk2G7Eia$Ho4l>TAb1o-&ieew%ygvS%f1WQk@>NO2#=5Wgg0g#l1~+Qz1$cfmoH_3* zu;$RbcA9rWqg1=o{q5xZ6(3@Nu#+?Am(WmG-I9-eBej_O?NNm6j29gTgE)|{h>jM+ zKZF#2KSPGQ6sLrjb5-<;8#fsp#~Cu8$+G3^Kje&0V`Q_^-REP85OCG#Ly7CW$ey?Yu^X=T{vXka>J>69AWbXOS+c-5OR7U8q z&9^Z#G8sf+&^$j()e?v#^K@`vZtk!(B8;S+^4e0nDDV!nY_{Oo=c;HfFto@hi0Dt@ zRxeip^eRe=u6k~}tF<=3<8pGMdpY=GvLr%6bK@%=&w+N81A2lEuV-8Mc17g&*#~;G zpdF@!(JiIX(c{I+`|D@4X_(QJNa?^dN{l}MCgN#1qTRB|K(|cfA4mSJte4=xGc{qg z`5P4sF)5Ycd7%Y;@( zSEqW_TpDFbxYg4-c=RynJCc0W+}0dr;QA{lP%vVg8!qVo(f@;iUQL730gYNuW3P3v z^Mydp1ZD+%_hQ}?v(Cb40QeT_8AhU)8B1@xxGQe--0cImfrjSwWD&JoC^^BbEa zTcvS*z!Y|QpcWrb&&4(QU_X?2rlI+;_(sX&#(i>6diJ`NmS^feKy;q}fapF$HEy-l zEMeL2EVjoWHfFssf+D|Vo`)MsI@yAEBHJ_{?gw@m3-Pyq{H)6Oe{?)FG zenpmf;#%769cg0oiXra3Q3aT2AJgn8s%ESZ-n~l4AooST?rj+13E z{4zo_lqul#RJKyk(_5B|HQg&=Z`f+RVuKJ(PgG^7??rL|Y<}+=5>S39hY-0L2J}8OBwv2rmiByF* zc%9csvQ74Qc9V9O_P%|QX6?t>5~0~-z!P4m@fNw<0}Zp){gR+%!kSsH*h%VMQcM6kZ08RD70(IjB%$`w? z`-2<_Uqk)=ZP|9Uq>2#uUAF4w=56G7r9{Tut zpW>~PLdL(Qqtg=DhrEgWoJ_Gx=r!bfGX}Qm3fy|M3Ae8{X5@ek85- zzxr+5d2dg*vnG(%w5eb zFHhb7%01TbS;;%Hgo`kn)TSZ5W@vEPL}}1s-b1>odp>zzU(Pwc>%9GaW^hW8rzs4k zyL20k2`CjpXr=ym%OKbN7tW_N{J+HclJd#*3-M4-*FTP}sGH}0yrhf&xa#tMLwRPX z76#n#y7I#LCHWP#fPJTV-;68#{|V=7@BV2MPP$9v80!zpjRn}w^OlL5#%T@*;uAGQ zFt@dg`p-OhIrsT0=0=C<#PBS#F=)u)yqj9me>l28kpN>Vk1#ImKAjL(thFUQM?Kte zxilD^lKLZP*O_fsBPnvWo9vDxzVF+VCW;2l1?7n`_62_svU=phMy`i$kx#Q_8R_Ww zXx%F03yF9MA9Azeq!A6JtL1q3SwEFp$M0Vr9Szy~W2QkFEfD@*hS`5Z2QmLo=%Bm9 z)rWsY2iu(f8#<^IA8P!3I;zg&>BVXs9RlwFp(B;G#boVl`)|@FEw^oYjft)u0D-N{jm|C=|1T%JfH;^Et>>Q|OmHrjDDiXVHez*K?rs zS~vfuw(@|>d8hbzs~4HmgYSog27lp)L3=;iDOnQvxAO3e3Ew}0oj(HoG#$}0_!?vV zT^E5{Tz%@rF;w2VA6<&czu>VgguAJgny#TV{0Zw~Ohub;eA`+5iDt<|*s9IORh4Z{ z6#{39nhkz_=8jv(%zCkWfz#E=@ggY&KT?#O-h=kE7G-w%G=6w&4N!kG5Zi9!erbLB z4?IybZeUi!T=?; zzxMc6#9vpKJGvkHD`}&}-jx+NPfPdzS@3^B6jd+iyfi3735SMxb_V8X_vPpC<2vpa zoGLvZm>T@`lk(xI>2!QuxagE4>`3^Qm1H;TU-3jFPobxKsyRmrQF84s)Rh==l5gSA zwdZ(@A)MOvPt6hLi?|njU*y>{B6pv%z%P{DLcUMBH=LO1^)=8_5TJ%7J=Vm9UFN8J z?uXCrP7v=X>SI(z)pqFBlJBd|*wYbP^$k-s2?WKPM-%@@y^)AnetHedI8ds<8~oPw z=Q%%if&XcbO0Uw`a=gL`p*J1N@q~g<2$mQ7bxniQ->J#7sQhl~o~O=ySym`F!adF- z6YFu1cBKPN5H(aEOi%Lg&s%T69P;kU9I33BvqH(5psd60)HXu$;$m5!siSA;TS`M1 ztF*dnJ-T%*LRxFbbV<5XiOpth)^nAq2Pw~`zG7t5WnSJUL*lJ+Rs1$vkjIEMUAu3vzA!B!VN$0jp{9T@{yu7-zNPELy`;A3sd6mO) zGLHWIEG>kh-0s$H`UjNL;nnV{nW-tB@NXzRdd?-2+~WR~QV=~yq1w`5+~+BsP(q^i zS7cr5{luJ9)3Vv;WNbToW9W2s>gtoP(9cO76L%zFnnTx)qGaoHReEU}5q#mSwGP{t zaXSo>I(68lsYUbTOd;l+&uL)>QyXK==AuL0>*y5~_NX0Wc&?vSK1obrMg`o{xwpu) zhxF*}Jwz<8dk@ILa6a5($K#|AW9ydT`UgJEjCc8!*xFyacMtefrkyW}76wm3HEpnn zB(w^`dg<6c4eo5Oo<`nyciMcc0*7Gm3~+gA7fPuwe&wZ>&Bw94n9u9#(&5}^^xdYZ z%9_x7{b(J}-`*G-?%tkg-Q7%G^_*MDw%Hiep1tCA zwu6cd8#2sk1-dwW7`kof7FAFKycI%xuQS*V38CZC%3koEa*IyYD$u&Kvyux37>xgPWw9kog)` zqVADqJw3mj%Dt4CzS(`gAfZU#r8pPA>6JUlVyQ*F@eU<6y2Sj(0;*27sp?>pW{`%+ zQq{K&Jc`XeyTnha>OP4l<~SFWR9$cpo5E)#!on(!zI=AcEtcS7#Q+x+6C|wLgllD7 zQE{`NZ2{DSbCtr51T{Gl68ntNl4H5+X;q$;CJe+L0c7$AZ1y6>bFCJ96W9lqN=#KfjF}7cO{0@rn?H8^INTm!El>tes!|?w+_Q7+&|L74pOewjhP4xLa zgeQnj2fr;45FUX+uSgxJGkGsR@Agn1RJ~t-IFi?g@3phn8tg~KWNoUwglTodCcX1v zl&-fiMX;NQeCMpe({gsjA!Gc4E+&;qs^SIph0s>QU9hJ6;v z;mg0c0F+7Zuy6ZbA`gWxTnB)fS$Zx;BX=|n{Fw^4W=AgXBgJ*r+y5nv>kS%5{wCeY39#+qLmN_4* z9&vx}gegV9BqJw7%Wi3@z}H{6P5!1`$@)6Tri;SsK*f2DkizfYgAb1unsKU-;5)pE zU%ba#=pCqjNK}fgyc1Ao!<_IU&*Q#?$_)z>GA2}s4aHZ-5b!=a7E7-y zr)7Ox=@v&uR%xcDRA^B6+!Z5o6sm})d^eQAP7K0 zH0l;kx?USMeQ(TX_Aud=Mt$V9HXqaHVZ-}MVIg2xjpQD|HK|H z-B_|~2P*g;Lt}^Y8MY56C)HM=C<&y$OS}mQiVqL0mj=vBksc^r{-RPl z?53ls#Cq%zkHNaggkof5{qm7#rvbeyCsZnZwi9ocPcx)>2liG$W2xmnlGog;q*>?bzv`b!i#ql`tFPTH3#zQ&Bn~4(jhTF@at#yVs)QoJ?|pj);}* z0G3gihnWy=D1L|{(wCATUfN5!P?496sGkt#2xdui3}2>MIEr*S23 z#Jep2I^+tzT^;YiKGNgLAp_wr0(x@Q-f)2FpZ3aI9sAKoo@zeUG&Nod{GbAnLsdu( z?&*=kMPIDWmMl*wbDlFBB=hAo|D$oEO%`Pp-(T!TC2Du!%X2o=q(zW-U%S$-pYW9C z5&dejkVGpzv_=b*;>0pwSJ`|~}>?;~7WdYGy4n$}7x-_~AdDbRBZFtQDZKGYJ#`}2td zB=|*q;Obg>uY)Sae#W+k|GZw-0KpY=9zu=ps;h>CXW`m?dqA4_Jz6+%m^astUimiS z*RnhfejfGNQQ?{rsn>U%FM=woZaxEikEp|es8A-DKgL58rv?IqLPa9z4<^H-0)66m zAFfXxDZX4-U^e8CI#dpCa4hQ-Na$pItXnUNNIXv6@5Sv@{NdXW9)5}AxvRv`3U=wy zxNL&U%H@=omsf%0UB|fC(TvO=IlKm9uzgFc_Zdsp5WGtl@AXrj2joq>R!hw|=LmnE z^aXbz0IDgj!O3i=Q20P{390ox-jvHlmE6w>ZeEU9sp#T97D$=W#%(=z;IGsPu9Ba1 zx|AEfGX$+h#WONbxE~>8JOTUbm~}O|jGWM*Idv7MrrN-dlWdi`7lKRS`?eKsvK_&y z|EtONY9c_|;e{DSdeRpy$veM<@x>|3YC2f*XVP+wf0&z z@^qQC`c=gs{sZy@O7JH3=eJJR++r5>{Y|6=>T2ml*V`!_wLJ3Q9>br83EyKZ8sH(! zJpHqivf=k|ZX=T1RPYpP*s*U}ZmbRt1cVzOV{Z*xmu`*c753ut`)*Ht)8)mI)daT> z5wU7+4jW%xAtpwrR1Oe5v-( z|Hxyu=nsw-olK^c;wm9vC{?GJ64aj&;J?XY?8C;;DhMhIWPbOS87Ybj))4!&h_$$G znHo7uS|&>}g{%w|(}nbt37Ge++HgrdPHZ4rWM#G-D(4DCGOElj4y&-~BugCy$3DyYmcorRzk^d1u{3RdK8>jzbJoMzJF!QR9R}S4XIj8j?0cW--0bWaVm<=rj*%G_nTTiFP}A_%Hg*YKush$2 zt=pT;e8yRR78+%Z@t+d0^)x1gofKu?pGQSInsnDJKn6{$J}vBQ9S;0#INn}b(me~# z`^2yWVw`|0<(F%R<0mp~n?<(W( z8uY`XiJI%X(AHFyu@P^Gk5=*d)9tQI>fpEm5(3jtHXW=!17B?`22j{gfYJnp8c47E z=~2AD5wfjL+f|lV^m@Bw@@3S%2i0@s_PnfN>Q|z{^^r%I0{O7h_4tOVsY+KdpJ~>W zA45kbSJt`E;Syh0Vq^>wyt1qQA4EMwyFJ_2R&R*8S(ptlMT9cycNRSz*ykIagO}sP zSatnFNw38tYCK}YGnY&uI}-2LTe5i|XQ*eNMweQgeV$IkdH?S{TM7l*y3e)xKN zthYbMqpSF z2KV)Ljy>XjYBP~jme_Mvv|dzr<9^(@aO)e8b-*L3e1hS2b@46|Csy}NO?7f55Y^KU zBA3vfW@Bs1)zhCPbm$zCv{OQVg@p41$nl0|Q57iw=`Z+q0vfmQT}2C4W3rIjGwz{op^pT^p; z7YDPed8O&QzPI{FnDdsUH83nT0Rw9IcwmM z+<`&E(XO3B)A8p3+n93swIwt=Vb0NCTA&q?rm+4pH2EfShSxPKXxdY56=Qey6B}gg zw?}eAqxcNA9la0D@q(q#**%%|L3|4fouq1~ZMNgGz?S)9v@D{%ncBWJ2N*-z_nmV> zUef(#Y(tx*Y%7iLw;t=9)!lx!ROX+nx;_?4eS_xkRI6l#8bat~Y(XNq+ zV!N3h>}<48gCkcK$T_i{JvA&Vicb^p-ec%)A206GUQg5nAEv8P5{PbS5MFzf&IH0P zm;2)!J5oeZCGe5XzhKTg=X3?fXmyl2o(qVSZ6q5Mco1@Xjxj3uWR{ky=4bZ5cZ?=m zp)eq`0v7uoLJgMe?}PEwoURYnhs58%r;xsJUaikQf*p*fD{XT=SLr_ciRTtfyfJrU zsQ7vEXuc|ikb6iVr%bBs$)*Wp+i%u|(0C$W=%jL%@Lz2S2!38q2_muO+6y#jrmG>C?=SX0){RJar(zHY!9+8cD#Yo_ zp)3e&`I(0uxrhk#d%^=;W*A?wYh8FXv45||ietgY3=0D~PvkS>`Te=wH)#c~A!M6l zX`bqwrRWcAWz`Q_HLj;rr&k}HH)m#?J;m;^*?WZ-QwYOzW1gndMB#&2ovl1y9&X2+ zVtIG)Jw-+HDW}01j&=JBRm-W*;YoeTZ;bDz$#|qOZreEH)uO+L$K<-QKX# z4|i<9wc4gHXwh9ypd3#dc?eMUJtqG1i>yo}`eXoW*|ba-n!w z?M^{_%fdMScxQ^0gL~+t?ipH3W&88bNywo_3xG4K97(d^LtLhR_^_hvogy(DdtYXWy zcu*u3hu`Po-p(rQeT130;r?&kY5dOQ(b<@6X6l*~jELm3bmZh8=@jl?(po=a(CV%x z1c$9D3o-ENZI>y={NPo4?&YzB7Bi zeG`PJKjbJ8)(PsP?k^=gdzKX-EWicJ;7=B?%|DD{)^TMHNVu_mQ7;~l$bwvTiLuL^ zPc(V;X{L%5r=jzmnLf|gy6N+ztI+w%?1S+Ft?o}WMUh(pLINmkY%GjA4c}8@+Z`Yf z?ia^ewbDwz=351%%BIU~BagkFQ|OMFPbs);kla;R{1Puyg7$4Q65rmwv6sBoLw2m% zpX{ew>?a8*>@>BM!~CaZ{4YTQaN1+S1ji=oIOu=u6!f;@$KP}d2cme3p%M`g;IEKx zz30KaZtBesnYxpR z5eXPecP%|;mzj{YaZi&Q0wDC4HSUwHWLwt*mXi;$V3k7U-7n|Zf<%0b);b(=l<$^U zRd=S*kw7GC3L;svy>2X-gsWxGvNfi$gc!Vc0%3giFmSZTkq#}Uyo`2j0rvkkg}j?n@iA_llZ@~3;A*thqm@S8ipZ!o0aIp&IEAuQm029l#lauAf zfAz-StIiWC$|A-H2&u8|4O4q!u5X@z@5X#p4Z<Z1CGOQ+Y3S0^+vT@ZDDzi%honW)5z(0-jKxi9*HXYEQQaP^wxrgDl8jCLu%- z03i)>MFg<8DL|oUPfzp?K)@P-Hc@wdAxrNtaK7v>zubT&q`OUN^#>B_yhxE2osjHp;+dQG z#`r=QwscxaMBN$Xv)F>1s}psXl@!hU3_p)&Us@)NxOkP{1g{Wy)FY-e4{a=}1K=kH zxWK*cz4ZCoMXGgt=9?|?eW1#YgPxIA-o(`Sqz}?^UiBH1QSbe%lEj*N3Xl89k%f3E z|D~utyZOjPLs{N>+P2K$}C^Zirya4 z@xg+u*zuB}>0zPnyZTPK)q%8z+EeGF4UfpoUiJDq+|%M6TTP$wx^HaJNM)}aztj_& z#w11-G(Q+-wB#d|O1iOqufwSU@wgyzb4pp&D*CEnbw8+UVOmUK^(5tRKsY_vq%$P?tXk^lYcYwB3Nw?~ z{^TG_jp-CG5SHt#?>C4`Dg=o^5eS-lJ4Mx7Hi4UH7|t=dg2lygITbq6zk{M#8+^Y^ z?7?Me$kO0l_&en*a*fF?J$Vh>$*Z4{Y#5e*U(tESuo&)~i_J8jcvC~na0auK^NXmE5Z{YdhHj&{d@ zyWKPNGMVf)V(Bi7UNr!g{aL9Nj|pg0<%sL@3@unvoKPDC8s>N^Ry5)WzYFManp{WA;214w=3(C#^s%Aeqd9-u!+$-H(Xe}ij$run}S-9-QXe>i*VsHobu zeb_=!1XM~%6#*rsI|M-iDd|?a2c&ZlL8KL=rKP)O=pm#*knW)yhRy-LYmEE3-}m=? z>-Vki4_Pc{*!$X7oN*k-dG0b5*!ug_jPncIacT8N#C^*TZ&DGt@jdZAB0Nv3V2xkd zKB~8%CNN>_@@T8KAhtf4ns$oqpMd9@Wq-`Qu1n^`XDT%UBk1?DqV`!~)Vj|!QwQ(v zXwx6V_OG|aAZqW-e}nW8N%L$5_&4=6OKEt5u$q#L%q|rDWm@Q!`ls$6?d~lUp!79x z^82`#ivLVxfq6v|Ko26%1WTgIhb+v@NWTlW zUC+)GY|yi%Rg@b92i}M|;1@#uC-Wte^nz}V=Hu-=cC)Z6IuSaF3hwtkw`R|Q%+548 z`roj%8h6jNc8i@b!FMLi9|l=(un*#m5q3dD-WK!NsDvL>l9-EZ{#_rFf-Mi;>=^;+MbXfmhESY)#k@)H(E9Nfg6X&CL zX7hyxytJS61wICmHbyPs(yYhT7vipTOBrHW_c3U9Tq%6~(8~zlKKyV<*UBx(s)>cg zMLU5`X7pk#SMZg|D;IuY`3~a13r|Ep4*~}MCNscfoUUTx(BJp>V#h6ffphZ7r|?&x z{}u%LQXtTWd%cFa^E&Z`#a0>0jKr$Nj@~AvI4YZ|bhR=;HrzFWnt+5Zb+lO%a%b4r7z)AS0)bT#0pR~?h( zydB1EjWIT8)zl(Bd#irC8X)Jq=V4lPrzeVYlLrG&?ve0a$!Cm{IDNVTqd7N#n#PUv z@q|!paK}?@>{B1%J<*xcf zNK6jv(CmM02}r-i2qNeU>D365H+I|0K8z=mZLc@c11;;nz8O>OH7I3HjvkjHD}GXzmmI z=sG`zf2EGnG%G%6k*29|2gKl#;Lis>YIUd}JmSA`Pnx_ARn24S9Xj2UH)M9g?h;Q@ z1)G2Hx&RpnisvLi(z?w~xCFSt3m1=W+1MN;ik2)Pgx7C%b#<|_Wu`Yy&Y5g}qvtAH zf3J;4hT+dZqB~viN?znD!8?9dK!5#^XS<5?FGH8_6*a%vdjWKSXz;VDH*UTCjX7 zT^GAddDGWhwc*x$d{y7l)2j!E%N@-!qPi0~kKg=A=}A7S?CfX5*zAx0F0b469g?=zBt&fp1l;82|Stm zDSj$*zurnkSy?6|AyClJ+&YH7tus%rtW|$DmX@mK7*B4ve0GYf-Xca}s6@#k@feTH zSWouFu^J#Ie6fz!g!2dAhwIinv2omUUh0`Vab8#& z8bYOg8)fD84yrQ~wVn02A>NP}P8#FGrJ{m|6)uxT-?GX_$xp(1DxR$Th^z7TP%m?~ z9)Oj<#_{zDXcU%}~@Rx3Lz z%dU;&vcN$9fXK*X>-#I8+YEiz+B(?Wm~$=dYH9?9QuF=dSar(gcWn~45`AEy)Z+sy ztH!Gn{e?$Wo6(EdF#_r0agwQacEw!Y_#Y@7SJomQ=Tv<}RPG;iop_%RP$e`JMCC3~ z9`0_vr=w?SS}Q3mZX+f>yMFL)VJmZdTpNF9$BeMnw&FHfuW=Lgm^|K5vxrph8Ow=F zdRM;HYLzqIPHoxS#(dNI)q{<3!|J6BGY zLn`jw744Df%{s~7^@Xw6p^9^Z|xCzxoT_ zSNQA&h!3K-3uDFIRJYp*qNT0kOe9?qk6qvc_0jxhQx3ue{sx zRRF=GTzb@aPv@&`a*#fVZB*8d#8F^Y9%F4zJ*K_K;`dAAf}^Z>A+cV?r_l%me4SVT zNG~(ZW>?h4!KPo7hY{bb4xv7aEj2%-n_HQfZEy(ruk3|knt4s3mi%SBxUxq?EGW}A zQ}N>Xe1UFZ6*@{X8TK9T0~fu?v8=~T<8KlgeT|Dttw#r~;eB1_*f?2w%ptNt%e3Jf z{kHSz+xXl#*Bxh0#ud4Css)8oJ$DXS@WFi4+w+WcyR^S6YT#ynr#BH}5|QGC*aUN!n&EFmY#4sfeY$eY`Tiz8T+H0QcNpEi7K( z_=Okp`=Mj$$3Bgic*}0-E|NqFdJDMQKv% z(7i=7;kqktu%Bv#FHNI$Yt6#IDvD+tJ1%n6;Kh@Uia2HU%5AmHCd&dF+TH5X*MOV(JG*5q5-imvR7$-LAY zt>Y1ZES^?EqI9>|6zR@stmJQ+$06dM0rb7CR+k0DH=5niRdc=YKB()%VZGZ7tHF1s z_Jdy^b}+LTm%*QGmX*R}g>Bep+%sUZl0fDBV)O`A@nqpOf6L(2v&()VL2*J*jp{%T zT<8JS>4xQLVQ&S4ak(TPFpLa~)du|_io*uL;*2T?a)Eihcrg-ywAQy#`1eKn(B&qV z+uW9WdwAj{N<0Jc2(+0kxSkV0>{z<^I#W!wUh$0RM~^&7Db-n!=p$l$8X=BX;qtg} zx8FvimSP-j+{fgKpVjAOR#ClC4BL53a`HlZi6yZZziq>}`}K%M3LWr+{1+u|K-0*# zT5^8VAW?`Kuh$blxIfUmNYX@&M|>AbUx;)O7O!*)tR@@epMnRQJU^24yssV!71idT znceMKqW44ex9pgNa3!!WSQPA2Rtg?1K0EZy4)WtG?{YE?eKXNINHAL)AG0KjuSqi| zH9k>`>W89_fs3 zrUBVfX}cAX}N=5d+O@E%f{p=8#d(^S9 zEz}*)-|M_mKCK%Z%h?h1(aqND=;*8tp~>`hM+eExyq)ojYsh0?V+iS`wq^#)=WJ~npj$G-pH#095djd^HiRKow zy7Y>GClp;5x3xWkJf;H}(W^IDUv# zwX5pZ+Ex8ECVB-|ZU>AdT$3L*Fn$x!qRj(c@Ns-ju;ysLvt}3CKS8%*-Od6M0`sF_ z3aOTW?Es7**mmK%5XiCsd`FNl;1$4taeI%VMFj|uRE8aOpX7T7rJF_j?D2IPxFWeP z0D-o^^Vk*I!8V&T`HVD5Tz_2LHD){xLUb`N1FJeyWXSN|r)RM(DQ>hrS5?e>BW(nL z`rp!p2#ChAH9+iG0ofs8?t5$ZmXkuj(PeV5`92pThxqAIz0iK=Sxv*qkgJ=EtE3JA zkIAK}e5#s+w?HJb(99)nEK&Hm$P5s#OS3OU+txb9GID~4b}~ZA1j2}G9r5KJlWA&> z&#AH6i?e=(8IEdIxpZGEMs37p%Wd@@^;x|?n;ecQjVj2>Qn_>MyqNRb0su#QjA!O@uEGBmugiZY8DVKhdq5EkN4W1JwHm_jt}3Z_t6KF zW#;EAS`Lmf%n$pLn><`6Xa}em>joxD&H|1#tG_R_9+OEYjoKe@DJ;HvY$(AzvH?p` zJ31bc$NfZH_t1wclOYu&=yl3ND(&56)%mNmxXBfm-ea70iD6aTX^Rr|Tlm z^obTG+oD_g;ZvCt*;yv+beuUq_QlY{7?ScKm<-|MxaZCeZHwgG_*^Ep3NOP;mBfE1n)7044K2P`zQMj%0?d{FQqc7DOo;z@mJpjPN}C6n{7JwsiCTD)kZ z6_b5Ny5#bUCBD8>3ALT7L~@aMr=Sn7@}XaY)F?Hmi)qjszx-DS0*sS1qo`Pqg&{Sz ziE)*0fUeOP+osHBhsW@@cP+7$q*UdSuS6GK^DyH@aQ4DhT7s$C%^zDlwOQ5iJh>!7 zGxlVT*oItn{vI!Y9yK`QbWfLIw>!BBjc@~xM9z7wlWTi&Er32)=OHBrSaX2hsDV&_ zp*H1`luJCT#5ySmGt?PZZZKFQZk;h~j3+PtYh=AR&d!;`eawMPlW(6YYjMVtkdpKt zid!={Le?fuO~R&}f~R69S##mUI;>r>#H28byy4(TV#ATDlUiEFcyejy3HqjzN0AF9 zJvvyu{qHO=$GkNVOn?u9%a#>z5!Z}L?@MELBJMwl-LEnsy8~3a{?F-GcnM6Q%*i9n z5I>arV<{m=s@f4l-@L<<^?=N;=vXUmjdxn|VUAYg&81U?&fT;lNOk2?%h==lbWAoi z53N#}F#gts_*V_UA9|sDMz8)>rL8@vY~U&@1r2FMh)L#3O4yMeZ?rPy-Rl0TGg?9I`6Kr8Fu$fk&b?&lWxQ}s^W<&vf)twz|(Jx z*>8)Lqu2PD6p8Vz4Jvyqb$uRsg`#xoJyn!hSU5k*PUd80ceB`SZtl-0uBGJ1`8RPt64GK)8gOG=cRY9`x9&uX$Nj1tP{b2K*`wq^FB z$%j?~-DADXSymtp4W8`uMkdH3=`_ArNW z2!h@C#{eTxt^yH4PW&A_%!+){x~Ro-?rF)5>Tl^H6~+?~an#;i6tiW%_F99p;{mt( zkhs)UX?z_6{MeHQVQ=qM=n)t0X;6CkTp?ePnlxJ(Z}|~CU85S?sG=Z~`&qDnzW*tY)cs-2f>CmzC+t5}= zIQGZg;hwq=Dm4jEN-!I!D;L8%NZ;NA3$cw+_*0o+d4PRl{t`1SlEEK-O-q_r zO<*Edo)~>$Yt9V5Y9V)IdVthsj$A(BNgY=`H_$B0g^3&#R8Mq|Eh_eB`SjEkWPfZ2 zGC0PE^>$cVk~sNxXJ35jSV^Lc$VqQK+Izfucq4yiZJHgN>IHzg8p#D*2PTRS9C^m) z;qUUnV7OQTb|1_0JP@;s=49*YCs06*)euU&mxJ~y>%BycFGX|zQK*DdHD#qh<;v{i z3Ge&C%30@IcX&K;sl|sv*LTL!*=HMHwwcdg2)n4ZZZtbR`#oJl5#1AKmg>%kdkech z0xqV+C^aRNVV>vdN(_#j?}HU^H$#l{og^R=*q&cTdz+tQiS*aW0aB7%#+(4<7Zu&W zioOv2{O9?}_Vw3iPfS_5^!NM`6wZpH?_vO-)StRMHb*^g{LqU8=e5Mp%f9~E1E$EX zU*;G#@vBrR{f7e6ASr$VqlGUh_(@mK(KjMOOOH8WDs+B}4~(+>D=}u25X=gM!}|<# zR{j{n{(uW5SXX2suG3u1dFty|x0Q)wUDRHOsl#e53^ydddX8#a8FMh)xdzL0l}dD; zyHLJt`=*MUT_ZPl6!yCStnJz>qp0gGFO|%QqP9OZsS*^g@T_2}QSQkA3t8O%Ob2X_ zYQP&t!0$eVV)ntG0hp`Q!VTV?x%dKS zZT0DB{L9fNM?F6{Zg*OP$nkoF(GsKJ)ty?U0f(JQ`3Ki_MA?mn*o}*eqeGGcm&&%( zoDg}Qyh2EMqFZ^`axtzl6qIMtE>62JhBQ}P{<-nK;+$L5$uRS0L{>=V=7GfC~l?UjEGnVY~ zs}dT?+VNL2s~o}q4d#nz{sByWec9{P^{F0}w6Bgg$S%DFvL8(8;$$?qw-TvCASN!S zp#1`-ekB(}^R4ykzy5WrdyAJq(yA515>^mCSDmv&1vX&|xO(gf2KX&DR+^fZ*h%L@ zBJ8R(Y!#EGXX!p@G*-8?$i}dp-#;hGeAN09sAQ{-hmJ!0x8SiRi02t>iUxFuDZTTRBPG0UxjYX_0ehF?*KMP%X(HWg_9!{`5>S4~b$Wc2uTe5IH2$b> z#?2c(j!{&5#&9$pIgZPwrldR=XqJsNcELN4>gnra4KqHUUX-UY+h6N#ZpljRn7!p0 zzJZ20TMq@5!uRmw{SSvm^F17|MakspawDu-ms2AlVc{!w6-}0u6Rud?jv)mL%(`}s z4ei|U>{Ft$MTj4Fu;d~L_{LpSHsPCk6>?T_K@aj{y-}1$PHH<7V>~0Zu1Ed%=moTt zl(eeq%8hdDky}bLe(tl0$}Q)k`p&mO4QRv#TnQkGtE2}urIIJ(&aGc)>!S}Bgx?bz zB=pGOJbDin*$zpvT22mZ&VwY8-L#0mn~LpU7odig?zXg8ZStrZ(W!DY~eVlUs=UO ztC3BzIo<5&sKVR>aeN#S_&juI+01MuZs>HBZFzp@1II$xetJ~d^W*Q!18M6+W?7J3 z?eQukWT@7zy(&mKIB-!;b7`5UwF=6U?4m-DC?oHYIywS7ipJ!yx(HVdga>_;iEQkh zg_jB32MHkMpMI#v8r5;1J}>6=I4G)UF<*(LCD>>t_t6owNYg6Nos8M^d4DxHmPjov zvG)T4w3TDm6-4<75C^%jfBy}c*+VTYa*ca1)O$S26mxoJiNZoUzqYut!b9(rE z12$o(r2AJvdVz@iREgLqC@%AZdorfp0`rOX;UiOR?#7*=Z#Kepy^H8l@ zTMkz*=}5*(130LK-Dm+_J=0MBxFm72Bay!nu^a@c!TzVHq_bO%IbqCkEPWuKWkYBK zg+8#ngJ2>Y-*+rKTkud#S5;}$^VH*|!0(2j`z`E9^H}gQW7Gikwi9J<1v#d2V_^nP#y!_;a$E!)bHt{!LD>d+$DYk6X9LcYYAb|K-aP{=Cp*K zWviK}g)Sm;4>{zr&K?*P5(B)tsSA`IKPm&~JHqvt&H0xt&6K$4es$=9a4e>z4wR-@ zY~-Y*yn4ItD4mp0E39_2<*$r2{DQq6xkVMlbi^;M`&CCLG9!bbv!>Cms*XktPfEt9 zv;K{Sm|1QFlOEJ@HyWk8d0EZDA$aC61Lagaytci75r#N9aqbzY-q#CqxB22?ppImz znbA*qsd|3b-rJ|T0PBR?3eEGwM4k#3&W$!wWzwrUJuWH2J?ClzbYIk$o?K9Qqjg%e z9cAskEhWW8x)kdH?sicVIZpF~D)z$Ix`(=zR&Gi9()9k2g5Y z%~ro~T94+wP(D&)O*C_Md~#rAK8)6J?%a9bVB{k%JH6?oH$^h*#fLn|%4Id6mkoWb zI=J14H15(e^qF*beX&`&eGnAXC!U%}VLVCmW^?Evk+mpH{TC=gukLx;exW1SBC1k` z{Oo$ZB}wl2a_WgDG*{b@+=aQHb5-X9cT~qbPAw8?;S6*V`w}X@PJ&uvH_zc9WXTJS z7ThDD%X`)4c!yPIypsOl?xsTk;D8E>kLpg^X@TXgSRhXYh>8zTLilR|sSCzOCGHoPQZ_&YIziV&*1m@m>Gwq6z`i${AI(Gv-oe-2&LP+qH#^I`^0q+AE<}%&k zyo`4rx-^NdMnZhfc@%anZIm?v%zI7Iq-dYD#5APO_ZWn>ZUwQ=kRag4FI?Pkt2g{8wu3>Zl~Ht9%0}Gs}ONnMTJ*COc_%*n9e{^&yB6hN; zAd1aSxAh(5D9_)h7g{6V)2%Iimi%@ zkJpR8O`|^P3On`Y|J4G-ACHG1%&KQX*E2oozP4kmuA-qQc{w%pgB)DEOlD zzol$OArW8KEJFfy>>%86vMqu?ZiEeZc)Jp5fecK)o7xoAN*_sx2Cy(jvy?HH>C&}}o@)=J@Mq*+O zW&EM5Jf^J?oM;{X#N4`5H-p8HAJ(D!6jk>AB3&3Vo?K{UT+hh-?IAKkQ9Kh)yS*1P zeptt#xuIHu89@FvSkCUZ%?7BuP5dQeR9cRn$T`r1_n}|MKTZU?{|!rnCD{f8-QCkt zp;zd#x-^Fu7)e;{%Ntn#C8le`l>Zswhpf)`4*HE8aP!b>O=N|ya&*98pzKD^A|7AZ zF#J?l#$xi9P9a^$Kp7OdUU37LfgVWNBb1l$0;03xZ1j%88bK1p*aq1*2(fPCWE7>oHV{^6v?&`!Pd zA!eWCpD@?G?L)~-XvM&#?mtE2Sy@qTq$D7UIAVlm$Wx3g+iyMv zFC|`pv?Y9(-&^5f>U51tKSR#%7#HXYTRo!Cl-cLGl(rfR($q@s)H?*fBB=kliS#k@ zL^swyT9=oF{35Td=2Eak>^kH0HJB>>z-MxFF%XBIo+|EEKF&PoBMWbDA;5*I!b$vTAcqGLRo3( zA>ydM*n^vq*Wb?-;6#njXKXbj9LIJOo|w{ryv-7&SviG$@~N*r@*AXbg^WxB6O)n@ zj1%!Wpl!M_6~$FM?B}d!(ntpcbEzPq`|x(xs@k!yudg{!x6gB#8Gl*k0&gUJYA296&)3lB0dr8@VCg#w$Hx&%Q6$1p_mO$D4JxrXEM)wTs_n6-? zT$|!3m$od&0r1&X@U;Oi%|?~0R$7qaT~Pk|-AYwPrt03llqzWAr-*+k0JI=b`)oqs z0WzR(pcXx&-zW3$h-g8?qvnrC3g% z^kK&+>&$_E24dBgs`G!CTkx3<_$*KUB0u+VB$_A#8p;<6F3T%F^Yg6?lv9A?>^(O*+ z#%-{JW=TM@43vV?kiE`lvc3r7z1o7f^$U1-T{Efo6-{zXd@_kI1z=n{+rqUP3>hT_ z#yM~$&>RDVgHiqIym0*i*n+Nf+1!nK*0yXN^)I0>SGfn7?9+ZFI;FL2hcG2F4C32(xPu;z6h7+2abWBAnEv$ z7UKSU<~+-AIqeX>rs~9qnB-!^vm1V^YAo>f7toxJ1smt!IL?lhpKf*UM{pzQuWzg~ zGN73mm<;o@*;^J~wPp=Ml*0C0s&7Z?o?fk37bq7@tTI&zQp63vRPXr>xDncQK1m&1 zjyCtGWDJ)Aif|`Z`Ea9`;e$K%1K;v20w zs8gQa3Za-9oLvac$-|@q`ap1%HV@)>9n2Gx8s9Pi`#2kvD0DOQO^f~B$6m_7u0#e9 zkbEiLdq+*`Le1rY~98^h%8 zm$@kZH&H)eib_h08+@)?j|eZ|`XT(ccpL!p#6AkMRT;tr_ARopE`3S1v)-iL2}`+} z>~Oz06V$ItLV26qyIEP;I+Vd4ySwCblHY64QB9H4ZBFdfYKp{HvN3yy!Myw`u!$U) zA~Oyp|96-T@8#uv4IDJAxF`0cmmJhZH5&DdrJ-L}Q1)w6R4r0UP&8x^ZRB*+r`<6B z3Zq~lB_YYwmU%G>G!tsYkj#|9oSD*uHGb(XEf;M9g!(8Nf(Rkyq z$+@9KlYMiGv5onkcArhITvqiIX$=^=Q@p)@)$a5kNl#ID`twemQvT1#$-feys*;?R z#w2l47BCerE0$Urk5jL@+k_+!8PK*qi+AAu)YlpIRI}Jg4K6Mn>&BmtX z4HaBp;_h{NHJ1_rZ625&qZC&X1Ey1&cli!G$Z-@g8NmM#%YqD`o#HG^rF^f|eEb%P zA!Ix}*_Qsuso^K|eQej!n>97>97BOJEB@l7dwT1KN95Q(s5`}C-pD&MA$B}VENvU?w_jVFW%BEX$JDo;(Hqtiwe-1EDN12F? z6Z)N-4dzO8RI^x5aD2yu#;hJ)+;`$w@Rdz0ITS|xcqcS^;O2bbSYoG!T4%F1J8l~! zY(IrxPA$O2=ztrT^l$tZd#o(=t89Lg$f;0sl%E!zNAygmFDGyy3DYSM-@m*n!-#Rm zJ-u`Imd8ZCPXeUGbLPBP9 zyWm@tVJe3m{T$yy?NDPt+xi|~k9TQpX3JWl?mXAY@@T^72nDo+l*@?^^BLQpiYj7! zLi@|)#Q(A;t=eEske93AvChN~q!)w(B_i6fw(?@m|h`xt@}vi-G)?^E}Rc~Gyw zKb*uZOkY5Mqx_Ec&WDUp@(`7wo=4KoktH%;VW7R5wc$MEw#E^;`_^DB_n;$RgTruX zKb81C*}}Li!#IdSjX#To(p8j~0i$pXKb(sk$fUt-$7v4dA9rY1dNWJ*Mt6U`WvV9S&GvTcx{YVqvJ z;JoTCS6|qYk=cyRD(&g^|2Io$l>cz)0For>`1YgfdFmkFOc@>9C^)T$xsuaP@Z zR5wEc^+Ll-R%bn0#8?AHci<`S*A5-f+p|vl=T}Y#+WK?%;=oDf;U`Qelz;L%a(0YZ z=e^f=aENH>8bLfPssoxKndrpI2K~+*iKOmfbfkTH+YVt5_Q*W|6tt26BAx&SrdIkB zG?{D32n9dAfQ%im`K0u+r&~o+mK-^5*n2i)-zi3oe>U@vlpG{Ir)`p0`?wj%j2aIy zdtb(9Q%j4e#fiFJbIF@8;ptl@es`zs}tD6CEx z!g2m>4kq=CQO~jsPuJL(I1&0vzNzJ%9*G~Sr|Ue=x?^YD;rl(NfJgCeGH;LE!}a)Sg6 zaoiROwnxpgG~Nbx&mt_khnH5<1EFK~#y-gJQHK^6-&Hbz2g(1z)Qkm0!L&eOTokPU zavw|rch3&QpB-O`hyg#ZLIgr230|z)AdTg<1=C|Zji;S~A3e5M@m-as+MW$DVgwM6 zZ(Rpbfdd93b8vBFXEXtU#&=mv6H5?iWKx2Q421}2f;}fp3Zj1sCkcJD>;&j=8l<0+&m9;N z@Wf!Bl0>*)j_=_UX(OFWu7JvN2Wa_m_r#FIx9QYrW( z!f}Po2IrA4IA3Ye#y9>1YGWcE#y@7RjOHe$m8w~c zd%UuMkm#?(u^lYij2yTisNDmYiD1}nT<`JDG_8ilb@FuV~4w)%(zt-GKbRKiw#&Kvt>K}_~XUFlw6j&m#7l5i| zHbfOequ&BK_t%$KDu3@2X?m~j*J*KYZ``@`7SjaMIz!U1h3>?)Li;+OS1@MJR{!z0jxaxh3k~Z?s1oel2{Kuk&G7qztFt9~#mDpqh z5_##�pufq?ve84>2thLiw|snRz`}Zqqj|gII>NCNB_7=ITtY{!8$X!(cBH#a##8 zDt^rdJ8@ld4*UEwBk&Ohi%hG_@s*i>jK(xx6M$LsI{Kh|GW8-M9}BSXIj_Bw2Af7z z+6Szys1Byz-T$%D5f~N4_=^N-@Lp86v;NP`O3io&WI_vLtDxWHGRsrFE8q$UGtBvf$Am;YjyRJh3k_P^Yikb zw?V6soGc3>@-j}TL{6h0d6-60IFZ4DA-QnZ5m0ad6toyl=`N?`*NLLQmOht@IkRM( z=E_X!juVh`2&%R*rE;Gur2B^KEeYl9*BKghEcG8!y!GopOgw^p{Z0~Y8q`eUhI*db zJSm`FpZ^*gm*MqA@_WMy$}61{V_&!Aa8|tT8P%fg5>1TPRfH}4w`x|=`&Y&;yTL~# zggh0*66m6cc^Ez`RO!AyNu}?+&JAY@|7Lkov^iw5NVmh)LCQN>MQ9%OMx@u4chbk-Z(kIbX#V5|MT6-{MRxbwH^LKI2 zE73)UlZTFQA>uZi`n(eFPh$L_tENfIT;9ny<@r(2|k@ni;QPSp=ym0Z#P0@e- zc<22vX?ePU-85IBjiotFqobnLs&^w-p*F>;lj?lup zlx4TPhkR;0Nu6S%qvS}&jET-z5;#U&f3Eqn7%xP!#=^}>jg=dC6>;7LQuECz@o~{g zSezxs?Q=nv?=lJ_K(Dys@a7v%cIG{tf^#cIImR1SkjO`h>{~?xSIoXnN*wOCMVzL=EY;sIekk1|=fSnu z*tq*fZQy>bG3DZ6Py;dx5t>&K@9EKWYOtekY1qgh{%Y<0w{9cQbWn!J4Sc+vFbsv&`? zlCG^2YN!C8d;hm5TRY%=NMEQ<4WI<~r>fz$2SqgPn{2zy#P9c+zgCiPaJn;&Crvzz zXnSbAw>~xzT5hquconG=99t=*v@ekKJnjR1C{^kCSxb=^g0R8SN=NB<=*_7RSrx3h zOg|N6HbBT>(OVFq#uPu1q@q=jBj)9%i)QgSBqu*r9~x+bJ%3Et=ZrLX>K4Ic2bTQ8 z`ouu$dzF}N`O|LS^;;r@5Tx84p?zL)&x<{$Js_)rq&|OxmK%hBjUJRN>2ltO32b#Pd*8wgR9AP%Z+IKs3dOO zxJ~f2yi)eAVW7v_NNv6T+$Z6@CQ-Ca9Uk>oN%CnGFXbq_?d)ci zz4gL4k{s@JP2a9&0~c~ik#ya~mg z|8e6EF)-DKTK7agAh?Z3FAq#0R?6ZZz}5w36BSREGW}fFwJn^8^eh*~3(cIv7pOir zr!V;PkB)Bl(W9AQxq2FETDqAm~Zf}l6(Sq?0|;5w_38D{wR z_=dC9bbH>S@)*_j#GB(;C!w)cLw1)ASbYAFqxnq((J{>BY0@te<1uGq*6F>#d>};=SFi#AGmk)R&If&=WAvw6w}GQ{B;(i5Bxl zIVyqb(aMNGgjsLyK-Vsp^`acP3EZ;2UosmL$*++hm9&~j<2)?!g#~zG&e7s1ZijfX ziIKv^;Uf92fdQ%VBXXB+=QM>z)iUnQmINv4Gkoe{*-Y8$i6SRNy-AB)4D{5FCGk2` zpv>OdmibVuLeDeN)3A;}1gW&1qvkd(;bbDOX+n!Wt=B3)a(gXbmW+7GD}0zybY6Kh zmMkH3@W~>o1BcaPY;`idkFWvRz5W1cA_-0ihi0k7g?E?03qu5P$0LjHVO;e)_Xl;z z`Xj^CXu3;e_rNhhu8ooyed2d*usp9t;)N=#tGSSaW`pZvO*)xJZr{06ZS41okLIaG z0yq!53x6heCp53XtY4-2`DZnCaHvsRDy<(_A2OeItwySqmN+^8lq#RkUMuPL0tFPO zY&;K7N2$g`A1S9>9zC01Ty8|t+GVH*mibd!^aqc7KIuW(bwe4@R?4ZCi_uFhlFJZo zgxiVgV7cm1{tVu7t`B0zB&bA(A7XBBz#U(}qFr=!8n~(qT~Xm)rQ6lnwO5!U+j3-| zhB(IC9N)sif%0MF-21qTI{2#vNcsuRgi* zua0bt`%ER{dE(Q>7J0q5D%VOpfvYc}KVR71n9!;*W*+lp(y8H4KwEc=isUs1AJ-aH zTpyI*r>a=eQb&ric(M%Mv!2x~2~5yU?hl0P^Stn7$7?6A0UWHzcnNaqq`fwR#{nDf zuFG)-n-XMwvhs(1{}a?8t@K^QXpx9bXqt2nV`ONwki*Nqgh^!LiATHl0o=9E4^hOX zSSh=zaqvP`>Zfk0`Pk$FvyefAfet~XdajmRRET2)B{k|$?+H3<6D}K0M)d}sA9aQr z)v3~%7;W}H{mAM;&RrPS=bwtbej8acppw^^Q%yOMrG=DHTFk?F6_Uebbc-tdIOA|6 z)$gw#&{#VxxAJx?j443P3Un)i}|nG^uW zCC+7-u-l2QC z*k2^hy~UbHjuv*A^h-Kex=(FzpVNw_`iU$<|Ls~ced9Aa&be%%8l?7umU4EjDltH)})q1t{9U|sPinn{k{>~lc(aAsKn1$&NA`1*p&amv38}+tI zn(XMbSYw5LN&t{U#re%BR|mV19ukBv&U2qaJ>I?w3%S`zwYxUXA#Hh*wdpjS>(3py zh@O5hslL%aagzP=MHiZ2Bky6ZVt1;}qE-iKm!+wN-g=Q*x99yDA5pjNeLNBxzg;sc zU;dX2M5(Cu9mntKTolixeXxI;AD zr1Q=@Zw3%n6qIKOaGx0+Atm}&1^rzuzoq8H>8p+0Ux`9y=-jqA#^2vSclpy`uQ}{p zPs>Fv!!rWJ^M=Ht8RGfOlm}@1_D7qWnu)@tjlzoO8JqEsT*f7ebn{mD_(*LUOzU@T z%fukMB`;pOXK0nGZ^6ZMkYfmWjXRd=)#Z2cYR+##hFGGx>i6psto9WZ34(!4w(Le= zlrv3r?nZsVtnrnI9Mhd?37fmV2z_e(`00U;MFGk2YaF*)7;^OH&4HDALfRuoQq=1xwNH;jN zw4`(lFw))448ynQ-ru?R9OvB6zx3z(&R%=%wbx$H^XzwTE?bGpKb{D&HhQ7tI@52! zN1bg+9@$Suck2l1gi@!0KjvOw7xjz3{hZFhjNgq;$1;)m+$e z@E-iV##2P2`pzlLZ@0IQy`!C@))Tnd*x^F8pLImeVP?a^n@msh-~vhx4-6I`IyMQVWw z)fcl(fJ&l;;}fEm5F930pf9*s;FP~>e}fC?TxwAOxU65dQj~sv*Tyy{u{_?tB;hz02h@LW=ZJ{J{VF?N1)!|850gCpr%F z#QGVYMcf&z9`&n--FZe`cghwi7h*{pwFzpX2?d$pzeMrBF=3P;`WL$uOfQ6CeEB15 z25w&|X6=q(gT^yNz&0Vz?{dHOmr(2%8@`3Z31Y=ZBICBJrt{)v$gon1;gb{dwOS^8PfIizE5B1}w%yn%-A$HclPa&JyM69ClEy`}5MPz&a$l_`{O&(ZB za{%fHx8tM2p4?DvPN?_;5zq5o5C6|WmUGAZ=5i$>C9e7U!}HhfFIYNg+h^Xwtz75* zChE~#@Y1oHOFB`6D<|^qgNfo=sg8sGz>X|bqH-_%X}!og%`r^Vw7057=xBRF<*1X6 z2BEpTd-gnxqQPdSY_sr3dBQb2cwM{0VzhSUXKE4V+JFKTD@Ce6C!FT7_QQRvMBYdxDh{d$P zm+kEZ6-IgxIy!NXq)(r+rYnz|ez8XI8r%`xcnvi@@2W9d$~Gk7RNf0$pTOf37IJB% zI_9bR*_=qc-spy^Sm_E!xbRu89mxsb9#AGY6s-6}jy)5tWzW;Y)Dn&bJL3vqG#8|QwT}k7=A?!Td{?#P+KMYJ?50*FCvBdID z!}JpPj@LRVDf%<-QKb9!@@W0GD*+cCB>3RiL9os)!T({1l=u#^=ykDQb@VOp0jODo zYlH`~L_)QikH6@Oe#spklZ8{RMb`TpGYuJYbnwlH2;TMQwxWc;az4T41Y!!wdsA18 z%xq6TyXU*SlDz+(IFRt$H$p~DvgJn?{ql&U>Vx;aJvtU)P0JwcMVVTUF(!o4OEf=1 zDz3Nb5!YMS)|=AsauIb?|4dlJ)@ev^^e(l?duH`~+w~pC_)9Kt{v=!oN0t z2$LOJD#p7ddeLAfwajqsSYvb4^VewzcY=X>mAtHcT!pPpX7BWl?ot=(*c$%wk;99$ z(LW)?qY?j+LL1|;ZgOl^Q2d$}dnPL={sUi9RnB;>NMZfcw_GX9YV6D*{ry#*hh;PAikyzc}^P!au;O5*dss1DRWP`_^d4nss+~)`% z{<&u%!Qcw$#PgH1EgLHS*Y1vOSK-`q+?6)6ha_+N#QijBiaB0cfBHPx4_Q{s=dnB6 zmQSv-@HU>P5y3Kgs8by3eq3!we9#vtQK%Y}ZbUfUR4QlpEc2EfcCpAL>(M|?x$b<^ zkd%!%r}px?QvH$ah)>{dg;1r#mXUJJ#=bGR-F8=(c9-?Zx`>5aQ!%kQTq(l&aPZV9 zMR#nQbtdWwsTZVn?T$|EX0hXW-#DvZ8RG zY28}UI!OP?)Zxm=>W%U;zSO5;0IPRv|9zc6r_pfI&dAwfHzD=u8$+B%QD#PFA6{u+ zUhFl*@8;@P(5tCdtyDC154sNy6|~$Mn0>~A4X(tqBPwZgHw>@4%O7-smj__eX-=57P=cSPGZg&~R*(Lc>gNMdm z#KqL-oC>Ms>{`~#I{jbjZ@=@gDhxafyN6r-dMs}}WAZ`y?Dn|m(%B*PLmrih4zL;X zx^VK?maXQQMS5`gDTVEJe)R%3a3U@;DBYR6Do4zOx?yB)3jUn!wu7F ziRuN;Z+Ap)aPodNuf18-+&$l(8*{5$jNMpzqqtOpBBHDiZ=NK2~_kaxHoGi-fi|1)#O!bLo8 zYk!5t*z^m+c^dZFAGH6PJ%6X-Htx9IH$_Va&F{Z1C;PjgR4vPcZ=C*@L*IBB+8bURnQz2ITbBYk5 zX*d4NxP~f6PYc4QDpH*zhhs@LpM!Z!+Pp*H99w)%pMA8jURJ8MDgz)-)Fu5Nm zsIbm&iKIUNTRjQ#gr66O*a>2BcDwu=lb}uVh~)(j-(<+9DKYi!mPX~(l5&U{++TNr}9HUiW2%-8BjuZaj9 zzwheO;W~V;XTi}uOw7~Q0qW0FxBZWT7`VYJ@zU&eLU7~U%~na#(G(=&T@oM<9vp+4 zz5n2_DdY(oG)=8O+PEd?v=C78-o+BlQGsh?pwN@)Xm!{T&+*F6EMGxcz4(I!_WuA+ z@$g?2!)hEYbN6R(IKw=5*1u6aU1Xg!LDE0wjR-v1tHI3-h6+Q-bPL`+9cWdjI!4^4 zq{v=SJ7H7!fmZSUgG!%mH=jL^w%*Kt4r-h=nHaN+3nLNUFN(yMhi?I`HY`LEvw$E( z7Z4op5I>SYshkEn{s{-8TK}m9Qe^nF2U&!#Bo2T&t$gJ#FdpiB0hZW{w6LsJ*RqoY zPLz*vGNq`IJ{-(V7QBo?!uPxWVt#0h^ApxRhgqeoqJ4hhRiIm1@=3|=TVM^_z!+z= z+oAzd&>1##(+>%NT5_6eB=ldr&R--VaLhKqr9MQ4scw%2*D?%t+R7!@6eOiIHD~Iw zmm3Wp)=AgT~FJ<%m?jzb&OfyNi(K@aa@bnnCiJZ0FQ^Z~eO z9iUJjZ%4_$@cjRt6n?_=z)C5;x0V3VMF3YV;jpD(BnL4c033S>YFqCRb+TYVf0nZ6 z2=)`7-$E^g*t`Uvt^NkQqNqU2(2Ty10P|J?`x@hU=6`?2S1gqn{HCLBa{wS&r~qIs zCyFV;@G>m~?S0RX{z+y^KzN+P@{fDy4K<>CQizW{-=sD#nnpOANXrTN-{ z#n8^efd5f>LczWbtklyf;-=&>j+Z!qt@D^!{9h;*HQN7iN0zih=P=Ft<3KLp z*U1n22nrn(K{y|8P*7mJ=b$Y%)B;b(#|jEtlFRd1Z|B|Dfg}>MdGH4*jP^^T*X@2z|i^!e6Y zFZ9aHM$idAwcP2vZQchVYco;OtZ`jqo!^#hbZVNrxhU_MSFd2-Zm^f@N7RA09RY`p z4K!bOJ(-ksqQQ%jN_YI?r$KE_>7$?-akta;0BwGWBgF9*iS3s4SoiqwoT-jgsK(fg z|641ek;t&HkOviRTMHg&Ws#cC3TR+HcN~S-t~tMeaOSiiTm;6|?cLO-zP1X{$u-2q zeq`2t=ve1CJRf{NsiqQY&$04$F`bT~KY>M)<<;@g4N`(rTUVz7ZB7S--zCw-kE#$F zW#`_|z`ks`p1EXbB`)_PwsXcgTP^#GKRolYva^4X6^+lWug&mnsXhSwH4_N3GB+b`^3u4cL;Yn6uPZK3~v(N}Aa zM@9D&Ax-?sO#ZBLFEqQH3g^|zYFfLTH>6t=soc33O?@}1#_C7K!n*5Skq16}ulFnv zq+#Z~a)w9Wvo%f?29zUZ*bSi0ijI*tOS_%`xXHdSFkUKaB@;Rt5_ZgY8&K!y6GT*V ztH;d_0uoW)jZ{P#){y-((m(o_Dr>3Ym=Dj8y&rqECnEn;sx!Qv!#=iP@q5L3GyAL2 zEyNd0&o)j2E&_j1a9x9M{lm_g`Yg~mHCNYGS?ITe$ZaP&Go*9`zUS?PI9#C>O z=jvxLyy6k!^<6c{0432TzCRwg<4v+d)o{;@3Lt%>_nWn&Ob3mQW)4w=e5C|wq}m! zVxeqrM%&A>JZ*7)hQLK%P7wC0=w%BY_ zARn_VzQCRG`NI6=g>-UUnwWJ@#kD*kI9l8em@Gljyr#L>gC0c-#B4^;2q;OrK@&^G zGoq|4Eq~;XIfQ=XvwQv$8p^lbYR-)(kkFHCRR6O5gi&07Dk}T6>jgtPN!sZJtVlmV zw}Oh3xdjeN-?Wn}Gn2_a3e%H(;NEz;^tlRmwqw_g(dE*b*J@R&L5;*;IGzjx3X8^o zC+9jO|M9R_32eJr)OG+s*ZSHj5?eL|EIg5?V;knzLO;}>QJWLCp6zJPs*t+Bj0N=a z$l)6hZdftbFK4^y-O1)S-TvG@{~i8vCI-%m1pJt&#V&~~yuv_Gs)+ZeV}wc+`Q>I~ zm4xL$_pd_1HtU)?d9cyCijmqN`RUZ$p(lK2rCX?aU0KA|q!pFJrUL~ULre7sZx4?S zD4UQt6#dERjo59lP9a5*#mS8^k_676 zPwFrLVG;h-Z}yLyQmvjr65n|3C>mcJ&OvW-tU<&0nq}cf|EfQxK|etKW#)2hdGW|k z&Am&l*|6`Qq=lx_mE&J2%^*hx2IT8Wj-2FQd3)~)E(Fu$SY(@M=-u!Eh6_R3AH%Zuzwn{7M5Y0~S5xn`Td=a4-pOlZc^&Lr={b@;NuHR_ zIq$e^@T1b_9&*v^pX#)Lj;tGTFG$pRZlt4k=>TRjVP+j-nFBRVyf<>lX7|k&PF~Vh z>Qb-SmC)k6HhMfb?9TQ!)s~OI4eFE$A6!Ve1Gd|eAvRtc8xMRHDMRuJ5FnEcH4t5uZXK*OJwo5($dm8Ps#gr^za*$iez{*B#SQK zybk|iH6`!MFye3u;+K|`cyPb$?5ssI9QOmNY)rT~o`-2{KI_t~2#NGT{uFbwOiFq4 zZ1iQTooWQ`({24yz{2QG=4}k|p*GC6ZMLU$|10XG*-LRU*!~C zjDCVnK>>|x8;@hU(PMN1#1r6l)^ z73%46>=}Fux!s8;`U8|22D}yjunsV%c!^Sy%`=sMUS>2Wp{$HWv# zHA_NGX_OlMslWyh+H){0e}68IA4xTcXnoN2R4q;S>Ad?9V5jG8CMG6Ja&C51Ri1I7 zlxSoknHp5*@bZX&=|Z&fNpd0>@{wuhNpBS~I?>n0MYTaY365yx@b95b$wufSTKZN( z(KEIk+bcVetp&bEYGZu!+SJaeObgd_AeN;^F;`6_t=_qh92sY5!W7NKPSPZ0Thg-d zE`}^DiFh1<#KFI8y-MNt{<4aR&V2sI7sepkXnt!LNS_1P)oEGhQaFD3uX)68avDtU zXo5Xvb4JEa+}tVA*>cf=9(9TC0aZ987Ff9wyFHU~%l!5q0vfM)KR%REuqMg+2Ry?6I6L zQ@66P-x?Zh&mW5C6JU!<0w1LamB4toGl%V_=5k-{&gCY$2LYR`u}%&7%xac#A^1lR z%E2L_zwy3GsbC-3T+>J zvnW-!6aEjl5eElM@*y9k7o;~|qGRDyS&TKVp@eVbOx<}4PzUx*iQE{@HK}cyejF&T zqcf>EG4tpy8i^Y|6{AzOF6SK*kU2q+mQeg_Tf*P^vzI2O<~8KiVE+WV>H_w(ns&t*n!OtL0};*??NIYir!pT(l`Wg?k80y!=LJxyM&j>5$x zIBanOL=`L<2clj2!b>TLflVi$eD&x>?aaR*#&RZ!P(BJDwlRW3%=k(`LZdfl9kN&1 z7)$Fh=%6&#?6JywpS&X{HnvrvX1Fl)xf~uw7x!wKvY7)LGT5C9#OXN_$CkU0gkoac zmjgT&e&p)tsOEvW{G{5*7Bu_rADYd)Vk=qCmd`OlasPu%1rOz0uqjI{l`u-Ca#Sl> zrazCH0tf`L7XFx7h=Y(iMo*FcgZpb9>@cZIepBR8GDvH=O4mFgqW>W(P;$HxVyp}o zr?)H|z+tBb+aMIhSZ`GEec(ut$!;#DKlH(Yj5vNK#fW8ETHG)Nlm=^@z%w+f;w6uj zD{fyLop_{2cOw6z=UYHy;=pGPjMpscK+RG?LwYMPrTy6@^aOY=#;PnVA8)BhY_Jm_ zHGu`jpH0#ebNnr^0>v}D5z<|d0LmtH-haC#0w1T*?sIf>CAna1TtjEq%Ya60<#~#K zdYdll1CXi@V`c6i{`oR4PNRAAp=xD-# z?#k%&ztjaVF7p|m1BxQN(s$^;?NQ$N4mM)ac4Ol~=b%Mup6>3BmL~B+(#N!5rV0`ig>DI>8!Y#^VB;dm31-1_lE$T4MJK>FE9a!k!Z_&>xi?PcMzcekZCd8Dn_ z0@bXF25zH6^4_gLdIS2QqlAX&Pi0l{jEg+DvvvyjL!ubHrlrN1ijXe?>)&+NEf&te zc?sHdd+boH-1wspCy3~#$;xaN!`G*PIh9Sa$LRSbtf#-uhy!y|=?f#&GQKiQUFG}Z z3fL|4)%Q)e<_Y9TPbS7nzk)kPa-p3S7vlIVZGYlCB-zY8T_DM-F1NC=;i$CI^cS89>)Yzn> Date: Fri, 11 Apr 2025 08:42:22 +0200 Subject: [PATCH 010/128] changed image in readme to white background --- motion_primitives_forward_controller/README.md | 2 +- ...on_primitives_ur_whiteBackground.drawio.png | Bin 0 -> 441153 bytes 2 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 28f64f47b0..cb96e85a9a 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -22,7 +22,7 @@ This project provides an interface for sending motion primitives to an industria The following diagram shows the architecture for a UR robot. For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) is used. -![UR Robot Architecture](doc/ros2_control_motion_primitives_ur.drawio.png) +![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png) 1. **Command Reception** diff --git a/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png b/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png new file mode 100644 index 0000000000000000000000000000000000000000..6b731fbcff7acafd0a24c722fa919ebf7fc253a7 GIT binary patch literal 441153 zcmeFZ$*%Lzwl1^<0--D27ofkTOXFmsh}xI>!;kA!#z`aAjC=?hWd}x^>^R2{gvQwg8m!!-@y?jOFlhZ<$~cDY&h(at0~KS_?rB4*6*#iY?`aS z`yJhd`rGAiINbK~S3>$L#=)1+MhJg~41aV{oBf__!KnWUu8SU^N`Lol&sU23BF|`T zR3FoO45|P4Z?E?EYqp0nMML@M)2x9@q{r_i7?S+GX8Qfz@lOo#yQ7%?ew#mcMLS;A z`DZ-8&$M1JboMQ)it_JwhV}V>!O{JD(Me*eAv&#r%5v)@_%`&>_b54Zb=CH=?4e?O@`gseeJ@%L%|a~}|x|L5QR z=gFG>S+xJ(T(15nuGwq%I-W7*Es^IZdjC)O^^at1QM3M;eG>#a`gw|IO3G@16<((d z9%}06%YTG5U#1>C<3GVq+b>A;VNIs0t(Iy7vAJM*Kkd+v)dHMcb2$t-C3FphDZD4_r2G4NgPbTzDKf#`^?_j_@Sc>M~ z?24MIKF}G67=Xh=o0Mv5uXeR5U4Hx&k}@_6&PV|S(K zIrwM1+){E2`1D49N|L~Z=!5c7?mv5YCFLDg;y7Kg1bE(~x=oDlG; zA3WgGjQ-Z8UES#wSc0> zdg{8B)+FcSs9gIBd0xX_PxT{kL-o{}${8< z6Wc}v*+%tOnyyNruvJ+o?SABM3F%xp-tOJI%+o!wHrBa~>Qhwci60&j%hH;Ql-hx7;~dfyaXj z1RgKEICvDe(Vbi2fb{#^j?2G%bO8QTgmnb5@~A}n8)yWB-1BBKf>{q?Lu1g7iRNd zm^596FP(&xOcQbO%a{I)O7~vwpl3N>Rd+$n>aY2Br2B-2dTlBNrfeJ|Vv_CO`Df9u zLK%iXdeREHy>D>2qb8UH$65GjdHX8wPreWYH<;GuMdm^zzI-?o?w?o2U8i+FGmW}I z+{;@$ZrJWQT-l1b@wP2;)$`FwDx7^&!@de9DKz-r5V^N_NtnqMh1@mp<2VSptXUaJ z@Pp*dftE4K(;3o(Z^Csodz87lGHqH8OF5cKuu5eEKa1R#!c&`#W=>ylF7v6J5)I^5 z!~g2~`*m)S)bh4lH`qryIKg|i+Hkm1ggj~MeDrk2>_}HUO8D>XE$SMaS69>Vf2LZyq#(J4B8Hl;@)J+ft|hbgI@!+b~Flw z``^n%Fztq4_EP)I;%OPt;$KtDoN-F&%v6W#d-AEgPbX1C#&R47d$`ZYV+Nn+6EF{w zJh`N>2bnLb@JzB*m>fk0+|?}i2i4gW$k%PcDY*F!^D7B_Ki^5i=MrCUcQUbPCbM@# zd@1pXWvl}j9pI9H? z+sEqS@4h}HFmyiHvy1=r17|%i;ek_ZSaHlz- z*=&7&O?!Wc5B~F*2{QB6OZ<>KaPIQw(t7A zb&M`C>12&Hip}c&ZahcBe)6_RtJwPt%~a74EmM z^WtuBN)4L!(3*!#5Gy&WG);fSG5QS17^%E{FS5sVDU{-U&9eL1)UT@|JiD96YdlR) zpBp^1Ok)FiGv1TD5>Brcg@F4tz7cfu`M&QE%gQwT97j2$8#-2ZBDK5uBd$F7TEZgZ zc7bF=en!0AIm5yAp1|$Czy%}QaXy$OnDDLnNU)AM4DezFQ-ds}oCY2ai+qGz(Bo!3 z)6{+)zhttZd>xjPxW#dt9Tu@QjhFAI57v+Wd~wV>@4b8r>e@-FmLbfRQ{L1ik1opu zQpZnp*AYzi_3hWs)i4Nlc&3yYQh4M=;#GTg6U#$-@ZIh6g?LFS+QbTGA4&b{?dI)~ z9lN9l0nbTZM|uz)L;>&4lU&T@C&@DVnZppbdvMJ?%6%2Cs`gcZln6<|!>c4eI@`C` zAS;ad-%#2 z$y;wo-q+K@9+=Vw)}{FtZ$doDnXswA#&a*Z-X5`Gps9Yu1Ti7EQYYj|64;xyG+tN9 zK)t3}?>;|oMN%6nv7FwG94C72aBg0H1y$f&VU|H`g$@5MvtIbYq4_Kx&9B=dFKMtG z6`Cc40 zV#_C%+-_Z6aL&2!+=DADf<}WkNs^?+bHM0pE?+}k4lh=M_vgW%cSWo0b`GXX#JiW& znX}b)sQh3-t%+L@1UV0L0Xdee5d_iATfWue4ZCjuOI`S51?Tq}emo-l31gOI|sQ`MDnd zdYYYB@FVL}y*7V%53*gb-=K!*ZYZFq2rfAYN+@QZh>bcl0Tp4yxs@a z)Iw2Eu~dE@-7p$zZKp}u0%*Y3Bh~613XmAOTeBw^H9jrDPqvMDj<%n68p5^EjoRiS zHc5pdr&R1yYx4&OQzksp?7QsX4;)Ve$8!>}geHuZ7wMyN8SakEpHx0keVf0UVbL;X0I*Lf_W4-=680QSJ@1_;fUr3kVty z!Bc~u-_)s%R(*Tro$xP(IfOpg5hc#EtXh@wn*78ywfjDg6w`To702($5fDS6h!eJ? zZj#nJ#r&aVfly)%th&TiAD7z|$sQY9x0vg>UcSX8HY%1Q6 z*mvHsFUt_&w5#)+szQ+Ycz@T_sZ8hVh*28Jc4#?MF47kHd5u_dzM{$9TlWlS|8WCz zDPjftd@KAJ=jTK zw!c(Ru+4mc9YXOhjqH&xdXouRYeu7hW}B|_H8JCd5;|h|gb6@aF>}r=dcN-d>-2s5 ztDv7e&XKPHD-&shIRFF!fr-GWSZ0Pd?JGeX&30NI6uu6LB?zqobMd;vO^`M*(h=!H zG*ayC5Q8m*Kzu@C2}2;%x2Vnjw16gi5Uv8G$CE^6J3@TW)3(iJ%Vo8i-X{Y~yVzW- z@_SQLSRJteUrAU3BQ$dPh-omCpS{Hn&oRf_e7%NoJacKvej)hNo_NCUH#PC@cCCK@)HMphkJa{kR@W{(4Ena;*MhY1N<*EbSZMmq0B(-OrStVNZX>#|%pOhLXo z%qY3I27H6t^;q7%N6_vY=er+>8hy+!+&4odd+vZivMA#=vOgirA%oN7d1Pr%ecK(2 z!M@~@#zLJn;gO|d} zW50$*t-dN-k{SS}Ic~6t?U~f%<6Bc%Gjw8e4&#usaYi-s&MHSbo zugWTHwaV+G;5GV!H*WGzF2{|sQj^)_MLJRl*jV}6NY{RNuaF>|HYMqb+$;dl%D8sGnkLz&}QAXWYY2P5tbCfuTGYw+{AsWwIj^ z3l(O98+1)m?uTOPhY7!Z`E$8$7J0SupGbh}=yiN&HA0SNh-)Y6Z9Ktdbfd&BUQwRd zTX}xM-E_Kl^MJvp+wFtm_4SP&rFcWsis3w5AFQG|z*uibrbJCkfoWMG(}5s9xx*;* z#8A$-7=~pX`$rV>y3s#I;oOfr8R=KjgVPdWI3cdGItie$ln&g%NDq`vPHQ2`s?IyMUAH z)*E044+)}Wn%7e4u`i4#IG%DR4!F=zo4iM2=#s&cfRN@^?+_#BatLlJfG@%JM>%B3 zKS;GNI-$B+)6jF+r?ypf3l5hb2F_!mw!e?wYrH0GjPg`#qmTMDv|0h^np0u*LmLFP z4ZN?4E$ghCFBr-1MvCg7Tw`9v5`b{-;Qb6mM|N)WyqWPNH~Q*pvAT|)e*jNFc~e$j zj6UMZTU{PJfPn%eixNUjP&OR`GN?ZI;$ey~KX9ETTdm`#yv+*t)avl~?(O|rjq_MM zN-r5_8P6x}t>)u-dETEkxoL7lNSvaO1lX0rzY-bM<_7(PgRo?5wBI4?wWz1-53+vU zHHc^(n+7Y;KQGxdX;Qx3KJpg-K4NvR8GtE*HeR}v@Nn;T?ZUU^DjyxESw<@!y4W?> zyQ)c_D>4f(k0^r5Yy3i|>+R<`WEsMyTap8g1@VA{A}1eEjuE1#7_z!zRiA>2*6j`U z1ub5RE^)vRkbR@jQVI|`j+ZbK5OAX34f)b@$9cP^5Y;f}F)dRXLk?IPa<5w^eFto0 zQlDJv2h~-3C@#dJHXQH7#EJ&GlWgkta6V*}(JS4DaLw1jNx5}*ItHz8p05Rj1N>+8 zbJPEl^BlyzYoQslR*iyH5L1{uCb?Ae5!-fbDe@2jI1RWj#G_mPF};-3nYnlQ#)VcwmUbMZoFc+(NV zmy|k&l2CDH|IFKFzdDTisCQw!YIkbnWX%$ z=$CKBj;LUzKieV{lmN$zI(~#uFBrY%fTKC(FB77QS^T1f8 z_;ZQ{W*9GwvosXQ!1lDhW`0%_;OgJP4RtT_^KNvv%=wNYK96jcTQ~X9Z_R5F*>P|- zZAY-2Crq-gT&$b3Do70IZ*vr(BJp`}FkGk{vxuZ0ig2cen@8B#w&!2R&kzc9bAlk@ zk%BKrtTkWyS2g9Jzuq{C`5hNcW9EjR^2)j%Z^v>tP)N#q>GSde+-}P*`!;u)g%IkL z7|S^K*~T8CDVQiCCqwyxV_Dwa$w2ecm{6suYKACikzg8E%c#iYlBTV_8AVZn(ZCgs zw6s!-d>Ns6{nx1dTXzmbxCW2zm}4arqd1JMcVh}=uMCN2E0PRoI1I7n-{3V%8qlnt zb+(ZqU^p|e0P{+xmAywKZ9Nz;P*i6Q`4GYEGhptR z!tY6J)lp&S>sQgH;jPGzi<{x(YrXCGEjZSj=i#gjes;Ocnwhn;QtXmn?JoLJ3Q8Kh zxwud8sGco-ZX6AalZ!yW8Oq3Xv520IKD?Ywl3Vi%PR~ zG|TW?k3+Dw09)1=WR^$Jse|yqIGEVJ`7m=81*EK&inPNxdtCZ_u1v7H+YPm%o*jau49CBQv!dNWR5CjCAJnW?7^=tr{}t>e(#Xl zfX#!S(A+Qc8Z5N=l~7*sg=+=^vj#dsHbXs+Rrm8M`v}m!O>RxDi+#w}3b0PxBZ4`X z?dkqVJqZ)IBa=X7r38vV%MFIaLj1v#aEeuaf8;b=e$ZYC^1$F}1u_rw=+`2Yi+eqV zG6j;0O|byiIHXs{A$uPPWS|==R{^j*^?)CNuYd|ZdmK;3IKdQW+0V6M*o&E~L#_wU z$d@#KLU{QwjBd(qG0Mdjif+j3)pkEp-%`M3LB=3ZNcYWiE(%ubOMYVJ;?)l*wac0c zwKY)(4SHX~4@C1}(K7gt`I~TG_eME@m`aYepu;t34t^r)%Df@lXrhSd%7XVfOZ4Ei z4Us|=cClv;S0kIQX*7B7{#y{$So8(x>#2F&UFXAB0>vgsiwa{{ka%ndnm^O-EJg-Q z?xLjG=HnhwlV@cPxqWG=ONl_Iv;TqM?kGTp?RtQX6^3kHnU%G{T=H#kC2utku>>psza8zHJ=6^y_KkGDE=b1py@M zp9uuX)t$lK{8Z2URGX*e0)Bm zd&DT;ce0=_SzAH+J}CI|Tw^^ZT|EG*sP>S9BA%h*-=Z9v2|nkqjNdhv|d zXx^dD6Un~eUm+fn_V(dONAY$i52svgSs;;@?|uSn?kuogGXNSHUZ~$1A6ZDKao=YH zY=yKh2I$`_cRDRjnq4mwOtV~I*+@bVAzS(kvqrjrki|aUAU$m-Z^VUvs9^cJETCG~ zEtv38Ip^aM)lsxkEcZaUbx&W|Tebz$o}em(^#W-@*MV(CK}j&Yq0q4&}|K zbFmTfoQhKlrKp@hQfi@$Cwzp5`xM^@gG1kcqS-3!pZh)Qo5fttbui=?=0NJDTIDrU z007AJ;AP@|aUm{O9I&MD06UgIV6OaR=ef8)kftnzJqN@Gr4KT1q-j#Hw*g!OhKE-oH6P^ch#{5W4ft>bPJ%6Xr{p*7 z)JNB(eyuW!Zp{FUpt>KN^8m}xOHj=##G>L0D!n%Xp|SFgEc5TySq~??q)^aXS>^)# z2Z5>&KA!I9MJqyxoFi|Xy%@$Kvj)PL)?t+lQ_AjO#+WOOrTWY5ydT|hTI)$$9rsoc zB3E2ZkpUD=MB13czmx~5hly<6pE%i{AjY?OS56PGYDRAuF_VWV*w>#umUnNNefr@i z;hB#Gzyclu&{mazn9G^7XCS6)3gV#xcCYfgiKcMF)e_1OgQcAU$GVTmb;ca3lgkzY zASLO`g${M#RuMC6HZ6)Cu36i4*Vq6!=lc=jVw?xgR3SG52nZrkO6TOyRD30Xwfct` zUdlGh^XEHiK!z<_n!bN%@-Y zlnixFDE+)eizFLLKco&}O4$0rP?U-4vW#_}CuM~C{k|a-Sx$)*59ij_)@h}uv%Fjc z&=im)-d(`_oo@GZN96Bim%ny>p3_(|HlbPwG9*(COh`@vQ@Y%^Ju!D>zj(CAVNijvcnVu$|47IHT>{tu zXpk_gEDOv!`QA*qWo`5Pl$C@%N!}PXnOgkmlF^Ji@^qjuT$Z(n9?OSwaQON&t(UYu zzhA+CI)f_56M^F+XbX>B_Djf^ikMb=Xj^orJvs;W>%ilBT=TrgL_qfnvm2riOcVG6 zj-&y{v>BHh)p$x`WDuD9wGra!Z3mQZKfRGmD!|~Vpjn2`3jW2W zY8Q$_J;K%bXaGM_2t7pYsGx$d_trC-*16l?q|p#+&DSs#RrI2d2dlLCK*kY~?S(qz z=Dm8)gRCw{Bc~m{NonNMk%1d0Zu|8ieWk)9QNCV6%=PZ7B(KwSYxMe+Woth;5^3I- z<|Yxc$GQU2v2q$tf2=&x!X?wglbc{)-Y_}7FaT!ZInki6KZTj_tIX-~x_d8$XY!7< zzTRj(jR!tcwTU#_{#Foo8bb{8FBC2$g8;vQ9I)AEljmXcu1mVoiSV|x)R5Ch;Z2hl z>J{S)_NZ_Ox%v@1v@$;!H#y~ILKBQ^<(umKpt*n^bR$K1tdkNU0r}T#vg~o5n7`e9 zLIG|7d|RFEz@{WS-=eeocJC)?9G>mk^=d*`;uJ{t=Ix6aZv2W$+#e305&*pl>T8H4 z1F=Q4R7V214S?D+ecuP^@fo(z6T%eYU&9+84wA}xf;8EVwn%Cf0#M+yolm$Mae>%) zJnyDDza12RU!cb!PRP4$uTD|Df)$LlB%{=YfA7jh~L- zlN=tgbRL;C3=p;Q3UbFAJH4TN?|rXhaaWOWL+xHc2@yJ&`A9oHP;j+Ym#BDg9o?Z?V?s6D`3j?4gKMHY zm%3duxg^&*6m-bNlirQV*>D#!U5WSNK%~R^VII>2?kyG*_NWxY6SQ~z4E7cfRrN}C z%egG3Z~`%mq5#L)M9O~aOm}Zy+Y?En=ZQ9Wa=>PFz*wL7mY;^ujX__634Qi63toEu zQVN>ok6U2FGy7(_(FQ2SV_6p?+OIx*%4J>ex3PVeFJi>Imw>&hOl%sQ^;u|e5wwYR zZ+*^O%}EE6ZxbZoA0-vC3K+6CwALDuXV~7WsZ(Rum~aws=W^I|zBkLM4H-VYfa{Up z9R0ozp_U=GyzKDpEd8MEP<8WUGp2yfMFe2!`2e@baiG3e3TEqo(xW!47nr7IfXpno zPIB{wT#d(tF9f(U(83^+iv)?za`glIVITZ2KPPv4pqT6Yn%?*AQupOePAI4m) z$^bTR32-HFlHKQbr(k?{lUbT32&EnrPOl-t0&=4_#+T1&fpE(Piq_?yz*)vKe|nBj zy#uR>ZU|chc_;jGGiC9(&-jYc^aK@*+a_%VLglumO^Hw`&+FZL?zde!?0^2&j9gH`p!Y}i2I2cpp%MorIT>PU2 z?+92NgGKc3sN`Vk*?b)58aON?SnYKg?{i)!h(GALxbah+fxNDj2ldm(s8kTw6>z3b zfvu;W@a-*xLC;Gw17b-!Cru8T#-5_NehdEP?98WOX1q*2H+EUxS^yB+f2xkrTdCAoz`!ZdLDBggb4BZwM}XrrR+e5{4r`TdiJ<5Yfgm;7#_FDyDG{{GCt- zt7gezal0kS9zV7FXKXMOEFoY58SLBdZ+@F76`)PTVSbR*YusbKdePr|Q0a%Kb;vcsYyfJ@6 z!72rje>lsJJ*VrDE9!;1wb^vGOUy*(grlj*AQ~-5Gff5Np}8lid%VMCbL`*A$=ns}Z&Bn5+K z1Vjl@tv}r@8E2W<@8!t$jWCb^T${PoE))I5&hzoE`>tPc{d1|Bal`PvfY{l-i*`2z z=@=D*2vEO~v$+rG7?9kzsV^Ca@kPC<2=KU`r(pRz)+6fG2%wISpDGuf^sRjl-0ATF z1}@6-P^8jA#y~-YJsQENxGxVyl7P1=5CI`U1ZrUDJfJ5b6z}hG25sf@trMa-n%mCQSnpjDGCe*UoJrzBg~ z#mI0>fC#a8Hn$#s2b2nD7O6&n57>z`!Pc~`WQWI^#{-ha#GEd z$KZRA7Yv*WJwp;$l*jj70=q-`?U>Mup)n}ncmj*!(=iCMLTrJa{+$hIS$aIdR{=jN z0`UtVq>6YHwLhA-K7=F90#eJ_8OngiZl)hp~Ar$Brp!X>*`8~ z0%A^tADibI%nW7ORyQ4xF$20pUNjNXKU^u=T%PwG7$@EKZ1IoTKV)HI6B?Mv-ycL^ z@s`!qO}j=R)<;DQ=ja$enlcS#fyKY|)#y9qcwidrdcKRVajQQ9Fc3mnh>=T?p>r%? z7T`}=!1+~{$p-ceeH($LbXQTN+4j`(iTmsB+^vx!$#P0k_-FV@Zd<_v>DjFe9i&2! zKup4W3sNM@jgxGWQj|a=7NhX})nzViugj$c=GoF-$xqY!z@Vu<__!mcH_ECRi{CM( zpBmKzzQLuOD0VAn$#;X^x``Es{4H$E{FR`Z2CT|FM%+eOLP7(Zx}ho?MDpWs*WxKx z*C1YgQ1}$YscA3H_l7Fns80a##}Ow|g70ze6BwVm1#+rIm7_82L*#9i_Gg)VvN6EL z=(e|4Yu<(2QsUT4L5R4I^YnBu0g#apcT zidCTywSfz3z+K%3RD1bOS_4eD9U?oAI8s1@Xx+Gl?T7i{IvytIgnYs}$YzwMVp1}9 z#_!4`wPi`)G{W?*BgCl#&>b%yj&@LQgtC)~AupU%!gGA?)p`$?PI$`C80csYyTX&M z%PKtpRR5^V4a#ynwbDy>dz~&=4LN`;iOGL3ls<;y#p>(H19GCT2=zj?u?gk0eUhoJ zGVZQCLZRjHk_S*10x;&vQW~7TGS4|n=_;EU^FUEXMPaqs64pr{P z9uIeL4S`n*7dmkgrv~VO&Fk>7booX!pSOFx2>((iCEwqR0r1O+T1!!n1G2q4rSq$!_IdDLqAwq0RB;}CdqWVX}UZP8cGqc=o zV*$MfZwTXp+qNu$drVgm+yGNQuXJIcwI%CRr&sBFy#tC&gH4a0Pk%j4R*{FuANc$5 zu5Z=VFOsBdzCd|699g+y5t8l3|u%?s9k z!6TeKZd2Oc_UTLIpw6$R81 zhX$R6VW)lP`w3UW{Eu6Gz@ zXVHTYK9bF-03F<|83L(HWT+g9m?z1QWp*n<)KSx(={9x!0km8kwMtN91WCXbd9RsH97rFy^;xchIxaj?(j4jVuq-6@%YE_>K62?=cLgN_Hp$ zUr7V?@Blr=p*9_zVIGWlT49lAcu`>*cjUN#HaU-D)JcM9Sj7XXRPqul1mt5C_{S1D z3Aj7I|8UhR@es8ToD%2TnfNs!P7$-#$2Vwq4CxKBduR}YYkFf?ihc_XL@-|_TDLcC zynfhWGxYTK40toX`&L_wrHDzlT3y@jiaY2}jhgzWtS&OjF}-yxbPl*I(bugJ|2vN= zj9IP-y?f6ReftWV1j#H^#-aWw#9m~**5-%R1vkj!8epYuB34Y)?BLTP?Sf4~SjX>H zP5SmJhXr^$h>3hne{!qZ<~;FIhi4R1xSol&EnIY?6M_67LC>fyM9!YnssKw+KAKOl zSi@6cH~o05nzFo6zY*#?LbP1q@3(r)iN(VzcLRVX_V&Vh4XO+z#Np$&xX!Y~AX7*~ z-8Np1@Ar%0!YlSK+gi}3Nwh)ZyT{*W+0k>uO5Mvlgz9C(8Ch7{C+FvSLM+9ZF63-1SzM z`JoMcl5Qw+A>u!Tz(YeE2$W~3XD)@cbeV8%k?zo!_QgU`(Xf<%QrnZftOpK1SaN)U z9rKk!QM$i0D^9+Aa{2aPi5CFG8Xv;X%l!vVHBMo>8@GkZYA9~clbOcKJH#&@7e2GH z1KO$X@nSBPkY6z@2Mp>bUt4ETtC5siKpb-+)#9Pfj*XHn0WoUFG0~00lw=_H`ar@I zL08zu$8E6SM-~FQNF)v;J;uj3s@IRD<&l07O+lc;v9DJL9t#D47+EC zcH;toF1!TP;e@KSBdU3r;P=}p>bwXvMltG7qT{Xoa8#x%nD-0%hiBG;j&VsHq<3zk z`x%Bl7?87xC{BGW5=^5wj1e>yo>wLW`wl0m5XM4xFdRYMob0V0MwZIbJkk^p|v;Da+1Uk-qJ-!p&!-t8Xa0X~YrV=q8_-9P}xA*qKK|2WeH+ALfK~ z2zptM$$;+mFEDh$cCf-}@UlyiM6S3?{vyp-yX73)tvi<*v?vR)q$< zD&-EbJ6uS(2HgDZc@kNjtdv-kNBvaE;ny0o1JqGpPGr2kQuGwOi9J?>dhp+Ca=Y7R z`Fvk}aLh$s8@L zGa>y`V$A+-(4CrPY58&a8v%W@`T1>VRszgSxDSEQ*52gb1XhO5@?yr@@d8CLs6iZ2 zgA$)t1;mn@h*R<%d5Lm}UY+i)8I?khki6vpJ+nVPwrS*`z$f6Q0Jl5P<@0s{P`?uQ zP=NJq(yW>Z#>iw!PKDmc@%s&&ySzl{xUsK86}H{@1uZg7xzk4NPDuM(X!r*zPOy&TxZ zER*K*8T^0*mj%mv z$Js*%{4Jxw2b2%Js79`*>1MuHH1;B(%l<-qKFoG=Qyi#|a#ZW`VGuNV@CA2OQGcHZ z1n2o#Gx>4W+qMJ66K|i^%nOij8tMj&vBM^#4q|E!c{-F$adU(N=@L07ONGvx`6f%V zT!ZHc<*UV!yu?FB3KJt=R<;u!TF%{Yo`P2*tOn$nq600Z7wOWXHxSg&SQp?=J<7QME z#!tRUuuv1@d30&$ti3l54kXb2I>Gl3c}SW_yn7=Ljqf@z7Ao$!BOiy?0pYsf=W^&A z`RPH}9szMVdK7IBKub5NU47^J4o@cSSJt%hVo&22a8;(T0syTXaw%PPTV(D}I(g^; zC_KRG5+eumRC~Ftu?y67;ngS*OSKTFe?iuz@~3-cM4cQYcCpjF0efLSVE}kNWk4Z} z2H+6xROi5i^9n$yB`R_jfMpcD3sNmh?n8t@$q+0-7r{vbIwt?{How7IM;OP4cixRG zIy>j*4b7o-qPXSAV%F!|p3dpuT_0iZCDerd5cr=5_Z!~>Yi2y6#U8lSeV2oN#Lm$` z%7h#{&0e72!#LLs-Y261&Z=i0L_p+C02;v=#egKvQ~#;_?+YpT&#HCzYq^AL1p0G4E`yohVG z<&Bm}$I?nQcGX{mf}5MO@=m%}S9TdDH7albupqDFO+ge-?s(Wxo2}<w zJCOPjBh!I*oBVdm%OdpHKNP8M<7&5M$g>Jmt-*{fHZMl$QJaUxmRZm>$#!mD0~HCb zNn8n(gYw850Rs#Nmh~vsBavUOKy3&<@OGFamJaTT`U+8`^X6ifnk67-pJ>G;|=cmoC{Q~rlQRmz^kwkN>0T;?Qe zV0bvq1dmJEr7L77;rCIC;$5SOEAm# z0vP`8#3M)zdV17sz_b1D*eqQA8ZYp?|8X9owRz}@vh`%@Y(T!8>0^Ip;Wm&6|?w4y6 z%<&TMZ@@)xZSd4kc{cnDn{~fg05yS<`D~{nBpw@NPr#G-%8Nb%&k;!aEW9dZlOX0x zT1O*p(9hKP#n|8AO);sUdO{`HRYN(RyR~E2E;zd$Z^*}>Yw-CfzjFp=kGG(j4E2&Z zT^AJLiXthscg1^AFFY1yQUfwZ7IQL`4pDELpL3o0_MmCIUK7B)jsq}3Re@?Elqt3p zKs-K2oiq?*$dG8uEGkLB_S3zyg$eZVQ*W55$9mHaco`3Rk5-ic=B5C(mV?$tZ!|LT zG#~RU@;hB1jVd2_%fb7mzGm=^RqKU=St}2ck}Ub7)JvWp5;M`;OoH@77Y5JE6%z#l zu7c$7rVDUL=$E|!?*u5|l_r?PWsS!w@FtYQa`1E*WDh0Qon<%&v<<)CO86dGgvbGN zwk&bW9Prjj;hheuK7fvKcVTrfQ8pauTWm2j(|r1Egw6tZyB*ixA)|2`C;04z%R4f3 z3lP8OQ1*PwR@a&&~KV09jhS4pn00g1X^d%n@}+x|K~9TO+Yl%y;zkC zS-<{1d1WN-tj&unj^vxqGb z^?mcCm~fil8YAyFIRiWL+bw8|Cs;7dk}05`zGSj?k)g1LM_|#ANm3=Y|*W&*XAU8IP&O4XwO~arQBZm9g&C2Sb*ERMg1l z0l07!T>lhU$G?dt*11(i`<(1eEzRMKC|~*V!j@zU`uA~57i_Fhu;TAQSy57v04C>s0&tcs`K%L+{H4 z=kxobw@O_D8cJn}tdu!vO<+wxQSA;KX~`rm!{06^!Db(%J1KH|>_akHX#RctAv@{M zO6C_Z?RQ|xBs!j)k$!BDjK2PBk)qo~rk4G=H=4Z(j9;78=_tjxTz!5nP>ogmjh=qZ;8-N#p5G zlWsRuo2N9$*XjEbx*X-yr`bl%S#Y4nSDx9EK-?bcwu4OPcvckn2%hS0cfCKzR};@Y zG-kf0&i4!DL4o_T-s@4?^sKbR)cb_))Ge;|5q2F!;d?N0;HnuksCkZmGZa*CA1b;= z;@x?Q`ukfxWOc_&d-S8oBJyza9k06a6g$!|Y*!wdpgi8Jd@8jju098g`YLZ#wxdm& zeNGkO9|_{FPFUzOiM3y=DD<5kU=ot<#4=t?I9VeZts7U6K4;Ro2-(uBW}=UH4mmCw z@W%e#Qy$?)eAG+h>D4sz)Y@CXdx_71BBL`;Uh#T3{M{?Ye)`4f0M+i@Q)O89O!HcX zFSFB$+tTM1Q(eTKDem3Zv0HlWqo6U)fulZzi|qa|G<|+q9F}I-k?}|X;l{zPEbe}G0*^_u+Kf?-(J zg7<91YlDL4c{X6ZgD%nK@AX@S?}QbKBH@uy!}UU5t~8@E^GSv@b(p*VtKo*+X&b&tPy|f zP=sEZ{&cJ7{Ojh46gX416C(Tg%j{I9GMI^JuRdup%d! zPo48Px6px8^_SXl@^ImCVur5-r5T=c-TNhs@#t-=(E9B`W}rloh7I)lv5O~eW1=Int@ooOuR1f6Nx~m^uEkQfgK^c^ zNX_;;T&KCYu53(RVSH>)Lmu;l-LXrWxi+NK#YY>fXA*Q8?Q7gEAeY!NC4Tuo$*Xj0 z-`je%;88Yk^1A1niFaN)fF)`{_ zQ#K|+wt{1`!(E{f>8f7$pmpdiaT?(SqkOz{L+MG|Yc$Y(xcg+FQoyC2hBU=v>maWQ zDKR}F7K%w;a43sij9f3I&t70gL24&rStjR)T>q!xfl}``Cxl67K0m|Zy5Ynw8c+~m zbo@R*0Eu~__&ke;q$2C}Ns+NZ>+0)*yF$*=Xa)ezoJ9V#|1ICY8iwdP82lyOi`8l$ z&p*zV%r<+g!Is$kh`1GmsN-Z-e)JYj{UZ4#L{c-ohSlyJyW_SeL|Egm(({k_NsE$a!SMzp9Jl-HcwS;2zM!Op z@aGGWmgli}xt}m#?Gxus->2n+YiWSKp3au|Ja8U)BHYG!)9ypFTpC?RvIOFztb9dE zA8tx$OP}l%9gl0yS*I7L!xGtg)wjmi5^gOn+b^k>4Y^H|G+V)1v-k`%PvzxYD1jJ5 zRmfo5k?sU>kEX<(Ka-Ot4~JJ0FUm9Ao7KlCF0GIwNyPQ0YZ!{njX@%Dh$370!m z7H>@&#oqDJ6tT09C7P{!Ffj-`1;P2_Gi|j#Yu^Ev=W$Fw0EY=49vto5`U7*B5AWp+ zMl?|&5%1^wNZh?RZI>sOpYYNLSWjhAYn+K@7v#75))8k@E)^)y!XF>Xj6(?1fZch7 za$DqbK9j3S1lA>q&#kPHrWZZ}-=2S*$zL7q%Lysve^MJBaCJvB|>s zP3G@0s2cAl)&ZG#6NO^lHb%XGvJj=W861i$s!dR22ovHTJBDZ|l5ad-|J0RaI-1sy z%%te1{7xx@x>3e#Y$LOelqsIXla5)$hx91wiQFydd1C7O{8&Js=)+>CUuLJ`cDvPu zDf#H=KWtb2e4`=0$RG@I`;T|eJ*L6+`E`9?FBu^Pk$WbB(QDmcM(sW4?Y?cZ*1=Wc9++abw8{uK z!z*9@Ymb&pkRB_XGe3v-fORJuKmB;>4x79G;KKQ0xVD^y&--{|(*!E{HwF$ERYO7L`~W}(QVk-^SPl%ya1%WQvVOa`a|5F!({6KJpoh<_L~+u#2`8}3z{7mBJROMOY! zKZvaH&p_}Nf4DXL`QL~B_-`Y||9t^htrRY{lHOH?@tGDI0un)9=)}c z`zraLu&lo9$$&vW)o97x6eXa2hqm8jAn>;|7N7S&%crC^JdH z{~SUb|4G#_Z3|hpg=Lz8&R*f6P6IJk0}fWXKf(m3CRjvGC7%R>C-2u>T6NU$$-?qsa4x>dh ziifTJOwVc}dKH}1V8%HM@9nl=9b}va(yvTFAO@ zlpM$KF_A+7K1R_o-$_Q)pYE&4;b~8u)81-VaCPGxUCf6MVT_Lb(Iw7XXqSq5xSM2E zX6@;WD%fJr_uoZ?u*Zy!D3Q?V)Xl=7Xc~-^8`Q(|!#d!Au#^+c|9KqeFTUEl-xWz; zd5ba>a-utn7p2X;0%PZykSEDh50h-!a>#0VYk03O^HbdpJ8(!b}W<8IeK zYp)_?MD}pW5`FC-Z5*s!03hT%lhLonClLbtWq*23d%>eb`MgKZU^}OQwHm$n_4?Xr zJZ>vXMr=?9K(h&+^ASqp)OwX_+`bROOejf~F)W(IIQ*Ia>fyY`FElss=pN8&Nw4U* zggH&xj4cLC`qMZ^>yY(T!D_Mp#-9MYQ`+bsA9C~R#~2<}{n%|rvULqu<8SPx5ti;p ze9+`cC3+nYJ^$M88#JdPY#2G73rT(0t6pc!&4Ws6)^pe}eihSI;1JH{;}akceeC5v z&2OHcX~|3F<-e0jmSX4lB&WQo!-#MACnao|pBLfs5- zdAT2s>Evzj$S01IU2#{g2mz-QK)`kraCu=pk zb}^C9+i9!)=oPk{2B(f!Z2+5X%dBn|s9E>D>{>gwJeK2uwUylecL!pk@x`-EAuX{=MXvo8M3cy_gm>@lI}HNg@dg{S^g!{;B?6?I|PM zw)*E75|Sl8oYC)*%$qpgTn=x_74JEVjvGtnPT9Y`_A|(t!dF*UrNl>p3#xwZ$W&xc zlNB2uLiLvnaQUIfcb=Y~nbut_>(OzH$%`aRk1i*lmt6@(Oj{xs3@yMB4_Ehc$O6;f z-6*#gDB~05_Pu&+r}9s0mOc(Yt8oTM?bO#5>azUw`0y;SO-zv=k*QRL5?nkW%b;Jf zIg^e#*^-3i+Z46zhW0v`{TL*{IO-Yc!?kf5a!Kz<3@|6*~(EEx&L1j_m!Z3dBYEz{#;(zK_IET%9u2 zGIwsI8cHAN(dW1`{Q0}zI9kT)eFlvg994kjiKe)Fg~8iGZskpS{8^%8^w@aS(MRbm zC4a0|9zY*xxqsar+O-VK%`~hGXCSmYDa)M~X=Ly%^WDlnz98~#G67BzA4wm- z9U6J$NmX?vA1@zT8fLH!{0t%neAU~;TdI(?pFG?fVW{aIYs)k6UgmkH58=rKxuZ`m zekPpBq)j;A|1>AmMoYIN=?~1!0))wMyPI>?#ut1}d(2LU>JU&#WFRUg|D<|jablx9 z52B@ya93?c@5L$~mf*NN#}^W0XEtKR{#)JCmt>=BGV-SfET_MR3tr{{b(m}4pfzKS zbe%StoEBy|*#P}qUeJZ{_hlHOBllX#(Ged!)Tn=f82G(-_u!NgzEmA>jH+HR!08|( z+20?({V%UDrDL@1hL=NMIgF!;CYy4xAYYM#=URpVs9`)wlJJ9uOiaJ(p9eX`u3mko zZ~Cy;%e%P1j|lyL>3%tXAKv*LarWUm{-L{m@BF0G(*~zAVQ7LwW<$?~N9JMr=aGqa z2+acNF4yp)>&*kMrIh0%5EdE?|H+i)a=>VuT**Q*B|lTcWljQG@M}ewmnl?Sq!Z(H ze80mVA~|D69dYJEQVHmTQqB|Yk=lXwFAcszA6;cYIE43UhF4484={gF$v$^vdBSbJJH#fLZCQxO|fG z>2Hkyo-_J9`s-d|dO@T6e5rwrhT3HBHVa--_y7q%O@O@X{CRb2P{J}8bi^1g7q6>u zg4g}e*$lAg%bSKLdBi4R+FT*U|Ee)Presy?Kel6qxpM8`Ve{L-h@g-~N8U9#z#9s*Ectz9kaHDg*c{|rt(FK+i52n0r3hRRK|evZd$`Ln4`d&KdgWh<<`Yr)QHt z_GsX~;UamU`>p(B)e9y7YvZpod!XHuGMTVxo;b{ozg&NPwcKi3v>_*)&P#YS|2=~8 zjbkHvx#)y|)qA)Ok%8`&W01`Q`BC`Q{I6yq=^T9jJ<&Ag`v=SnF51Tkz-Vq#9 zJvYrH+gFQFnJCcKt|FZ7f2vRqF+;I#Tyk$|Fm6rM8)iMWHc5eU4ipJ4IRj)>{o(Ln zO)wbhtJFZo6~2OOP-NezIFTqZex&&Ie|2a)Vu4Rk3L?*jB;!0jsD|d&& zBl}x7)}vP^GO9oeZ9k|w0KG3#MB@FXG=#hlN)kn_uSfrHy2lClssb5YXre&0OY}i* zM|T6XRKVH9O`>l&JngL8$9OAH0jdK;I^R61x#EpGE^3HheM?_%j{%&H%5lM9`4XuU zXiE3*5su0#u?b{ zv0&&}h_MB}N-A_61@@AwCx-&b!uoyCN>>-nPBA`WBmU==VZ)FKJmv{S*k3RGY2JID zH%z~M&yBl1e?uYsmdV+B%jH{0T16{sf>$WxEdXESSmNTs@9-c-V^Is`>4+2BrY(=a zLGQvRklqoB(0l6x{&OrwQ(A|ep4-%DykEr^TJEQHxzB|u-+iGXod%-8csm1|z4yC@ zSrQdy%N3coj>(LKv3)(wD;UY{Ml*Qe82&XTlRV-I9xCug@mSh}mPS@kZ?9ffwn3EE z@bn}GudRSD096_?9S8CHCQT2t<4uff$pQ1Z-CgWhqy?jEXh0KkIays=g#8eQ3T7Kw z+Q}RI6d-?jIwE!PnIM|5(2l`b5+V`ySZ?esJXSHJwNO0!8pgSE1=8%2hk8>8%+uau z+o?WOt4D7mZjn)x%qx=ov_1bYvs9o=VtuLFzI4$PpvfIpl;!0*==F85UDd7)Q0^)^w*#FYo-up&k%AwjgOW*ZPh( zfz$;(*WIItEm_A2%$siVCDnvshs#SLFY_stI2)cJU|ArfetrwF!YnGm7aDMe92O$$ z^p*dPg80)FXe@|~O_h9a69%`0D`65WYzq_(!h`wRF&fI~ONi8_y({7N+pvL#WGyBX zD5SbdA@yv(a=nAt}z9f6@9+$?SXx>E&)y{LOWa zX$!jtEL7sDY|ursty6&Y9yvk^pQL| zGp&H+TT|zmiJyhceaC{sr6Z%A4GQF`LfkzPSg+gC&|=$A4Sn#w?f}Y=@-8n;MqU9i zn^;nE;bZZrsHQ^Eg)CQ2yDr(;O1aWCWn4xiJeEzn+N z8x@hm&ifLYgt&*4;lC2Gya%)2xb~jR!2e_Yu=jCAgbIGX{`6ZTY)_^BqMOlgJ}7{0 zmkQIt;&ZpTq3f-8cAQS>#5I+5)WAq6aymiY1&#)~$Q5M8B`Qmj#y1+%)&6Z5unL4y zP`%Dua7gjOBW4psT9S0N-Vs04)C9h)o-<6t+X7ZYSphHVcENW%T{o-CKHY_sxMX_Q zZ;vaSTaLhz_;c^8hr1@+8phT^358<<(j63E zyl8ZIJU91oolzWUH}`{D7rCNm2u9Nx>4ZJlhTDg}3?I2Ah8~N>ScZc_z#dJm@@JaBz=in@j2OFCaP-|% z;F|;foxGYjI|VOCEKB@g8gA{CMVN{EdPDT0Uc)KkCW;|DA1O1RM^eJ5SMs^LD|u&+ zq~Y1Uu7*PqqkK0nYG@y8|3*h#Szr+N>FZ}f&vbYMl?Ei(`Ro>ohVT|8&1wHl=y+otE3X@tq#0bnERrB2ntY+Znj{ z9-QN`ypu=JK7Y?C7-!n1z~x7sX2>x>m46!PJtAy`Vb$0pj>tDjZ1*r2Gd3`KfJ=~A z;l2CY{jnzTjquS7Fa`!^=ka`Its++F08zF7+38?H`f$Vr6iYId7^Y>axt3|}+ncvf z&TQK39Aq-#72aq(>h#0KL9<WoC8ZRv<(%3g(&biufBPWQG05kTT#iJ{A1v;4vsvF{> zQ})yCZ|+Fu|0I3S2aW7~#Ifp1ll>f-U?jB{uajz>v^M=6PUrb#Rh{QN8Zzx-|JWpd zs-o>3?L~$7WXMrZulkUEV03XbTjAXy)s9zc%qE`S8`dd;ofvG^GD~;VlY<`KJ>6CsSG_af5k98DtGkmN~;B7E`xx(>v}K2`=4%e>2O&0o6DJ;OC>vq(`ESo0$64qbH*WFQGRnzf>bI8|3*A_@HhfgQi! z4m{1gtg*ua3vkt|hxnCnBKBN_$L(X<2OHb1IUidR!b7hwa(TueJo#5By+ri?qUjw& zfKBMWXRt07X!s$c!}t`8c|mLir9Y55#zBf#`%$@n+kjq^Q@BcUNxCV_CZrFO{dT`A z*lb_y#=B_jNrUuWlsK|sUMDZiX-**3LrxaSB|X?OdxRjb8u6YsHYp=r7k2>NX6Jp# zC#Tdmd^MJj7`p<~$2I$6Yh`Kop!&69M|q;iQvvaKD4n% ztGTeywLC`she|m0E?#@5J)L1l*Gz%$$bB(?kTA**_XPP)n7C`i-^+lRO`h=>?#$(! zw(F2%j(CedXd@kYxKnp+fy3bN_RaQ(``ll%3kK@+S=wU=HEW?|F)!-c6jc~x(CV?H zy<3~#L^`(m0!xjdQ0%Sa3s8qX<+Z3rt@0-Lhw*&2@-Imii{wuEUA-q60mN6)h0_7^ zTlcX%rDFfC_rqKgeCwT;nd8ZX;I*rH)h_UTIa-qsxZ2)9Pb4l1(m2c;7_d zGEH)^m&!g{_Hz9Kx``ZbNP`j+=7NCCH=RR0;=w!#11xO$mG4X5qqR`v5=62N%+$BZv5#NWN5@w$k5@=`Zji!g-urtyO!{;15RPVI6FYvRTarY5(!NeEK&0 z;6y`i?$dxy#L{w=8jJ+!O`L`C4hQMoBPjxbsv{<_jEnv=}WckdEyyM{+> z!kE31vmJFSuQhoGEdGXv2if6Q?nI)U?@fQ--L6ACz|xiF_do!50iQyg$5__mDoKI> z@)6VZrT4uMT5}7^Er0Jn7gw~?80hs62Bfwkonk?L*+=Vg>vgQ^@HCnd(Y%u9zOM5F zsT7Lw+iTFC$?xtBQ(9Dv+JJN((y{u~yjN`P`-jJ;QzzQo2pj+UoWAaDndf=uBzrES zoaHp`g7v?QX`0qO=Xb^Rf#&k=rgCKOu|+a<{&N@;dK(yhYbt!Z@U5ffLa6+RUstAh z6i`QJx%EL7o|G>9H+YRezm)p%&RZUt)Hu+@(e5p#&e<*lq?!K3qih5*vO~9uhIbhu z7X@R>HR#EZ$D&B=pj~r&N9FazKK)Nj>fa%A6^#g?{wZbNl;d^AdO6rTr2~sYi4F4PCxax%* z=tO7(6@;W-6ofbQKrHpxMei7RbQ{ON;%^ia)xwKzD-^#o6w_^S+}+{x082~$FtCCu zQjXTs;|KjgnxnN1llu|oK;o@^i=?}ng`Ze(k(pMLdw(QPw3@&WMvGg)c&sgEkF$m^3yUlnJO&CQ;~Cu_(RSi=nBd{ zDqj97A4zF8GMHMh?2(UlNq)J}watA&)IqL;26!cy5uT0L4MO|6O4{ z{$UKbmzv9;dZe9a@27KkT{mY;(CW9QcA3brDaSKz6K zy!d{R6%{N&Yq~&V(O_Kl(K+%WojDy{s`d);JNlX6fzmgz`XQ!3bh&)9)}mjfz(qwa zg0yd=;`(>3{+}Z5_vdN>=TYfD>nYuxUe9JAw!+6N9iuaw;;cq zm*oF=RQt1sZpF^o_&BEOgbo2Owh4JfB)V}7yAzC(t37jLnUG*fY*l2i=OuC`LI|P- zuEd)a61D6)kK;Is$-^Np1W73U^E8mgD2XsaW!6yeJQ=f1d{+)u3%NPokw|cbycsy}&Bd9yrk^%>$rFD-x8O%=*r4IZr+wMZrhf_dN`0YNK&Os_oG#=*fRj{yd5k8) zBMtmSL`nt3ZF9VGA+`l7&#>#8VBfaxmgnUC*943=i$ z`jvh6Jh&uzj;u@}+`#yb(RZ4n>n56YCvgw{K;Faq#!t7J8|#S!G={ee_mbS|QWFx4P&q4p?XZM*akwIP1$e7u=(o`I_;-;>|Z z+_(bMWaKbP$Y1T3dtIbx=-yMHc%##kQRLB)9~xoKkc8{#y(ATU;Scgy&nWHB9~Bto z@pa6vyx7r0zd#s(r`(pnj1w(muDfU5dRj4>pT`AsJTe&0@fmo+<3?{b0?LVEkxbV( zulvE-SO3*a=_Mik36ceMfU+NK5_hZ?b?ef1{W<)|eZmvhPtfo`N7DS5g+~b z?MZ_5#=6imS9uuBF7M}d%2dsUTgz!K0h}Skv-kN6oc8{(&BEk}e9iO7A9$Kbf-!h$ zZf>{z&U>2+Y6hZSA|3ia@+CQ|6J{rkPAM(m+C_JZQril&jP3P_xFa46t^wR}QL=yS zm7csFo($IrWC9q{{n4q<*so?#YqH0)+O1Blp^FJ2Jh{_*1^lGvXKx;_v5|k0J#Hqv z$0NGtM^(v6)U#<~T#ci=VwRFV$otk)I0+tXZ}G?gl>9v6`~!U=sYitw6+Z>%EY{BE zc`pB|?eDlpuo;>-1KW_(_~i4u^|!Z---%*)nRR6a$;wa$TZ@cfrO+QROW~gZx2O9z zCv%}ZBcs*9(57u~2%KIZ_6U{qjOH=DOBHgWm{Rx;xfF>RcZ1f zimi6{?sy+6G?6n;GEVTI17w2e0{ua1O71Is&bhm__8;e4B+rXvp=`(?s)EbO>b{KS z7P5&zlh{LnU~4;2G}%&eSZ<$I<5l0kzA#W7Y$s&43x)QF@p>x__)Q9oirNJM&lo*G zxp2Lfk!OI8uQrD5&F30wplltpppV3z(HPdqz<2QGWgk#5;Fup->E^g;!yx$UH zh=-~!z_hqmh$8y$w10apq)o)~%x*VAYbM-ge4FWv^t*P%SLDkPBTKklo?Y$JCtOz1 zHt@e!BXKbxUJvg*0wu@z1+;mKCRsp zh$jDdVR#oF%Vi0vR+~^i-=T&RPDefXK}T>+bnkgsrRIT_R5yZD@Mf+75^gt)jJP2_ zottgp(Gg`3kb6~7VDGX;)4|YX?57L;?t4d%jewJIROex%SYGoj*W$%td`#I<2$bsi zVr9UXlS`8EnJZpa7#-w-Vlg2Gu;hpt^qT{|CS-m`trHr69j@8l(nE>*8^xRuL*jrp$V8+@5-D$JE6@#o*Z!b(6y#;nn&g_ z>gMx7JnelbjadA%&n7g9pdqNyeZD`;9D2B*y9J2@9Ry*m5M>!-T=rz1Q$TtUqkqTe zhX9A^>!ak0qq`!J*(Dn$`U5!4dIFl|=mU4(@&*%Bd&n*bI_qSskHbw(*f-fy&2Rz1 zb6;$~-afW%s-0h7MA+WHMtSBvVCKLoe8UHx^ILZ2660%(JF&B93;l23jYX z+!M}zQ3%uW&u0bG)wJKeS>Z{N7ypq(-RXDVyyO&>%`@zgk$8fv2(c;e3bk&n167nC ze)Q#%bN<+6=MD*F7r0YXQW$&?Wa48Auwcn?^nMg{kX`Va2FJ^Kkxi6lZ|w&H4(iX>Qq+okXoFB$-Wo~4xm=)8f~Jo0mum*N_q-Z@A(#(LR51G*$;1A+ z_=U4fOGkD9?E@A%;QIU|%=zY$n;Uj67_qz|MjH;HC&Z3(^t(hfGo>kZzZRj?w6{Timy&%f-ZvKW@<;p=ww{ zcA^*ZCU23otJ?|1GKGzIv8(L<3#916RXJY*jBrkFK2>AOH0p+b31>>)wf1 zdCxy6JcO^Icfq@TRU?2WfvjlE^&Vny{70Crej&L7uq)yUARiMu;v49D2Z?T!=FrE; z^hJ_3x>NSMV5vSjMD34%d{kJ>F@wjQ#oRSLJw7q>lCPPa61L3!4(LmbwBM%-9d{3K zAAR2+c84ab#cu3A%#hkqe)7#@ab6$C2(#~?IzV~gzonh^l3%DVO>UAhy{ZtQlhnmy zaPbbmqj!x-#o3S)DD-N_@RyCC^JPz29{ad?QFkx356mN5U<174boo81haIj{1jmzp z--KO_Eu`UeUVaG6yM{P4QTGbp0W?N|wJQdw2(AhJNb+rM81zRARm9)^f&VzKA98%i zmF3a+<$wPrM~hBEfing8BSKk?{JZ}ZF&GjO?G|6BdfVp-atT!X<{zQep>oxD?Xc9F z_L;nMl+YNuv0VZFGeqiOlEb*~kH{XxZ`x5?#A7!I0U8V2CtB|Z5$6z)chF5eTFy~d ze%YfeJ%lZT=1H7CM+Rfai0!{r&~_a%0?1Pbu~Gcc@1-^vrTVHZaZQf91!BNQB3#vu zd*ZYQW&<}GAKG|s5ZjdthYN%(4;%;5&Jl=nI(YEK8wz z`tetC&JmArqf-OEmpo`0`e>n|9nJGe(karRmn2J*IxwG4btp^o!}Bhuzg&*p;p^0` zHFS^ss#TR{sAH?;%YBb$vQtdZQ|hsA7lN`r1t2La$Erpq*?O(%;Z{Sq_LJohpLi{G6^AE;^8wEequ6=bCN&46y#OdK3hl)=xIEhWB$)R(*&@Z)#bd(n;gaWwS) zr|$`l`1v={<8Va?(v@W{YVIE`*o}^d{SVG;|F@Nn#gCa0%J+e0V7HhtgHiUZs7&|LVX9vs~fWI*>m&5>NT=OfCc9)%7IM)|4wX9kXjOK`( zx(8tJ$FIIWiKMM969t9_ZwP}tQo{@k!;jBF9Hre(J-1Sh?DkB}@D8*-;s-#s!;{#G zmyG1Ix+U!m!BWv*Cu}i&M;0$8M)HH%)40mEQ!Qm$zW=-|IKxenQ3Ou#j2tgeELu_I zJCCJ5q^VM$$qR`u2Q$vL3{7d3v3j@NwjG9$ch+Osu}EP_uFgW1uo!R3OML2QFmek8 zITR!{>~ESNMGvlo8eT%wo;KWd{T`okoZhfaUnKZ&AEZwyT&rR}t!jhb$EZM6S;c67 z^w}1_4#-l>nxAJ{=w$2qAO*B~^qjv-<1EpV$0>YpHWV+L;#5H)BMIVDQhfP^6OWbYLF(gK7*qnqsV&v8 zkfN)rPcmLJ9F^9VV~_j5v_E!0WeyJv~R+KHrw3f&WwC9?c? zE*i6M52IsWQEU5Yg%^G9T8-87X z&$0^o|L_WrBQhqCdC|wM-M+`S78Me0pSd;@K^i}X#7~8!d3YRl-xYq34L8rex^1fEF+TJC4mhqX|U!ntmxN&=O7?T=xTUU+j2!y&RebkjM(oX<;k zfIn!?V1~kHM@Li>Zp8K4!Wj~F<-_hFsr8|)(cv6K9+{@}K(0nGw!SU>i;$%y9SH4( zsH{W|iLp5C{lQuAN%#oBW^^bWH^SzS(@iC5rh7kn=f(nKYeJ*JR(Bc7k0#wT|0nP? z9<&U5!1p32$X1?IvO^{-6}C@kWh+6_UPeLGJ3h=fO2BoVh(r8uu&K#Ymv$0MWW$r4 z5+9-_)^7J(O0Nq(I>cW%1L-dK*@zITN|agJ=F?xSdQubfM{9kM5#W={RW zyhZ{YbSKC=BnzVGQgR0ggO^r$_AI9IiJR>Ku2Znl!VufY5U!w82N4Z6#xOA}Uc;GP z@b`Oa*Bp@7aDpUom?9qug?D>*CzEqb0}u9YtKkAfP$C`-+}Ze5Yz^jcw63isNm+L| z98^K(|I7kTc zbwpdpC5Q}6l^Ed*;j9zXdU%mA zH-4ZKBQrOEFuUWsYyq~5gLluU>$&_n^_zh(3|^X*BXiakIC;f*?sN=||4x?<;_4sn zkVC5m!p0RDznT>Wo7=oWfkvnA@<~*WTukIpi-~1a|E2I*srAPzpiPi}*jFCzH8QJ) zE8uiHcM9qX>d+UZ_4!4TR`r-n>~KE&4_bTn=x9ptpOWY$Vt z4y1m%bJeGYNQthMheA2K8H}nidKJZr5Cisu*R`inRszRyK5=WqBMXMqxKcaFjdqg< z@g%WsyrOymiytdzTqzyTb*I;&Im=In=mt9K$)u?5J8zc|N&@p7rXFpV=8e?<5uUMp z2&dfv_`IEvUf+Tm_f&q;P(Cny6$1Qr9GMr+7=@J|q}E46ha7K7?bg&6&IhCc{#Wm{ zh?mg8qmZI%To{8kVQXnwf5;ks1_B~x`Mg9wqTq8J-x`g{sEhZ$A*-+e8gyrVzqgXS zX!e2$4MX#P4{S?v;Tc%_E0B=$4+``{^SutGhFPf{U{5HOeLL?)d>J85$Pq@GuQOP1 zdNt^TJLYE|6ls9$Bgwpn^i(7L036n(AEK0PQk=l3@H)*gD5v1kvh2{6BvB53Ko7^b zv)oIvyTw)&ME0K!13Lxzz5J3fW>Xn(G{`-S54OUQJur2&+GpW{5b$t@@d5ECXuWx+ zqmqZGVk%tfPu{<}odtdPcBUm{3@Qiq-QW<|CcPInNBD_rNE+%R|AQ5t z0=U~=VQd?!;H2>o2ta*w0Mi#TaLy(>7d}QL&f!pqnZenJkGq?`@Bp98y5>7gduv9T z^B%#Q*O6L{x@%kH4;)8J7&{8T&9D);$zgfs2bmd35Fo=Oh&{9v-12_?=^+(>^z#lWssU5G+ z&npTSXF8miZ=;3HnzzLpK4`9J`a3kp+T0e_tR1AJdcap@NyM4zo=%)FLVfVXtQ9}< zYoDE&Iat1RJVG0C$Iv$(GiRW9btD%V%?$9|c51v2vK_-=#;qKnWCuHJz7dx=_@`eL zW?-^J+{s}VA7wH70X(GBt*Up(W(*sI1nq>oJUGa`EG}f~6(FPQ;&qu_g&Tg3uH2z; zd9?K-95~;;f(m^MQAo%#l{0U6)!LNyED#wE;6V!ZOkKZxQ>Vd)%y?gGC(`V4ZD*{U_q@?oR=4&HZSEq$2Z_Y*N7Z!sivB^Lb0osgkBnYH}`FkS4Y zn>1iA9Lv86)Zy0)MjxON9koTUf3j+qs zkTYnWe*+rZ4L`oVH)lw=*4= z4X6-xnhVi2B1(Shf=6?Dv2FN+9&4GT+9KyehJ{-UB7@n~?{62q3*|CTW>eF;Ejl;D zX8h&=OdsI=OgkB)_0TV%f`J^mQ=iZ4owQRPT(h=)&iFt41fKs(I>ZCQhiW5HK=AOI zFBL4Eav@x)+aah%NRU9atNKTH546WIQ6I+>Qu{7*nT{vv;7OqCu>AAPE1_XM8W1_! zgbZfzJy+Ii&p7L}G5`&;UP4)}U9Z?Bk%@j{QT&k~OpXb7Fs^r?O z*$3fkjLYGKD2;WSubhe=5mJ@Nxs*B4%+0**5`6uR|LZHy6%;PB6~`SGm}iiADg8PhkG|6+&dmMOu?Y_U_ro%>G=-3XsOS-0`$&ouXlgf z6v2dl%ceMgS@S2c8ZHEBl4Ous28sNf58Tt;!ABBEjAzl88o90P+b(4iqJZxa48Asj zy@w0!OQ$RO+b1s|VLAX!-Nf#)WB)0s8zgwSZ$q3)T1ie99CQa@4e(hr0{#++Zb;oI zvnI~=vudWke!u~p-kiX>y?)$P=J9X#io8AKR`)QFLg8#{CAei80!Yl{B0K(a{tWmg z8^oUIM=HqjX3#h!?+aR-998Xo?#*eq%*cL8@Nt`YtHsSvqrV4Fa+K=h41Xb$O(z2RuKBU3KI?3GT6eZ`NP8%dSSKb;Z& zmwk|*)! zd8bfsJRkJFH|Aq=c?Zrh7Cz>iqx)~|++p{sA|5@*{zddu5src3IQZ}IjcoLzzg!~a zaLqIf{thV~AUw~Z;#z|j#iHG?bM^{UoEHV#khv4QXahV{3RWe&n+}RN{0Gkx*3nqF z5oWsXum389=U|fx!G*k^X0ERPK`$?Pfw9wqQqC4LGVPFMiFIUm(6eX@2lF9( zKYCTpKglEul=d3Fmu|jF25gM1%ZFW{1w)jA(TcylmJ2YKn1(!svMDp>nJT3D<0=?9 z4_l^&xBth}d2K7IbzAtAR3vywPLhMdod^OVSp|Ih)90%FpVr*Fs+KMT!VF{d{&l=f zrL{1Q3iW65i02MD44QOIKvTd+ydjBNB?ZQ=pu9nj?q>b=K^h?g3rP{_M`+OCco2~o ztwK?iVBn6~i&y`UzJXHca?maYi^eJGIMH{Myw4LUQ9$u>`%CFTzl&(;1xH0)2qXsl z6$L%A2*C}#+F0TzirtfC>u(@~)e-h<>Q+g>DF_aTC;F64&sD$|^^qny2s<%5HRBhd=19vR2kyK6b06OE4}~a$XsU)AtzV5-?%i}_HXf}|9!>7U zv4^jC4XWCYfcs9qm>CUM;YI^&bDKMNhhrss-McE!a`TKCsB7@LZ^s*iRo;1*Uwem? z_w*4$`8Gn!hBb|nfta+Z-~I8Aqm3UVf~j`P1<@{Wq?`19wgbtyp<7?k!y81dTR2AT zsoC&1=MkH{FDxcmtet{Sd)s-eH=IeVHcZ2Q`<{$#yEy0Y)NIYRS)4XlypV16fzQNna@v&OLS zo3Q(Qw^EkR4Pt?-eE&fr=2f9>-#9eqjsvWi!=tpS^9@lE9Lym|{pi2EzTCbQHeh+o zQ)5w8A<|GtEClQRHbg+DMXJAzXLo;slO)oA1QqOA$rJ%@EMl&_`TNyHg0?rw*)T=J zL8OpjlpT&Aq$CveI|Bk3M`Go8QsDSPt3SQQ6CYA{mm%}Mm;NzLRKl#!exbgn5O4GT zh^l&^%kJ4kJI9ko^aYxgOVzvPKEBDXB^4RSZq(2D-|iMR^`BLU8_0WjvE@8GDTdl> zQx-gZPh>odl2-tH>khhyP1XgRIx47uFw4}lzi?NK(;rX03#k~7AW03;rj+~Jt$Ci0 zJTE9K+#CpZoyxd>V^!-n^7ip}g{DLtH~%Gkn*pc^XRqGuJ<_cAsBd8B1cx`MUHFh1 zQf|4Y+EZ|Ep)z{I+~EV>lcG!pNM3RGx=JdK}ISVYV&od5=zjnX=c3Sa^b<~D`+NHV(y zsdYSQPb5C~A$)r(S}b30cfua;RGcyHVA11pCOQKkrNNn&G#5pONa8IaQn&0bikY*x zlK11ha3p1y?3a**vx?a-xslKKC7de3!M>iW;KaXnKnomo^}Tt%=xrAm2(C}lnxFKi z&AA7K-@pxD-lyF!Q&8QpsJS40ZWf~A2impYR&JqlwA+7KmJ%;BnJ>^F6|b?A;-UTh(-k1hOkVZ1Uh3w$dOq6;-tlSDdO!| zT&~w0>Fl3f`e2zui*mr!GOugK-%4S`b3v-0-=T&>L@9C-k<(M~>XFC$ZP5#+otov; zym&cJ{tg`pYFPuQf;m9ZFzN0;`}&hgTt!XDFzK9zYw!DZU$1Z4y1ai9Qb!V>L?*tB zRxhF}8pY~nK{bOSg>rsz_p=DOczypSn3wRWS6Y`&t8?j^pe&nLcDcKpyTMa zr7e!og!XQ3xuq>J)w`YPm;clEs(x_3T)4U5CY~`=#5DAH6jdWW4)`BnnxG<~Ud82`b}2XP zxOp$@nxad>seP4K{3+ufiQgZcW%{li{9e&1G3~LZ38XU=f$tSclgY zWpvYM$`p!&jix2E1IZDW_aLf*d6Em8eJO zA$rg}h98Ah&;T=`k4GLjGB7)*XReBX6oT)z%8xfNKKP212|^rjz(cJ55)|nC(TL&x zi#4B9j=iGlXYaS$-1Fs*PbEqiy^WL*T>AZC<* zClz6ansoOwx z8T@)knel;-(o<+@PQIdwdjJeEqY5p*tl$y2NZM3LM_Mm!^_P`v_5P-ao+bU_=)`VG zG>-`~NUC%ETo>j)MK2jb-P2o$8~cuU1DU>>MDq*P3j+^%*#uZl>EGv(aJ!K>g8qt# z^_KpOF*?M-3q8j5$URnuT)L;AL*x_oQ3@?Vk1}xWd8Vq`m1x{qA$YRax@P&?Z=d<$ zT;Z%#le09OaW#OrVLm!kUWQW=Bl}i9MNmIrv)(7>mLD$bJ*Dlt9$Pz*wZwd&s=I)W zpq{?SLQ02sM!Dr z5GxfpWD|0^RiNZR#&3b!0yFZ#UJz=_+K9~qQ-D3fDxM%HUC)eE)r0MOHmL{!B8j?aQhL`700E+^10LR=K$$r9ruuj50(d=cQ z>&a~Fn$U=T{9pjWb3k0&eEa_9?~v95O-=(H-{;)#ZZ7hl{g-qAVdxTA#(UiJ+k|a> zQ0zDBMtP$HbgKv5it6ci=!}oID!7j9u_#O*&&zCW@$<=E1Qq!$Nngjyht3E8MH066 zO#x*eDD06A!kmsHjCC)E?v-RPmfSj|9zzsG#33;^mm3~){$gZ)^&(mOkd;t)Xix(^ zT%x@dK~?Sx&%b6qsnfI4G@Y)5`t^^#Sz=x8V`pXt-)a{QvfLboSRZ18@c7K2wndli zHJkd=mg9hZk#GW_JrMeUuioC5@A^NkQzJIPj^Zovj#%%jPA)Ip{@8!ZhNNV~ET8fx z*>x2zwcpdN8^CTTiKX&Hj|Bm2!14rVsP{lvFuIY8Uv>)NBA%mm^3T)&v>V>;%Bny0 zRLtElMTRw0ut@E-yh?`hqUQ;rVgkk}K5ES=C`p-drCGsA+TZ;|%c)D7+t_gBt^mjytwf>k~mwDk6k> zFz`N=wbCTlmVHqpCDuBzq1UE~rakT06AW$FGN~_OWzmK?-!UV2HPKD|P*B0QEX;6R zL#xuNh6cVgbVP?qs8_FVnqAl4%J#}k%lVmFm>4#pAO1zk{=or3_%m{-NnD8^0zGerzoOfxi^A9Hjo+)DW z>p%@LSX`gS`KC=@lYdQitF~NS6Gf+TeeL(w?tO7r@Zo719Z8;a4ZdWYHU{1vkyCq+ z_F|3L@Uw#}Hbl1yd4}z;!1w~Y&87ZrvK*Zz82b=s2K4uAdsVO>RTSe@It%Xhh1A30 zkNmFeuxD6d+@pdbs;C)}s>q<&71 z?*k8~SbK+$*CG7~H62j1UiCU$NDT%ZCUWdH@~Gp#^`{X2`vPG*>Hn!jsNK*ON&&j*Q~iPm#=D{9g&{rvt$V+33~%@;g~|W+{`YOYX|$-E z&&mHD^Zq9WY&huC%g1|r*Qa=ynUFD1R9jRVA5=iAN^Q7q45?rl&Zw9cVYUQu;&Gpq zT8;@>q1a>yC$IfL@*sO?gAl|7Xy6k3OhfMtozWn0kNJIC#^iC&o!#e%3ih`6O@ed+x}16 zfo8$mbXd7Y`G$|JQ3d)fJlvKXM_!;Gz`whfG5WM#(8REV=cV;-;eWwtHldfJ4!)^A zy&W2W7?g7p&l-Dow|Le%IuSooU*d@`k!05avj6-bKjN*6#DYE}<5@w%N(o6j*ta(_ z17xZ}4sKV(w#@OQvsI7-@|Qubra$V}&N$LM1OVLO1K{utn$y?i!DQctEE|*U#yyer zAWT0_08ip!c${xXeRLhWKR4KRHvu~2eY7QlREM?gCC-w)a2J&fqVR80?*s9Fh689g z;EIrQ5i5U^|ItAhq6!fhHuikCw{~I z5BQ_Au=fR~G{_ zbwl99Gxrh3(FI+w-s#8JcT!UP`m=r?7;?cq!6A9+VRqv|8iX={3?AJ%zkmWv-#?JB z!-)qBGdhCg9^AgWyi1+p{iz2gZ+fKN+>B&J0(S^akEVE|6b&a?c$<85aV6x{38}mJ zzxH9HsZ1XlpctWheOnnh#7z8)D+YGJ`*XWh2!JaNk=T)?{BvL;tkz@?eDph5r_}CQ zR3kj&Zx%J>Df+=)#!}bzvvkhkcEE4!4}Np2=5l#skwCvTJte&EhkKc>90d7a?=_TG z`=B3)qmS_Tk{j-ZiGUL^gQUSVC!iG1Ii`xk{_R6#oa~S7p8un*;hj>HMIr%4Al}Gi zi>$>*_ROHl`)`ea{%&OKH-AP77>DW$sgK(vr2wl|M6^Jvsl(kmx9`h+Nwy1f@Ks2W zOw3g(Wc~Gb5g8SdNA>DHUMfWW&ApjlWVUoE3UdltkxgF;B2)s?{jsz!4@3fqhY;d+ ztzi@~BJ*Pd1@@fnuBfbePklpZ&hSokuQ}$s4bMa!jwpq8>0fd`ez;DeTcMvTc5gfQ4qp@)56zJ5hZnY8q)+xFS9K1s3vMOeWdx_{d!Eu>VvDNLdP; zd-$Qb`fFs?Cv)C}5n)n*uL|H=+yJ8=HQ?YPm0WGsue~)`fAm1Ccf(_Y(ET z&{p)|%!RWX=rcqv(Xo#JchQ1CL_7^%;9oss5*& zUD)?RlboLP*}o9~*9hP7#8L-zUK_7>JoSL9d;{-9og=_VHt7%g%pMNlPiK3WAiI17Y9hz;$B#gR!IW;@OXzkJ2`oHX+X78+5D$$|Zm} zezt@yj6ir^HyGmccW*OU5Pc6ux49_Sc&&+l@Sf?_p_6Dy_Lz)=;;InTQHZ;L3d|>9GsjH#v9NqF`T_;n!4|=#7 z(A~TvnbjQXIx5)nI<5FSAkZBz7}t4BF~xnt-@U*3$uC;xl3(^aba|J{{_|DTlZ6WB zarw)BU;X^?waQ;KZA*QrBzyd*h8$OxQ&rZdg_z6xe9h&NRTaR>0fJL3{-yOVzY5SV zDlbDaZ?oflWktH>(1#i?OiAFRl@|K)0S6HZq0dY_TZ~pfzAI&itW^U}u&_s|uj(on zZrC+|gp2X_{g*Jj@Th;6DHi4&n~|aEy3RfGf=d{3PqUI0epFiR6kYK)vPk*M46LQ#E_pw9&*!@}`P>bvq*xT2B!GS&^fG{nJ ziJSwgcx$e~ysx9Cz?Z6QS^TjfEv2X44d70a;Ey_crJ5bB(om$r;Grz{8lS$ajke>z zB_x5mhz4W&m`pJ=qy#Q6-AG?&ujiZRtK+}>daKIF4Z9*e?v2)2aUrYM7h$$Qi3TPJ z53-twZ>M_4856I@_;`RQgHJ7Y$d9i{Ld!6o$YB8O25c~%oK*wz4SblR1&zbUco(?W ze=@LQxaNFB41Hh8$0l7m;SeC0lVf|=Z}kj<6B*?uU@yw!J3XK-%AU95M?5xrar)i_ z9#-^S?+$xHUY%Jy^Go#rG4Ft?k>UL89DxE%zIpNod%gi8vbGk;64wvf*~a0CMeH`< zon#;cuXb}b1L&U+#-t0R2PtUK^Q3f1$^0ZKSw1B5<!aYLmP~;@HA-eV=S=NA4BS{f0K4DOsJDoXT?# zW$h%8q(AUdZrmPkj=oOSnKN||Y#<^rM+H>Tbdetg}Gw{NbD>NY`wowDriT=~s z7AQ*SQl7Q>{);)QhKB#wrT3HWZZERJCMTi;nc${la5l(wp-c+^J1;NXIdrrSiaRL! z!xL-N#VMU!!7}}eju;KZaz)kaR+uLkRYtzvW#H5w+R1<nMBLG(S%->EIJOy@iZ|D{AKL08s|1u#1RAo|eR%1mj zN09z@>Fye`5-K(L4U4-_)$il4p*XNE5^P`5KTg7zT^>vCTcurOFOQLT@-IPq1SQyR zhPKf%P~E$9=^_6M+a3N0P}u?Uj?0V?aT+sjve8Cx0>%oF3el6to}waY%?|bW_%Qob zNYfHZXgbEbPcDOxM842?yz#al1Pw)Y7^Lqk%os#}cKV}^9i18ha594pv5%boYR3l5TX@kgXiofg@kN~1A9I_< z@zUR4XFqDhd({eAKy^Dz%?r*3FFLeGDlh0W z{ezQX(jM19KAaAJwB{4)B-wo-MHEDyZuDNXKohu`rN}M`!E`OYZ5g=4&2|yY-b^;{WelB_I|hD?+qf#holdk zHhx?@rn~IUJ#u#AM9h}-$8Jav{i6kaKZoeGuCZ@AwHMkGf6qgz<~1ny{UgNWitO8F z80%8dW1nKGeQu)n81haxEa<_-O5^t)lK$F4d zAE6{`&+o`VAi%~+$d`dYO;m$`k-m_;018Nbi{I6)Jn?n5Lf8Pr-FN?&&BrZ1o}1(U zc-7?0^_laPTvN}3xG1o=ODBIsZGDtVlo(X#gEMZy*s4H#p00sj)=wzq7q!`KT9TQ0 zIj5^;H?vbKkM@0ja97|6FRv2OGmw5wX8t>DKQ&@H7@I_NptvAIOL^a&+myi$=rG$m z@4&+Z6li2NH7v5Yqvs`kKgs$Yx9>Dzv-Jv|w*CNoU-KWcu>QA=i{xQ z_U5`*18>`KdHZ5dZ${Hu{nhNK^W_anc(Xmv&&kgnf$U+5_cvky*IkVzx26mB1VjYCzZ93(d)ModD^hoIq2NYm zR9Ds^dz|IxkGe}Af zJ(}ZZ5F^L}aHT6_((#4uWQSfL`>gEe^#d>W5=j71oMle@PRtB3j$x_XpY!C-W=DR0M&i4HhFssikkmR9wXnvzgy?d=Q>#^Az8s*u&BBa zqw6Z0;4D(oX9@iP4%%ADzE?Moj zoRh4p@%;FJTq|&dJh2>U=i|TTl%SKVb|C`-ZXCvX1o>W`a&vxM@%MaVBjY#2c~g-| z4Y!T_sfMK3wNSv#OJFyY4rrx-b1EP8Xx126DRDOd8ddPzF^4ADd}y5iH23f+EIcZ3 z40P!?mrP<3hZi9qy#j-l?Dk-%_fbHcx81EUD@Zhm?E!0Mlg{!SD}o#}VhHgs`c9p% zI*FE6CPdY^Ibe=?4$gLLa}=&}Y&US1mtX}@9UFuh+6-#)M@MX1JWe2(4xc~Xn(~YuH+rHdgq~j6t)Wk4 zhTq|Aw3pAHk*OiZ@R1CRSCICHuRc7odhPwQzN!miKW(Y8;_JcSWO1zqNnQCzC&}=Q z?hzM;aL$ZX!GyTcnQ9NWqEp9SbeB{wS6r0y8RznyLTOG*J{RVc2n(%;jnk&9cgExN zt+)@la@u4@3M9aTah_90&Nnz3lYH#V2Zl27Ug6;;rz-NIoZsQL>RN8yj2dukJ7L@> zxCeI?@O!;m?%^(H!kqX-1jSn9kj%O%GEeabZsRmjCHhkiihChOLq_WCGD;If?yiK} zOHOkLOKMuvK5h_G`l*7A+GD^HDF(zA{H5RQ@E}x_g{tAgV^Md4#U7^QeeVg;Kv?{@ zOimKf9I)3G+#lT91q6@_Sr*`SB6Y}TO=_#SfhqlXh;XXl?PDvC~`I@D(|JW)$_ zpAEWZvsaj8%MoU(}5jnh{k>}ZEl&5ox+Rb z8Sx22?m{lYE5?<7^QGW~EOHNQNV6Mqc@bZ4E%g!{SS@EzTTdoDGAhycx1_gOi1_lE z>|k+wlC>mm1x&BH>OPYlp?-h{2Pi6e?{LbP2-#APeW1$$;uHmhDezNeQt4}JfRK~! z_zY0|BB^9Kv{6J@z9!9eWhkS9&;$bTnyjjshK@`yCYY%^L7>wrysU4SW&>KE^}8J zgxWXAbT7K(FklI^HX|o@uaQue#gq$z2QZPe4pZ&pL6kykb4j4GXQ3sA>-A{-DhMg? zB7757%ZyUoYqew&nvOF@*`n)1a#9-Zc`z6?ZM`sINHOP7zwbO{n62B}nNZjJ?f(GY z;%>g|D-?LHwmqzz=$8kLta)nYNkDUd7t${~oWA6;a~zku6P=1uNlNm9Tn)p~?PVau z1V6(ANc^!;CW#V*jFe4fv8r)F+N={JHG3 z*L5v>=lH%i6*j4N-m<^9oqhMa?AsOj^G?YDb-==Empwb|JSFHxj!uq%zU-)n*FTT1 z%FoIp{!5UZ!fH&`LLiy;A%B-DQFhDP)fcGR-EYf^vqRvOs4r^|GB^vbM(VDpNC@${ z_}DImE)asI;eRCG4{TtqL%W`r&2S@p6LjlEOoj?YaBOhq6JVjD!Q*kjpdaAxADvv( zM72jQrIB1_IOPfz32V|#i}zz+AsN>w~j)7e>wy3{_a-6X+FCO@yjTV8aER*|;@FF5`ut?rr*A>j z$Q+?sv9py7Cf9R&_0#n?mfj7mExSBAZW%vS|A|fiXJD!C;^O30q+=kdsMPKk@e3X4 z0gY`Ta{iW&+RyxLP^9(Ekl>17E$ggQKO}d^>~Pk`rK$bdFlaeTFcXm>zo3^FQ+N1E z1gz*G6Se+={Kz-KQ8@B*DV%StAMczxK6WJ?qXBWWWiffZdW91)6>j12W*xY6I@g@LsEzLU5l7`u5n4*dCL~x1KuJ=#9_Hs+llOLCCt+s0xpG zmaoWw1;ASbf%B(nS843-LEP|j@61ThiL^B8u2FgGCRk6x9w`~!yiUJV^v%#qqpp@T zJJ@S_1#>`5zC+v!FZ^oLJ}7_kq%s!wRpjJG4`#VM7l;062%!X&$s-5GvSjXveIX0i5Sh zK9WDNN%t34eei;0>Z7|9eCm%@jHmMcLo-dvb7)gq9n%L;CExd_G zF}e`UnowON; z!h@Ck(f2#a;Ll{+{P&G_m%f2D1T&^C5-n1$z|$*%sh3CYKJ`knNO_oBGgvV=fqSjU zPjp%9US~H)cD?30y(Ka5srOwNC`D40>gRp<$nvy(VXLW7*5ss@+HXemy7cG(yB|Y8 zlF8><1Qc{Eo%we@uD9*rPh^ei*^Tx6mXxe}H@*~oZ`tVm54|&Hly~g`DEXrLQ^Di0 zWqnC+TF9VT5scb{mNHXy>_OEbXFMWs^;6=fx1P7kezk@W8aXaH$5Htlw5E^3wJp3UWI-5 zuo6PgL3|3I-=!UWVnKj`Z+Df=s3;+4#xa~%`uah{x8vW3Z}BDGMCF|7-f?Nh>TL^y zc%fMxrQTBuu=APIq~}71mD7odBlKXf8bjuLWfLOuXPxL85SwNc@-3KeI1`%Xoa1K3dMl) zlYX$q0ktnslpr%dl7UrXRU|AUJL4x3=?8`l#gxMIt)7Z58~T=L9%gLh!AI4R_;w^Z zeLpzkf>IP@Y9;C_CuiQr6iWuOs%5DJ;$V%Fs1U*~nO8*DBlkc^^`nLC&bg6v)!_>P z-&i8m$7_<$8r(VLz2Ki``nqTymN!DeH6L5NCbi6+sqgcO3@%_iUYoQ6N@ zRt{M+-hL-?f*o^S!Y5gx*Ymx4R@t!pF$muLd=@wT<$s`x$4dHZp!fF!yIegjhKh~`~`&wX2&Kp?m%1Z?GVISLu!BwTiTl^~gz^p(VUHqwW9esA;+24(ULdTIG zV$FEO3#vL?Nly+Lgcw#YUZdCNcuP7xsDkel+hnm1zoaS)es5 zIV7)BqX-~27)%@>E9Te1I4M~+58h+IjqhmTKO&FpFPUK{s%aWC_YpKKkyFYKwUvd- zO=o048)?AmPL~h*FR-H`jbV?MRr2?spgN#L!x zPQU>*Tgc-}5Q6OcOi!fN6|&&@Jf<l)g74ppk3K%ExH^9Y6Q>Caz|o(_x$LtCc;<93!h{L_zJp z0Mj$|h(kU2f*;4Cams-@RC&!Um?_j+Z+~TP=ZJh2EJjO#3>5Ma49_?Sp8Fv7x?CI% zWDA0xoPClidrk2#p~`(7)QQa3+WE8n8+S6L{?HOVhL#yZY+U zLVr@bJ^$?*U@}GH-R@Ll(GZBe+3Jp*RacnSo}t~2l}$a6DsZq(<7BdX{`S%9`yDNN zkX-5_6;5?RpTkRqlnBPiMi8-GU`Jl_7N&IHZl7p-PX)y%0VFv%1PIZDW#ch&I6STG zWzjQ3&A&be7w&=cSlLSI_hqfi8SVSep_0!G>Fy^v@;uQFU!kk0sT==8kGfet`7H%3 zXVbfGj)ZXE_F@JhjCk!10L-M-7FFi47sK3&oMKyk`Az9d z0O&{kaCq@-_mm&qfLaMuHs?EP-_U=>ZpfC%;1c=sn13CAW3FVuwjR}TJ4VO{STc(L zAdu#;mSVzdN1@kWt5gTGhb9(T2`)9l{v`K}zbaY&AlDk|PDlwk^t%DnI2a=RnmI8e z4sw|4;bFSjB!iLEs`Ke%Ul1)@rt8w7o0m$S3K64*vu}$-*J!>r45fvV95^HsqsqaY z-zu^eYk2dyHB=MZ#OAg8uJ>5+@v;wxf`p?^`Pnt)M$Li(i^!) zT|OPVhr+2h`{z?mUwai-hXOqF;m%YecCW#LNc7L~>m?}}-|ZI$B!ORxfjVld`r9Gq z7l#)DFA~}(8W6xf1zSUSTV*EuB%L%%UoPR<5`6!q0Kq*` zSpkY1_ZIR~)hl1X#^<~|j_v%Lxab@$Ii|@$fK6rsg$Hb1-){)XRVI=A-P6CLDn-kw zK9!UB_3Pf-5294c(P3ZhfuM=5G}g|~AV>gnL>qHUZmJL}emLbG-~s-xN4%L(Q~^0= zA^?C;eHzcwMt+yxh1g7Bj=@_HXk@nE)7|TH4$k$<%1d0h_>J9@GNKq18=(4rLhyz^ zvWd3H&p!2*eBU7io6h;L`Ubv!C^cXEQezjg6Xm=eZRQU$DqvDnJaX=^AodpfcVD=t znSZ|Lv*aL&RYe0SXG?=|{m-bj<4{paZme>q58Gqtunk8ZQDy9N0S=Jrf;tqkqkB6Z z%cqRf>KET+7vOGBYu`6%DEGiM#c;YGE~jv}o5(cn-N9wu*SuOFRX~T#hRnexXT3n; zCUbS1q(cP`7};6vVXED*Hug6ELh{{vq$bUNKFq#KFTTu0U@i8b!}iz^@kW*N z4=gc-P-5jB+62yk{1W`T=Ps)OKF)Gkk$qi%z|d?RjGd1wZ(b->wXktX04030Tu;kd z2!avBkjR0{bGN>;Nwypmo$SVC-HGK*i6)PC z?)lw5DtBS3blC`O?mGq^D_4it0qdvd-8kY1M!fm*G z;U2H#8^Qb}fPK;j5VWa*G-#BxR~){P{7p*Mcc8Wt?`n=M>Nr~!p5*~_>YSnxI7_6< zYsjDtb37PV^=RpqpIpDMr4|vuVm8+90B6Cjfe#e6QJi9<*lv=po%-Hk2T03w`T+BcxZ7_$yX4+Wl*Y7rt76}SvGwv#rd|({hr{3(b!mKF zPg#PvZ00o)1i^c7IOGz?l#(NZxbAL0Fni9wAzzS#WW$4yK!#>$R zX_Qu-W{2xoD4E4t)=HM0-Y6enx^Y>qmP}zmPhr?cGoxkE-g8!!2?u zaau>v*9+Hee;H+7pvz0;yZE-TpC?gDg5s~8a${K8r7}_9V5+^REqXl&QS2P+%z$$u z_IkW)XN{cDYi&Oy0YzMpOnxeejg;ERBVfXic8Na;Dp9NYQ7BluzG<_JrZJ8>Q4Wt4 z6(T~9f0S;~tHev+>kG(Ws}rd}v`g#5M;bSMxtw^lS={bhgM&-|j>y`fhFl=l4B_~9 zo`R8kNp||1Q6b&llkEtH|8UoluH zZqADA0Jp;%XA2e)v!x32AGr!drU-e}a#GUN<#Ta<;q!i1%D&KyWr_qZ zM#ud|U6`Jp@5wpfc}Tzqvt2XHlMGh#v6qS(vnGrBd@U3(+FuV*w^Mp&MNpOU)Gb{~ zw&TN}SQ~JDsAgZ^;1}dJ>TuV`(Oy=Ae94*rZ~?%-yT2zVBn+-}iAqkDG8b#1-V-0( zbKZj-yRc_9x!>FUZ@3dSJkB}jy=Nzo$zsN^gNQQ5+aZ1lHx@0U_)-*o>myBOxgHH-lo*dc>-Kb`IV$K0(P#(BaOM=E{UO?t2N`s#C3_CNnmgGX)##8sCTS>;@8SaTvNhChe1_iQJwRn+$?+X;%-^2PcbCH^hk zf{0w)&|>%uDJd-oC*^Y<`@pID+#!}yJRdqSPqwP3$|qO9I-qSjF4xf2ZzvZk?#r7V z*p%MH@71ICJK!e)ClT|O7hFTUoNgC*&Nq~uk!M-DMI6#hu)@6fNrRZsTohE+{?>qx zZJ6I!tB8@0!RDIOIF-Bx%|F%Ckb(BrzSr%D|j;n(^++5%Q`)fLv&;2uW;mE(?=*j&V zy-dk_-uyhGq+EWMUtBROS*1?we0Ln2H%dri>$F`0MTd|>S4);XfV;tT4xoUKf+Uw~ zxMl^(;a?bW>WLpwP*H0NQ?q4}?=CyfF8Om6ty|JUs1n1Ppjfh?83Ypj}v6fR<+;Bi!UNxxA>+<_or9hOFPB# z`E73k$A+kuZU{$Qwdoh=YnaU^#ca^r6-EdCf)=-zh6g*z#eeltqshxWUKoB_)7 zlj03F*ZW7Y zQ=#gofRa^e@4P%%Y7EZk3oKTK>ha^}S<^Q+@qB;1@aA5cUI%ibp%s6^@-uECiAk&l z42l6MZ%+w;#2=`Rx9W1qeK$%qI*qH_ZQrXe`zDN1-<5jV0n1e}(#|z8wZ(|6%rNgM z*Eh~BL}70Jh;v%`ib&8^1NHE!j)lgNsS$DCT#&ELxvm2efLG!z&Qowfb^H~{1L|KN zM_23%=daV%&R@p4US@)pK^|kavc5XK5rm58!BN}5>q-vgxVOd%t2&T$BYrROZkj1K z#37xTKDUSd^q6q2<)hep0B2U$IsBcqs*oC(Gc@qstaJn01aCz5+%LR0?`~9SWclv*-`&qs&UYKWlaRjid{}T97`rB#YLocUFH}bML(d;Bl(pXn9>|vH2r?lgYGWvj`9}Zj6T(Y^dY$R2_aeKRF3b{*yn& z>GPr=sN@3DdvtIVnB|uA(BbFLIe{*)oas zdH+}`{)i^g4(;Jx%N^F?6l4^F;vUF17b2zW#pn7xg3-)9!pAYZK5!UCI_K7INuF1- z((I1KIJPx)*o@Pic3tQycj7S;V_aI}IEu={TN}X*3?$^1DpvRJEO!yVV~ZOSBhU!} z9h=P4D!q@9tj;3qg#SHGCuB<=Bc8grR)&z^Nkh>Zul7N@1;g-U5(~y4+XJ#U8D%N5 z4u0~jmZD*PJqF$l@M&bspEIr6nAZ3Kbe7xY;de9Fo8e(B#I77c!i|2~Z8g9J#dk8- zyNoj1q=Ykk(nK*Dx2_qxH`9cZja7b?>FW1Drho8zv?<< zR1Qr*fvv3Mw-^)WB_3)=HUDD6>-!Gf08Vs^sZgmG@-Cug_5AVqO|dov7XMgWIsaHR z*Zh(*Wixy%}9$ClZZl4Usk?s>UC5#EuVg+x*AUofm+hPn@ zssZYOB&DMqHqTa{ZR)eI;OH4C_~IS2R?*#y%x{GK2A%=-o8(GsZ&){ke>GX!52Fyp zfpd+BABNT6Ay*5(w;ilmrmV?@2Q{Ia?usEIqb7yxU;xjdL_W&l%9wJ?&Yn~4fOK9< z*!if(HhTLHT5@7rE@ZW!V|WB;fXc|L{Fp&lshffR_NHkID6*J+a(!r zt%0TjP1Fs;#ylMhe?+xG_#ui`%&rCs+n0I`KDe%FwFtXrW)A4=Oz{jHGk$gUcwP?? zV!CJFzIDZ@`~GZ`P!f6b(MN*nUJj=Hb--J(pbYdGZ@f{DdAv;W%a@PNhdG+}*>(ps zhIg^U^X*KvujIOab8#c-2aIxLUU}3{cAN~XR}>eDRFGud!LlFkyouHal3NY8@x0F5 z_Lm9C7*}>^DMKyW7guBMgXeC{;5J106T1~KbGqm@Maj;^7MW@$VP^s&dsX~YQ`;Kh z!SUvy774aB6w_p(ByqoA^6vM=wB3)%$GfatekAhh1Qk^e2dJRUzZRUac`xG>KwBKW z)Od5@#k4ebQzt z#E;xENTg?9sJ`vn|6}jXx*fH$bkSdvW1Rbt9`wzlKth0MBqSQ~at9y~ec%83JJ*iA z!(pe>c2>FSWSw)v+Y#D}RxsCGv;98nNu1^#|{V#Me^*4I(Ki zbWJxktP0dj^+kPpC4D{}EHNSnm!i$c#=r#Sya3~`k10qE%<~vj2`E6dEVf8hcYn~s z1}D$uzyu;O7CsKtHD}J~(*&SZefEZ@hQ7c|!e3}Ihg(lZ9mGTv3DtZ8AI1YGZRm@Z z#Kt=011cav^P-m)Ca7ZNY}rOC$UuE{t~Q%)to6dM&4dpRV5TXGm5SozpaC9*cMm+c z86nZK9AdF=T^9g#_R=Ihbfx1oUfH8l65ejtdzK`cK$^*y(mxx51!R&^Xr1MTZ_wwGtj)2jb z){;~LU638gDQhOcfMd#)(_u86dBe5po!sHVIPs2J5Us;W&cMqpBCdiG_-- zH}*QZO+`fjFW$f91^6jPLX$6rpT1>qtr@6zzPfGb-tG7i5N-RE;S@M=W&jN@w+zaK zx{gN;nHeD@T)D_LcApZIvW41)BvFnzMVJv7GLUW9&shnu?{^267`=HoXM1{Snxaj5 zt%{H?h1I=V2qVCt0A#SR{hmTsQ5R%8C4KfNa6g!6hD2=}Y=ZpQ^$N21&Q27NrT{Ii-QQ5Wx zfb3@zz`mCg`!Eh0s>_AEc!JjBS4QN(cKSZPX0pj2iv$pXKokd<y613J%ybC9x~4&HL~W4 z2xY!d8upSNE)GH`flmSD+@dNsGgUpZb9d#{JpjE1p5*$%xzqCo{EX`eZ`;QX$!ttq z+RUZhDlLC~*UAjlMiOv?m#6a0qkb=lSEi7tk?54w$Pt=RLbmj62a5?nHF%NZ9)e8; z$8bfe129k8`*+^d-17rVW2iE$UqHVH_1ZP?eG)IQtfX_Lxzh2lU2&i^vLPp@bgM8d zp&5YD7WgfZ4>h1Q0N#z6Z7=fW-9GAJptZVh24aV`N_-zZqTJ$asA?9vnhpa+L+y!x zN|PGk``+L?2+&d7KA{N93Boq$pP?1V_a1aOxU?Sh#ARnFEz)zIsVszXDljO71OH~% zgiXAonZDTN@cP1?_U+p}Sxrc|Z-^qGf_6k#u5&za#$fhFYmM(caS?&{D5E1BD+( zRF&-=46n5QR(lOSWg5 zieJPFE+WKMrr^XKQ1jr5oeoX$k+Rkno6tpi5-P0AGUWiZ0Iis*)(-m^O9Jtc2WZG( zh*B3<>jmOtXXTkH05WULn+lTB3MQ#Jhv`B^Eoz7mqLQDn7 zvP|@FLu!s?EuQ6iw~miT3sC~#Rshgo4dCng7uy&|M60SznRo>NaZowf3T>f7@PUJT zRA1wC@w);Vuej*XPB==~iM$bI}ekJs9ZC0`#vyKa$A}d~xNKfkG}ax$mAOu0DF?Q{7CVyo23# zV-BXeYYO+^tXZv3`K)QTB9=7o1)+j^07}sLl~QHhGYv1Gpdyw&0CN&$#19wo4gu(VI{p<69jq@I zOI>311o(9(u$9QSC%gj$FGM;e!1sXH2VIo~GY$Z!Ps+u(24w|k5B~bJ_-R;+DF(zr zX9xpAeKSzs7-&;Ns)nVB#dCuW{T*;D#hdRM`2h(Xy}R&tEWPx3000^QIGe%ox$g|G zJs@@|5~Qo)5Lr9K&M}}g02H+DmhV;GL#|@ zJ+2T|pM`WLAGgpuKX{4PfUK;C{Q}Pbkfm;bj7x@NSw$COQ)vu7KB42|*;@e^H~jG` z_!3%%49i)F&jrD)xITk< z1ZQxvmLJJiMQ_jm9T;s7#P`t2l#f6a)|B!sRjmuynTtVrW(oasRdrxtota_r>kTTU4{xTHdi?a+cF0sdjg}B9PkB{D%`v00ofLf&qKEevcGdH zi7Dt+5W5FZ(sZ!cAma#rSQc73{3;&g#PFdSR~4UGYPP(7Kt?VXFh>>&u^)UqG2D|0 z;!r4R!|W>llo>hV+8ke%4jiE6Ya*A|>p(ysX1wk#4bKapko@@$<$7(hdW*x*IV=tk z+hr!m5L#yo&_vXQBohdCp^|e6h;CwFmz=i?fD#>4&yrjjsH*^j*{qDscO}ffL5${j zqO`|>&>knsIi40XS0I6Blb8Ll0bRh-moMY?h7*VmW;rPaxayeyXvdJSTE8w1dVW|< z5nGH5TTSV{@iWHv@W#xRFuDw$G?$qm!RV?Sb*Ys zL?Z-&e;bJ=1 z3QmItmJFy@z6R-^Nbq&ga0(gL^y`+s_6>$_JHEeP1MP}l{O{i#sz#Km6?lBgKiuB=+u-juJsegy zHQbw!H1+s-n;3+L#g}6>-+8Zj0pPB zdxkIajz8t`xA&w#<)b~37<@b9$5i@#$^15%el>6UxD3W@{_!jX_U|P7pU-3t%IWha z|6wxxEb8b5ENM2zcX%mi_oWY782dr2hctM7hzQ#EPs<&Edm=&l@!b;N}LX-3dDPhos6A;HQ;rf*FS1_dC=j$)U?{5UjVdy_N@}J7r zU#Ue&613>IDv{s6n}}9sixA2&^u2pT8$XAQ&wYnXC%X zr276UHKd!a&5(^5KnZ|qX~wasV26JqJn*uhs}=tIaE>o=7?JK3f}xEgG{2KdA zxa8q$6usron>eQ9*up{tiy<;NmSy<~XnLXZGHu$QUZ`&dyqXMIB;O8zoO|EACOA1* z1Pnr?l`6=|N>dF}ydQ${?|p*~|NGScos9n;h4lZ6|CG0HxZ<}5^c#BXuaqkuqklq3 zJ?LHho?zkhr?CAfSlFrRUj{Rwp&{(4H|u(Ev&{yRN+a0dQiN;4mp0J0ZAz@kqp;%@{4 zab090z|_P({`@$^ywN7xx@Qnk`*s4DG2hPdZQHjC{a}5ejbGaPBt^L1E z_pj04S0q1ZnD48}KP)dltYghImRSuJ%7?6gGWqqg0yidp{DB+$<#O_~&GhbrR|ad> z*O&QRioS-A(9;=xs=XSSkl#=BWdNZ?@Jn%4D;(FRKh^QLG<`Ar)JCxNmy7c+R^M;W z^+%QSPpqAgul;4-Lv{>NR0kAM!^0YmVkpPRz(!Ii)N@(%tNfe-{fZ-JoTO@4i*F}V2G zZNsMzJLzu({SiSxE4>co&`^0ugJp_F`vx^yfBp6q+oC_BTQCe-m?qH4;cxU8I5dB- zFU;W2eZQiH|Dn@-T2d{_t!*4Yq&W^eG2F z#%1BDf((8?35Ia+zb*k`+pi4-{)1qAhH1ZV{KdAPRR2ab)z*+Sy-=`scg<7Wesf@L%nc{vG=X z$3NGXKOKVnGafLKBY0Mj9Jr#V1;2c)7fq535LNw9*x=y(L2&--JSc+lbDrV%@8G{6 z^iO|2qaW-nBv$u78Tv<3^PdU*!{L9{5<~l4<359g42p#Q9P;-*Y%ydX{b?KK2UF_P z*!np*kG|56`VGSF=u7@(L3p$RqKW(`te($E$^SO1=l7-Yn*@K!F_@+SDBSO};Zv8u zSN-#6`8wCnbL-1o0 zn?ES^F9Y+N-uzcmSU(z+Kbw<38k1-pCr=Fe4@Bb6n;$Q#*{I{33&sfn9()Mj8{UB8T zB=PVsKJmXWAMtZIjQI@2qc?&urGBLYkXA=SzjzB@35$QHIsa)a{N7uDLXfN-P)6|& zru9Fh1%Ig&ei1tV<*ffXukjD_p1}ehXMdRYWt^aV$FH4^Z>b72#lLa^aMJI2Ofdh) z0J05VhTR`d{co@Dk3;*+ml*#A^ZbX2{9E$#HTG{LK3}WY?}<+j1O?#)Uf&;y&tD-e zV76f~N?d=f694B)%cm~-%J2LS6rNAD`Fq0izeD4^I1B^ey8nx0=&Ru6f1nJ(B8%49 z-;<%S2cY}+M-kH>h|^!8ftUcpK1yf)lm>eJMuPf(^cwc5l~9=UPnbmij!W8S!0PuT z>MJ=teiU5&cdTmx1SAMl#`+~y-%BihZ3lfX*!w?0j6Ndg|3l>n@)PLJe{g618v~#J zN(%ZvnyCHPgPgzNPyg8f&mR{bGoSA8AICirq8WNM|0Cj_zY$5~=%09!;8|!DV6jhi z_2rpz9Ptx}5fsDYBn=-v-IFh$;oHOc%q*a1@UI3R|9iu*|Ir{R`d+_GqI|_rejVt= zIr9ICFzi?0^3N=5Uo}_%;Lm>*^}d2JfE51slHD2_)WysZOl!d|=QrR<91ehMmY!_X ziUU{{hr>}34^Q}499?LLf)C6CD^E8EQ2Nb{KZXD!>D4nxBZ*Zl7u#!o2RKLQe^R2; zh4-#(6rY3QV!JwkXqIz#lniqBYVi&9L^F;WrJTD~_7~KX?%!Jt0F63gehQaXK3rJR(_Z_ksyKBDWYqi#FCS7U!5k}H`TtUm`4VO=X}q4ohb zCPB=Qcz<;V{;^-(X{3eX4V4YTOIn?yT`PGdQOo^o3(x#`IqC(#cmPm@)G%sbxAGk~ z10!%BuVTyezA$mXh%+H1}bFit!!SMtD9 z0Nk$18Ql=2RywJdpEk3h8sIY>Z6>(pH?=+tI-W$k1t}ZpzFs4-SaM=Qy?|$h@n%U2 zNPGyM{(8KgmF7kstVry(PLduov$_E=23_9JdHS}-^QfqtH%Wxu&^oX|Xj&wiNgLtq za)=McRx!}G7H#RuZ#`<&2il-kHT~dj9d;4ITY}D2l~BjGM!LtQ?KdhAFq#&b%}qB* z=lc$9r9u~&E+F1b&$ANxfNyq)@~cR>m&cowGGUf7ToIM|5L3q^Kwkox)oml|>#{OZ z^d9}pYQ|LcQwtL)=kdM|`V(+lZ077Nk{&eRb10I*u=Z|1OB;in(0+fAS2;+s>YP* z&<(C(pP2E`6{m-_FlnSlN_|qX_ED`Jx;B8NF^L}pVsgl9&+BhRaJp-PcI#B2gV;#l znr>-o(a=9FjGbTsf|)e}t%AIQyd2eG;}tAI_>j_RLXFnY5ARSh@ty$j0*!wAnMYC@ z^t&7TDPorZeA{Q?Q!&gGNqk=Q92)9mS;NlOLwqsrcFO`8rmb|n!@gwXx#CDmu7T;~ zJLQlHfN`n3PRHA31gdzSST+`G6L2Z6u(}C`3bS9j!v7<>0b%YUR+@P{INmIep499d zR+sM17YHFk<8n9_hfkxi%oF|(=gNIQ#da~$$56((2!u5E; z8sL;6FYKH-m4wxIgqYDiQx1JW0Pqt|n0s9?<7(f?*N&u4zTa@_7#aN|gWo^^r39co zw%uD8VNVvu;!-YqnPyXWND@589#z`B1Xm}qn*DAdMPL9k6C4bmf)Qxst#Rv~zQ~Q? zt_Tzqu}J-xU#sGBw?HTWEWC;mz^t?v;KzoI@I!e7JMhUn1ziYmI49be4?!X`)eX%E zqOf%`x^3Hd<*V^wsPvAm3Ye)nmhH1~eH=wlqySnV3BcGhC>QkVQuS=-HE90h0(kE* z0L1bXoGoDUg(pt0zG%72bM4mr5^UbkVWM#nbR+E{3PbCvEu#W;eR= z+um*_RbIRkAi`K4AjJx0{79Bl&Iiy^-uZ=SL0%CqSOhy@v2E2(@~#z3&vDdJXv*J6 zk2*7!5I724&Or))B_Ya(XpV_JFM}tJ`ZD=gxL$iT`uDp{K0(Bap*X=cmho{vQ(!x*5wg>(2{x7RomK9z8qDB6l9C-FrcLtJd0B;2K@H1Dil!tU-V00o>at=NwI^VgQ{3m=qNc07&cTk#WxT`7M}e zqSfbhSONZIshM;D6T;S;%CUT&kWqPrZBCLQxT7#J*@P5K@ z@8A zB6I6nYS9&*=_Wx7UbsBU2roE0e@RzgyirOXv)7h&2L%pBq8oFjiOc}`2j+Yjz0nz{KlTQyLtoCU7F%1e3ba%Ri<%>kx*~J(%w!Bww76Z5b}+7B zd!E1&*0tz%!|s(4C@yzQV9}8#Yku@SeWfv?JI2ixB%a^cx0o}GD zAMs##6m}x9kE)k@S`O*F;@E|bwbMEP`D3Ey)Z(zarhf><16{%h~){8u31&d1*}yvfW-F$112L*(_`kW=^R>Nn!WBF1C9zX zs9|NbV0PM7=t|mhHHGUonjtK)%nL0`j{+a`&S55lVyiBf6a5U3%3wSRVMDoeMFO?l zgIn~A5o*+pv30gj@^}4S6>ki)_tk5uN6u-P^9Cs5mo^EGa1ehTAvk$I=v2$I8@C~azA@lTwAN7D^u}j;2Xz45PW8B&O z!!YrXnE@VxkW7b+k|U{lruh;1ghkQ-kwepX*3$qkXuxn=72r-EU`d`lxq{?$JVcPA zCeL^I!Luiq!DaFVP8vY#r(0EP6>Cfv+?)A{0>EmmGsTl~-m`}(PB;77FZ|X-0NeDS zxBldYQU>f!Lqey3`>9fOCMFk*9%>aIn3MDJae3-Q3~oz|2g?b#!Z^2tM;=RlB|E>B zr<(^$J)L0=nu<>nm#-u3$+qLt9h=e(4~I@#ugO(LKlB#-Sb$RZY5>wK5^)4lR9J$2 z$(}A%561(*Q%x+C2J7hZ1jw7v*koX_0^p?10URGdo~}IZ-UAXS)%F7q81L<7DeS8Z z1y4BF5qkEjxdR@r8xdDnMBv2}m+Bmrb9QOFNVK`d4$n7E2!*gV=A+&|DZogL0JHrv zg*^Z%_JA$Dxeufz0iE6rpQn>Gm-Hbxy_}PaVcQUcBkJ@Qj*@dxf0_*4_Qsi?{ixrJt$e1ZZ3M!U zz_i{a6A`D3jUMg*+*b~uE{|@f!=#>MyvuHQ@YMSN5Vt+dz$E(^JOC$Mx83(+NC@>} zY|<@z!MZhv{S!FD`;%?=b{D{cDuuu!g|2=n9wk2me04!k?qs=?%UVQ^t3~QwCuE)A z$9t#3zc3TQ^5=@>79z1nI{YFTel zvC;KR>f1c}Se^{V zhoRI>q;$5`oN2eo7qs#C_MQr3h8+R47&CR*;JU2;HYW{S13_RKrrlrF^BOg`!dF|s z2dmEUm#M_v@>;Kfgy@*fZS2HfnGFE2GP+M(}0V6U=N^R*YurAW}7 z2^|W)7(~NKJ=ho?`wpgy%lf52RQ%&`2MFnSJYyFNKuDQOnQju}xxT4YE7+C_{z&rjeekS|S)?nEgnLtyDsizH~slm0hix|XL`U?D>QxU27 zlS6OO@ND``fY?Zn6)<^C3OM11P4HYP(1~&B!?MnEu?Frz{>YQY-Sx%uwV^*E3$LXJ z)Dn>PljZ^%tKwsSH62{$-o52I9zfJ~n%WTnk6#mb_nMCOJOQ^9Oxt8G_jgve)^5VG zUiP#L1JnU);K9;55f4*7lJj7{j>(O!S{DKuRKCkIg3%Jdh>%``(k0vZ(#!(EU;_aR zCNNXPxiS`gwBlfQV)OVy&V9HbdDz!7H{piBpn9PO5J@-f;Pl4RHJEo1Rf{tUepHo`)%L^r<}}mlKpQO!D;6-|3in(fm3(Qz%k# z41tCFwU;AO%%mZEp{M_1*Q{NVK-x!PzyYqSK%zC?U4>T1*0lj!Er)?8+^-L3Cb#j) zKFo{rZuyps2L62(-VmG8CQXw4c@*j`Ct<(-T3)xdrX($STYc|6%CmhP_YtjpPBKoj z=XNU*0F&GsVESGi4Bw7TXJQY4vO$=SPqw^*2W9gwlBBjp2D-hDVJTgS=?E72Q^;qa$2zTVeVoBoBa~b) z9pcR8!7V}x%2nk0cF(vS;)?2&o*iw`<+vcCd((@|F*k2vWjLOhDjnz0SOL)AaNoPw z=i>7z&2OGLY-J!-;8GN{UlzLdG+_s6;;mT7<(h2WBrs)sQO2O`d~4T%eh!F%Isz_! zdJPqRG({DtN$GI`#zaoSB^2LrAx`mpwue3BbVl1RRa_vw`@ZdGKr110K^l*h7XoM@ z-o(foxsbQ+n&rpvPMl)`lhW`)wogW2WKpXRXb%GXatydX$H}ZMM!0}2DS$RJ@jGo% zH+2JKq1JgC5>u#*7ubgEti{Z|-Llg+<w(F~X zQv1oLRFjOKNBaf^x7(S+`Imx8WoBIwChYR1Y`9o-g31oSBzn;;}$Q0{>c%@=-C!DC6ykuE+3! zA~tFiEer6+tTEy*6O?CY@>Wru_q2Km2cv#Gc1Cp9Ht2@=aXZSx+z{4@1V7x5y+J*> zNt@Fp!FX-~RO0~f&m1W)kxdU+L>5*E;1b?sg-eaY*@1?VepM3_>1L*8m!u)z-I5!} z?hH($MrJnldbdvdVYQG|Z>QL%_?;Eq96o}hrzSRG3BIQL^GRW#XYvT|YZIdPVH}f< z;pgF?V+9Ds*-|geaqNLRj~js64m^?IG(Ri*)M93bmo{fT?jlB{#&%Xm}^b-i#-tTfr{7N|Ps z5zmC+`!p$f^C&5re$p}yoC~SvZ&j}Bp(C-U-b8Y3AG@JqY&t0CB0MbvcPg&{bguQn zWaAYaBF0oI@+`?j^E^qG=wk^3ydrm>KEBUIJXiSqNUu?qAb)zn6Orf4@M6|?R&?`X z(Wa|poY!+;g~xH(j`?--mQ&OL&ZayQSJRUF6GX6TI@~jgd7fw;D8(?x4)0Uw-n>Y{ z_LY)&Vj50yfb?U`!2`+stOTF>7W667A>f>-xOKoPJ-)h19E4Zk61e6~`kX!g-Q5Q2 zC~ugo6Mg+=GapD41hWcX;dJP$1&;$D9e_u%A=UhN17pJh%y6_`#pF$vUBGo!HQ%Q# zrBdtkREbrd$;Vc!Fr0jz1*h0Yjvatv97cxbKR*BMBA}+;qspI{9)kZz3?vl>D6sZp%wN!~J-& zGsp}~3L#S|qkaRxKb2e}3p@@=HFzxOS;kD`{z&iY$ylG0VcqWRy4AUw-a@eP-Ti%{ z#}@;kr0f24!E1YsG`EZgNpdXwOdcR+{D}JUvavGY8hR; z0W8#m#`TBhwFt@0e{Twr%`3$A#QfS_?u%RAhMV_}8DgePP`?Q}cKLP{H3>GAd zjd|lf0|VaMWKGsaDLUb(7zSu;r|8115csa85CHsh^)+7-QlJCNh;{nrB=ofpm;*`b z*=4G79y8pmoq{{ORl#t#_H>VSZ9P*$osne%sHHJmzXxQfNrCE#Y?aSen?felHfEr9 zRe{@kdcWt}65Er@16@%~@ja=?JAmzikszQP2?~fED7IICaL|)hdbWT!UNqI#rB-VQ z^g~4*A2R)-^p)wJ*f7U$GHLNgonKGfWO~DS_fP5b1wN)QMAxf@+?Lrp>^!=!kV=43 z267iFF`jmu$wvcSPg`Du0SxaYTwU0`)TBHt^Uf~?0*E?I1VA$>UwNy0&_?te9KwaT zwj==R4eaitFkHOm)svMBs^QKVe@#Qc_#e;xNzqUuLs)Hh$WaLBEP?STl-kL=wj55c zHwvwTpq?b;SEW7X`?<~d$;V1wS)c*Y*?}+%MJF3+Q&_fcz&KxokKA8DO^yNE8IHAiO>1_A7A!2ZbadYmqbw^dOD8P{c`Nm=Ny7fp;hK*F=(JY&d(i&O(CYAr->j!;wrSx!#q zau=OF=T?+>SwY9a_KbjC@w#_$gpUyGfO|AwZv;drEnRRi(NV(7Q($t#kj$>|JtS}U zM>=(ASdO{;+||@x_8P;8p9LN(as&Yfh{?2(KeY?PD$p&_8RpF zyyo!K1mak<%xTbo8+_kw&|un-gb-7ht>2Yo5HHUkW_91j#Au_-1> zs(~>j@f@ttl0>f@7q(-r^~&{eJ3z`dfg)RXcC z#RpGUxd4$ZR8w@odbqqNL*%qJ#aQ*cd7M89ahb4W6# zl)EN3795L!Q-n4opp-zS5-DpyhkWxqn>zIip#hvMNSTyFjTIoL=hOww9{$0*C}nb- zjnjhW+vIzkLXmU6b{o62I}SH_*?P^^2@afL?&c|>K2VB(leS|9fc-@@U;$}Pp>5LI zxI_HY;9iNb&|!TC%xC3ET(rr)xa#4xwGMd`vqKH&>}Z~15QgpDP2pC{f#e-reLnDL z#vetJ#N!D{8)gT%SdCsMD9bv@SkcQ*D8@YJ{8j)}~ zuuv_wwrxk(63eJP1NtxfhU4K{K$#Bi@3y(I85OT9c)F+7tItIj?<`aWZ2r66XgzOr8Y!zO#5})exmRFRlA%JKiLKyjryGTo8qT$b5U!VZ}l-Wy5f6zvJ~0 ztdGRK*za*`@%Xf$RUmR}-P{lilf>B^&DTyr*^HT-Uljo41NjNu@KuJ26PPC}2flU= zcEi)wB1E|T}48qA?g?_(70;{=kcYjl-~&s ziSze@U+MX&ta1*Eui|#8tR3-3t9q}OI4>&vdV-T#T)XG8V>Ae+MSuhJlSqOMwrytb zet3y5WK2l&EVT2rz%_9GAgGxG_u-Dc>C4-Tp^)Pv1f((<($tWbtWD$0^Nd%+udlQR zVi%cs*d`v1m=*@@OW~7!OGilVSfuB{d;5m--CNE@b&ogrl2UVigUkz(kcI}nJ|5x) z@)Az}3XZ2E#-dE{^?XxkYuQg`$T`;?IJUiXGC2X?{KtlU4M>CGcc zL?A#hf8Jgv%$Cpg=?pQt5+ZHaQhB;;v{=)^ zD8xQ)``aZp{c^Fj2#iMXD&_-tH4@~n7$~T?BQ?@H%*~&vR~iqdzsyCH9gg#G>h)8P zdQT;mfE8V+sIy@!@N5cGo}Kf{_G+KPFrcry6R_q<9u)Gqu?7SYS7qJ+^9RNl~D?d+lyREQ;KhWR!~h`mq?lj=MK*$6|Kin06!cEye`$&v?h;% zp#{skATL_nns21tLwVhoa>G@cc$q3oChilMbiv)esLQAbjvB}#@eG9o^Y1hj*Z8@4 z^U>&t!l>^+Y8?|BMJF~1e5Yi+UM%S;liu_G1c$k}DA5x#<+^w+?(3Zg_sLk~?q(Q% z22{S{Ss?q{Ch^VVvTVRkKwO2lz0#4BJ$2ycEHXp7l9hcflaFFEAkX#j+2%dmdqkqN zs784}X*9|$cRbe@1u9#(e0c~e3Dre>SVO9a8Lm5q)?n@y8j_d^(V4e);V1!5k8<6J z)HV$3Xd-j#$am7ce)HTpf2?Lfq=qB%Pw~DgFTXm`786}CZaz68Cjh5jMKoh#Y(RP` znQ}jhZ%_40CllT%L}bmz;ZzK0F3ElVqQWs=T;~-oJS6=gvNbnpf+f1?CCVVB0Q?BCzULH2lvNG% zKZSmPdIC2DWPYRn#!Jd38oTC)e2Ky$(Wcr z_!VnJe6)#Pc)I>nMR~u!8pwh8MWLfKYJXSHp!VR9X6D@Tbl0`klCH zcRR;3wtHPV*saCuMLz<42`?Dl#i=#tghKBj56?~_=4%~|e#&bnpj@Eh#wQsxjvc|0 z@HFQlI0jTC49S_PUt#@XUSxU|Zjq}^zRHH9h;$EC#cP$G*6aCt%AHij^1F61FenYl z6UjJ*Dl$!;^W`PXM9y$s&VZM7n2^Zb?knUIdan>#Z!N&m5q8TAX>)b~%#<_FlLs_8 z>U*yZ7Qa`eiVY<@!>dQa1UtVwl2e3>&upNczn|Nd^7vwi-4+!xR+=jZw^Dx!NNsZP$c@sxVzKy8qTDbwTsN*(WPD` zUJkZa%{1_7JNz4*iIM`=6bBO*{B1K#6TUp)-hqpsjM-SW+j`y2C&$H<#^H=F)AGt848ZxM-!Nk;luk)!OWO9;shrDInNY`R^g#Yp;C86d>j=LBKSbb zmcj3ga?e)MinWf1KuT>-$f~D)>t{albvUGvG{d|zMj5&i>0Ev!g2%(nq z3Y9)A)K+8>-$Bz7y7GY^DpV&cK|uvO7;?G0`o^$NnvLZQgkHy|Z zg``j`e$qOL+dP$uchQ-Ex_P72q4syEZtBkm&sww9_QTnpcoqu!IX_JNI(+*jek6O~ ztv7{m9oI`&rIxWH@n;}K6?%DeT$hNf>19`yDA6k$E(QUbwmU;mkllD5%po9UytGO6 zf@mgeWx!zP?jvc-E(9vP^nGYZ2^hr)Z!BD25HFV@cGgd5W*rKd1c8#oppygzs*$SG6Ga1!2UM>M5_i)t$h#p= zL@PK4PDw6ow9;K;!Qe<6Es)sxFAh&k(ejQml(WpN^pF4ytIh0>=Q+*M$OHR|(*WsI zNJIL~QCa@OOYxF!cPq~$bwhq$8c39#j6zB@lv+5>{b@()hGJBn&xZmYx3pL5i&m@GlfHM+ z16~NJK0q@gl@yM5xLBQPih5U>=t?)`O_+2ohbJvqqDd;F{kr3jUhVnWJsaeDrh!6G zjn4jQVnfX$+fH$U>vX?Ud1{6EB8tJo$~-*LMo6+g#YlNO#N+)uznOgR=aP6F408(I;G2$GG7%-lnA^WpZvTTD{_42`%n}a}G?C z;>Agx<($$2%o4k)ngE&sp0A#h<62rd#;0&bKdZ~))y3Vv$!|Q8x7!_hKN3}gv;w`s zwGFs6_(9VEe(LcIyjN`E7{0dcS2_0{Fj{i6oA|LRo11b+Zh(}4EJ~u;MOau9@3vX! zj~qCasq~6oj94PcwH|%22a^7nxIDd-V|0T-H`R*UrbXVkak_7c`9=1z4=Ve^^pKWQ zy*l=Ir+2?`Y-WDez_(513&)DUYuua(ceo^2o1W{N203Yv09N0D_E%VGrbH%BG)EZY z9P<%Z^)64{yRM8(ha9JmAL*7LMS(0;VIPoc=DY+JZ6G5u%rM?aB!f+`)yTE1p@a(I zl}e$IvM=D^3$%PWLh02K_e2%IyrGFFcaAOz4a8e;66y@!Kl4kLmosICq7UDRog!w~ zK!KvwC&e9mTrO)yFG>RiMFc#z6+%2#%bl9lHcx4&8KK6%t*n}7oTEwg8~!GN0E9mutDhO0zze@9WyCva#(`b4bUrhA_#Um?-K!L_GYAa{3ABvxR|cL& zdVaaLUNAU@laHk%4p+Pz2P&wy34`byYrmMOdB>IB`J|yJ*Y>K%6v(-h-}*!8-v%Rm zc8UQd!VEW*E>ypq-d>-ccx}T_P;du{4vt8G?wJ}0*7f+BUZqzj4hGe}V{71NyKMF7 zjnC7Gg{0|23Olf5u;BC{yBEh2@^O3Aro)F9{8UT?6TI7<7=TP&p3oy8$C7^MN9%oa zz1y3BHw8Dx;_ur7i}!O3k$lt6^bv2oJ5-0pEB#irl2xO3++yDR0*~$ykpZy^ymPt9 zk&`R89qSHwKCXGHPkfnpQkTaN!<)c|yMS=SRSO>etI5Fgz9yu;N~~B*2D)zlEKNSY zvO?`x7lkeGlI5;Ay#Fg9w<4>^3dJ~3})p;pnwS&Vvf>&+XlCr z1!grt;l+?i!UM_Q63z!2wTwIAR#><|4%#!;*e}pA#*O&J0#4D0Ua{zyr5$PA9meq_ z*$D0}tG|IVjl9&Wgqhg8b^HdOA)Q?47IYZKDa1v^F4nSbY|f@X%)1QE>oJ5dg8wom z_4V+35oVdRzx@*)tmi({TM>slzuKlmt|~TpKpm&fMRoy7`^uD32#wh0xv3yn z06bvBN*_u_x1D2ZkS8sNT(Of$8QImoHqQ_~mZXqTh9U-YQ+hD&l=TJBi1wgPg?b0R zWQSSvFqffZD6Bjh&rV3)TpG-QNUo z4Nh+1>l2m}CUzX`MZk-c*MSq+S)MK?*oHv7IRsL>KH&V&-N3$Qt9Pp_6=?S(efns2 zxy#wJrMNhiqiV2Nio&S%ZuS$S;r#|?C-erPg7emF2laj+T&q5*S|ucZOV*Tyg8{7L}+@OWYfkI}Rf#Bs87j(I8PF4Oo zoIM;iQ8p*cKJ*}%s|Uo&h0>UInuh+~@5oZZg-T6%=nzXL5!?pJn3=PhKI(-#LRwJT z-Ypclkt9#?**S);qJmb%%NsIS_TCF_VTW_dQD+bQ%oAIzd!n7_!B9!)GI?BxQh@IY!q8tSR%9ljA4%3-eXOvX?(HOG(_$bxyg!pY6&^4#dXtkkDW8`^3 zI*-qSj0hi!W%d>HhTIl$zQ7Jq>@4c>e!G%94-@0q&M7dl-Yo0oj|9{s^QAuUuT$uV zWDzBsCC|WlJC4RGh{UzuQR5(8yc1+;q|<8e-1-2u@J?LY*N$fm6ENp0@Kmyf4oo&o z8AhP%JGGF~8ImNpOHMx3&tSP8sK~xr)|y~N6Hk zN!vaVUie3Ox-b?|0vV^7oRYqQ2BMm7a8W-5+n|?kHbSF=;FbPofp=vR@ znzW}jOO9mi+_xq1iA*Tafa z>SNoa;EnH44x)yZht+dKaSU@b6qzLLo7*tifyn)keJ-j?-_SZiXwPW7Q#5iOs5+#5 zsu-Z7`H&QNK;xvkooaU8^(bNA3k1<~<~UtWV&c6S*Xx)EbjeQOM+yi0Ahq|x{r}jz z4#1}BCaxeuX4&{5d$01c6PcN9nlw$@v`xY&SxwUHJ<6VC$&{f8g5m<%GGt4E0;DiXVN0QPP=}90(dEAsJ zyGR4sBp&scS@AKp6qY?!1EdH}5|X4)@?$&_$O0iLE|_!4Rgp{_ zjulFbDNrIqk5cJG9t%&yQK!m*5eW^$Q;AF;&&-4%Hwk9s3coi38jv9heOP66<= zzzR^rR)s7!)|P5@!rV`ifd^%27J-$`l1I?_Uadnck3m6~-+~GI$oY`vL`8~8@~fihb~?DT9J)BxXK<(}@F|&Y zrX*6pj-Yx)TsPUSVMGbhT}u;-sAMi#>ET4{{BcnPnwM*iuzDO+ae|h@aK{Ph2+uDx zd)!ejmDL-|Kw_MF0zK8@5^?Q9C^Uq;2SlG^VD7QY6GurDvY=d04F&%+j{rQs7&6PK zS8D93UZ08Ou(A}4q$mz#uvk$ZpCG_)MHqGp)5_o_K?$iMNvst>Q4Gzj(JNy}!0=bY zxMGWo=Zp|*sa~fDB{i`44qp`4>Wmdz{Cu^L7sZX|Lv>(eyfVQj7kVNgDuXb{P(~d| z)AA`P@(8|4B_#-*R(V8#^%@VzndO}&MBGC{Z#Wj+(B9C4~(^+J~ z02YNjj87ixgQ%sMr2|aL(-93kb(BS5x4Gp!yHOFtib+akCXo!O0GTKntI@#*dPQR>oIEt2>MiQC~pv@uDHC@Dt^pH5F#l2l%mUJ)ga;?QlZB)iZqjpoN1 zoGhZ5O;M_uahfGVN@TZW@TTz;aI>57d?5yN*S zt5P*Wk;p+138VciUy6iBN{MIMBcnAcOC*b+NPsc%Nd zGje!NPoh0u&5;1Nm7sQ|B)EhYkxk9F)3g9+cm{Gb#{kK7g+?9;aD^pT8F)fUe2glA zuGjfhB9b8v2>0kdhejD8Ylegi`l4y1+5%j6Ts+1;Z zp?v_bgc9u*zg(-dCDM~z5E^jB+aZrFW{9FwsBVjj>tadBQl%qB$PqFGbdp2wktn?k zsM)f~BH(`V9JFZow253FJ%W=8f~V#2lOpL72(eg`q;UqnRtBVIpa~`U6c(91%FmBC zLrRuRh=akc5Jph4#gtgSl?PnO#3Z5&P_i+`1FsXt$;2T2ESuaThXP9i08FjUVoO!a z?a@?Qq?!vUlNdjui-F80FbXUZ7IZ)Wa-AkYrjNBN9jrvP6O4hJL+2#MrTVPk@(Q5D z%)pbGR3wD1LXoD`Y2>mTF%p>N3r3g`!%0OHsUjIwq((8YoEW1MI^)gIEJSZhVaxS; zrw$brqrglNB~TOMX>bzTOc78cRjElv8A(ox)u?20KQs%GxUFhqY^>SKb~9~6vMf;>xKT7Z!OS;Wgf6ux z$stw?4MYjl9B8a!6+e~lbBf~8eV3%A%S3!3pAWExL?o$%FtDBCaGN|bF_14(wM@29 zs6o*5lZpjJ5*!t{Ef6Z=5u9?c^M0*U5)W&v;xcV^pBZS0=!W8m4FXL>swE|f%akQX zNQ8Pqq5yGFMLH^EUyQL_t3wIAdV2yt*5@K5NPz+5pfCcWqvNNl{UWPTBjXzpR}{(4 zi_m)&%4mdYjU-0XBCSTb#}e;R$41IMG&*pwtPv?OaulE>@(?J+ppqF(SAv@0iPzX@ zWWSRL$#w|}@jXh3jt(QzHBz~mpm({!c$y7Hc?zmRj2a>0^%|JKQHC>P7)FDJ5kt{M zLVZgjo#9pkrPHM+u$5}6o4^)P#Z*ePm15$7nHR_s>?B1J(dADCZfz>vVgSifxhX=q zK&;bi2~xc#4tV2iw?rvQa?7Kkm`8$MLTNBsB7`vtF~e!K#m6Q&Z2^$wNfZ&-Vq1#S zhS-c=iQM5!(D<}AYou5ub=$y`W)YbP1J!bLvzeoS%8EE@Y_um*8c$UkxKx%NaJEqZ z6CA|x5)M&ei*N(Rk)j|-%1_ZzI2NesQ|stjL=nRWR-sH|0R{!1%hg25AWbc2GZIu* zmr3N3=$saj)#iv{DG)-eBEslT6@#nIQp;lH=+)ttMgeUAh3^Wn!c0h%#Ofn~?t-Z4 zrqoof61wQ{5@I-%SUvig5wn!TG}?#`JJI2l*bJ&zEn+5XNIFttN@@%zk{L-P0G(Qt zYDyKkv_`)o+C)-OeR{eXf;L2tRpWD*%}El1%>8k83~D|NJ$Kkr;HM#O{{Up^Wy{cj7dZ>5XBOW1S{08GW2L)2eE)-GlRzRIs67w zYJy&o0RA$(8T3>_h(5NDVz*jUk#Y-z$~Q!4X;P2bXf{!(TtX}fRo_&Fi7wTPwPuL_ z%3KC&5*lsx5xoq$OJH>q=pvp~U_#Z8%xM&mS=6|MBs$G!_b3TAF|_amkA(`nSt-da zlh{%TOeaO5Q28QRQju4wPIAQQbZmlJD2ue&1$I=R)fSXKmq3%+X-Z?H8B!n8Xn~t= zRwV?ee15heC0dbUW|;kaPGSPVlFC$2U7i>;(g;z18c*+ww8ayZ+!&sn!1c$|lT?AY zcnVbWxC}CrLlu`41K}nfU8%4OrFsj`s+GFf&11T{!hV7xq<83yjg~sKIxF%Mt2uet7a1PJyaWdkfsjf&G8)ywF zQ7L??SK)Ffzz)N1;>GFx4nBz}BeB>?iC%G{MSx~pOmsgJ^a77b())-8xja%JRL8|J zP$kNe5xfdXgab<5v{q$Qsu&nwGBqD{K7G+-kw9T*8J!#@LkRqTlg5%nB_=Rzz|-PD4syC74-`cm|(Hg;Et&f+baLj`I81evURpW>7{bsTPeoPOXoZsgvaKVkJRo zV%m-1%*QyRq{`GdFM(&#NSsi(sbEq$@gklB614EG$PrGDS!I-yB7kcsG|Dv!9o#(@ z_)%839uY%9Wg>!*IZzf%jG;y#5`_+GCw+*L>9P7{>PVNvM6~)emN;X)g6`wmfGL2A zv_=Tca)|LNvOkpz#({ulJXt=cg6FgaNb^32RAE;j@zE(vuOyPJrSlUJuT1GdlPJPy zGATk#q{Ttmy;PWF^(1oRO;(s(<_3nml}qz^CD04SDj_=POm3V_DTGQ)9$%FtNR3z0 zI4pZ)Txw)ogdA{z&=*CMh)q70J%R;c9tf_K)Ho9#-h>tz4LXO#mg?AKMS`9Wp#XwQWC5xr!!7f2oou_= zk{AV-gGxS_xk~fNya8IRiIYMzMOhUb)DEY}*%CX7D~vX~hG?ZYxk`e@A<-aoR0;CE zI)TfKhNOAX@NGGqcsnK51FQ~sK`epIWsuZVo5*eCr$(wZW^01N!Su$Y!fHWr9>W|N zOZRdpR;nS|Z;VHP#vmlPpPEyi~n4CW234vdBy^Q>ZrirD(jE>jZi-OabRh<#9BT zpKFmhp=8!=aZw0niHIl>DH7dA61v(kBqV6rW7km< zM9@7(F6G(d0?9K&44npJLU)uQ#X%DinK61R zpH1gTUGWSCg#fOImI4*Y0-ByeQt_1{fzx9oxa@4DP@V)K+QVfQo2&OY*`{r7eNke?YP(^wUQ@cNDL_gI=oRtfc6wm(tiA6%+F3WNoyS1w%Q$8qN6%X1CEW>k!i385RUMcZk)fFq?r~{(_ByuFl`luz3|(t}Nz`|1I4U z+g^dOMqs=*nV4g%QQl;Tu_n-P2@X-TIkOEy)hq#@Cs>-yHMXZhWGh}{hjs|>gbJo2 z!ie4gu6iXx1s-Uq7%@oLfwxhN@GTG`M$jfRFyR|c=Z`Lj7_u#llW1QNM0G>ETdDbiAOd;`9~ zsrWksSl&E(gd2~6$=8J+F|Q?nDKY361hneH5N7U3YxG_{4;19xALv-MLIghFmUyoG z7Y!A0AXGF|#AW!6LB-<4267_=*vyuk@Bjg(z~nOzbTT767lJ^@CwL$6O&Yv;|6uk@ z!BI45jDi8<^6;O0ABX`i=Ln&fr)C-#mC~ z@Dqf1zNjDz6-sDcO=9Vsz@{K^(2ZIAc!pgAA5Wo#G+WS-wW8)Z5H^BZQ3@LP3NdX& z^u5u?ct9h>4?qoIh`}pl!x!A)h5K_kT0Q@G)e;=)iv`?}a3Tf29A*+bV#{pT7@@0? z8;ez8h6dkOp#ilQ3u16HKX*%aBw%qd{OZ_4{6dzL6o&?63l+SgolN{PaHh%o26qZ1 zee&%Tp2ZI1#6hePU|i~*kdA;~|MjS^kWElrt5=dy-l};T8uM$xzuZ zj!?b|RZK2a5#stMHvq^5^@tsX{G!XOhE^Xz4Vin6&|w(@y94x@^=)>0oRS4MCu#4w& zG~Q02f}yPtseCn70<##oK0TO{oRm=EvseRGCXhNpv1-sIf2l-LaV1PmIo}_9N<~=|C~9%?ofz1z@xA6PK6WbQwX3Ug<7R>I5qYHkScd8 zpi5jjl0|tVOGNlwA?|4*k=KBJe9b{sB7(ABQN8P#Ev7tp9UZmulvmAv~FkY6&IeR^(x0KR1XqbeSpmk>$b&7AmR}hh>!rrIS=rA9iK&L|-CofQkUJ~?h;FRY) zo$mv^y%BjlcUhu}q)=AZe;kY#4YA+$O^ohu6tQ6%gNTsx+08ewZOO!N8UpP}p{|ht z?H#a~7OqF$;%$q;l#<-G&%u|Nvl`+flrC?$aMvHrN&)-~JeiAJ^3X{0xzRbH>2L(0 zqAvxQBSYbFIDuRQ27)ui8oS=4L0!OLpdq*w3h|ms(kZ85Qc!YcpMc~u`}9|7_6ukX z%4^UVknGQgHlXe*FTj6`^#X=l-sy$l)<<(qA4**M`?5kKAbqxQPWTZSl z(TPZa5*=(m6(bjuZ|9W)q7zQ%4G|a=7{y~m%Ulu@H}~j&oapp=V(Iw={vVh+blexJ z6N-+p;Zf~>4vk+4VFbzr6lg6E4sSX@Ktz= z!vWa+EX0O~kjhGe%;tfLJ{4LwYjQxMILB zIvCF@mN_n*i;v4!0W19~2yO@?AIA)X2(Lt471+-m^X^~l+W0clQ4^dt9yDl2|zQQ1lE8A+Jab6-4ot^p}+}(C8X>B=8i7;_$&d)qy!>? zLV;x^l8MB;763vubQmN_h2^He!sBU(kbNGo&S2!pR1$>-bJ{UY5W3Iv8gL9Mm7;x) z7g)V$Ni{~J-s*r35=B)^7N~5?r}t?Dh6biwp`~%pgKouu2!)GHj%=2IA;`bPz^@~d z$dHOhsmK8YUtoy~o>H0?8AFz@XOUBA@LwT|3`#!u6L>DP=TgoyAQ+`W0MJMtEOY@N zfMp_arH|qS6q*w$BpPTCDt4Pg#0TC1P#+aKG7-pB0+otKu0rMKdFPZS0m97Liv;MU zA!3Q4fmh+=(V$rnH~@6i6M$wFSPTpo02=V|2~eH}L#qJnkG?ccOC*fTRygWQ_Qepy-&oUIlBPfPqcohNwBn>))MyF6I1OV!Iup>tRXw+~L zl}?AA$uv3{2l}DwPX!G?16&BGkp>!q@;n1ls-1kuaRel?#Fjr~F^TjNau8p|>eCqE zuu61{V}P1(fXItAP+=w&;=x*{yYGE?2F{= zUj`^&u;2s&1)Mh;QqY(G+Zewz2I=tN{}7aa%Z>Mk@r7(}>}rn;VY{m!{>$K6Q!h?huCzD7FPMcBN*wlS#0AL`c2Ss3Dm( zT(Q%L2%34LG6E4d2DKoZCy>JFR5AgwbD+E-c~@A@7Mwl`kw{|zX%hWAsK!du;uj+t z7xcygc(6FO_7&t-7zi~ShPZ+|M2DmqBVSc0fkuWrD$I$(f3VvevQuF#X%Jtfz&?gn zaA+bnxDs!hX2w+1i?(XX!SbRrECsD{;RzKym{k(EEdQ!PER_cO8x#NsSdKJN-I>O1NJ7;A?rnf^a!;8Qlp^e z0fE3d$VX5xLexaD>~yL3!7%*sBGq3C3^g4xkSIG1sB8!wCj{g`Dhjx|V8g*t4!FxN zw^RgjI2q75B+!C?V|$`BZPV8pJu5*ojmuccMnnVq50oz?u3`KYfbD`-`Z=eRrZp`_ zQ0px-(j~asn30A?t3>dFfXfIpWD<>z*LY(J03u}s289Zu0Q@#8@Ldb2>cATy6e10w zLg_fMuxQzHPANsAf;Y!3T2S%UMoa;j)Tp2KTvLJnD>IV4Q%a_1?$33Y}>rmU_HSkN}mjU;*w70r|;oJCMjvJ3YXbM{XOm?1nfgDpL# zh&tv>nhu4DP$7YNVxf{uq+puAG)ZzXqBbvYjPi!^VVHs1;=y_)oXhR?lF87(fDBv%y0 z_XTnmqFlgD6j<%4hyObB?^dLFENSBxG!( z1!Rhfmx*A~hR?kU(PfZjA{Q16!}MDzQe}A7eZETNutJyxh0lt9!E`7b z0;1!f^J>|=+BB$D0@{?s<)Htesp4c^~E z-0Tw6m}tRjKp@{%jfux!FdYd!`!EH7@340|GM|owJUcCAQJ`;Q` zY_4}9p`2n9KZ*m-3NMp~*}a&-!=)B@H+V26#I1SW6!v^}zZ4WXQ7|nKV!(6VUDTuf z2TlvxjXq!mp;4GDU;`nhj@rOtG!6?7PP#ztBlgmw8sops9SsZX=b!)BKL7%F0anqj z6COu-OMw6xZ`g%zPsrt!kWqO)+NUD=b6 zFnFvcA0q}8=F&J!;>C*Sx%<6OB}1-e=~r^yJ9P*jo|#zTR}OR%G0wV`?#(V#4* zf32wCHu|j-m0}Q{iV%@74-pi_g^>aCL>%*wt(r8v zAq6xj4upktg!D##8V>J`U@lT}|H5#!JUjUSnFV(1m%0IrqFtwHF65UmOEKZ7W8$2vFNY zZEYyAU14|PwBgXC7YzBaJ9#hz0dq%+$1cV_&Cm6A_xvkU zDcIh|uM4AL@?P|9h+`JI*9VOV%QLC3juz|h<*yCJ|DVoGUZ|hr}f5;)$qTeC# zKvpc1kKUM)PYO*tRV}O^~1K z&iHp~0%{>~ea6296A-X3@=g^5t@%rM^8pl)-?r!IhY;O>dqlY^B@_?^t?J8^*AyQO zV1cs|)B*Tt3fxR0|4tnM<0SLv_HrU&IP7_A(E#2YG9;cFZBgq}^co->AdqNx=q+aW z%>wy1l*^!VI<1iQgI{^@N2_=0T*`1@D8K`|#nBNf`EbBP?ALHO9B#2|;Rrb9z+8ay zV5*fFJ)pLz(8rpf>x;fftygI63KRM(ypEWRzlqwe@aQeUZ4#ocoEk4$n-Y?5EPenM zF01z|lxUhE;FMU=slf2nI4voxmJ|-Wt-|HB1X&z`RA$~fW2`tiw16Hv^xVx{fVNN^ zfc%^i5J-vUh2qeFHFzK-I7`K|M4|a+Jcx^nZm8pqz6Y=6i$4|?wqgT)pvW^#-oR-@ zL=O!Po*&r2>*PX&u)tE|LoV{x$@~H;sw^(o;a%d@;!pY>^ z0&5JHm!@SYMy@3{dxBcHBGPqv(*MPF8UjUDg>JsQvViuj2;Gjr98fDX^b{4km7y(w z8APz?yo?2?406Ck&rKmwqV!4*9_Xsv*LJwrGd3oMaN(1DHxLtnV|N67m-C zD<-0)NzAY>_9AogUnRf2HfaMkf1aP06}H0Uu{6mVCjKvywf_iN?zM>)iI`8eu<+Ku zPmvW?1(nZU76G~bW%Rn&CSx$oB#-*S+wlHv87t-b3uiODNPqp8`FO8Q;2^b?N8n!8 zUgmj|QV7oQ8ov;M6GN0G*hMy&tiv?lXv0)G5JFN6dpBxv3TJ9Swh6)Er}oF;4DNu_%V<}cxO&ZOgQk? zqanh9XCO+ubtxFdj&~}YP`vg|J_^wsATckaJP7!t*AM}rV-e`mEg(4@&k*f_*Hs5P z-644L0FGh>+yShS^9YUys<)%DSqP!k+c`Dc&uf}j?03gMlNA;%7ZBxqB53a35x>!B zq85siObW=*L3#`^DePLkxnrP|7JUw}20QxUPbe);C!}x#3ErINloq=hEnz`l5Ykjx z<+9s>^`NpCE%soSdb?KHhKSPR(3bU~zqAeZTE;&jew*+wffPurKg z3tVDL*dPo*HVD>(#_5B4rQ9n2;Mc+{`f~&+c-smb2C>L{3=R}>OCa<9PELG*q(9s+ zObh}7_ZG;B4NBK@ivPCVX;M*!boSRn+2 z*dUAcPCVX;N8#e}GLrEhSG`2U2BC+Sxp6?kdB=3aeIYOdPsWdQRSP`rsdM7CF1m!t`VzRh3$xglL9mnz=;CgAm z1vo4i7<`wL%9SDqFw2wi*<~fAfkWJ@T#Q&^Ec&9~{ht;O1qWCCCkj!aUpF;hA1opv zUw134^-oB72%)g*G8zP(19ds2r^g2rH3UCWo&u44;*r}=25(@bGFn{F^{l9#Sh)?f z&~{UKI%J`WCbai`-X2)bYffKC8!UoSLC~Pb@k*AWYGu(Y<4y2G$E^kLLujAM*H-P^ zkpT7ax!uy}bm%!A5EQ(-5e2LB3Xw1(AsinpjhDutP3Uk@Ekz=RcbqPsh`sinA0hQW zs5ns7BqFqjM5|!nAz49ZAS$%hrwH--r=$Gr7O2}p+fkA@XeTt({-C??jff)>j*y|n z8vX-y_*fGfyw;jX4rd^_%^1jq_o!iDLK`ZcXcI2{cqtN53O+Y6ccdiOt5LaveixJ) zy{oA#wAwa!@HsV=Bp`g@?OWKKg7634FB>d-etd#~zM3Zqb=)EGma z&*>Oagzm~YuaKUTd5tBi5_r%=^-XFg0<>brQA?;jEJSPwrBH65Pz6=&dE_SOR{Xt! zTs*j3s;L}!5h8rp0RIFnPKOW$!bc~_rNCTOh>;^HcC^JZk`UJsBpPHH|7Oog3p~e5 zg~NFqsC*a}YqwLx-Yf1#$%i3J#kL4Ez{mxW`5z zVnlh|v2Hy-#i@#iw%D?c1zQ{hKVfc3G_mwLD0#u91|cX>EQNtf0)wtnk&6K?a};zw zxyu<9{RY7z_%8HN--Ur-js0-n1)6`6DL9sdf8P#QrchBV*y1-%qfkTA97#bN1|Vh) zB)mgABowZM3Tf$Hl+*g32(_Sg9XeLvKP2pS=LixED0bTr(*bR2A;*9D0Y(qwY;c$bx z3(_mK8(l7ANI9;Ab2-{S`K0^VTFA z$s5es^)iOEntVuoy=}VYP?xr4R*&0w{dnTZez&6;=cmMXN$>Q_rDndY?X4XRuJ_}2 z@ATJ$Gh;eU{ce_jNBdI^ENh$ge{^S5&x8H%9f|lh`il#_S9)(Le~|y2dOWStj&j|f zWiRVB;Nf|qFH6mjiJ7)(Xoa2gruC7Fmrh&sFr7n;Y2Gnu;mif{pW7whj;r6O(f)3g zqn?rdcXXEz{`3XeeEe_&cHOpd-yj?1O|n+O8m>M!NpSA=p6=5IK6{enzx&tuyW>+w zHJ|WX=T`f^yL01Ia-#tc{_O4VGNDZ?|2q8Eg$?U5r`f=!X=^+;!k20HR9mp`$-QGS z^&cFB+ax~t%cKoQ_&2T{Te-7Q+SNY~Xts>5)AiS;i>_uiA3w#i{^8cNkB7a#eqP;b zgFhmrWd5}BWV^6%xUG{P-Mu2Xa`30~Q+t{xj;PvTgy5U7-k(idKdD|u-vO+~^LN#& zZEv~q*7h-I?Z1-d`9;0ieD!$y|=M!^~^!tIH;5ZCaZ_`k~6_Uo;w+ZS&pS zRN?%Cv*V|=p5<+JM7{Kc=cMoAcDOII@5&A>?5)}VeQaBPnn%#$vvZccX_sdYd^)jw z)&FH4{Hf>pZH)&`N&HEE&5Rg)buifKNHw@|2nWNvqE~4`R5i&eu!J) z-+k?q&e=CNpTDwb!@WjB$G3ghpqi~VNjP16IilyNnk~=49n7k0bGO_nNZwvqiFCix zD)EbFe~xUtbpQH@hOQ|yeHUgtoN=I6np-?@`i=_gv$J+)ou8KM=M(weFMTz1?I~E2 zl+{-ju33AkX_9!8Y|Wn|8mRZp<(`}!wpp`d3STqT-m&A>>Yuewy7zmhgdeA@g{5Bl z?CE2{wWB{fuFV+U_RrpfvpZJoZ)G+acw^oDKC7QTx-w7nZO`cKZ z>Aho?-{-I^ScKl+`K^7XPwE_8AR}3x4w}>E+TkT%-<%;oQ}Kg!s+uuv@1>3E-6N*^ zljR@#FU^q+8K<5#=YEd5So2Al;UluUKFhwn&RV^GizY*_em%b1C-VpJ#@288?D45* z>Jz`XPHNj!v21v9kCilVP5XxpB(YIX>xS1mxl}VIVp7lHy{Cou&S;l@5;p6Cdpi>) zM{g}u`WUe%zubPR_m<>Jc7}4|hH{KkOR}h*>&F+I=y4~e!-XHN_2{wvRL0slUybPB z<8I~4Yn+$kEbm|3+Q1@Q(0BI%-$PO5FZgwzrR@5=Wpck;!>csz*6ZM+N0PCgR8=Goy!a#lKtfJ zceA@B#PN6|D%3B#k!m`6?!6mBt9P5wsH@*QyH>mRhK#yd-B|V!EaTce-5;K-#khA^ zwd}g)D{DrL2=BmU^IU)J|Ka2fV^bEB;Jzw-c=u59JmZn2b`bHMKOgFI#gyzBH+^$P zqpg|EM}I%Ekw0?xCs#VGKKp6swR^r3&S*BYeAP+($*s0$KfJx}PG*BcVc*r~wwM}~ zMY~G!nWq!2Cl)IDqOv{q)AcvN0b%I7Zm^adX3=g?E47eDA2ClYZaa;r;F&NXi2F_U}j>`{3(E z8=m@qv)^pl&368?B>$nI*xBVmS%s;n~ zDu1o+{^zh-8Iu;A-8!yTrgR7I$&d|{R$^hb54E@MpBg9t5n8wDc0y9`mZoDXb`5SY zCvoFAq`q)$#Z8;2saabxb{_0%`s3ty<%oN#arK7{Q*RPKtNC?jS>>}MVWC?5I04?{ z)a{=A1}&ZY@s>`eV`u$GKe;=WDc^ACcR`>2vF29$AJjco{Z{o3vlel_8+jw_>uR6X ze0Hr&-7$%tQ~g)o|2Vs5_txXrrQN^x*QuY^HW|37{IgBpZ{F4@?YAqQP1h%|tJSFe z73{p*{l?wUrPXOCxp_tiit0;7?Kz5_^%m{g7JqQgC#|a?_2-H;D=R*s)QWJAUUgwb zokv42|M6W~{{|Xn%N>czqmf-)2Is&*8;(2wh$arm_WlqzZ}f7@sgpg&I?tZndb{$Y z78?%V=%Aa_ZA81OagKAD6NfCVvq3ZF{_2afuB_YEWI!v?%uDMgUowoc2?i>6Sp?yG z&h_SXRo!7MuRg16wS9`l;yQ5);r96|vE3K;CdoI~YtxzcAbk#dq<_QN%~OVE?|b&u z#&S0d3s<*_=vrg;v~IJg!iLNTJ@(!_`K@K>)zO+eF%OU@9eBxH+41|4&H8_!&+sR+ zx;X#Zzdfz)wajat%e170y)O6PmUavD{ha}=>k_VI9&CT3Qri0W|6)AqbyWP5{O7f{ zigel1p=rOaPj14$sqZ)0)A&hsRh`&RfO!zgUVK$Fn`hdqqp04IN5nuH`>)zV{SFlE5~mCaL&fZ zvk4Vd<+hHeewy~%2;=&Ui%;sBXfzeL_WcSdW9mi6f3b ze){-^qsxe}4}^YE*Sq@{+&Dg}N!eBnBErfH+TQ5{(&P@UG6(SF6Q)Uj%sj=JwcT;{ zv%#B?3T4*a-rae<=F;)i%Ob8a_x_^ko3$z9%j?>(Js*cT1$rKq9MZconIb9xH* zy($|9Ww+e@v2VoUany<{$9I2vxOq9%jL!A9-Duj5U!7HE_QvU74f!Hr`j}K_7=N-G|rv9=iE5zV5Vg8SA)6R_B&h0toUh5hp~I6je5{@CHwUKt4Bx;-ap%F z%rnAAKikrK$5kuy>F|-|D%U-iIVxdV#_c+^u8}=jiKqikYiIYrVCuQ0v21yz(VA*= zD#dl$VUC|>{~EuY4rH)rD58R6SKA$ZZFBK^T_|m zy(aR~)bUTR9Y{*9^Qf)C+;i{(l>#~XedE8{PF?-v{cBa`?q6X_YdrbT_->CP3r-Wj(va`m7!88P%@;C|mYz#Coaypha2j$d!5v%dw`f-`43ur^Edp zUH-1mYAd>`SA;JRWTREwa*5)xTj-_l)$Gn>sdmu%N1?_K55Q-RRz#b@z9l=NEpozwwgO zQC%OK23~Bq>-wrD%We%myY7!w-6z_n3GNUM4kv%QqH?FT$d#MhH&*$)Q`kq+gz(DI ziTi7Co)W)pwrG0i@>yxTy=%68`uNx7OE}vS!ym3$_QV%vR$Mu8a!=SOqoy`0MwzWhd|2vpl^v<$syacE{`<)1k$au`K3ORu_UIqsd^C zQMw`Sc9u455CQSsKjB%|@zR1`s>j#YSQ5K*dg@-eg3#1*a;=YAr`oXALu*w;(iN?? zZW&YWzNkw?|6!|ZF^y}ScT0fZk$)@QKy4?Pa1YXC5YFn>4njCGqES8ovvsLux z-aQ#j>WiIXv*7gabC?~ZWoF*^X-K`bO+EA)jqHbNem$Z4_lgQZ0XE{B*-OP(UsvYqw>y>Gz>9FXt4G+rR-K`$IrSTW7v&ziL z^t4%X^CN?BZ|r1tMl1Pxsi|9fFWa#e*G8`xGMmlnS&o#^Y)9<;UiM>^9)6qrZKEGZ zNlO|n|084Sf&SFl`^N8Gd9zR7q(Lor>#I-g`{~7cip=C$<+g9$UAN!%mNWIYAJll# zU`*Ak>P<~zubmO@&FFIQp1gb3G^_CRxYd94dE`U--Ws(c;#AoWqmrW^{?Pi7(S3J9 z#N+TDKaKlk{Eb^}YhS2;ciXS+Qn`__$EJ-Ob^FqY{_pklypQbbHe_u^+QmN>n!0D2 z%O0hqMr^Hh&^vob!!ZLNw7Aja3f3r#;e7G)I7r!=n z!T7HxsT5@sh?Ud^__)`G)@nVlx5m?M>l9g?3)#Oa%ii5qzszjjpN4Vw#_w4=NHB2s z{Ry9UC~s?cf9a~oWDS4WS04G?v*FXSTXrA2sYVi#XsvfJtm3LQo3eLY8c=?F)g$BP z4axplzedrx$+g%ks#{0vA8z@{3j6j`UtZhu14?k%+5#~`*h~&S~q$h zyRmA`i8JG9n)iAeQLD%zM_%#Mc9fNRlo1~TPGvu zgt>m7Zt?LS)E+!!)O#(g6C+1Nd{D1r&524babVpR?Q5Uw)M7}>`ZHP_?RbAc4^|K2 z>5XE6oHb-{crDS`<vf z4adSho_ajJ)xa6wA2Tg(Q~$`0Pgh5cRc9uzDHm3zPP09YPM#gnXtBEcDH8Hsqv?I) z54q>JKi6b()3JNYht-stCvJF9Yjo|uPBq$UKcboDYo{4Ic*T~A#0Jk4%J)Aib0oFS z-~mr>RNKm+S6@3rEW5kx@yD4>1z$~=+O^GyQzx$NI7rK+-Bl+v4*Rx)wePUS*6Jfh z?{09uZ`}JI4rNl0-K;d=e8oo{YIOgm;~$>A>o?7~XZh^H1m%P3t+}f2YaQWTpJW#f zxM`WcP?a?_rtfk~(hm(rWS{T$sA}yaQwMS0-HlSou2%9gOnEi=V9TeaZ1; z@Wrz+2d6JM#;xC=?$(yQF0GMPS;p&P+rNCdDZND+@_ll{auYXfzfVQ* z;}s8PHQZBf-5)hS@=W|z@RV4-$^J3@x9y8rHhmCt^s#;)e75gNm+sq7c~z?xtL97Y zT^umIrToUi9>1Pg%^k=+CA!r9uTL4}pP1I(N~xbkTM(1ce4uaJ(&j@5-TE);x|}?= z(`Cx&9?Tva+xb`iZ_=U18?JSCS(uqKFEAm}HHr5g#k%BKdf&{x1NOuWzZo6@tFpGf zQ_gKztIw}UUpH|p=Z}Te*nhDG)cEDSrSGYhj$rNkyz?#Pd%t~C)zNy$t;mk$qrXo- zBG;ZBGqL>WPii|s?!R6~I!QYF*`}^-PmCL5oV_`t=J|?4S*=!^KT5A~*?ePoj}^8{ zO_)vCi#gkqGdc6cOh(;?bIWq)w!D|weR9tRD(dIX(`gOdUqjGgNX^^w7T+??q3P40czebDNrZI7=|);rbV z`gIQJlYac=dwx0Bsj~R{S=WX%J;b_H!(L|DHw&(42Mnk&B70o7y&qOF>gx9UV?}h* z41uo78d9r-bDhq!?phN1t!*t6x~|Mx5xHTkcXR`uH0 zr;{H`4_7uY&sm85KiD(&{%%jbCLM2?juAEL3Khu8F)ChGlu68>-K6}?S!o0h+k|yr-ZoB8}w};j8 z+?SNCjIqsi5$P?m>x!~Z>PLOLM!f5nbBh|L9qYGPtUfzoa%=bg;XfniI-QMcaB?(p zYvnJtEZf{>;FF_LqN=^8%F<;|RyQ_}I@q~?rQ5Z}dcw{!4G)&|KCC+Qet&L=1aEJB zcju}D*MF>dMd1Ik*@ROSjigB@tM(+SmyN3S@YF5d!!KL*UylN*nq^v!{(RZ?(GlNp z_GQO@P_I%JZQ|nU8RAse_TVk2YcA`VaeUPGUHfhMlC$MU$CR{tO^Bep`_>wg zN$ECJ${Vh)kho9(-RIfS=VqL1nfTH1`qq87x;#Nfb44wq%oS=d_w86Mbq#Mu;Yv)3|+dhN`*QHDUG8TbDLhT|M&s&I87bU%KmX%O4(`tXgk~ z^25&v!^-|ybFS)#N##>z>Hnkc{_YDJE3rqPV>iPleB7b#s&l>8`WK&S{nyB0=}V*! zzwCEiG}ZLmrb|Ot^_ti1;hGnuMjlH%QEuPyW&ZU-3(R2dX@E5oIUg_Ghr_wv=>x^jg*H!m`>py4I z9ZIgyCBi>RG z%TFxRbnLuI+0l1qbm^Y>(P4R&?IVxScP!~e?v$Av+1k2A>5Jyv{B`!#sgWD936~d-toNvY<1u^B_~(!9JGb1!zAFbDU4Hy# z8>+eeDdu8kvvD6YesA7p?yeK5dpr-CeDFWb@QQN=Y&_BK@fpR9`~Bw*NY6SlV&2W> z17nki*5h?BOGd2bKjlrH*JT=ibk~n}jn8&H?$%(yR|r_ffK+w+m`lD8@szc3-v)(w z)u+ds42=E#NLa0dBW1=R&Mj9vx1BY+4mE4qV)C#7UtO=bGvl7^r0b6U`rrv+SE(Zy zJ)K|Io82L0*au51C8am5HcEMGXxi7+MJ-#kTw_(PD?23fl=@M{tom2_>vs-XI_c>o zBC(ZXEwj-_G;z26o5Id7H`Kl}>{^q9gz|sxWR>y$9l4z#H~r>0Z8*iag(6pyDy22+>9^n)-np*!ykFTmz44r_ooB2cwSs?abRY3oUC(^C zWOtWH=kYD|ceEVHZ=CF|+O(YS&xalEamMq9?D%5#xkbqh1S!VP>YcM3_G??0dop=k zt>5PAyNscotipae;_fI=cb%)sbVBm5$hG#r?vL*AV~xY=il^>=K_U;Z{5bf)o!Wz0 z>F;G&+Oo^AKe))Hr-P42$A5oKJa1yF zzk1aEtbSQlS`(3UxNgCyCX*B9w;9?m+wcc>(u&zoC?>R!5K zHoroYs{9ROr(Kn^ru}q+dQexNLd+Q4^+DA$hr(Nl%UA2fE;ritzcnYqVTWjj#Iz}I zFt0zpxbDJ7+bm}W&0fmwB#-@E*SM|)*`2Yo(aoWs@7_B89HUJ)@!ln_F1lvCw87sG zqHD%1Z8;?N!B>m7rcaC3Rop+jeyX4@B`I@ zN03&d?vx9wIqXQ2R!H}2(>L}Xk?apz!^$gUth)WHAT|218jp~nt z)s}Lfj9gt|>pqLD!_XZyZag_N;(Yqa8fQk>M+LMIzYpk2RCM(?&W z8qOcP{$Tj$Su}6+iW@7=DX(vASqtk>^-3*puP*ezGjHFmKQ}*`(&xL1=cr{GjQf4s z&1!yKPjmC1F1If;y!!i*eJl1&KYhH#;L7D53hu6+%&XXL#UZ9xswy+Q*;aGf-O3MQ zx)9P%*J{_G!H`W|HTBEvY?M-WovY%~-x}>0el+vP2vzh4C#DZK4qUmUacpna+9T}! zar~#P9tn}Lv>D|b`+uK4znyL6VD@t6gY$JC_MF2i*K|OKt>4VmdYLcJ6q}H2kL$>c-+K`hkn}9U~JFd2dDjX^uV`g8$IA1k#SCM=(?&RcXrpC z6Vi@*?F%dI>e{!`Z%t4AnsK!9AJMJPjLbMReC)C%{(+CLt?aP$i&0g5BYxXB{cw*} z8O_gw)mpeHLr}eD<u=zT32H z*Rd`S?;J}sEm?MJ^NF%Y=T`5hDx>$f&y{~D=#&0uYQ4{OE0@1tH}Ph}YHj8x%unpq zy?vW=ohmFKOkA<`@gG~yXEeSn_-XaX(MRsLA0zvIi0RaCtPIH5t?fBiHR<;CK^uQf z-%>p`rm^O6xAbL^fKd}76v@reW!p56OYww@`{J;h7l!xJ2B-(xnEqwgf++Yaq_yno~FkVcUW`1NjwYI}LeqaM{R{(Rxndbc`W--6l7 z+r6@;-DIvkbTjR@hV8@TI~v*ROL+HhgWBRWxmHazw(fMD2jS#%ooYp9l0EHf zPS#bFtcY5AVB7y{wU%s{%CXHq(RJ^jJx6{V?cbM>O1P}H44{+oVRIH)j|JH5lsM-|zeA*um^UzuXeWN|fY ztf+47`WZFgu0`^Ib@@$s;YRgSic?sI11h6xS7?|ik{hm}8`Qmf{vc3Ha0VJoJLS+S{U z;+7S9ZVj+pvhEXO7(qT_ZQRZHb^i3e>&betjYiH`&T5TLqfVnGeSh98wnAS zk_HiJMQPZiTe?$1K#`V)At4PC(lBClj~Ih7?$hh~em>XzJFee-?2q%G9ox=x?^i#b zFOdEi{;UhR;pxdr{wUS4@;KYx9l5A?-bDLxzG@kSWj4FBshlh(j4D`sv}WsR2T>2j zg{{@#Lm&T`Cyk4lT7;yG2ZjF~sSUHpIiLbo`ZiV-n`rMDF;lNAwJkpDVI3P! zAebFQ^x59nnBxn0XF@R;--p=qRD6>9@JSj|0esUff|J(x*;LI1L0Ok{-@()4UFrXh z<_D3e_Bx+@63@W2QRf9$$)`Wg7=ArW&E^oqjgFyTVKLUW3ZzD+c`^OE>JYZ-)yJyI zlM50hbXrH8o=pKJK1V>n`iv21?Ye7kZ^F;Twaiw*=SMp2%8St#w`>=Na7g5R2x>ms z(0%BWe^*!iZ|BL}Gw%3cGsnJn_7tzqrzK0kkYV2o@V1gmQZ55$XZiMAT3FEI`c-t3 z4i@zCkdS;UZo6yShygq{x~xUp0?g3i(gZmFMtS2y?(w(tEY~(11VLfPl5J{~8u)=9 zy3VMUZueCFZR_&lM6xLeE{}6_;4oxs3IInv^mQkR!>fKZdA9UyCC#Q4mWADgpR{@6 zjn$48e$01PfpN1PW!uVd-PzfW-J(L+C8OUAmZhqs(kT`qDK!!K!C;;fUp2aK22gNf% z)S!W@bF25`l8HH>!T#J9zKBStzQR~(mK@zVW@~Y_o~lljzdrbY$niuGaTnEioKPrQ z1PzY(VXbf>Cz%XGWch{=z9sDp#>4-X9J@(}egd>2dR-VIvSL;RXwic|Dr~Z0$EL}} z71av(l%bh|bH?e4KCgF)JVevy_J2WKW){D%%=Zn4R|7+#E5cmL!vKeql>_5d@g>E0 zt@Ga+OV;U&4%Ub7pD;FPFFVnR8!vn@J8c0H#PPQV0j`;;{+qS`)vk$5f|W7pyq7kgv{>!W#fv?w)*a6*E3jret< zXrDZBx8Mkk!fqt26Pd8SDQXPgkgN z-p4ueGpXZKLb{Lc<1DMTl|s%4Fd9FvYJKf8{~>EMX1%@Iw%6A~M^>3>9G|`64Sa0i zH&E=9foTcQqqiZY!`qU)EiLPhaxD=&XyQ+Zw00J}#{qXtr~9EY$m!Vkg9VJzo*1&K zqS4RfY~~T>msB=36P4=Vx0E{s#S8&5A+&c*Jolb8oJtCA_0$?8D);p}&neAVHv;-S zgd?Mo3yYssNgfcji-&QFRT0!vj^6L7mRR!JGv*W|i>5e@o0N>E z3^B6a3&NRxS$?d`@wZ)HY+1rA9#*tisK8SmlQrt?G7GV!0LGwy2f+=%HR(;;dvap! zm^JUX@$lN{F!AT;uCVeC-qG5!|D@q?lYl=g~Uv4NB$@U zD#HBp#X5sXI9L84%5;fIPFomu!Nlj{*>o*o?=xhMK9|e1@ z&!#QKAMj*n4-`oVsj}G-zP-hS`?iMQCm%Yi=IieeV7?E0M+9>N(5L;~K#_LTLuW}6 z&}LEkce<&G-M|~TBmr;Uk$w&2$yWZJ82LK6R>J`2N4Ykx@((XV}M!f+M*kh_bIvqOzn$nt=$OwlTq z9U`?nJU49_z-MIPo;#E$$#Zo3$L?ejyK-Jq*QZDP+uDMr%_^A^6)S#FfJ!O0UIV!! z#(D<~rWdTpmKMdgH$&QvJFXdh1FjMBo4;Duqad3DjFoL%@Ec^qq|H~6!5%sJhAHk<8`yo5ed2%?g7e^dDK z-YaAp@_c9Rr}Qn?3+ck*F40~doIs0jga|1dRUMLLB+;*1hDgcLZ%R z6QQJmKeEJLt)*)BfZ6xvSQpGThI08-Q4t#RH~ZYNar_L%MGR|_1Ko5}0}qq%`Ijr( z^Abg*ocb*%YfIl0x}29YxU1!{SoB2-;G2OZ7u=01lrUGx{W$lpB;69uvL730YDF7< zUk?_wvTA$XaJomcey#!k~L2xlYy_5yh ze3g4k40GK}!{K?5J?7BgXE~u{bun@O${PWui(@|doV`@i!sPv%9l0`7Nv$b=kM1e~ zR;D2-Inju|#3F~N zOznpa+y7#%51nV&{z9($2jxx`%{%-Klcfn}?)}`IQ$%C~R(?3)1TV^s$NXsD4Lo#R zNdM4Gw3v?QfkSWF%zU?tk!x}CpbVvpdDoWxhdwKzbci%d$gv2r7C@l}>KrBz)x9i( z$7cZBDU91Czh5`edf5D7n}aDcng0r4*Fvd3x;3uggZlx-)C?eixx-nSZB4aLYn>NI zGsM*`AZWWL0LN)n=6Wi%PJ`ZWfKv^;1h_W4p>)ylDr@X7vAg;QA$L=?=q#bvXYM;? zB?ABz#Ck~t!(M&^JdqszXyX9@8>UimKX2${+V46>TEW1U?XAnUc7v&;ep>Ao_VZNN zJ3k3n1vhj3Tt8v5-*ysNn4fNqaf(!K=0PFL*9$7px4#(d2?P9%Ye&BuRa&Hif4gpX z0n{|Ms{g`bb5p#V4`E&n0Ek5sPrqb8kr!ljjXCghp~WoK7He%D(00GLCvR{~u$B}J zZZ`({Tl!$9x=87RMoxoSl9Z>e=cZ+ESRtVr23cfy@fQDjpKb-V#kcJOQ^i@0RT*>v zS7+W*p9jaNME%_w6z>%&E!uoO<|OGRn68NbK#gb9T{=n?b(<*+lOyi*rOstmh2N-* zAEtZ5^P&B@hqXlljJFasV;h(J>MB>-HCdgd)yTEYsp_=FSwVArQU!4E3iUMUpsp7awRXlLedh%2X0443<0jRUY5aYiHq-}1w<1S>iJJNkZN7Bc`a;6`?}P~-sKMmB#!&w z-l&oqit3{uqt!0k09iR=fb{ANAzI?lf+v(g#5gwuPvJyC4h z;3@_Xp;Bl>l77OUXATHMSWj2*oO+G-EKYHOPB@M_`1wEbfmODuIi{of9;xN;x|M5o z3!8bGgL1{|A1xwT%g^WicJ0P@cZ;sadizW{dqaN7lc1%~sS7dti{>xuWS+?}paKl% zU>OvopKF%$W9lE z3Gc&z^Q6H`%iVz7a#{bIMfXGVhQ5zZZmEHi3#raxzIhz+n}i{-oz)Ho~iLlr! zHvo2xo;H^;r^{MyP6C) zw=R0G#V(!c%AO?~#TEG=64ZUaI=?N(30lgOAKdwb}bu(JU~_)Z!9&&bvfhfC(qv<)gP7X7ee>a6?MA@m>j zI-c=-7YEB?!@Qf9gNS9|fyoVb!I*A|9om>6>fqxtGGr9gv zz*fzmaP+np1=DbrBx;VU@oaB)LO&D^;Lt3d247z!7+LtJvUo4w-UiT2qqJmF95}dA z7|kdE=j|w?i#U>8@>X^QQ2tS)XZ?ul3rI z3}fzhy3=M`9lKf^O$R5>VriOsi(;%5UDNg~$-hs9f)_&-FKz^6ZARJRJZc~Gqm((&~Iq_v6 z^tvKh8eev+`1(Ana=;)h+wGU)_IQm4qd5E<7Yu_bd~0Q%RUh8hQYb$f)g!$>Dqp14 z>-oC9^=amVMfJ>swn{qXi_tQeA1n@y^mAkR)Py*!glQ+Tf*_m?iyvYqOHE9L8!y~v z-EQt6es|4XCBpP?(mC4vSa^~nKQKx-@I$Yq{z%tV_{L_6tp-<*SH06eluE?_Z4^qe zSwze0{pRuWWlsyN{M9MvVWuQ$83@@(g6A&6e>D0tlj5R{Su>y?)eYgoGN(8kV4s z6mi1_&p3CGF! zQMs!jPU(KuSBrq{?S*o&eFsSMU!2P9$n?4z)rF@a>Hh72gvDYhBmZ+{Cjf>zCF9LBbb2Vk0Hd z+-}-CKko*eRJ0rne9ruk0;4GT^VQ%)z9L>O z7He9zZ8l$a8qunc#@z%nHBZ|}S!8Aes8RZKshDD>Bp%(7FPP$7HpQbjz)>!?u-pIy zu@a3wz6R-lRX=YuWw(6NOAT+NT3Zq-fm0pdhWv>(q!Is28l5W-ZCBrVP9C2`q2C&@ z=q~;)yaQjo(-ilQ5Q5QTv^%HuL~>i55y4w@vo%&|_cI8OCFAy3C=CCHbi|{oYe4KK zvr58|{y3kc0vI~oT_v=^TNUK3q&R!HcgKaB7f#VTi30RzYeG8;_=?UGQ^u`7Tl4;{ZX_Z!CM=lJBli+^LNs z5sp-8HsC|f0vf8`ZciWP0IIq`tck4@LA(c{3={NiMexK?v_5 z;bp)QU3^Xaq9TL{y<2~8&g0qr3(%wAMjvI_rAwXW_@XmTMNbK=FXOgQZ_6KQvJST- zHNVylg8jBs3R`tUgt{lvEmd0Ge+9*&?Q_pe5qNi?xms9bja!y52=QLfT)3t5YwgfH zaZoU3J*O8(Za>6}|B#1v#n>1j-6HZ+x=(m(8KvkmIs30lGTxL>CERaW>S4JOP<|pp z!uh$cw@~s)*l$6+h#f1%@x~26^sI2|aIs+(FxP zj@Fc9v;bb}IhpHNcUCwl)V_}0PrQqrD)lQIZQs{h2p^<9$iK0p>vICjgS#wP`FcGL za?fH;Mt3+_TT!3V)WU5)q2#>!E&V=Q&Jf72yN!;h_j|$pxlwW#joAT9Jtm_*r=PD7 z2lH<6pK=}#I=RInw~it$STF6Sd#dOGgB5T*htS&Bg<_49PoM#+=dBuC~lwxrc{xc!P@Ffj?o;3!7` zGfz^a2WV+|7(p3q6)qE|5qt0aHq}Qbb`{Y+y~(s9f^FhzVj?=4`Ea7w^Yt#ZlLowY zd42~{aSI^$1pzLOTF#0(aN>6Gpw@|+a?e}~W#ZJaYH7E}32{2^cT-2>Tg4ue?9{t1 zHV4k6@#+7{qEPnEf7nCrV{N)lk9!Z7)}e9z^(vXve1R(Qp^u_RG?d~zs8v~;fB~zq zbSzF%K*&K+Fj={nAdCQe40huE>Li_By&3}`8>fhTW1rCFdIb2c1kAtiYvJ(fVSH_A zm4iNg2*r+4-x~}o>rb}rjs$x6#eGzbM$ob3wAz)33c*D?kQy#|RL@yb04DGbNuSI! zKw0_8W>I&(`XX`K_-|?u?-#$}sfP!Bt#}&=PpnF%Ip39xpk(rfLHueI{2}j-tFL{@Z@4)LQ@r395`fK-q?zGUajd< z-BfMEx@iXsg^h!sd(p2^|6;8JsvZHus|eR#!KZ6!g6%aL9e&APGy^uYns30HIbOLa z>1%>+nQJ^^lh#5ZAOVXL{&m^%Z+BG_cPjnP(!;FaB{N3!2&4O0Q^}LyuJd?KVJ)m+ zTqTPoXD!G%kta7m_32(t(;6rj0Q(OgHwMmm?Di*slDp3&7x~r&UgeISoc?BaA0)kl zcuB1pSVdYPBxy}Y<~*e^kU>El;@a_4x+$yV3-d{jiY~V^Y05qZ{eIZLESFA~UMm&D zjjP(*W$JhQDbkP0CFhf~KoS(qC!ig|4b{r>L03*}_(eH5IT=lt6$wDn8J|q+CyD>|0a~m5NSX1Ry_Dp9Ha_Y?)XrUq_B>v+)PNmdREb_8XugVG zkV}D0|EZ~Kh3zWYarb8RcrT1SwvW!yt3FEk`HawBQRrQ&Rv_F~I8|fFkaTcG((upp zg@OUrCzKhV8Y#9Y}rOuo>$;TH}`5eO1e`8lNP znaqSCrqA-|M>`8~I2&@>Wvv<+VtJJ!;hgcNix%$v*Tj~4l_FyMoromolDMr+e8_hs z2~DU!$j`SN6JQv}c?DB}L9BdU;b`dFI`-#VN!tWlN#=P!3AU$QBFJgYy^R!};r|g` z?;btse-mvmlJ7;Fxbi0H9~NL6edZ^qf@iG*&sD{KiPpwg7nBs$S+hD{*P62NRz_}w zLuM|CuOWc75xXOjdQ6Z*IHo{;({@ffX{7w6*#!@09!yI3im?DM1?+jT67F|MPOHPt zrpI$4M?L{nz=pXLUPO{Q;I{9{R2>h^>it}mFs_cLqM2B@d}?uK+SND6VokQQ053rD6*$VN>SHni=j75}`Dd4E4V$j_v(JR%PpgsXg+I3m z{^{K++@<(<8j6Xnx6ku`;o5w_KiiOOCd@_XmiW!zdt z4soDhMWv+WO03)`$(VN}$Z)FMhb&Mcuf5=X<FynN}*Y!C*HS zu?B7*^lak}OTmz?Df$jq#3*c2QLe!9?r9>^h-ki2(!jJyp6!b|yi0+_YnN(?MDRy2 z_A!0as2R{xQphhNRmLWQ93>eE$nnUdXb2~PxYj|f78EI*q_4!Lpz`(^qO)Aa3lH-p)%~D&jEh z$<9O=A}*3Ml@L8B8{*NCu0ll|KgwqQ3@Q4Ki|aPEqE_QOA-K3=U7lj5!c#q3jrT8H zwOE#GuPdb1-wJHRtm)=8avED`pCp_#X=c2GvxpvqM+||P>-5)a)^r4By z;92hO{u8n;>+)reeOez!dB``u^tb&%6cNxMq^PtaPb=RiG7oPafV07S8s0C!2lpn^ zrRF&=XM3#Y{fq?xY#kz}E>EmzzZ=a=+AS2$r25V^AS@II=}i8GYl!IZ?l;WYiATjx zN%kohrUyHBa56%Z^WE{=OpVP>cTsG=f~vk)@C7e=D9-X0azkCNC)9D*@7atTn$sn- z`uAKCzj6c&%38s=5z&S_vbPi%(NMi`ed*X|+3@{{ zs22*rudep-s$z?HNo(LV6Krx)17B@>dZWZ_i%4nDI}Wvk-TM}BwB$K2$_4&aL8SqW zun<{(Pb>N}HdM=#hQcx<=ZPSQQn){MjaeXW*5dhP_`d;*1J|%zD{cR^sO(%jc1KI9 z+El%4sl4$+bCdtL?$zmm0dh212)WV1I+(yL=C$#w_EjIeoyQ{q{OePK<(CnOYHx8b zbff3WY`}V(7d(+j9&^xh(Iao&qf|^Dp3!jqRQim`x9Yt zJM==e5UX>t0woqg z4|XR+-d17L)JTi@_{Pd6?q%|K@`rMQNp3CN)MtX-0^O|CDFBakm-|3D1;=Ly!FZ4I z>rdltHR=1f^sm^G1VFRS;VOE+4tYt*HF|xWdBf!t>Xgl8MZY6W$={ zdIVN(nboA7F2Ih#osW*R`^a9zUZinD`@>^RwHcn3DrYN`98tSdy61%w=f?TQHiuP_ zb>{Ye0D|qETZ`^3K+)P9O5Yuq9<%1hTgBF{H`}5%H%a~qe@9U%@FS-kv7;9dFhxq1 z*iHqd?g>=J)1+cl?Y7d~2u0=u@yl-UT>)BFpRcbYv~qjwyEWCuwC_{gr#NP!r~l3r z1A=}hSEpvKp3CFb+e#}3A5FNd)z#+9;HBIvz?BcFi}ip-gBx*w5P5Pox)1>v`Iph6 zfN_-K`0vz(beLkh7VEl~{57*n$2nf4RfZsXumWd}$u3ZvYme}*cAs7{cFNxPmURNo z^C&C<>uWlqYxDBQul1;$w}{`2o)S}3pU(bQE=V!IR0+4O<{)(Hb5Vll`;KuGJr) z87F_Stl*E6-XE5v*y zyZ}t<$U3&4j-qu5!c!Wrf0xB@=a{6*Mllb?6(T}>OE6i)^L;0M)Y3op3|oTkcCK_2{?$K#YzXQBL0>>V#=wd@ANNHXNyijzf^@!PFib5B?TY?p;Lx8{D2SsVKJhKFZGt}mU zf;K%SLBWxNNrK6c(grp&HZ#2~1y=xjaOuO-VC$0xjc6OPk=Yb8?te`64tZ32*9@eh z?b}B;zzEW1qM?=D=JI4wp`->8>Jmy%J}|Qf?tYyd2v?R!MPCGQVxs$;@}k)~82zds z`uXe+V5Z???>_3Vi3#skTqH*K<0cSsC&^DLSOp=kexwOmU^~TAp+V_~rzU@v zYYcmoS!5e~h>mGhLQo8*xGUDpihT}KPQZ=CkGx-m34O!qrv1@}Hr)JkA8>Eg2J9bz z>S>2EiXwqRU4|GQs|H-NRL5NPv_4>-uUS$x{F1?j@_Q+2JH~0h_gR8 zu8Z)1{yl#nw&P><79nONUFZEy8g70rHWvbqZ$Qg~JlJ1y3laemDUr1uE7B7bOyY)a ziy!0dWH%Pn@x5J>rP>$2;EraV6m7>Hq423j_H@#(7ehZo!}E(qBMnB34{4LrAlDWY zQ$?y4>>PS*rf?)D^cp$f$1{fcP0)y?+K|*ZiIw(mUL%zrteE;~(=``!YNO15QB--o#wQK-m zi?;XS+@QUDU)!MqUvO4A281~;=87YN1D<}n-s$heJJA_}i-FGFHhh#KXZGA4_Ft$^Ynh6!-o>T=&DH5xpVgaZUYfO5V4cjIcaxd(1tkOo#~K~9p80a7 z^MTV)aM85YFL)=L{ef4K@d4*9AWMk!tQL<6(rW;bx1N6Pf{5Uh?wdb^W)@;{q?!1W zAeR;(EGBKzZAPOX{+p$M?%;qh|5Eij`tHmRB~|RfK}w@^GAq?BZsQM_wHL|Ee<=Co zlN+4*)T#$kEhWR=^XC>i@ZyBx1ujVWr8BxgX@OL-h7z4?dm^v-FTi` zaPd<;FLh${F?e^5hsE!iE6gFEDIi9wV?Sr;&cX|{>CDT74M};*BmEnGbXJ~3!RSb! zf@>noaFO6RI*3H#(R|V$n!v?-f1iUhynT_=muNO9iuuoRJiBsh4viz;oxsH&uwH!a zE^ptnlG+y4ze1t^?7BeG1{&;6#O_F*i|h5BKf-FnwU!515lMZ8nmiF$h5k;=damXh z7USm~J9KSb%k)7*8oj)BY(h{G#%Cvn0B^UST?&lf)SL{vQA!=<2Nx^#Xd)-b;r)p{ z(M9|0;r-IAF~f6b_R3;aCvk_4Q(uLmu_nCKupBGTssr{zsLa#MhBxbW({Y%^63D&U zd8DP(dfiR`irVb_T1Zk)9Oilr#W&t!&tuZ=T=ro8=9a@`V;M&3%nR)__o6VOf}2wv zdQb)t<%V{7hg%d9zT$Y+-3Jvo$Y_&)jx=g3RA4{)yS;{|@IA8Szj4=p>X`p&_8Act zF}iy;=^?_Zfzvy%LLhN60xo^lP+AA8DNp{c_uyy>O6Qhz99N!jueRQY{WA!26h8UY zoM))8rs4@u{|8#~=q82}z=h%~z8QT_Zi{`4Y8+Wa6lh)f*;6(?^c)IDBG$&dfxO-l<)Zij`;?=zM5@QyA^Pj-Htlrt1H8V z0T5#5x4lKexw^-~{;@FcEfSw)76xGWx*^iCJ8bRg#hv{fEFae=0FKlXR*wNkI4`hm zP{=3z(h)1tl1!)_9Tgea+3RmViix0<$@+btNM3k1%mEq|gBG!|kqSr6BJ#d?(SmT# zd0+ciAwIo*0IZMtGB?r6|NmlED%h&VnNI74ekr;^$jxhgQ_Lin#e7gX)3xnS#c`J1 ze?$-LpaD%%H%0x_Zc)4Y=$*LCJGuf0O{~Nif?|dNiK>|AK+beg*7}(gnU0cBw<`^O zKC&UhebBw9PAR&JW5eOn7ooRpf?FkJZ*hN8BZ<*U&44jeOeMQQ_eFTp|YzuM|8oUjS*2c~<)lI8uYp;<=?M^tvxRM{@9T+t+Vf(6S*_lfJOAvT|IY%IvkI)M`m38KtAbi(u~>@94~v>r3H+iJmd zT>3Ma?=G)Ysvv%(ae`<<^*FNLa!NQwet0a`6;j_vaW9vS1U9&D*7%t<88hrsClT-; z67K)LAQ=MxZo~stXT92^TSH`3@DCC-(qY_4&K$mxK z+t2s4_A-8~Sa-Gu&tY6lU#Pu$$opHP7nWg>ob8|sMSO&w_4%U6>;48SNctlV5c z>^Ljpw1tf$OEOaC#{CPN<-OU)C^pTG3dSsL*LQ5LGESn4nIPwIBa74c{+I!|oyM@C z(B>`m=a5($M^(GcXhHma0rPJdiLnh5p92&SM%Z53zH_RdKv5%=XhI|H75X7E|LV=IZecJ$a#MLtoNXK zr(%;Hs2kbdy*!K{LQy8{NN7idPly$Di88n=X!XDA$cmn;qT>)d`l|5>&@PkbiU@O% zlk21fpyuE8ZrZ9omF3fUx|3v0M!c|6Gm%>LOJ5Px1V(DeZX@Is?lXX$e@k z>>MQ%>t%IgO|b^ibOUh9xRkct$@tAYf0=_b-$0J4Z){Z_Eq!0lG)U{ zj_TD}qxy(PBg%~v7&J>%h!U>P>7-f%!cJvGIT;fMQGovLLwiH!ThiAPVS<*R@n(}u zueS@Ox}FzhtY|+~*aM$6iG&2!FMi>pP4({z`#yi4XvM@_YhKIh$@9fbA2zA0Xx@w4 z`-G@u8GS*|Y75QFcwxQ%!L&~&Nd_|r>K4tYqPH8v}FW{BM_l|-)HDNF_#LiFRv(l~+* zNymZi*;H8y5YTz8O=n{NqOF4R3bi(Bn*_`Gq@C0c>#i7dUsuIu79tK0mX9AERPsZ; z!sn*M{+Gk;a1B+6o^mOA*GpY=zBHW3k80qwNZt7HEi*Vg4CDa=Ce1V;+$ooVBQk&e zd09#gJTzl$_N=!x;c~>n2Xht3)t?ZXN8HLR(8m+KfTU(ZhcL1l6rwV(EQUC(RdM_? zas&vAv5X1&zN)Rka6ovpPd3E$i4_Vm=QkjEG&$k#|AOEQwfJ*B`W_{p?eSu-9Vy@1ze@e`rFeGJdOn6!_*uN==qM?2IyJOw_S`8Q)Dsms zWR_l5f5r)g=5dU#96bP=b*F>JYkNp?Wwj8?sScm};7`?6Um-_9WXB;Sv#_Si4-oVV zMIYBp_Dg~NVuYJw8Ts(P4WNI|FfWdDY{$lMRsCIH)%;iKbMLaC98X?vHicXogL{Ewu#w)vI) z9lWs1g8N#Fx1V?OieC4@#}3sI3*wyr?b@+>Mf-zbHAJRB7az2;l?(8G_Y+zU zhT~7bBTulxmMjUHDakZT4kdglM7(Iz2!5^Fum9_`M=8kQhLJJzgIgul=JI^o4~rS* z>jzRZU<2nK-&&JGq6{mzdv*!J!@SX#Cw6`D;zer1QGszwH9p^z$tuNQHv)sHveL$^0p@X$)bu%pdGkSbRh{)V*kY z0#v@_wLKQ(xFa0b_e1iv#!X;`iXb~jvqzLhudS+upI^BANG?Od#Fa|xGqS6LG^)hTR*7=wU8U2-s{3c-yG6>0BZ$|1D?J$lE8I&r5@A)wPFM?0 zAO&|_HK|CtFY%Q@$vfPAhC6(hUiBR%!rd`SL6|Mx^-E*VcRQ0^5+IEwL zW~v}Jr&?^vlndF?cJ|HXAeYp6U$8dQ%ww@_)U4=)^mi{w^j=b&_QJHayL;Y*vb^7) zfqOMx*Zl7OX)MU`BQIrm+EAz)87nBw(*KhT=AzbphhdW|NoC*w$f3=vm5RLLA~0A} zm2-a1@$E+ma~|T_aDEm(X{=TP-U;XPk_vix4HU%263YEceY`cjeba*X%gtc?$fC*| zYc?pvyRn1U)08>gnh+i#bM;E)z>nAbpjl{G@Jr-^>?7q*4|a*p7+-6QjyNC}B{>3g zN8>?$(c2~BMK3)PuxYA)(~akqiecIBAz^zzj8q_4J`T55&=QLElTO;#KhN>=KrcEd zd5tu?w9z=79l(9R#If!uWgM5Dt=9c!`K*oU|a50@Oh4Of1B)u?I5 z?6q9^cC7aJO$P5Y{H@Z3HkY^EQ+Mwl>`$i{fQ#VEIwiyJX0{Pg{Lf3Cx)k1bWh32@ zL?(BovQ=2Z+9TskWPXu8<-0pwnG~>Nl=6Yv&1z?;hbT0cmk@F2S<4xi zbIZYSpt&|bv{Bv!nO4-`Od0p$`Y1R8BPGERCXXt2mP%+t^~bM0j?VTpd}?s?$Ec{k z&#RS`ejF7u^o+dJ->umKQNqfR=qd+yyCG?E|H$qq9TD^3?iynyslh#O;1s2Mm*v@QzqeID4pgmu9)BXoOK8a{ZeQ$>3ek!CMz) zlIb*GCJiIW6NSf0S`Xg*Rv<4PY?u?cAYXDM^EI_2^Pe}#y6mOdez%aI*59sHbYQ|E z6ds|?z$>max;?^7mh!ElNw1=1`%?(AU7YTa1l=M&`p54c zKuBAGxuGXGuLJ&78vS39#V1%nwD9A;4XZ)nNi;(jv>j z?cWDCfnm9bL7(D(qQc>ib0xVKkCO%6y~i|lg<8GG_)Y4abLbp#){h46Z7hEm^J7?l z`~9ZRD!D5IQNjPG3?a*ppj z5hWF>RY(#RQ#64myQ{^@UnW%+y_*O~6yBgkroPF{}C!6r~omsUMn<5Bc=V zG(VZS9K-BR$?d&1Lu^dEL*{(RgHD z_U0-4^6j4FYbQuy5#{58eJpaiu1su0i~91j!TB>PfM`j&zHcZVE?A-a2yutuITGdD zw36DASiuN93f>69WMM!}qgYNiobqbt_nciphE55sxaogOCE z7&vM6%MSM8*9JgWCiCoiFtcK-`wfWS%GaX9!Gb%S?v#PUYUmcwll8;arrP4&>hLVQ zP*o0txO)yxL9j3PhBM|#s5?AX%Q&>;Qob5|8{Dd<9$K+HOXC02g@OyAmOP@(+Hdx%WKo$gl11((*tEMozK~K@|xn&+fJNI5OYWtrq%?`%OUiVg_q89%92dFGn?f+ zuZIJw{>fW^$@@$dy+3VPR2s?HZdrQ=F;qL6w$^e!r1z;O8Y}A4I@?{5^QN;_F!egC zAzpa#sYrO1d8Ws{AE=FZR7zsEqoJM0GXX5em?ZRl(-LBO|AC{RI`f>;C-Ly#q$g4# z2N#9p3H>k(7fd_HiA-EP&?QNP^eP_rjjz^c#STtriB1-6WA~pr2Yq-a2H5@Fp0|6J zQN=5l@o2A3emUcHNz5t(FNM;rRoG9` zG5!tGH{iB9n+Xz?7kVPQ>a`Mt=D0W9snC)Tb`ksT$f{Y2VUO|s+tnzy;@98j#4aa@ zo)^B}4;jmlbqZrzs40tlXRZsmba`EWRSDa0_gTsKjGWO2KRIl-e-+?$+*C5ya@guh zcKH?boy=LlX}I&3uDriJnZP`U7a6bt8+PG-ILC%W{i8ebOX1`EKF{P##yNk`vuO@< z%`x+LfHv(PT-D~DMN5V5O(wPYvWoz%Lc4*N>Yy7;VYq&rMceu|U6|iz`+|OWoH~pL z4mnAYIqBvc$G%avVx6C5dNyUUBl(7FpKQTsV>C+uI%2WPoNw95*X;`^fu_~qDq;1z$8@?|Y2hw%`1#mI_)Je14U4v>jX9QY6ES02P% zOTEi>PM5N9Z96NSR#pHGh7%#Ngj5qYra8FlVP^)7s9($wHK0yjjKSH z{Z*9S5#;d!fmFWTZaMhnzR_rixCsYz$czh68J)J0k&da_TeP3p7t($LL7RkmH^7?qG@}%~vbqmM zQ*LU*@!{O4#Q-O=8fi+wCc}QX3gyHuF*VL?AN*G=<7QtAf3z5Tzreck2RvSE6l|CJ zYs`}Xlw+je{>}6J$(u^wI@l1d(v{mjtm_m$XHnPI2&rj72L})cptCNIN%>gjDssvN z+S5M7e8!TVAmYLn*cukcRlmOI=SuLDxI#wriLI{rxG#iGhw;y4+G)KSvh^D1M4u>` zSJK@h!=>Ve8UaQBVw@9L{7V+|nBDn3DGX&#NfnK-;ncQiW^E%U2f4IBv;eq?}yopy^;^4sxuzb>z ztTe-)sBYd`@oKC}L*V2$?10bVmJtv&q=MU;K zQrk$;#Db#IEiBV1`qZ#H9p6L@ayATr661N`$EPy-fdyawjj3Fp6b9fweIJ|GYi{{D zx}nFMYb$C-KfAw0G4nU6I69u%dTAW8=peQVQM!nFC6E2$G#N0#2iUW(k_(gvBDPl# zXCJ?>dF4FIm2me@v3G3P?7(Tiez4t<(6m;Xa9FGUJU4|#GNuiI5ns<~&~~=m+d3q< z-Riaas9b#I{x4>}8kd~x$$5$r&gcb;_=PN+SXBE z^!R@md&{V(`>qXCz>$)Y5Rj5k8YHDbq(MOG?hr}o8X5s9>2B#xsi8qSL>h)}7w z3_wW?ehxKKyQu^FuBxAkVY87bu3&w&Jg$pF&=lCfH6Kq~W61~JO~W+R5a8WpnNXRs z+<)@8r6&K66Rz5)%|3=Mmg^3z+=SGo*BiC5&Z`*cP|pC(N!o9rBa;p4#MVCIw#7Pa ztpeF4=|mhyU%#opD<&z6n5kS~M0?WCrhj|w zCJke!hns(5y6(RsrP1Sa%Ji0HQ=hQ5_caEcZ;c67APpfrWRR5UGgJ0*w|=!nbHF0E6-K@m9^ZR&nVi_Vg(hi+ z><*x>_-ay;SV;-;2{-~@fL2u@MC?Tyu#yCu&4YWKgfl8nhSFyZtf_3hn!|BiUWYW` zqzXMYuR7sDd=2Ym7YLYFqupbhA;qq53n()g$iVuec1Gk6ctbAP9T2XMZj({FY_Ft} zUO+6Zb#LHVW_vHirE9>ze-I1miNf0uGuydI2B(hY`T~uN=2OU5j#HCIVy8XWPJ`Ad zFR9Dwt(Rs0R_d~dDQBz)D>y`UFN#v|e)LQqUx?TS`oCown;?BZn;@fZ%mOH!tC$K+ z4Sg@e(w$5!cU_zeJx+gVZpKB6#&F+e(pYAA3HvgGyqn2#f=i6#AMaWY#pH}J zC?bE5=1?cHYahf8`3xI>eV(F1(ztRbUW0G3RJd{cL9z&w$mp@~soQ*=brrV!D`IH) zWEm4GP4fK8jmRw$v=s4 zK9?2jG8D^yiacwn4=jGK)Q*V?S>$}X74W+J5>2sn|3wmOEHgt6cZ`1nw$?k8Z_-;M z&7`MVLh95cpU@^;@8BEPZJF^#tr@pTQ~pT%RjIeG@4b%vPjh$qE}R$q@;Xa*4CUSl zWycW8lbW*hle|UuJ4&a&+H-OZh)RzU39bir?X=9}tEIw>DQ*&j0!f$}Zw~r=s#b@! zC^P)~AuXXY?~hgGku`Z2G7;B+KgBI{>9SncTbXgq)GUO3fR-DoS)s)a9@YZTO2Sy; z;+e7-JO9(xcg@bn49dx~U5Sq}#q28tXeuIsBE!Lm7kZ_x`i4LSEu3TcYt+fw4K7e; zp^DVJm^3uP)e-8&uL??q!)opGFZ^xWNV|iwl5OTiu{Hob^SolI!8R@3O@sQ{{oL#H z`%617QgsK`O?${tWuor!BEgSdl7SFkE1cO%mDfI&)m!@tkkF>^Kcj+3 zQKAvNy4u30nh%0H79Y?;g5=<4V)6fSLnFpQsd2$qOM(bOF^myIz8_Xt+(!;7o@kiZ|_yu&4xpfB7=OZV&BPcadaAw z%NhxEHaHBAr}F45#t>9tarD!9;JdrKYRhd`;g1Bp87)_R&{c_S*ZzhP=9|X$a6aFl z+>*+=-O2TAd2x>uguqgw$!Mj5%YNuM^!PVnzenlY5wzJ6pecH1WZTH zy&em+_#nXuB@^*JqF99q5KFid0A=^xX<^T3+2}%vDSU<0X_pKF5}%z@ZP|>v&vw@8xWA958V{Yz3tkUuTOnul?avf#zE-fLERf`r%f888Y+@}W`jo}6WWwkA zfO_S9bmTn- zX$W5-hubV2R|xds(onv{a*qMlDq>Y_R`h?@`aTbJ83RoBfannA|?_o1m^8Q&r={k8!Ft^dt+_2l630Y?Sq~u+kVHZQMCM_AE3XQWB42u zph$9J$?H>;=)JS*bMC^*^(#X+nhyu@TGb{ABKiuH{2Cnzu%xNQS{wA`azixbEKvyr z922&`Cgzf*$27_U+gSl8)c0ba?@WG>8es2?rw0GErPou>eSvJBQTaqQxYcQB-uV4T zFk6vMcla-ed{1TRWn^JpUbo=|sHn0vIy(F|k@n%Wi$DD+&Ms^^ZZf3y??M;l{eji& zub-TqeJyqL7&3Z{oQM42wixaRFf7bnDa1j;^Mpg+P>K15nEfW)b$yn^v7)+MU|DU` z&$OB3NoL=kf&t9odbiYkoNdtNdFl3wcj+UFX1C!7r<(Ii4A-I3KlU@eXH{7mravrxnCE$0Q?lG@OskgKJ`OS$(`d zC-dreZ|Q4zU$LEw-Yr+}t!rHsl9WXcYx^yQqTb9ledxaW#7i-Yhq%RyVI)w=XN1X7 zmo{6U2r@3$Q6&p%f659=l_$k88?uuc;?rm?)N1XuUt^bsmPWQ)h<_skYO7rD+uK=XPZYh&k ztH}mcj9dij8y%Eiu8*F$c5SgiMAN~&)38Pz59|+FsNp2&P8)T(naz#))*6WOJWvD)Dm72z zTB)2yk)OrEd_@k>xPB}PWy%u0f zliTNNETuD=LFX7N-RK-^^V33mj(1v&$(u~%%;J;cAUm#ss{Q;%mCD}7Jod|a#~p^j zg_OeX`1>>EeR2KKoX&8@e!;|fyBt4l*bLjN*MU_EC`sKbSmaR@lWIXMoSu3rL>zg> zXBM?Ps#S#?ptekoP|zM7ee(8kq7t)wQzmFcSNo0YI|umnR5ba`#pL*}7UIBA^j7}! zPn$0g<*2oD{=8|33k-w2AoE*JlcEq{7N@t!oFN0<(-MepIcjwzn-wCHI1YkmmF4ji z8?F_@#arcC3u&$E8X}Xc^JH>K4G5kiCW%6gO4O78K#s?2!`v5EcKkl^PPx~bH z3c0n?xH(fmHGVeK6t`)VDuGNhoGR3B-Qd z)=`t;=y=~rcfnXYQac=lBl%e-4sbs{SP>Z*U#2KX{#M7?sKr&`(R)6q{aCw(xhWwLW}}SsL&vD z7k`%2oG9lFfA*arcw)RhFdT7cDYfF?xgd7Y7~jufxv+L)B zuKy)*R*CKER?CNhHf8kQT@!4NqOs~9M)%x@4%*d;2>UVuUeg!T`~h;|lYut6xViRz zSO3?Ao?#8RRh`Yxea-JM^isoW83ksY#;{t`mQkENeS!BVqM@&Ij^%z;49v3DTb*qZ zJIfe%EHL<74Vh+-UiT^QIE{JGmUu9c?ZvOr%^gO-joHU59Jx}ag22l9Y6LYe)5S{e z#F*jn;RxPbOUXb8FSCxrjuHIh#NFC4cIWDGJaw7Xd4&(`su$a6D|(OnNHap-3{&{y zM1Mo@GNkk`dY#yNDH3oYZG@!F$|b2Zzopz+bF||?%B+qU=_Scy$aKP{R56!$@1REh z7}Qm_mkymCHba-B^n~&gv5`{^!1B|{L{a?6o{&lde2+eTJ`df0fF}*s+af=DeHRr@ z^ipgD@R7FXcD&pRWUP!=+AA+M`AW6r<)|Uui?m>5gCr_plL`D5R-0$qg9TjXy59VU z=-Wa`ba_%J{*VdU7G0OmBnT0=k^6cx^UJOkE-5s>gT|FxI;m4A<^pQ(Cl1Y$XN#A{ zqo_97mQ|`8WdkdCE7MgP41p}FgW-6(;++~Ufh?Id?r<583%)<+J@!u!yw3(Fl4dIn zW~o{gza)tjf{NosdU}2v&nToSUSsYf+fmvfikFu|>5tOTrTJ=!SaNa$Ayr+Pk&@wO zSUa$*jo)!MpW$%$+m#;_Ou&+Vve3Y0E}jhq7w+>Wko+&upt&K&hwsmlA1pND0j+kr z`z}fy*EX!<2eL>DobCf_t_^dt<-fd#tb7|B&0`L1t3ljVd3brh*;Alb0$K;sP7doY zKZozLvk>^KJIKIw^L~U#qVtq3e3n9@61*1X{z82a43UX`q&}z}!w-OihE8h7^(VXb z9VWVPA-lSeYJhOTL=J|&J*ejb;J#!CxE}`=J!)H z{J(fg2w1C4p~`(FA21#gA#95;dbdLsz7Tuxxx4rzpKcW#m9NyENVspZ2vG};| z%iOb666v1Ib^QT?S4_YT(i@8uX}bkMLSN{82Jf?b%gDpGhy?lY zI$Z|ac~32=k;5nKB{CTb8&BHdq;DNn84Pcjs3y&agQ*M0r2SC`Io^dYFhdy;8Q1G- z!wBQ>p{=Q0CGU|jF7XlU<{e~Lva!gjvYg}qW`i`vz;-$1X%Fbj?i6pvp5JKbCNfBSO zu{q@Kmgiu0JNgT=z|sx@c{^2U@kX+S;{6=?!7k>!3_?)3yUSdIh|OX;&r1e(it}rf zn0#oJVio|+$0f-7z>>OH{t#FDVSM5?RAhxgn@%WXuBLd~G2cA_Rod*Kbr=X)l0XdK zS6|S5MTgatg^Cbi=#)EZWapy&2eqfGJnVLEo5~p3>ksEoT$O9r4jmTBM-9>WN*^nx z-OKw?${5f}-l!F658?GHXmlK7`}Ul4FL3@`|4O6*Ti^W(-Cr>=zH!0<#(a{nVDu-_ z%i9QHf%~J#Lmcx$TfTf3xy5}4Q4XD(UQQT#zM95Ss_)`-dIPBXSwDqM#cHVx}mQ;9S? z{$iTevsJi)4oDA)M?39KWJMaC0o!}rXKfZJXWIUpT#$0x#=)uh0v{awJt9&yGL=qyO*kviZ@jl`B<@5tZ>> zPH%1LIuc8_k5-Vst>Ci~6o4hd|RYu`F4@S*@T&ZrObs}fa^6@7Yc}X5DNrr3C zZTyiApA`_10Q|4+L|#%ro4TKv?+nbE8anrtxc9c4_=5bg-x6;rulH4X2;E-oNs6Zy zZAi|#6;Y``9WRi)WcwigAMS}d~rGeeUBnU1YMWB2iyIQn*S*E zpJSleVx*DN9MQM&hg|M^-2zJKXgt;7UTep+kodkJ^WcFI#TTJW($IV4b15I}Ts!pDw}x+LaBWj88YzA(*1NkS`a zF5>?hXaWGjT=T!=)kI#$>E_Ty)ExqmYx&4vxwOOZ_IZho8IP z)#D{D=xUm=zkp7Pf3w~>|6FWxL=$PL?^*Rpi{TjhdeEGVIW6QHQs`z!^C9597Pk%7 zjoWbmK!&}YYNc3z_ps9{ig>nr8)2q{s5y_gEPsbAg?{kZVKtl072g3|z1tkuX3as4 zSnFe?=ha^l`2N!VK5lIswz8WRh%E3wM4Pyxns|HQh`tMOB)eWa<1gbmG*K5IKK|~G z{vRpV)}qaARNK8hZpo|i{{Cf4Qz^95C-T}xqmRm4or_d}Z=aavGpQ24uu$v~5nX3x z&;k7Di*`gb^6t6)tB+K#4D@zxGq_Eigne!vzaCrZ(&b4_pv7_zd!VPxUbeZA1D`JD zOO^&eup?^ol8)ftkW>2se*W5LgUyKgL_8k}O}$pmmJ~@?v~p!#gjaHruxXpFbmIQ` ze1k-9DrOL0+>XXS-u%SL{Pt^sr`B!v+eL`ijDKQ&2^m(;WBBb%tR&p?0E6OgpYv#? z1$|yxt#UUsO5clCqfE=c#+NVqb$b>U&_I8wd$Jc|Jp5d8HI4<(_x9f7 zu%;LK37jRaVGh@6{sIy)ru6w{I~2J;^XEiTEucoEDZ3`TU?@iQx{psHbTo^`@dv#H zt9kzXmpfI$GOcEeDa(5-h-W12bRq>SR?|b2uw>0^###vg2Ti`*m*i|FwD@<ydF z%^qmI^6_1{oBQggMR+Q7)zJsEYd2MX zcVewA&P~1jiOdjE_62>r?^(DX6K`<4!sW5oF%;`-)RN1W&ycQkTSaJZ45VO#%VzPl zW~TRdzj#5Ar`*l1R$;X5z12>4Q5bh^8HX}agrHm<04}SRH=S=kka?6p6qto_{Pf%f zU#3$0Ll8Z%!cF2R*SN0!-&T2E!uY*?vc$kqtSOU5YH7Dc8c(fw1=+DQcLF91qxj8@ zqbLLdCJVw>e@`V1B(u>~7`8?76n`|?j-r%}dlkv#BcFH40u6)l=gu99x?`o(T1>6l z{C+2}dVC!1ft|!M`ywX$=y%-foj*r(WjgJolG5KL3M<;qXK>(YTEz8;7%L(b%*1`bdYpEfT7MYDGq3Ix_-9Bp%eV0U}(?Q;c1@C z(>{PPR)I`-CG(jYyr23ud3Emr#~0vc(2Q9OC-_Wt_{Tf{8|relUx%T+mJ~;3V8;qH zVravxP&rE)Se7uCM4phHx^gS5wUi2HgPJK)h#;Z|pj ztnd|HsAhZIVIIEK2_#H8>`gAsl+mVZi6&8To%I**tgz5vn&!|-ss7Ys=mC1lRz(j^ zf9`6u!c4kkiVQ=wV9D-Y0b0lHVXk<4dk-ItZ5}Fg@h2(lY2aWXaM~$Q!TJypk&~`7 zpc|)3*1}E3S74`PK|6CAnhXiC|K2J5+6QZOc>{DQqXfj$uJAV;u}Yn@pWD{+?qis& z=4uL<(zcQew~QBI4O)DAOm@p?pD&d24;a|j${Uxt3dF4cID&);kdw7;Q={DkA0D0n z{JN03%5$Bah&{J!Q8M1`b7KEd#)9L~yd=FM+=2#?QES9hGF?Wfm6qA5K6Jg7mw3o& z2V{R;Dr7-V41J^i9t!S~;JqA5pPO>Q{)V#vR3f#b5{$lNW+C+qp0*78XkO)fkyu3W zE&2V#xZ18#kq)p(7^t%(Xb91N3`LGqbDhfUmk zVP14|y$>Bo1MTpw3qqz<}iI7cWzq3L0Su7zV z;kY5zy`qr%V18os9vKqU%aS1Sz7&r+AjV~73O_WLGM1x?!RA8$df**^_QCO?V>M_cWlM#GW_&W(As%#&ikP-($bOIcm1-U7Y-E_e zz>m2uB+~8wNjz(p%<&xl%P4wyC^6C()JldVk1ey|JCx|`YOf5_hqy8vEVhFH?;yEG zFNeB%oH|nCo0ENWdv)~gu*7^^Ug|80ihsA>6=*drcE>9k%xAJAu6T2!P_~?%8>t>3 zpv;7J_|KvI#4tYrB6N*JxGEuzM#nrYu*cani< z_&AVlMOdLjCx~Hk(T_0+O~!Jj;1@|* z6ZMiqMqwM@2Nj?6=i9RehWM@`a#I}4$_EP^*5ImoO(&I@cfXJ`5HW4TGhrBV0%}CGfFnk>x*Zq&M0eiqSPuTW=BsA5Q50vrNlg~UN5`%bM z^~!E{U!;pU;ct&-NT%{wE6$-@tQ3c}+Lz00KdFQb-OSE18h&8a9dSgkp8V3x{K}4%?CH-dNYeu$FpfF1W^XA=Aruei-kjM_JFq$1H-n3m z_Y!^l!%%|xQnQQIg|Wz&+e^$$2rwi9OxSWoDGBuN)1Qm1+oXNC!5?X**Dep{Kinxv zPOLG+vU*@0EYuS6+w0AUxIJgrk7#mS-}@Yb4z^!v_4gcnwYHe@3HCby{ny!6e*yNk zqtQK8zFeAt#8e#)u(48JEQ*;n31AAMClW@SVR{_6%RM z5Dd5R*i-KG>+T6VEPwYHI2$(gd`;m>_%HZ=3$=AfzWW z*JCyYFw>u)m7%sZj1(0eD~v?C&CfvZ{bgCIysw?waKywQvW*NltrdP9D>OM}04cz#v#7KjF8-@2Y-P%T12^*l~ zmj~P)8c*Q%97A_h2Y(p=mVdXwennKRQX8B4X&T0UV4Ce})E_30eKxaIPS+>E3ZB_kujx0D4&#jYdJHi3MX3tiyFvpsX?T^Rjz0LQ7`@))b*~Ww{ zfaoH1FiZ6^OcVDbv{IA3^hy!%WLIScEu%ez9Ks-E^S)g;(h;zbNZuHN2V;MS<-X=t zbypjKOa+W+rNrIMMYZXbf!W}31UC4v|0{7De6RPD+GTzA{q0x`FB@!!3AXeM+v1Mw zx$Qz-r=J8}3{SD?L|CK!iiRpA<)r`H>wy#$EAAsU9y?wVTQ#qbi<&5wtM*v*;!gC= zo+fT5q;9as|B@{NOHmZ09v};EF*3lue_HNuOF%zOa^-hFWL9|_4JsIX6rt&9&{N3* zwb$58J^OG6g=%Rtt`C~y?9UX9{goNK`N_q3?*>j_9JjMB$i)V*$o{)G1xz#l@Uf}# z5uL=a9&Ba6PDFG+5ElnHfHQ#6gM?3nX5-F@;V-=FtuCs}he!?@&ox}(Z}sbHoio==s;!9%g)zrH!mdu9=o!E)BdtS!TbE* zzuXeFM4@y)-{|S=ex38?>4yhyj}_rE9RviK@^ae?DO}dVAvk*xM{PHzP-v_xzcZ3T zrKSo5@DOjVG{?f=ysvh!;JUTAoHhnKP+gzluF7W6Aj;zvrN&$d)3K?6qY-EyF>r(@ zYXjqtfHh$cYjpf`sHtr%!i_%ukjxfWE+Q4i^UB^+;_VHhx+?j4#&vlghLH9hI;zva4teeKk%r zEB8Ko)s^?8vxWRG(-7&x4*~3|+ZeGyqFU%Gn$Z#oi(vhfT7Zbr!DDdim9O|=+-n|1 zibCUCKIpPOO%4`~rpHPAVUYUVpT{VZEpGAA4t&^qe?!CZuli&B$#D;`cWRA{S)`-U zCkq8XeADU8{5dpEJQ5I@uvh#F% z$}brVU_w;(DvBmQAfBYz*f9xy6^;nzF?zx zxuGfTY2&|UAJ45P7I4yWyiE-GC1&&1P1F~#)_y6c3-&6p%O(0KX5ezgp$n%LGuED1VPd+g_SLnx9#3|3NHF9^v3m2B>X8^{7EHI;{y-Bz!AHP=KKWd zq+&cLs#co4TG>s$Z2ibvjN84=reKo%1BGU6v(4SAF00jNH}%I3)|-+@1ewEzJ(&Ij zs<7|VO*tx~_}hhN;P^^XHApJzuncZ#{tukMt2dS!k7AC5#={Nnxx>wTp{dCk> zn>;~q(_k_ABwin;f8PU-F}oRjU91bwJG($Aw>v7mQY46=rGp9?Um zm&7m6mFqT+L+tqhJpNd}<)W)<^->B?+Bbjlo!LY9r416fcjty4$4Zj>8urOTX*OIn zq%NPqNSLt7bncr$@5U;aQQaFtc5BhTym$&vQ@oDNdQ08v+uuM=az~;zqZO<##Pg@L zAV=y2OP{y7C}Jd2Qi_t_Q)G3a_iXRXsXpYja(srAjLX@VIxW%nGbyw%{$`+Y)Zv3o z?J#WNlYd%D591GEYeJg>j^9t~qxwH&CC9_j*pR@1xh~zqDcmP>*}k%|JD4}TULk{0 ze%pI*j&cvzOs-3m{9!XYj{ASh8FlIy*ZMX4ARmR_0oR18TJb0DBrDuYOT;QmPzj$@ zzn;SC+8;C`T4&O=G1GZa_nZ6)i{T0~uxt?g76Z98g7;;Xgd&q%wS{E{6iu@Xd0wPH z9e|grdooRbwrcN={YhbN+xrh{(MJ*Z+dgpd?nFmJfs2q$5FhbRJ5&xkJ!s`~jtYK7 zrH5tN&-PaU+<~Dc%bv&~CgLKqK0f82@CaY~0g`HTLi@$ME}zD|@(GNk3&|1J0BHN0Y?sssp#Xu~d9jqem^g2@>opCq%W zbh5=N2(ERrV~B0|(JSpcR(R9OJWu)a-lBqA+-i)FdeG1;giAztmHYw;39IhY;oA{% z3@84IsqwnlkW?2x?X!TuT_6*R28zS7*65@iajJm3yrBH`PIZW5Qh^C4C>Qu9b0l`< z0RDpx(KX=Nwdv=5aR797#m~|Eve3$Ywv?w@{~XyA5g_74)mHpgu_5sX0eIcCL4HqG$qjEy@bK2oD>p^jpILZ`Yw6@$a^!X8dvg<}8aDWY&gIXoSYkb?9{YOe240Gi2} z7oqNbos1Z04zYfs(y?$5VKV z_ix%d>*dFvd=X@ksjbK5lO7|jxmd`LRpbdg6oT2t*W_R#76SU!$bIrb63v(o`q`AC zyFhq}p9~u*16m%Nvgi)y-X7yp9Ysg!=h$gHj@&(Ez@c0~^>VY>nVSjs&3d9Q5c2%m zrVdDl06~zb&PR6YhePU?&KaB!7+SG_`h1+)0N8As{r5@`;8S`#c`*Vo>&@iIzKx5k zhF{o-iw5F^Yk+Gj_j~P&?ll>Xfw;(@{!uO62qY}6eBO*$9au$s2#V6&C{@LyUp}v3 zy8imJyF88G;bu~V{=<)rdTHf5A5<~LJ83BcyB-(f20-4U$XCchA!gQ;9O9#lVX$$X zdD;`96DAM$g5!^8M}ewMP;BRQW0ly@SNGGkQRK#dBCMnWrBSl~91Iv{u-I_8Gu8`yhB+s;}VY2U+o+u)h!)L1lNtUSKrBpw}=W?iARA ze^*=)0(miWSNzO)8aMs#@GnSSgP~875;rScp)`zaMY*qP>}K`)%o2;eZ*rBJkR(&g z?TL35P1A8l&d%Rj$WY%p4vrK9qQIa~8D(ACX0}?XTLdIa`1*-=g!V)Mx=M{RK20PR zeCPy!63MCFJwM%XeMbK0QsR_I<&sFldwemRTw+1M;n$%*q)ZrG5ptBlQ~$hNt8tp# z>cuL~ZQrLYKwEVF)XDWg+78+>;u%PTw+2WnFS}o?4LqEw#5O;Og>(~xNFOnU7PAX_p=Gg-&9O~QH#Sy>;i});aA(L|ei>)~Vp#S+|GZdh&oPHNb;yq+m zx*Z=;!b%NrPhyCup{!e-=wlA(*d*oedYPy7b3aMH>fHrHST>svXkpWBgGm|F2vlbK@XGVm~!4JF9H?hh$XcdLIND6n?n{})WOIQ#zr z6OXEKxv<7mfG^mnohLY3Wyc#1sL;JM6dhIvU5^rGOXKBX^&<=cK~KQ@e;K1iS{h6b zf{Lw{OMIH{#z{;D`PawK0~3?q0v!;6-HHSr)j4tei3|o<8>KwJawhIsx#Tvd{QD|P)wum0Zu{vp@a>$K;M8l(0j zN7yT!wPxgfl6z2AjP(8e5B0S8ESq1l`&7@62EV*9+plYOR9n%b4ga+HcC+A7i;5qy zG7)erzj*7iTXBRo?4-jGp2lfMbXl~snZ{p1r_}6Rq*Y7~klPy<1YH2WX=5uu;nxt4 zMyLZlqSEXD0QBOR{rOY25-5lAqnS+um(HGUtF^u9(k9nK@=2g)g7aR4mi(~VgY~mr z;1hO-J$i`AO4N#Ji7tUIGqWvj96-@d^t)gzDJ`*FEa91Z#Mzibse188(8)Twd*Yn# zpAn^Wfv-||)=O6Kqqy=>XJa@C+N9*wjVh3V`?Z48Jlv=*M zoHs$yEY;IKQDRKJYA0S+xTN`?a5GFya1zHgrEMx?U*(noYqKZ#%(B{d-*^CI zOG#qqdVh4x)a%Af#-sD%xVMgoBIMQd3pY9-HjJhCbxXw#oAH^EmL~CdfD8tb)}8M` zfDuo93rgYxgt-DI&o8D&kHE)EE$9K$z!VwX#+TKF4;9!=?kBWZ&)E_4BN4#Z8N3#^ zW85zxhqd%dsYE0ZQui&Dm6hQizF8`3`n$|hkEH?VYM)<;R+rCyx$K8IA_AyWFWDfo zf8QXGM9l%4+590N_#fa|26#~s*IhH{L^hCfetcbPsWQm_+(dh&L#8PRE=%w>Zrj~Y zTQ)+|J-j~cDi=uQjZHO|g$w)Q`#SwNsD zrc!$;K=4RpO|Cf}09}0Z=JV}?`sZYcXAjIL{ zYGRV%v`EyQsG4M0Dv{9mi%?D~-u*w_WgZc<3<&^f5OMXw{ z6?U*s1SsnG@5qZL?`v8vi{bB$pQI5%M)|KuBGG~5QR$Nco2dum-`q1PVFth<78pO* zZNF}GB=B^O76mROkGV31JpzI-328t5RJ@^1jA_6F`WAHp^BGZBAdc%HRMly`HX2KI ztMHR`BQI${1&c-+Xfg1>Ta3G(_^_G}#&?DhzCPbEjtZ5-7Z|l1%iN9aw4ThDsL=a$ zj+CtRdFypqW^lhdRVe#|9@A-iG_rBoQ-L}h0)f~OcD`U6%Mz2xeIIsy6~~|u0?g`z zW`U8I6i#zB<`)ASz`(p+Q=|8sw}rM(M9z2X`$Yd%8df%Tzj0iY3Mc9Wq;H^R3LBUk zC;^V{P0r%JBfjX)SsnWKRsVbI<+{KWLjVv}m?;EzKM*|@##vA@w!E_pik7)M@S~@ zFjpR)IDHgkAN}W8J!_Z=UwJM$Ll}$=Wcz8AmK)Y$P5u1PQ*o$!E{>5ntX-QUwI4mv zZtB((MY*v1rsdWjfX+U_X5O)?;-QeeH7#X$pDcs&L(o2@FDx2eT-iSL9TX*m@sMT2suZ zYae2MJ3Y$m8a&UNXFJbIsDxZuISDe@5at=c-t2QGWws$sDQM*kYk?v?7SXq-h&Hb) zT&x?jj?$z`*vrwE1gM$u*yV_bh~$U^zg}vu=yZvjr^Yil_VX`SIrjfnd?dfUI_!hn z|6J`RvF%nrj9ASwS%Xg$RnmGFjvzMcn-OeYI~@iG%fE2W)ZfE`zgkYTX@Z|p2yn(USVnrHSnXf5}+oq-akR&QZM4gy^fOn5bRsJwv7?29SzVOwG#*38p(iKhOr;2 z@sbC?>QLW5WqQw;mOq3g?7PxP_KkO*#!8|?HQUlXX%89rzK9hqD8sJKwk4kw*#tI@ zms>)N^dDe{)S0E!k??huWB<#-zI{w|z<&p+|9B%<3dFFM332PW?@`=ZV5yARDn}>V%U8w>ISdLw zeOLoV9U~{!%U5i8q;m=b@d`k#1A3#B&2_l32C5N(xCQyL@nU-e&u;=wYO0kV7o+0H{JrF={MYm zohxky!qSU`zikQt2Y%cgil_3{?bUeKzE7}o9IZ@HmvD#mu%x)}H=vShM*}A+aU9S} zI1gSwdo34UZKy19*nEM;MhSSE?}mVAV4QU^%|`jen-5jQ6A$B{**gsJ)@P4Cv10kV z$>9DB<3hui_j%3gsza5czNxn@d6E~&H-NXdC^pOfz=)r>%8}PY`kUn0qt@%Kw1E`v z!pyq<6cc(ruH2<`Yr2g$7IkD3O<(d5dLTNwJ?@R$qo-gGw?9o*FTb0Z8Jc0yJ;MZJ zf=NBd=GOL3q+ErMJiQfzAm>N=wHA@>^sRH^7_D|of+AQ68la$+aRQNqhp^!oBc$pOaCqZ!B^z!}UK^Kg*T+FW<= zJ;)ocBfl#EOvXEaH>mt|`wsYVBflTT1g$L5r4V|^`NRhIM^Z&q=Y_mvAo?ThX!cAV&=5cxG#$CsWy-2^_Werf^UR6*}TV5O5uo-BkAHo_64h9G`=s7!b5M#j$5Na~H%ozAyqwHdy3U5Q zO}dg=x}YuRJ2Wq^i3PEl#M~xLR^I>4N^+J+`_Tb&HSQF{!|XXkDCB{=9F-wEn&MVU6;8p?qp$-56pX; z0-jOrb!A5x&RvsykIS~I3%swd{JF)~R|7htRXF~T3bqfmHtbms)|Fs^3=hptLtPH(WlTCE<0o#SgIRPk@Mv3iZiGwdRImOj2c5I^ zl##A{5_`EMeHY_9h9l~CUR_+$v4-v5WPs#8MTfu$C$*NfQnc!QHhJlv9obLFa}x5n zlL+Nm^y}F*x+9=KV%nJeiUoyOLen_ow$`?^Y(pw>oxY z-tkGhl4n*Z*7cqRtFY#073U~vnerf1J#Za`(_i0@4&0V$*FJe=1RQhvYd& z7&V4bvC)TLGvIC&XgT!QbamFH665`EYH`pkYV>ueR1}tNx8ojDSXwpU)hR>UG4X;z zgrC#d+;&{P6*C2s-TIx?)#pQfH`@!MT05m|aeRI~r>OTa5;|}Af9U$}c&h*Z4IGci zp4qz;vbSv6t5CK$WM`8-juqKSqU;sfnVH8Z%ATFnqC68tK=J1?BKS?$IY?(N7H!sqNFYT5 z*Ci0={XXdiF#bL^YjNSTBCjw8DZ(v*p)2i6l0BS1-{8Nv`ny7Vj&d%OH*Rgew7=}a zBr*rH1ltL)|H|!J8uLqQ#{&2F%CEtE%;ZG28rq&emlXuvvRZ9Xb$^4dFch=+%DuEc z+h6&e-^-qbT~T@_AvDb*WO%RUv}q&en4@B$Ti**F!|||e=lXKFu>C2DS7Sz>dH#IR zm_e`tWd7Kc#0~w5WZEU&#@k+9_RTZ~9NM&?ClH@F;a|p$LB{L$NcEoHvb)W;`fNTR z`9WuK;zV5xGNzr@}BxnsxYeTF@ni!giRH?T|Ej!?Sy57 zb*4*nn$d~qyLJed=&)#7Jcej8yy&Ld2p{XqskquiTWiBSH*c=wm#^b%d`NF_d~OWo z2oSrbZt7OY`uyv6X^i5-58^U%w^Wx`M+=7K3m5jPky423SH5!u*Rw^<-{hyPavK(h zC6X8SMQcsHq=eIbnC*ddK4K>95#5tw>ks{U%IK?=`CWm~%FHy@m#j;xLxnl-^Ts(_ z0d4;`xGBTdhy<|~>r-Ie9m&zo zJ;lj$r?y04zTY(?KgXaLcoF2Q^-GrPb47wvFTfR(8FFA9iQ8qkTf8B(TwlO9%7|GG zWU=zXM<;F0AH6$k`3Nix*$n_2b=M{B&mwH{lo4G81wF=-HPe3>p>`~yWU(<vi ziIf}M-Ge0wO8abdu8Y@bOy=wkw4uH^n=8^2Pu5SWE$8FJH+}$6u}K6;iUg&X1p2OK zNo*0-`#w!=Wqn*$OwL%GQU=E~9Bz`rR4k9XOf4VAcwirHjw`Foqs)z4Sj%=Pfe_lh zNpnEaO?7D($)Qdg6Ac5(F=G*oMbt!@ggc3A4{xCDgI%L)Q*D2Xipivo`+*F5C6hVI%=fO zP0a!h!QwRz)eQwcyBYS9A!;_+okIf#0H zre1@c;OyENA4&JkGY)tqmce}A{AAX!#Lvag?!^fT5Gq8s;JGJ+ROpO^&I&cTCGjVR0B&~Ba=VJVEkckA3hHJ~!m zyZv8UyjU1cJG=;`Fss8cs-RDvD(*`$i|-?wD>AAuPJOOHPKQ5lhNH2(Kg3>I2(1wm z%zC_!iAt~8rp#!hzak4{OA;r+cneI8hKe88TaOAN1`muIT$#fWbbMKxDHayOzg;R? zf8uc^PEtbF!M|{#(wGjSXA2Kpb44lh%rD(UWo#?*wJ|N$#)IUHJEk_&7+x97} zDp)u0z`GP~@;KP#)ia{~Clf3cEU&4oOoNAw>;P)E7LvS6dNtSDEq`FTT>~+Hj zRIP5@A#)?Y!EbLE97D?ZBHS%}d`w}EFrk;ZXq>Hxtp%R+O!m>@lrX{rV82dy=>?w> z&b!=T*}&Mp5I+;bX~Th%g_3Hz45jTNvk{!7azYGOgFbOg^{jt-6!ALM8|nqn>n%e* z=`Xdu2IM|5>80zUo1dGFj>d-)U6N(tsC)Z7B%>T^B8(!6Y-s|>i%YI`GF)Zf4D#LBVJ zWroJzeaU-<;|*6RiP&%ckR;kKmDinll<|k6VLKsbkL*bdCJW#EHv8=7bItJTiL{oa zheLPUaCp-8^pb_yv;_OuZ(A2()L^v7g3NPMVZGiR2-={?54lxo^{GHjjO;%~IF8%d z4%4-;il4Q-gGA|`1~z4(!THUp3PrRolIAveSrlyfHnTKj`yC$N#$n=99!_ef*-CDT zpo{O$Lh_@ig0=nh7wo>K_;l;(+qeSP`vT0uGeu zDN(g4A>wp*u2jWQT{b2Wn|j&s72&%*C=@_9CW(JM=>bI=U!K0oW038}K>2KL7km)e zt94~3{9>xyq=g(5VI2QfX?rIVQ=5zAV~ta8F-&k*leCSh$+io^HM8=Ns`m&!I;ywd7Y>_>l`=I2{LAPc zaujCDJrJ&=XX2s{ST-~m1~=D1B3D$C#4LSd?RQJ}C~;4)1xm+BSKtd*G)xZa27lXx z7u||CIe!zKC{lRp_CUCQ#E;Q(=qP1;o$CBe+oUw7t%wQEYW9Y-?L3c2vxc+ff9#*G z94y3Xq=M7dM+%=M0=6gV$C%>z)M(L~XCJEKhHBPfeF z7+Jq-bf0UsG9uyE>RF;vb$`4nBm2ny=IdS?JIb*4~;Z7Zg*yp2o7r zcS&cc4XV`pDgRV5Q;;lL;+nfDVyaeyBcN2Wi4L!z8`66kF`nBXB7BNhWC-d3n~dX{ z46a=!dj!f))laEE%+4w>gpT=VrhdY!!mH+w*}Z;7wM*F(1&h|f%ZVO|o?t0;qw)HF z6pK`B7h!6mIA(H)7PKkH$vpR;Rj92g13THP`KG@tOkJFL7PQ<0(_U>vg5;A^KQQcb zGy#-xcd+r+uk}D%6wMQoJ?2GE>s!JbGG5v0YxS2QRo^uWpG1K2*p?JNv$#|KK0Rlu z?Tcis3%dWYaM-{asi*8sR5*eh0xkw0PA`&V#&}oS$D4VouL~_fr`We>MMV%EagUAp zEm>J6fJYa1IT>~wzxjjJWWthA zf$wQ1C$PKuojB0o(?+1}LA|>@5V|ht27rFoFw_{z`LUpgl;2GHl6TN|d2R>T6ET(y z!gu1(_6>A42F7`YVS8hd$3f@q{7s{ig=vr`*0dC!;6AW{&dShd*jjTECC?j&2U35 z#pFr)5>sH9h<19ww;iuXu)*J7Ml62aqdp(xaSnUr<>3<&os3RgA>;DrM~8^I(xX~j zLYn3lqka0lG{m_SlDag#Ihpd7=+UGi7zRHfsz%QJe|;lLT4Ll!$pmh$oMhtA+jFs9 zOW%2U`up#Iz3nTWCJ(JPz=0;v*CAE{5lAg)@uQn~P`6#C#POHWu#l^SWhSm3fkyH)igaLZENt^$aDF?`Z2Q(^e3Y8mZ}M;L9C*mWn-3;0T+6~f$K6b~qE1TX8{ z(&+br0`uf85u7_V@2PHS)_z?j%yM&MFT8!2VQam1ubb9}$ENroAlMEe6u}}do1}5F zu%)_|gk$x^^GfF(|EC%ikj5{LC*D{$_Y%YtOT;TtS63DVHq83FZNO0krhe+Jk~C;~ z$e<*M&xkG^r=%Wm+Awc3{JageR+8{`OCIT_j;7=Y+4reJ{2Zs!Z59uIoLww?z40l!fjfTgGaJ!f?{&hH0_Cm$te;kF(!?k zexaLswLLsat|1R?sg}!g^6Eay`RgY&3Q_i6e1*7RRQT5J)&0!HaW&ot{zb$gAWe4e zV{;EA2y>`TG|Jh_7M;h9mV(Dz#)5z~4h4-P_46b6;e~Ap662Fz@~{4`=9_&h8HsK8 zv^}7yg@8=p)MdR&VmJo&r;ZMAu4zY+8&^I`5FmN zcWY}Ez}2s=qH5gvb6Qj<-xKt1vraExLzuIdC=pcgrIoF9Uymv#9+SPlGqHdW%2P!I zKGJ+h;jkFK5<)l<7?p^a|Jf!Zx(!-lAt#B^9t~m351AI%mTxlh<8{s3;&q}GY?u8B zJ)R@m5~Ut6+~fa8T8${f;>5P!<|>5BbYA&IJ{R7+ohNBfg9$FcrNHE!F8tWrTRhhY z)kA)?(SIJW=ma_e?{ali<9QHdpb38xW0W}0G86+F%y4p=e5xXyuI#)#5&p`e_q5vz zHE7E)ec5~w2-P)Hq~xLh?)+fp(3l^^NjUqntay10hitpaJQb$&RTy3y3hMJM@@pd+ z{Z2qrfy7poUQ9-~kVo5}(Z^}k`k1|-hRVKA=9ugEcH$ccy!xV-o=Z8LP}Uqh)06A+ zHq-t}(|?S7^_>0r@dBem+HsU$+1>f;)Bkx^mdif^mWYxH7b+4BG@v#1;zkWRLDU^? z>K{3T?=G$LQ3%i>yV&EC_fHWRyU8k=8^T;R3;6h!sb=hl#(60B*H&(%LGHiG^ zm8Qig{jc{l_b9qEx~sig6E(=3ESIOU=u~?q_a^9Hh||&L@h9e8V63?8K4^FO@s2kwp1v;5@=)^j2L%n406}w(!G_IjEUgEB3q6G zT2!O=)wprPHcAHF;iK_H5BElgAV3lN=bc}Xpd}!yguzHUl#8hj$Lu*C5IWQHE= z*kOd!bp|&ks{%D58(t4QDo-Dw@zW?t9=r;m`%#!@Hj32wXnAATh%h{mB|^ABWSbgO zC+P7=_;${!b;FZ@P&GVgl3ku0H)H6q0#PO7t&vhDQj|{kaF$hdQ**7qP;{ju3G|$8 zS3STdZb|GZpYn@8c0;in!Z@wV=ew>j@9cl+;s_7$_KefYiZMtjaMLlkILdy{RloYR_-@XFqJ#36V-<){R+bPfcy!jn%ec0!6rMznb*%7cm z-15X1rZhYF)mEQZ0I(G!!}|7G@~-!6vQlF940Nv}96%>Vs$m-Eu@}ulPumA5HX~kQX`OvDW?X%OJ!|PY^-{q!FY= zNK%+psnpvz0?}t_skwORA-eO-+An$`j^Z!4Q95(P>KPM1BTmU}XwBEh*cUW)e`uOV z?hj{4ZA(%Cp)k^D7+$&h?FZ%>W3n?y6q)m-QUyy76)`IKVoJ+(sg6hp(xLiI+bFe{+kc2=?x7>A87fO6Yk;JvJs_#aY3XKv zxO|(qJu`9plco5$CslvqdN^>vvdXmvJ|P2OI9~l50e?C9`W^+yw>CSPkoh>eeE(0t z;m;3EGJ;d*Ohx*jx)xfOt5ja!E>qAfe<)Q#5_=a3fB8)NNwo>bMU%E?}^ zF^qdJ6)V-VCN6&4E^sw+yvT-D9qB$(ch~f`_Rn>fkd&~k==SLH#LeM6Mc5(@r%9kn zoOMQS186&N5^<+|E)`m|yTu_{xa*wM)u9xio2irUdZ(&B=VsBN%XE1O_YJ#Z(SGM& z#;T9B;4G}*@EWO`JaG)FyLs&<;St4#GAm&i?97-)3$FL|m@Ws}kIx;Hfk#$G5A^G2*b>OMHeStIm z5Nbb1EMb3eCv)!+2o=`^iu@TLJkJtNM7+~arz1^Hj%Z1>oEf;!dn>{Mj`-2G3Q!2|2%0xRw{QT%r16VOP(P3~E$=}%Ton%(EnTMQ3> zSvyegsCTg3b~0s)!qF>V*TDVy`1L8Jp=lYf{h&$D{L;JSBq^4`^E!tU?*=zaHOA24 zr>pd9F%veq;0x8exU$IrhIiZRO>w4#2bFe)(abkj;=DfFYf5&9aRB?{5xb*mI@%OLt0&QOz4gyTp-Ml$=exwwNnh5QCDZqU9I=I<`MA)L8 zUQl1zOe8+ZA4MMLG^JlUS+UrTyYa1CRSbme&2Doa|9aYqS1q5rP=K6W@KOu`3L<2~ z&u-g6sAd!xe4dGmJ-D}>2f$alZ{Gn~D5X&d;N3jso^7J67BkNh&V>eaE3qco6(v$T z6gP5nvnRbt)0e?Au2ZnmE`ftUZA8wkWPQ^B@FHaWri3faKjQ%g={S@<#`u*P7}py~ ztMj)jtJa#*klOC+bcIzfNn#JJ+*jxTK~wc%#1-d!^k~!WQm60Dl7!#gliVprg*7e6 z3OEna4MUCz{7tdB)RqvxqnqRwoP3WmTNMiZ+qqC?St72mb#(87f@!Z|jPVJVYQgPJ z)7GGbNw+VnSk#1qiZ+YZ%VqfFF~AiUk<`kJzB*fi`a;Yi zRn(^@Ml;5n@n8)+Hpl!4K?AA;Wew&W0mT#o%bZ1e^^T+N^k{o(sa%2|Z|+WZxV*Q1 zGu{gd*}0v!LGPJpDU&kk@9*ry&rG?nTs-I}63%y9!y^*HA?a>KlH@G+uPxf$M*ePX zNyzXbl^eDnz=p55AO~p$;mrroT+3~m@IK~2kfH&0|GtdhR$KvRe~irLa@3{m;n&Xq z?-;765@grS-2Eq~Uo52h8j{b{_cGSlO?Fn|yabAl@e{}@R0CDL-xc=?*d|*-efXaW z)2DS_675S~YSwUqpf3;z7&cxNzlp^rvnuq0A4x3$RDLP54$k_%w5=PGd^J<=C^KJD zbuB`$;1;Jg!NH~|3@iGB_+7qV?uD`P$TzYMn9`Uh-owb_cU$_fT>~RMcYG{ zvHoHGK(|k;ioL>>EP5y#WFoxw)x5dHP{s)5O9EwAuC)e%jbE% zCq>6aXbd2%f=93EOYF+vjJ57^WiKYFF*k)c^06@u2OegsRw088!j(la4{$wE?p~YV>tKGO+#_ zuPyyGLzQ)!8Q<4qIzCjJW;aBmlHvDg&da?VbIvF4Dp8?ZGIoG8sXYEcqCARh+nAt2 zD)iK2K(w#`Gdm+zD(pVxiS}LN5VUL$xBKyg1A>X%oT@U(_dqt^>_Z&g>bCLOKFtw% zz9S`kJ1Hf%^W&Rr{5+4dM{dHX!Xp}DY8rq zQ<6+l-T;D867~C%G#*1>CUlTG*IX@D`t|bv9(~eo?|b}I`l`tUAys{NNme2JCu1Cz ztcp=Eu!7kqtoKgyWlZfiO1*WgWiRJjLU_~i67)>JzN!M^6tYbo-Dgj@3YFKNml=0R zmj5hE;y0_e9sKCadv8J3I$Y_;#QId4@27OKU-ml-9V!$IDBEv0X!s16Vk!3eb1mmY zUg)zIKg__{mGx7x!hiMNaD)nVi8|n%`eaVWo&5Kuxbx(_zldi6Kp@#~_g8u44{F5d z!?x5(ZhxBUFeMX!YJBRwB}|NM83q}e=%F02K5m1PXlck$>S7MSYpz@nyPU$8J(HwY z098^@?%%LQjB=^Kdw>K)@9U7lX>~A1v0a7#{YwyisW^x_xAF09>QnWn) z^+I~{F?rUF+A{qv4n?T7fhcdT%QL5H)6a#fn4o^+RI^vOK#g-|sau2$qrFyR z;p)N|9m`9}h?-N1u!5#H>=IjT{#ba-$KY!4x4HB_2{fsRT_GeKwD&%3E}Z--$7D;h zB31EqR?if=;7gc%YEc5YVOl!$-8K7>WUhybq>^^#58j>*CtV~h_BJpc;Vvcc17j}7 z)qANsWA|cfoV(WY_o=nGXI=9fPMxNm)9)J-G9X^%EfxRmfQ?@3@l%)au#~7B!g^Zl zW+onh)JMf=-)V9h3DaZ3RLo zRCb}`{|n&!Av}zEbG(#hsO_Dv*#~H{nwkXqk$bS^nasoC`}T?l;+Ywqszggx?E%Ro z8%Ey0flSEW4kP+tPDn=BPXaA}bw*@Zp|49YV&pRQ;I6%jLAxE}+7A;B^C(gv8PS%o zeqRskp1CU@ld=_cEitsC48(owh2(}aLGwb)@FZDsI1+YidZsf}7698yVNdgwaO?(X zyb7uI^-UeHx}nvET|4{M00;843gH&F8x=UKJvd&ZWY`5!Cs^vzu_w1t3tAvDjS@?R z@nu{U1g{#Gn{(=Z-dvq4wjx`2ayAyH6Vy?Q*w2w|7SW#(sI>ZQh%@8(id9xp)L|eJ zjZb3xqYz?A4wZiQg!q~sixlzp&&sb+1ZO7)B0rvX#OxO?brl5gnN4vsfqNvsk$cP} zfz4!@a!TmAv8KG((>rs4I5TwF`AmtWj0XwF`TWdu8dQY=xSXO1#68^j%ikUV+#|A& z+2gBli9NPo1FA+t7;+#76>mh`0YEPQi}(OPFb73{9a(6OU z2p=Mi?Qi*#?MAh{s_Bn==U9xqt5;NwykM03b$*Y^($)B!tR=9_gQ|eWRHHaI@|{%2tI1hV3sdC=sHSaF(sE6jUIz2ha7Ke|{mC zthB7UL{7Z9)o=*ZrOM1l=t~CP_OGPl{0IiHFxe(I^(dM2@lO^Wr03{C>xa^-=WTyC zrHe-?k5w6#-Q$#{effy4V@7h%l6ZC>8RI%bBmv?GE_9I*BOTGTAu-?&PvX-JV zQbTx{YFkV(V+UAwA*-onu__KQ>QaE@ zp8~2<12#UAJIBX-D6MK>ktfc?hi33?URFfH5{p@-9ajGSlBGcLlnchQzy2_$#Z%y~ z86LeDtPyWn$x}uc8DDr?QVE}iMy)&YS#M;SslE(R2lp`tk$m(bk$U+ScboasjVM*$j4o8i7zYTfR zX8l&vfnN6gHMU$EYic)sJnT?t)ETan_<^{YLWZ|(rg%RmQDxlVCoF>iPphaapejWjHp9^}&2AGQ_ z8U01wR4>X1S_vsA;AVG$w)W5WEr2#6CLw74fZwd{tE74Yoq#U;1h-$p zgYnHUd1n!pG_5G8L#-xMgjt{(ltM!(LGKJw$a$t|k9+bDC@r)PBdCl-uEQvm#SLW^4PM9USV|**p#k|Pn4pEfM+0{m$@J4cE6BN$m zqd`cXe^%xHXEn&rISCALE3n&rahdD0|D&b8Cr4RHXRdW(tkBjVfe zagOtliNH!zx=)JCe-||Zkjwq^omA=_hmnGBHS!e@aogACb|b!r7lspISKxu+)`Tzk z;^C)~E(m;Az++DfQ6p88+wytxDB~R|J_+5F*-bR#2SsSuRq4|f?+ZO8rSN+XSQJ7S zu&o8g{zeygQ>hhZ-yA7&7Dpe<9 zoZjHZ^lL>mgx8l>BAR35uJw&2boI1L%t|Vb%9v@y)62eW7+jrnat8Gcc5fHvXk`mKE=(&AXX3q z8eQd09>_^<-lH*jIlstq@|buOa)Ittv`HLLw@N6|Aiu@)1@HMi6dH9?WxV`haEfcB zV~pHK(K^Nc*u0RJvX}GwsSI}d23`EX)_y3dJl>`TUwnLPfT+=FN{9Ocdgpe=SOXCQ z{!->{8}x5j4!$lS3kyr7V0*&0tF;3Tz>L!YcF6c&KVRD$#1J>TA~L*Pj!m+s0Bu8~ zU&F2agcuoG!BQ9vg1k&X=7k*5fSM`D`sy8NJVAG$_vH5@0VBU{CcN9+>P2#qsZWm( z_p4WEcQoD{Y9*B|QTotTX~W|a;16?*=v+&yxFjd|HbNr^)TCX6-)d zke@hnM;COV{1u0P>OcL!gU|s7<)mc#xVr@$n3ghJXsBnJqYcngsOR{Qm;J13$$g>K z29SjFS$lt0S)A|%xV|(pAdCEUTP=RG&~<3yE}?^id(d=YJ@3M|1bQl3+LC24=K2Ue zz-^!2Ta){Da4glNBfa10&^XQU<9?oNwsv28K2@>w{cfl>cVReS zv7=nl(_i18Fa$A>E2#lO9c<`8wWc1sN*YE3llWw3;Tf|Vnylt8e+PKnx09zTU&FOH@jCY*D~(5A0~6UO18&fsfq>S zwgvJp#liL>A@~lXxmDatMH&=ORFOAOb1goOfT`E__S~Z7NoQQ$i>=2IFk`DbiU|T0 zNcihG{7KV00{+$WPUEdrg2i0J!8DnQ{*r88+N3~TBiRFr?hVGx&{V@ApdCY+STZ=H zTz`fsUV>hCO3+cmA{1MR`SZb=dq#)urPyfS6~6x2Y29T*?;5ELlt z82Pa`R!1mB56=<1vbX=YvSJeG^-9vq*sotzS>yur^~9kVbUwGx63Q7~ozn#M)L6|N zx{xomO0{!Y>g*Vi`|sF%3ZH>R;bYAGAwZgXZx-cZhYP*(U5}{w7#g_|OFnTT^vs|A z!T7UpS0<$ITSl?rh-1c2DK0J~Tj#eJ zfUNuy{qEkAzTKJTOqjJOX9!Tp8qHTDMhN>zaF^#6+yW0-|E+qtlQx65y zxyC&3~@V z?Pq@Jg6x}edn8X_x2b{Zf7=v<%rK@%O--HMix^A)wulvn%fXqiwNaT{+alR%9oSBG z87S1?*X^fcV-vLMO4i}lh{v@8H|oEo2?qGS|1C{u@cL4g@C{oqcYQ&N7IsPY4+*XaUX7yG1^ZIyG+vmw@mV=!I|+>o8A~Q znWJWa`zzPJe3(xl^mkM}n2_$3%lwzmF}-`wkN=iX2;17YOcWDozvWr3Ubbh!-hg~u z2YO3D)$RT^Z08gK`)SDxP0~fwc+`ZLzlXK>Y&>wu|Qh~f$GFPpB3%EC;PdY4#b zfu-9>64oN_JU?Zl16)M-4y!x%`23eTE^Uf&q6QhM_kLEIJ#j?OO3eyVc8RL|x_Rxi z=OxMPhsbvn4Pn9`S{24A+DMglnJezpV`pLb-$Rfgo7EENE|N&0F6fS4f;Ya~KTn!J z4TcDmgFQ(QOpLw@tdpRD5=hJclx{qht(OLA&J4}iN-36b>~bLRCl%=E1gZMfFo=tx zvKH@b;$Zn7NJqhLVX-J6cE5cpJvaA=5`FkEHaz^=R1IXQYUaCp-WO6H@Wvl`tbI{~ z1n%m$9zDUU4JZZkQ`Gk6TLjojqBn%F&L$)MU0^&e<`ej3{yz1udEeLtiGW$vn=LSu z0sVydU3(RKT8#GxZ0P;I8yF+R_Ln|KH1vy5C z2!16wG*s99eKHRM+f6$8vz~^)lFM&mjXK@u29PR&8x<54#B(38(Ww_nVus1l59Q^9 zkb)LXx)u+{2)<~h-gY-aj1{Q-Y7eZxF$%D-O-Z3>louX8ev1ShBUUQA{Rz13i!JWd zjXVe<@XkTXzKl=6_vcH%v-sZ=ShdpvKLA{3gI5UpP6SM$vuh?Zmv339KKv#%^$YRi z`Q2ZiIe`pwTGD2=VtVfDhRA$+VdekH@T*x14Co)H~h$5*&v*!P5)yT7mG zc`X1w%Rxs$+6;UaKeptSAoLm*%Z-FD`G*fFVqYET1dhw3XQ{aO4j4Pf#NX$DKZozY zp`orm8$V$L7@@@YKbj+X5bMO5me`yw!-J9tLgQHk)@6aGi4=Pv+`*xQ7#XV3hg298 z#mrs*z8C%&DbPl2ei;Iev=w`4QQOCn?_0-aA9Jm-r?mTjS7#DTL5ipRvIpiM0LocC zQ3Ifii6uf4nI69xn)3)r_|c zX^>jrIWE@f28scr1o4;H2~{DOD2|rc?iti=1R?#W>Wxc~m7hx>PY8!P55!dzuVd)= zj7ia)4?*^ZSma>XovAOqS6Is%`r?K7;qT!Du7@9f5%<0qHI>N$tVPmePC*cqC`7`z z!Hp`y@db7I1;+S9?6c2+LdH@z*tixY?^Y9@F6MIY8Q8Xx*-ILT!EX5@l9IN5n zFz==x;0p;e>n%2irGO6rhLaa$dwnSSEf;aIaX6;kp$mcw2NAZ@uL0viRU)!*`GuX1 zxC+Bhkz-@}da-v_v7n=<|9P1xl3THWJbDf69~buSLX1HyB2-gNF$7d0jFgQT(MUs%Fro27Y(n)YlV9Aj&j-49@Dir*uRE*ecKtKDKVvH@SlX zH>zuanDWb^UIZ@w@fbg8v-2buxZ~`grRL**U*_if_eh}mr)AK_At^}*QsqNUU3dBi zH)!zN4gYf%Clg7xY!YzUu2HMh!yZGV4%6f%R3p&_CSlm`24 z-(15U6?Oa}!B$?RiC+$Qs{2?Qr;+|<6}-~LjEx}dhc+WU775de5m{31vi-LIEbYO< zn?}yz&VwOyL+^LkQb)FoFEOan+_)voyzJrWS*sD{XnY9ltgpfSCV)pP0AvTYB&{3R znNOqG{=Zo3AQ-47g>}BnCJ&!sA%Pm$PYXPA2H+pCeNxpQRz*la4wi0*k?Hhb(*$

    @Qiz1dDFnvG^stLK!Dp-=(XC%)D=`d z)31gc0a!{Un(s>BKh(+pi*&%bSh%{n zzaqLHco_Zeqx!J^{QS10+}Vl?mdIH1{q7O=Y6xLTe;ERqu$O#D6GRPcH}HK84`P=X zl)Lc8$H!+0?(^_yUS0#y^*K$RWt(5bPiedfa5+AkJuV(GKlQu18wMWY%fEgF8ManX zhW+rG4sqS?rMRH)S&;)PunH5;-64ak{Y$o;SbxRL_(RY{=%3YDD^>S2R&?*z zQjk42@mtexM-6NT1pOk6O+JZ%Q_3n`-0aMZiKDBg3L5LUeE( zTn=L7g@q|CTVEVh{rKVfZ#9ty_)h0tJCIq0wSjb<(Zl1dNgmVM{Qi(|#$Hh8=!*0N zfBi~0Xs3-_#rk^q4N&i}S^dbU z{cEE$*7MTx%>1E4?23&R@1O6w&YTfl;4YXSd1{6m5~RlI6Z~KqjSuopE&!z)S-+jJ zZTHpM|HA^{FM+A_%f17`wm^ng`XV+;e90)hh7>61ES#LI4S~yjyf$y=YS6_?oUI6D z0|#COSQojy>#j9F2GaRJK6vQz9vdli1f5jge*g6rG3w<%CvmicbrMG)EQzn2_{4)q zBetW*bV}Lq_jO`Ky-ms!s5#T1O^myL3M}tqezSh@dt~V||CYIB@MqU_G%NyIQ)s{K zhjQri;20aOWW3g3?Bu3eHT!mE+3NCyVksCTou{|ME<$n48=Y%5x?|5QB>VFNK64mW z?yzb>orim8)MjeK$XflKk_$#VqL+nI{7zp;ThY|s11VOk@B|WGNg^b6A}Oje%%XB} z+KwAC@NJ0SxiGxqpEaEZBq6MosC62@ont@PS7|XT7|=TY?%D7MiGj5JV)7Ee-{S$K zywct`2WmL5$N#yZtLL&m?9?J$@4co)4XQTygBr#Yu8t_s`Pn*1AP=Cx8TM$q^==Sa z^KJV2XF?}mZtve@U5foTJwu+dqk~-)bA$ZutG8b`d_1@mLk}CWkgx$W6`8Qoe=ATP zeX`n^_6h5SNPutXo5a7RO9jR z=;ZlSxzXTbFLQNaB2^mC0$hi`*fM#~w>Q&0_l(&9Fa=HHSc=>2j&B%Gq>BFKOj}|Vz|;+w zdwb^s>w=2L1y1%NT2qwBpbMWk+W`L&D5I6`(k6a%Ej_kijS;FPiTUA252{wZphe-U z*w9-J#u+wUz9m%or$mS2n@pk(|X7984Fflrz?5tTj2Ea?D=gh|Y&bgbW#rT#ZK0cMQc{ucF4$cxc!wmDd>(Gzw#C$RKF2-&s$dtf_ z=G%$hHR!raEPV66hzQm33rCy#MTA*8GNaG9+dt>4;d|iy$|QUG>2V4FDOV|0UBltO zfXTywj{|~r!7892wEsOLw^xI`Ga-bmtqAoxrJjFnYhV4A^WuiowOGOiA_2f=itXSnA`FC*oG0QYPe|15|yb6cicKi1A#wm;)hCY_pe#>9d`4ewrB)9vb zvEsOKe7pSqLecfShL@)&^m!}aY*Y-pTjk2HS&FSu5OxjN8w~v6Bl1YhdWE@uW7{?- z0+v@{%1J-c8yN^)DZr!@J#S5h}CII|UesVhtbpTHY%GU*#{OuI}e2OV*QK$sdS&z7cjU~WGf0{KAwmY9Ho z?b-vG`qz$EEeuH?#QU>nV9(a$OHeNcE}e>=?M}7GV#_Yt=@l~gP}U^r!7S59$Hc%% z2YnOOdR?eghs*znj-I}>Vj|c!LY=R=Xhtg6IJ^Gq9pV7V?nlOk$A z5Fo=Zui)V>={{d3rn`CFwIN5=zYq)y1z3=jyDM)wK!~f~wNqFDs*E-n-&s^~&Uk>1 zu0)+^0vU$koY{BO`!%;>AQQa_CXzz&oY?=gMX@)G6t(@`TF2N!ec0UQLVwnMVWy45 zSTLoB{U~E==P4akLdqp`Dxa->r}AOcUY-%xPQC_Pmq7Ev%eXW}6SYm;y(P ztX^x#TRHMWVHE7zs*^zyhJDYyhR|*b<%SQ#p2X+*yDfp97^~WGlRQ(k%ysCDhPfY6 ze==JO4n`2d6gL;_r*xSMEZeU9K?yJj(-C)ApzaktOyXHu81n`{Em0kb#mxr(H5y5m{Y# z_MfW8%|byuy?xOr2~7D3l}<`wxCf6XQ2JHX(BQmt2ak&C2mO-q^W%uYDl1mIIT%z? z(rq>x%s{#=C&zME=Uv0&GU^0yF^h{p*gV7ZUtk36<0CgFoBBF69vLTM+z-c|FEVNR zuS#91$tm0-T}o4)9mF%(o9Ihn_lB90vP{%1%OPN=ja^r*&eQ*2a(r)Y_vl9B@x|Efs9{rSP==HO<;473*gThF-%%O zsM82r$tMp{o#Etx%mb@c@M|^gHK)H-X{onYuUvNaG0*cU(r*(I7NYWs6-^ZC{Y!k1 z`O>@q)xY)I!yO0H{;*$tYrc=ZJ;rbNyW7>R;_+%7xvYvG++UC-v#;Zui(@7AHz)i} ziMAs{o7sEV@E`csg0E4(f>HBit49y3iSJ%-q!+4U_(h7kT+pi@FL=^Sv%vrvB*pYy zv64hWd*+fY-PL97`^UaGlSK1+j;?r}3e-n>04_-1qI{dt$3v@hUzQZJ=ZaLPKqpe> zrq9PLeR8BZ)>iCJXdy6V;0!^Z`o6E{L9i18VP9j52b4_{1YZD!ig)|Y7eA>k!z}*ih7&!$Dd*2USx!;LC-JroAKiyqO z>RX-`P3kbpB1dhVotM9Q8a?o0A^vNciF9N4x;mm#`hjQrxb6J%)srM}K>OWY>!&{$D>WX6)OApWR6;bl>V;0t#_9(TCQ# zmmB-7Usy@lCxeOr)EIp_m?9Vpu59+!jn~)PjX~mM)%Jq=iy}5#WH+(=%}W|KP?N1r4v%R)XxM4-nHX*u73tL>2w${RNpjY};xfr6?CRgf8hv=BhY)yvle#G=#QS z-|H#aK7m^TL67dt+S<@Lx=M=o5r73T=_%JHX_$r>70k7;AtnlyydsON`+lf z6};EmGEQ}VTX@FQc=?GzU5t1ml-1&`9}Xqy%hhL!Sq4aVxnQG+Mjh^mOKi>R%4^zw zq%iz1&+E+0R{*761X71t^2p)EV7Rt+rFkPU05`yI;S&%PIZq~boK@1aeZ5VL!cKj^ zvM;gEEmS(C1y_;UU44qTCLtf+FMv{wEre6&0owmWlw5HR7e2!B4PDkqSOe!+2&=me zIyhEwiwm>)8v_3MzH`X|r$73U$f77=_a1_#1E%S!_~N4t%8pQ>!*!i={j6`(7_=>2 z&{9ywDLnM#o8!Tcw`UDf0yZU~mn-!t!swaqrrUn%zxRt%J}&PCUw*vrhYaroDq+X` z-Ae>-H}*r;&oBGi?FWLEgHo-?DO)_*F6I|mn->Bp6fRs_*(QNxT3BDO-+s@S4X6I* zUm~2HtgfuE4t}O)pCvCE!N=kcQEdRvJzp-`M<6dvTGN3sCKkv(L9a(eo>=&mZ1#Rf zRGYTMlVPv$JIT-4YqY>doy6O};Q$Hxe{W4E@ssALYzX@i56^I!E|L(!p_1pO_ z13gI>n3b#_J5g;Z%UpT-!d0}B2l4QKIjPj{jW{D3WF-i(A)OaX&D|>8opLJ$>-e zpV8qx z(-vw#@|lDdV`Jz(;-Or53-&Q=o30o%bN(-%2531lN*xhxXgito5&ck|Ah!ZTxX$)Q z@q0CwrB5Ob`9ZSfT9fY>lTGRj@3l*v`-BdOsjz)(hUoQ92|<-=EcU1Jc9)t7+&;v( zQ0iXBc6H%0J*Dmww5ZdZF~={6s1wdt^c;$5WEx9mRV2D%3+|EJdrPs{y=h{l6yB-X%L2IZl;-T4WVwHRpG%p9d;^ z%sNGM&YL3=>*fqi6u=#V+4weCC{|{Gh84z_BwR=lTNrSYAAe~au z4I%;}EewcsD$+5OsH8=AiiCr74~@dm-2*5cL-%m@-1q&Q_c`x3zsSt|WAC-s^}DWR zfk&td_P!~pz08!{~#JctFWcNFJ&#|Hj?WI3W zaqhKRK99kO>;#LXop|u4GbtmRxnl#98pKNaaUX*EoA#AGr3H%|HQ5oA$*oCRN-9W9 z(Dugl-poLKmRWPaS*662x2^Ho)RSDyF6(}Vu7n4cGw=^ak&5e_J;O^!>>OyP9&%hMajN-uHyN&}dfpwOZ>@Ep-MwwkvI_`7_KP z26m1n@9lf9G38$f<_ueZM+I{)obc>R-IZ)qFj!qdJ80il4*VFKUh0g(^o`YG7_z_i z)PKUj0PDP##~4(y`~p)H>fxn<^1{0))J+hMdhnW-|83Ty{2le30Li`nFfO@6;y*_gBb1MB&3n|Mu3(U1!O$mMl=rhnXPk_9)c+<`n28alf9o|K_5YE~vTeXSrj z>HA~eo3=cRF_~|}!`};*rH(5^?6Lg!p!pw%s({9cX-Elpg?`Jqd%N+aT^mKBh~F>< zw*^`}@_uA=?A-P9(}bw?`qX(J89e*hI=N2ooqx2BI84!_PG?wv(OF`-F@lD*-Y-4O zN#i~C>R9nBAOcq_gQ&mgvN9p{Cr6XQhkOOz!e&6P*R8PCj_bUO6NPQ4|8HZgw0em$ zj?2;lfB$7x6|((N%Pev6kWLV}uuS+XRf2WgC6;azXLnwlvWW{R zhS9uS^WL;dglJk+xKb8oVy@j0u^YH%o9qcJ7(tVb4GUzw{+!|(v}FUm6NBOc$h}Ve zB4IOM&{M6~)l3z4akd)l1{uRk8AMuOrpzT~+CtDzgoq}l<5Ek69wu4>Z93~NZ^< z{xi2cbSlm@(^Qy~UF`b6{^~%SVDlB;_QN+`np?vk{<&Jom|kZQb>SimgL{-!gLk2{ zNsbbuw$wtfXzPsY-+V6$4zOq+1#6UPKS5FvIhq080oFg|XV0i3Y5608yvcs2Wv>Wn z%N>Ah!Fv9z(uREN56)*ifUd z$H}d&0t{H9X-}_4jl#kNq?2l%e)QX1i2*8#Nrub^&}y0Ly7%0M)4eZ6!f@Kl$#R`UZIhtudA1TB<7qyPiiXBb z$FZWf0MDrxdyIny&46c(@8^mdSMhUq4?&739=f0c7X(YzNZ7p8Yr*i8N8uYH1(;in zNzmGPYTEVR3|fpRQ^QpTCTcm)H=4w$vRYzmd$&KcyI=omS#8iev5(4-97JZC3-8L$ z69Kd#r})JM^6KK5?f?B#(+tZfiVHEP@Vk0IeFiuJ28jS#9f*{1@67@<4(3%g)N29U zNHIcx3G9-ZAxE1N%Rr*{>*0H;Dt)t9;vz}b3c`k(*pTix+B3ld#IUTHP6>$d{gIiq z0pL9D@<-otf^{(O(fvdNPRtr~jnTP1t@0LOCUh1#)&G3T3U3RmwNx5Q7x=7iIG?F7 zYcvOu^FlK-_)}w@qxRP=E1Ejy>YSa31z>>70-Q*7`vg#tOWD?X9c`&joeJv5x6F`k zU7L5S$;M}EDC4;-6Tpko_tfy523#p#jAlqwd`B4Lcs*nt4I4&(Os1`FfsEu;Id}g9GI)7Bvdjr4phnr9 z^3vX9nRFM)<3iek=b_%jo&E{tK#idXoJ!xRuoER^-w+J~_+bQK1Lguj%Y%Z2#kEUU zU|Uo~PIUW%;%2+1$7NR!!OiN>; zK$|f&uoJZDt4LJt}%rcJ~Pb z5&1`utgAs6BFX?yjHDBEb!ggZili4*O;Ztk%ZFTFsoo`n zomPeG7Hhr7>XX9E84!M-(!TmD1f6>$D)neWk!v}|%P1cz z{r*kBqH)p|LP1R(4n%z&y9ZRx;OU|QEB#P%9}wGL@!Sf5Kl%NaiogsDox-07hTqX7 zpjELJ^uTf{v1f@Lbb72+^1PY4O35i#`P&aLZy@HpDQ&{LZc8X7hcr-rlb4xQ9HvbU7Ci${_Ng6vtY{bBssw?rWQbCx~Pjgj%t{3 z8#fK%B+=4>bS(v-`X8o@9EaQy6cWKf+-Dl&FIp_QKCf zp3&FL4-s6kFux>31)S>MZF5R!XZBur_d7Fao054_bEy@q+o)XQ8o&IE-3Hcxjq>LF zTt=Fty*VSF*Ou~+FWq@|0<$uE@4YTq0HQ>&YPv+%j>ps~dJtfJP-C0q+w z7j%P;aM)}`s7OX=+lBynrW^jawJ%88-LdozuS+Rqz(DB@rL z?ecgV$-bCboD>LHWJps9i%?>hs9@I4YE`I zvYf8lLa(u@QlkNb?AW2@`jfvzH2elnxM+`sydlzU{LPmN;LgP?O6=ukuDU?bH>2#u z1wP%geB=q0BKNk)Bp9cha}6nfskticu}tqYUV=%%f1@Zle<{42NJ|^u_O~~2Vvow6 z%2|3CJpMVK-I#%mboq$-G_`~bLe{rvW(KikC(8Sd5vUp2)sbNz+}Iv?vml5B-Zc^# z|GdhzC=dG6!KPx~?A~7cx5udCM7~e0ilHjalm-W#aEm+D^>{g^v>YyKF6>k$Ohv|N2n)Enpt03K~{~WA;!9&}+`8s?rbDk2p z;-RmwOO|p1J6wBtXjWoNVhlY6-(lAlr0X%6H98dy2Ms*Lv)du?h6!OmMIDEUmb`O1$0u>IZPcRAeE!I0_VM07)he=Ku{Dqg5R0X3lA z7Vf8aQsRXZ)9^&cGrpjB-nRFy9|XodIUb|S?7Xi(-~KUsVEOMSYuS1nP!f0+CF;4! z;;}i7amMxQ;CnY=ueU-b;{LG85?vm}c_x@dg3X2uvp~P29qH7kI8BvROxEsQa&X2i z!2PDC=6>wwH8&OT7PArfqsu9tW$MjCFFlU8OrAIS89<-xu7XrRryH~No=#V87hYh1 zt_%GuFeYJ+E^1-#vOqi45oKQMzDNz5tfMwl;{6{Mz!iV^ive{R_N7?ES`l?XMUU$j zNfoS3ULa;)%t=5jC-re!j7FxgN82ZohU1@&?;aVA#w2Gp9}5x{55y2?A#U!#L_!IJ zcm2yU_lwdu$~1u6UQq7hW_u=cwEqtD=B_q+b`jktIhcwRgjM;ZQrM`1t|LpY>ym~2pd*(2__$^LdF{u%N@Bz@0xV5tZPd)5&@SrQ{I}L{*&R;( zrwX7o!qgg~1z@TMi9uj4@VHNzsauf1%xZ3Zdy+ofQmGJvJ+(R5Q9Qj5I&k@s)OMfh*>!$EI|C2lGTX@e(pW}2AC#tjt zw`IY6-V)K^VyD)|W^7Fpp}YZaZW_uW>z8!*Z3{&IW&9IWtjuS?UeN&hr*E9c6t2-t zQc$eQKE_~%p8agsjDTC46(^az_RyE|uX!3m%?WhaAk3xplp@XG1UoI6@PW1* z8%AB}vCWGpFeR|b`>-X9Og>_7H}Go#XM}pm6`fn%m1}^=w)7RnGSkI5FJ@*A2nh`9 zF(}H`TekH<=j#>OA0NH&jYxCo1ki$gZC_9!;d0f0OyFLIW36~+?O+gt^4PTAxnDAw~z0Cnpp{#`_ZldO)l#mwhS!vd#--=gdZUe4m zYj-YK#B4)(AgrrgD7hlX_{{*xd0GmnlAAk;KTRDw?5~{Kv%Bk)*gjtj}_VE)0-2_7m=_I={#=zL&`N5g-xrE@dzz> z=)9Qz_GL&-aRC;}bTFag)RRtgIrsez3TWH2x{ds@ADBYmGu5tL{BvIvcgn@g9=MB6 zx1dj!6EmCDKYY%oE^!X^up6+vnl`9?{g=ps^+JG!`802P^272%N3Dc~s^Sr+UIncS z`A2zq^!!iepF~ST9zMT|Vz{2)J4^YXuveWr6Goq^I%>BCoZGos>Q0+p%!=<3cfG&J zUolirs{}k(?D+OBM%VrPh+02z=_kS7NVMA?Xu+>zPu9Y%LH92tmj8|rxz4RXtoUL> z<#$i!fV5#d>#1eLB<+VQ<`|LVc*FprEu@#0(T2i_tpjkuGOTCHTC`DS4SsK%y&MM% zxg$uSG+>w0@E{~PovBu~lf6%yT1?MS5P9a((zSL(ltkP8G`~((*HgvAV&JWz-b4xy zuZ-7#-b}l9+o6PdQ=YZ2{}T1#wuHjD#qaVsUZXc`p^_fV|SN?BD zlhrm~<_T-s4Mq=!;#6w9>rU2k!@wq~CS z6A-mp&v!cNN|gw;q=m6l+lmXZGSKi^P$zn%D>R4J>6RLDcviSyd8!@JCiUN0F|$PY z$kkp89dFCM&+*mD)lkrU;4pj-kG!THpAxbHPPcu=V3d6FE}InS<#Aw|a@u!`oGcHm zb?G1UZyI;Gn)=Q8@nH!Y2`s|i@;-=uok!pD84qGs`6&7O1*|+#((m*mekGzdP2`Ai z)X80z{ctsT!D^7544E*q)23pBXJyQ|HANFQWm#+?ANy93gR8wc} zP6IZi{T*p5o&Gmu)Vln4#Jrj3SZk$I}#I&{@^W)>(gg`TC;8|>?43x0Rh}-?wRh5kXD?dXtA+99a$4$p3N!vQj9%4= zrZ9f=L4U5g8E2n005`Ltr_vQktphR`azwCsA`|w!8MlUKavsowDD>Au7ul_fyiET+ zG1BTOwEoBBsi9rCsQ6n>{7azGW$v7eOP^1!B(hv`to@ySa=u2K8l-kCz>15AdY+pt zI^$MhyY%zjIWo3kG%WZ#WOHD6Lqc|j!2h(@gLU0s0)2XP|5DtJFh$(WA?j#TP_ENM zhitTS$@oF+MV(89J85Gwo(q%KoxXQBM_c9mWk&i|Z9p}4RF2pCwD$33-H;cTmiceZ zoM0HHBAPH9g|C9aL{*yuMs$gSkXy8&)=}@@E7ZOI`&{}xqu)%Uujsg|aZK3#<-tM& z^YE`tKMSK}FU5#D%$wifz53~oa(n9fRp2Q-7}E3%miG|-u$ZxcQ~4!kARB$ueUt=a zs@4-4yvBdB7=U8$zPF^xCuo9YV}MmtQVFFAaB}w{d%}BKdA5t2{&r16G}y+rdz=vV z&FZ9~t@ z!R`JVPL(!D-b?4~c&&|z>j~%R1}lMZcbV>BxXgT6ka4wFagU02P_3&%iyg!VZy@e= z@)WhF?YF?z8h)PMBrm2)7_u1s-7K+MyG+7%x)+76Ume=Twn3B+)bUBW z04(Dcl}Ls)USb+cYUa(J_gD&HNZ)7(CcvRJs z^>RJyf$Ae-^uB`aTW8}c`Vgr{IZu-}?158gQ#FA_7G$L?MBC7vZhms%4vWNQ(QlzY z?Olk8e?&KmIvGH|zS;XlLhF@aV^X;K6BZ>GC8>CqP5WNN@nUTc`IX=FeV@&~i3hdj zHNJ^K%o!5`;p4bgI0R%(R<-T#s0@ymCEqmENi<*XBvM0GH;)jvI3?%n*l974*)48z zhn59!7;-vIr4@RqUa4-0Uksky5>^XcxyAvR>vEPj*q;IY=1Tnch{s<>Q4_z)13eEV zWwK=g^d)S4hI?LMJHrBnQ=op{oR{UH4(jy@Ewz;;{Fz zUiNM5o4zr{eDF#5`L|#iBn%iq^O32W$5Ds(h)(OV`&%H6uddCT$}HzI zLHH)sJg+HbU;I(nl`^~fq2C{syR;VdAD522)%yXR!w~q!X@O*jaeUfxyt%1iNV3ti zK)KR!1WW!ZBkfb22~9X7ddqT-EZZA>i8Za9*x8rBHDHc|9=5A7Kk!@cw@KWearq&_ zyZdzf1}oP9M7;ex`}Np{aS8GydE^_pp%|{GLDxPc%FveKKA8q7R6f8>#scahDR+6u zJL`LLC2_bHAG$O^X3*J+b|bX1pVIT~36d6_BD!0Vz<`=&%{+H98EQ=B$)YVLA`-zl zI?$2p_?4JBl2Nr+v^L%3ecUp+_oY%*b*#MeE8I2efoR&cwFq+ewx`8)cSfz1-w6Di z1c-t+te=fLL*r$gS{5pA_?@G?zl6dyxzELsf~D%NaNenz#J(|9VxZiW3e@1&jus*V zP6BYo3A~lU8H^4sXn=@u`H!POBusE$Z$Fl<7{p>g7ZC@UqqHqQzco}-qQD!*m{K-t z-U5p8N8Ih{1`l9R%DOJp>-Zi0DoU!Y_w52N2XYioFufQsK8B!tCCUs;w zw^Z0E`9_YGG-XV2M`j(KkOESz2K~J`kh6!#io$Nr z4X!|)tbs#eoxaxALXCRVAV1`e9M4XYOIWsP8js)D!6er6r@EdI`*&=xgw<1WQ4?jR zS#SsGv6Fl)I)fEA#mdb|yoKwpX{5<|)Zd${5Tf&=o|UOK|SEUCwW2Pah$^IchN1M}`hpROEU z)-jlh5GPHw#6GYC4bT*i0NX_o#>CEUxpVis)y|QvU6X-X=1MVacNnH7mY48YNPQ|hy>VQ}_^+i@Yv8Je$Z4HkEY3*VZ? zb>qwCN6~sYj@%@?II;Rtu8*0Wn9=@UW5{Y}X^cCdjM>BkBB=(zJ6!eu7rdLLNyj+s zwgZ=e`3l;%2CV@&dVJ~UyvBX(A<&6PJgoXN&y!y93~cKz`(jj}ji{sBnnBskXa z3@oHe_@MVa{X>oXX9$k%jO7P8t@he{jlt33m|eiM#K%@-4fZVpj(Em-T5#l3BTeq2*(USmPrTQ-`Tu)kDtsd(UB9` zlh$8Ik4j`2Bu@OH^NLIFjtd7EoiwR=I~hKY3q8BKtykPw{W3Ss9pI3tNd>&n?k1H2M^sN2W*HyCYoZz{Rvz-H;IXX z&Et3H)3uB47ZkW{KU@*Wn8?Us*q8Eh30{u_GOMzy1^xELq@>%<({&7;JuB*GkLYLg zU*bchzR^TYWIt}zeX}uX635?%nc1AWcMc}T?OgE>MPc{z`~wclAKWFltCgUxK^xU< zu8%79TN3!nW5&W*&0$AjH_r4H&JOW=;@|NERJaBzn^trDF1Ttk*I#+=crg|{zM94l zCM)Fo-A|N~VK`2_Dc)U7vOx6k;;TvF?&EXZ6W&StO6H$4mD_kx)#t;nsVRqWclylgLqr{uY5E)6@}8?n;&3L&q(d^)Ez;B@%r0dVf}8| zzhT}&8-G`an)Qv$Rw|@HBQ`}e2-~E8GX>zaH>xwcCnq4S{#0FScfIk5X~wf;E5I(x zaX-7?Ox=j^K<>)2(1;4VeQ=X|YijWV}k@thZ zc9-xxDC$JiXrvo==6Z2&DPf3*7t<1=E~+Ho+t-ZVS@+}-*6K_-G+wlhBJLgaz<^1o z$L34c6((yBUBA!0%8xQSR`kPYe~5X@YOE$t!r(p>){5#nkPQ`XB8ZK!Ez!aj)}prQ z47Y$K&wBT#%S|U;dbYohY`9|CQQlWQ+FU8c*wZ!Z;lM%XujWiYX7kTk>rn_?V8(Iy z6Bm+(2w+EcSBE$(yHHkB9@xUV;#39H(bGrp*5w76*ZmAVvQJ-FdF)2PE&MVcNbDBN z5JJEj^w|HPT)6$`fXm!Z=ihfp$r&HGMtmU>>f+LYSPV?I&w|6cCoTVgLt$(&jVYu5 z$=3KPgCN~ROUE+91EkEFe=Skn^m2^$T$??zeT;^$ z!i3e^&qJ=!mz&8we#mOXy|O@A{!^`n$OhN-P|%3qc;RPIJf^U9Tzcx??e+B*ca%v5 zT{cLKsVDOWmC*wU&g0Q6^y%V^;F0`xg@1B-p#MPZ`N3#%>G}sSIbBUV#j3qt?4f?G zU!Q5#6MyerC0%#IZAQf1*UpB(Huh_~?OA2HqC z5bJ0x6qC?U%G^=EI1Uk@{C2EXw@)(~7E0p>bI%+Uog6Chcqj2)^%k(MetP>+2-p%a z`qleK&CqC|OhA@P`gM_RhVi}gzKjyC9blx>oBMo36WPiHq;}?034$Qz@!}-xG_4$u zmcIPnb#fw9TIed0WC#o)+aZmvJ?K)y};E*za#;VGYd%>3}pMuNbl%_ZnN6cbQ4 zppHAZ*Jj)lQp&fUR?|~;#dfLXw`PYCazV21)*sd4g=GX7a!8!+9F?{#Ae#06Yy#~c z99|xSSC`g|ocJv`(TYYXUM~O>mp!W`ErzQ})54MRJLIAjc>cb&Rx&+azfhO$h{s0p z${Sl|-u@?mWH*1VdmGlhwn^t`gm)wB%0p~5=f=ort%V!w7Ee5K6Eaqmc1%fvh`|h^Z3YL`x#h_>M zDr(^hD{kGW$t2!H)bF#AByVm)QU>u>P<8s{zL|=h;u=3{QI31jcEM`bAisVmANv?} zGEZ>+K_;jO*bRARlqaH*cyJ7Wg5dx#v|QidQ%o%7xmqTMSBT~7=|apF8GM1Tznp3E zmjLk$R=pj4d=J~e93NcLH-tXx+=#9LT0Y}o5Po(CFzwT?v%&nT$r>GlAj1s1@G2Uf zXM+j}nFlg{SR=<)25+ccd3*@77wPG6e)AnjtY6|eKWB`3)Y(2%r8R*lSXzMCX*WBK zC${|8zc2i!f1mXK^zXGOqDg+IjxMn3f^qipMiicB*g?bsQ7DOxqdcGd zV>2Yd1OE8zBDX_s)WpM09}qBTP90lT?X^A4T^>Rh3Ff<($Of#>n3bA}F`s^7S1NjUC}poy`D_Dvb+&xzlX5S8oqm7F2{z)v7#Kf1 zxjMy(4my*1es*mpd0Fxa8!q~l%)S3j$(;;I-`h|N85pFB%xFGOF#7g~>7L%vOa_?E z8pUI?5B{!j`oFw}T|GxLp0CUteqbhyI~^U4&x6uqvqy6l1HNE#nCey3)&bxRj22x= zG3Z-kpwxC;UT$aP}pE zs9^EJH@9@DSO-nJ(JDo&l7({Kx7Q`2dwv%`2?>s~6}Nl*7%qLKUCwpZegqih*I9s< z`^Us6qd#V>L@}o@#=F^zS=2?i^Vx|p8g50D0x^E*957(nOXFkDgK{eUla^Kl@Jh~L zS3;S=q~x7?U8WgOC%@qo6!kG_>}&ohe}27hY)fKP^o$SyNfTL;Oz645lcnc=}^rB9dM7&SL^Tl4-I{J0y3*s zF}2A7Dbjib^jDhkzzbc{za}<)d3FHo^5QrvBAba`r1+EhG3`KT0=P>oxB`x#xw0^v zuQe0<+a4dc{g9^m?X8RDiiVU}Qm$COO`j@>DJa6o&Pz z^p~M$S5M+G#LWMONPv&EOp?C1X@vDD=sGCqjseMUVvVcG7}GgifwhA?s8<`K+_Jif z0_Jb<1sJz!*7|zKiwt&ffq|kAufeSN zq2vw>wE;39^n|#`TzTAS44e#AzJEkge=CT98wo%hTgD@3qE(3m!miZlOOVlwg*vU0kqIo3jev!COG+j!B$@N4VZI zIxemopt27JUFI95h^V=;q#;#~@e#Gopw*)4?k=Lj@iL!PP}CQbngI&PZ#N?#%XPTr z&cKOWakO4v2s`OO`~f5w??UUnE4GS{AX`N@$5}5;O#>FLMTY8 z`tWhsW^Z@w+TDGD?ayzD_e)rR$qUNAO5S&9&i|(~6G;S4>sFZH31$rK7pP93jNu+n zLjmej^zA7F+E1VT5*b4jRitsCjrV#5@jYsCa6s3z94Hhv_jSQtD<>Pq^bHRD!|o(D z*Ivpu`Nou(hU(KAT7yIhmYxLu;_GIY8S$<8CbNs9vG4lo7Z(qwZ+^z`W31JQyhi+tF=jp}LYn8UuPnjZzKR^RF5)52&UyYoj$Q#xGEeSt@uq@>#(hE6c&Q zAcd}{s_#nuCaGE)@3DA{kXvG%FC@Bb`jOwVu(iz#kpi*bu#&vZRW_7Fpms8$R*TjR zMoP-hcdZl4zQ({kqDhQ`GU?s$C!s-r2r!R-=r+$7=)r8FH!Vlb#OTtSF!PG3>wj1P z{)g>J;^fCHZLx>(=eOHe0JA!D%ps>?b9tOVicnfflM)~vxjI;&Ins3?=ueZ2o6h#s zZ4U4S##N>31r%@pBbnE+RT$zCH8CyyEQbnj7PB3mZ1Cq|9s;nCt2n#%O2*b+g#C+25(Nc?L^RxP zfF(WIVPWlej}hwZARP9`u7+YB=oLEtwO(t3Y<)YY?w_Z!L59-UjXra2q+9tgZc}(; ziM=y5*Ybc)&~DjYeTZ8^8Aa%Dc}R>&BX}++psQyku?Pah4@6JZ0x{pY+No0|Sc%w$ zgoLza-tO)DhY3yCZxsW&NWxfmlB{LRvL67h@zcGv;A8f6Wwm&bf%gdkNYZ!jVB+Gq zQiYG`B_{P_N>8UBLlYJQofVK)f4=PzUTXUBk{>KxYdYB8*vdu7eiA&ak9!{_cwCk@X_~jUHfVVhK8*dAUZpBFU5ouz3)8* zz_O;{{a82@97DDO7w%F1gkW?TSb`ZRFVSf_c)6}ze>YjT0Zq_4{obPiE&$S`T2zw3}^t`OuFL`YGJTfHf-C{L`u(A2uHxU{+uRv$!p4 zOTuIHV{6Rg6EYB!7S&t_Ik+~%&b|hmK$tl7ekoy3@ zla7{q=Vb(*Mr8T=6A9xYCYZ*SJ<^D{^+4fU0lGQ1ceF5|I60`fre*~}h4 zCb`8TQy5r(X1CBBcpiToNyEFLWU3y^Gz6RT;8Ws{rJ$uP*aizE7hfiES;)|F)xNr1 zunqEK1~5cbY9LTz#Q$TAlSbh{m-FV6^oQ$ks`qNDst&b`OiWwP6vaiGA?e$q+}xVG zMz#qfpE+b%ktNeId315$NNv<}5m$qKnJ(*JOmF*CL$PIba^rgWNR0+bxpUa}JSDa8X8RCR|Pi$Hs(`w|=lp6cjTMgjb7wTq* z;=jT*3dqkei9Xbmbw>u{|G=%mH4TVKfY{M;DvB<0!d+V+#{+Vb;#L`-^t5Ub9wvp6 zee_`5(BrZm1SHh4Z3VH?5ODTdmUel$7Iy-79BgkR%QOCH$}IBdR8NMNYu>C6Gwe^d zLpJI_vy;?M3L2`_CcUA30TL=H_g~BOC!V|WlLRtPY0Z;B>#lFkekW#}h>Rf*0BLLI zyU)WwaOYH>ahYXEkV0#q_I6n`UolmKK44{IQ*}$Obi!I0*Wzk*f>nac%p61l-2?MdP#^b;LrpB zKx>XZZqKp8*srC0R-r&AQsA=gbvCf&*st>UTiBPeMNz(|oGz!Br97tm^NOVHi7hr` zauQTpEooc~sC;Mw2AwV4_ivHGVUDj{3k$WoN|hWZ!OJ}TR9|G%ijCq_3d%tnbz-z$G0 z+?W<+J!aMJ$*}+4?`r%lG6=`XdP^?xc=LPze__RBRPt$&{;X@OmergVaGu$XfP<>f@G1aA13CZkIZ> zKum>iPqpJFg=ZngIW9SpN&!dR?`KnecagL8`(BFN;(Zr3A1Vzl!~tlR*!D4~!bnav zClNtYB)lIGNZ8d5r$V0j4J`V_Z1w|=QO;T0-259Ao`gY!AHmXqN+_JYUFssX%@3wlJx?N*RDL#}?gwUsMUhS1ke~h2dNMb2CgNgf7$dMz_ z;0)$A|J+WYf}+s_=EHvYt4GJwv4zBk7O>nW*zk8?O3s6z-64j%o@!9TET{Ic%Ow%%q^X~{UbxwOD@rps?bj1!vUfCWBJO6h zM0w^%z$4^^F2u|2wigAhxU(H>Q4&?Fuq%)RfiB1p6n#qwIeSN*L}%St`}gwZY+B!? zHZgjbCzO5wv0QG`&%*5D;L~!O-a`ww>B{dxx7qqm{yoC_ zQ=<1n60elg)ma0naqvk{=h{;Z-fmaqN!tl#uB{~|6^%hpL@>m8Jn97SN2kjZnLquF z((v>C@;*}n(Hw<*IinYqyQR zzh1BGMjSZ}HYt0M1nzKXjbjs2VMjNco# zv7uPjkSQDkoR0<7fk4`5uNofzFJ6iZ48wfc<|8;d| zw~Ln4K=y-)B2*$hBK!=uGL4t9LXGhAWGz7wcc0n?Iksyx3gwf z?hTzsV8Y8Tj(55eGohiZ1v(Wpq}4|6f{%arvvdGNI5!kK@`pYC<@RL0G;RL{@$&o` zIhnkOP~VT#G1&K3L1-6~?CZ(Ds0o^by$QMDFgUvC9b)DPV?QG~@obfF3)SqWm3iIt zW;iz)9JRI0%)wEA!4qSSlY3z=Xxyf%bf^6mTkfmqP`7oPUdrKeW5#TjZ06RNes~K{ z+ab-v155VKUCM;*3kmceK=9enog|Z%=w!OI@K%J-y-5+G2Ko&6aWXtQYA|Y#{6@vk zn+#@NB2dv(!EWmU(ZHdb?MW`0yPhBV!YJ^d3$F9^IGYk(?2!J7>9CPs9bSA-rFzW%m2jmo67JUX>(6JK zX%??5{b_y)T&5q5klj99!#S@v;JCPU&8Or;0=+;glrT+!LNB!d7;*yY~VqG0zQ z;jJ&aaYFGP*|!>R|MktN3`8=K-X1V^fVDo_x{MC$M~vGp57_j7iFv!XmWxpH8Sn@V z4SgUu&(e}-_^5P1>`GOQXXNmKdT;*9;VJx8;Z9JJC@*{+WU zkUh!fYm;}WLHb`+%(8Rl>&6q%9FthCqMRX^*tNkl(VqFeNynZFfr~*%GRmodyujRLN8d% zmMF)}WE8p215dUkP~)jEw%0Z!EL$ErUqq}Qlv;4ny22y^8w``ho`gsDUD;n@ERLm##ul$|=6Xcb@vY+1E4RRQ7 zf$>AFQLx60?^mIVBNy$09zxK5*3+PKx_S$xct^3p!dIe=htsJy1@wk#uV>*w>I?p^ zokj}-PYHPxeHN1y-_M*$P{u+!VDbYk!9gblT&K1jwf0l^jSrVhFnqx7;@u62HV`T^ zlXiIut<~eQysF5}S|!xQWI+NF!}#}T1~KKI zZ~77#kNf_dbXy-5w~Ha6K^+=bM2tqn*P~F4OLOrbmFLep%0G z;N4qoUK?676uEngH`p4Q`fyku4c-dvK8Oe-(@pCuswRMgYuFhQt~^=oK;vleD-N~6 zai~m!^WY-9R^$UCD5X;O3dm3W%`-vYs=gyLk^a+hU$gGlfT;6o>;NB4H(%bGlC}lb z<|`r{(v5ckJjFYSziAA*+(I6IqlfQ`Ov{&PVIiR)NX^P;`=~}l_I?x278sv6^_t=3 zlYh-hkVyT9l_hZ=s{>ZsU6Od@#j`h{cKu1Q**Y>s^8pPJexwWz0AGtV($kK-O^0o>C?Xsxe& zZ-1#C04i8M<$+Vk!fF9zFgEZus>aZsxx;lKN7l3WUvBsf>!C9G>;$jSa2dLlPT)g5 zcHSkwPF}CTr5SvK;;DUh_@F=hg<=`+^FJ^PMJz_HLayW2@lLx$78DeCpXUAV6RO_i zIJCH%J%v7C*_lGPR`=~7b`V=9vN{}g_;v65SV-4Qd zVKPF?goWD*LOx7Q%=JL%&LwEP5`5VFq4(r8uX$BW` zd|&TB$QRe4vR)_(4m`a*p;f3Of7v)l7*5c5^JtA4C_QO_{Ust zJ8B}xjfoKYNs2IwllVnEznNjM)o?_rBFd*_0z33aV4+R+7sP!H$#4#vUx3jSQv#45|* zfaxi?DUY*6emF`CxU(pDezx{y*?yGDS~YX8>>_G8vj7Upx!|!c1qgCzBC5t`kMeNW zTRxl7m1S+P&um4o+zp!6q~dE@o->Kwmar(G%V6e5^NVKhx!qVj9L0a8Cp9qN7zp>7 zqd_|k9gdJ)E9=NTjAmgy;EVCu;#P-v@1DmGr*b@Set=jE^H z5cQf*>jX~tYw!5vjRjihj6y9ZnKj6x;lh_<%a2oXbx<|9YpO$4cY7+{4fnEov4||= zOVGa5lS+Hs?us4a8KLw-#1gNqb5cnZw&Tq5@zorNy^mw@Ow#w^2R_Ozs6m5fK*VWz zuscDJ@S_%pk7K*z`ebW5wd(z~`V<>(e*PHIVC4!Dr6B4E_&kT*X)27Yec>Zq*2P<) zp>07&E=ePomGOzh370ygncA!cAx5QFOXgfqLCZ-K+%w6zaaum57qy&ZlTiX+5fF^q6_}>8jpu8TPE^?nUO~*Vvt9)oVGGF?{RE9IKw(&$=i?8M$~dEdvu={)B~J?EKX!Z~gacmj?&kyACMx8c8hoI^i4cPI%O;lkhmN z9r=9Y{a4zt!SeyMGanXVot%76>w8fXm!iP^Y}59Z{RTx4f+#TmGY9|>%`f~_iF4Zd zLGuG82X2SrILFSD2AtMkxVXO}j(^P`enX~m6ZEHxsDuE=Co#;}hrj(+7GMLHBqe_< z85hwF;YbSWF)lx%mNPbG<01jGaH@65cmn13C zOA%OE(BorLlHjVx!FV-dIG1AeYdmxTBX(9ri-N9v$GZ!V%!oP~GhQLLc^SP1EGzZX zD39WVn9U({T41HCsqCX7Bc+3Y482JB*hX1;BrUJz%t;3M1h#2A4H^xil;14K;y5f3 zKy zeVcq7e=L1qP&Hh*DoFuaElF68o+ zUdiw_fnBqSRRZ=dd;3C5m8hRi+S(1nyUK`1i-hPlFRW~u$~7@C_fEB1FyL7>zd#Sx zB*l$pt_*yIcP+W+llXCd%b(nD87lDHXi5F_X|c>5EeLpY%pnU}1e+0HaL4%{7KVoc|AB?-|xq7qx#TAiXM0K#E|YNUur<0Yzz| zbO=qPSLr2Dnu0U|m5!hk>C$Tg2t=d_A{_!qZ$Vms5NGF^_nrBFm}@?G^inTP&N+MU zweIy>_bQG?n({Y7yCD-i%jGTc?3msDbg3vr*y(}9-Fwl^lla{q{*+bdexC6@UEw zMvk&OwTMxuBNKC_C0q(#SHDSzb%{bUrB>4$OMbKhw^X?>xhr}k(uANJ5kvTqe4=pF z^q$$`jdr%|F*V$(?9Mg3-}~-zIehlt0h5E_f3pS5sE{0P?!#;DldUhB>pazth4R>} zyD6D@?_O1h?WNdRK{FZY&xCm~l|FXYFqMWkt+mi->^S9Jn1=9}nSq`c@K zKYXXv9J12uRFiI+ik$a;8h0*E)7H8mnTy3K9i%}qG?(A-ln8F|Vvxb0IifS<6A&y5 zzvDG!|AInA>Pw1eWVO*sWUBt<=5^{KC9vMEr9I!3{)^(wNwjhlpbl{}HdDr9W};HI zzwshQ3}ORFmAgkbw$zh8ciW1Rk$~qYLxQqurGUD78wuRGgM90!r$=8t|6$?J-sV(} zFur?}77-^wwgW@lA_pd(g59Erg}{$Cw>?)PcdE9ChH5OBZt^7)0ADbNydJEZ&W;V zD0dsPD>a1FIaZPGbPlQMoZr`>OZ*c&R;)LB!MrMzUrB1kFxYdEQ`+mbhmQj`U+cDM;R`2I4W2Nh%rc!u5h6#HVJDdG$K@GBiJ26Vk(#<|doo~H z7^i8mgApSPLgb%s^8eDd!);o5MI8etT6 zyffw5YK0VDW`2uXIrM{ptu;9}O+sQ~05gZAMPfM#{NpCD!-;$*i4ns%gW?|97TJNH zN$YnvEL&n`ffv_l{Gt(7h#aAAT!+;#icMUQQF^&h8NiZ!@&jvnmKBF$moT(-Ndf=P z0y|-4bBT@sh(2rPFUzki$*_Moa-6*BTDs;x$E_Ou+iV#{%q_3gysu>oNeNau8#D|) z>0&y-Kkyt$I*W0(zPE$f1-qYMiQW?(&*>M&q87KduFVCm@@r3n&8UCf=vTh?%fPTc zh8nK)e84I^-Xh)k$WHC>c$)7X?hI9BDD8p&k>GD3r=PEQUGOez^ypMY4wfzZQI}iR z58h2S6*NNYhP2&LSuSM`((yZ(K~}$iTatRcuJ8ep^&JM(k^t;V|iNvwd%Z9yi*){O=wtvKzeYUCR**a`Zb?UpGo z#_as`&>8d+(0^FjHYGR^I;lx=H4*+;gL0#ygsLdjyxcW0$)rRc717vdA38+AqrR>3 zPH|E(uZr_`O!Lwa?4kOk+zh~8dv56X8WNyh)rGOvkpLl3BRX75ik4AH% z=u$Ix$1l`U2Gh@JJovprr81}Hq39AOvq4X=%Z17ved?xJiJiR(FJd;>daUfI=%WU_L5?=sq{hG%k5zF2A^U=HVe{Uq=@r`T{< zlTZ5F4dWt9vV*0PA0j%&{!!F}awn?;CuZLnxdZ*CQ?-~mO^ld#G;AB2bv`zx`@T1f ziXA^Sx5GEQ(o6ji(e)*=Nblfsb_+Q>~2_+7> zPNK@>&Tqf}?KKl$3(I*jg5eCh0lh?m{wRX#jEpP|$ZhbL6+-Z!ICmcN8L^6UB;uFk z|1Q#sUu0yNYribj>Ihxy_c((nJ?*JP?%GRrz)+;7%Ba%Us9L?qEttW0b-L>vKU*lcjaV0y0QrgqmTA*NVaegmo7!OD{FYL1D_x>e=S961c zvxtps?DoP3Q~QwzPdZ@`w?Lasch7}gbFbNi1<$-b_L|(EvJCCP@pV*Un=oIWbq8xI z9k-b&e#j9yT>r|fzP8WTVzr01E;&;I0zX(_VJqWc4`&B26dR)!OLqN(4!NwZ@0rCP zEv}wuzns0)&UUeaZ2mGK+Fq;Qum4^Y@&g%aa4TEE=`W}EugcA_O#zW=`=RSD!RMmh zN;S`Q3k3=bWfVJLW)rmjbXbCjaam)5a{!i2EZ=J)v$B;}bsY>bFA2AkJX{-lPuPX= zXT3G@(o^<05U^E1^pAjq>|u7x(Q_JjU2W-2e3TJMxD8j66H zKm9;Pa2aDhrzp!kST6dt+heg7G1Tte^4$N~?x%6S74*3gEU4f~d zMu{745%#Aqky@}ojy-GH(N!MF_X~p578GR?`YzL4p^y271ai+&g>Cbd!z>f-b` z@QU2ByHLgtc+G7r&aW;E(IAegv}7<%{15;mzB7P1;-Awl){D=)vbG6q3cE8j=damTKIrCjma4!eI`XfL9aQi+Ac~TvPDIZ#K{b0jI`WzL?D9`zt<_XpkM`l zBO}UPFcBBcp88~3_~#<`p`)j3XRqs|^>L(2^dqaIg9f|s83FErRZ8m@o;TrYT{}E? z5y*zw+X6W9CNg8x4QfhUsigo7&h@i66Ta%Lhw-{_7wlMSnT9~}c7cya9E{-dAgKp; z-QfWrDVtdw7ID{D93_MiR3|ZZuqW}qkBeKh$EjfE5>*HSc~f+9Gpc|fV@dCrpf{^W z*t+0^)qIVO-$8mIXy8N7dJZint%?}BuKE|SCuC)0s#?h8wm8}pKt(4%xphX~82v`C z7Mf`0!1n-4YlTgRFuu>p5uMVg=j>UhA($^KecUNZSN`V^eanNR)_Jt2AnR`-sfT>6 z=REKn@VJYSf!LP8oX?WpzU8a$-~b^}u4$<$Qw~Nf5BLXLbt@CD(70YgTxP2_%`_D@ zl`=I#H2GvV(^I;ZJ{!uh%jPp;KYz?NPJJ9~hvVE~Zw$tJO(+I(-iC-v9yIJKJ?Qm` zGthB4BVkAFU@AHA^-jO#%hF?3KA43Zg45*qL^@?VBHfs~3nn!Xef#v%ckJ=6?@Xzd zmCZi!2k!+=W!D^s=1wbWWZVaDH*Z#-_qD%xcAjBR_MwywJarkK8P0tHaDpoOb|@JV zkJ57=EEyd79nyR4TUt5#OrbF;T_KtlEO$qn=W%Tv`yrKhbzf1#jb`IX@tWC*Mz~d&S9B!QGGcd52{q+o_@- zxCHb(1*V1iAgpX~XnXknfLyJ}nSd4N_{+B$wcaGC3het1&%p6V0ttiI@s>Wvmq@oW z#@K)hJp2Y^eC!1En(weMtwj80u6p}>?sA>3oxfIpaHZ?doYqE7Xq;8#@rH&E<287| zxx7)p-(aUg6p=jj+$H#kBGOMbe3}8Xmyn3afIB~kghQ`FTOfez*jPp&1@g$^C>&@= zQ=x zOOYxUl#sH!BR8uS2Nko1}2mh6s8x>8`e3t@OXn(#~ z!GdpqXOcUDsmcX9Y1>dqI%YTNs)p0r@JCyVNK34U z+la*?Dw!TGaeoBH_Rk~RJeIquLGsWAF7sWB%eBEW@4d3TUd{XS8-&n#(k^FwoTsT> zPWj0FXrytv;LfvR78@L=OZQ1&IPtA)d)ST<A!Xv3~VZIg1l_i7?*!yv`#vbR*Z zBpsgmf9|i)^uOW8a#M(2b zKTG;%jaBVt<5m^Q z6Uq}sWHw_sx#N1f>0-;SCM{DUID~Lhb;C-T22!I1>1@_eCJ@7*5LPSA98jj@bP%DA-@}G@2Xcv<_%nEl$D(2D7CXL{U+OQ2 z>q$o*h4D<;I?%%RpIzie@w6Yyh7tBc`kKD%2Z+~yF>2tpf-gaupJK9!3Z=qBmBbg| zCf&*>s!n7r;FyBzmqw;jbDL>O2_L2`cw%azn8a1(1ItM|ukv5obwAWpL_xm3xPA~7 zPb$d)wZHiBB@z)KuoHbO_4TLC5<(ebj^29OO8#nxt%j4)MDjBZhN5 zhgM{dsJG8=9FuTOwWQr?c=Nd;d)l|hbM4)ui3A67V6?aLP$Jx!?Q_FrTKJ)1 zsucY2=g*3AalD9p4K86eyDjBwz)l|5bVKZ?tom&Qqplv4+~_46GE=BA?=Rw^oOPKB z=lbjQ`->5FINQiCE6yOJ3|b*kdLa`*i=b18`pK4~<!w8yCMYpBR?DN3V(2&G}5tWJBTP=uco>4 z{5`bAxeg6M+O)c{CSuo{xQr3tA-pj{EL3_=`TS4=r;;4y9_>UL=nu;$|9P!zp7&eL zNd+xDKHElWN)e^Nc_fd%YfO=Idhh=Ii~cHe>Li$_Ka2(RUp>AQzSn*vVf@rX=`qkm zp5iul&F#T7-$%(!TwU|%tN?BqVHDB%AsYERqw>|dNEggkR|Z@LD2SJs^k7i*X`B?# z93aJ4N=Zp+LiPPn8|20+*b(DrqQOSw^$Gx@WFq`_c6J6I$3m;nC4E7x3kGMq1}}(NG z5~vdu4?vYJtad;^$VXoVBdtfw{3)W5wD5DQR&aSDB-vn(<4oTlEN}#m z&y~1En(wnnw1Mv${>3nhb_z@;5&M+$1|0E+zwJR{d?Ie-2@WU)PRE)cc`pnEjODaq z-hWKt#=#-$CJ<{y&Or+&eKOd5mJTIwSUpdpX!2;jMf zH7TJLp>AK0P%FLA#ZcP+*yh{;_X8_el~xcYRv@NWcZ@#f#-FTO6x^Ey0ZO=(=Z(x5 zFq!a?u`z2l7!U1?Ff=sG|6l>k7bCbEFJgh~WYhEIK9-H)j}c5Cz*Iq5C@UH%W?F>+ z=9p{J&wY?eSGSvI!M%lY2IJW$zgLy+;e3QC!pLrFz%#1OVG}*2;n<2^22R zWzYa)1g3oYxyo765xR=tnJPvV;IeoMaI#?p}<0S#8rVd~@y6_QFw-*bZh)zwk2Q8f6A)oH@N)%1dK`tDr z6)-0i`NgcVAy3$gYn2gYN^Xjvqn4N*tkc=yH17Fp2UvU<~TR0ag#P zaBNcx9AmC%tQ?F7d`;y1)(lA(Okt>^+TNo5`Ni2^4KxE*t?xKw?#mq6+^L_dG|`TI zl%tm+{WLnE+{dU4Q4JQ1j4{kZNfiWA&1?w^l{)W{sqh$4s2D2EtsmTw_@86+1EBpPfKJDP+JqkOk4x}~A|Dr*FF3fKUV=awMU^2iBERGF=T+Ac z)Qh|FDyO2da!!&+PIB_qsfYUdY||Y#NVY*5kdwfrpoQDg(z^LIQz944ap_cE1V*p5 zLHmw|Rh7Vz`#ErYu4d?YMX=F@M0ZWIyF#YdF4Dr;38yUymkFn(j~zUEv2v2DR*8nl z^PV3Eoizm_WbnN(OSwXl&kgQFKp50Sxko+(8`jm742Dmd;1{&;y0Z88rr#}iei~@} zw*(eG(s)B;z-AvJKp7VU2Gl6fk>oL?w^vtJzn~i&YU?M5f9wSSAm!xy*_Hq{kpEOzfS2cfp51J{sOj`R-ggsC?#_~Ehp>eb~6L$IoS#ngDU~EPuAXic1UP@+pfzuDlL#Yx zKdbfJ!az0>`z$2q5wVJ+qZC&okS?n-Bwo=S62^w4~o z)M4~OW&Nah!~iMpjk!^vQ!-%<$$76!>MU#uhk4b-CtPTKE^=wLgbwk{jb?bO^d5(s z_$Q@^24ylMEZsJ%m~|>h_X>Q#_ALJfbVO~C0@hg~=`fDgf>}1Y2Yt}3$=VtTeX<9? z3wl8XZ`{yAJTaRo2g5Cyxwv$1>gRj{J%(}H5I8i^_Q8vzpY#~fsc#I_leWrx5$Dw+ zUtd9UZKq$jIl3h(e-ueSi3=inGNY+`EXzQf#)K8>h@=_}Azt`Ld;U|e$`-gSJpVan zGYFeFx(bhyz|$SgI_{pc6U^b^L&9>>o8MB4qT@4!-OCL>%%1T7`LgL?rBrMf%&J;%VuP6s25ksV7ridBp6LMa z74mg>`faNh4cR4`Bud_0&(EjEq)$rqOB~AsGg=(VecHXo?zqf+Fgzf9lPdwUE}mK7A-*EfRp;LErd4}gFJIl3W`$R?6_)OUX!^FhT)O|*`W9Yf_ z&UV-ZTH|1Vf6=2MnYuAvTDZohAuQ)slyWmc_+O=-AJax$yVBpa%g_mZ;bHuVxBkeA z?xyo%45$x71LUXJ_lCnr@OFwyA+XAWmMY1kw1e$GVuCj+ZVXt}M)##v+MGwB`NbbY zq40pMiL2ne|1=>4PDCLo7E={=0(oKP#gMBsRAxq$mMA{bA9}V2QAHQc_f~T+ewiu& z`8#2#Kp~R?qO159_T{nQKTc}92Pm~r@{d)ScfeTN8(SA%Zc|8VCzhS35$^2Hw6}=z zyRuByqs2u(tKQc)yk=c3vo>OF%7~*b$C|K)YIut{|3vtXg1nhUK2>fy2E1WZl)_T* z0P(O3g;miv^ z@sk7_@Qx&G_X)-mfKN_;1EjKZ$b(O!ybpSWheo>!v_@0(6WMx09s3Io=Dx`ltJz74 zSXO_h`kT)qoa%-l`ynfzSND#6rp}k5&N=6rYS{t4`}X~mZy9|?T0yBz`$;5)4-_)8 z{-$>Th=zDovJ3bpdT%b^Wj4P3ptNESzx?q_ z(3AttHKz&1j|Q&N7r8pQj4l663BGB^N~;V1Z!&}(M+O}@>_ZrgO+ujm%zxFhR5BJpjj-$XBzAhzp3$M#fY|mh=Yf+>?;AzK0evsZWl-!*Fr^mIyPHF~VKdH8h$8 z^<|;*V5M8aVH({IUMH%Wr%3M#l37St!0wzb7+%L>%vj~DDk~=WZsDJB@5}aY-QBN| zz$dr@s8Oq8ieVQeIWN06nTKNv5k#kZlAY4!Y!>1~mpVe$1Du6n zHN!;v_+p`f> zQ%NQ9KYAR}f1ts8bphXw2%Yn16vAO2PU+5%&&+;R$NBP&{N#@*F+4X-&Ta)Vyc58( zp5?&PcHmBtqZi_X+~mXX9d}QI`}BX+g?J96tkM(mli7MzbUoW-U(99UF3$R|@@lt` zdTiYnPVMy147g&Dvr@8!Kz`QI{8>R-M58!6R-$V(mC+O>>prbL=K5^}OF=#gzZoWa zi{Iw;M|ub6q9WP6Z=a&2J=gCH*e`JL5z{Q_pq!+R*B*lJ3QkT`&r2;i&r!`qMV|pFfalM-F_O`gqFuKU;6{vM3PEm6~ z+z(Si?cmeNX{?XCwcr`|;qDjHm5qX=9FnMR2;A_XpUKp+K`O$hl;wz%P+?xD(}cc# zy@#wgK8d{?QVP1pnc=<^@Z@Zo32LR_W6?nG6*0W#?_Dshgp1HT!C=6Fon*pm=3Z+g z_7~!IG*(0p?%u-*m$Qq*5kDZ^@~o0?e!|o1XonMbADLaD@16$&P;E76>9S?HiVQHM zq?e;jy1JFP9bKt^7XDx*(KDG?8uviDGPdmvYWE$Fn(4f1dFS#wp{Oo1fMw0t zvBz;^L^f@ze)pjfJVV&}n2pd(VmRKj*<+j+*LQsW(dd2mgG+>P+4Yc(v7+43mA`dE zY2(4ott*M|axl9cq-P~TU3X%+?)siS?HJo9LwG^FudFVKwYQx%{Ci5capUuFep)8Y zmA^+8rz7~=HCG57vkJA$#*B0Mp;58aUMdUv$3dBt#vlTLq$JXiGhbEvO{s?isFa9a zkN0At8?8e)m@^=aco#8G7N+{{#%UBEpD`VXPSS7VF7<6mTcQ`qW3oY_nC+O-+ld|D z=b$VaAZ^b)-kQ{yoSaO^w_Ow5x{$Q}dguxNAScEm#BM;8nhoDg=X3Ihaxf7RD#1Xh z>WE|KZ|#7!&Vj~jlJ-zSCoHQ5ny>B}cucamSg1rY*Sf}(P&tV2cEwWlWZ7DK`SP6I zZ=s}u+v-E-VF(81D2;bwmq@V@N$f*T6x&w~A=7GXTl_T{Pv2GE*=IX@U_phlJ|LZ5 z2mm2ecaU`zcrjaE0(l86YtF5ffjKa5n{FPj^Gehr@b#P4SbI)V1jLCe4k}q@7EA0w9liEBAhn`$fo^A z>B+o|4OELsVI8I%jXr10yBvkE9DpEf>SAN49LsqEESZFBUP?a zlYdt|x+s~q#Y_v|md;dU1yc98s=PaQQaKft!h+NfB9M=|?7_Rq)o5Gv%a?KW`k3gu zPqmGIsvHP*mhxgGw3^9M2-7zWz^X)V^*+$WkJ4mmzOH4M--IuSg+@MAQwrSWqhTLr zdZ&fhse0@MghS;)%>-^Gp}{?yaRi*y`T;JEz&pwY*Y;L+IO;32RyD_+_xXMU4cs(q zG?et%Hqf5?(*w-c{5FN!tiZB`ss0u}B6T8{*HTl?f^UHItF82ZlGNbVr7h6RHIE(G z&OhhHZpG#sf01}TJ zVi}PVnzgk=Lf(DX;VPr$1STKC#_>1#ejthnEo4n}Ez#ZF9yzAhti{UnNorsluM5fj zc*)zy`z?x`gy7wHFWG?oUk@2oLR8sBhp)W+Oq0SD^$hYAt;HRhWMB2G=oJ58gm0cD z#IaZkEdJn(x{I-miF*qiZZ6~*U|YoTew9~O$fnkwY;{jR{2sd&_>lc-`Q3xiYqxP} zmqKZ1;Su9W7UGGZ9+17tmnF*}e-qJ73K`4$f%;z-AoC7n2ST-{R2Fb=EpGq9g+URW z+>^Ld;L*>C9}9UilM_z;;r|t&tcfL+|671MPah*Cs7LkCxd^d0YOjrFrBE|?SIA)J z@52NLbrEarXECF=_j8Q-Cp2)L)?Lwz)9q^w%57ioWlVkLv&6EE51}7{L3Sf!{j;^v zIv4LS7le#d-@AqvG5gBAJp=!ON>LQy7%#|b3lUfvk6^Z{<50q5RMs;qRSH&N!70%* zDrG1;g%VTXitr(V1^XFD#ncB(Wb+5bSGG10!EM}wFSQZ2ajYVjyqK{p;ci%K4J~q1 zCGE)?k9F7l!XAZJ^vfG)d=i$8?Ii+*sCLrd*1gFi_|4NHi8q2gT@liTM%{htp=z^E zwF+?Zzl#%)VJFh<4mbn5_ymtEYoL|#)T`QxYfFD=L(5|hIAcMD&GP{-nV!e8U}tb|F;iUerMOG$&4o>ZpyK9lvJ z<AJ)=P5WhJ-+~4%0IOxaoy{QNd=3<4Xm(FoNF6lh*tWC7)ium-ZEUP*_-aN$AcHm@E}4?zcXo`PjSv`}d2gx~$5{Shjx@ zf$zyQ3>+?;L67n=y+A~|5~cI$UuHio`KPEN9*jhuq^cx-)!|)XKVCBg47g$*HdA+Y zU@hQM45k#17g`NuW=bqxG=v|dgS$J&sMP^0%LN)%b%H_K6<1X*ENAW4nA#>s3EW)d z*}fR=q8E)8*aD8fd<|SApKrh=q`ugd3msxVJRs5gj8#e;a$cv4vtJ5q^p3s>_wvYl zhW5QUzGZiXG`$;rLAk{nHlYYVydvE28A+_xx%SmF5E;C&f9KDNScw_5?BPo!^8DQc zr8{-`N|Op{>Ru64?e)mzoC0cnj1G7brdOf zEXRRX0fiYA9DRoDAtw}J_>JzhOR4cK7WNLTP>#g25}%wWk80ho;oF|C=L@*SKrjih zLb^oCQQ`)3kn3X=y`ZU6>O+H`gYG}hdNgG8S8@5y4EC{G`qM-28O+(@=>^9Y?2vDcy&1BwxAAOLd)qe_vJK zgXr@1eKfYCn?)}#c{zfQPeMXsu{zX&qJ_qc`EDnSdB?!y_gt+rQ->={l*X{A=(S8~ zXFgGGsK56^gss_@hHpm#jwn&(72gW5@2!Dwy62O&R*?QqqdSkAdAqL2f!PL#t}8@svsdv$H5(|5dPAv8$xtwMT!q`O z;^eEcG=DGen2F=ku@!RgGMqHjG%Re83TH+sVd-)8$p3_2CZE$7O*M zh8K1cS|~=#17u~n@`f6_B z&p*44k5)aDvU@`}u3hiZroo)ADDeEO(W#f_J<_~Rwb^|7`T$)}kc|@a*Ln#p<7o$z zGp<9uOR;hl#!Au6&v!Kw-*D(Y$v$rQb{K2=v*jNJlx&OJ&YRsJ|O_KbE+ z<-x6YKvytd2goRzwueG^3UyzsYaYV->P1T=AVNiWg{_S3<-AO1YPEn0?ZSNPrEH=D zZu9#JR9^(+e3_p_|3Tgd&h~~eD9ufW)BFz~a-d?c)_>j}dGw*Mr86F~{$Fw_pnOu& zem+HlKVL7(bsET!0hNS@;J*nq1ohqB^UBp%;Cw5&(eTudEU9?>i*uOJmuoy_mdJ7x z(=*Ba22FF<PQ`81|?7)-HIMeV^2oo2heCQQ)$!@bh4(Hnhrx_^M>XwZimm; z$dS<833Hgs@07uCir#|8LQ^h|96{Mz5Di}i*d!C$CY6h&;8qJ_dZ!Ca0_E2nK5uwU zD|@YYc62*4=yTl}T`I@XGZ zheymKWBsHyQf!T8Q$Vq4iNiPw+4wP@bNXwJn!vn8)fTGh%3z#<02||c1*ovkJ$py2 zkF~TPA9AyG!P;1skIKqWKg8Y?$XN&F5YBgsq_IaWG_>HLNqaUv74{6riNY_adjh^8 z|1v8^)P@}+tZ3w&Kk@bH1E|{=*?iJfTBkP(YM}m>FQ0W27bkk3#~N?((i+dn#*e6L zL`CNEe0hClgdG6g2~}+Fi|RCNq-)O_7sN!%3@>t}KfF=~5l*TE1rcky9OhTjI8FdQ zAsm?>bse|gNeYVFy*1M~CQK65{uh^g0q)&(c~zshhVf0qU(ohJGsOLN3trTo?P z!s-diloTEco{R|65}!JMZBEAv_#(Q?cB z4?yeT3w@2uK8l-O0d;^!=`cARAh@MUc@dkjh>`fHf5gbb1m6rH2uVT3PTKze&cF9;FBWdFp6IN%pU(SsMS;K#Jn zf%RT&^y$HRfqsN2s6LNr8-w!On$x&3cN!) z*@PV4Za83xn(*NEQiu;BJV}(x2Ne<#InUyn|4=>9H;p7P$4289K6 zR&h@D{=fsC$%n*}EGq<@w7+&$Im}6Bz$a4^pOXe9<#sG>qrJ8NpCJ|g$93A7$zZ~W zJ2ylVy5YtD_`JBDyC!y5+u>!WKLweb17=0oW37|ZsuB=*?SYrH9ynHm?!q#6#9~mO zITf(T_3rrxodw*pP)_7qDCe!LQ5%b(nk&t=@#s#+ue!{?x^?{kpT`UajiIL~ohWi! z1QOzk^0Cq;j~>14dccvyJ&D1^k0+BQ)V;|3OF3iEo6#1ymtRF7F*P24Gi;wtK0*#U z{JvCgYqTo^%`qrOa}fN@|EywLcBJghK;P)}>N&SDsC5W5yT~9LR_V;3Qi3+txJ`}g z(LARj{0@@a(+&C#x4KFh*&4Aov^tu+o<>OF$2`NEuJ3~5XPL$BCfOD}Txn7fbPqnB zU|na&{)!=kv?pR8$J0VS0xAxQ#r{gb?f$$OmngwDR|+esY%7J8jT2!tkpon`a~Ub(@k~|E zs3GFR1UWpV+Y@R> zUI$`D-DBKv8lVj$E6_Y~DJdgWML*sj%&H8G`iT&S)bx^#qiYA6g`RnYIxu&)02Hr& z=28qA{#%(Xb|KsKnxV$B@wOTkXm!4$j`H5K2*x)D6Z-7xK`YCpJPxxKMD5>_8=#l; zMcfpai`Y4K1kGdnZQ9s`@a0EYp=?y2G9N^FptrgQd}gG3gP0Q{%I1OV(8bt)BuDwV zXlgABQw#Lv7^{2o5&!W9<2?WWyn$B#G@SImyC)s;rSUQi%rzpFuf3{7%_0u3WC$1h!XbY=w1O^W~VxHb@yd z&o2r|!+ML+tf>OZ2!@sF_o2~@GVBl=sNK`XeY{fGX)T&uOIE@|9dhRZ4tTJcS6iDm zcvzwOpmGeXBIbXL0~FoUa&ox0e5hUEKpk7QpN=5{PvnQjHRpr0aCen%MOA=;RJ{O! zs=N4W|0|$;d|VSt>+Zy)_kg~oTn@mZith$Hs2hbK!Y|vy&Zg8q7)&Z+_VzR^ z>Y*;~TPHp5#7$dB7?g95eJ8{4%`HR7y(_}Q4`H_#B=?yK=aA;8gg-xlz4&zJ5mc7u z66)+F@@uguqWWMijpJ&ZNhi!Nlh{}aCTl;M(6+I*Iff3+fqMRJOl80LJLRqoIc|&; zZ*6N(UN~LYTfjyhI{qImeSRPm)7EaO2Xa=0)Q=@QfM_TP@?v&Do%k+Uiq}aCIiElX zfjmFM@5q*jPCPChBW}b!FNRbmJ^80rWy>oOTwo^#M96iTd(@^vr0np(Z#?bo9i67| zJTZ(U-t~}DRo9e;7i(pH?jxvEIVo<35i7f#lqM|Yb3HZ6QwkpnJ@6)dGNp`ri9}zB zIhK+{EvgoG}1(`JgOI;3}(^|n%sM6+W&dCz}; zO|-&@dDz*MM+@8VM-1J+FbBgSY0K=HZ~p;pB>-{Rnb}7Z5tlpv0lgpoysxakHxH5t zhkTMP&=Pjs>Am8KpotBz2jBmJAR~1qKt2(V6#FXa15ush4WU81WFw(e94>2d1e=Gz znvAWxmk~`u2svgKD)ib`9}hgn&LiQ-Drr@JVN60x@gGQ zMJ*NJBT`jwa{^_|e)sOi6wNbn{9#3Vx*Jbtlb&Vb0CxOgjcr2vf5Ez!7~rE2ELb8x zVa-zrM6${=XMn`?E%#*;pKLZWWz;|ysC3^Y=Tx*DJ8p;WLpBW_-}<1M2`RyG`yOU# z$~u7!;4XQIb$a{PN_kO~7(|=|%aLAqGf{}p4L@n`P26SMisSP&{QMv!HP7H@XX?A~ zx>p&7&=6Xb*@RTB+vJEyF_G%t6iv}q zJ0gqq>t?RsG-#rkZCc8yAt_V+LnN?#R;C{DKLs!8_#>Kk3O}f;NYsQegDX%(HE>ko zmNKln!ff5%60pmfNLW&TLJkqMx%E{Ix6l1jn73Ew~s0JrzJx$N0Z%;MSwK!Kqc(t2pHW z#71_)l!xIyg8177BwEvoyrj(O=@n7Gu^*IMEt7w;J3)jB{>@2-#YeWUH8i6+35i?F zfckdj7y(#=X5ph{ORc)BwzOmHt4g%qTD!iuWx?=#S3Ta*DE|{**q@BGK0P5o^ zraoghyI>Zr%Wevk(a8F2b0m4a?W_yO5z3}-t|`JAex}j9w9^s3-OC9eELA5KMr;6R zV(tVcfDXn~qBzI2bn3EPaOXzjk4GvH0MnZa`4&<|lKc^oEXyEJO!m(taQ91C81$}p zg%My{9-Rfb7|!sl#o56+Oz%0ZGvFP;py-u}&tSf_U8s4)LZxwc8M5tvnq8CrYj!mt zHoNwv{~v)|TOy5IJ1kv1VJ;U}_((X9b~#4@Y-W=0NfM`kDf9n<6PkmCr2b^T_B)X? zw>{3e9Jb&ba2^<1rpilw`6(a>X?87Ue!XCMNsE{R@rU8C$nZnUz}0+r5MrY1HQ$L* z$3{_~+PUq-w$=e2fVXM@E0>h!whfLA(7`Fi61tyyLbK~0h$ZO+tRENp%TpZZE0^RN z&>oLYcRjpEF*}*dI+&?zpBwUeFjqxiOi>|Y!P7yMjJr;g*hiH7I=0qB5+7g7&M+Sc z4uAa+WuHHS#Md0dtT_vO9j~PFLd??B(<9&5`Js@qw{NEtfir_Mh!C(?{tPNg!(b?G z_Egd^8!Lmr6}Alnwjk1C5}XLEJydlTFt9dfkF&Jcmp%n8co-24*T~nf}DA zUuXljdoFgWR4E#H^kGQYL{vDvb!en^xBVj+I`F9W?}^WOJSovPp+qmgBD-)t+I*^iJU&Kc+R{j^K!MU3rRlJmlIxqqbuq0KOF`b=t}03_$#rnn})GCBjtX z0#|l>sGT080O|!WCu|9wG?+}!8{5Qn+vi)!>*8Vo!+u>l?b<7(Y&8%;$H?}}F|NsS zrb?*4SBJsBSM2k9HW73jG)eichM|x?YraC5b+dOy3c`GF@=&6p8%qG#sLe~ zIi0nJM+cFhKP_VN?54g@fVe2jfJS!*kYUPBy`N2pqI^NyRdb|vejT}}o$WTl4HigI zS^(Ize0RieFNf1FXZhO6a+BOWieabEKbn}En;S%7Yc~d_WAtC#i$I#E5qeb!3lqyl zx#1(tAqLZ3JqzzFDmvLBOSd&ZD<73yqa~>sGE>%_dShb8ALI}%pXyzb0FG4TJ6<_m zq8sNBYw|Vlec9CFW9g$KLYOmQ#_Sgmng%}9{Mxo5Drt0B$}M7Qc{WsiT^lq=pVxNu zULx|CLyyQf23jcr0UG4r=xJ<%63C3{ieZRzn~!4?yK_zb9XEGGbfp+?`EM-6Dc`6l zV_sRESbKed$lu?M-u9r6_pmOrcid2WVKo=d>i(&y2-KWRzccQm+W)=IEH5? zrPc?b<1rM3XhE8(Q>i|F8!~F4{|Q(+)u_VWOj;#3fc|dsRwr@7$^PnSkIZyQ=2z z*iCg^x1GQ@sI~KtLS~(~9`r37)q(TJB+mTQgT~VuUeM@c-)edL*bmyHD4V5Bu;J6i zV`(;2F!V(?j#sxnuh4BqQxHxSK4!l`*Mjnqx3Fl{I_*7`6jl(JV+e7NLbRczvhIuc1NqBqxLF~<2!xik3 zVPj#Wp9cH-F2Skm(VSDLH$#Ut3nKkSBcf1AO`&3TeKlj+y0g9B= z^l+03Ik5q#rPwhVxpv#l;}@BTL~f%R`8@3Z*qIhGhcx$BabeiLC;5U+w)PFvDz^a& zcTf(`F~C8SGj)gEewZ~(i$Kvv|#dEjSnqz=1npcL2oQ8)e2 zLS8Pq;?KqM**ovek7A#c@tj7rj>w9jy8j3k9Cy}aiGS?K{bG!Ta)dN

    m83 zp?fw&OeJ;S%QD2VRDC7^sIP%GB)!R8%1O+!QB}b7IUeVIv%D`=P(x5qFyq__s%f*E zl#-$WC!7=+Wg5R|UpoMUuABknoIs$k_(R9G3G@kmhx0<~@z+P&lltrmzYPxmsQ;>W zWrB9y-YN$h#%9;NK{+^PKR%ku=mqiEK#J16l-hlP z+tk?)T9>2`>gOKKnu=!FA44jJ&!0b8K2Fs8uSJarEnOKXgSBK3@yP7vqr6Xlq8E2T zApJ2$JH9?fUXj`uMgCtLfsNY`Y;64c|7=3P=m_NgfpfwynZ@^`o?Xx-Wf*%&z2>}+ z=wAThN1XQir;t`u2pidKEUU;ygF2#JURyP@V(vYfTT9FJaAQp7g#(hoV>mjPEy#D^ zRK&0>6@h#>RZrK21kM+-c_UphSXL#M{X33*v zr{?N^<aJabllug5=V1ec)Pj;GSS%!ZA>*&cE;=T)rX5Y74Q?8Yt|NL9Wx@OpUDVFox2-U*6OIDc-(vN^Y{__Aekv%Ct6N5}e-haqS&IXFTbn-b zGhiOT1jcFLrXyM^)j;UW@$D<7u!xy4>oU*w*ipyJu0_!rl8Z%vDSwse<4XHsp;Bh$ zJAE7Ax?;@!NC2g}&5ax4lDr-QNO)UkUQ+H>ftA7vn_X8oEM>G+BsdF%!HV`6=kv_I zX>n{ui;}@HvJb|cd9c9w*r!C;H1Wr914>E^>FC;F~BPg z{r_1g-hZK^q`7@2_lt>paY^F8 z5Bqkh|9@LSrb6aG+7c2T^gOu$+&B=CK8R0UsQg^`V}$5gu)e-D7;}%fPO*So28e?W z7+6vON`bwifn^-PQS4B}Fh3Het4VSY#aN*^2g1>ZK=@XcIXyp~r!rv3V^cvKNgCW^ zNdIQ7)zbw0qM9M^pKeD?~PK>;Izbt)rTL!@u!uFhE+Rkyh!H5J>}2k&+G> zNSA;}NRCz-6_Air8tIM=kPtyIC=uA`5=IXg@Z9@+pYL!64Y#lBBP)i`vf`j{`(djq4^1y>VEbT73_y^Kt zQle^eb1Vr3z%gK;X?t>2C^veDgp#>)oH_Ra2Z-6D@8|%v@1dqyU3j^ng2QoXqz5Qi zz+9hG;{P$1=zLdMNRlssk>! zZ9kg{ATe-&>VfSM^^ioFRv4olY6TQ2p)p%)K_>?nH#lw4ys-ZS@xd49R$>oV!9*O& z2?Ypu_YCylvQG@C!hQmgD90Gf8n1glg|gRD9A7Q-xzYN1DM^i=uwm&{?h`OdWkq*M z=AHi&{-Sck#yn+6&+N^UaqVxVXp=!O7D)v3j-XMr%&}hs9o>x~vcpJ5iA-3P*EbZc zg!vY4i3%{CGha&8^Z;*u%Wi;p$+R2aOiW;uXoPkCQH0=O6PC@-dn8A|0F2Ar*F{JP zf+l46xUJ*+VI7alK}cuJQ@>ZBEO`tHcoOiJOHSWBF}~D5z7eTK8my^ekDk^l^U=fp zW#O+xG@}&o-zHH@!8v483Pd5=e?FawLz9mi!#KIe_8EO&K_OuTv|E678SVwN3uyCu zzfGNvcu>(=-nde(%ECx7wgi=MS|6)ea8^PN{sj_DA;Z#l!#|+MuzOv66Ec7tFiT#g zDs~!2>TH3ZDn@~`?t9Dv96$5&X$Dx8t6hl=l4$}f*x(~Mk28fFDG7*F2gx)0mGo8 z{#~6WHQ7sp7^3hSIu1RjsqH8nN&Qa|6al23Z~?kf6YB@Q06K3=KAC~UMh8g~t$ z5hb0wwLRbG1WZG`-Lfp;29$VlxBxPoH5y;GK(Atr2fyV7Dkj}yM=^I|0@#)A@yOOQLTmJ(7lHcqfirSW+upXRYo=4bu#zKB`~``hg6CWW zvI8>ffq^OZS#VP_3SFg~<1uFoZohQUwaij^#C~Rb>JJ{B%=fc><7b*~egC1|RH^^J zXg6>4q+w|7Z`USVvA%h2l{NkURk$4za3KlVY{Q9z_AlCXDbEq zpP!q%ce@c7(EK@AbH!`4lK-u-RlP1YuFM`*j=0~FOBWvIy2k4U-0PycA8960pfR4? zdQXC!1v3IDb?HzGs@*x|2m~$-9N&hse~Fed;%)|)OC{JGOTpsNt-b)1Rw4-u{O>si z{ue4`%}v?CquD3a2@-y#^h1fhORJV`%Rh|ZjxRd+f#WPkI>4*Owx=&NQ8ZCDH3gsg z-;u4NCU9WJ*_$HiL`66u3BRHDU&{hue%+fb@HWEs_}IqI>Y%yzX7Xrk4)D1Ii2jV) zuyiFqpIy1fUW?MxcwkKZaj|PGP^JoY-MIpp$80CrmH(FQR&=R{Ss8& z0PB|qWo>hnQIiKY3>k|$KT`m-ffhA&5{Vo#*==1gDLqEyCz!rR6$@h(kVt+1ULZ#O zB^5+Bu;JSy#BaHG6_8uz9LGzGix-eo!sMzlD~p0j-lA?-Fwt>A#ua9Z6N)l2DWzcI z%wGOmQYP`GQjOD$ODFS*!Y@{bElMZr1iUx@3OY(~>|vTh za{)fE{sdUj{!3&!{%5~V21q)8|Cb&_(&RE|#Q)gx{*$GSLiuFs?IwVrte4AC0fmV$ zT-uWw+t-k{Kw!;?Val%Vhmhgo6A})bcai_F>#@Uj5F1tjMWZ5Zj#40xHl{OEMX25% ze`H-pVwIJYWcBqC!gjSZC}8w}`ST6(iX>Li(8^m1Y`YKzTKpL=B>dOUpJCa7gQK9% zTJ3TV89{{LpV98dW|F=imin|y)zQ3ZD!u03Gd6##nj^ZN_$5>bG>eY_!TF(3`@@=n zpJ#s(kMxU`5nZ3|RTHq-uD4&K1@4$jzijXGha6)Sh+?C= zXjcUjFZ|Cho0T^R`^w!NF@|jQ${-PYaXCxR-=lTO7$TSM`EQ9WoQ#GyE1VmQ3sD2J z0Hyb>#DwJ@4nM(v`yC{$zs$+L4GG%*N>0?d?QaH5!|n5LT-8wGNhH3jmi zslh{(Z3-p55GGJzV(!&It;2lB4MP3)LWZj&b%>TM&tHxwjL4oYFgJ}@H@#TszX)}O zZbDu_+4LVjCe3x7ZmCDMNLkT@&e?qKnSj8-(*PrW5>H84B4ysX6pH_e9wLU+3L&cHJe>U%kLVC%xepij>@VfOgS%Lv5-E=IIb?*y2NW})Mslv)_Yz4h05a8X+ zEWZc)Qh7!y;=v@PE;P1NuqNJzsUjts z$#NAzNmJmKF_2&1boieRYvU*r)c~r0Z~=WMUO+|1e-eWh2kiXqx@x8WwYsn1s|y~g zyBoHg^+KiBURN6wsmnjqc6zj%`uQ@=IqtM^Z`6V7r%Lo$tiPZsYVG|eNOCR zO8`-M^dE(%JxY{16(z8)+g+Qz%8^bC|GA`R+DvV6U5AWF=Cck+6Qm7-#)ni|w!hQZf2e0tQZd_-94p@h9Te}RKRDWp>4|V|Dr+%*iUCzF;H&Iir2MA6zsi$8kzI_gu^bDlim_^OLn@7|1 z0&HCWKufczY^hT#*{)h7j9qw6)!g< zfE1T91|9)1RWV9b=aLmDd0>>?4UqK8dgswgl_ZqiXC>gE)$W;HkSvD;VfCqVuhj-X z8Fx6^@S9N2)Jq~DCFw#k z(?;}plvF-n{L8$-u{+^$j1PY;z1=Nde2!Ge%J`d8o0cJ0zRq~IB%~8MeLk#kFAB$( zn2^Vx?f-rD*|yLBlx-q(A<3V@xo86fk(BHB2ag^}_o!8y{$3nJ)DGVBJJ}w*F+5T` zd}}s^&OH&oVz1B5&#&QkJhyFO`?MUmUsUyMvtW>d{;A1Yho1FU%0b7v&!5-KpRa9W zlC}OOk=!>VR~4j0ch2xwq<64nw%lj$T`0NFZq+36lWc-UBB6Xr7w`a$K!~6xkXu{n z3D)VSq*F@=V9L>!-<3n;yb42Q^*Z!Nb95u_+J0JjewNd>ch(nA4DM_G*WXQdrf<6u ze6ar;2LJni@y&n;R8?HldIS6FNaz*+)&27kH{ThTL91p%;?4UIs@aV&5I;0}tsr3M zw_GKRjKubmYtrn^dd~F#F>OW{tGT&-iv?O*ke75yKRV z>@;}Jt3x@q<*72s367y1{YH_#9>pY_-9Ld6;X*s36Un>O?Di@z-GGV6mf4%xlQC^2 zGP>P}6*38msW@PirqumRW{n+5NGw6YfE&!EXZ6sBw_Zn!s1%S8+KWr*3-8IocTH`{%JF(E5a?SsZ&`E zlOVw3r#`54Q6T30qq+NL#Z~CNAIxt>(_k*G|&rlVOfak}Ax%=&n2!&oY z0%=m_Pz#T_=x|1fhfvTQ`?J+Xp!hTrt`a<|V2`0Mt*>F-)z!&(s922Xn=tBy;v1YE zJc+10dJ7N-KmqRqfpn?@&LH2(x)HE(Zz8XeVmt-%#1-S90Z{F0Nqf@sESY;Cx0}%dJ*R*EMHFU4;zGsv(NG2?9Y+gjf_at`gld5 z`LVZg459bOyH&4ZXBn^Vp!T{s9}{R9k?M$Jy#dUM^RLqkBNu}K{f(3%f{R7`aB%V3 zxJ4GEIpbs5*{fdO1bF}gdr_)|;@o0Vp?Vl<)@%^mLLWksbuX3Qs_fR)y~uVFOzDr% zLH^ZAsukfId4D;WZO}A#E(HDvsf_}U2dF^UXp5{TflP=7b=9=xg`lW;LtJT!s7^@E zO-;Mlw2uPtY%UeA3`%2xyLvJ%x^D}$v~rpk$E{xS5uuqaD$r@1xq}>)Y#G3!o%{d# z^Ym)>>|or`?@w+*J-ws(*UB0NzCu1l2Ku#>A}VR?o(&1{;{%rV1f6F~lPBy!((=H| z_b0raX3NM%2OwdXCsJ@(4S%JGu_&tGIA(f(bu)jK@;;twg36rS_97Gq*_k6}?F6A- z%&Ls37XXHOIk6eG276KLcJU58DCGRqH#(lgsuAY5)Y@+hrV!mk+-}4dZ9$e1k=Qxim!NFoO z?yM82s*juoqhl#e{4r=KG|YMyg8u_3IE^2Yw!gqg*4VlEd77_#r@O-{aKF@!b{sB6 zmhm&68bU8iyUP-ZxWS;Y3s&*760x1Ad@nHGjq2-7NJyS|0=XugPI7wsgWAIL`_1OH zCBD(x23p(j7x5JVHLH6F};yl%#OZV+)kmYiAvsBR-*B&{#M zYSR$^0-u@Yn{COak{V2~ru?An{YJ(qNBYH@ya~)N*c{#@8?K>tJ9CC53ieqK`RlXo3|xMnubX zK$A*TQTI@?ltXfdK0j&wQt-z}XvDEfu7Oq zOThL5mDPgB82BPtW)d{vQ7*hns40% z5OpRT1j1rrcLp}hZO2;9ATuxu+ABA8CvM|oK-+p#Dga6k_%@6uvu#ETlhf{K2Zv>J z57~wsWbz`i^umP;JRBJjs0%5jkH7!u-ZMV>X;AmqP%|2Jj(;n5<(9gPuu&m?P4eSa z7@(L}HzLlhh_S_X4*1;x^b}VwU1rt1k)}l38jqzgtSN?vYaPybgbJ003DgZ}#XS4NqVo9_1jTp*WUl!F!5LFvE&M?!hG>l%@}Gt1H+kK`qrY}c zWO|6zHDh~&4Zx_4E9-6VDF8rDH)YBeTwk?B{#xWl=jne@W@sJw&E0XGJYJ6*<6-X3 z7lOgv^rywUOkfW_JOhY;AI)CNU#?d{>T{> z*310-K`lxS;87AJgm$wR`)oaz73zW~&IYdpoE;auX#i;eV97N+z0)ewJv*{CqydzX zp(8}C!cK9H06yyJRiZHgO?mGP%vfBpV*d#2ls87j4b}c(sAxK_!t!zv>n%uGbT~O( zOcXel?-}8MBLNOkC-VSBXrzV&hSN%1Dll1T5Ni$vEhY_{G`+twjqMYXnK_M9_aixX z)F|r|xWtQ|r=8{QwY(1QMA!y0#|S-WHWt&n_({Sdk2i8PardRcULvaGc7@-c06cd$ zqT;R7+`l2>SfVUJ24Xzr>N`q)LL|%D{Orr+57L2nk6%t7>+e=EbuCjrMI)hmv*%}x zs+XH2<^A^@yAD&6Ll3s!#l?O6c(p73yGIY;P_7(21kCu2HdTR+@f`m(!H1ffRO3ln zz7|oa!puvX^xzq+5NAOAKXmn0LP{o4Y-yB>gxPoC_N1SHg~1c>7-Yc14!Y)`oOM-R zXf@^-Q}ZLCEOy)wZm}EAn@i6SH$;Pw4cMT`2Wl->S|! zD(hQ#p9>u9&oAMEg$=CKyJ$kdpxrATm*Da!!j9&4cAYck0jUfcjB9U0Caxiwg8*04 zoj6l!Q~waPtyJ%Uy+ejR&y)bW#k84cjh|vthUXR&R}>=!QSyA3TZ$`;cw7<}{qA>~ z!$++!P}({tciqvJXmdp^MllZPzO_7*D#j%tCvR-O&Ef1!E96(5JZdEQ+soe{HObe0ev0Lr zVz;?y#56DwJXM`G@Vf$N_58n0x+M~aB=mc9&xVqa|7@HMUjO|S=qb%>a<7X-)zsF0 z=ndPgBo0G4OD!`Q0z%a{x`A)_UQl8#LUS5qBB+f`t_>;khVTKzWiNXg44UV zLb!ZCB|diJNeBs>ra8?zO4SVRkUZBIhS=b<0g-ui4n1ZMKQn2h45S=R zeBh7|a2h&z)MAn+josb>h$!QP4-jM2`A*SV({*K|Lcf*11^TKz z2QrL>$>r)=*nu(V|4*0SYYZ3H0%BQaC0>4ZVO$E{Ta%F}YLc_~TAn zLJl#5tnb+n{m)$^`#;C9hPCma+wMwzl!kfe7Ejoh3A&ho_lFN{!!Q4Ur!|E%K6ZtAj#&HMnp3v zlk*0{3{Zh(u%G4oRy}MwTFUHMu6qKL4M&8W*5lr%VKWvj07RQ1?Q}^^Lu1NrqL8f* zaOO^6sEKxVAKoGwey^D7UB&|z0LW#~Y*G>TDe+n-I=X<8k5ScAilGP)MV!ozzaKb6 zp>AFHI`sYyR0lq5yA07g+?oaWkRsAmxalRImHKwue56^9JF6zw4azqfq|hO%iqg7e>W?C!}b?TQP2WSe5L*kFcRPz{(L~dvh8Nj-Vcp;@86qXJl4WILl1gNPq4ik zf1ACiUWDK8M@5eU4@90^O~_Wq$us_tMfPV+p@4x9%ErC=0t5-KYrosr!+AA8 zImhUJZQGTPuzHgyUTy=$+-S(N|4O+!P|BTqTct56b}-JqOALnV4qpqF&mHsp||rzJe` z`UaP_-RZ*@*h{0uSG4qE+WV5<@~`Y2SqNq7X0Bc5{{b|3YCd_D<(B2wRG)q)(DZDu z22cYzvW*6d#kzecsx!XpZ$QX)5A%y*rNf)IF09~>*DLh_U^eZO1yUVx%&@KL*0jx* zb+J3wtEd?k1J)}V2irZU*8mFS)&)51bYRaFJoWv#T<1Rg%#PzpE?c!siAH6}NH^%t zpD#B1{p8W;|6eUYm8{xJ7bCO@F*RtD`^4SV!8N4G8=Mz7;t^rVsf)ylSCZ&Zf;?o1 zI8r>=!FlhW4z*`CVYZqLWY)0Sp<-C`oBoP9BHz;YG?X0Gw;PPE;($a`@i=` z?1Y&e?ufuST&pwWVxgYngYiF$}GE}j`F;;K};fw1yW?9-T z)M4six{OwElZWNp^MxdP(aVb|AI~037+)7OY$-1{LEUwWZboRQX|azzOk4JUh|TYL z($K$Qis<(mR^-v~-V`HI!QV7$pj&u`ImO!krtbx53y_k%D>(`5 z)epeC>7KNkn7U4&Y5h{Tj>L^0z5(kg_}ko#Vh|KKS1dR0dPRKAxX9yFOm zqo#9$9(QEP8wwd$Y$7|{-o**0i839f2?RvPq?8SGEwY~uoP4dKTTmf+v+$v_dtvgk zI9@56To=4)R`5Of3T_1C!3>a;AUN|z7s4QcQ^xt-3()w?_|4Oxyn5i=~jOeYuqG05fZH`c+s`6hdD`x&~bBkQNtcCI!UG-GxEd;kwGrRP5G|bI#PYl!rhc zr)E2y8YCun&gDLR&qxd*l2UrLKg{l&Kv+w=JUg5$su;5Q=;h(i_$QC#r!{D3OgrOc z*&`zit{5rGsEZr-JTzns6gI0X7UgGM`N*`@a_T2CXBiEDn!F_nV}n;mR4*L8(uKuSQ~Kp>Y-O4P)9^Glx_(E}oHY1UBp{$)%VO3sVqzD{xYc{KCd--j9 zW-6=GhoWhAmK`thcDDD)LZX9lpQ-(eP`8$|2M-5gD?7wEayFMFGiSe_M0*v$?2T1B zXW>*#0(h5Ram!>TT@qBh&|k8S&GUpkzX>kJT$lm+2~+_+Yh^UbRi`Fv4+d3=F`mHFqJDcy(x&%5K-{0g&S1x|(r#nVjfrYvWR2~c?iSVX&i+g4*JZmKVMf9` zO#S|sfO{}iDd8Gnzda!Wl?Ob*Cx^_6JRjlN`KJFh-!hj$V)>s3n5=Xm0@K zEJR-pk3r>8WPJ!qub>D?c5{*bd9&P5%I=}%EOhxWsG=zF*3#u8+l{MEA0}o#ebt{0 z5@!6yutOO#USTTuElngT=L+1e(baMbzpLRi-tm^&Z<)j%ghgNB)PVEmf`cZrAKA`^ zAD!WaB%rmWJ(gbh#K!%W+B3j5;73pnGFB3VvKIy!tFiV)pJ1C|iWx@A$2ADEf^|j{f|l zX=vW$p~iGMrnFNQ>cdQ@h*LFa%uPL_nxbMD`H>HP=p8U8{DM>kOQ$fh{RPl`jv_f? z+E!Dz2{ge7ll@0sh*@C`JbT86_+e+{y&wpgoZBC1X^yItDgnqkxrr*8@=h$!d;R$n z)g6PA6MMVe)siUfCOFSOywim6_YP4n)Jo^RTo@=ApHb%_zcfe3{Luh=68J~iksp1A z9qOnYc%R(8kS;d-t#ylz?%SDd0XV}*KNBCYJ(z+(>rLJrs=0X@xA@JtrR@mUy&vX0 z)6OA%$<_Qe4SIneov~;+rSc3IjqY0RbrwsgxP}$%4K!vlf)RS!KRa=EDE^PH_}c&1!7+XY&L5EJdYcc zjc=JP{chj3#9xqe{(ax>7t9q%(aho*F|6~JKu9E%#Z)nZ5pN4hh6e2{JXqGnyo__T za*uqPFJoV}7yD=x%s~^HwT&RYhbh>VwyyIkVZB%$8NTYy6xNBBMIE^(`$o$}@pkZNo-~372 zPFNh5+++2GOp%H|ic8N2w{0{&nnlh%aVQe{KwO0rj4r&W+Zy%>I_U z=lJ_4nL#%X(oo7r9rX-VFoN4mTeB;;i#vaUFf_rF$XniP{l2q7{6LOs)YG#EpRF52 zC~Cjz;sv;sQAY=moO}8cj%$O^LS4t!7<4Fj6_ey<@4#GQ<FY0I zzW@P>+^{=Drg4eQJk9gd6p$Hbe%T!#x;9#-aQg1P z%+|K3E#(nfS$ZET@J4hiI*TvfT^I_kd^nu;c47Z)t3_JD{eXIP=eLa*?hvQ~Qi1|} zzWy9FhwGYh;WDkUQ~VV^sfAG028QVe}koa-iFWk-4V zu0)5WMRec^$G`w3NIA(xWBf#G8PW6$fzn`miUPTtm^j_7gfbRQrROasH+ z?iK+{+&z$cehn0FX@D_jxz*Qy8A;mGY z6mYX|&_R5FK%^ARdMajzRr2jJs4`F1f?+@hvIPH&0;CaC1)%Wx`syMdY-g?g`C?3s z2jqT~12=bHL87t{R|uiH&j;f!_j1QJ#f>^M2DqZjBq6Wz{4zMtcxzc$d$aR_*sS!_ zF_QBv--If7sqT^C>3c{p7!VW2dd7&}5;f2phfOX+&_0x12!)Em>Shqu2bLjxkFePqTc}SSDLM~{%5&s1 z^VcYyRki+nvVBdHDGd~%tZbi?l@`i)bWXmN;+QA7a6WhKuUTdNQ0*0{`3E_RWBT}o z&l#5rH;EWkErwxsKKRb)ojD-0)Ojsz0IA%=x7Gi?=L%TuR3sL^kHS#64?R6hQZ{;i zLzh7iWK*uHBWH&?b_)y(V9f1?Ul+5gL&K@YXvXLu_|0?_gd6!1*-}*s!Dx(0V%kB- zOyA^)vMVFTyqL~!jh9c_EH4_xLc-bjq+#%cFSP0xGEz;tLMZ=J%8y`AY`7A*@3g!r zYknp_c-F{GsGo{C&Pim&RG#apZ&7s3V(OxcR5nsQ_zbB6dmm-p)YG;2Epi*58F&rE zSO#u|8j`<}uS09u1{R4M6epRcO83mavcpqtXFE<=Fg_Eu%&(JnA5~YvHrW0!rWLNg zlAy8-W^*xQxEP4v*3P*l_~~JvW<6UyN4@OkyY^P!{z4iT4xJvmq$ABS|N8X%+fS>Z zLaK0>k!mMG!zhW1|0i;)zUP8E=1DQ6O3s6dC*DNm<6fY-$otR-9~sWrOsS}C7SB{T z)aK4oT<>Kc#5M-m^W$BtobEiQsM!T%exZ~mGz01a4xUwpMw$~CS_^&OudBqskI-n1?`iwD8vA2l*~vqQDxN$OKIm60g-8r z<4T}*EE3ax_)dTaudu;F|Eo~zZ5krjG*nlyqqq}M!NK4WPR`Tj;prJuZtZsjJ8teq z3xS!ky7^Xm?P^XFpC z-BJhZt(F&76~Qr7>J;BV5fW5+8BBdS!TV~2+WtjGZ=skV9eyy4lR(P0QCwDNQJgN2 zR)&5g`%6LRfGJemD2XHMP{Fn$i;!DNlw0{8pP3*ium!7=W4!SJr^hm^dpT!PpyEDS z{h9bi#yqRebz1wD?>f(R&vX7=Li^6H9joLE&;%b733qn^9YD#XZe zC?;7rxF3^J#_ZeB{1*PRvTZa(*tb1_R7Fwin%ugg5^V7j4I2E%rZSK!?!RtafQKoP zQt-Se=`to_N0%h;WxqOJnG@!VtleboQr~ieGIaoSOvs#Ngnlvy+1KwJ>A)s+yBCD1L#&$q1N&3`r7tD~%E zqwXnVLj6(ugPC1AEUxSGe03kEK75uqiG&D5hV@kGpb5#W3<3mr1i48M{A!zPHDV8n zz-n;5yl2M_{cer2X!Fz4&bpb``#RWq95X{JW(kR^-qOvYMKVWXt9+~aAf+-*@ygY+ zRpijzWGJQPWh7!F6qJ|h`;zy4@l-1bQn+!^a)HKl5p3Q1 zop)^sA8_NT-`2byf5nJDzWrvlF+s`tOwOij7M*tXl|RRT>ESVPl(au@v~>_1*viF8 z$f!NiDQeobm00AuDmbfYL)t55uaQ%T>2ZH2`e(OD5^^Xf48bcT5oUh|$$IRU`E!@& zc2#=!<}xdMC^XCvF)yr_-$c@K)c925XOW7ik{k1(Jo%fiW%bOlIObGZq$jJCtuBNn z{cV2}sf3!n07!p=XQ_={qx6UJ@|s^9yVP$&(d!HyyMzpLyli!t1td^^NTf-s?uBH# za$&rI0atdvUop_yS^>9Si7M?|$q70zO|-fFL$b{mD42!HpjnCHzx-&HSy}(P+d|3d zbHMmFSS;jY|7W=3D9i<#OL0PqKbuoxFt}UjB!Od=U`lUq>Q_w_BLqy7R54f1vp}5i zHBS+W=Y(Btf%Os&w4W{9#+BpN3*B@Pzu#P5UFUd(XJok&9IEcgylS>!aGX@Yf$O5v zD`m@A)(@Qm$QRq+ z3s_RLI?{%FvgBCsD7;$zcu#R&SIYJ;{nj+Jj%aW@X;oZTDt2!XbAL=GANGXqPC zXCj9}p`zz$d=C)7Vk)&cnXKW8fT)vNS4!Hy8>Ue!CvgRvm-$&CC|ORG+fRO~qCeB} z1sXy4e&e_5lz~U3iFX-o z|K_O=>E0{5haF^ zsMxMfu)Zg&``@^McyU;x8Jdr&r`d`hsqwG96Tz@jia>STssLF-Lgq#!y`5-8o!8oL z!BJX8m*kh!l?Hwjb6Zuu9?>Y3)4jLv0MKMN(D?`A!-#7RXU+i2v7AEDlFHrGgse#e zcpKjZg%KZ_y7guAkDBf{W)*$hXZ2hbt^?Tv1z!EaM+3nTv(Pis1rxy?`((Ev>pv#Y zzkzp}0v0l@2O?0RAWWMb`&vwWLjcK-vtqW529->=&~sYQkoxI^+94WM7=|J~soqb! zq{#Ds0!iCxkAGZDK*}bZOMBB$MFZ&xeem^Jldk@86jXCy^%KeG$ zD0Uw-@xrqRe0^7d+%+7t(ItVa4p$)wo+46-*i$O5dmv?Xf|)WikKzMah+fve+F@n= z$v4G6`x4dOpkZx#<@RSYZwP`!c)Zz**{tr!4|pf1xV?+@9aUB_kXA(yG7{KHGt z5yMG5?FJQQJ$6x{ceMEW*dtNue|AW-g6zi0rmi1fP;0&Yj4SQ5z`ekKJ492RYHTvp z_#bH6i;=}ekd4u9#1&8sdWT-NMaIX^|KT<0VwA35Fb<4U2E4BXNk z{Qk=Xv_qd_Qu985Asi((z^7WunR4%XA*xzcSd=2S9$edRQXZ=c&9bpkacUc`(~l=bmH$6vOHP5MHsR#*kQw8iUUsLw>|RA0z%b z+~pG#bH5AWUbTypJ5Tvlq}@8$TfBJpAy4tidtIfDXVc_w1=oWuD$Ha!5>d0O&$IO2 zmwm9^^DF3s|9K`c)tBjgf06h6jR@-%r+FqS+fCThuJbW-KM;rYjziipNr?72fOZV` zs38pLudCElNl8MWHaUSi5A67pm4p26!UfKb*Ts)k3KAE9&d=DiZK4~}TIDgaaV@D6 zG-g2XBZQ;!Pyz}ExC=BE1csE>q+2_LZUZUg;TuptCEA2?;rh5jL^Kkv=uN(7aR)Au zzd$ZA=Pq*Gr^^Qq!5WrFe>Y*DAme7Q0YkrbHfo2}1IN2~NtD0!*U=u%M@{IPFgv>Y zNR)zTU>XsFr0I3xBrK)q_Ue~d1Ugs}n$&DsY9KKH}f+IY`LG;j8nu=PM475gA&dd)}iFM1BoM%R* z1`i%kAyjMw`M~h9e32WxtjQ6m-R0plkkWENu_PJ#Y{^4h;8oXaWV7$IciOo1{B^RW zB6!VMayzF>Xy#2I4Nb|Eb1yCFy92(Axy|?SK;oBi*Sg6oL|;byGHU}~GX~tU#C_xO zA)X=7MR#*HVMD@(<|I6Brp@_B3u?|`leIk*rn_gocLlL)Qtuq^&tS==Ui&7#WX1p8 zkA`+T#o5n09b;R5B&?a0L6<4;YKE>Rq`3m`Sz~VGVJ62BA^+aN(t(&eAq8lHZXvq) z7OMUWo}T)@_`8%g%eg^lB+4?V~s#% zkNQNTZc?Je0smY2?6)74ZTY+dL$a)!S>M*#;z0MURG3;!$H}IGjGgUPx9=4cI}4GV z(18Y4-hPi&h(8fA#fb*4e@`tzvVvD9GhgcQi1-&CLg67CiQk2!o&s<=FT+vbk0dOZ z1o~1PUHapWU1!7Mw;gB(tJC-|&(JU@_aJ!fGxc2Gz)7h~X-chqOYz?)S0?VjgMZ|t zW5fwgz_0i39aQb(@!?j^qf{`9yrdlQWj;~mGi8RFR1CBD=M88ee5Uc|mP#!efeem= zkI@0b&VY#%Fcoir1>k{C-!OBzoUSxo>IG1ky=A>&FW{G@5)xd`?2+x`Ny8o|-hsa} z`NH<=8#T_C3m1uPL`|A1M65uCp+7wBMokZHH+NDQ?anI80q7pR^h}@=F|_$5!lV0& zevGsK4(epH^%LNcC@oy77>up}LOcx&4=k;gbDyyw)`zC`&M6s*Oms?nNju5vV>b>I z0$)HiJrzYXtyt%@qVI16=-`-7?>I0}MO;VXH=$GH5bp_9Zp?%DoM{um7rngh$rB$o z!inP_yAWQLoU;9H6rVVAI{2f7#mKfEYZkv<;i{G>U@4O;%Ts!|{?A`XR?CY!w+ z(&gN@txT7K1ziTz%+9R@QPBD)e<#slboeK5EBU zFThL9LgUj%DSeNNfn#}Or z_Eq}VPs%_kd-9Za^CA~l<=(-IS`yP^oX_$z)tCRP1&BJJV2JJ>7Q-}5hpWwObaZ8L zF;ZASLEj}4yTGcB74IlQ4|9fQb_>kJc6H%5dWS*+-Bq970TQ@H08^GGKwU#Xq+4k= zS*L@NvOX&iz% zKy9JUJE+-ZA008>HMbz}d}Fau8>?(x-U7IyL1C?t2b~Hz@+VHccNnJ1E0w!{>)wFT zy>Qff^0Pw*B&Nx+7e7rk0gaizg9lm~3y~}?qQD>zc?3i7yS$G{f-WKG!Y9SOQBfw=!=sBdF$iN1`JAPqSKLXCYc#8wy zfz130r(}5b<@cn=pv-P z33msp3emh$$tWhQUl`}la2af=r{_n*Ay)+jANcRBU_IHnFZ&&AObXrQP|-mCgna6s zP-6#P4TGSk3CJ;!VVF*Zp|^qTOm}`vqj#%d@$BYUo6a5^T#3zw8X< za-0xH+b}U(^|uK=X{j41?;MsT96&;T(25m%+`RzCv_OBt&gOV&F-#5gH#xIgK{k<2 zAyHcY3EWje3apmh$o&45QNYU(jW}W5O}X8(7c)d76bO-OaERbi%pH!X0ntap87^7?Fn&DOdeys=yF0ROca0*hD;js4Ak1AzLbAiyrWT|Q%eS> z13_U53ttdK@t{6D1M0WdHyv`5Vb_*DSs&E0c4oe-zqOZ!(o5KQ2wLf>ikXxVcfq@- zD`oq7(BqUxigFaE?=R+R&~tR&YXXrKg5p|-I5}navoB@}ompG|t`vAl`e(`Zf~lPH zgxfk~ioRJ^FJ|$_x3#}!Q}&5dxVz1LlZdhA!NilX48F>O0sR&-t3UPYJHfXD6Qj(x zegQ^3BAFwB>KcPhcp@j#9N5DRurjJP1dhphNF@X<@Fl8G6dGb(jU4v~g$rLm%iB`% z=`%y|u_EI|+5Q9Rp>gA$VpfthVR|B)zjRc*{VC>QbUjPp`6^ss$hceRo^VB;p{n;i z5N7G9(wsg040x(!5U?_!u+=sX%Tzg9xV#unjc)@?ojw}jmg6^--c$w0iGhT~n!At* zcDZLFnyDgsTh{T(N^YOJUY!N=nl23G+zHH~j6gsG$+!pct&uo6!g|gd&NyK9S{Bb{ z>AHNU%B9Pf=}b}Rcs1gcZ>>x~lC35Nf45BkZcemTRGS1J=i&9m0aPTyr!s*Ia+0TSi$NUu`ZkI7fso4b-V?r|F|WoQIi zUQssMZ$4g*p}f}l{ZZGi%)%dGsN*pA{$u!;o_JoQfe8s{N8Xc2IYKnNmIeiZBw9Zb z<_R4u(&2iEjb#3P1gYsaP$Ltn3H7v&++bI=+K|CRx*gbz;9#b(F9m>nHVTs1RYe0s zJjDo+*t_xhVvZyM3~t>&{|{ep9aiPqy^BsJDUDJpDJUr*1|TgVDcvm~B1kFSDxs99 zfCz$8(jZ93B&0)BB&4OgJLVa$YklAToxS%te=M(SscZ4PPmH+7J??=+cb{Ie`cNPQ zwC#9=je$n>OG50qv&3)NE23M0EuuJK8foMOmQ1bceoLQQwEHM|FGF1`{RkIv(aBW4 zGyE(!1k=RvO$n#1Og|wRNg^&~X2pa%?zS>)K;tbv!^3i=It=GUG)_3l z?L-PrQYljPz2QgSPF3ey;0N9k@UWs@we+F?l!1HVK)V;V-JojH)qD%%*IFqbc;0yH zfcQQsij*=uU>n!(-Y`j%+(z+DYG0fI+#|L^LdeDP_;wJ-B&&;a)t}(ZiM$&>-tY6Z zqII{3<&4&^QRXr_rP9%Af#|6YW(er2V4anrh|{|p4J_e~tKY;@1>H3;sI&EZ;VrM_ zJuWvDiwWuwx@0uf zOsN8uV{G0S>jhK zIL05+@|9d(Lo%H{{sXdUCK8XU_)ch;aCSFnqDP@| zOh6@2HCPb`u6iZvLo-`0QGh+F`!$DJwm8ik8@NG#<(%s}w<_7)J-2*}P+XF!f; zKrUwFHf2O8b_iJ=H*HD3(q&40arYnjh4u49cvNmGAzV%u8r(pAJjc zjKMP~w6E#N=viVK^_j(;-)T@5boqMw8Rql0W#gcs0=SQnyHM5q80;dSckXEU;;tJg z265sOPwl$DOBDC+bH068*gttBt>efM{J^w~zuQF8c+2-3qnT2RB_2}e9Fc3L5#Z0|jMo2)6y3vn5pm)?+fR0wK!K{o)qnl3eKTuq)b*$i> z+ejywe*X1d+jzmf-Iqd+eg@@tQ@yyu*ZP?xNfLv^A?^K@ms7R;l;b>+w*zkX3t~JZ z!ZG&>I=BzTIi3f}JK%A!xAp`YlW^meAt%-Jzl{QQBy|$%Oe7gGqcU&7StKWW=Ku+l z!99Jh@%6A5ONP+AFYPIE6*z05kpRYh|Ng!PNE|PXk-lM%&2tggA}<8R3wrwfC||V` zpZ<9zxs}6`Lviuz4xeh$!HQ9qeulc>9!XV5de{t4RY-%}i>yabOwT8XN<~K_*@fz+ zljo7VpY32OBTWGI(hCh5K4al*{Bx)LQ>&_o{8Mu<@!tJURj4sfv4x-Rz742Z6PBgl z#s;|yibZK~k_EOra9{p?ku&yQka@HaPwwd!dOPB`AekiYZ~0KjrS@}v0L_G>@uf+f zIcD46n$2oS)6VhU|6fcZC6D~n);~Ia#p4l85@L-lG^#nu5 zZ%S>|@u2k7n!GW{c0dX5_txo!uxeJ4b4|YbQy{R?jH4Nt$pxjD>+^$GXhL70b)RAE zbos94>Xa@yYi6q$M78XCPUD}IbVv(l5Hc_<@$8&_3rfcdCB#kd*LFA5;@(I)x!v}D zZPV#KAby1VK{8oDHyHSL?JRdPO^sH%Ug@m3STX!P%UU$?$;~1Q>LY7)9By+52;910 zF8Db{n2G+T)KoHwmlP#HKuXWzSiK&+Vfhn1uD6OEf=u+RxYw64#Z}v8h z?EXXHaKdsrPaY_@L)s@6E?#5{+mnmXu72sgocx3i(+Yfv z6sj~uE)UU96j;acE#dA?n;GTkUPiFnFx973*wt#!%`}7JdwwmaR?R$6c2^$saw21l z#x_%2QDN0`%APyQ__=U!1+M*(Y@g8eoRl4FyLBfung#OsZSOgfbB8L`03$D8KLTVY z%`^3Pk>wCA$C2E}vJufz&o>@0!Ma`IPf7pS8^QJIbo+fmyt6IHWk>7nrPU? zF^|HV&k;-cWz2s{JUpQZY^^Bz7YrZ zUSa)odb(%MjRo7!7sF~_m6s!o1`eLR8C&1E{qyrC9VeLq&TzgFc1>(qQoS^x)JMl1 zSAP04k*i58&r$nq3T0>Vt9>PaoxPHExj&k~AIGAk!G7g+UEDr&!L|YYD0|dp7mLp@ z^2PSG8S@yhNtMt28+0z$nbG5qs}ptePMA(zhS>p{6)x7rq*0RyZ}TexM|wC5U*o1E zz`x6QVv6xoB{=?s=}Z>Y@^i7;z1Ky{aoMQsb@zyug3ssSXBdltNA|CXWiDgVxd-c8f(b_=Sr{^Q?#Op{#68_{tX9Hi5ZJLgqi)`K(fq{M0#)0J*;^N=iE_{E3Q;-0dP_ye1IkP1F8$I`h_Q$y|ZW(0g*h2 z+_Z1a|4gkV;M^#E@QZs|FT^~$ER+8fp%nfru0m*X+dh|cLBI%h@1dM9(?5(k@kKB( zqrNSDSyE{bZo7jxF)@sIbed>jvMAgc5Q!4PNC1I@%7YOGZwLfNy$xpT zFI8Q9Q3Ynt9JiQeN|n=mm~||tiPStq3Vik;K%_pL0YIR}IsB@U9K?B<82on$?lYb7 z?N6jhPzIN;_Qze9f#aF`1R$QEWi#ooi`CD{9uCnuD|1&HN>7lc)HwB7ibO#G%}^wMB3#gAHF?@y$hI|TZRTu-*KHO`a4?Ck7B zVj)zS7f}#^e zGpS7D&YyfDsRkW)4zJ17aa7@L&8^`7yA9X(yjvLELGMilAroytFsumX=~v-)dHe z^Kq-CqG^#ZFNLJVLJJ%W5_8E28Z5GOZQu;5IXgSQ;y05pl+?F7r78(|IwH*LHAM6b zlYymr{u_0DFNf>{G;Se6P8FNoqQ8{m_|0NLBC{QcoV}n&Qo!GOdWV{89XnF)oZ6eE zbsOna{`Giuv?hkb>F>gtDNoHYtayI*g(rFevCUK0ZKAYU-ofpW*Ye#_1=eFZY#~`$ zgT{U4Sc;Y?W;$a$n~qpj>*F5>ti&W1lYGl~{(0ppP=7QoX$>D_JW1&%Wb%*#W)%mR z70svmrS|dH?)TJ*d;m2P#r}K~adLr+Cm6sPVxfQ|GQ@cGUN}lVghzksvT=Kn2{&Z| z{OsnL%13>lk-%XoU)<&n{#|L6{NH~gutNJ!#4h4m5?wMzxX5* z+CJdMs?&adx#8a?~ZE&ed2J?H2BtA5Vyf_%|;6b*pMb9hQLplk)dXb%7IIMhoX;2Gj zg7*~2t%xU$0}N&F-c2d`NF=v3T4N+&CJVL0G|=7R-Jm757$l$xg(h#lN~OK?fn;@j znE}rMLB9U|t`jF@rq7T$Iz~{gD>UDih4PItIs`GYQ05Pn;*>_~xrnNuTo}37P`& zlY94_d%yi&EQYhdEJG4*_@ zZXjV9P9b9D6$BW1{#SSNLokIp_xtnTw@hRx#VFy7LK8U2iNyULmU$2exY?I{ETeSf zk7FM_QD)V4`j=jYO1u?x0knS->XFjDDz-xPRtCBbWM31rR@0SYH0cIHJL9h^KR*ozQv zFog`I-ljM!;ZwdTE@eRNKUD2m?A7(pC#(-@Lp1o^C?AEgOV*O#a^>I9t@d!XcKwP( zhla3yhITc=hTP^h@IQ|zSc!%ftaC9+ZGTzNAyGH{F8tl+2k;l=RS$aHNaqeg$4c~k zQ_vQ8&tA+#pa&4|vN4lajI0!{WJ)Q)Hmg4O;*yM86PiBvy98hSsEGlfQLaL~TjNys zmI+vkyq#ZD*47y!EKX1&!WTM21*75Q3(FLqWBFmWRH57J(|r^HQhVWory(I@at4t!gAQ5Gi&+@z&KO0d7(O1J zzE$-hi^IOIA8CGM^P`(O^Vrhe)fbCT=JbO1otwK8Si z8a4Mg&{V-eld56?R6ONZdsbUYYaICPn*P679Cuentf7InUDslvH>;iC&)oOag}3nR zh?ky>Qxr78zox_D7Lrk)q3@k?>8fM&X{?#PWE~o9&_d*2XmB1ktlAl)g>%Sh4$}v= zj!M2sOsZrCP$BWIoBxjDzRQeumT^fX?m?->E10r55G~G9L< zueNIIpk;=9D)*Qx;1&a7P$2Yc1r~V>hQA0D_w%4io=wSlcdqB-j~qSzxS4a;?z6xi zX%*1$>Z=B;9mktsM#&G@#{11)+>?mpcr_eo3`-S@RDz>;^n;9x$8gU4R?t zf~qt-yu!@^MmVc);Akkh;JUD-UpxGWp83B+L#_WpLwsxQ!*f(W3f%dvIri`0_0H0* z$r!Ho)UqbxH@If@L!{P>&$Pne1r5J#WYaV!*kj5Dvjhh;{KA*3m?5`k_bO;yATuBV z&G{^t*JMEA1JQ3#;+}@K6n7EmnzVzKI#0U85I{C67@m?E>&xE%{CHk73rKf*HCpf? zS2)<&TfwnuA3~Uh5F`|VCvALS87<`Cj)Y-ZU~|}i-80i>IUv@jI%!Dgzn@mI$ah<_ zPMnEi_0Ujl|8XbBM%#emkKZ_tww)KM9MkW{-+~sFz3?wFlg`N5BQHmQgduMR40yVa{TAd)=NCH-47G5qxHqV7-|$Zk78c9K925c%1x1RU zXmw;UJJ3Q;A@9OF5NAv z_(uGHxB$z)`JNIiy}xGr%8N`+dSW>N=3~uXDfA6E#B%3n7u6QDwMHfnAf2y zo?qEBq>3VT9I5;@c-w$;AyMxV#@5U(Lc8zoJ`Y> zFJhut-fSlk^cz+xujL{EhUYrlc2v^*%wcpsBPM+$F!c+{m3JKo% zYa~37;&xQNhGWc{(1No0A`T^}XM2i>gz*SC3=7Xg^HT@!OKDNp1#MeUL*CqmTB)Ls zPc`7Px;1^d23Ha8MTh5}dl)U&DnKRShN|b5SJ;~aY=cob7{TtD+rYV-d7?6%6RGrr z2=!n<_iqGJ`%idecYNG*Ry|OPy70mgnU!B{B;)nFq1A({I`jK3uc}9}CjF~Vift6) zJ~2HC#DFu6X2TvECM~WP4ZG?Y#!Y@pJ~aIkHXWO|JN>FAL@nq+sC@`r0BX1Z3Ab>d zC_GVMpx4YaS@cg#CGJLILuHF^zCWI4{<}4r&15`VbQs9H`E|9@%wC6t0}^#eTmI+; z$RF+(Lo6Y9uao|l*oSRs@1I6O39P&Ym6brM0K-!#d@u4K5W)55aBv9@f{-&AohA<@ zex?(sAB-W~S&i|!&aJQ_wr@4k=NoxIH6PRGf3zNQ%~9LP&3@<)+TU#Xm#Rdvzzu^y zVTLiNELe>u#{XE}kDKapmn2$z_t_bqYWUwMf=8KAanCMmx@g!Oa-lAtiL)gU>t(64 z{&IQlZi%<>PmVU#rk{tQZIk{?$C<@~;AGE!>}U?1LCIeXi*{v);%_Kji+tCAE?&H# z^()Z-YXAz)PwkiT@R32SRUkFLhT*%i2dN9( zyarn_Uz?_#jzq@rPZ|izVc4I`L9gPr*L3zN7ib&`By0N4Hl`52w;|~M{ej}@o}b@#+vR>6b4Fx1iCaL zGvKlU@?>cMg?0Cvw*-)yI7Vw?%{-1$Pz=QNtkA2@GPn6Lgz2>S%PYIwPLIJ7?ZFG} z|66}m4^-fyTwL2d*tQd#lRUOQ8IIrhna+ICu2k4|u=4%ml|Gq4Vblhne(7ihLmWd( z___6HpX;m2`zM`eTYeh2E1aN%kl14Wz^A~WLcRzJBr}N{|EadFn}i1b#GBsKx*_f{vR~=9&O>C z7y>;MBH_B*^VFYUoE|@piZMOqZ)u$_qL#xQ&|n`WK4X|?AW7#jbLry6HoJnFnbyv7 z<(gkWZ2B%my2M<&KXYC&`J{CA{2vI#xn=hD)+ZOn0DyQ6iXfRS=o&cyW&Dq~`$x!^)e{Eu45yP-#m&TZ^j-Abx8U2wA%lAQ@uhMZl>8*df$P zZpa*~4)PrpZp-g(767!^Rulq6I$mVZ^73XgQ8-yMb{F1q3XP>~eHlQ`Syv`DNeVMz z4&;m}Dl!rts?5KI2(rtp6e;LZz>1*p^F~7anU82DWbJLGdl1he5M1}*((e*w^)y19 zFQwun?#QQI}UK9xan4`Sa8J_&wg z5(w~o9*a=Nmx08YZovrfWzpUtg4XRGG?&$}X4KhFr*VnzgFDx*aWVZi@64 z!>o$mmLG*l;MJ>ug9Z)jprAFDN1zXD90Bc#$zDo@1g9^!qT+=O_H4;=VjpgR!aPKO4 zNZovK{7V9w@L*J}!2zlcVE|x*w{dw{?psqE9lk40M@MS{5}>J6%*<_04sW^ZGdTl3 ze9FJ9Zu#_I(6XPU!fSO5MCyX0WCbk6!n*{;uWGpyarf*$HNiD!2>Jo|zH} z)WEt`Zaoi2hP{d=yR1(sGk97LvcYoP5D+FZr(Hw?XBGC+#T~+tzq#7OFO~1M8zI)! zArQzeLTK9y&HxLt{0xhwxM8@)c?akwFa8wUalb_4Z`IKX5v`{wKq&aCgy@jaY6oec zt|43_DbM*vO^_>hkMBhtYxscV-Ujv;ou_gPcT8`dQGaU8Ge7b<_ufp69{|2kXEtbM zp?K>$BICn_*Alo+u8oGQ%N zFvj`fTYi=lF?F5lt$^Xi5Q-e#aeOi0pGRFrL&4fEs9(&Q7?){Mo-Ij08mU>MY-;B+MT(6u*<|PRZDo8-B&}AWnc4?0 z@VDXcYQY^!%b!M)AoIc8ei9f8Tc-ePVs zFop+t#H;CQ$);|rqj@jt=5g1MsAl2f-m1euq4bFT7R|~DhS_iLBQ=+%?E4fN&!11} zc1z94qF=ro?^KcB*#L;GS5@two&Z$s2+=^rTj(|DD!l;Jr2kb>gZR<}?ow)wf2+59 znV(cNv!TQ@xGyM$~n;?nFhrf zxkhDtgP#v}#(AoNoS_)U_x{`Z;<3N;(%MAhMJNfiE8XJRn90G>X8=V{>2d3DDfvwh zGGqs0uEoy?G9<+@#P2*h3poDol6!XAbxUyB-uVUzOMp$%gp|ussrTx9MWJ7hU;v~^ zndAJInL(0{mJuAE99?8%1{$k{Dy0ZWFSiJNd*k7|I;DE8Tr-R*B+%179j{wf;F6~S zsoG_K!`d~GU-VQSt2@@riW*Vq+Ni^&pf~*l!=bWoWx#xys+$~Fu4rVaB|Gf-Fe!i& ze2k>B`6o;7!P)tP(VlidPQ4pe_}j_#`kMFJxb$;i3Pag3JIs=RhA0Li<&T=Lmem92 zxIUCUZhg%WHGUOWZd?qXI6LC(RrwnHL&ClG+4h)@X?3Z72suQ|p4P~Mpsw#7C*VsG z-)zhvT5llXZ-xE`hL@aPL#Gmnu;!f+h{M~5wOq%ZbAG1Hq64jI%aXE(pwq6= zwLg~`(wEfiayo8p1sH?!urc06={sU)4BLy%xG8VqLlJ|!@P3c|86O%um@fa$>%|mI zz&6D)E++pA|raO)9^iqnO*U8fu znUrCJtdI@L9bJk5hlf}Rf?82NlLHM2hP_x`qarELVv;VpIUrLLa=tCcmq5WdGBHr7 z6)8c31P)aEUf-xBYdn|$ADF#IewjI?iq>rjnnw|<)0Bcf!*S;gU;>0LleqWIYgkYDzTAh0$IgCZIqtyp4ZdG#iF_fQ=?J1C|t+<$p4~yU{9h%4OxS_(!hX zc`p6(P#@p>7+zBWwT-C`{*FHTN9?HK^ZKb`NZMD3z;8EfQ-=!g9Xmli>*oe*rLslG z=sz*DZAVw5V*H&zaDyZc^cSkFw;nuQ0lLLiWg&p3o+L9LWl>PSlED$aEGB(-IC1#1 zWynpu0Q{Gy35w)9!G(X*WsLu~6z~7*==MqXlN&v|PxG6J{C381VW(AbM zNs!qeCwcwR!1wypZOr1z>@X*`Kgs&k`fE@9#!g*Sn#tkNDFOs*|F>Mt!pqi^%luMA zCq?#o;a0u8r5=uG{n&tsTz4Yzur3N9bp0@pb}g?ns<{KABbw?o{ue;ho~4z^jiQDO zCR~_fQRj*9j(nl~!2>|KIyRW!7dF`n?v!SMsrWv0%Jwe8IlO_e2>**pEBze>1*cN7 zMM5jyNiO<-+&3i{AY6^G7EQ=(kYKqlFJa@v+p#Ut;3oqu`7C28+5ZJ!8>@B39uNN1 zthMsX8q3U5Ik+3y@n`Zm-|?#2;wou(0P%oKV8BE{?Vqw7ymI}?rkMCr{3GgB(A-l5 z4-+5U^w~olh5rV|sau_WNaTOHSet>9Mj$OfBDD;ZZ(KmUykas^R4i%Hbl@SBT7Q6s zd7Nc|8HNu=#kznP@%Bw(%tsW%AFy#QO9NN7-St&_^G%FasyFX!J07pn9*NRp#}IdM z!Nm|#ksIvf5CUqmTtZ$;oAqp(rGDW5Dbv+^N58`U^CZ>f=wCdsN=@xL))N~;JBC`9 zd@u3u&ha+hj*Kgfa#t@fsn{q^Q}r&}6g44rym;q5@mtM6z;d*@qabvPRR^zqy5p;~ zCe9EyssoSOUxrHfE5I7*dIhGYvjEUOiU(azFG+|?HoAnyi2S1FEfK1HyL87CBj|j6 zaU3(H@jOIWpdVq*N(?C3iK;bzZatBs6}Ui;HA{^9$3MB1l9-cWE&d*29dZrjWBxd6 z!_0X^^5S5uQL{#qi%UH-GWb8@(Ixv|lEnHLTqM`d(v=~o-mLu^muDUoQE#A*lK>S?yVpTe*I<|(_}c!c)K6$P zb#st6`T>N`>oKHf1v7I;>?5*@s@k_Y$?J zs({87oH4U6?*SW?va(`pY(OK8M$@dupt~>1OEZg9qVN#=8qm7*g!rujl2=d4`|=*Y zGJO+gy2w#;SUX+B-4Vz4hU0WXMctUgw=a4-l;DA zTWYLP0JJH>Lo%VRc3q6+9xe69`fcCjy@-mRs5b&ST+HAi*R2Vx_jEhWv~@0xt8DN( zIQ?q$GQFu6+zDA#oWE*m5x+~#TeMlY{|mV}OZ`@f7xQ0T_@9W|&CfN;uRqlu>T<_& zO`-jhy;4ee4<1B%JzPoo#dqU%vKl>4!Op^^E~AU>Z`aM}8JU2;rOna_20z%q{DvBS zIPx{J>1zy@GbG>EI^X7Lf;Xs(qm%nV>G7DNj|@uP8(!!IR9!QUM!A!P2s8l+76|~g2Xj42Z3R}z0rd{Z)#ZJs?fe_D-`^J}c=Ndt3VdhvDV;Z8j+uhRU{!J`HIrHZgM&IoTca zkMj}vq1+rEKebjSDeHhUcm{$^33#m21Rv3t;6({}g_*;b&1E$tSsDZar?C~n<~MjK z4CGLo+%2H?@dTYp!VbX5VMUI*r}(%+iKk}MJiTgOIndNgk7nf++j>R~J=B?sonMXvj3FCqFP)FuISg#xc5 zp6oq3?Yd-mqbJnFV~0>dBOS{f6r@?pN5Pb$dltBXNZ|D4;ZWb=Dd6_MrZe-=sEM+l zU=(#L4=@R^uo{BcL4_ptuU{FJihUWPPd_{h8Ds zCQI>bKhS0D9}jvV4xvNg+sES?pON>hZLT~y(H2{ zQx2IOH55Rkjh+dK5~^|pj6q|Xu&*y66tYpRWB%A0?xJ9n0yLz3s^0Ef=KcXJd3Jf) zLJUz5b`?Tfc2?H4e9_1KGY=CwHZGE+c|89S zdH3N%ZRgSdMJNM_90rW#&^_CcB@64EU!}gcZ%dB|4;I5N~E z=yNGDgR>e&g5}r`|NG;~3TXZM{7gFJP)aXA=nR6o+js_bqqivT5)=bxBp z2693x@Baz8<>1bg{txMxrx^WgM{?#@6ofUG6Bz4Y_B$vOyb6v;Xj3lOX4{MSV|uS& zyY4j{#xT4bJh*N0j#QvId{$g%;3`ddo)pw*tf5zMVfEke*)wLQFVBek5Im2^cpzb# z8OD$M5#Cxkgs(7Rgj>Y#sQhb7O9!;e>lmFBy(l4$~UPM96#foBw1T-4_7~ z4InNDW75!|FiA7tSWYRcjp9KQ)H3A6cE;Fq(hCftZYa{U1waEpeZpqLSf!!TNC@l-o! zC(10bj2y91t7g7bqFosc-F9siz;B~`3qK`rz9}^;;1^iK?dm7MhZ!4Wkc2G&;)pw% zMj#OW#wC3`a)1MIqKF?a4QO0aeU~=+^kE~U&xuXLV()vPmWNb`y-3`MQF*HGt|_{4 zvTVRodO@}|SQVkK9Od8QgtFfA+Dt~&HC}U&vzaUNXF|-0J?zEbI*um7T{8RT9k>=J z$%cd(kb+qfD~X8q1GLZNjxIusz`{0Q_N*OCw|vcESpQ{Lcq?@N*bkMeA_LGJiJ*x_J&+!8 z00gx0T50H;;J(Ej2^-8#-m2qxBTg^Mb&8i4;kq`_y=?r1zM=Quu%rXR63($vP!qYB zunqJPR-|JaVE>y@Ez+RQL1{%@MUA?R~dakI8`Z zg`f;9rAXMgygj>QsRl)^0i#FVZ;8LYf{p+D<#%F^E&S>AdB0y!TOtf^sPF@76?-VzUvrkzvj_ zi06Ho74F zR^cwd3|QYXC44}$YM~4&-f^rT{0-<*j|H-u$Pfn7&h~?2Ks|ritr0@BQi_ywjz!`2 zznouW`nN{l!#Hbu;o}B22*J#Nia0k|{0TZXd98kbW(CV4#`9r>rQuuh;FEus61ax^ zcvIiOo8Yv+>#*>y?V3f3jMQ#f!Ycpe=>*NvBh#&In(bqV@d^TJ70%c3^Pc`P0Mjk% znCWqpL&2oBBIIF64!bRpjz^GMRl9+r_LCVhM5;?rt>qWn$NFt{37w{+n_ca-T3yV$ zyf%}mk(vhQic{8j29jEV{C^Bpe)!?KJNk%7v#aNP>OKi5EO&716FnQLndPu$W_*|*eV zT&cykS1fx){@tykAfP=%H#H|H5tFu;N=x^f{IMB z2x5J0ct~Mhqd#$m%^XH`T}rp z@nR_h;lD+^ku*dTsdwZEHsJ=agNktAjiyP&3x4=#^T>EvC_bWZ0Cv$YAJ&!yoA(l- zfH@Fzo1@{%rIr!>>l@>VJ@m%mOA+|=l6SyRokdS)MX(Kn)1FxYR-$ z>&+O(C8jm1e2vuLpWZ^0i}*EI{ud>zhja#YfdoZwfxAAQ$Sn9CaVu}n!-l|Y5%ZaE z<_%*#`PYpQnc9H0-5uik+A}wj5C^&h_+vp$-|OPfNaFL|NEj}cyc*4p3ce4|hmeZG z+W{srP^3%;GT$rEl8oXIvi%|ZCAka%yP+2SzK`Q6(Jm_pb`D)tM0nL; z`RI-p!g}hJ(2oG*WZgvo-z!M?O3EwvNdf;caz&wJ_YVfWTwR%%U=2Y=NvEds2W`ai zfl{ZW6*Mnz0Ary8Ch5Jo#JS;yj3MjYra^>N;bP{Pb4L%yYHL*9-_)5Gg|Rd9-%~@ZzsyL%vr~viOJa|T+n*gD zI`%%L#lKaOAU#-QeI~%-Xr5=d*oy*s={eD}Ou&(i+uQS~@H?*b;-Lf>6Wd@(KPe}+ zH~zE;dQ)ZA27DO;xLr(90!Mo2!RK7kU~PzV!MIHf9=fw>kwgazv#T) ziFp>G2(DiER0lz!ERQx_h3Vky80sGH^!^&cO8$q{0M-SQosXPu3 zUclPdS?b&vu^(T8w!HRTJ!kX!t-p0IBgJJd&D`?GtLrbm zcx)xFO6i;F2l(FDIkWH5tS#a;h1r-*_E+dO-c>#(P)(cV@nu(z&Fy{|z)_T;a-a>$ z#he@%alZZnlbGDWKWXxLHzQ9D6i%K5p+^OcgdE?{Mu~Awx9hzL;<-^d{4!a{JNU8Z z!j#s4ST-6Z)q;p%~Hz#Y&-9qDFiHrZkY zKva7ES591u)_+)6tMw;1CzvFkC*tqJZ>&E89_&V;HJRn!%NX z)TL!`ta{jvXu`sS^}#5rzxUMy6dY-=`B$hpO+EUqO9zgRnNLZ<*SH)ONdSsR&-UDg zk`PyN_(N#mN~}oUy6#W-Y0I|a2;Z#HQ3F> z_bpz{5nOo9x-dWx@lNS?)oN@ixw)9_(S60&GkgYBo&{g0ThFfj!R)%3ojv)^;%U>P z?pZpt%%M?mN=C_5n(ZoZy(UQx=54YMZ&4e8sj^=Dc>ZL zxgruuT==HvwZ__T(@FjkKxP9c7q*+AW3&y&e^IPgs`hP(`WA+t5F;uT4A8-r*R<>W zX0w0q`bCmyZADyfie#6z9+R?r>7>WwCiC;HC%%O%jW~|XJ}q|I1@GF$Ofky=mf@c1 zvyap|!uc2fX^4&O zhxA75#WUU^sIX-1t{LDRK8JG9+0$FVsCi%y={}+#?DbpP`vD8YA4PWkd>DzAV1o9i znNs0g|2Tg7q3}e9PK4jU;Xd~MPGr(aTN}<7RgF(TQhIEjytIFiHXO%O_Sn0!rgPur z9XgkyFK4yLz58EkP)d^$CrcQokyupw1=A9XIBLEHn7AM%^k+R48&i3m>1DglnKbWj zdTFl32OBE=bWLlr zmTqWK%3qthqRrC#53@(8H>YbSGoXS7I9JCL4W5lD8NmMgME3Mh(QwA``Kxs6h{h-N z;!KV|VeEntuX4Y=4pY^Nz`*g|t%|E15oZ1|#c>Xjmv21!Z8iTr@AV(D>kNGq*X@4A zERbWyept7kW5N{Ra`@de^ui2}SjfdnyNo0cS%`d=S#jx%17lw&iG(a`4tqf8?!|Y5 zeiq|unRRPA(-&(xTiQN^uOO3G_T=>PmJGHgd$3SD&TmiS(?4@X8FMD zpu!qXtN-(G;~o$Xq(`9R;NoJ#$Vt6|vxqMn`1Zef&b8HLsg}D9%Z;oWfuTJAT)|LB zLN^73m5#KqW{8s7?I`?=jr?O%EXGt&KSs!{6C)S-$9Cm=g_dZ%q)kR=VwuVVaeX!J zxXUTTWxkI#Qmndt9E&EE>Dn%$etzOVSr{iSdyU#z8fAs9(Kk9BbR-8dQ*8-mrryV@ zwj(#Jn;HvDkL9e-o4NO<&2JL$avae21rdVwk4Bv)D7<_qZ@p!$xK}m)UDJyA;~ur3 zzH|L4H7QgZ6sxl*U#7qCpS(pab;fMUspV9GEw;I0&z&=uRDjQl720%Uwv$2X>er1E zLY1b}A|mRJhNf%HAt&oMi&EEi74TvDR%%pYDY+r0=d3^x%$;Bgd9vwLpCjF>K1Z7+ zl2F3zzIO=f8C*SKq-ItJ=w9zI*z7HT5TYxQ#5s36oPOe&$ZuiwEiMU((cD+(nBowl ztqLjP+D7wm;6wnX(5vnzGm%g1NBws@1~ZD|(4wUT^BsDP_KX|-TE7Ja3Tud zjQ^n*wrBxsR~RKRwY^v+;WC$3pniZ&i2^2=VzLC**nE6G6cU)`;o8Y(SMPHd2IVTr6k(cLySNIbM=!iUl1ey z;vHXiP2GpX7x77swc;+!1>=gZJGPv{5^u4?n2`&q0oLO%HEf)Zm|+4sxix zws|jT{Q{=DU08dq>hah2wgES}A;RhvYtXrq1K<)o{9PzJQ0rUeg#ZUA`(u2EuX7~7 zy55WGnQxABt%-z<#Ur>zJMat{;yL1vT|bUeq+|Ji|BS*<_D8shcu2}?huGQW?a8?; zsSikTgy80F#}>OaNCB&+TeFlG3{9D1+G%4~YsFa)vEK49QRvOe`{XzLHYzb(S23?b z79{_;Y;LGa-phf5}oi#w8O*09Y8v3tg&|!_k@@%eCN~Sj!rh}*|y3q$$Np)OvFml55lL{ie}=hdO!Fw5t9MP$Y>G_CP~&A+tExDX zkX&|>$uX_*@{@Z)^F2-Rb+2=I8_6M|PjF?+bVuB;*AhUdq{r_x6a{P7WMg*g))NTj zZ(mP_2_`xy@}O}<%}-ws!mq`A#@l!BpCBrhciML93pF;ZK6T$Y<-Rh&9o4J+@>XQ- zZ&gw9tbS~A&DFrF2Zq=^K@*|;j_s(&G%-C9Zz!o0n}4v!zq1NeQT%>cM)PcY%o}xu zH`iLJv)Gli-*xi!YdiC2+woeSELK&1v%?&Y94^&-^X~TU_8gnt_vxNx>>jl%*v@s` zkyxxs+V-C5PO|M@a4Hh1++XLLPuTSn8DEf?S$ZVfyL@Xw}&)xc39n|q~&GaIjs!!LLx50eKNh$f$({WiG znS|{*gv10Vr?c8izeA_>O4+!^nx7Y~0K_RR zFSQ-m=$+hZ)=WPX$LzbMu`6oHuh;wsKN_K1J|e*jw`rcquUdJR!#(dR&ZNGV)5zM1 z8xQ3oc1K=&^o_}PbW=sVke8%vL%LcibZwX{SgI4wt+>)5)ff$*3d z9&^u!kDd?ud@ub(!Z*CWV9#hm+- z2W!(kC-w(t+HB0Og)mg^`{eh}q@{KVlH@UaA9y~xZ#fbXGw|8#R>hW-bp4q4?(k3J zM_t$XQcAB~lJb~+@9q}B!+l1i|AOF|=Xe*qQ>Iurv4A=7KPf*lNtKW2S(+X#EnIem zcG`=jhHo-zP99aT0*KP{i*UrM04Mi(2Jw&t$xHTZI%cP*E$*jHy0A}t_IHLH6QD*Q z;z?d&PO*30|Lmk}J0SI4wpjGHM&9%9Fu&FImvMqH`y-MSxh5Ioj<47qEtc`0UGQZm zF>u~?ipH$Bw~KA}YTdDsXzl5@4y2u|2s*+Qq;%%}d4QSQV}8_mMQ%*vl{{NZRxwj5 zlRCwl_k`3ZvF{7El@AZcJuSS`}z*@~&5ueO>kxA!{)4B%Y zV9Q&@`q0 z9m8s-0wzv(CQkaj4q0jeMZA~H`mq3$zE&_9w`VXQ{BndS%Uxh;EUk56V;7_~zQxm8z#Y zphn89owX=Fbb&>5`OD82*J72m+>6_iOx#4)m2`fwa~w_->>3~7ojQH(Bg6;~23D4? z2VoS&Oe7+8_KYMBuAI+nr9Rre|>@|2KrGzl2 zC4butSFpHtc*Tvg@actoYeVcV(D~iQsJ=Q>&R^Qx#bCu9T(^X`1H4$G#6GMEMctIi zNnzr|1>St#-BiaYC#tFk3pm?S`cD)2BCY)Iz&Zqb1eB@+7KG`uspREMiKh#5|!~=XQlu;GV2fg z*6U{|JFUb?Km5FulJe)iT*grTEeU>_qwUf#=dC|s{FR~RX{-u{nQLV)y(MZYd5%=S zInqqzs??eJzY=0UuYi6R`B^^<5B+Xu0H4m-9F?XKyo9T+_qYd0f3^;o*3I-8b5?C<(Dn~*ye?k4w9o<5tY zktq#E2wDQDkpQdz)m)S&hW zX~nKQ-U1;Q`<)T@u@?e(B@qjOvP|aAcqFgg6t(q(DRlP|EJ7YQF9eG1!owVH7+cM) zo+?Q2ix5}h*7?owG9v>X@YhYL`g*f*Hm7Sw1gJ~J9*Mjo_F)ePi_)bL;7z**SaS4b9D2Jr+7*@NKfc<#oH_i1)bN^Dw8IAn(=!1i17w2F=`$p5GdRnha_SV3nr6|DxQ4S9M`Qt3 znDeM>q!l^!w|dkkGY-{LhfqrJKUN&o?`0FYe~EOEaEe*B*#AeG;!OC}?oi%y`-EFl z)-B(l$kDmoZ^rDw1jISsD#KR`%kaT*c%Q}i<+5MQ*(5C=@P;qBiGM(QvLq+Np7Qia z^=4!f<`QxX9(9G_tj#R)bnT9{j7^xN&X{JjJFLGtnvpsDLcS1a?EU}H^`7x?zERic zFiP~6C?UwG(MzJ25hX;Ig6Lg>NC?qqMhS!H(SuA7lIWrZGts*c(WAE@dN(+i|MNcQ zcg~0RgYVuf5jVIXN?;iEUtuM=rmoPuy;5eVf)Ko>=EnWc|jpj^-toj z<6z`%k_5(;Guxr~TzNGTQnw2A`FLkx*~Z&${3Xi*_+E?tC2$6M1j!Me(v~}CU3n-h zfDrNDjqUQZb{LnqN^V0b-bT-tI>l5|RtEX+uP&aq9y9`WOg4_qeu~JG?G$hkb<2;; zyDQH(0sj)EvQd-X{&MY0dm$o<4j1Owu*7By1lf_fe;}GPDI)igPZ4%rZc)8dc8sI*GV_2$;UH32JxYQ6N8I-)zqd7Am?o9?el4D$%l-=*S|i zE!CvCQeJMFLG`_`G;ik@(TVqqe34VgsQXgJLN`jk+G2+@eoR*LydU%5rrX4e!H&+ zLth;$Ema1sq6U5b=S*n-s_-lJ;|yUx>P`NpPSQ;A0!LEu+o1DXO-k7ZPF2$oAD zT5Q6t+JX~LjDO?6P1+Q6Fy(`VE^YuLs!*x8q$d0~iKXc3xm*EyCd84wJ?zQ_HWH{=6dGmG5?x$}|yrv6F(8 zc|kQ4%`o=vdn`Q2+;rA`MzbuH)OBh8~iWi8BASX%Nv#E?$D$SUo5g{OMC%|qID-*H$oS@fEJ+ha5i`U0gXL4 z2$`=Q&AJbNw-U`^?-0EF3cqap>?!~!f#u-8>yK+og7SRlqF{Y03Fxh8JUe+(YW{r; zqFp@{O{}^^YwBzH5?v}rDv**xlPQ;}dS62#@%EvL0nHnFig(K8L9oIKeH%C0gjyiU z1@m27EeRWge=jh=s&xRFcv=25vP#@5r!TMQb#6#kCjmI_Bk{)y+mySJpc21L3BY>D zZAqJfq95P|b}6P`>SC+Gn$1^y%U9cfp4<~yoED_#b9o`Tx`c8nBj%WX;Es!g!y?> z(*e70qt4&nUpWBqGz0Jz@197Zq^7`pl-k>$hvVq|346fS50uhOphShIrD=$H@muVc z@(ADO)M<2Ro4eXWunO{E30zTL6A@2IDIj>EwK|QrwFQUQ&NX~Brw{$$vn4U%Vl>=g z*fE_Q#>e+?qMQ$1fpmOBmcc>otek?Fg>=2(V~hl_qS>xIUC+FXxA5mU2IkvLb)8#c z0GJ}J#)Y+9;!8|Gcd&4XV|(ghGDM-K%934GXWfUTq80<@`Y3& ziIklDoRAPrfA>_Bze!32&(n1c-l3MT0~V0Kr-wWcnJ|i%&~(sQ*8`Xi$8S?SQu*{3 z>?mqo4R9B|Dx^1(%5`$wfbzWuI2Gd#aP}TF+&3ibH3yPSZ$(#K?z+ea-XhfE1%PE< z46Xy)y5H#=8P2Rz8sS(vI1O2e>Q_+IaXYB7$oBe@{F&!N;w69`q)$azz85r7lb zdblVL7dV?lT%1ljf~PL2z){*5czT__iKk3w?E-d&BnlNG;zI}M8M!MyR?K1NZ@5J7 zQ{hj7{c_>}W~`3$(_Z@wPyzS;B`TmV6=$IsT<4KX(o8QX=m+{{8DThtdmtC=ko*wE zdp{4VGvp5V9auN7_&D%%Ywtn5T!6b{%&q!QB+Ok4t_ovDJHcwlg>a9!N`>K~~ms)?IJXvXluR=u(T6{YXC4WqY~)q7ZbD!)qPHqeVZSGru|l zxawy;*-*{v@>4sYrl$Cyb=E;o@HOWuUtcod+8z8&F@LIw%`u3vl z?4K?>n?BG`YA-7*nkgDMgKx{sSuubA5vZF9K9|>LP6GNC1D4Z3u(J(Q?#J*~a6;sk zC$L^P&b6Sa^-g9BWEfH-syOK?3td6V!kYzm71NH3qju%G6{`W3DZuLf1v{$>!N1uh zF~H7k6tOb$it0@DX+_dax*x9LR1yIJgIavoq8J%*Ih+}vdfcWyI)=PSkVB$>=#>1y2d${ zPiNc#h@(vZZj1R#k(;D5caDPWO?r)3SS&mj@CTYn3yInr-lHE{Y=+VzxZoTbX&ua$ zlLU`Ry7zd{$ns^SR(wlZd4h>XR#<-g<62FX_-aelX*KHNRxJM?)vw+jZu0RO62WAr zpR$9VWr2+$pUOHm1D^64W!R}#5&Gy8-8LLj!#hH6|6Bsr9q40w-07yALX|Y{xXkl`J3wHiiE7<~9gru>B z*CYGNU%-RO_An+=;b7z~8Sg*hofGWnuORoq8yB^%&F>hUGUCTbQO!7^?$0#)m zBaaq@ugyzeW;RqN<(3>TsNUc-dwb|;T3^~Q#rj9hQ*l;|gbA8<3z%ZR-X341eXB|F zjHuxzv;5>vFTl`dvCe@*(6N1R$E}|jYa3renYBxFR}&dw0SgG85rw~7$>Kk{%#x{Y z7&^_1iJ0yd`Q9@G(qYBY*hWZ19s~*KK7rhV-=TcAqr{+x!s6{Q*S`H>SkX-~Fgl77 z)re*`yxo~H%gZVED2Z-tq#-DO14uzUwMMyZSTE+oreJZh{0WD{X6|0syDhosnUA8b zYUIDw65OF5ixB90Ws#=g69UP6xF`Yl-cAhj%QH{zgdwkAz5h z6f|et0aZaI`Ym#nfV);K49jzBHtXJcMCmN}8#)JYuN>oLH@vfc3Gvic^sbZHe9k^4D!R{MEnh!DD($KmtCbw0Tkm}V+ zcIoGtwV)5PTU#QhbP_DG>I+8m{-a6^;FLJ|TG1yUC4SIkg_y4yrjnkd9bE#%a~g15 zU-hS9R`A)H>1e!vG7Al$ynegG_4~gnE&blV+W-tL2Z7FPx4}|&mpvjFyIuz$d6b*j zCDCbS;t~(OER|fek(SI+_snioQsSsxtfJ$1l^d(itt@$=txMU_#u>i}+e1yMJw$w+ zwc(SmAi+`Ombqz0({%ZPPmsC(thy6CQo_t*qxQg#J4>0BUwJ|ie^CTdp-o1xk(rrg=x8(5r>2Z%}{_4i>9x}cv z3B}XBitl9tOkOwGY?_YzdvnQXQe%}*Z~+&8s`Gb59`(fQ#+Hq&IX&BWB>z&n+HIhx zzWha_ulE$p)4EypekLMlZl2e~!9>{2X2|Bf{4R*JLjz(bMT0;?0i zo@Ua$e{a{tfOqJwalLuyPtloNu#hme{bJi_Kt$gQ@%1v;g!{_iQ)P-kwZX0p5^txR zMLl^B8^f*FAZ=7Vz8v7AL@?FWvRqH#j9(M3o}4ppBfK^6&#>QPdvnYw``<#2nD>X$ z8o}|Cb0v66_A-CJq!5{Nayh7*+O<;!_U9UJ$Ym^&^S7#n8s0097=dI;CQu!nGN0)V zK^6#Nf5d5UYFVPrp+0E2Yx_&$Wm-S+2&@ z1G9;&&-trXU(!-i8WNeNy%_H3(LAQH{{bZ?MQBa#%!JU8Jlkyx!|I3)eAo}x4T#Dm za`+^H2}&FNR1T&he`o`*I;wSIO0Klz_0{tqMhX^dnu@f?|0Efub<*ZfAa|ao|GRhx zHEP2daS|`4n|o`){PAH#I(hK4^HoeZv%T6}mzvp>KGV4oUt=`sw`{lO5sTLrk8`=p zx5fk?=Qd5d`peYgcR;q;&LXK3h#Gi7p;9XaFXW!G{qaU!U{xSNY9$YN)~9NV9lx$| zNtfETlD`(>d`GN^!f7sSeYJk+4y2XEfnbsy^+=?y8Z6~PN4+6-RD@1N(T1*c6Pxw2o()i3vK*{JI1vz|?SJ>EvwrEcnx z4*&Vp$I~e7UVm74R($pev-?TMufyDLc5G=JC7q!yf|W3=^(*zusrSp7nGwB?=->!d z_ojEdmN$EkTVRkbD2uPm5r&}QHGFmmq3SdE%$> zSu~(OZR>#2C|Hlmh8Q|w5NN^}JGCxYEw{#9`7D%5TLlp!0uPnLb0f8Fg`Ti^bliNS z=^d?ZNS~?kkMh136;7ILMw2K!KEfR+?c&L75{Kk}myshR7dx8-_(ry*vlEL2@WNlq zzJ7Z|lQeuez!^P0IaoUTy{1jndE-~^2j8`~BR!GT%2J3w4RwECKIfAR9OvHc_}HK7 z*v_b*bDE7nIIfNqK0hdWFw$d%f3ucMf|zJlr|Y*U?OAVduWxC5d9s_YGLk;w-Y`JP zac4O5_i-lXfu8arcg2fyg^Ha&zd@g7F?Thu9aQ0l%PLGrhYdiHR+gbrI$#u zCnE9*5E7#^lo%Xgt-%R>dBIo+?Knk^x?O6gLZDi%~&|Tj-mf_LTP(egFKwX6t2N}b0U#&n5Z zWWJZR8JU&saMJf)=j{H${I-iME_ceN9q@;tOcW*2=FQUq2dV!{aRBCnU+w6$b@>AQ zFT%}@HlsuANI#)ty6*J1BJs~(M0#nWG2%5~Kd zEe&7qNgrAqX$qdbc=&56AN~8Z=rufKbe~3!wrEb3dbIm?X*yPNxpAG^wE95X6W92= zM~koe&S6Zp`RAQ|`+d0Y&SkUATLxCG+)B{ddQFn(#`#Qu>+VX`#B*(mb0ZPMib5g1 z1<_?FTk1+=J)!d0>T2wpeXFQk_j;qhHwhV@*KfCBh~$h&a#-M50s^%Bv`PE27DwHo zqk^aKG2|7<6$a0=%wIvpfnyFS#Jqpz6?kt2)lzdZvdleDISsh@`E0?x@z5aXwqY)oOTrKY{@v{EE%6lKg)7; zfXtkmfZ5H#CW>h$qi#mKnCgmUtw-MOHUTNy3{3TymH%zYiXf-hp(^7DBpj|@{Ps4@ z%=_{!r7@u3jaPJvgfF|^y=%j~6pXt_4^PiMDf@0MfNe1*<0$M$qp z*7bS%>W0(p6sb|WW%~A!38&Z4RLiqP68Vwo%!t6&9pm0JJB^ImitI8Y3zt6^2cs4F zwVyBc^P5?)peR58c|pA%pkXHIzw}_KRlOub4l&Ws`{DbqJ?u_7rjA!wKh~Hg$@r3+ zbJ+0*dJDOknUVOs#5w03rQIIMrE!-MVFHTyKxTPw*ZUD2Oe)1U?x518-7ObV36QWe zPKFmSTmJutziQXd0mW;y(h%#vOT zF>Ib4O!O0w$0KTH->_oz?yRg3+6VKtxKd~g!}#eL;pqaX9@*v0d212|lczKzob)jl z1XRH|@h7doH$nMTnv>^#3`$FeHl)C6FZN8sB4XtLYMG+}!ZLRyf`!W&6iNBI<&KoKQ3 zHAU#QdbZ51Bl~rF;+TO$$c&f|bc>s1U%r9a!8jDu3duz%3j0pL&1uT)TXD-|gJDQRFCRysv*pF|^#=~s zpO@w~EP5(C8G1u+>8H=@Ih%gHp1}DW>$l&#D=MsS+UlUqByTcN_pi{=HJzSHkMWlV z45&M3GCl^<$m4j^xn|9=I<@z@4QY}nXs&YO-F|<5H`~fB)q$~Ri3oiL;u-lbq z{D;3QgWkJ1l3q35&MDz0B$+j_G69v!NN%r9r`H_L>iIbGuvE=kCm>`&0R&k)u=}li zu#I;QJL-IRWERno{9Vq8{v1O_!D)Y!+<+G(W&&Bt$s8YD8Ilj1FLy|sbL)^8OGI!; zFPggNFC>D0`=A}{SMU5`?0zF}D(I*?m@d%|yHrxy0Js1i>zlYC4!VV&I%!tk`9Il0V!+Z$)C zuxE`ZD;6#=39k4%;=Y^W9S}Put~}4&?{i|Xz=1&)A3jlNMz!v#(|5l)7p17(i(g6j z6_j9#pS=veaNjT~ilZ>p!#wgPe|cIpmwQALQGmc-xNWKS}jZG7~r$-!sS^Wk=Cqc4SE28H#% zY#ko)eg21u5+NT7TRh``L9WS(X`>KFW#yo`l&N-!z9#`!|J{Fah4_a23fkN(F z+uBO*_I1r8Vb{zRR-SjhAS_Mm@prF+ysXM0l+O+FP@J-Zu`q^3DJ_6-u_)Y~#jYrc z(P166cgj0V29!9*jF)lhKde@Xo$HR~qEtTy5e!ci^_qtllmcaYUg&<N?9w1hRyqA+xd!Y zb{>q18^R_K#voc(cGWxZQubne))C{M8AsyTXx1m73?18g)rO5luA!SB!f)6JjBU26UC~b$>$7k_iLT8bu$lc% z{P84_+kJm+-3IG)VXx;p))tNM@f*5z(&(4dBJ0v@oUqAOzGmUrdr4e}WR)`Za z5kfo+^M3)D_fOG3^Avc~FMVreE{04Pn-Jb2^W~fnYVsm-_ku)Owpx{eF0Okqx1EXjw!IpIny#HM6+1zYCQ8q;-}v$X)apcK z-5D4a>KMR6p?$OzhE?mp1V-KDfHz4qTB%u$WNf{CPYSnV%qCG`2D>MyF`5;0A6`0-?iEi>rk@0*ryX;NX>v;$|Gq!gDUd9d$enZM1aF%2{) zYjj1iew^PgM@OxTQ zk;TV}3x<40f1t!pM7!$xT({dG z>S4Bjo2hm zHTr|pG0Tl;4ubY1;T`3A{e|0&u#*(ei2Nm=)lR2WmpM_S?2D8zwE(^8Ed|_Wrs^MG z5)Z1JN)AU5;=%Z$$CiB`bIx4~9X`#I-3jc;_L)OdC)+6?z)l#3?_EeM{H^{=i{bY$ zV5{Se(l$Q7$$Ekv8WGg}G5xpc@58E`h(HoeBnVTPa#B zbR{aKaWqP14)aY`ldUarS{_5Pa6N0tNuY-HT;+yHp9ZG{&q( z6&yNH8n|l(GkNJ{9)h2U9wPb-jXR>G1?#(=e5I=FpmnC)T0C5FF*Jae*8Oz0c+7^F ztK6A<{1kB4r_dMdKXog`4?W|P_-}J;xsptE?*;+>`FWXGG1<=rpN$HkzWm6Y!zRao zwzHc8HicM`v7Z-<*DL*Z7CJXP6uQx=NgXRS=bB!bP18C)Wm{bafN^#rM^LycxV-%h z&AY7sO<~w-N*3$qta78#%z;?hk9H%2lu$)uMT6&xmk-(P8?dKSu3w#DMkaTP3^?f= zG(|fbL#`W0lH-j?W@5?sk;(JNW)k0^lIT=Bvoektzmk60A;Y~uhc99Swyvbfn&JbT z+=I8?eX!G95E}3w3d?;O#NT&^V3-?6CQ+8n>~N|$nIq#|KFVDy9R%JEg8-PcW7LN5vzrt?q-n5@D&P9 zOJ2$i>Ix=ulc~6?e{pR6lc+w=yu#8+2K{lv5fW>Qzoc^@DH5lt-BQ0@;cZu zb;*N<+aliwRxi@9H%L$RQ|8T;d@)+RjEHduSXvho(kABYtA(!0NLDy5^6h3-rT?sM$U z_nVE@UCd!z#>#uW*BuX*p;gqCd<;wB*dy|v6cO;(58KG#!DR>kUQegre+=i)j2GIe z7L(3=y5PQT$jEydhb}Y8>ViKbxOHVi*O30|V%{IM5c+M3t;I3ukJS0@O-+u{5`N=|=Hh>Lh3+^uE>(dV_$lm`Ja)p%eokwCLAyoQ+*-`~xn zvnC%>mm_d)S2M!gKg)Ty8?pCp7lj4-B+ta7hZ+*82>d*UUbn%kkh69uq{;PU@9#zc z!GcZufMo)l2kcY6vcSC}=l?K*k6AIFotAv># zfQj$MmbyR)x`BI2kg(DFPSS<%$L2!P#EVjUUzHIO?vI}LP51aHU^p18j9?OHpCdI- zKFlcYyaOGSIR?SZ%8f{HIi4WT<(qxClDETRPv8jRa9>ABX{L!~)$kgL zVsgNmFdj9zQi@yv%x&5N$W7151$0Su4$pNzdcQT$_Pvi?J#yR2y%sA0Du<&c0r zz!`1e+$XP$1svu`CnQU4vv8Bk6mJKxiQ9(CXP$y}+Cgv9jBQb^&<(yx6in zZ8``ge)abk9OE8LO6`D!D z@bMh-3d4kYkLz@AJZ`g4zJ<>dnxUP46Gq&nDxJPlK$@O{`+ccv?Vz?M>LElNvqnUI za~^0Spj+*5qSK;58)9OjI8j)0?KV-b8MgTF4~`%_9DS7>^lG-ieWZ$73NK;WDx(Wxyf%hxP;ONX;kCv1TXf zzT-)XQPUqA6zjnhB4XU3+Rw%YFBWAr-?tWMxfBrvUFQ7lU(c zp(B)d??bp}xPLwab_{9^@egyvABY;98z}?~vcj6aN*dl+&oSPl0Ik zzH5Z7PY<7ddJlxNA@&Sg3}Sto4|2G~XfIysu)SZZnTMwO>~sq2HiuA)-#PgDoa=*< zlv?`P7-27mRFGTHorwwV99CDZ^BG*>-lNH#k1Erh7;+u@=KPB`9au<~h`awmk*(i%k>#B5$K_kHZB9MU z&vqFqumO=5EO%NY&y^?`6)2E9L#l2Sq!3KB)!tBd#!D**Bx>6*( z4o2qQ1gqtKy**+_L6C#M2A1>{H5Rk3yZ-G00mvkAT_FaP3gIXa;Q`PM_&z1dk(i7MDv?F@GKLoG}R-km7t z=O8us&vU#bH*JluoS#Vyay0*>UQc10Xm{n~ulFq~`Mo8_+8N*`G;kRBK@m(~*?9*c zJ;D}8eI>qN%h=Ml^@l;5Tof_R3g7K*Yfl3x_eEchdFBPKCQ9eK4~4UD6#r*@QDvD& z%D3^Rt+G_(o^w_hH{mi~8O)TZU4768!hrrXMI9oh>aO7PERbfDsq?V<3)1I>91ayS zglf6ZkJQ_)WEIu~7Dvu9$ zmr6TacDpUeJMl+YYLom>KC3}!rtqCIs1Q_}4*(!>uXl+Wf))aqp>ccorKCCQ5`;5Z zcO|P^tL9hzA@!1AxCJ{w>Oi>QwAOJ&+4NqkZ{Tx;#dYbqZ zVG7c3O8Bp32f6*tCca05>|KQAzGpY-5eg2_?`QBE7Y4?h82HPeIeF`(72KfHUp1n6 zyH~NO*vgDGhJpKk{`zA)!YNs7`#`wNS53X6*%GX%bG8~0#TAnJ*;sqB=^#J-%K`@D@vATj^G>NC3O$D*Jwc_lz+l~T&I(F9>NwgmX%o&k0qMMS9_^pw( zkepC=75J!s49?2EmJq?BJv2dskj>uKnJAFo>|UOa;EH)c!Hs*?mq#g^RWKR}K^(ho zA74`?4|V$&P=!ts(FS+H`oA4&#IbpKw;Cfm24it%IVbscN+!yfx${2Sl}gfk`h|kr zvWZbG*)3_a6Kuez85YjE!j*GRt0kq4I|E`<9xmTae$DDTUJOr+IXS#sSv&k;>=Gm{ z8gn#`fBjojq>i2HLX51i9KXKyO=1lQ)Mn2g9%YP`<>wWW?)AYxX}tL)`Fue=lS>reFBJd=)QcoM zWegYo6F+3`-VeQ^ACH-l3DCkQ7i)v8!ZJGxGfcuf&yB=F&<@28v)T{dVLu&oS!-7v1$hcx93FtQj+&_z7)i*HMBUqzQHk zF%c0wqUgyzt9;+jH6N^L6+o@#cr%pWiZboWiLSjMP_-?3Hdnn!&=4<<3kI7l2Ws{0 zj*_?AoU%`Ombd7eW9$1D98Ntm0}{3Y32Ym{Fq=d%@)27HWxT=jOdF2u*}O~vgUfn&1W4w9Z- z!IqU}bLe_5#}UiO=)b!XkHi`2jnuz+T+F5kMSWR!B*^Fe=KA--gJw~d({FwK&CF?3 z^cj${$=8zFnQm&0T(mwc+zlUnG`-jDzEo@0D3RT8o_IP*XZlq_u`>smpn+Dc_Hy7UhrK()dLa6cB*w}vO6aMC(><9rxg9uKB2$mtQ=PFKGt+S4TAYi$bgXr9VP}uG`h~KAfl4sBDgG=TRk8qA_p3_7(E~UE| zQQz#dY2w?tdZb&mLi%0?gcvc6U3cpKihK=IIU5)*gdyTXX#Wzyss>JYeq=gdKMllj zx6nL}4|fLo7CLxx%PY7xgc_GpMopF3_LOcl&nf=o`S)GjiWxyNnJ&^s9TX`;M2~Z*k-wt-j;V-Qq{`l`now-^6)(L%& zvyJs`UOD%mq;pJCJ^M?F*;$!5JDi?AmZrup?h2hWs14aB*i*gekhwfHY(%+N*z5x! z4B|61bnEnmJ>p02>$=V&g-0E1YLfyv$Jswlo8U3iwM@Idv@4y<;r(2J;l+|l#2Y)( z%aVFB+5C4gGK&g1^oPof<;WJ?!`s>F-UQiT=cDDu8Rj_3oOJ&~z=k24>K~*Z^2yY4 zR!`vj{@Ww)r7&WNjp;qX5mML=`x!ZYu|j2tZzk<9j_$)W+H#qlAUD4#Q`Mr-GnJ#u z*7YILQMV+r(dH$icEY;O2^?l~oY88*sQTbv@%HLkN*5A&0M$cBsUB zf_RTl@ra|m=TFm&%`z?5<`b)4JL9jC%I-kJ`LgvI*tVdgr8i=?I|;3QgQfq*{%!)s z^c<8LijuWEzoE6efZUlpwk-Jy6#n+pPzP#6Lwq`3B#s(Fra;?q#U3g^NS9h8S<8rP zN)e}5rTcb0sW2Tan;3*{TuhZAtK-ksqF>fPnRTr@@TqhQ<1sOr%?soOaWU&i<1VBN zR0ip8#5m#t;+7VMpEasM75QlbyToqjL2htL^Lsp*k#D9c?Vxa0O>_3=MdSAYH1q*0 z{!ky&C2Fay+uT83vgbgP8sm;_Fnl6nLp_FI=54k;3f`9z;jl{mu%!e?h+g7ZrBMz5 zOF*cHX?uy+Nw*+zKKgs9C|nYhTcgBe&*$%MK^gtBUFPLv&U;k6GL}dq6=^9-tKp{x zD{7t*RpK>eHB5!Dj1%-Qki`M@_8Ro0=8dzCe!D1Hh=91(HAXrJf^5`VF ztT{EYVS!C0UxXi~3tXD$rju@3YED*A>)jwSZ(kglJk$Voh)}Y3hU$tM`a1M`-en zzw*jf!vJ!ceLLmAwwvt3LlK}++g7L3MKEqWzWx5I~(+jbvpWNV#-+f{tH zl%7U7pEv%^&zL;qWE6V+x$50hukMSqqAES%ecIt<8b;UK6dHl^S-%3L?wm+JEm_{& z1}CZmZSC;QCq0+%>N)RrGW!>H{r~_|gz-v4jF;xJS@sTc{63+j2-OgAmbi-D9OpoC zJt>lqT1NXgDL zP9rc01rD31NcAr2kgrI_Tp1+08j}ZG<4*d~`xYgn`fATNh!3*STZ*m^;fB>BR0@cV zDbqyGFy(L#(h4bvHE#U@;d$>Qo(OI9@-b~mKmXHp`m#JPyI(tL``EVLMuL}MxWhqn zu%q9`p*V4ZvR|!+2}S`^(Hhxps;&4OHHzL;VvgBt?=UI za4gbd{JK5zMV2<({JtvhiJ~6MHRAI*3Px%Z6C83Q8qK}*wrP>Qzk&1ja~7QFA(`(I z-*49BItT5Gl${2;-e?QPhew%GO4A~?H@;iYA128h#BW%ob2LsZFup{u7z=WMi4N;j zEIFdPoq6PO0qGoYu(_M-|9yFhUT*qvx*e?%*XxKuZ1DDkt=!q@J7S^PI-$N~xNE|X zlozNxIZNX^WoQ$2WMW0Xa0gNlqK9~d2qT<}3!HWPNI6>uyodt;m>5ux(6X0!L5Ebi z%6uNjZJ)$vSc%Uj<80qb^xjr3(TC*gI1_ufXyM<`7=JaHE$$pX6@$VUZV_kZ1mLdh zknhp)#t%-3Hqy^7$1;*+(wZ(zOGGJyO3eZC?Gk%^yL3&yzG4ysF%Uw87&$uk++Gw2M_A|5QzJl<6c!G}uu6 z`a)Gct^b-^Q?}aD&ao<%?MU1H4pP7PX10r#3BbK|Y@!nM=L0w6n*z?q?r`qh0F#!i zWx_?;B9YD(HAWca`QUQW;+=6^9|X%GA#M90OI{y=)|a_h{?+oanm()o2GsZY`V&-cAR?UPuU-WroFzb9DXHx?^!W*{KC zG~IdGf2z&8v&4?*9{8ChZ{OMXSS5(PY(roCpEi`f*=mm=ZA(mcj*r0uA|w_XA;5XX zid!pzOH7i1`YMDnhp3Lg>KiIYH-c@I^NE*yTlJ-$Wwk)bmK?Ssv1phgF zmpoG^x`7nzkS?6r%uxwp+dI6zNdJ%GXxUGVo4E7UPm$GC{iWoMnpruUGwttF{>zFF z++v?Oe!{LVtdflKL}t289KkUcka2p`KCpT~le<*YDvn!NlS%IBpKIs5`zA{<`hk?ve8iJYxKG8Oo&OBujVQ+7HYb2nuw6b^<1V=knDrKdt zaS%@+^a_6*y?iYyUE-YCih@x{Q+wkUXi_v;=spO2zgkr)me<{4(aUI-&v(q(=W|xJ z*}HSEQF4WhhC``-@BJs9g)s15-@FcKnyzQYJR#eMr(I&rwAv@4xd0_B;GpPP_e5UZ zNX}F>trHY!Vjz;4R>FcAcD;uFuQs=!*#Wwekd4-@i(6QyBALujz|KSO3{OwuL4C38 zXOmugUfwUe%qBfcdKc2f^NhKG?1g=B8a1U8Jq2yNH{l3c^KC+2T&|Of5}c1|`q)Nz z1hT^A3o$1^`mAMA{};3>7}Du$U}dO0o{C;EeJVImLm$?AQE!K?q8n>H0>iU_pI3;N z2D}NT_mtx#u{g4j_yCwR{A&hp8FBeN$o`G_E(e>s0A@!Apisf6P~-2)!i zFxi1o=_K$>ZSEf5RP4!l+agz{|>Kh-&Q&_?PE&q*(Gs%xvKxZ*6Pyr z^p4<#{UOOAaB~nJraqJxlaPi5i59}t&j+7DlyUEsS}`+jas8W(r_X-@>((J71&aa~ zpcNn|$1ykM9exh;+%%U<7Cy6LG>-V}6un_?C;00mxfgw1+wM#9xpfxD!8ekroZW|09KZieD*v-G!)pku znezknQIAac9o}J`^RyYswB?HgH7WyegS&oF$G!&r9cqhFj0uSENIPibtO;wF?2|(9 z(D-`8DxYoJUkzaAncJ9)ky8$YLETb|zDfM0syu^rupu8L;OX9hW)f+H)^Abss1An{ zWP!A`RA5M!L)^Nm$%3f$HAQQPl-o9|gZQ@Qw_d5P!}CM=S1U7|SFK600|;|gr0U+C zpAj9dxNB$n9Dh8zg{kpB9s6wNu>Y#w3Edv2{0hRk7je|{Z#+?oUmll;H;8PS+D^P4 zJn^Up1HSs?G|#K&8mIBCGz%j2ZMmtZx3gJ5hD-+o2||_zB8cAOj=%ns89H7bn02a% zOIDYzD)OA3wQLWhQFPDZo0NnU!}=kB3F?w041B5O)4BXk(`o~nsmd*aj5{TOyiU^{ z?z~_HVa&zoP#Sp-XTg3>S*s1*AyQno=UeVqL)V;pf;rsUX_8nM!=2qzHXO1+rLLMbNE^66! zS3GO*-T$#^zGJ!<^SdjY)Po99duZ#xlaZ7=@_$8S0(ghJ)Xva)tx(}aUpUj|w*1Un zEqMmcc&Qm5RK7|bj_n>xhZ2!`BB3X`>OS$+v>Hhi792zK+*I@aO@VWLHM7hsj*y!y z%ORD)g_8TTPas5SXX?5v$jh#HP4h}2Vk7AN=RkYeu`*ryobMUm*M=!i8I8*4e??Ei zigJUpp>u%!F@hzeN=c$gG(s&ze;HzjIC8pkZ%m7yBUNCVoM-%oeTlq^u3mT77@r1o z`Pfs)mPV}HLT;DZG_%ppowb&TNV;InU8oDHv)?j)FXcD1%oL{|<^xu`*BQJ59I7r= z24BB&At+i!pXkqTR8M~SSzg57cE)y0oP}jBCyG_r(ZnoO)Zh+D(ERs?AzJ8%OS&?o zM-C{?&bi{G_u#7n-I?6Kdyl2$*RNAo%*(i(7nJmdQv`{DzB%iZ8uM650g(6^{g$AY z>Tmey1(cFg&}%H`#ik8iY?TPzU*%r%p1zysj$62M$JRlfm|yD;mfe@;x=&KQKV=#A z{4GVDwna<);?=)>;kTKcOozAqykXg!`NCH4SB1VZtHJ(hF;@*Pbo($}i-BE?1F?rX zKL75nyJ+z_l`DhYu4JTtX!48q9QE1U?nSEKX>Jzw?RCkiS2AE*c=v+h$5! zi{a1UvC)|R~L0_7H%Q9YtSUP6PyH>5G1%0 zEVw&`MF?)eU4pw?74Gg1A-H>CMIYYVU-#|qG5Qxj8Kd^uveugOnT+RinP0-W0RbfF zDPlxzd+Pih_6z$>Y1Re`&oKeZ=luI~^kfdW9qJ2^Uzs1+FR z1WwGfs)QJ&bpuf?s1v;~)mk62Fj(XP-eZ_b5sM#qGeV%5->G$)23<~LJ)BG>waF#Z zWe0bQQT{d~^Cqa|<7eS|v{lY=X(<;rVouL|o($k_-ZK%^1fU6loH!a%fYt&8S-$TX z50$YI3-yX?a#AsD_ib8wB(RYBb>YwSkLKYHk{=U$I-9ub-JZ&O(3ZPUGeHyAnA=?y zbz^ALu6t2JChA>l4R8&L1}Eb#`u^*^zu$0xhpU%`dS|hUe2UpPNi_1czh1kq_)i|G zLJYfZKL4uz1Pva(bF&#)M|d0_BvOo^$;()&YJ28(xlB)tjGQsoIS(7}#Y%5){5Tfy znJqN8fHZa=N3XQ9+})K_@Onfvk5KuThRqhlre{JN0?&X1+xm-B@e~q6L+j#0O+HnD zr_(N(3s|nYLfQo&KuHRmGc@C}tz>yw z#$U+&^vd->C=F1kpB|i@pOljI7DjLsa{kv3WxJ6O;srgX)WbhY{Q}{RAjg!&n4IH0 zWFB=*_G$zNVl2g}i0QEIlY-^{vEb<-dfs+MfRhBBu^$-adl=rN!3aSS55aO@)~6IX z+IXGf@d)^#O#vV86lvf1y@{p3cfy`e@J3KP3pQdVlT&Va^iyn-`utmZn#1jVO&o&~ z$Y61Uk1Vm@85C?ypqs^zN|&O8kE{wL-nBG`A3wXs7)D>IQG`a144^bP&fU%!o~&h- zRmH8h{L0CFliHs5!k@do(f-qAGx!ByZ>VUPKde>UaBzRnrB)~_JWXt;U)TYtI0gdM zdfO2Kt8#Bv)=wNVDnxL8uJ^zq1Ae={9g2TInmYv$QZGJOrrgE%KDY5QEL#rSBCMUd zj3z(cT`y3Grz`|RoX0eITXWA}#utow+b=xVIE@e@`0pd_X+Xm2{J(kfEJ6$a$CFnm ztXXl_O{rh;yQp0jyXG=ujhq1y!}9!W0EMrkqJ zb-2KWKb0^A>IRmq7gqA|xl(@=H1d2^V>1IdnJ|<{LG=J#3Q?_zA44-~{dR*68e#RZ zR!2Q~mjtN*!LL;F8)EsyS8`hW4+diX|BJSV}IXl}U%tpQ`Ocrio?#T)?#@Jy-Bl;jm4argEE1O$Nr zDcr?c6&a+4ih7~bOevw~nO@su!Q0$fwPYhW!sD8&>)|8NwvWmdgX<&8 zlZWv0hdQ4P1pcve*l&1JkDXen68Ehc5OMF(z1VDkG)WcC>ANWZ<-QDgc(&P}wgZSB z$fl-E0d@a(w6~}a*rO6mryhVyPT-`%(8$#Cm`j;Fi;Q}<&F}$3%7PZ#OP_>6n}yPeth+nL%l!c$q*R!jbSk4Xd~z64!gF+_3Dko!mgOs zcHz>G6iI%yri+E0R6W_{^tuD9j{U&*m(R;y&E=r+HBAO-IUp^dr_tNfFl#80BSsOF zqkxzR_!$NJQ`sMgj`T*Eb#Tbt>7+LtNF;DzL&Q(7eJ&?tM?T<){u`t#A|*yv&!-$@ zswUYbXA!AaU8}=gi^>+iuZtUum84-M+6#YU%`a1;H&9VYT zq?EsfC3kCUGhw{`zKl13u5KMf|5Ul=f8S(@KHK16q!s1*;?d|Fum2-MY>6lwwz)_6 z+4bcZZ&uk#qv^+HI7fj(x_CFc!xRT3x#dZbKLpmO*|+vE+y1lm)D@y&6mp z_k%V|5p{pkvkxZ6hhnb2&P6rGS>qp z(^*}~Q;%(Jpm}Eb{X`p|`Q(S~YU&kA4Y5fDamtz6CTr6x{{yOVTKg;ds8pT<>#42q z`t9*v<>6^&i^O>hN}T{|07bL&e2O#b@)sF_Qk6227;YtVp-Q2GD1=B|Ki%;H6fPN5 zlYH?u3p%=Y0qg+x7w;R{9L(W}l+&xjg(=3X&Y#_kvA=)P?BjizPQ@^ce^oMGY4QQB zAdWOT+G_qerCcs?)<^6lt{Y9t_0}-lCc-Lza^(1_*x=v&wOp{co?|aJx*U3bK!;|8OwA2AQtcS_y!;t8!hdHdjHa4 zeCheikQvteu`iNpg~v`Y^`Z=3w3O;?*U)fP%PaWJ?{R^{V%5$lxkB@4-+ksZ+;l>x z%-4%{?(`<}>EVyd>$Rf)2S-EV6`*$)?p4`dtiF1)4gXPqDx|u8(h)(P`lsw;`C7Aw z@RSIb->>9z80%E+Le=&->V0Fk-HHE0K6cLA0Xn&E)c|7nXm zLs|?XKV21H<6?^x1*8(`Bc&w7B#QirE2_Eq0J*jg$s84o;BQ;T{5Niw6ht17Nb*EN zhT))*Hy7dGh}KGsCg{^%UUpaMf{6Cjh*vpMpJbIZBCR&1`Ai+vEpiujM zl;eN2P?-Hnby$kx72r;obYH|sLtZ}z`;Ip{nKAR=nM>Uw9!sNB?E;#!DZmXu(Iw1C^O&B0wsGHvi4+Wq?WU-gH=8W>|u)Qc=l1$FurvyMBz-!sv z(PZMCMGHHD={k#dhZT9I%jmn&F)4*yyZ$__%lv%tB9c)52Q!XhnpQK7yM(--muStM zU(HVfeKS12dwtk&Scr;y-()KN19C|aQ~j)hGw5|eI5J|$i6sq-?4xv1nh_UbV4tk(;9$X0L0gl4uk} zmf7BT+!072Qg7!;_2;wyfxTwgf19NVe}2pVCsv;Zo;&YO(n?MRPMW1y@~HcZ|HlJo zn|WAmLsSEn%d^w?ce3{%i zmb(?lFvzh5@Si=i5N(Fi zp^{jPgt6L-Lq8xP!GKpVX0BQyT1qp-DIm%U4GS}zEr#R_Y;9S3Ca&WO%>)!*S<*r| z0JN&W=jM2HPU@Yi%3#~YsIbAms!L&iX2f?2f8G@vd1kt+GbhLQy_1a^NJBe+c6ciQ z9)g3XbIsV!wGq+%nGN%pq;EZWy)F?bCgGOvu%sVe@DOt?P<8WQD>CnE4_drRla>RF zFVAc5UmDebhYR_By&-HQdPw6##`ZIe9!EQk)9PhwYvXbpIa*N z2#!G6QpVTb$hEXufl#hQ@y&SR?fl!Z)O%(n9=4D6ssCI7+SsRTk!b!0qJ9=!JW^B! zr0!4|j?<_CRPn$fM6XcSc)1bRwh_0$Pylh@Pg^L>jc6UHfr`txA6IDRrK(l0jkx)s z+ZiuSQ3$4NTLi|)sc1C5;~itKFW$Rwgfsn>&Dvh9^!gG% z?Zd3|{s!8_q)b*d!`6iig%4K#5$u~?rqrxwHl{N$M_mN!DlJh2N%cJh~whn_6PGLF_c`tYxM zl46_xqPdb;W9|HUkV88%->6MQB_LIIp|YAWzpvkCLcxQTQCQvN14lw9W82=H-+{r%YaZlb8{?hHl8^_>!! z@{|uHM6=&}0qr%>H2&kP65j=ulz3W36b*t$%;9yhmftssj>_*^6|NXpy&T9HBAiUx1;fn&vq_9*7=Lcpy{wiYE5U$RGg zQ)u;{BLF(gX~BXr7L%>W+0Pl9l{VYY(&1AnbcJ zYs5QH$a&7=L)0}EZ@7Y?Oj{wrk@SI7%YB6 zYtwP^bOD6gELX^Bh~lAAOuEF$$oRWXFP?A!Ot;N|n-vaZ6R8|e>+VA@$gLX(WD!sX zH5`oN8t`$ZVt93$*e{-iB2OsP&ZuhxjOmX>1D<&~2aCg+Moj(OUOS6YBtFbavHjTV zO2PpPt#1zy)|@ z_?4*ZzYYxmQ0@7@d0(HEHt8d|flzloq>6(BiDMbzinWH122%%v@E$0KnAuD5QJIyG zDX@UsIiC}N55>dxzj4=xkm@@1^dD4sT2QL!0sIZ`FMJ!ieVmV^zC9&|FshAGKg(EGO z0XEXm%Wh|72~qM%QX#0)H9}(;35UDhPcjb}d1J(KKS0t$3=}foa6lM^#k$-=0xTSm zx#w~XB`E5upO5tFnNhvf@St$#Gywv2QF z31_yF*K+M^dGx}swk$t92^1a!?(>_b;hk6)Z1Baqy<)&HNZq6>a3!(*-{y^I7wwcj zEPfU{ZH*zl3x+h}@5&Nl6TCGB#E6&=X7^&Dogg!iK%j3L+U_RvosZ;`62p8QoN z%FuMFIvpkIWYG>@a^xoGSYMV-3h$uS6`68RGm+`$j47t$2p9u04mJKx6R~Itj)+0a zrLGm?-?lRrCt7LyDw4rwSahK89*mfVY_YF`hXk)8gk<)6uL2kQ*+9zDnjv>cjmdKA zXuZLZa@D!hb`^ZlMWrRK@-e}9bc6biYC966>@f6r3laOrA9f>z6w;3q`=2d;lwA( z$G{-Szj3K8FrVUE*riH~duoHw`3qn8?N0h{|F`r-tSxbz#Gn}P`n%te!03NYkK`L< z?^0+~GRSf%VH{6iUa5-s^|t2)V`eRr+(mmoK&#t)>wH z(7yi%G}ym56?V3Dn{#XQy>JZY(aEKC!vs&>(vKO0eA)z!a!Hz&jpr*Whw{3 zQ#sp5ZeiOe=8Lo$o(z7s;ub6AW)RiS7xTK*=$;pyId&6@R{Y%K2og1O`3Lt;Se215ma zW*nGL+K&-ldp%Fz0f?VTlwDbyH*FDcy=@c2{Vi|1pXv20b^w?m@!UuIFz8a^N&@9f z0%(TYP9=7K$r<|f1!*1klZ-1fm|y_&G6IW!j|N2TT`yq<=?R1=Ci+`7n6FypnjYu{ z=#I=<2PaU&7G-SVL$hXe-y+sh_of`GPf-3KZ;?wC;U|!ri~5LJQ2ToZwn;jD*hKk) z+K%W0u90wyLxGBG|Ae*8fFHZzG@n}C22Ia)I?!kiv&tEkDMUOSRe9fvp=h5|a|9ka zxw!?iv&U3P82h7T6<`H2s{OtQ{bj1iuDTqKv_IHQ#;Ne+EPCld#*;7qk{O>E7P-3$ zkU!^TzVY!t`)}rY0AR6cj`Eiq00(wt%syv6{J3y^gL_~ZyU67pO1tfc(5~vJi$8{d z9nkwQ!UsUw1`18`PD;?8X~+8#=+A;T|O z_t$&?R>5U(3IqWePXz1;D@IGHPuFcd+U`HSeTZ1X+By(?rlb@Bl#~cJy9jUE=b#lA zEO3zH%L9U^#r1~|d8a(rmbPPG^)Kso_@0aTo0EQ%mXGem}o zgmda0e7+|C$2%$G6Ck&_&KVQBcBF7gUrDflwvTVYqSbEm@m+pPMECN9^ePbgKwMv1 zb`;{Mhs7Tl07?2fbM4sNx%$sw_1ubM5uz$_z8M9nC4e5-F0?F|HPjoERVuE4=A>TY z;kDMG1TJYOeMQ*JT&ow;u?Da0!gu)2_yP#60|8L6unvN;10Z|B#*-&a=>^~w)~tf* zm%+5Sq^HWF3{E<4PxlhsLE4Jd{0QwZ?brd7I+6txx-ajj1yds}sy$u>_3LFh0A>O^ zwX8*UF5FGWA+`oiAilU}{YiDI)yw61ibO1(tu7wG5$7@bXLN7+!y+?n(!n!_(^_En zjA$D84Oy)E`mE}K)nR_s)a8M=a23lQBK;Nf4dV;XaLTSgH0q>kOHem}6n5!5rSt)! zD3&jnsDN!!0nBv0^G?T90Tt2@z=jC+wZWQ3l7DUlJK&3(AIu9F8CfGCDQ-JswirgF z_$0q=$!GqPP{wc7^o#}vx~E~i=}_5rLcF$qtZ^2h)>aM)l}n%89AyM6hJLzNnuKyI z&Wbs#PhX-|W|;PxyJgnk8S-jr*wGAcbl<`h)heDFtn$dAyo`5KSeHMQsD<52ZE^)R zl1Nq&3^%2oR-K2GEhh7NW(Dq-UQeyqQPek7#-Xp%91cxdSW>KD?sfglkpj76np;ge8oEE$Lo2UJT2!d z42Exic@2qISczqO^t z#ouPL`$_mXG;W|Wn*^+KWX1jb8pGBHR#b>yMA0 ztth?))F+yy7esK)QuxP7UEnxb{p&w=gP0Rg^*jby_Pbe;Up|PGKK}!VSB_h7dTW0F zvoAV)eg((kiD>=Jh%0V=PCZ%qF6HTKL|fhDak6@xugUelCeqLB4$bhffO<7i+UJg{ zndCFseC)ZM{47dgzR> zHjd_wekPDvj4AqL#5On>728=iO3E7PZ)nmg@bj&hqE56b1te$1%{(S(8CLn7JMhdf zxyAi7FCS|(YIMv_JtR0&)(bp{9cN4DcLWIGuA*9Z7ytF1ga8oA$<4WLQ0LmT=+Gk- zn{QKQ?&FZlt0J!rmNDU2Na#N`ZJmH^YEkdThIc!_(EFnvJdm3^`)SA}%GqKxZI8G^ zM-Yg#aOEYue%8qPGWR}Ugk5w1F+3O9B+rQ>)z7z3^+lbb{PWWIJePyE9>WC)d&Qb% zU*$@xNBG6{pn5B%hHaTB-Un&KCG!Q!R%ml|OXmkEkyItW1FE5oqSy0XjQChQ>qgJn zFvv9$J6UC^@zU{Q=7|QH@r1)hOqB`f8?Wil<99QGUu5p|TPpg>V8YWFT;K9H>$`r$ z0bOEFMD>`!=tPDeNH4+G`BY3x*WWEkaf*@b0L*PlaDv2oUZ}nQ%{>#E&^ww;1h&wS zd;=xAWRbsEcQNt|exUB{N83S_PvQtmwFHeHpPZHVJCfdeBPI!ZUs?$akc#`aCJTDy zkog}tsyjS+OMgncb79??6kjcLXF3GXo^E>X$%LQy9Z8KqfuXb?|Dx|f4ypb3qXOfwlHB_x{L9JHJ~_`*wqeSzhs9$Trgn~fjJZPC&z28T`G|p z4Uxp2qn+Cx>Mcgdd7S^rT>w~e5=pU0G{PT@=}7xdFY#(6Cm>FA5&6`he!y1P7dStd zz|yj-J-YU_#At-XNTXrB`j;KYk>pJxiTs8fdP8vAwL5?FwO#6_aXXiwN|907T!;V-?Ap_kZPm z4VVSm?tQMJEhV>`^z z(e5)WHSY(HPig1c@SVEiP#GE~6}mHHS&v8v3GvSlVbW(t+iQ(-?h&DRi}TSmB`4xPB`cG#ezGY2L+Ga zq6T2U%*|t;*u)xtF5HEcfr9d-Rav!n7U6U4h`F;@^sF3S^`UiGKe3QQ|M$2cQ$WY& z6doMTublXJTaub*w|JTU=$GvGxqAGv=Be$iUbII>Sl*T*IrJqi2{Jg5P0u1JtxA+& zcTX9$@9Y6*0TEOw&i(s<1|YI-1L0flF{P3+(>7^GxoIj4ToUm@NbrF0RC-Hrjd#fX zJY?dn%xaLeqf`I=K?S%nmbjv&f7i8OpcVxKD@GjGlO^l-%^5al+Gb(JuF!>{5ckVi zSOm8w6>WUF2ozTK5l17AzDg-60sJO<3m|LtEMcF!r>V&D7Ne5F5Lv4W+GpH74EY zSi)shAHG?6yZbWm$;bA3E%yN@umLl3{2;a0KRlQ1WJ_YvKcGethsnCUJBY~I{FMf> zKMr^}=}CCnKC^1AiP*yxlw?W$Ngu(nxlK)Q=M7*hV)+L7#uHgrupg-Oyj7T53(cR^ z`?vdnX;32s*Vup9BQwBe>bK4OW7Ve1Wwy| zPAv=V%jXAVSZs9uzH0yhd9BnWB1;pKqw`909kHBd^P5~nXIRtnt_q4(^)F)(>~M(kR+XV;v`RE6qMDHMHpr|Gw}vW-z2u@i%ydy zjUp%hH=)gAAi!{@3_WQ|U%7AO|qkulgp0}xQ7Q>Q&;sNLsHEP8$s z9c$!RPY^|N(?u|=;LTUk{ErqOY;fA9uG5(2Uhn6Lz_dl08^ zf_AAU3k28;6srxue>-WM`(1<<^q<@F+y8QVM!UgSdO`UENa_Wh{}kB{f@UVPz3QGr^nn#Y(a28vD2 z>ll+F^%umS%kZ-C?Ny$AfSCg_=hL5Zsi&Mr3gB8#KbS3}uo$65*`?HcV@w6skESK*V-pRIN4pPlVg zpv>z%!E-?5&tQ~#!beG)20?rU|skwE%l-X@1{yG(xm2JsU2tqTIIcF&_CnU$h%|5@#}1A!!Pgf<}MJ^=j- z@+iV6$hsd5{c@2qG}Qg1++rjJ>F~rz=jLa8hsAi)2)~|AQbRt9>r!e8UuIn#%caBS z8$@qD>o}M}j^sl9Scn3hK%j?&Ft0=diNhf!qE+H9ma!hd|xaXk2?GWoS zmqOIP?0nqLk=(kLw(uh>z8xY$kU@0s1pGN(0BLBsy8NjKgw|%!Hu8NE6+-5}U)MR+ zH7&IbPq4(-({%Xs3HMn5fbB#h*1U0piHI z7ycuE5d&64Q6UsNHZU8@4rKV^tt$h+D)b%`{o$&;fIIg!E#|x|Lc@lG?RwloU5F>L zQ^+sYc=KPsq;G)a+w}}YTWiM$PqZsOBnR+x@HOhrOfXH)zl%>|t;sPwI~FKA`YetX zpDmDX=hr+>ooPaHLV{TLO=;h3P>JWrgDADGId-y9z9q0~uG&_E(rbvMQ+UB|l#5GF z^6xybE#TZ;iNrWfGr>Jm)S9OrY0V}KtWOp1GO+?V#zIchD-#XtTRXysZ06>fIq#G1 z87S+k(Mp8+=Eey1d3tt-DUdDv7NwF*U4ROH%ID`}%H7SN8p+F=UqA&O@%D4^u9737 z*{CeGQjCDh^|lXkYpaPs&tfBL#U^00{HlmOORAf|(j-IeYeMEbwJ^O&n(8S8PtZ1^lOIJou-sGX-7j&L^S|!%4 z1Dn{tU3$webkj1E(~*-g>NfkL=y`dkV+P1ETGihe7^)dXy>ax>=>sVIZPkJXp->5Ic@D$Y!feK|&Y8}yGMT`=VIyIEB|@-RlCV=GaKwjhQ^fH| zY7LRx9rV*iDPKkkJ08CaymS1B6z|243=8Q*uIR=83xwaHqoa@CN3il24q_L3S`7d( z9yIH@QDX0rP*4!#*;^%5`ZHs=9I4x5pn@=-PM*+qoNF@~{u*drD554IF3d(cKYl@W zz2ac!_z*IbQ-+6!ch=rSI)_QYZ##}6qYNNXsdsxQj5ZI1*YZT%50j2(>uj{fBRk`W zSDq3p+``#3qt-%*@j+?P@BN=zp=*s%06JmKXtf$a70QT$3~y#gbR|ZSLJ(Jnn!|>o zUX%aaZq=IOkve%(n5f<{i;r2qQc*BiOkFEZyRPv?-3yK%Qa!Ji{od$JVVbICR}!L0 z`R-xbmi+jTtu~^-;tS4}nFVUPaz9cm^m4^4ty(M9%ab*u4+HZl1Gx1$SUWmE-XLWC z;Uy3WTf(hEZ--qddw1zU2o)&Z zhvPupv=lCSelFU|v#u>_bR92#5t59Wz};HRjjp#aw^b6JB2sZ4I}GP0v>K-Sgwwtz5jGmKun@xk z|Jn*yF5-T7wWEt$HaJUw*}WrN-y_9^iDNAwPdfT6Kgy;Zh#Jn;t@|4J2Y8Tv|Bg-3 zT+>S31wqli2yn0xN?||dm-SN9aPl)mTt7+=FlwLk$>#g+32I@_HIPLI_Q)6DoVqGb zXp{=vZWv}xblU$441!jFlObd@oX00TlEf%FzAu?ta%C3k5Fs)A{NTWhW zwu~e)=v!E$U*S@NeP^Wyn(58xkz5=89za# zD<1+;@9Pe|6DeJ{_5yhq zS@Q<5Vt@JZLFkvq$=SfC9a(DnK*!#2t@yru#2JoB;iSsh1-e(wji`sowhHeBdlg`P zMuxt)`^ixoE!8;XW2{u0Soc7ZN)H*^!104VBaJe7QV$>+Wb6BKS(`orkr2S=r zY*AFI7f5jsLSex0=U_qiRSi_|CR|l}Vj_i)4e@8!EqkrP5Y#;^{x&0-q|fnjW{_14 zdv3K3A8%oy(~L$Z`z0%XWV5d6NL_>-QsYVF9j?I+mda9 z4w4YXhOZ0OIM`?e|J0!NvIozhA@FZ9T$Qr}QQ8%yDtH13n^V*dECZNnDJ4Q2?-sXNX~`@me{hjF>RP!1xzn zjz@32{9j^0bdnv7Wu5~i6*v-m)mu(igXS;D2qQ&XJdB4E)yE5tcp`)Mr?dHfvu8w+ z*X`$Y5R61Qh#^oUkMny%4@iZ#%~l#zH@Eu>@yjCL8jG0! z6-?Oujc~w!Bq_nZsMkFElKQ8_X7lIEKiOS|yOCL@jE)cUswm0K+1ifs*a4QKMv*CX z2i6vo)lO_wo0EL0s?ADXZS%7u;#oZeb)RZJ`YC1BbWgUm*r+Nvs6weR8()BdR=#{X z%06a5m|e-khA@z;v5GDjkyug1w|+xMlg#r}4%(N$>PnIM@JaU#u0%?K=gF0 zdV5aeBmt4p$~g+15@bN9Cj(QK)5(#-cn;5XvUsY-sR>2r*tB82yxRED_4&J%w_BIC zhFe?ib&6)-L=GnRwi>y#MWGBa-B4-mTAsZE_|qEmYn7DVD{B|%BSD@lTGpAgNq~qO z?LXdnG~~U})%G(M%Jm7UOZ%6Jm|+Q zn1u8#i_h)&K8V+RUjTB$#KtvEU1k9n;iP`wfH_ehWMGS-4T2L0Ikqn5(bI_e1kbRn z!L&2evjd<*i=zXzKm;g|k4}DuO1uK^D7JL;jdM1z;2KNfqMtm^9<-%xp+MP6x@{?= zcQh&TAIW=a`vPzFNMCS@uh^(a4=cxfsM{oB;R;0z{Uf399im0}k4^QpM40f#L9*3i zPThxHoFDf=f4|_0dKn;Ri!gd^j@Na$4jJno<&^{ZCRDQd!!f#OEi^p;d zw5qhKM7S`Dtm7)4&E4b@F0mE;oik@a+$xe5oQ!UIuk&o59ZOD+Yu@xXdM$<;CB;~f zG}*m%-?ta_$o#eu_mE|^L4Byz-+mJUYC}| zS~Jqga0dL2CG}1a9{2Sn@vLcY#YJ!%>`883vvAxu;mqs9ilF)Uc+^5>E!a5w9imL! zw?lc6ax1%PS?vBVPTUq(oI`V8Xb4a#SP;}(hf5^`L;+iN!qI*EowlVrit0hpW4xMU zjInFnz6=Fg9QKH6t-q(#BmQVnZBh>)w%X9CX zm6RmAp=v2>hmG%osj#4axS5fc4`pLH5IWs4&+jO*^LIpS0|P-|EG8@B;4}g?&dc`K zUX>^1O^=g^mWLTG>|lUsZ$Vpl&9k?T$1o06*QefxEL|U1i-XmH>hi!h?K&z%Fnu6s zM2}#CB%|W-VenZ2KdwucJqrZ`&bD&BB*w(=Y zAZ%gSoQn&t+|v$(IMIYdjZzJ3@qfRLmcxY6KRjOjMH%{MRwh8m+%i!D_j#w3)SH*d)E?RU4^do84*oJ%51@8d!_T#5q z3j>kz2mcS$Y-aD^yHtRs;MY2o5}j3>RPTl|lxu8grE|L3s4oC=IRDxF1;?X*;5MJi zTb3}@OusF6O72gDrz9x)-ytDsmmNF{k;e{~<%0!><;G++{^>{5un8Z;mD>H4)XRMm zWFCL8Y`MM};TNSNP#g02F(KGRd^L%l3@JOa>WlF#S2i=>Uu*^*Df&n6seMGJhpkRT zR);pePi;f429id`Mp7<$AKfw+NqGDUk+M0!8}Qo`2nMq{3#k_Y3g$x|8}0m<_8U@) z7arNU%-*NpV|@k_IWp@z*H>@Bi$S<4_{hxs(L3J5&@JU^FCHjC|8P=78Jc7}!mxju7hycqF{tObp3A~gU%&6q%L#ZL0JO$mF)(y*Bpk?J zvti}dIjk9$49>m0I|UMs`3)0p?^Lsc1~nEMRBp^R1c(DJYR~wZfHB@If+O##BGp^X z(p_s(?$z%=(H3$433x-E1|>vG1xjf^X*L|7!Npe5J+paUEJ_a+nx$>n4}PVlM81&o zAEbWaZ9!*aWg1L!B=*9-=dsN=W5l^&xlh!%N|{Zr>MJFG=EhD|>!=7I50oWZtg1IN ziB~sPkW-nb4y&nSaSoHPrH)${%TM)Ew7(M3Rexi11=hX!yKQ@KybU+$(yg^8wnnM) z?2*wZ{P&&h_l!h-=4)eu=T&7*kxm+@_4YqpUHQ#4qU;velbQvdR#s(_)!bTXxzQj# zbhx9xE`Sj~I@Ek=%A?(MLLr*kW4slqF+qP23G_Se9dkmC8h+p%pIG4dT^X&@l&_d5 zb8`%2Kb+jGQWSIhTNZ{-whk^O(s zzLWtelB%G~3ntI&Cb8=DNe*ZZ9@SY!)`V*M6cdfejFaSo(P(6jgj+tLmYBZtAh$f^cPK7tmwu1e-+H@ zQKue9#aq8`(&;Th3OzB_sh_qTmNZq2SN4gTe^OxO&wS>`y-&dI9(`nv7NEhJk+u7F zE>eiqm)=&2*(+nyx>NA2dvI&b>|tJo7oA$%ODN?>eN`)oJ1-X+v05^u#moXuZu4vR zH1THdsyK0OI225Qg8Xmto;!LmpEj@N^|~x(BMKO!36q%hCjfrd{vLr^dWQ4H;-|&P zUG!jz-zS81G{VA`+lnuj59ThTN#PIFHAd?B%@K6c*Togqgy<2h%RLsp{(jlQb+oJu zyIUMM7FqcJswPr`0v?W6^xnGM)DK>MHWbi8(tr$q#R+L!rhsVvthYQCNZ7Tf^U9hYDsb$kL+3k%@ay(HjzQh?;a;x5=Tn=1e1=GXh#4D^+t)n=$I!i8Zxrg zgH=-MGf7=14ey z4#D&psC5ATPsT=}01VU{$Z(WH{M8;#$88fA2+Nx?$rKFlBVUBklC12J2_GQDtwRcO`&n`q4+yWr8m)N|C!g}mZ4Wg73Hge zRqGCWtU!qczIb|bo*h@ZUL7Xm*+onjmn{uy>jZ(39~Y{TO6rePFg(+5Kq`#|Kz0 zCb9F&Me#yYhL@-JP{`BA`;(g{1sOY^XubnUlvfQ!PiyMp{{~fLMpEOyMJZjgbWqzN z6e1jvpx-u%TcpeAYAvfl!kr5}^4}Jo>`aXdxPA2x?hxmmBE z=Lp^|zQzT))A#9CelPdluEa6sS^<^=p&KsTq&vJ}g0~lUoMcC%ekkzf;_{n2tcRWv<1+zW$sVAQ*!$Ok6|qkfkk;8QH%_or z{CT(!%NSq$*x7`h7GUHNId{?rBZn_G?G{6gAdpsbq?`an;LODy_l_XtBc|$V7OY*W z^217*F8K}=UofY8gvZAjmfwH(_?1;l?2!yEM{aMnvJm_@?T6(IK9y-@Iv%dn5SUQu z=6>iK-Cgl8j_28M!Tzc#RlsqFjk-DR7j zCUL3GzSP%W*m#&k-Sz3CN<(KgBNmt0D))3Ll{LyMWkR{g=PmmNxr4ZdW$)3(SH(;H zLsDRZdCNpQ=*0(nny^nb0t1TX~9gC%y$17@;TrFBSfX76+cWjYzGZ2G7~Toq|Wv{cDxpvFf%q(h zA2VIi^sy&wEh(A9G>i4I$!6N#@r3+QPS2Z5ZSmxLtLeVtk(k`YMm{rbBl387@mjN$ zA(BS;S5r+vwo+4H?dNYmOcbtG&3Ud6JVKBDbp37BFFNDLy-21BMwFB4k0}a~j0vQ~KM_LfE!XaN*#fpJaskz7mg3!(`PoH+_ERJ|e<97Z?A?`Gf!y ziUE>Jrxpw6VjN%Y0krMnj=?kE4h399Bkr$n^r!ulX`8Q`6n&uxgT~h^*;shrB<9dSG#G*E^^^Rb} zD)4$UGBi6oo6FE=vDSL?ROI7pF|XC9=UVB847g364)olgKRBQ_1JWqcM4}g`ifUNf zFOfXX+*dE@2~u32nY))ofJ`UcEX4JKBdymy&R%1dt`KTh;-=JFMI?H+mBZd!{CE&> zScU$f7l%&vTsU1HT5qBGQZ!xslO#h)GCEw44Yu%D>bg4d{fMAU2oL{E=Q z$U!O^XJoMZP8Yi>N4Tvoj~N0v?^km3CY`B2fAh=7vgI#6eI`_Cd&LeM5#OKNEUCQK zIg+nlQNMas^T7+rq^|PwA-RnA8vM@2JfSQ_Pg1Vaj5v<|A755H=X`)ZJk?A|#*rMw zkLDBY(JMaonxN!4qEq2N)Fgz+kK!n|_BL4GTRf7zlsIj;wMQs#E;(2_C64L+?p}Pg zWx|dD-ybzEZYn>9{abCje2aDc3MHV1#WTrBa#fbFk^XcgfBVs(@56fXI~SQNk+4c> zf7ic|-r;|3`*>uEi?y}XjiuFz9L3-@&9w`|?dpMAb7IbHmKu)*n4g6O!B70V>Ivqg zF=pZyTPdv;=*G!sU%5jGHg^Uj><~4PjxoHI3(5wDp2qoczgo{z9;20X7DfD&~^jw^fRP&j9A&@PMK9nd+?0Q!4h_ti0=D@1Z;JT;Q$6OCM7O=(g@?QWaL$BW`B3Qk5 zEZ|U$kn{Q8__WY4Nju>&p0olM}%Fye1_YML8WDlCL&CxBK2ggP1TZ zVN8@vWq9Z&9QvSd9B zl3@j2e#0WUtUC-tblVO;-yS&ty;z-=-o^(85Wo^R8U;@MQOVUPQoG~(W(PQ0cW28| z^$5=SD&K#@oNx1KpkAxBR{uX3d-Hgz*YABeV-lH_nPi>`ktsuz3MpicP^L}haT^-U zRK{e8BFR*UOdFw)G4q@{^-@wDfat*-}kz&b**b%OW3%S zzrHeX=hw-2;ajv|BGDUAbMFwdb2s=q*q_^&C9qkb_sdA@2+?#3iFbN0AoxrGD?4O5 z^PWZz^OO*5ybg>%>Arf#Kbeax`@G5QsP_j93+?!K?|cnoL40;~&~YKHWVH*G8w-c+ zS>JNlbI!3&3324m6!t7|7PM-`=uVu8v)L0%-C8y?))ZeXd(}$*E!V2Hz*54A=Jb>( zh9$pIBc15&KU#nVntLoXLlqZ!H~F*KN3&m6`X5C2vhH|M&W=fCmzNsz)kOR%H0FyA ziOP*HX!Kl~Z#%a#?lBhA;PbHJzzM@!N9#P(k!GT%>nlY^_~FzGG0t4KYT|;*`@inf zTe-=ycQguHEk7IJ3YOW{j6-dHBQyW_;E)v!CjUnMc?EBleK=O}o2F_h7yfMW&$^a4 z>=YRl)qws7vV~xxqZ@`^%=IX6oZn=5?+BJ(s=3$FXkSDGHiE`#U>`T12ER{tYjOuH zR`-!ou}6KJ2sD{2`bfO_%m>-vx`gQcpQjVWH3-B6pvVWqGd}rd?`Kr?r_d_reX9%q zVgGbz@ihlU3hxmABs9$UgAGk8Das%?_2wp7a07mmfyzb4qte785xP|{1@|5PSJg%sf{m1)=mOJEr%56z| zKjpewgYD|ujg94!Q?=Q~>Y9e{N?BUgeC%vnsJys9KdQbGXQ$%T-}XCE|$2nI|C^6@bPrMF%;Ieb@UZXD`t7DYdh8~vi{fRWg= zBrOt%TIdj#hlI!aunCvGvS>nqr_~*LF^;!oFscyY{Ab z!JYyZ6Z#30ygIhIu_ifG^Wrg6{)3v0!kRpap=18X45sCeD`|3ADxn-{6rx+6tv+G@ zno_nR@=|CzBLAEj5Sbo{qGdlr{cJ3Rx&|*tJwY+56kS*(Tc9&3Q4n&g9EOr-euPg^ zT^dTE=A(AXCD^$NdWZx6r*q6K$_1(`7QRQSdU3-VLdO_`tsT0vNY0^Eqfw(h2f;Gb zj-c-+`S7%+kNCh>`_kd_mI18S>W?O4@!`zD0-$0>!nG8#RDKA?J)J`R5Oi?zWOS@@ z4K+yXH@2*AAp4RqVr)0hLmozmJ#}zhP5)d}t!wzi@;z$S6oSjzkJ|;;d2-j@Raw}O z=3YN?w!l~6O|79WL4*4OZ!`x<#q>{(c3~q`rE!I{ecAKpK9LXwcx&frGWN}Kkhm2& zute-F@2S;)t@}Qj`#rrg|8U~E#WBtl8`fj7*6S-gDt9glOuehxIz@_O7XPZO1xtA$ z&(E>zY~hDV(`p}^E5Z+&XGDS)I(DSk2^|^lW*cl6+)-%ePWGGGPWjcg|LMJ<*Ywmb z@%#3-R<^EICm&6Z-*VA3?h&$_W$AonsAfP9w_F9iizs5tpa{sP$EgJHa1f$wKHyE3 zMWu^YC+Y&>)Lh>@&;VvC3#VPi@4`5`msyA3xUjOzQgpaQ^uPyoVRCN(I~F?MpOwI_ zxAY>ZCPb%nKbNw*ra5D4Ip z9H)4>^AzS>imSG+gQNjn&(}NH`$aiMEG@J#_myk}Rqr)iwIH;#zm4~bPC7lE zW&WTxeOa0dT6xC@FJMQ>a?ywTUICut?Jl!Sbk1&_psPzee;W~^0N465NYa#Ei;J99 z-kpq#i|d5td8gsCT@m$T{eSa1RGrWGV$0E)lz+x~sPP|Ie;=_R@9?h2*)vm!Es zWWkE7#Gd0)vp>sJ_Mu!o6YXMi;w19qS(ZI!^jh`g=ZHq|JL}V5o^bDeyX(blG0>JE zG+T`Jh9MT>K5IXTbAPa80q@paVqIFWHX1r8%#W45F#pWvD8eh}V zXtQzR-jEQ#nMQig?2NNT1hxcxwpR?SWT}$}c&9d?%Hi?Cph#r>5vd4!dnfsJlN4j8 zg%Drdxd7q=-k3tkeEv9AhDknDvQt~uTSpL?6TZx=ir%7v#yfWki@HEX`|od_Ou9p% zL>0t~n-j+!{nx>v?$NQB$f8h;MeNV@k$OV(w32*qU7+7B?a8bl6F_<%+A=V6D2y;L zD`;R+45flQ`m@q)R+vaThAWc?+nyklbTD|DAXA`JgMUT8QxojIv>P=4$lL0+o(`-uRJFC0UcYiB5oPMYgtl5x=j@nS zbUON>BrpO>^#KHEkEF&&JpyqqAox=RK#T~5M$6c4W|$qrlce~~AtX76ZY_~X97 z(p78qkvf>rpJe|BrUkb6OT)2p8IW8 z5?SlB)7DSxgC(G=>}P zcR`Thl-LE1DPAY$E7mds1gE6Vq)cfKI*>=Ll16a0rxwe~R9=0wBvyz2A<)PC#n?$iI1nI`RpO=xsvIe#& zuy&=uc~DI3m7zn56Z~h^2V|1+h)}V(3M0nER zpjdmS^7x@bcUZ})^^=pLrdsrtT1T|zzADmrKabs{yDo3%e{rHp;7Uu$Z@Z((^Y5ex z3JJDW(^7|&JJX6Y_NK<=68+X@Qr3l!8C)fmE)qg@tSorIqF~#SaZ;ENh3fuONeNO6 zxW%^%Jr)QUCYTWHDl|I}4Yz7X^{TyH)z#I#H}dFbckUh*qYnd%k2tD2{SB7KaL=#q z9X+VAonE; zupB(kGQ(eHIjThVldQ`7gDToURUU=g^3~>RkZYbT_;H(b*LCHA*Qn6;6%!)cPsU^C zXKy=h5ZLyYG8oN?T%~>fn0nxjDBaA(&XCFV2Q|MNFJg5%E%W_!?(XB#`8K`*ppFT@ zg=v=g{7lY_$)O{oID;z0nNi_v3I@;4;-Sqi6I@rwFBYJIWLel6!VN#Mn{VR-zuB>z z_Z0r*u{h&tS&HU2c$ZurZ27_XN=#9s@Imuw7e`@yGocG1dQ2&TURoEfwHA?-I)Mev z3o=6FDw9Q~#0cPh!2l)NHPX;6O5*AV3C$mqIF@8@=C1$zn!T^HL@ePGM(k25$r;7{ z%A<^F@|)s$I~?s-~n-4-{7@{JBf(FbSl}{3)&EyE?g&@{u1u4?I zbbNZf#PGp+r*BNgXYI~|hY#nc@aG*M>EMU@OGqya(7Uonx~|XXNZegtUq8HVD2b+v z7t`=UxSZAF_^aK@%+b4Mvs$30MRy0)YjBiW+n-68EjDKG@P4W(pItm zc#*8-a^J>b8KEF0_Luq9RZ-tXnvkBx{t>3aS}b4r{fne`)@+|LOGPO`kI;61Z@YG)gK!BQgL0WtP1*DRG=H29Hl?!-hXwn zNLJ_aUpX@8J^IO9|B#RnjId=n*e6_YDD2Ms6yyPk+xQb#x(+F0eV)C%WZ7cnK^(zb)i=Uk-Yv~}V}@heRLWQ8-t`5I!Ao~94PH9; zHR{f=&?yTG+iG57rDu}ng-ywMY|?kC$Il6wA8*I}C{vm1Tx@2WLlp}7O59gKD^Vzb zRO-87D|&Hgr@7bb?Uz;rP~HrlYZ{*0*QT=c8i8xmygVRx@ z#6^Eup86eOVN1TC%|_;( zGVkOl5Eb|!snj_0V*5t9zV$oD2W1cXHn==D@oz#aV=9%$qxgP~INT(XqLQ{X{T_FK z0bOpH{KJj)EJC3 z)_$Y$5p9X~!%W=3FABZH!bB{7P8cxIO>(e184}NYlzr?Ra#;k>(zv7&4bel ztg;bmLz=_Ja-nE7TskG0_+hELxWwLYN6?}&^p6Z%aY;zQShCkTT%A$HNtpP$uAv`2 z!P8_$Lm5n$3kmx_*NV1FYh~)B(pryD4}8iAVyW?;M_u8tSdJc0v-DuFBD1ubGPx|`@lI% zmgz`PV*OtdNQa)LQ;>}XACtZ>atf1e%gS?%Y;k8e`PXl7~-`fUBaMM+w7n`ZKxn(V`VvZM2Ki&u}_Q{kJEl*-&e69t%c z*LyEr*Ev6|k}PbQE@%DPM$MfqnvF=Rz()~(u(!e-_<^U1<%nsv{ zbq~K>PwCCY8fkI;Y~u)HqiNaLPWo@f+j7bThddbvTAa9McS940@$xu)s&U$hY8z3! znfw1w#asFRu6SDv&aCk4lYC=P!#E>q&Sq0!t|-6w?x&5zjhAC<45l$^q+x^ynL%yX z0S*}+i3o&Avb+h2qd~$`$RGHrGYHZ6)uZGmMc*mkYmm9y#Yw@gFv#8gh>9Zyi*->v zI*~bA_3_nu_ngvB)OeS{nNmRL45< z?lxr?uhn{CBfk-UkNuCWB@_Nz=VaFy$UZ~G+h_gh(@J#$6NEc7XyK}dTU_NjbPLGl zF(hrO2mj0u`tXbJL*QSz3Cj|P;EgvyV^v;@0#KwQU`+nd!zgSN1e%%Q&+7x1Klikp z{CCP>Vfy5K4*%qN5G=@yU3P=3DlQt8{rm? znrV>R)37EJ1(O`NUQFkfnDMDJNjBbI6G;wyUj?pl{6^Yd9)gnZpSBm!c2RnZN84~cKZ|-8 zKG7agRu^0sd-Gk$is1ouc5I2E_(5etEAf1T(_YZDZv7)E!+JA<=WR~6&3+A@g#1VJL1=f*7}~tSK-T?Wlqp_>ChP}~YO%B170dm< z#o-X+ZFdq+bQE!IEQjW949sRYg-Q!0SxxB7VuRjW#q*M%F+^_XfoBN;@Z3m24teiS zg;cO6dDnSbJ_#8Xs@M2#Dnw*M0`3j-fH%QzeKOSm&ujrS%afl1w#7&@`H$)EoMrGK8T+#nO2 z?vkNxKBmNb^+#A(Sl7dAqfWxRe<={QM%_AZ!vS8s#)lm+E1PEVGE_{Fm*CwRdI8)* zqWNS|r>OQV5SWA$9+07Hc;f#hFLA%%J!|lnzQoj~C0#?MaCENwHMeai&VcCqE@i6v zyaV~?1PXz)%*V_Br7a1^SADhTRtIf~kh8!Sd~crimltx{@h|%X<3D$5p3wY?w|T73 z7aN+=CSt7kQ1GThCTfM z;QkOzc5{}s(Me6>^W~@u&wTrI&+wm8c2>@;tMhHTt}vD(VBhDI8CffLSj&1gld3tI zDI6QD)|IbwZfkicy!b=`a;;@?arPqL|r(?RX26 z9bcU}9S2`j`cB(Q8ET9;6+If%pb_z7rS8y^KF3Y&2ooU4C&;tT6`#5B?`OqQk^CKk z*&Jh7p780gvnu(Yy7gZDo4dq1Xj0VY=?ECRuO^a^+rph+OWI{qX*?iSxLFXLJ8%b_l zx8$$lyE~+JzQoahHH5~q-B|0S)-|UbNq-@M{D)B~lEF+3y*bx<7QdNQ8{ZPINcU-L zpJI%*Uyx1@-14CpGN)~cWosI})vKE`YCZh+v<$Aw|EsFIBS&SD*Q0<3g<@N44}U`d zjdLe|Lse)~E5>j=FW#rN{>;^X-u0hXjyX<_wGO**;esWjxCxZwB%DXj#oE>e?#qXS zhPr}?N>QgXT~Pu^G^0Q7{5!n!e`O&O%B1i0^i+^|f8^%dKFk-Lmg%LByY_K=KqCQg zAuOsLSB8CNPF(o!x;Z?pnq|EzDA%RU7dGW3ZCZaqL=Sr0@7C>E%iI05nCc#&H+2U6%QwUOVXUGRZlzoXfP6M_&XE%NFA6kT4N;{cG z4XH@@^)QN=M?rU}+>Gf5TS|Cj8tcoT5`6RGe)BH#!J4maWM{)?!(1-xfMILfr>r0p zut6-D$1^3YW#vk-N@6X?(6NF>X4%)n%Cm4TrFN)xzM}4vpmPx>mLFDwjZr}|VQRlGkmo(@c%D?uL~oNBs7 zf&UhIlse)mdy&tHI&1b5ng2VKg~~N4zQ%3##PB1T2I$(b+MiM6H!U@~Zf5m9hJR8Y zDO24Dyk&~8IRyZ*Ei!`MiIJZ{{R?BiEcaQTc?lnf-Dx*stwjiM2`-@kHBp<{QtT#$ z9msxY#UzX!7>U^RR6_WZ06&t}g{+_egd;P-`I#|%-Je}nP816R%BsnGdc?+W=AT>va&dE;E*=L&2ZkFyp6{6q3Z%R3IQhAg z_MrAxhEp1{G2d%)ipeW!zBe};Dn*}&M0mFrg>0z7O{ zeQ#Y)nte@`6&o&ha_}*qzl(zJ3;h(^41(R^gqL#RxhEPXgTrbPsqi&48JTWL z?5#=^MPK}^i-0lSr0da%}0Uz3Y{{yNmoNij&Hm`XgA{e<R+eV@aRx%a01v`ZmER|zI6?C!zOxdpuf zo=R-tSLv~}@SSUl@<7KFM!2O1j~vjUdYb01YX^~U+Dxt$W50`#*$}s1~fFrM7p{bl{9s7KOtmkhd_r?BiJWy5mbjI-g zyfD^q67{|^*@k<~E~xGwEkIV#V`P)+sxTo4uNJs^-O{0!_!5VWr!t?}FLkB#pE zXRKF|GYrB;)XE3A>~R^c-EcZScT$h#(XUlcD=-$pbppTa%(eu`&%6Rw?E(GMS>$|X zz}8#r%;hWjQ#k)?p(g}f7W+krNl1ckVGydFSjtP$37R0>Mmq5}#DHbXMY8&U#ieRXna61i`eu0j&2zr66?W;$sJQfX>e6B=B>nQCI z6A%y>Cqcc~{>xY$8f`|8>UbeHJi}$z@#2((74gDA5eLyhvuq2DkNFu?M_fy#xDl5g znO^_kF{CiPCBtP%xA=c{!a`>HV@~h`k_juqZQu~=7RQh9H=4-dd4hfa4&Lfqdmj)v z$syM3GvCyJ-&HhtbfgrNLdQBB-Up_g^at~}u3R0CSZl4QV-)y+-z69K43;)_iay6Iv% zHCHw}jN?x@P`=fHR#z-1Q3%8W24J+>N1w>Tc7$EQTUTu8wf0G;D(slo1ef2|Z}~{s zbLUP$?;QC4qJ4HrodE0xpnq&4SF%x{u|{@|?~JK2N{4p)~KA>)L0D(Tank?`O$W zHlKTZ_nqQ5st6lN>fS0y75_aJJXqs)zUS4|(Cb__T`S+bN?iBt{m1cO;Jw z_Ffcv0HS62oLhg@q+c#^8sVbM>&mb^mnTU^o0O9yLcq)+@xq4n!Y^Ij3xUdxf0j z+kwfy8O?xU0iu4V;m{z{O0!z`zx#{hTLSGL)O4|3Xu3R!E6FC8)KM*&e9C;J^F)V z8@A}*Km~u1AOwae2+I9{V!Tjt<-)z}eIi9vXWIGPT;E>_hM0!?9k=RiDXZ)bKM|pK z^z<80gs5dXadGNSrM-7sv(mEpU?k7PdnGvt=m7g8D=&814vvAyXrMR$d-^m4)OFJ{ zf_j`Ke^R6m=CSFOZ!M_OOwwA~rc^$g|5oz8K6Lu0+IB~$<1i9ykwr3mi2;Yi$=MGBaa?MT_}BZ3^q`8r z96@)mR<=LnDN<~|LmQQfb)qmiUPO{2%$vn9ICiJxS$y>|z%e@;HY@*zg_bNNQ1{Q} z;$f*@$+?>9o)eXeG;D(azOPq2HAz;Xd2!&*{&VTy>HCX$jFL)k32Q}hwzKPSq0RO_ z8B`}&5sLH1Zl{xP)wLU;E*>m49Z$^FE}DE(ayv}v%bkNnex{JJ)(|e=MeGeJ%1cQF zVz)e_#F@Zm+{6V0CDY>Sn*I@&;O{r^w8B3k87qb(HrEXl6GOz2N_3Sv<2WMt1{PMN-NomZ1n=X3KlK9|a z-y=DTEg_lVbgH3q+#NgRL+mrqMi4Oeh5r_D@*&9aFg;?2LEIP z04Os(?cG15``>UsE{vRlL&%-G`nb8y;dxW zCg$92F?3K01E;>)Weeemtxz5#|VSrzi1;3bqADgqZe!z-#`=cNh_m z5A^i(#I^(YdtIk!Z9wfvj>;Tf^4F;922m4A?y2`)$o z^*d<c?sz_F)b0RE^j9zT{ zR&f04bW1jrV_kjsFB)pUNAGX%y7Jurs{ww|1$12tmj^HPK(_Yui*O_)WdM3mK}wN- zQ;#i`zXxkct}fhEdy;91uhK6~wIaDg`#) zIXHkjLU8&c@7BslDARi4)GBkCnYj*98hQus60M{dj-Y%615Af(Iy>qbFEz>24}{@{ z%1w-K`-&_$;2P^GIqNt`4OrOiyr}IyR7R))fnO5;>#aJsEg2F4z6&sg1byLpqNN5w zEF5;0ptv3z*PBD?(vG87M$Y56MsAwXM<3KY%jvi{ZTqCjdMK)Zkica+M`Sa#517$R zsSpkk{S%RiD3wPPOdd~${%7}+lnvp3buSeztT9QtRcK^C_l?fY2w-oDNcy~LttsKv ze>PrVJGuO=ICjAMh+)3DcKuAQwORg^p*2@y>k8HvaCJN8z>}x4g+1VgcYO)+n~7I_ zCI(2h?C_6Dle5AGaY2GU+j~wfrRIgU`_HF5I}i5vwydA|qO zDX}#2b=Z7rdCYHE^W(k9e($`2#V_#!AExhsvDW{Kj-34(DoHM0H~1lz^xJZI^y0we z{!7$+)HpOe{8t~($a`0(np~VQ*zxH3u}wPjOJ1WdE`vDb6re!+0>LolNY-a^I|UIj zjo!>O`RI%T!^;iq-`Y*B45jz><$W{P`ioLVY*U>7b(R|ocTm%!=#7d zh4B7=>|+to2>x!L?Nw8IE4a=)=>{)|jS0}#A%jp(OZ+TI{z{kxn1TmSd9*_;h9LdQ znR+F(gve7MqY?4jznC$yJXBYB_x5X)JI=u-N_m?G2X18Q0H3rMT&)0 zNU_kF@AT@Qq7ed4F8xYuLXs>ElICcZ#}GXi^+2ttytOh>^dYF=tj_zuZ}>}3_N!16 zN-%?v42C(V7Z{g;r1cI6*@=*(d$r-X*qknavv9~dxP*l%eBRDO zK4<|*xAtM(z#)$4a5TE~)B7Gt+x7=QtTheYltdT2;SacubinBM+-oyOc!5U<7>=L* z(|{A?@?^a3!9z!Y!cD-DiX2mGBQw^#b3sWVluj%9Y+|#+m8FeyNRM5*Pcs4fR>d-SYl3+AF=<{&y+w0|qMzqakTx~0ArOya;{LDJV8pyz zJ9M(EtBW7|5hxXJ@SHtc!Q;OCJ?~k0yo-5gW}*QN%%K*Q_ga1zjOxv~s#kg6hVs=t zh7y}L#ghY3X30}*_|y0;u_*r3BsgZE#J70?LY7ICR1z7XO|d?3k}16Z2B3tE_d z@^{8%m-o7#mjmCC#=~L(5-XVqMv(|;RpOR?%PqE0QKM;lxcpgH`hcCbac=-)L8@i6 z3qy;npv_@!=tC~)1f&FBmITFn>Ao7^js8}4tB;}(P@)3jrX0Vq8_Q~V+BMHs*f@C%FswJOY zIsF$Zq}C7iTpGUJ9L2PIEX2Y#s;8W@5E){Wma?#PF`r0P0u^$Z2z@WQ*l*jJZLKfg zP#X6-x&aJ{-`y5>;(#o6hCk#aTRZc}QKBfhPB4BB1}-t=NZJ+!9HNFG0wQdWw%ALk zT7Xlafvlaa|tby??_!6>@_hrfR5P4ZjaUn$DP+ zoBQTc{Xp8>7C~c5yU-I7l#;(H9dg&Uz&D=>r;Q#@JMXn{@0j7O-=Z+P_#BAR=sPD~ zs--++9pWo*x3Hb;SxNeanJ9A@u;;MUnG%~lqcEeOpL3kpRur9CS z6i|L7%Wuh^9fUqDPtqVn;w5zx|%_zVxb#C@zs6o77JY2Pd2$Ij?QzTWU9S(K)SS-dQm|;tm5lIx1#a z=Xa4E0T7#vA!eOiP}(5LnHA#_iyW5lOXW;vq*Z8vLaDhQ5uXR$$We!g^=~xyAaRJR zMly-&PD4*V@>lNg!E-i*RJO$aBdd6MHEz6QOiV7@Me!4%|oSV+$@l8?3-q@{Lm->lnavnTsoiinfU1K>GZtpx68jzlP&6cDH{W^&(lK5QLo+#%Kl0IV z#9Qt24Z|6vWMqM$%mF^mMFccRv{vJlIYGCa@jQxQwq)lX;%u8CsMqP0(im=Z`BW3Bv06R zib(|@E4t-g1i{f8<}K>I(dDY4V$9FxY01;i-PkFqV9S^_v^e`WTy>I?GDgmB7-22Q zcZ$UNlFE>cQG%@XAbA@e;WQjbem3{^w{X`Z9HcP0xI;Wi`(QGI_MwqZD%+%30rlN& zPLX*y390VJZI_XMfz-5y_x#Vu>w)SuQ(8de@=_1{$*(hKP9PjPqT3EQT_udLfb9G( zb6s3%uB}$L9seO-lWE{oJpp3^BVY^J(}@3wSCG<15=p{5a_kIX6PNY5YKbHJ;yZkC z)xOCF>AJ-}A`}+?L$~D3$@+oZ>y=K%_)=Z~)Im9v3->)D8H92~=w9)p!6$fj&EXcp zk%4R;W8s$(tIh`>Cmn$TQu}vGVNGzA@VEByM|k}8I3EgPtgLyo6W!_Apd@+~0ZDJxPK$4tAYx zehK3=e5wA8D#q@CGFtE3A>t2lx%=i}-J?54!Ab;49`4Is8bX?1J|pP0QWREzQ$vVT zHeFyBXR}@?hAc64qXa5cV!O7dJ^ z{z;I9O!rqyei{EGZ8BjCN6HxgagPVbLltr&-fQN)HGJ~F85%8KZd`})y-QFf| zoPT%Mt3<*s_(GpCe}!{jp_J z7O==m;pfHaxiT7a_Fix14K1b(zjZT5(>i936X>H8?M6Xa7wX@bmY;fF=1*&JH5~8v zwY1qI-)c6d;MCclMAf+asFv-+gFO`SFZ3xA!sB3ur|8^*EO8aGrVdF3TC8w>{^lq+ z$zLguKyylTW+rFAvt}76KZ09LHi#n!-`hlzHmsI)b?LTeD02+ab;%g=Fj4sciQ~; z`G2vLbjZ|y+;8;BTgm?W+elKKvudCmFR>nB^xyubPI<-f-NYl9TB^0pp)lzY#kO9u zJo3iX?M{3AF-->XbV*m%p4`qLkJK$rs81&q6@?x>-Bsbt@al2`^KCJAP2CdObAi9# zgtR}?6|Q(iijkTX)BHBPshf9&`T)0o=rTD-(x)uxvl^=$s0s4JzT8)mFRc>nlV$e& zG$~AE4})f+?f((rRkEf+M)?~#lYbS@{>5)0G5u7h`H8kC+(&b+q=dl6bLvySL>_q+>G5mDO53gb zL9;ke*zko$ty|ybu)lBw^Q$dW+sIEi`8-{=az>aZ+kxM{9ivOOe8Q&x2S#DTu1fX> z3p5EBi%~3o{H^A)`gFI_Mw{_R<qf2T?)Q3i63?-LU2Y4%)2QZxZD3O#XQs( z)ciNq?1<2EhfumZ`(grYqqKd`7}zlhP(=Tu1+Zwe5cu@mh)-x8L8JL_;ZUl;_H*56 zzj^eCH1l8m-@ludL-|&<(*5VgcbMAK6e)XWg)c1mQf6xfOeL-Jv%S!<8BfGKDxle| zlx$jG6#mi2;+1t*VkN*g>{eB2;Vu|2?l%{@<^M~Mi)b9}((PlmFZzdcnEB2Xf)hpa z+UrPc)9010(hDB`bqksb23)kvQj6PN_50`C@m3UyrZwfS>i8`Y-OBJ3{TWi^>P{iN zKRqusZ*v>@;yoecLtgZJ*0z+2TUWSUevej4LCW$7GTSMjADVzC-|Q7TeNs>;b^`Z2 zZ3+d2b4-ZG5X7ny66;k=fRxlW{GB%j18hsWWv-u+O2I#!P>n$ z%m<>-9@7F7OZ1a|BzF7>qTVKmVzkb@+Va+;4e}UfmPd1;S7uP*Pq~cpg->ODJfS1q z`1Y4}vEveByoez|_idMr1C2GCrVLrskI@9J^KbuA1*;eQU#o&0j^b^F$4xD_& z)14~d71B0YO|th1!6>p!xAOiS8LA871*fw{l+Jb1u^oU*bK=Q%EDz@OiiC)CAbwS| z8a&;74+fco@c{eJ;%yADFotL9iRd`{AJJB;KP=>A5kd?9kr`K}o<+URoPB4s$Aa54 zY7)c+{-ToDJ>^GYcWBCpm<`gtw~gLucKF9^kPh?>1M5rUWoAR7{xM*h6|`9LOH7v< zwZRc3vvjadTmI?g`fNw0W4H>v7!9q%g>qSQKN@{r|EZw57u$JV7sCdtSdJ#FtccBa z=B<*@*K)Z^klRX(p_m-KlE=y2_Hd_`=DM-d|DD!3N%*g8+BWb@Q8_3k_or<+j8Z z8n@#OS9NW;Tp1e21CCoO?~~DJb_9RAL`U*86j{zjfmU_|^*ced_#~1Bn-?fm!7fON zkV&NSpWGK1H-+d|&-J_l6N`7HMwWVIMYX$^8y$VO-&31xgrHXIEq0ehjZ3vmq+OJJ zi4uhjuieBQG}_?yx-~h1sR+${w?s|KDPom&-}EEnl0RWs%IuJ-WaY_|hbiGsT3S(_|r(C=j8~7h^r4V@DGw zB`CO$Z{+<7xcToqcRF71v>N|g zI<2_Y%XOp3hueyA*cZn=JBk*@Vkf#N>!y;>C5&wq}dNLN>#sU z5caUcT!=>KD_eyOr3$7afz&4w(@m6;QYGBnY~}3O?ZiRbihr%CFl*VCDqB?k%rd(J zDBdP$sDGH75omle!{mc)^rJo?+}!B>tyu}t+2#>z%)eJ-bFLte(;SFg)SX9*VS3ix z67M3_ZW8wJZoYj9ih#h;KovB4Gvc-Pr>pwk-;Su9448H(yBA8jQC}g!O{3%zw$(NE zKT0CGP5)IAQTiIQWV{gK)S)r@VtTqRO$xnp2m^1jss$IycUma#;?$-5&-uPEPtq`% zU*B^aJdU#;&Gp{gBp80G3N=empyEkI^wRldC!n%R+Q)EBURHVNUoH^j-PCGuxA;9TMBHNfI=3 zz>Cwj^XEuExc8WfqaRGRY1((dJSzku?mUv(>r0}iD+piDz5S1!_HnW(O@Z?uqh>uQ zHtX&oE|y)jh~VDK?U)UqDuc+#Pyb?|_a`8El@~@%eme8UJPdN7j%V~;sW~pF_3T8C z18xO{LyiBe__-yTG`c({6^IM^`g^(EYle4dMQQH}#ksjBbsCXLpP_=F_c4$=VSEav z_ng|Bc1fu78vafF9rgVzUeMQ=gnV+BazZ79_*lHIjk-$-?Q5*b94~H%=cbQ4%lE=} z8pF%#+#(GhO?NJ9Ev!&oBsTbo?!0llh(-52yZHTzOEvZj%q!I+1UttWn=R1k z4Ot}h_S~{LZ;KP^YCfTZG`Q+3ytYLH)8&t%&Z3wC$7ERs>JMtFT(+0lge|HlU$@1( zeY$!-h+15T;7Oe=8`HfcYHC7PRk*#Ti9eXClaU3VgW9u4NR{b+B)CjzBv~s@q?fb#HLT{I?O-6 z+Vt2ld3pV26szK~(Av3d_2tmL?I(3ATq5M<=rgNr&bk%XQqP{KztDTr_hE7IELnTX zamv)QEt-nHjT49H)UV@pXsT?@6O9qCBV7;hw?sIw)^|FdlJK0ZAARj7#`D}vBvrPs zv8&!<^2GUD33ZNY=S65!x?435a7X8R?a1mjzN{Rbu0qwS zd~%=f+s5_B(Q{3T5UU^fwrO2feh>s}p{hbgM!q8q@A2?CD>p35Ki{5?&gJ5PlIp422DzoW7Oj-iBnKk}sh2-sHb|xHIzC4*2sQW# zKB?nncR%@@cWr>=?)@SX+JE>Wi>R0Ax27I|Hze^NIto!-L&Z^)F7b8Xj-5q~vm&&@#jE%esxoJKWn3bS`tQm4 z=S~YgJ##4pIPa<140O!(gS86Taqp7UkB+z*#onggHA5M*&GgDMiZp}f1JMzRse?dJvvQ2LzC69XcAaA1vGmS4*kMnIWs0^ z>!oQApT$YM}-0#&$JYzf# zU%bG8wzm7#B|7n=#ZIg1>y1$K>f27~uYZF7wW=Azdf~}wjVM_a`{&Q$JLprzp1p>g z+B2MMvL|l0y@rJjbAxA^X00^Ug_kEqL%rjW(;Zh1?~$5?I9<{25v0PFz^e zH&PZ$fMzfZJPvyBNLc$ZrH!?8XCMRK1)2%X(UaOjOrb zmsZFRlI^fXKYHq?q!>JmY%nG>tYM~NoZy-oz{J^b{j->vwks+|F*JwF%{RHO$-!m) z(DUM?mal-Gmss$i=T&fiFfWh6@6da;BLR!)cqXBXd>tBzjOLXU4MK0ne;I&GN0UZB zT!j;xr=co(RbB|6!-L|#YB=(8;Jws{{_`3#I2R(|f!jne}ILyg9gpg(^ZC^qaJ;^*802&e)`A9`dj~LG0>Nh(FKorxwUW~v6sHi)e0UQ++i5~ zlzx$c;F}*_s!rgd|27FnB>&tF@?W>RkKk}aTeoHOjMn!W`%tN3W!VFvG1cv)NiZ+q z9$@h}fXT5=uM{0Se2w5pFHdtbQz{Dy31Lm=hFFI zux?!cDnzg>X}$jY2skQ+97mUd`L{-<#9uhL;BaL~M}jk?KZ)_adRmYF^E<_%#64;21L1hk16VX~ic#j7+LY z1iqdJ9T|o?@r*nVpF1ps0tQ0ar8(iRFUmiNOC4J;qvNNR%^&2nTlY@kDkXFiQPt7N z$P^B1s24Oo<^SHQitYY;0@K|8N-p0T;?elcxNbk_XWJpxzQe`Y#=wKAGA%+yLOS`# z=MK->tjLb+_hv#E+} zx)D%_P%KLA>`gRoKBiw`$0*uBr-C}9wL@e~h%W%gEDjWWH8f?I^kL)nM;8$hHn|%D zipfS?;+1mPMBU+*%dg_UUXLH1ROnrIdh;N4=T4#r^kDh$-QoM#-t3|P z#b^~~t=y?HgBCx3CPFS#8A6iV8YIpts9oW^8fJ2(_!!B!8RBmVL1Nbf;U)SEM+Cji zi0Kh+VEweofW68cbv)!x`k%XZ#Rlv&%$37zf}+tyna&VgMhu@Xt`O>Jh8O2_;=%gW zFS^2L<}I|8c(%AqVnBN!XsPc`b|jnGu^%(LYO&(?BbgfyT;}l%=Gq`8fkoEGk(maPnRQW9k3<^c}DK2-YhNN7jOeg^0?Ev ziS~^POSGmp!HrKR1!tQvyb#3s|0PoVE(!mToIoUh9pAE*R?FU_C zJLrP|khTV}dSH+4C+ddN19QWR#TEvRuoW_3seF2P#1?Vm+cg+JVgkEzq<#B2yj{)K zqK4_u3BG2Rg>Mus!noL3>+{S;zQgP5q$Fu!chTqN%Rvc78>L?e>b_*N8b6X~fYCiH zZ;vZE3AX(-A9j$aTb^4GfY!HQw?_m-l5<$rAUyXR44UycYmrSfHNWPZYJV9eMLrz; zq`R6?Y?Md7byKbFKVmkA9dP|U$Ug;n@+vX={Ia&pLSresCu_m8@LQBdz!zj6110^6C6>z%AgTOLhS?h@e<`KU#LpTH2?oF!SRNDsz$dloC6RDurGx5a`%)RvMcpx7!Rp z@2H+OHY=Shxt=$uekHZVO{gHKUYf)auL-=2wPC${<&S3tm&5g{t3JPX{h2f}7_2;}K%`qb>l z_U5;aa+7xj6XSj_)M5`NRfOx7OctvzoT{%_vBPHjEalp|iR9X$b_WYru{U3G%L>r1 z4rUd1*Ht|X%%qq+6WM}1SitErgRj9us z0%B-nAS#J~67v~Tgp#phe0x;64V+Whg~KdYz|QXV;|8rqlk6`>lCBF_HU<+^9H`%- z=DL#G`u^gn(N~GNQ?f+gD1TT{p4`rLnIwlclawswj9pnQXm$}F@7d{&=YF6}^!t6t zFXFe$fUJ3COYVDo-ugDpaU(id%I5 z`oMLn1GX(MGqC1`Seq9H;FJ}9UMVI5aVow^{=EEv^Qc>Jvv=~r)Mgr(*_7x&!HtU9 zV#9XHtfclItZb5KXTTW8Knv9r*~$g`$a2~@@O7s4)na$NhH0I=8PflfoBHxv;x?ZR zbVkFde9`-9isX&{RQdd4ZBzf?hE9b@>%}DhaUqwAx)LLQ2e;Z@rT_Eswg(#$D7NlEJQQ>8t1tGWsnQS$1fIp-@4VeT zd;KpR;+&6ieMZDo;(8;`+i&FtVft8hro{g`M+pBKFQX%*{TT_0F!DU+V}8wUpD3*$ zTE(UZa}6Wwc>|8$Bo{F=#sgTj#56BhC>-;YiI5CJn9c>PfbZ{<=QR@q)|tl(3sTE3dp)XQwQn1(zN`5qZKJ3N9ph= zj8v1~71V54CSZ1F$n0FzKBL34z3|O{-WCJ+Ii3H!@BsMwKh7q0`pEwI-cHPs&)vsPSP^}){$5Z@bRJC*jYE=fws>p8eJ#bip$0)HUWZmyhW{s?-#YZS0Chhx_8 z1Zm(O+%#i1-IWnn5TDB!n&o<&hnT+xrOQNru-^LqWsM&^}u+1 z?T|oz^bVIB^4*O9EgGueS?D-{AAK@C`#%NlehbYYa95pxH%+oc%Q=5{M}FF@yNB;v zzF9XC`d&S4J&(4P(cz8f4N5YKR+NAviL2L}GqZDDF*aUQl^p&Z%PskLEBsZAa-+{? z_1wh)ps`c%IO8<=PxO64ZXOOk=(`Eu(Fy1cb+grDat!WO2ZUXjZq562hjnjmJK`m` zTUdTxYM6IE0ij&vqePXpLY7)#yB%7yfds*cD#<34qVgeqSAedSVZ{A#4)7Z55j7@# z5bzWo_;0(4s_m;rmCMNMYIDUjUXSXp6T1s(8Q zp}m+k-qQ%$56II9OSnciaH|EXuzuica4_`Y-yN4Tjq~V{TaolL)U2Sa-YE@Z4Ky(W zd&(KyQUNvC_w5l@%1Ef8X}*Xeu%K=&`JVq77FDiA7b!hTZO|e;3*Q(2}q2;_q%x@=DBOv&{js4 zTGU{=xAmS#GhK)#CcDk5p-q?cwu=H7JCpdNJrVGsLZ>0$l>o=!Pp=M>I>FtAA)?co z{y(lQW{Z-B`Yk?QdHWefGXxwcg0qoS1`x|EX?7%UR!~CE0gkis@-y-cStVvDupUD0HIlI;}|9U;16|;b1@OsJXr@Ozw>rHoo=@t&t zM|+`x576r!L$wqgh>C)jN zUVQs=>e`h0*-88NWU#w^8BG~a!NJc@0z%+kt#~02EUs{Yi!CZ>kFGyQe~8f0Aisyf zvE&tz9}l4+!_bVRrli~>0gI){`r*eUU!Rf6wZbyqRn9*2gP4JzjEDig#A602^H`oKk&Ea<`gzN zdH0V@!NvUF?yE1l#kUvI(!S0J!wt{>b95`^;+VlzO+tj_%^W}&ssIx(L)7iA+t%86LnW%3`70}b=^^PETjkQW$kXiax++nJm|2KSVfz46#Qqj z+lK2?d^8a7>088lVMPB2>lN~r1rT!af=+Hx)S@Jy{1M}3xvo3%ArZ3*yaO-~0zvt- zVP*2fi#)6sBRnc9yXe6?03+>lg`;{C66gf1_1^rt)7(-dQt;rrQkNRqdB(l_Enoe9 zy!Av7ukzP&v(^Xz_h14*3g1a94UYS)@Rc^{;Ch%fOrraD*SX7{r@_TJkjf1Mlr093 zl4sco73j(Y_jCT&x%V8snFjM%9Ug*BP7I7=49>v0B>L49D~A*~(H|7<4q}dw#;;@i zB5!2U5uf^O_yBf&nr!#SSA8;P-giffr+!&gG6xG~IjD!l-CEF=4Aho~(}jsZ1W>Ew zRFDeA?N76W!>7>5#XS1NIU`O&;bJVKZ(ZNFT+{jxVL$gN{(Wj7n7aoA@08OYGxX(S zuCKmaZ1sJJY#hAD#b2l%?h;&`6L1PAG_LjQa&Si>CCZn5-b;8NTYzr&N=Z*ryVmpH zdEj{c$AbDnY5E%Nc8;PQI08=l=~h<+NyOIBJG{hFt3Su5KkQm+p5rup0CyA)f=@Oi zgAeD&@UIH$|12?>4O9_exeSWX-V7`>Rr-lR<*ihHmhPB4-tkW#bU=p^_cXQIdLSlE zm%0T}=vF@Cas^p;(6=`La98dWfV=R&C$NA;y)uHH)5BjV-#r#F4=?P{NYbu{=J!sQ zVpPULWCXyMgMWFL!O#~{lUKZflQ~H!fHGHIch#Z{Vo{(!0BAG#=&l0$i_H%KJIPg* zYJ;gtF3`Fb@P2FTrtw5wH+cMrW9)0~rgg6qb=-1y%LeYzmFW{K`eCa#XK39tgX&@+ z3Hxowtsi5HX=ON#m`bv8ZEWS|%8K6h25rKhmQuwDN;7feWbE?>lGPL!}8IRQ{WV#RrNE+n|QUpxKiX&D94f8!|vo(Nee2(3gDp zxp|&x+l>eV`kU{auvv>2n|YhW5>URYc{57_I#5NO-PSAB)kz#{Ae2wQ`Y7q;(msqZIcT z1I<^1Luj@MJP}r|78z)K&$f6|7VRo$1ac28gY0mwdwj;L?+p;2zx%OHcTf9JlFdiI z#u+y_p4~TXK9!vmHdc7_4G0oh4R-V5q&^Ih)2tAh1##2)ZW!QFhs|uy zzx=mCDZOI6-fm z0D}BG=z$GJ4{Vt}SDw<6ejKYghQyBmTV%ueEmCg7N5bXiUBZ}Gs~spw3VxTnMm299 zNEsX$3HO0~iB_$T`jmHT{M>y{v^opFJ-aK`R%dB+a~!*#o!-q5Myud}nC$cy{dV4j z%d2%bOO&lzW+0O?veI%M1M9`${*-*mzuZyK^Xh22URqu(NjsUU#b$^${NPHXW9hw< zW|qX$)<>Jp8%IxTUQOTKXD>mG&bKvFO_QLo2|AWS=mIIK}lcLK(SC>g~lg{YA&(zW*I$8u~ZLB>&$* zrpWs4B>Rc_RuKheX$^q~~#0F%;zO->9I=}YTs&CSo{_&FZ`W30bBvwF=^^W$UXNJ$qY z+vOP&2Z2x8`JLFB(e&yxjjYOPOk;lmMiSKMDn89s@&qis4u|8J&oppP!;fH4>|@f& zj2(cXQNFV1NhQB>h+zZ0Q^F$vA)ybYu!)!S_+<}Uv}T~wCGz3Z#< zK1DkJ7a!VG8S_|I0B*bfPr8W*A6Qq6qjSyoI@^xmTvd2dp~n@PXB4uJvbH@^NqTcp zX-)M654U$AbVw`j`J$2s_q7{w5B>`sZI8*(u3cZyxm;hX+g|ukVF`I>QE0<-*(ov( z@zkK&Dv!L;SQOb3y{FgnJ9ED3y#Mu=R>Olq^LZ$bLK3RbmJ9KISG(OoCtox+`irKz5y4iBh7^VyoQT>S> zulPg3F1#JeBwc>8t4%BZym`fG z^f_dFYyL~U)7mgPIkgmhnaOH?6N0m8{}c*=DJlQym8T$@qp1ASsgT7tGJ3LSAo(hC5L`;5|Ve|n0joy zC4b?s7ew)v%jwI524@6rp+;tDIdjh?m<1ykK>;=}Hw|HdWSdShrC9I9mvdbB)iP^4 z9Q{pENf2Xyf3HDFMKS_ z)lx`E+mtgU5zW5aLIMuYbZ~b@O?`9TAR?3!#qOna$Sz}PY*cXMG4!P*f)V-}6BS#p z3euFCw{`+*&?^b+Lqs5ByxYN?V6EXp1$5(9-4Je75D+0CiO3ZT?qE z(W;qZwF#}mhpLoRF2N$tC4A4GxNdk6|M7LPr_a}Tjbs^5>TG|TMeo*Q&0e$wy7F|q za)JC{U3oQ989?;UP~l)$V|`|WHHxN=C(v8pijXIMy~lQ(JYE}By~*O(qY8(rbKb)e zR(HhuBNdeWMW< zIwc5}Ofpz970o!mj)h-q!!jg%O(TD(Q}0aKsBZKu7u|GzS{_5ETip-xH|H`RhRmM8 z6b_p1F-%VjhjWwRrTkgBk_ z4a|)?56(nLGH|{V4e7CRS%7UU+g90hY>m3z0?NklNZE4or$Bm2P0$@^4zU|m18NF| z|g9(_YyTurYfGMvUhh>PL^V$AV5U8@I*KE7}v*}79qO!K^`AR1FJuSd)XI5fF znejQxaH~=9lUz&P+?Dh>?fQo4JKpBuR^vENEP3Te`}+I;4z;mj{Tph-e18u?GBoo> zVMl)`EPE^q=fTRth(ce_4 z+#CsrO)J#iH!xU$GfHy^B)qSz0K1$5xU~^d`EhoOO@bghRwR_nr!(8=#@cp$W~>Ve zB!PxS)uj5@nfg+_vb9)gRL4@QZ#+<2>i+vkLzq1cQ-afVVfLYD@)Zu+Nd~T|Vp5>| zPcd#HzQV|s$hYqLO|I7v_7)Gk8x!wRsYB#~>L1$MS!Vozn^$T9`sIB0%~8=rBhyUi z1CPz9g$d-{Vwz5=O8yc8SFPhGU04~ib@F9cPC#Das`Zs+pO675$!9E{JCI<8I;X{a zhIf&PY@y4t!mnRHOepnhxo4-}E5$ijA5Xq&T<*urbb5}>7!qu&sWW3-la=+x8+VF z4h!))rD~oN5Y@m*c@H)%wj8fT$1OF`A|4d~cN#mjZvO26T1Et*hD*w8T@aMB6~&%U zV@lA&9P%i^A(?CT#bL7W9;ijJDg6}wdcFaJ)J*~WiwqFXbo{?YzszS_Z^@SMuJ)P! zX{>6ppO8NWtmvb>(iCyf1w_k(_AN05;VcGuWe zH@^Uw0jl1!<==iwgDQ94QTrWIT4|pskUY)_VM%FrKP-@U zQyZM-NS^L>(#)3X2?W}r2Op*4HEcCee1mV-F6emu2ge$me?Q^7`$G2r4L%fS8Tkk> zH3&`v8%!EHmes009`w^Oq<{G*%bOcyR$Mz>zy&>82xa!GZ5dndNV;$ysC+EeDI%1* zkvQgH&-!%SUe;UVK#Eb(j%u2#v;~TeyWOCvw64_(sQB*Bz2-sf6lG8KKJ&l)`)4;i zqoL)`-w@=%RLO&%eW2ue1=Q5s>5(>{-J0u_jxyTxf&r#Gn|^sl8a@n#U~L0kAIWA1 zX`F#XLNqve7(kzd-9u0S6sp+^Sl71?TTVt*U(@A^V-s!FUaSNW%>-PmVl#KCCbEYD zZg%n6Px1hv_RC!kzoT#17l0lE$k}(%WxpeugFnN!Ur1vU(SD{~dI99owCAwRVz0MY z41vC&a15Pv45;`i*&79pgkNO>n-+un;S$YZ>-mx@gtLM6=+w6rw5ZaqRn+7JDSsl6 zq`m`m#(uWL+Dm&!sxIdIms-55T-Kpvf@+RPDTPP#1428mnSMgI-nKfgzEkPxI6U8- zR*eqLTYDY9UhIGDKSsRbS7G?I@Y3&V%Oa1UkLPfptT)okZmLR}*6L!TETwrr>5`Vt z;LmnY>saBo50kzpHU_|1T@d^~X<9a@(Mt}^55X|{>%dG_#i0NKfJ4TWT;xH?z;f1- zVwXlNh@@Voj68-(PP&bmPCrNalry{dZlWh7A8Er?4vOE`fSgz;#CqooUNx8C13oix1a6#RO6 zlbc(Ha;S!I;UY?c&B~ir#V{+`D#IcAr*QSfA?&6sgu6hnfJ=BX!YdlormTW$3Ijk4 zB^k2ri_zn|{HQ7Q6j1j`%^g|BL9d9OEbjzyP^jH~2}~`iPF;FJ063*YJa*xisrDP& z@gX_t8kED93Cm0r zs_*S@=C}O=@q`a$ecBEsS1X_-8iVl*5E(9b zaVM{%A)W|dc#BftRU8S%d96OFSMbPXREHHW$!oNflLuzN)-a{Vx;ihq?5yiG9a^}M zVVvzAxOEsPJ}C41=re~6O#nrlMwuVSEuS>~%17or1MPm^C(whkS!`iDOO1hlRr~9Z z1Pu&R3A_pf5@e-HytWKiY%mo#+oy{!=Iv&ta<*OJnrF)d@scqc+>Fl$g4c)KA4N^& zNmvSSFnU2$MV5wDOP7B>^WpW0$$g(2CZ40S#FMM6>5>Cm1Cqk!OmPl#VZTPdSwk{K z-ZnfC+s<7g#AAi3&ykyDJLFE$!yKu5yydjygGm2mz%??Aoj}jw3&%qr6;PRO^q7eW zD?8w_B+WR35y<50xozadN@;5i1M{M<9epw?bbz^iC-1?jEM*VQE6D>)9oabUijk23 zgSH!#uZJWQ?rP?W;@gdPTQ(nB?{2!JuB}hFgNkSGHQ8DQ>IRW2mf!YV*4a_&1AhR@Tl&f|KqJ>mUgLAuLOU^K6%Am4 zX-x#X#<|68gVM~DG$*(}s2$Ny5C5~3xZbs%N~E()@Znvo^^i$AF#K9ADYA@QlTyF- zFhgyCw%pW(%czU#>h?8=$s$%kwLF|>bNj#4DYtU3_WUIXuIN|@YRcrU(}aA z!#HlP1qNFbfB3s$^W>%|ZCSS%ttst7KqL@0$=Ka~u_1M(VrbJ$na%}k?B$V7A?{0L z*V9f0;mpU&1sxfkrsIVS>$>#W*+T!y*1MFhj(aT^h8Er2Hb-E^OpjriZXKTr)TP@? zGk!_6dcP00%$>sX1|XWtqLER&MX;UmU)JZrihYd9$BUCNdr1IM|00UK@ZQEGge<9c z0GJ=m%rXW%EDJ$&)XD)nv}-?+!uPEzsg6$&D3K;%)p(O{7q!cC|NU!@DDt~;`AVxI zwMpYA%97|*KvF_G{51gE_yL)-Ft>zF3*vRb&fv7vNQ~PB(WDo$ zl=7$z-I`Zgr(&X;Jd6(@8UXt%&1WwV-p1}rA;P^-5$ub!)})7ikPDgxGWyIEjDzNi z+e)c?HVsIdW|4CdPq;9t=nF?s>;$a}SI z8+EX0o3PEIUl+>Y0or(}j8?_gg=Q=N$a_}6wki5|j8EaQ^gK1I>kD@#X+`)DX>Cg( z7tGr%hTh2xQgJ$lE4@eh8kqsaN=s_6w0LtV3YqdVqWid7MRO5slC%>W2lrxWQ%yRj%emYAS!yF2C7~kaHz6J`547HI& z!y==XqN3RdZ`%)mCKO-i_pE=6d|OCb_{n9Oiq`09517yzLeg#%eZ+mB+E<&Qola!^ zSC^yCKmW~E#`YNBme#u8%dF>v!ZDPva#8jya?zMM)@9*`7*e;^Y~wzf)T$>!<*b_L zHXK3ap}fmBp{Dsq2Jy`=Dk>{qw~$AG0d_jFNC7ESu*JfI;@WXYM1L*9BO1)jWN2B=x@j#^D)iWWk(O74?_i!wrPl$4Fs zB&uoa;?L>xt$mxRSKTA?Y*^l3huC^R@KA;z;YAx2JLu@ANFyk9JLpWv-jqg!#g@#L z>JZ5VgYZDeDM$KeIw>=YBXzDbNN1xcHaN~e3%MSaJet#2dOwOTYy?>Iwje**d!97(^k}Cvg8XTslDG;(ItzdPA021kz^iw&M2p8EdJ> z^ul?^$yV_3=_e*P2%$SOw+0>N-KsTokCU_C1{8WAhJ=1K`dPEXyiHLixoX>&gC1cM z$=SrC^w8}SdL7W7m5~z{2~)9>3NdJK{$wY9Gm?8gKHjwdFW1fO{>q`U38TlKUhh6^ zeKl_@fu3+tABHdC5Rf;tQh64GPOKT@TvQ_kyC`Ty-DOn!JZGGBZo6$k0devDUbE4k ztr02_?=^+M@c4vh_&?Z8w|b=50U;q3$3O*jd}=qyO|GJa$1tb|#oVpnn-4Bi)mDsu z*<|ukm)vck>KVhIX$!_?9XvJ}Fb||qAa775l=t|n_J`Z7; z>QY4S=fSOX*$aeh6hS-)m*-U-#6FuXM%vUc_t0%}>IgoI_$ux5f~_yUI^9~;a*)bQ zQXNO<&NHSRzOi_upev#2lv$gfp+Y|2Wy<&$cp&M=I)&tR;z`J_gHrv9tcZrGu>mRG zwM=Gq#89J3&>%K3+!yZQ1OJr89_*R`1GNOC>o4TJl|PLXLnW(?k`K?MU>U|fc=*>> z)ch*1>Vk=@>p~sYe+&@qJOfQ*@7i9Vauy?%l_q?{=};V6~CDQpZ(l9L{y(difGDR2!4c zC^?vX@WX~{vtSg?XINpIe)be5L$)YtlGvU>6!q6Owz_bn;48s*$Oqp@z1g^NYjat0GtG@#UsyNlKem_LYrKtqF|#Xb6VJI~i}4N)ZfP5{HpXSGM}E_q@2svKU#D#)s+VpS$KRe!yu zB=oDffxn)4lVk{nI-z@F-nI~jv=P536$r(e@61)4o&(FFXjgn{eh8szDf6cs4R68J@ZS zn+tYv#z0EJeI?W*(J(GMh(F~{iPO=h5{gd|!c2~z*9&n*ggMknvhK+% z+fbZ*;xkIr+M_l%i@Y5JRv0M^l-PjkhDSE?Py3`vhg*c^2eC!#j)m7S??~0GoN_W!i^S64se?9!ce<2Ee=k8z*#$3c_D{k>o;Bo#ZMGAaGwrc$8S3$9J+6=W zq0Puq8*d^lnicQ}oL=QFAM?=A&RvWlKspS0Ci2XLuli#s30!yytcV&;bFCP!U^SQC zbXTYh-^6tMo0YxMsHU~MtPvlz z5Z<}Zwj2i08C`k^RhJ$mE$I1JrzMYpp^un;86_nxoT2%L*fc!*iHAsBW!Sm1!%uOq z$(W0Oy} z`DmM-`F;Vh8&7W{(k9|IpCu_@p4foQ@=-ML#1kL(JE-)==MX!?l!`>{!11c6BwI%_ zXgPnHnWj03i|7kDzZ(O8LR7Z>R@mmYV(j21Z`7KthGk*-%63S$e`|Tx4@MzI7{q#( zHo`F`xXqA??$@(-zs5(k6i^A+bXdG$EH>OWg3R?Y*)HKY@{IbgW&Ly=1w$#0Lsx!9WilHZ7^#m4=Ul{ zIHeT+I#*>KHmI-aqNv=7Y$E-Fe3X|*G25wR*>*hkYQ&_`wItq|2?mj;R9EBe(Pu!+ z@i9}IrwcQ{yziO$c83$&&3Fw;46>^Tn4(5y`%&C13PjY*w^&qGnWu99o91X3YZA+&C~{BOBt#9O@z&`I%!(z|qN z46x{HS$c*(3Rd&do*Jm1_0vRo5{c3q3v~qcK9HVD%Sfo-5;u0_ zeiS6G3N2YCYdBN-55WF{KQ0t92e|d%`TkY;HB<}Ylz&$p;f_^oYZfY5)(9|Kdb_6+({QkO2b7d+K^3kB-M35#D zW(HMx9kyte*6gR`7<`QE$G{m`;nBJ8^0D;SAjnx1o2d)?TJC;8BcwCusrK+jHgh%`m{mt zTEULCusUH)5-S6^*LgFb2qCyM16`f@uL4uSn8yFX^m?= zx(SI!-Vc|&y#VL3>J)C_*WEVg_kEroo#j{KmTG>;x`mCA;l9W>XxIkkCt0j zOSdTKj6O`k&P>;;KFnhC`_zIz<|x z_~wrN{n(gwp-$zX$qXmUBHY>mN5b#onL~{767fylxuET?{M(j;^NS-}(6Cx5jthUn zlQOv5TSZ(_W6aUCw?LDf!R)6FwU|4O--%4bIhwC0X$=AOs%1|UUbu1fGx z0DWjYM86#1qH?2UUV+9fTdM2fl4N3bj21i4XLKRfTA=P#pGirt04UyyecC9wuRoYU zcGSf>5nu)CZ^D@|9Z?eisv;wPwYA1U)t2f_;8);~)%M4v#j9$tc_gDO>Zl-O9W(q_ z1S6tMT5V!1p3_*UwrU+nM)CkL*UtbOb~x(~vj*@i1n}>QOI;6Ag`KjD3p{HrZ2eN)_g=W1TF({ur9j~QUKpn5rOnSZfS&1<`Uy3mCR9lcA!em_xpIPl?abb7Ah z80zBXGuZy}SJms7%nF&O?gu~c)tBFpy-q>+qTnB_@AGlvz%r1gs?2Aksb60xEc!%$ zZ`GF``Ib*qF^0YWe_fQqQ_#C)EhDV1ZV3xPv_)>q#XQ&4};? zIewtrX8r5?CpPVT9CUHCvt*71K%MI6j^cL+*ghcMcYwSRTwrRGrCpJ7@Dg-xkz4Hy zMYjn$9Tax!K{s$I{Q^X06#<9o2xL@C#ef#LETCg1>TU)XnTc0qS_b`X{$ptQzDQXuoMb z9Rt=?F|w(JOGo6{@7-g-In?B}3Rnfgc%@Q0zxb?@B!JRzu~5SrCcm#A+iM!rAy7Zw zH3(=Q#Zp?O6`+|8P-B!=Qo<2QI!nAayycM?$j>##;b9f&lZ7#U zfGHyD56=JI#Foc=U0z?@UCTnzlM?uCH{mK%W zfG4osCu8&&m@rZFI%@UVPZI{x@p`=TY+nhxH&6H&P)>?iIu~*%e=QYYioM+ls%X2WpQwU2Ev#@F zpUJ#getY{&$Z!4ne-Ie8&I$ex)v=&Q^fTFoy3a<9q(cFwqLt56Z zXg{`t)>GQ?rY)=6TM8}8+j|3`AJsFM7vore0+3GDSj_(_|FE`j*<>%TGyOrEm_z#6 zH?5GQ0JkwJ9~IofNDJ}1M6}ejG!Ga1HGz(zx&LWm6L0P>3nsuSZbbJ?Vm3E$-{}ZA zX>n@#a~IShl0puGzxuraSr{t39ftz7oMGSv=BiozrDYsKYiyU&h&bN@Qj?1Rm644> zN;z4~YQ#jhA&42b0QD;ZG*4oC+Ih%dUz}I0z?e-P-wtI{rZHz;Q9>m|W}STkJbfHI zJneMf+BdV>4yd}qN#gm$XMY(*k@Y4$v*mbWmM|qg?U{e9+H7Fq-RgTm}r6;I@^5s`8Xlyl76}m2R%!m9HO;|ZhfAiUqnVT?waad2bXVfqRE3&Z zfl`vqb~Co(m$QlOtTA*7%UN{vupn6qF{?NE_U&e08O{!7KV)8MGVtg-7R{0AZ2~!! zPnHLR{cr@?XOnuG673?FA@5Bl*$y_0*dcQ+(w6wGy{@RHT#;oVt)Id%i&kT?uGeTdyqz-Y1286$?+gnut+V2tReK|By*ZrwE7 zjo-)^x7ivgc@@WHD6a=tvx^s71|p6Nwep~LPuO5+A#$_Km+mx_Ul-wLQ7jwwy9R{GTgeYWKd4)tgZu!~m-%icZ>0 z^2qWLWub>f>77CI2&=8+O(Vd*GGtC@G~-)~(`tBP^0A?9PwTTp)*jVN3VCQsNGNIVbnTH8@}m7Gx|+rhUW zONxOd8Yxmtremo`9M2aw3776=zJqNOXxn2-V`{eq17GTpLUAYbK94wtW5+?;L4tKr z{XbRZ6$N7AZ`TVf%F%KwTAZ?;H&y&z%&J0uKdbJMhhka(?%XWaDs#-oX#6{-K*}Ab zt~{+SPE>Z7$d+QNKwPod^3eO_q5J$TPycpK*)43#frx0M4ad!+6QOc_GEh<6x5QXf zd-k%H1Li>WO?d0#CBy%yDeq}$1sePcnRYg{k|mCoJ#z>BWeNtW#J644JJyer-&KP~ z(kj$PcT=>3gs&E!g$l1BZ)wNz*$rz=r8$h68`Ik{$*LyP4Yw*AUaow@JQd@g&)Xi2 zc8qgJsHS$Xi9)fp{+%?Q2ogTsM|(+$#g(kE=wnN9hrA4jNvWTBID^zGG?FC0L2J(E z#O?5Jq*zhAlQvxDWiOi{9|wY5!^Ryq?znoD`X zP_7%?(%BL*M4lHfG4W@fUpEpRsXyvi zP^x+IL5Nh2m6WB_g_UJIF$Itwcj*j9aqJBf~iN8nTu`pgIo0OlEjO=8V-Obye+|2&G<*T%KrhrB0 zM_j!lJ$wuTucH_<6>b2y-oG95Up#62%I}jr zKWXz6QRM64NY36Qlz7AE(q?5p3 zlzLNsAV{GZd_x4n>SK#?9?@<_iA?E!`-VLzl}!9Xu8pBm0E>t^h2qj zoh6E!V|r%4z<*_ih~{V5fOKr{dyg^~(+4%~w8W8;jR$XnDSsWmTsKky+^ri9yB`6I zvpPyZw1@mQZE`!By5LO+p$0kJNWim_^m7v$G+&D2KW7rgbS16b0wDf}?-QHY%v|O@ zHmmlN3tr*J?_BwtKz5)|23^opTB?|_Q(?Y05ftA6Ts9q#+=O;0;^;0&zpJ{)Jsrj| zU!rieW>Ip=nSk=!!%2pJO3b~SSXNXvxOF6- z^}F6%Z$~sv&u~EZk1OOS%Lm|Leh&gW;}ES4t5lQtJgo$Gs@g=U6&Tz5 z%=5v`sab!lrc;`PrQDWH9zkYFBFfCe_8!hKk{5dANW7fGj!=i5?`pLn+qhmgBB*CT z-cJ}*-IYo{IlJJo`Y~Rc`>{Q$ZELRN#&5+VrS4t)_`;jm`03y9c4Fy=e)I2VtmJuM zghx*cNDmo1;2M5ict+*RHH$3YDx7T=GXCNsBW6Nin>VdLURP`r5tRpDx>;~$nYQNy zD6Ys^ZH*+Y(E!8+CfT}E`Zg-}uPg}b-roO5^T0+T78cw)!sGGdc5|^i!np9wohQcE zYhU)l3v{mPt6q%z4VzO(*rn-m>N8}|H5_!OmMMK?IZ!=KbxQ6$U6{U_YhzKKIzK<0 zk1l!8XZfWLm#U&KK~hn}Z|+7l(QPJC_Tjf;E0q6Hw`ih~)o}6QpVN-E6dq&rY+x&r=0#~(8@BogF8Lm|I@4Qm z&=|0?1Aroy<2ZSyz&XccyKDgn_-kp0xXN#Lgx3J}wc=&X(Tz7||0^jK^195Mm*WMR zYSL!^VQhp|(6x8v{pQe1UJt?o&Y9-s^ehT5GO3e{;^?B<0KGn6X4H1FfF}SjZqQas+&tJRAJZ zlzfVx{R$Kl2eNLbmc&;o_w+$`g8dU7CypGlRvy_$bUrL*Br!vR+{DTh`X@8nmNLIz zX8KdIP*pNTI3>ySaD9^b*#Lw08*~_g7aFpDbKenA5%1h^>t;rt`NP&l!#xt3-+dA- z@B^@q=;7D~jO3kR_NP^onS({F-*M#FG(_khzUXh5qC(}?=g$y$51AQKqlqPDA0MGcwaHsGf4a}$Wa1AzOTGkO*V@0 zwdP4f+vxJq*Qk}9b&!&Kxo8!dIQYpp+jXB&U}pNqvo1|&m0#xh9kG4O0$~o*bLX#q zPVccDh+y%hd{qbhntTu^L>&~^5Bh-2;nr^?XI(iQ{c(+LBKnOPRL(9Cf950!K2%r? zuxT>k7%i<+p&H1g@MOo9>+`++TplX#U7Et1+CX=e!k@DXy3v%-`mh9IQHhu2V%;dw z;QdQ4}-!T-$vfjFmu)GZbd{%RP1?nT05Mx;>-Me2zFjY*`=I`+fJYNCTl7?|edA^9U#+ zpG@gF)qsL7HOhAqj|k9~Y>X-072nFiIVi7OlJpO*f{F!~WJ*(z3##Z|O`&$|_>M#V zBq=*J)tZ+!wWMa$e-qDeg1M$$b5lhypI()6|ngu6LWkCCo%YyL3t^jAyvB zty;XZ#ie>mB+FjUIxptHT!5GkAgIJlUm3vEU&2^WTxJUY&uRp6Cx|D@ZcP0!TDHl$ z2srh~cWd{eY9qXAl&5}Mrxx@3t|>oHIX1JgF{CWS|BB#Q6Ezzg$NHL`{R* z+S(KgBzbT^*ep9l%`RFhUtyW?8IGX$ntAps69ft+&~qkn**I(6qE$t%O|6Stkoghj zBQ$4AbxrO}M!||4q1D&+(alki-%igNi~E+6#}draX_iY*W=Ig#XS|Tz_14|7o*fh9D$3JO2 zINs3w7M%1oa;i#$?qUIQD#~a4NZ;Oea+;&}t*?{hHex$Sz&2y6+#WL^rD z$zvXrkaa6_0ir(D_@pN!-Mu>TBnHEN8mP|ILanC5$i}TjLm+%N9^i$ZVzGoc6z%K-Aq^3NZW=Y$*v z#ZCu}dcKsRs77apDEYO^`L6nxq4GBm$LE0C_)5lpVqIm zVP2OIY^|E%9T8V3^7-$!S+s#SU(eo}+&Z2hEbh*dfR1prUb+i2H7#P_E&vaPqinm` ziC~!s@yyJ)plWvT=I*5WE7{okEV+ShdhjeVzH_ zTaIEVHybzeBh{Nz{r_ftI3S^E!GmvA0%gn(ST&0xKjbi(j1l>K?DP4uF9u@>{flU1 z@TJsO(ZA{ibh7!_L5m0HO{q@C;bXP9#kthc{tl)ep!kv7bDbODMY?FuMT<8c`bH1U zkxl%YBGgR1%&?(Ez;~^c`XM6b)4CVeG9sYHY>;^=V$HAXj74ItqoJBrr0(fj{`P{~ zms)u{@81<8LxPX-^geZ$LG; z^nl~KHa>DT5q3acf`aPZu4Jc#9MD~idX5f&Lg)kZn-kXK9W@ke>2Km^v->$w(@P5*!=G*-qsU1& zPXl&aFy;u$jYI21rIqcKpip_czDtQLvw|{M{@DkQNI=AA2RQ=0&{iNjY@xeKvNYH_ zu-FTMRYR->cp(y^#Ck&vS7|%j_^(`m4{hQC%PQ}5WMc6uyzAcrT$dZhFBfk&(hW_5j_(TL5F5c3TamW<+8Ef%!V=CvI z8diiQTN4Nx@bBs>HUT3soCGBO@T@V(!?;jk=hv{9xcIyXkh|!aP6W6 z$&-A-u!t|fy0wBy1#I3psZTrs0mfz+`K&#a$xbHr5sU!S$Lm&k-V0DuP>_~eC;vrF zvGDkvei*D$Z5l`TgFcFC39Lw~l>b;%D8^dYt20AFKFbf1;=M}E-~HwsXfwTp8K zB@DA-Ap_aw(cBzKhlCu%(u5ofLB$(WekyB4wJd3UMmi`dheF_)v~Njl%GA8e__w-4 zV?Z9|e?yXuv`%3DqdxOl7JYm0$}7*EC;-+q8^qv>G%Tyu9UGkM_;>W5C$xdM*LN5} zx%;t*ZNl=lzOuvLhg}%40b~4x>$h>8%pT%Qs_R0$w3|ee zYF7}_k1=RdZ8 z8%GodJU#g_LHoq#TJw%#ib{SduGm?~D;=m=&||boAzyZvv;RGY$G73dG>#gs%!X=VU)S=ggke+(DG8C^6oHFw z1mni_lD`|+P-0HuLW3Q_-Geh;_VRg_Qq-hi2UvI}!&WEgEBknW9&Gv)bL!`_=mzT` zGRC$-R`g6nQG-RBp}o0L4b4l(bLyAGqtN`3@LlBeU{S$|AK~WjOfd1BSXTCFfVFd239|rW9jG3R|p!n{tN*${WL}af!lMXL@BL5Stkm4 zOK1NP^quEhW#P5#k8C_A&GIVuRY>CWalfmm;2z50A^Bciur{oK3=h_KWqg$7XV? zb=@?;dt>kD$e`1Ym3(Y92QT(b9CFn_$$bPlrb8#=MFtjbkZ{;TUJI#&*Bs-;heUnp z3@cO{c_FAB2O& zmg4M2`=!>HFYn5~#AixSTAiBg1c|;WlYJ=4`l6<>iBh7ya9;3R8&&q7N^{R|Ii2e_ zgw&ue-MU*@hl9IhLI$jYSJeM4M&UG@rs?5I(;ZXIQbRl!L;GO!{&}%Jz zlbeXcl9!wmV+~4J-sk&RA7b-VHxTWARw0?*wBjkY&e{DRQVP>*A6)zD2M=LM0kfHZ z=jPM(bjsLs7l%U3=znCp%rh#5P^5I-t@WGjO*lPZieW@L>Iu6%UObOl(Nxb>2mmEaET7o{ z3C5qqsydiuP+&V-VPcbJI08#S#pZqvsOb(}lurl;2)^hle-@?!Eef!rFd!6@G90I~b)44nCTD5OsQ5bM)Lh%D8gT62dQoVrP|2o=#MRt^0ZX&UTt#1*LFljbO3C zmGwMwD^2fXBKA8kH|en<7TpSZ%_!}%jdxy5G507iWH8hFn&cXt7=H(%#g??X@JZR2 z&5uglJ6vSSup5Kp?NyS+?pTEif%%NOD!WlN2H>G_YQz9tH7WqHtj=aI3oteKH!9pM za{l7vVgpRpA{(G^=95a_Gt)##RaI<&Uxa{g_*&Cpt2F%nYs;cfsM+8jt!V?r1$yRU zb6_IYA&ter$Jtt2GSGuf54ZPi&c=GB+#h2Z5D?B8_eH==9cCD!n$O3r7Z14#`41|a z!cY1a?MekUFj{3DrI!`|!DX`#=TViXCTzp?%8y243u$yBTX&xA>nmBMJJlLJWzFf6 zJ3B3|z6HhEww%0;!ixZMD6WnlTAik49qus z-25&}?UzV?)jmSqqSE$7A(kyp&^K z9U9~kMZF;QHppbBobAy}JJVtC##42RB4^7NCgaU7XPF`^`p?Y=Pn-qLPASXW4@f7> zX@oy(v9|$cQOyzt?|hZ^LX(HwmRaSE3h4sJmy`WwZ?<0<;N&*ddm;1Gl9Q|Fefre= zo7N#TvW@bfEn?L*s?t4#>i3j=VI_ZJn^V`2kyZiXdC@9lytD9CX}(^wKrlw{dtmS2 z`*|oQGr&c*z4l-~=4Dp$KFWoVadF8e*szv`kSEv#CUmjFz1+43Op&1H-q4H=fj|2q zuiY;pKsCgyZMJG!DNkK?KT^@<<*=8IsZ+%YZ`5s<_q&VG5`kUqHnF?^ovlQ^v&?s9 zUfZ0(+r*zWyo1_=j%=%%7Jtzvdb6HS=_|k=*^_J}5t<+gyu}0dMeoiEJ-!gjDc=e!PrncHG;Cj*_dv@p>z?n1=fXmxmjXTR&2+ichYFliIM$ z3|ewsnrWhiLJ{bJAeu3wsj+E$7$2K@PfD{udyutNibDJu#NCU!j3}8=WMn0war|T` z+lrFDLzSSzv2KGC10Zq>8T!me2ReW-tA2Ulv-vLMP1c>ccAbsmxmzd$p+U`9&g)rv zN%(PW*!s~7E5h}&wcU4EJK&3fw{VJ4S7~tAy0~{Zz7`Y8AAJBKS<7`jL~PS`PlxA5 zNKFb+y9k&y5pLqr?(D)XWdPG#c72L@uWRvhDl53h9icjpg6ESv4MG9V|5!PyNtMqP84Oj$R3Bk*TbO z1B!t-h9-5o{Am&<2W>=Ky#CaQN*_&Rm+hh>woB0`EmI+fy)^7uziEq?7c>EfxL+WH zXkF|ms<-@uW)VqGU#l$@@h+Zv9JRVtSq)Bd{-8ypt*J0zbk(KxcW-Eadq+^5nX8L3AuT0|0(l0Nr= ze&VJvn8XsU^~~|E_yF?%BM#eDZL~0~1C1Nv!I2X~AyWql2&Yl74wsQ}<)P=Kv(*>3 zS4o^1@-dO!fWBCpT*MLX;-WuMcpYn=Y_d2TKL^eJhT4`bccIh6B&Jdazk84)a`l;j zIx*MFMsfkjp>#(uPr|!`%T1wnQy`a`*_^1Q0FB$2rLDn*4-Zh@KR`()3J5~Nl7haj zR)JT)wWNc?rG~R+lsuln35mq-KD8WGZ8G%fUR>#p+DaC-%{EQN9&f9)?$w@Mu2aPE z&y!@mbIsE!9YW^Z(?r*IqadtBtBs^8cOFI+Vyp7rjY40Vuo&o^9>L`Op>@4FaGqPw zBIbr+>ujmgt$Nt{ewq*y^Q*(znO4l#ZxL<9K1ta+b(nn&GW&L7Vj=z*HoA3+d%_C+ zpJ!G)H5bT46>*UpX*(Uhe+=w-C?Rm>|d$|JrY5|A9iIkU_0ll zj&lxUg53eTjIqHUjAhnu#myf|j>D0@VUs$zaXWm^Wbb=+aT2Rp|2(oWDx`d$b%~+g zg-$ZO+2{kmzH5CwKOuZR(ca$P)Yj3#g8oo4FQw?M;7UdXFEW%k8l8l%;~DbMf~Np;|)7lKJaWfh^5b2wS!H)^J8B1KQTA@3KKIUUo^fwX{11acHmr%6Q}F)V?vX zP#6vRXqJX&*yY7O*{$$fW&!(GYzPMhkQI4(hRz1(nGEK5!D_wR7WS&(T}`$q_z={n z=nb>T@Upkxzf;K~I-=YjW~RMFLF)aj64{nT&^5?V~%VOyFKZo)bR%QDZUu>0#^+-}c*TSBkW8#%O7kHNQj_wgT?B$>WoFk!+f6q=db-P!^U%$8K zg8N9pXJP_dn41s0e|S%lScMsOfZ&=&J)nAG76rI4{z!ltP8q%#=`<1ugPREU&JB8E zB$W4(&#}QH;b{sNjDxQtjd_o^tpF3gFy zQDr@YW*hkm?X)oM)MsWk2L2?1%dK!bmyvB?F4};gPv)pS7HD2LRM%W0Aj7Fdbs8K47}WC zfa;Nu*(LoiZv*OpIs*(rHj0%zPY1`w1eD?c*8{uE|Kgn`U~?=%ysqP@#ALF5k*L*r zGuX`eQbX-NiqZuf0$5LU+n1J%t`@tyL(E~Dn_2}$h6Boo?-Vwi@s4U4908uN?9dFDM{z+wTZrt2;VgW15|3kWM_2J&v;0qF0U= zlAHdR02(0@6pR>jHgX^xFXa>rh>(!`Nov#;F|T|iLc#6&C9ffl=oh&3>7kJO8Tn%C zjX&r#mZK1m_GTehU?Sf!{DasjB{`k0Fbgnm;SfrMPcIFZ4e+^=F-FQTR>o(@a^&6D ze(kh%-yPBc;~nWTBjXKZu$)v=!Vel9a_S8;RO;+r^(Jv;exNa9oGjCzYI%Z0Ydc3Z zc_%F;RbjdVU!qruaK8vevR`WM!IBWkHr;q@+7bZzHWe%~P50%A#6n%L=PxOwK}HB& zjQ!7C@r#2+P>Tzdnzs2_;|WC+^9%hcu2JEVKn2W}sQ2&7`)-}J>-lZqu`0vN`)$r+ zmH4TJAap%(6ag5!+D|<(Me|=^0oK-KVPj@M9wPZ&N@dm=g3ox%1CMu4&a%f04ff(H zSJ>q+1=ogX`&!Y1*{)8)*0K!vb|)$D%7 z82Csv`LoK3w=nnJ=%PX*Z$tm~vvIenYq4Z*>qOcIVKo&lc}Ke&i}1r_Q`}#XZ$Ufg zGji@nMCFUPUfL0ZDVtB7%FzliWnyhelxr=8aSp#TcK7$gRsl6oSceI{ajM)iFZw=< zas`Gg&(B+9128LgYc#|3tRg_j@8GfbCWmao>(a^K`5K#O3TUe8S4Ee}B7LfhiwmK< zOO%pVt;iCV!?6ot(9j@h*1Y?pr-oAI=_O~S8lwcYuCDbg2y1y!o8eTC89Tq5ZG{M> zJT3pBzu$!4(&!?YWJgJS)k_~!sXm$bXc30(tywXFMaG?2X;Q{5V zMI|8!_Jt(;TlfUa@}8<1QT}k5jZ8bU1Z=+hy(nG=RAS|$&R*lkb`r>!_g>jU=LVy$ z$FK7DsP&k=6=-2~9YXHMiKAnBy--id&MVGF2XT#}arXJMt9lI#l>+ zcBnWWtvz%v7PTj2aJr+rw35_nc|nv}jk$?7H>33|?&R8)=DL<>)xIXhrNSw_tp|&~ zH-;p%e@#AW=%qb6Ij`c55w#`a?Ck9FZB3Ixvg+KM;96;<3)6vMo^6IIzhdq3ycr%q zposX$$y~B%@~h*)Z;BXV&@DR%>a);&%^Mq_*S+L#t@AN@?uo~#*{}7_q}DT~hM1Nw zGQ0Yn1>f^~VYaNsr`sF0g`(!6(t3^j0{ z43C+=$axhq@cZ0cuGZYBM$We6WIo@GoLmxq1*YoGVYb#3OxsNLjt(cl1TJO#JFP~y zO3r*;=Iu(}>=8)=ip+@$JbNZT!lP3Q!Q|B>E}Fu<-?4&+i+-tVUK94SUj6$vj&BB^ zA9GV&V3*osCzan}l{UrTnpUR?u8McgE4^u*Df?XAk6^qQbS}n!0TgFA3)p28CYF|Q zsR5%O0OcIU&=f0vC&33AuY=!h5Ee5)96F0icB^f2e!U;bP14%`e45sSk1hN6NKOTQNr+gL_hyP!skRN8i$Zv$$KWJOzC0E+VTTj>?mezM|x2#?rWC; z)8y2pl%#IN=GYN3vx!+Ln z*!M1*hq2P%cw8&!$Qc`)ALuX-QD=^1doG?)DZkbvTu3hQDitJ1kYf{~8-G*t8IDs071yPbl$*}+Ed6KA?seQ zHAL@*;#VEnFzJ+Rn99OYZx@MTCer0YwGv4I%_6;r)`FqFDe|fNLEd+(SJk@QZitu% zOMn40Q}UWP%zm!R)&QPzvOFnyhACbvl-vurs2|zWG^B46FV~&APf?auBwsap82PAZ z4T!8xbHL7`Je1O`zc8EgyRxIA`G7R35{`J z+h7chT6d{v?qO+GsbP#0v1noS^h#B@p5~)fN^#H7#x_si!R9GHm(L!}X6G`wZqJJ^ zjSqQFD|`-lT6(`CDqt-KrTU;#jso=o*0miBd~kVJF;0?GZB56n*Q#Remk80%)_iF* z?@X_rIkKN>b{blv+hj$=il$ccO~WqFLBGB2#d{H#6otFIwle%z4>OzbJ|R6zJo%~- z{;yns%h7bP5ZTk$CYj6~j57%wgQGvkM!o7+8>|%)Le|Z-D{nn%s8uUJ9eoyo%L&D3 zPYY@NP3r=n2@R&WtSo02SW8^$X&nkg$p-x*? z&$K3VV1>`mB21XCz&N>%sYfL_Ha2~M#+HROiKRr>)E$e$7MU`Z1`Y#uTs{4#ji$>G z;C3kf#Nz~dWkU;s{C#tQmze0`r2&zEaGUs3W-2g zpmInNv-z~V?~9MWIqm#Q0ozskdBT_q=lRz|c-Bp_y80GOCWR2uv1%m3;mnYir%5@W zi5TfI)Oj~FeuGTy76a8YmKJmmG=c`sx*XBVVOs3ayYC>B>t+JloeoRL+zx1%e>D_m$%c21+XnFSAX124@5U!dJ z=C5_Z!zlrmDMXe5IyX1B(z9Sm`eT?^rtZ}g;9hxk)Gc3*D2{5O;)-yL*{3o1FEj)1UTCz4l0$pRd$ zwOe%0d*$7kFG^vAAG(ZwKGQQRdD(y-7EGb}1F`0V4)S-_T~vc<3o2X)CCuXyhgr7& zx=P~Pf5+S$ZJli_U6d8yl8{UVvOHAnVBvxibo^fM!b*($5*ogj9~PHk7C5RH16Na= zh%10&pjx6A#>^M%B94x8auuZX?toJ?L!8Qg$@Bi}46$u`6yZQj_m7sCj4(XdlJ^&e zIZxLQhfp*ubChqm*>ZjqsI)i8d8`km6Uo0YP`lonZ+Xa(QvXHqTrW~Gh5G4i98Va= zNf&u03$c*-<0ns$Ry(fv-Yiw|=+*9ox88-lA+PZ+*WOTnGnp&=noHN@$by>hLr`E~ z7byj|@1BE+^}GKPMdD@i=vwwYGH69EH*9S;ReMvK0T(jOY49YDlpu-@bh(h~YkA;x zv#!WKp;7;|g;kNKG5mAeiBBT2Vb!~rd2u`>?e0qctM<)edUnzOAxMQ~(A?n8 z)vV*WvZH{A=^Q(0e)R8vB7#V>>n9TIhBX|DR7N{LZnSO(l0@0c79ct;A6u)OA<(T0 zuIb|CUjcNMV_phxOvtr)}6R(d$d#lQ0%$Qk+jIHMIV|{4ggWFZ0{74YFOd<>D+M2 zmfKOhR|=n7@brwlVXiP)V6EJuW^kSz%wc1VSbay)1S0C5Wu9Tv*E5K-EoQ|Pj?BTJ zBAGS|k~

    tG~RRZ0NmEqIH`XHCd<$pTwCaJ@-vwx%r4kg|;MbR-qjq=9~x8ZvA^x z!}hfhysti{@!7{b&u)%xeXRu3G8?7W=z$vFUrF5>Fm)~M&vK$xGCYeX#-bE|x@(s+ zd6y?~w7T=~gTxB~AuX!{bLiVtE>p>>xVIcJm*{=BEe=*_4*DpHbL!2EYjyNY!)TV#d&@>~W zOG~8&14~EQe2G#z!~0Ri))-4mr`OE|29%s1A9U9xfWOqZJ<7?62aH|TFYxK_UHnFI`)&ceWzX_KIC^ZD|Jy78Ha&Zaf7wq(HQRWs3__n<^gnh`G_AwID#o`% zeu4OPlIuWx*UsQY?l{EZnOx>3vtjz&7fFa3TVA!fSbL{L@QI)ooNVFOH6#CvB(Y%`8(GwmQo5 zd<^=t{VqSfS**_&SCap|dw5vhyt%q+I{AeBIm~&0srg;vJZdX;{a7rzFDE+FuWzWm z`lEkyq)xMhEb>}Rv*Rnp(i@|Lhw2$y(*-A66caG)q9mm3{-`x{#-po2qK}1(Jc@?~ z2EOgdtQJn>zxHyvu+?sTAP^F0S}nX;Fepnkcr)dwrQhmG#5in7z~X8!t%-56H%(re zGCA#aul1{Ot-DyzGY(B+`EUX4y$tfNp2v$pF5#gkE(#LgdjRTCuF+&?O_y-2q>fM^2_+M~z!%VubuJjdO6E z;KAs4Fkr53^)Pj&{Fq@qYNWu*+M0;Xw;tsD1%4|Xt9fR>1kx4DII0N8dO(o*r0NAce34n0XNxcKgF#O-&5J4rQA#h2I=`FrdlpXxM`Ljyvee>Ms zIE;ZHbSD}DX_90*)+qxmcWFVNJ@N%7lfx+bg(?O#(+h+b3%zf4u702EPuk5P9ZGml zdQg7Gcw!l!q`o(dA9HD}p}I~ETShP(p_~OmBHFtVwM7$^yE9kydJwMnjO5+EokQD~ zFI)9E4q98s5x7ip0C90S7>$KNc+AiqLaQ=qU_5_owjqy# z&){Oq`lFXP*r1cxz8l0WP)?%N!zIt~wyIUgEX!bp-CzK7OW4#g@=9HVwU+y(T@V6_ z<|mACS+esR^#`uD{E`Le%Q6B2x+2cpsO$Z&A%Qq@Rog}Vs!p_E8PNfm@#9j5fwL(Y zHW#mbo}kBq@$&(xAYVR;v+tjUP7bdgPVvN5{DM+E1oUFE3a{kd~K z$Cj!iq2Y2FwdN_Y;IEf_^Wycj{#{eQCr(g{t#g;R(5iVcr6yrmeF|T zxT$IwBDxnB4i^tr(!VZU_<;Uu9kcE^1ECr>IGbSQK%UY-B^{dfIg_oFXFbn5VVVV8 zBH*+yen{^M5a|kC;5cwxY!eIp$JYRR3P;rfnjsJX(eIx!Fo#BFJ6SWP{vael`(vsq zfsd?hR61#ZuUZ01Xd~}0G5qT%BQ>|?WI|FVHQ9R4jtjE>SJ7J!W-)lrW{H%Q_J*P9`*F)@Il@L)r&QxhYChxr8}1eU)Xwu)d+X^euPxq4W+?`)FF9x+0* z%Ze|bc670De+0dg5BA1*Dp)=yWiP(wxi*-DE$cs$z!x>bqbnu97{syik(dre7YR)E z@nss7glD)^10T$0nEiGqdAq>uCI`Pn1LT(kHg)k`3^F4SBmx41VE!5G#QlmEIbHOdWI$jD z&%5<{NR!$@G!W|vDR^pXxP71t`q}=%(y3WN#4=sPk|WkGlY(uvJUZucc?W>XX>tl$ z14P{)$Hmqbo*q+@AI5$pqlJrtf!d~Vu>oL1gOJeYw!cC`0T3k+<2b&wY2f>_&pt`o zSV9NfmzsUTSnb4Mhb+UbOoWYt@fv!rf}Q1_>yX`(!|$)%=+VOwN`5UC-bhX`lmlLx#;b&Ple~wbKVPo=4jgj~VMoES;;j-=<}4 zb$}VeK~BztkSP_s<2vGuBpO1roC!VJ-i;ZjYj!+1TY`Wb!+%2F zP|w-CBS9zK^SscYK-|*7j!&j|J)FsRM zd+yLstbCgVP6(@w-;2GpK@HkJ(Wr2fKPaikE%GDhyWq5jQ(9f*)|M8;EQRq^cjz9A z92Qyl>6S{T<)Zpyt7%0a)O|gH9?W~?Ld`spw^OB9US3{l&>IA85OB||e%*T@?brF8 zCUL?KLd``}rJ{X3{dEgfUsUuLe&F$htTRaW|YdDhXWD z7AoFtAhwvIF8yrLAcK^i%kESW1aAWm@>fe!t+ej7*?mSj^UFr|TQ@2-!zE6kR?jQm z3BBt47hUK6#RJfF@t+Fq#9-t9ZLIyJ)WFZoQjsyC!4uu5 zy&_BHQZ6b0-^!}`bM_}ME-s=Ceap zqx;h^ylv|3^!EW5DCuRCqgklQ31pnsd7A8DShV^zQQv1c0RaIazkN7ey%M#oeNH@9O%O>qkaxUnQzY$mdLbrYCmQ`SN^tq^ z28))D<=v=&0LqGX6K&%+7irJlZ~1z$r+?sqpTH{JMHUtH`i1Vz*}REomG+_rwcA0~ zyf35an#*?}nZ!V}wga(EOSi>Wv}n4pbo_F~4@;Ha{MWCndfFZP{-lWG*HSZONAFrq7jYw{Gsmo|0XTyI2}pl+!l9D>UCvC#Y(Cl&*z~z1f)?NOWK4I`gCE@<~2oN=0HW3HALHX&UX;D;kN3$V*^UcxIgrTGp9wVybYySre!I|#Xk$=J z?5-8d0<_NhTNlHX9-Vq63*XQZLkjigSnAa4IhL206w*bMbDD9TEYsFC)}H0$CMZ07ro${{!utyH9tH zhi$#@U$*G`^wRk>_F+{!vHoNd=?5!#4&t&XP?jjl(GmBhWR3(m?#^<7L~9w=lgssJW$Pi zPA=(+t=ih+Qz`qZcGp*-A~Z7Om(0p@tmXr04C=@~`9zpQ)(*r71f+0Mn&bWnIHSGL z{|DeKO(=KzPrR9nbHV$6#+$oe%y4wfv5KNdcP|BGh*i9SvJa)Sk;kOgj)h-l>IlcQ1{bd`0Z-_$wfS3jYb1%BD+Bn28W;YwIvF zw@fR1=7hr}r-2aBy8E!GnZxfqK8W>hb`RV5TXid4(cVtGP9sZeQI|<((a!p<@3~1o zp^Ge2t>$t`e%;J84;fe7ZELBnv6uzQ54_!3fpH)s~xi zSVp^iVV0|cw`oNMoPS=~(`9H&lb%?N3yRZ4bU(59tP*||*@MF@v&W$}dTodXBHzO4 zp|Mn=>Aw(xP42m3Y6)_CAaXDpa$lx_3TEt$#Yv98-ItZK zNB%TK98LSk>GzXa=j1r`W=6M*A>AhKZ`mGQu4jizQfbQmRULA)rlQU(A|hv`#qMIk zB%I+=)~h<(mn*i!9jQ-)TRE$P36)Rfj%hu_-+zcK_?{VzKV3 zwX~Qw3E4+uuyM5}7zKBAuT@sg^8SRfM=K4ze7J)Y$ELzwjQG zfy>-B+Z@JW9sg9MPn@RDWqMP60 z-|v>2ym1U$yaT!cq19+!z@no;qdO%(E1~=*`%A~|u1B-;OgfwIGdeJSYpF$!ht&BT zEj3fN)!61k@XJA@cvh$4ga5yhyX1jyqXvTo)Ox#(VVNl)`w958a(CKy#!2ifv36L4 zxDys1EJuy9d$=egWp0x0Z9eeWkXg;Pwy8v+n^2kef24F~bYCqv12*#G9U%n4d!oXN zYc0wr-S&wyWt;~m9!}=pQy$UPgwE$3y1zn&P!TFqgf}<%YF~PQQ=hf*-JQxaQ3F@3 zq0C=Y3{j+8qC;L4b|pUnK196?mL+Zbzdmd5Og3@l)`WnB3UV7CVgyI)!P zHV-3sQNA4x2j*)tz)}?c8LHP6h69-tJdn7n?ZrwSUu!KRE>hmp+Shnkpl}hlcq?uU zTUQHjU&0B|Cp1`_Iw@q1H9Rg~g>09G*AkEV@tTmShhU48>ZWj$U*+^u12Lv>Q#+7$ zQ1V2$n)zjiYwa@}hf_@7{l`Pwb9psIA3Go>3ukCTQuY9Uy>hRvrPP z?0lzB>NQ_}bT4oZ>Y4WN10@iFCl&303-4TKm=QT<^E^Rz(tJhm^Gne;v$|({Ka9*o zY*)*h??+O_Fq8;Ky6@VX6qsaQ!u&N-Zgdn|+-w&9xtGnkZ6$SF2W@@#>}?02b_PIt46(oi zYAXW`qwRD1>j`kU6Y*59?ncrlvGQ6iDitd=Q<=$*U9Nl*FoPVy(p>L9=CfPC)TCeJ zE=CZ3fh^U5(yadA(;5ion1NUWV-{D7+Xk*tcTn9e16AL~rC&r`inuRnZVAmy;{CVV zJiuO0>_y_p6C$;iaDPIvHg> zu2ZSub-!N;I;k89R)0%igoj+dR4{6|{40-)^rkP71Mf8&S~zKp*NQd%B4!G%Qz2GG zE#nQt^TGu()yQ_7)Y6K&?YS~I#^IL~8{S2UxyH9GE@T}`uI|84T-@_$I2w$X4@@mX}+(+T5VSR9ThjotuWNQ zW>EQvoIW=xzcp>QWJ4v>Q^xC}TUj@DsQGBCwXJN=5_KM_CBPX5z+U0Lm#|lS)4C!{ zMAE%fPvE!I>>I;HW0Wn*cz#n`>#7h>A2D)=u@Bk#!K5&cYLI$M;}D6@lC!6BtfO zy_(EFgevTY7%pmzw^_11b}7#1@%yn9y4oY**4oM94J|K9-L#&tqb&-w7eiE0E1`O; z%@TogCxY6xGzKyMUWb~!och|MVLO)1iT#ubi@R}I|6TEk&!4I105`OzeOs!XMO^l( z@yn@WTsk)eg=o|6ucfiriGq5A!5$H;7YU3UWedLK7JiX!B01*rc(Ali(=TZNZ2h;_ z*6xH{h+59^nFm=Gb$wFUVbnx?_GX4;y+7lTHBs!O$bp|5CAIY@bVZZe@cp5X-R&{! z5|M|3nuduaEm>E9_}}Dnn~8d9n*0s}w8mjh5}zwxes^x|b%|sc;RuAs_P4^J;Jy(4 z%)OfqUAYh{QlvdjhzbsAI)nplcwav^LAQ)g72xRLs28G#rSX!R>Tvm7t$Os)S~b>| z{B&vuwu(U$*)J~UZDC-XPI-7|cSWc*%UGq~RMVk!5yCcyY|8GxX9c!PC<3&|E~HTN zYWw4j<3NYj@783t(MYjr7#t~#ldAWLcrbuChXSuM=xn|8kFn+X^-@=u+V(9H&LMuc zrS6jJVH=Z!)j^(<&zPIg_2rvKFW3WEKY32>i*(Ipr6USVNLQboH#rQoQb?h%RI@Hd1m^rR?*GBsTYyEm zb^XJFpoEm9NQ#QIfOHB1ilj)lG)PGIfTSRyfHa77cgG;9NY?-Z42X1h4e;$j&w0-C zJn!}X|JV0@mveFMqr-jgd+)W^`mNuJZGRKY4Kd)PtK+q+Q2_qKqK)JTu|z@x&L(C@tah;%da5vRK;q7bGwV|j@F z{vC;13W*(PET#lf*E%ciYXi�msP_r9z+Rn&{&6l6H}FRB+O?nBHM_F*uXlIXqOq zR$CJno_Vfphk@G1R{&Bc1^;a`L+z&BWqVsNqybbssv>yI7qv+WLVQSGk+UK~$TU^d?FDQUt`8G-F$Sbspc3e{*+Uzh%K~zzV`#B z-jw!djoC?QGfJz_RS<~-B=190w&~#N&FOqt36Xb;jT1|n%Ie8|(j-;REt-N&)s}NG z22LrEA|Ur+z5%to;;7|KLN@|(7R-$bF>&wdfM_#_R-`na63`B;9DdM%8owXa&~Nm{ zWts@A>VK~hUz^Ak&^X|s(!*l?;8nf#q%%eOeYUUX@Qx0b+B!9dEW@iuB zcXdUBHHAyu_uyP>_zfp2D5`==$;^FcFAA=228&@#IMasVs@oWXpdblTq>7Qz;Qch? z9z@GKXqqh}$#|LB0sH$8H>Sq!u$24A$mzVlnrMp3uwO!DiGxIFaIJzwM{72Podyd8h=p zBk{!D<`p-FpUkhL3Rv0^ABf|Rt!~C8fuf4$JE)Lpuo2gTZyP+Ib_gkR90 zpNi@U`X>c2kC~}-bEuT=5Mce&x86LwjCg3H|B2SFoH@PLq!sbDqOv`_?QK+g?;HfJ zRCN?U-Gv4!Iz#qG?i%LtzbBMm>-qZluE8?U1X?H93H;|J4Wz`1-OEp#3VcIETLIe{<$o5lGVK zza(c;5u^jGOi5{}GL+BhC+(5ZumP*yY!Eo#o05v*x)#bs-QH=im?q?ih)KMIhI_Xe z8pgWSPr(I{M?!OmQ`*l>BKq?Qct8krv_J0H3NO1`1VAExRISSYed_nOiT^LD-*gs( z#{8~p4TLh>OHPmfxG|rf^AWs98hz~0_y`e0+CXgF}{Us>NJ zHa$3wo0DWljB+xay&Ee`(l?ePOhOlah7oqTY>4@So@sfA)AmX-1uCKUK5)fIVJRFx zqhI2yKxAQcy>MCQ+jkD)`(+QhtpARFwvnJQohu|&${L^dmI`jWw6(SKmsnhTkts)` z;wr#_+Qo5rXjWv9RO}CY5NDZrRx);NT=MFYpIIPH^7E6lwU9{nlR+`r)OCqHYmPRA zCC{qCydWe@vF-hB?i(NzpDez78YGKF4?@LzZ^$mJ99y}3cxX80aFTY_gVUsiV(;cS z6!fegT-9;~2{bsrzWKb&RhgR{5u)T|)qHsU?6fX)--POFWe5}vR%9TK*!UL3C)OdK zl3VHwYNG89_MRmPyIj>QU+iaLA3t8$x5`nuvr~DdThb96V>-UMC#T<%y9{Ega4t{x(%QZFwRoooo zZ*~W&v~s$9u@~jD|Mh8-6u);)#uj~>ca}zDPN*WgPk&~kv2zS+;r>1Z%34Q>D89Q9 zfx#MtDnJ_>AD=UwakwiR{d8_751W1`xEcYcZcne)p+W$pCM z)(e`?Pp7*>a@>!8-J2K5_SB4K{pkfseq1DcEa$A8^MA!o=Fg_s+Zctkjvp>Rm3{M<6uJcdBFw zQ-qB~d95`Vq5?`y=M+p*7=j2szd56%;B^;y4i;gYY`7iMTrb*D2ASSN8P<(10^y^jZ@Fftc8klgCnM`w@enW~2}M zWr?%%wYsW|?;mrmDei2iOQ*_}hU+kp}&y;fQon8`pLj!PxmMNP?y{`vw*l^E=!qZgvkeqJ< z2N%DdiIcEI;>F~RHc!~T&EY&@TE(9vDZHRN8cuar_9TDh%V>EXpXO{5CpJnudqbX$b!3J|ij#I9*bMsAS0p zFx-PBq*w_3d*`1XsFJ}CsNOwN{h#=4d9pjt|DE3c%9XowUR$1BVm{5fMl3b<%e~Cx zSm5@F8-cp83!X(;WKuWtCw&eK4Cc|BqAH9A!zE~O<^Afq848I<9xJ~%A2}BNJG-q} zmG{q*_)0Qkm1CBmK4eU3&2V0D>0EZ2QS8RjPYf^sl_w; zMI}u;ik2{=f+(;NR)t+Q5-^_5+y>6;&WqocH~8rc2;@(CY*9p{UYlL7CwRIZi5|W@ z*t{*XZSa8Wl~Gxv+o_)B>2i5&WPGbwmXkOrOQElAoK@{~dZ+IFYkwe$PS_nu^_W8+ zJHkjiIbAz(Ls$LRi%V4c1dIg;|98P<{B6=g~Z6{_E&1)gUR zmYF#!;dD-UoX`(??C3GD-91>FxMmSS2TOq(^XS~>9dKfyJTo?|&>UiHvHd~wl4QJ% zi$!3o7h2=Ei}vx|YqN0>DzMgm)Y5C6$f;PcPG)Ewlk5-dmUthH#v=%sX^(z5XvAyY zcG_2X`+>S}s`SEUEQdZx-~3KY9+vMkK|8Lg$^nI|5WR9qTF31^6G@+ z(pxd8iQsLFFu#J2U`q3aoo&FBic0~s-$3@B@$>5S`Y`=>+$ikLigv6dXuc-ACgdsY zdV$HJS}O@x-|oa{L8liGeB>gXsK1&Z9NByt(QlSRU~|Sn$c3NA#j@H3$(Tvv_Ar&Z zH6lr5BtP}3aN1WYziM_qpYN5xu}gwG{L4*`n=gxB-ZW|uiq|<>5E&b0{C*5nh6~mUIFs|lb$lhH zN-n;QZw9(blc?r1a%t+`M!x;u=yB_CcTteU4j4Z>kr`%m8!_pXM;0Sqetv$+ARBuU z>hkZ|*b>fHXG9!P+1M?EX`v;KSgFS>LXMVjx$WJ3@_5(_s)P7y68VGx(v6Nh9aRi^^4#YN$_|LrgY>?O{-RC_PqJJ532b}U zh4W~4zZK`c7&FS>bj={q53}Bx%QMPm_d|^OA^g>uxS#j%y|h!~G4a|i*4N2@rL@U= zpXe2EE<#V(PG?ritAQVh0oJ7ea1)T?cE3sS zUA_eUHz&i-_+bwsKpw%*rCgS-)l<-^HuOGw&WpxRcOnBXo^+QyPKlf2#sp#Sz@SBO z9e&8Qb!}ehAH389)fa?eDjzpT@^o;*5*~G~VY1v1eH{OeiiG6u=#tO2QIOH;bov9m zviGQ|E+zqG!jsttoS%~C3G`%cY+OgohiuYq}{+TmOFgU;xAi7x5lPo|g*?20UrOnTu z(K0Zk&XYCxUo^Pr>+=81i0U#x@Hdcih9=_ZT z>-o@zkRiB`oE45YNEH^~LPkGhtN0P1NF#<06O8#F?1p19nYRz$3lF*qcnywXl<)KJ zsViF&8q_as$B6aYu38Su*EfdxeM5>=m}Gq=AukxiNex(a(%{=UnG)jduq|A<-QaAZ z?$SVlUUEPt+Na6QI3_LJyaDH@&h^KbDZtnDlRW7alTtMm7k+8SC{@@4-At7{X4dRGJK)3$1DQAyiN|F=ooACFkbBfZ-P z2{g4d{15kH)JST}GulrNH;1KW_wa+S7NDr^d?*IiU#Jj>QbDYEqD{Kp_5>Rm-HL<_ zGwozQO`dmJ@xfW6z{I2cbUty-vBENK7enstX@=8cR_7gYp7=>jTal z!pSloAx?|lJglmlgQgOt6l%~SYu#h556D_nNNL#!RBIqjzdw$5>CU{Kzue5JpMU$w&E(pe zuRQnO!Hn+jgzLHdis1y`-|ILLLKXO(M!;T zQVt!3N2dVl8$wA+XDo+f!wL(jKZ5+4IoJqDU;@oW9IXf8d{QCN%FfwG`7F;4xKY`# zS@*k8R_gB$>)YnKp6d@yS6-wW=?WS>3?b>xg$XODPR!ZILw_#KS=;5o=czMM*X0eWR0e+7|7`xiy+y&LyV`Y9kSONjT#zKh zDkzNbN|jRoJJy8CXU68F6dw8iBcE9ft6;i@0HUB@WavxSl%u7AU6s@N;f!4Fmd{NE zxBZaXr!iF$6?pr{VR-@VUsgyH7z^0j?!O4y??H-qiC%&3pU=TR5-s2|`UE)#ztSD( z%T;1$jTe1dEF!bEhN?UG^&fQyf6B`qqUgk)V@C?0U&P-79?k4M!@_SUU4?Nj_=X6u z{WrIByU8E5_m(ubLTMg@QjE1vq;rw?qSEzFS@jwvADsuz?%JuUST&hO^mfW zsz0RpS{YMfrBqd5jb}Y1wE=6Y<#u0U z{9mnj5Ek{#W^6I_GrEtKtg({%BcMdvh*jJ83fA^3rEHumx!aowxgN z{1DDG?x5c6W3wJsWBGSl2exZEn3BTq<;o3EBixlDhH>5M>9n#NLH+?7x$=c3((s~V z`Dv8k$`{@`jCPL__UJJb1IP=wIn=fT`K5G4sB4xT9nct}nH3ALWUS%7m&J{sb9Bzn zQECpovqI z$N@NAPT7pk_XOzdZY+oL`v`Yk0RvFs`|Sf;`eUmg+P42;2&UrVrx%s+j}6{XptmFV z{rfTjTKJg)+^xCu8x&x;01or`S~$R7ZLh2=2d1%?WbI*r4xfuRBz=X)Z{X`|J^a=^ z2eU=I6KLuB5l}=}r7(7qR(!9zx^W$!SVXPP)Obe>OeCE{ypf6Wvf$|L&Xtiz9{b~+r-mC<@~&nWWIGjNElsM`Wg z-G1U-oW6jiN9rE*$OEnqTlqt8*FaY&K>LIG4_j8>1uk&?Mgm+X87zK5sm;GW3)13R z;*NVqS2^@>2xcC9v`ohN)lyMPWB1g;wrndCuN9OXKAi3(-|3ssdW(VGU+nQ5IZ;yg zm6v#8!RvU1&D~wGJ>Uml`lLf%G*gM)%9SV$k+>U_jF;)H#HdP8iMS-tn5cOTB_H(+ zhT?xe8Z{))0JNWlRlk~ekpt1v8Ic-!rH!2Z7u$JQGlvu2!V3CZCepT$b0v{Zs@`vz8>cP z#i7K1KX!5Qul5UA|Ni*wgDHBx&3C`p`}udJ@MqVOglw=M?(*3jJ2?Ftk6a>) z>XQ=F*()FAqxt7|IOM=HpT#VB5&|Clp?N{FintkA*(KDQ*I_kB%U*A3%d2ZYt zjVa=OD3f1B%~O;TbRp6lOn+u)hp=hzVwvj-P|)?bVKUcJ}H>eM&8-zk3(sIeAaJC1_1WWQPYjKYcg|qE*h+lD|PAd{fM%`?X!t zgfJv|$K{rjj?fRz|`>0MUT+>^d&qhI$uGW|z5Eeo{8yY(?61 zx$%$(zh1s1vQsbCK-VO+8GSo%KA90ayz^9=O(IC z!>-lUfXZKYq?Uox(Aq^Bit00bR5TR=4inQJgS@-Jmxa<>Ol3(ZYjOvrx9)_$d;FU@ zZj%Jfm^xb}=RZAdmOz2emkKsxOWRAM>BT1`97#fcTB@@2RtHr4ZX1C+b-df^I8e|Z zu5G$C8Dw57?;OQR`cd z*3Y8u`GHKX!l}$cNzm^F#mVERHjv~hK2hd=wXg{&+5Ws-tBSPu)ME1A3sg@aUxYCfRk+dh-?=XzcMCAL`T1oFZgJS!F%t zbFqPF1+8CsMmGoQX|Dl+{mdUm3MtmB4G!GT1C9RZ__1y0LF#_GXFGF^fiDJzjD=^a@lZ^us`Vz@@v2#& zD$*)kp@8)kkeIKOr4#V<=jQL$k)c01>tF9@nHvqNBUQ&0%zq$tt6XU^f+>lAZcb{d za5@_3SF9chU4~+cLFn;|ZC@|t&*G*xD=g<^y;09d+C9SSBM=rQR1ZQL))Dn8u6O%7 zMp$C~uT0`W6q1P6-AeqNP}vLAi`}|^2c-TvdUJXdZ<~w%0L6|1ThxxBTnjG{rcM$p8dOKvT4=+*u>2At1RcT&#^7oP!$9(^Ik|A!Ou=>jJ~%B zaNaq`-&^yQ+BGwrEpq~uBN?Sd-MpVPJ3+6I{VlFQ=pK) zC5Q&RS|p4)%E#Gi4I+4O$N!bU`N{=N{0i5sFc~WJ9Y9Oh3fTR>9l5_R9wwp82<9|N z>hTv>jq5z$o|E^bOSk`|^lm0<*B>9RRJfNU>`l@tqbLre@fx1XG}nZx-4k}(!IDwb z4`}qVZ)``@a!Xw+a?yWuk_j3r=%l5bf?i1=!u9zh-fiM|s0w3vJ8gQP!O}Oe+36q8 z8#j8_wfpm}uD4qqRwFzNx@&T~JWe`tK?_s;`kUvXZ%Aa$o8IfV?c~CASj*h5@2wY+ z%trxs4T_NAX^=t6)@BRV_`~5^@=T%W*xkftR6`lNX4WOFMnwR3SsP)Xakw zgkoS5FOg>RZoACyv@cDa@nxFBeZDfZPdM|}K=^o13OiyW2{EQ?3wx2&0u^E)@iq9> zJ=xY;@2eTI$!b`$eI;(Kf;tU$ydTXA`yd2sw=YoU5n|Rw{U>$JXPgj==!3uaw}{`J z?tW7PQK*Rln*NLH*ViE>g2qRw6oTJ~A+%y|4>u9?>KhG9BQA6xrl3rl1k7ZU+alt^ zu*<(xqF~aGF@m-QbRi80B~cM}XpMk@ZP+97>L~>2WG*He^7`kRfPH$X2gk4OnCtA7 z%pu)6iuBImL#IDa^jPi7{7#+cA_gSw7-lHf*4CAqUXg+xP3Qvl3u;K8SdMrCi`Y`H zO=aU_fy5SZ7=PtED80l?vWU^m3@la=Pn8V0cg!P}%pR+wxs`WB#aw9$diQi|J&Dw? zea}WO;Ptrt`FV|DbA30aa-X_9_se)1;!l?rJg6gH7elD@nd&)%g8#a#QK z#PqdUobn!^e)r!eVe@m#B{>|}LiCC^h0N9~VJAglyD5w87pwIQb&ks)X}TjHyLBh< z*pB!12oFA-oN+<-hk93M$bGwwdB^QqJfDIuC%w-VbSygXV}Q9iEq|cvnHd(H9WA;7 zK4jA`Oq)o&Sq1|O;$@shaUUJ4?fn&fVWW;1JtFZdXc&Ywv7nE5&;Rij zqAnYX4iDk<5sWv*9;3%F>yFMHJbKa`iwWkyZJ$C29c!{0%)w@2BtGHg90Y#^qeyS- zkjJ7Uyb5NQ(?>QIi*AMoTsM+OBEt-u=(-5N>gywdiwb69)RB7F_&jm44BBh`qnH>X9UBX)bSO zS0Y{#@8RRO*f)$CGA(M2N->RUz(APLS`bg)3{d>_)xRH(d1yi3M@Im3v)K{Ry&r7k%nG}r{B{v@eUd4e|11W3U z?{BHQOI^;xj2=1?zbTe56$tWcY%t>Yj;{ltL}BN-f~qmBZuUKK<#$c*Q^+*hSBO)6 zJ>4?GhIqMdQwRe2fTH9B5lQoBkRd4f_|hQ)9zl#+#x&-3lOv!C*yg`~lqRL|>fUTY z#A&j*@0)>XgXrll1YSWuB$)|a6nSULquH<*)Z7>idDptl#m$M(L#!%BD=3~ zD=iS?g;ln$vzy@17@jvsik?IfNg3#=TD8s8%Z_f%m#gm>N76U1fP*`yt*K(!b%#9| zWX#?ACC>KdEJWgF>FcX(p=gpQlvZ!OlmML*_12fXw)bYWv#ztQX|nDa%P1uC=Di>O z@wTUG@|CW$!d|70$;>a^S#fM{R@2QSgGrdKWq*%@hVkkd*cqi5Jx0H$3hQ3;rhy(1 zoGmi6>_F((uV39WH1y7pLl$1UXMM6!yvgv7H)#5`=fr3VBgB%kI{JjOS=8C{y$ice z&g&W6tK6(&*j1*_$3rqhD-5SVfiL1|R8|k(GDE{w_5NwNy7Au>Ug38< zvI-bng%u5kHVWpueji*p9VE#b%NaDk}OeD2O~D{aypEd_U` zRTCHYscuMlf7KTpvx022l@J8mMxSgZG@GNC#^_QdZkd1$vOhm!w1#yQ>!Z@DZ$*l5 z_sW^}@~Dw+5>sP?J7Q^$fn(J2f!#Y$&}X4gNaBAt?P^^zP0J&ZDwmKO7?xPqh*6|l z&b^44>)tbQV3yX3FuA{HZPWsih*JBzYaiR7 zw~N2%y?Wz$Z{ZUsG`at#YJ(9nKHFJ-Khjj z&wYPic{UK5Ji!Bd>sG#Zj5Nv9O8=xyYvz5d*^XnZdX64Yv5YwXLDG}1?|uGE1|n?M zve-tyUP$P&nziq~mG++bWleDBZ1IRMOS89aceZqEb( z443MItcI4mn1vGsTqZ1I^(GFca&CPxqlJk6Xzw_)YTU-%YOTzVg02S80~*0x&>|sl znMHB*(aGwH>Y3v~0(f;06H^PTr!_U@ygLk?U+=hI-DHl z*V&ynBb+`c)>v1XthO9Gl)Y77wX0}n z;T^wTrg^;_kMg9h?r_5v;XJbTttXx{;6;X9ZhCf~+umCLtgTb|?&0n7U6(^X#^`%i zRS&&>btTEdigkw~Ajm>+HYyX`?^#T5v_XmUUBr6G>!W(-eR~mDMv9=zW`0_6W2WE; z%hDkNG8BG>aOh8zVR_D=kFt=Jq(%+@5|=+$gx2Uy6z9_LUl;2+)}i;cs*KaT2ooxC zdCj-cRZ?cJi$rs(d`qWcN>LX};xBU2KFr%{m6{4PhzTe;uZ+xi78QsTc07V-N7hkdwH_^}DbN6P<$4VJ$L9dd4%M-Fto0QvCZEq{98iniv+68e#lgoPy<4u$_iWHO z%f>eG=?Jp&qy)db+?ig#{@_ro-s=Y`Pf$0WdSBDkFNrbdgj+a3?29$7UGx2y*!z@Y z@H>uZuJ*hp+A;4gTDHD9p0li z6FTjohx*I!$UR&}K@(7(J}OG}Iyr&UrvBN@302e1^`ZTjnJ04xX|`x+7bAp}f;q*a zw{}ysv4mcKdwycR_rPgwQl)j;mC=~B$UDVy^5xw9o*R6~uq8Snbw;CUh;}g^wZY1* zSlINGQ03yxvudC5M1*=rptv!B2@EXK9>99A0I+#7V$XH!QhaD{V&UMF$!HhriO^E= zNCNW?A)!OY0K92P>u!o!2faAR7v)T|lq4>icGIl)SQR{1;mdB#2U=&`o-%I80q z%Y&vgvNO(iFW$fTjpYer!QWF;#riFb1Hc#y?Ck~X>J^oZuguwzT&kA!NXegV?^+8E z=by(uGTnR1ruhf~hG-~CptK?EHgXidIFjbza!)Sq!LO8lAxI%X!AIOwuai>Kp16W^ z1U2V{O9`O4Gu`nh^R4>4vtB>psy0hG-7T2*I(1^xuX~Ep$)Fv-QYEFLc|S`ri^@WQ zGknVu=&)2#leZ|N<>d;JlmaSEhuEu|;8m_#&*j}h;~o57o^4NfAKP# zg$jVBs2h=TG$_DHhmUzgO%-$`Oo@gu37nGTLkSI`T{D2?C@|W0}?DcI-+yIIW~Tiu9pS+^|EkY+x`|zhqb!a zG=fTpK#cM|4z&D&bk%9jpP^eYs9MrE0K|7OkAB{I_Ar6r63-FJqf^yU%11f^BXh_m ze&m7h7ajOIq55MV$*q`B_mycRV|kZS(9^iaDa`8?*NvOLPk}y^Mi0#bs|f)pbq~s8 zBK;3l^F$f|e=e;GAlm<{Ch~_4NI#PSHwgeDp;zPxLsCb9qk z-w_9G@c;H}jslvkxkJUFaoACIfmecx1dWp8@1Zx*0sMfQ-$ntJDGv-(Ic822Y-(K8 zrf%or`t4WHl3Z?TUDT$g5|NY!oBAerO!kN|J9vy1YUNt8F>@A{hkh)Q`YncLtFvD9 zyR;y7p8+1Hu33`1g~mY&eq}JgPy_r58+g({%Tq@1Ci$o-9*HrUyqw}Db^uEC^&fXc z_*|gOQlAzVF%T>k@Fvj{Wnn@0(|Ss`D!)D>SP@aSJLzmXE14F-^Qz71hg zG>jJDRiBJ%&sxuJW^B{uJ}te;tWqU`WxQ!ay*H$o&ExUa9?@b_;SIc>)z}|h89+Cv zfcbJ~mJ<5CT3^(CB-PVlQPW@-t)M2gIy6+MkqO!8eU@NvB3tMy8I?^aIznzbBRe|42Lg>})17s0yICk~{p{oYk#H{r+`9M7P0gsYAsh7k07ZF< z%LnTQCOs*Vc$A`rDOtsB@1n-mwM1Y~Sw6AbCrTpDC5LUBm84$oy6lH!Qi?fOG)-5_ zs2Ax}b!s%dGU4t-190@|Q~fh}-MKzF-MKJ*uR`lYKJ%S6MaP}CH}~YC`->ceU$+T$ zedI|ry6EQG{sw$d>E6)MzgFRILp>vdu0R0MeQY$o6EpmIfLk{DK`B1XShhtJj~ zx7Mz3fy5npmg(ORq7|Pl|E0$yerVy$0gPL0wfxrZ{*&YrXSn2bs9N$0DXG|FPadzL z7*HEsGzC1QSHyXuFN(f^&`}}ag2$~3DQnfXwA0n7M~dL$zP{TPR-L>(DFUjR-Cp^l zw(5Dq7Hd_r0Z<21d6kG>>lmoGA&=F7mc>vO><~d+D!Fb2xhOn-Z1pnFQSW=lD^j~bn_o`CzV$2Y0o)OK-XFas>Kl4SO5}0EmwQ}I+*$+ z&hK)?!~xY3#-w@jn;H10P#2Ti*&kW0ds^@7NP=Dlk8$6QGI=A9=vR4OKZSTba?hB) zy_=h2H86U9+_7)9*R4{y_e(|o(RsNh{p?&sHbklRCT8?(T2RGm^BYVIjGXDYmxmL+MZO%9pb`cI?dn03T*}rvy_F#;-EM_h z`qt?RFBC zJgyGNk%34v8UatGvr|VNdVBiD{S6r#qg>s_xAA?>)`-(&5V^C4m|T9aH# zhCMhsKh?RJXOI?DX|t+V9a*j1 zxH4hse6@J0L7Mah&xVt-o)jZA?UQaKI+{c zD)Pv1l0rVUT!Y7IBy3eoR2Xp`#kCrIpa2{miq5+Haeg20vgcJ_y04=lNKsBGj*>{@ z&3g(3FLPhWj3Hs%Q1i*o^h(F?=w~}a5%h-HtARpSpIecy!%h#)FFp)8kG~BrQe}B- z98lC({W{x4j0yrv8_jz$if^{*oT(6{hDbq9+1wOFdO2-9&l=s#@vtvIRP`0*ui`)$ zC=*p9TtMT(O2DTi1CO(weJdHZxEq^m8K!j*A&dvPez<83JE7*b3DH%!vp2Fcp1oFf zQ;otpV6X_d%jwG5(<(MSx~cNKsU!IN<03@nGf#oNlVKN%0_z?N;GG-!Z}unnw(sZ9 zbf;gzG3ud-Xj>@QF{6+2_P8@b7C}nHA2O%yh}_Y z6H^c36bZK(2{FN0&B@L5_|;}>6I2qgG3k_}1;^Lj>-a{nA*iPQ&YyEG`+-;8^%h&J zuBR^x&udU?4^x%?@;su+y~4f{D^;~@kHNVXQ~d~@Yh~NGbMmzMK&aYQ1)LhYe(bU~ zI28RV#{fZWpjC_S8!CGQuh;e{w{ra`nkd>Qy2ZX{LM?6<@6}{bE2600EaX)+K6UDU zx}n#iAEEC>d5!`O`Cw`P7vSK-5eOYcGfvSX5RRj7nJD?guqm%PbNJ`J5%TJKvcEk2 zl?~}Mk~jrOE3XpGC$K8E+w#F$@*wwoXzbn4reMuP)~mmA0fw~}d@8*>oGrp~4L!`P zXM$~TsL%0l?|jUa7nW_6ZZNuDby&ASc3$OP^g)ePH)A_WOx-U~vEFGUvr%BlruT-_ zJtVbo^BPD%$`?Z#mkEHggyZOWAz4j;P_=}yva3{~&u%u7eduGj2k2KOc1i$$pxA)N zMyN#}U&`?jiUsvD$)sRJKj)YUowao=3}Jbi%QT`??U(H(5AR_FN%xSM`}Iv@x0ax9~!ZuSSZQefNeLn)VJqd#VO&l)iNfUMj-3ApiK>*BP+rX3&CwQi>r2Uk ztGFXv^LKS(t+F@19d_oKB;rpryh%Y4!~WM?@!W&T!ZG zmbBLpKk0dH;r$!c=z6gEya=R5WkSMkJI-mRKNKm+EC`@tx=K_Nz@v*8M?aSxo_F|M zMnRBIfG_4<7Abetx8`PzH4PPo2!V?|Xo0fi;$EP`2|AuXY1E_2cz=rGeFF5*O1uU=2?PMW~#4l^Fpdg$_r`fauOl%AT`Y?o?YzHVocv)3=s z<~x5oiU%-Iyr*XITqXl5VTsIuUlxH;hB`rLhFlyR2=#!Cb^NtOFQ4*I4V(C0*>h2i zzDo8M#L{uOJO|1f*||^W3Q5ug-^Nk+k{U;#yfYOU#!^MZ2FPPdPX|p=%Wr6({QU zHk?Wz2XN#}>DVuUXB33M8?N+WA;cF6 zM;`A62|b#)Xnor!hTlNYK;Uxj_x8{i{Gnef?hW?VZ`#u4W4%7t`nmSW(KOYzz$E3IU1p%(;1^<@lmgwX$0nYSw@F%DQD#&o+MU<;Q`UnM# zz9<8SoRV`HL`xbJ05h@r$sdj0M_dQDL}fFT)PQmGuTgNn`!fpLE6)wJi$9Dkk)#L+p%7KNB zbyN=AWU*p)hku11|MDFH1q8lnhoWkXVpHDz*NCqOLENr`RZ0a)=FH8>>y^z{(`YnN z&KKAIV@QBB@rRyQXLVztVVtAfQ|rGTafvqhiE6AKqV($)GRttZWYw?vfv3*<8d#AN$*Eh20iMG z%;!!0#|{u?ncm42I3x#U%{$x<)@Uh3R`3dSN}oWHd+9&hLyN)jVfoL77DtMV)Y~Iy z_0@~@Mq1stne_~Wsf7^Io!3qKUL@T9N~FUjv`PYq7D;g37k$}@M#4< zC-T`$80D#+KHFa!(zh7Q3f&7m>w%rVJR5jnxN*AQ!WN*uTMa?joU9E+RC>cj3w5eA zhO*`Qi_Ln0D@>3pwR#a>MsyVgWy9PZ;_$t8D^a?yGjF(mt9lxjyUALccV&)XdSD}2 ze|a!7R5p>lky$P83r*JE6VQvAL4@2!9K?nFp@%nrI{eqXZE2%120>#vbYE<+=Bid` zJUiQmsXA>==^x{g4N4OmH`$;gkeE13Mp@lmX6NTG)6Mo4Q_X=T9~fK-citS9E;myc8P?R#QA<9t z*&M+kE~v5`Rr-VRZ6Txe+Si4S3YGK2En(K5#fhmlCrW!Z7@k+HX;pgHzsOV|&OIE$ z(S=UbX@YLs!!$y0KI!d7U7~ zI*5Iu#5o3Kim|iGEoR>e+@GP&oY+qp{B>(rvV+%b^wIv(Fy)@^P}?gXSU-NdSR&rY0~lu7He(GHk+zJygd~lp7%JPH(zcX=RUt)diL$% z7a#-p(au?^jWwg<(G!mS1CoM7Dl~WM8l-6 z{9Mfj$89u^^s(hYg)cffdd2LIGkPHxP)4f?^5D+4Pi+O=7Cttvjtf350tN70@j?+I zVz469{Bl6Pe44io*!ltUx|LaLM~qH{(x5hfdw_qbVIL!)>Qv&XbCw;CfOE4co_zu0 zp|#~}x~2P+kMNJz@~yRpKOY!bjufR&dmkE|E`r>=52_MB;ZcwWZXqN#XWgmXD#`F_ zCHO(|en$?031)gGO>gGz;>B>9k(q>q5=$_9l2AIAY3~;f7uu@RrGeUH(Ns=NeO6tw z*vOjQGG}J>2dYW|IOHQM@g@ybdjEh`!8dC;T`}FZn~~EMXFhO>0v|X| zUEvPtsLkv+cXpg^pEZy9(yIHx@u*>kRlv8?gN?yb+P)yp_k+J`uzexm&D==;C*1|& zXIk|te|x+^@X5;EYCsHXRhvX;-&S`E1lT3-WxPFos%E9->Tr&^EO!M@<}J|?0DxmS zv;|H2;-3p0c+oBhT$l5jqReXANRLp3HMHli^~v10oiVW4uuR6ID^xM)^R-nT zZwk%1UQ4xW!gpz^2w;?i{$m$KfyoIe5c84c*T|&Ofi0_ugTI%L4e*Pmiy9&Q{_clE+c`|2eYc#?YV}+qk|0p!czb%0J1cIY(Rw6Jg`n|Zp`Jcfo{CTU zs{UGLR5GEd)qC`v0vknydw2T#qumj)~sz)_Ca!8Q2YUHRpXQWLD=DOMPIw$@?cvUupIchu35lU{A)x1xw<)P%RHqxetnhN ze%-PXpL=z>9`en~X?HE*6{Mbsyr z9mXJP{+DM4H1g@ozD$@xP^uPk;am~OrW#T)T@OA|k$ zyS|}ZwuwrgVx6Xf_}#Z_gXB6`Pe8cC*3oj1{6AL(>nIuoLe7Gqqi^*AtGXFRl{WvJ zJU+Q08^mrUP6=xk3Ma;AEnU?CS78a;u{cftqlpX?Ft1;SXVPXVrhI0|lHS_4f`KqU znPyPI{)&(ifvM|*uFXUzSKUJe>;2a6b10ZW#s>ck0v??jM^<=_s3^rBCyClUTOn$6 z+GG+Cip*+AsNen~s{Y2%|4=uV=5>Y^ z4T=lV)ByWr1|QA&d`IwqHZ@+5We@?pOv@A|$}cKb6^g?}V+7Dt&@d*R;lG~l54f$> zQ;v?E&jFTao<sYSOFJJ&%{2M5X-*jeFp{;%Cx!vXf~>CfGe#Q&$UD-VaV zd&3N}eMQMqQQ{*@QOS}l6Uv_K`;3z8W6N5Y38Bc+kZhGgVGvnL%!KSw(TshltRthW zjlu6s%lE1I{`mEmtLu8_J?A;kdCqe`_x+r=D{Ix1D0KYO7po5kbncntwucO6Ut?P- z14;8gQmM_8L9K$)e66e+0zf5Me(gwx_y(43sO>=+5CO~{qK;U}Nm7EPQ!zvBg zc^L|9r<+7$GH{23C+7u#YLy3!OX=JM4Ho>qXGgYzy*ymX5yuEbY=AIU%)2nfPZthf z(7*ucb_}Bk5*G@rHq5%WYLlw-$8RFNXm(km90>uas0J*n7eGaSyidsj{LmBquEy=& zk-!w9sdsegeg_%^hV+8}|G+Ifcpz&b0q=Ucnn*WtNoM!oIUf1KM$y8F0&hu3bBP2~ z)v_O{d?tT*y2|gs=D{@H18<+GzSR`|P~?@~Bakp<6F(tSN1qvha9L;}^ZpHC*yMiw zDWQ9~owep*%(j--erggn84wx=W*l<*${Ix;BzHDU(c3I15TPnHt&A9NADqbQ%1)rA zyu!E(z}G+Qpk)t!Q?6#{1lA;LH?KSp#zbNR6GuPvt!frl17H__;&OJ}?<)n~>vM2q zVQ#s1nK<3BOvG1WGA@lz+)er0)nu$K%d$(2sE6qfcxsvd-Y@>?`6-dA6o6x5C|d>G zHfCBzBWO6rbExcOc=noRYqFT)*nYhN&579%YHY~<<+UIRT2D38)Sski)}_WIPkoQ- zuW^qqwy(*%!opFYzg$NTE$#U}}J&I=CL zqI+@{H+ss+P*1BWn+L;!d78v47!VIgPo(6JQ8CMCaZlx{iDK9jGZ4S_Vwv={S z+-S2bD%u;mCGF_8Q?pY$j96?Z>MOenueG9Kfp4ga-3@4poPzA@bCrF%D1$G z#}(Y@qzuF`@rOs9YPQ*Xkci={=3Eo6FVuHH0%H0KiNd_n#%?7)*?))MI$J2~nXM16yk6wId%#&<8kM;R@Ei}e9*2HOcdIxNUW4me`LyczzRWN>af+3dl@t}wB@M_ziVM|jb;49U zz8i>2qa|0*R%rMLsV&6QN{`^`o%MyQh_h*rEkdn|Mc4=i#Ul>NH{&fc4GDj=+ zsps-`r`GgC7X-;K7So6Kez|_F_RCG>fZ1JQ(g@$1v@!=i{SJMYl0fZIjPRdzD;2fR zGrIFgZRkYW4lc~%aGKF)A>4NR(WuPkj!u~L$RX?JMX4o2eB=1xA!V1Qp4j~-OQflW z;3%(CU&|M&91b=wG&5o4njs8p9!Qb&!|Rm9N`D6<6{KGIPwPC*Hw)}qscrCki3)e1 z%bo2Uewee%8RYQFKu)7Ij~7KFm9{1P;3iqG$X%M>l36ZMdzY0jQ7v=ja)kk{B{~4! zhOsUz&g-(CQMl=(Uw1ZR+_0w)-6}xow@nK8u*I4Eq0Wwb4D-ZGO7nMpJ8j%A-uN#k zNH@fW!6@eNoAFAELw`bL}5w8-Uk_ zoRaIp8~mN9Q(z1A_gKy3>%5EUGK{f%AK98cOO5xy79*=n3Bw^{i%EzEaG)#{ zj!y0|Ik5G@M9Bjp!w=49(@}%aRv^Moe3{Xp+p?XY&N!#$q5! ze|7!#SC@`Jh3hxx0!xnzBB;#|7Do@}BkOEz81~tJ|F)-e* zewxe>*JR@*)NT3>5y6Arcyws>nC&;OxDt!2d3xnm-w$^vI2;f;IAu3QVt~< zz0ybH+qMog#61SBt?8T{8@WUY3n)iq5P^jIt=%c4Y zZUUUwnW>;#`@AxtG#fD`@{A^)U-;Zg{QOSfhiN0RNw6?P3{*Ij1Eie3f1K^0TpYpD znZZOX&WIpp1}x6JJCmVM^uGUfO$zPso2m(@4y%~39qY)_E^Ziw?OrGd!LIn~4A_{r zr~7WN(Fmx2uBJ5K-c_)ma}G!;+%}R-%eDpkMPV&6lE?|>prWHe>8k*0C5*8#xRL)2 zK8y9i)16?{HjW3)m7;-!$TgvXBgmfcvw*X=(8AQO&g$HTk_bQPjZ)#vD}H^#V~yPA znP=L0@Oq*|Eo5+~p70y9t76o#ihq*Q^P0$`)F<~l$9T$Fe1w*wyvdtc#BcJ$LLcwp=Ilnj*oHo3 zB#$UqTMZb9ZUPBYiPCX!}ePZPmp}0u&1u4yt(V#RbY{I z;PcmQ6I~mR6HX^2`zP9KRRpM7_fE2fV+#?;eLi*bRc`jS|(|lXSS62%)BH_vx3|+gubY=v;JLGGbg29@UKA7`T|5jr@i8+xb>M;@=ceX zjD`z~i}`({=|`QUQlw15AgYzx+fBZeMgi(xdie@`J1 z=gnn3f5|=vgu-m+_vV0C3Va$)ma&fhVC^JPkS2t!rPLM`^_A6Zl~lPsS5ItN0F#<3 z=$=JDVtI5VZ-Ek9>VG*QA}yI~!eENEIE~jk3Y&l~d?Y5V_-dwMQizcmt>S}B7XO4( zgt5@U81HHv`8Gm2jjDK>2&pFujOF?<*Rwq|-1}$+WdbdIHn&NO|Fg=;oGIl!TH;_| zb5do;EfN{1M_!rn%fe!M&YGk#^+T8p+g?Q>9hr-k*8(ET5TB2@nl{g+z* zR+6r0BTXTp&KLnnz^6nYZ;{rU@RZ=)>#%BX*tfFW8`-;23JeUatGZez&3Z}|!WJty zb{-UbeAy)qFf`TEYdZi*BPB;q(#+|Mr1n7rmwX#*CRL^*Prns$5R#~JZ@!&0U8wUU z84%U34`=Tmfvg`)JgSS_ae%EfzoiqjFuBrNnEuG!_p(!i#jF&)j43Zg5AFu!8-as4 ztwXU^@|(k2)*Qk8b}Z_jM#Nu_LOnRnQuZrU1oHv@4UNkZ+s78}sCOsq-KF_J|2PZ*WhCPOLJ?a>6tK)nGO}->a6z(u-IiyDx|nNzq3G9?86d-=+<_YwWy=DG zX@kabvGlHyqHnaJxxJClpqem@E6=*J!$*9`dp6i1_9wzsKP@4islN3#orA#G%CMFIrQ>e#jStarczVY}MLg67_J{Zn|fn z!VpH&wUZOYgLupUH_a7?MH3Z*?|mSKc9*DH)x*iwa;LBUYewWU$JskCFB7gM0X8;{ zbFiA%1L6>{(WG>Y3ydLw*(BYBE7q`;)kvluZiIHB?C9QT*w0_0Ue>SEzn>SnL_reG_2@?AuqhTm{ zSbKVv9K#;&7&;Xs{L>zd#SH#$90?iuKZ4DO3d%iiy`+LuDa{bqX?x{j9P}@?hdP3f z{$_uW4?5@mvzY8%iaX?Yy^xoISbYjIGeST<7WIZh@F;}Eo#>UkLCs6{KuRvAtN!N- z2#*Az^uvjGI69GXoT zfU7KX$M8$!>ImM86sN|=g2fXzo8tM+h;wp`x13t9sE=tdfZhSS8cBPF6DUkFw;dP~ zVD=fsNrtHsP+guT13<{|0bSE?-uA$J`2T?Q@Hjr2gti`F;p9zyryX?WqoOY`Z(sB1WbTzUv90HS`i;rg- zm<=ojm2&BpH9B_zOAY=H$qxi8A)`5m>3g| Date: Fri, 11 Apr 2025 09:57:10 +0200 Subject: [PATCH 011/128] edited Related packages/ repos in readme --- motion_primitives_forward_controller/README.md | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index cb96e85a9a..372eed8e29 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -41,9 +41,8 @@ For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobot Sequencing logic for grouped execution (between `MOTION_SEQUENCE_START` and `MOTION_SEQUENCE_END`) is handled within the hardware interface layer. The controller itself only manages queueing and forwarding logic. -## Related Packages/ Repos -- [generate_parameter_library](https://github.com/PickNikRobotics/generate_parameter_library) +# Related packages/ repos - [industrial_robot_motion_interfaces (with additional helper types for stop and motion sequence)](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) -- [motion_primitives_forward_controller from StoglRobotics-forks/ros2_controllers](https://github.com/StoglRobotics-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) -- [Universal_Robots_ROS2_Driver from StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) +- [ros2_controllers with motion_primitives_forward_controller](https://github.com/StoglRobotics-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) +- [Universal_Robots_ROS2_Driver with motion_primitive_ur_driver](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) - [Universal_Robots_Client_Library with movec from urfeex](https://github.com/urfeex/Universal_Robots_Client_Library/tree/movec_movep) \ No newline at end of file From c451fb46075feae443802fc3bd406a0ad3de521c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Fri, 11 Apr 2025 12:14:27 +0200 Subject: [PATCH 012/128] added/ modified copyright headers --- .../execution_state.hpp | 16 ++++++++++++++++ .../motion_primitives_forward_controller.hpp | 9 +++------ .../motion_type.hpp | 16 ++++++++++++++++ .../ready_for_new_primitive.hpp | 16 ++++++++++++++++ ..._primitives_forward_controller_parameters.hpp | 2 +- .../visibility_control.h | 2 +- .../src/motion_primitives_forward_controller.cpp | 8 +++----- .../motion_primitives_forward_controller.yaml | 6 ++---- 8 files changed, 58 insertions(+), 17 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp index 1d2c101f4c..38c1458365 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp @@ -1,3 +1,19 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + #ifndef EXECUTION_STATE_HPP #define EXECUTION_STATE_HPP diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 13f2c4e134..1de3bef76f 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -1,5 +1,5 @@ -// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// +// Copyright (c) 2025, b»robotized +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -11,11 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - -// -// Source of this file are templates in -// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. // +// Authors: Mathias Fuhrer #ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp index ac1fda9b0b..9074f4d45b 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp @@ -1,3 +1,19 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + #ifndef MOTION_TYPE_HPP #define MOTION_TYPE_HPP diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp index 26b0c01dbc..f8054f3dbc 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp @@ -1,3 +1,19 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + #ifndef READY_FOR_NEW_PRIMITIVE_HPP #define READY_FOR_NEW_PRIMITIVE_HPP diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp index d9c55b99b9..b724f6adec 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp @@ -1,4 +1,4 @@ -// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// Copyright (c) 2025, b»robotized // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h index 88afabcafa..106bd9b866 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h @@ -1,4 +1,4 @@ -// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) +// Copyright (c) 2025, b»robotized // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index f08a0dcea6..a17ee48a3a 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -1,5 +1,5 @@ -// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// +// Copyright (c) 2025, b»robotized +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -11,10 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - // -// Source of this file are templates in -// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +// Authors: Mathias Fuhrer // #include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml index 8c4ec46897..d63573e0c1 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml @@ -1,4 +1,4 @@ -# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) +# Copyright (c) 2025, b»robotized # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -11,10 +11,8 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. - # -# Source of this file are templates in -# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. +# Authors: Mathias Fuhrer motion_primitives_forward_controller: From 188f8b5dda67f4265d7c90cf1a1d8494e8ab8395 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 10:33:47 +0200 Subject: [PATCH 013/128] removed LICENSE file --- motion_primitives_forward_controller/LICENSE | 25 -------------------- 1 file changed, 25 deletions(-) delete mode 100644 motion_primitives_forward_controller/LICENSE diff --git a/motion_primitives_forward_controller/LICENSE b/motion_primitives_forward_controller/LICENSE deleted file mode 100644 index 574ef07902..0000000000 --- a/motion_primitives_forward_controller/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -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 the copyright holder 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 HOLDER OR CONTRIBUTORS BE -LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -POSSIBILITY OF SUCH DAMAGE. From 93cc78740f2b0666fe23bf4f78ed9efc00202802 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 10:36:35 +0200 Subject: [PATCH 014/128] removed repos files --- .../motion_primitives_controller_pkg.rolling.upstream.repos | 6 ------ .../motion_primitives_forward_controller.rolling.repos | 6 ------ 2 files changed, 12 deletions(-) delete mode 100644 motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos diff --git a/motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos b/motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos deleted file mode 100644 index 1b3910e7e7..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_controller_pkg.rolling.upstream.repos +++ /dev/null @@ -1,6 +0,0 @@ -repositories: - ## EXAMPLE DEPENDENCY -# : -# type: git -# url: git@github.com:/.git -# version: master diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos b/motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos deleted file mode 100644 index 1b3910e7e7..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller.rolling.repos +++ /dev/null @@ -1,6 +0,0 @@ -repositories: - ## EXAMPLE DEPENDENCY -# : -# type: git -# url: git@github.com:/.git -# version: master From 1122a31a1a20b94d401c55914e2e40baad6387d8 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 10:42:25 +0200 Subject: [PATCH 015/128] changed license from BSD-3-Clause to Apache License 2.0 --- motion_primitives_forward_controller/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 537b46911e..3a853de316 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -6,7 +6,7 @@ Package to control robots using motion primitives like PTP, LIN and CIRC todo Mathias Fuhrer - BSD-3-Clause + Apache License 2.0 ament_cmake From af63eabaf5731513643b991002a954a633c76d19 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 10:48:09 +0200 Subject: [PATCH 016/128] added email to package.xml --- motion_primitives_forward_controller/package.xml | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 3a853de316..a3b5e8552b 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -5,7 +5,7 @@ 0.0.0 Package to control robots using motion primitives like PTP, LIN and CIRC todo - Mathias Fuhrer + Mathias Fuhrer Apache License 2.0 ament_cmake @@ -13,21 +13,13 @@ generate_parameter_library control_msgs - controller_interface - hardware_interface - pluginlib - industrial_robot_motion_interfaces - rclcpp - rclcpp_lifecycle - realtime_tools - std_srvs From 3f3881fb7ded5da8621dd07e01348f91a753b28c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 10:53:22 +0200 Subject: [PATCH 017/128] changed version to fit the rest of the repo, added maintainers and urls according to other controllers in the repo --- motion_primitives_forward_controller/package.xml | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index a3b5e8552b..eb107bd920 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -2,12 +2,22 @@ motion_primitives_forward_controller - 0.0.0 + 4.23.0 Package to control robots using motion primitives like PTP, LIN and CIRC - todo - Mathias Fuhrer + + Bence Magyar + Denis Štogl + Christoph Froehlich + Sai Kishor Kothakota + Apache License 2.0 + https://control.ros.org + https://github.com/ros-controls/ros2_controllers/issues + https://github.com/ros-controls/ros2_controllers/ + + Mathias Fuhrer + ament_cmake generate_parameter_library From ce8b93790dc4eb62839406a00527132ecee68e88 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 11:21:23 +0200 Subject: [PATCH 018/128] removed .gitignore (was not supposed to be pushed to the repo) --- .gitignore | 1 - 1 file changed, 1 deletion(-) delete mode 100644 .gitignore diff --git a/.gitignore b/.gitignore deleted file mode 100644 index 57aaf61f1e..0000000000 --- a/.gitignore +++ /dev/null @@ -1 +0,0 @@ -**/COLCON_IGNORE \ No newline at end of file From 92ee81042cc69a0b07a0938d647fbd253c3217ec Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 24 Apr 2025 11:27:43 +0200 Subject: [PATCH 019/128] removed visibility control --- .../motion_primitives_forward_controller.hpp | 10 ---- .../visibility_control.h | 54 ------------------- 2 files changed, 64 deletions(-) delete mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 1de3bef76f..add7ad4ee0 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -24,7 +24,6 @@ #include "controller_interface/controller_interface.hpp" #include -#include "motion_primitives_forward_controller/visibility_control.h" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" @@ -45,31 +44,23 @@ static constexpr size_t CMD_MY_ITFS = 0; class MotionPrimitivesForwardController : public controller_interface::ControllerInterface { public: - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC MotionPrimitivesForwardController(); - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_init() override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_configure( const rclcpp_lifecycle::State & previous_state) override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_activate( const rclcpp_lifecycle::State & previous_state) override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::CallbackReturn on_deactivate( const rclcpp_lifecycle::State & previous_state) override; - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; @@ -93,7 +84,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle private: // callback for topic interface - MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL void reference_callback(const std::shared_ptr msg); // callback for reference message // std::atomic new_msg_available_ = false; // flag to indicate if new message is available void reset_command_interfaces(); // Reset all command interfaces to NaN() diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h deleted file mode 100644 index 106bd9b866..0000000000 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/visibility_control.h +++ /dev/null @@ -1,54 +0,0 @@ -// Copyright (c) 2025, b»robotized -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -// -// Source of this file are templates in -// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -// - -#ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ - -// This logic was borrowed (then namespaced) from the examples on the gcc wiki: -// https://gcc.gnu.org/wiki/Visibility - -#if defined _WIN32 || defined __CYGWIN__ -#ifdef __GNUC__ -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __attribute__((dllexport)) -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT __attribute__((dllimport)) -#else -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __declspec(dllexport) -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT __declspec(dllimport) -#endif -#ifdef MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_BUILDING_DLL -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT -#else -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT -#endif -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC_TYPE MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL -#else -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_EXPORT __attribute__((visibility("default"))) -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_IMPORT -#if __GNUC__ >= 4 -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC __attribute__((visibility("default"))) -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL __attribute__((visibility("hidden"))) -#else -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_LOCAL -#endif -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_PUBLIC_TYPE -#endif - -#endif // MOTION_PRIMITIVES_CONTTROLLER_PKG__VISIBILITY_CONTROL_H_ From bce1031039bd6303cfa891bb2b2eb458a9ecf401 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 30 Apr 2025 17:07:41 +0200 Subject: [PATCH 020/128] removed/ changed license headers from template files --- ...imitives_forward_controller_parameters.hpp | 7 ++-- .../motion_primitives_forward_controller.xml | 20 ----------- ..._primitives_forward_controller_params.yaml | 19 ----------- ..._forward_controller_preceeding_params.yaml | 19 ----------- ...d_motion_primitives_forward_controller.cpp | 10 ++---- ...t_motion_primitives_forward_controller.cpp | 33 +++++++++---------- ...t_motion_primitives_forward_controller.hpp | 33 +++++++++---------- ...imitives_forward_controller_preceeding.cpp | 33 +++++++++---------- 8 files changed, 50 insertions(+), 124 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp index b724f6adec..aad3111815 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -11,11 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - -// -// Source of this file are templates in -// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. // +// Authors: #ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ #define MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller.xml b/motion_primitives_forward_controller/motion_primitives_forward_controller.xml index 1d9ac20e10..eab3a4113f 100644 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller.xml +++ b/motion_primitives_forward_controller/motion_primitives_forward_controller.xml @@ -1,23 +1,3 @@ - - diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index 6be68ba92e..573eb4364a 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -1,22 +1,3 @@ -# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -# -# Source of this file are templates in -# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -# - test_motion_primitives_forward_controller: ros__parameters: diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index 1bcadb0c65..e3113c2042 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -1,22 +1,3 @@ -# Copyright (c) 20224 Stogl Robotics Consulting UG (haftungsbeschränkt) -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -# -# Source of this file are templates in -# [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -# - test_motion_primitives_forward_controller: ros__parameters: joints: diff --git a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp index 2c7a6d38cc..a7bb555bd0 100644 --- a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp @@ -1,5 +1,5 @@ -// Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// +// Copyright (c) 2025, b»robotized +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -11,12 +11,8 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. - // -// Source of this file are templates in -// [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -// - +// Authors: #include #include diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index 01e062623f..ad0442f74c 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -1,21 +1,18 @@ -// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// // -// // Licensed under the Apache License, Version 2.0 (the "License"); -// // you may not use this file except in compliance with the License. -// // You may obtain a copy of the License at -// // -// // http://www.apache.org/licenses/LICENSE-2.0 -// // -// // Unless required by applicable law or agreed to in writing, software -// // distributed under the License is distributed on an "AS IS" BASIS, -// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// // See the License for the specific language governing permissions and -// // limitations under the License. - -// // -// // Source of this file are templates in -// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -// // +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: // #include // #include diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index deb3122f0d..c63549ce49 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -1,21 +1,18 @@ -// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// // -// // Licensed under the Apache License, Version 2.0 (the "License"); -// // you may not use this file except in compliance with the License. -// // You may obtain a copy of the License at -// // -// // http://www.apache.org/licenses/LICENSE-2.0 -// // -// // Unless required by applicable law or agreed to in writing, software -// // distributed under the License is distributed on an "AS IS" BASIS, -// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// // See the License for the specific language governing permissions and -// // limitations under the License. - -// // -// // Source of this file are templates in -// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -// // +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: // #ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ // #define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index 0c0f13a949..1182c14ea1 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -1,21 +1,18 @@ -// // Copyright (c) 2022, Stogl Robotics Consulting UG (haftungsbeschränkt) (template) -// // -// // Licensed under the Apache License, Version 2.0 (the "License"); -// // you may not use this file except in compliance with the License. -// // You may obtain a copy of the License at -// // -// // http://www.apache.org/licenses/LICENSE-2.0 -// // -// // Unless required by applicable law or agreed to in writing, software -// // distributed under the License is distributed on an "AS IS" BASIS, -// // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// // See the License for the specific language governing permissions and -// // limitations under the License. - -// // -// // Source of this file are templates in -// // [RosTeamWorkspace](https://github.com/StoglRobotics/ros_team_workspace) repository. -// // +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: // #include "test_motion_primitives_forward_controller.hpp" From ae083e7381b847be68e9996fbebebe3338e322e5 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 08:33:58 +0200 Subject: [PATCH 021/128] removed license header from motion_primitives_forward_controller.yaml --- .../motion_primitives_forward_controller.yaml | 17 ----------------- 1 file changed, 17 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml index d63573e0c1..62db1ccb09 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml @@ -1,20 +1,3 @@ -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - - motion_primitives_forward_controller: name: { type: string, From 487e88a120480c09b70c5353eabad8a8515b836c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 08:44:26 +0200 Subject: [PATCH 022/128] changed license in readme to apache 2.0 --- motion_primitives_forward_controller/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 372eed8e29..0d5215e491 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -3,7 +3,7 @@ motion_primitives_forward_controller Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ), LINEAR_CARTESIAN (LIN/ MOVEL) and CIRCULAR_CARTESIAN (CIRC/ MOVEC) -![Licence](https://img.shields.io/badge/License-BSD-3-Clause-blue.svg) +[![Licence](https://img.shields.io/badge/License-Apache-2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) This project provides an interface for sending motion primitives to an industrial robot controller using the `MotionPrimitive.msg` message type from the [industrial_robot_motion_interfaces](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) package. A custom fork of this package is used, which includes additional helper types to enhance motion command flexibility and sequencing. From e0d87c67c1ffe64a2d1cb62c5eaa9332846d1f78 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 09:24:23 +0200 Subject: [PATCH 023/128] uncommented test_motion_primitives_forward_controller --- .../CMakeLists.txt | 16 +- ...t_motion_primitives_forward_controller.cpp | 516 +++++++++--------- ...t_motion_primitives_forward_controller.hpp | 510 ++++++++--------- 3 files changed, 521 insertions(+), 521 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index c73778c958..3dd291754b 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -80,14 +80,14 @@ if(BUILD_TESTING) ros2_control_test_assets ) - # add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller test/test_motion_primitives_forward_controller.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml) - # target_include_directories(test_motion_primitives_forward_controller PRIVATE include) - # target_link_libraries(test_motion_primitives_forward_controller motion_primitives_forward_controller) - # ament_target_dependencies( - # test_motion_primitives_forward_controller - # controller_interface - # hardware_interface - # ) + add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller test/test_motion_primitives_forward_controller.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml) + target_include_directories(test_motion_primitives_forward_controller PRIVATE include) + target_link_libraries(test_motion_primitives_forward_controller motion_primitives_forward_controller) + ament_target_dependencies( + test_motion_primitives_forward_controller + controller_interface + hardware_interface + ) # add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller_preceeding test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml) # target_include_directories(test_motion_primitives_forward_controller_preceeding PRIVATE include) diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index ad0442f74c..1f31006fdc 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -14,261 +14,261 @@ // // Authors: -// #include -// #include -// #include -// #include -// #include - -// #include "rclcpp/rclcpp.hpp" -// #include "test_motion_primitives_forward_controller.hpp" - -// using motion_primitives_forward_controller::CMD_MY_ITFS; -// using motion_primitives_forward_controller::control_mode_type; -// using motion_primitives_forward_controller::STATE_MY_ITFS; - -// class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture -// { -// }; - -// TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) -// { -// SetUpController(); - -// ASSERT_TRUE(controller_->params_.joints.empty()); -// ASSERT_TRUE(controller_->params_.state_joints.empty()); -// ASSERT_TRUE(controller_->params_.interface_name.empty()); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); -// ASSERT_TRUE(controller_->params_.state_joints.empty()); -// ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(joint_names_)); -// ASSERT_EQ(controller_->params_.interface_name, interface_name_); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// auto command_intefaces = controller_->command_interface_configuration(); -// ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); -// for (size_t i = 0; i < command_intefaces.names.size(); ++i) -// { -// EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); -// } - -// auto state_intefaces = controller_->state_interface_configuration(); -// ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); -// for (size_t i = 0; i < state_intefaces.names.size(); ++i) -// { -// EXPECT_EQ(state_intefaces.names[i], joint_names_[i] + "/" + interface_name_); -// } -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, activate_success) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// // check that the message is reset -// auto msg = controller_->input_ref_.readFromNonRT(); -// EXPECT_EQ((*msg)->displacements.size(), joint_names_.size()); -// for (const auto & cmd : (*msg)->displacements) -// { -// EXPECT_TRUE(std::isnan(cmd)); -// } -// EXPECT_EQ((*msg)->velocities.size(), joint_names_.size()); -// for (const auto & cmd : (*msg)->velocities) -// { -// EXPECT_TRUE(std::isnan(cmd)); -// } - -// ASSERT_TRUE(std::isnan((*msg)->duration)); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, update_success) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, deactivate_success) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->command_interfaces_[CMD_MY_ITFS].get_value(), 101.101); -// ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service) -// { -// SetUpController(); - -// rclcpp::executors::MultiThreadedExecutor executor; -// executor.add_node(controller_->get_node()->get_node_base_interface()); -// executor.add_node(service_caller_node_->get_node_base_interface()); - -// // initially set to false -// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// // should stay false -// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); - -// // set to true -// ASSERT_NO_THROW(call_service(true, executor)); -// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); - -// // set back to false -// ASSERT_NO_THROW(call_service(false, executor)); -// ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_fast) -// { -// SetUpController(); -// rclcpp::executors::MultiThreadedExecutor executor; -// executor.add_node(controller_->get_node()->get_node_base_interface()); -// executor.add_node(service_caller_node_->get_node_base_interface()); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// // set command statically -// static constexpr double TEST_DISPLACEMENT = 23.24; -// std::shared_ptr msg = std::make_shared(); -// msg->joint_names = joint_names_; -// msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); -// msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); -// msg->duration = std::numeric_limits::quiet_NaN(); -// controller_->input_ref_.writeFromNonRT(msg); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); -// EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT); -// EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); -// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_slow) -// { -// SetUpController(); -// rclcpp::executors::MultiThreadedExecutor executor; -// executor.add_node(controller_->get_node()->get_node_base_interface()); -// executor.add_node(service_caller_node_->get_node_base_interface()); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// // set command statically -// static constexpr double TEST_DISPLACEMENT = 23.24; -// std::shared_ptr msg = std::make_shared(); -// // When slow mode is enabled command ends up being half of the value -// msg->joint_names = joint_names_; -// msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); -// msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); -// msg->duration = std::numeric_limits::quiet_NaN(); -// controller_->input_ref_.writeFromNonRT(msg); -// controller_->control_mode_.writeFromNonRT(control_mode_type::SLOW); - -// EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); -// ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->displacements[0], TEST_DISPLACEMENT); -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT / 2); -// EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) -// { -// SetUpController(); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// ControllerStateMsg msg; -// subscribe_and_get_messages(msg); - -// ASSERT_EQ(msg.set_point, 101.101); -// } - -// TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status) -// { -// SetUpController(); -// rclcpp::executors::MultiThreadedExecutor executor; -// executor.add_node(controller_->get_node()->get_node_base_interface()); - -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// ControllerStateMsg msg; -// subscribe_and_get_messages(msg); - -// ASSERT_EQ(msg.set_point, 101.101); - -// publish_commands(); -// ASSERT_TRUE(controller_->wait_for_commands(executor)); - -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// EXPECT_EQ(joint_command_values_[CMD_MY_ITFS], 0.45); - -// subscribe_and_get_messages(msg); - -// ASSERT_EQ(msg.set_point, 0.45); -// } - -// int main(int argc, char ** argv) -// { -// ::testing::InitGoogleTest(&argc, argv); -// rclcpp::init(argc, argv); -// int result = RUN_ALL_TESTS(); -// rclcpp::shutdown(); -// return result; -// } +#include +#include +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "test_motion_primitives_forward_controller.hpp" + +using motion_primitives_forward_controller::CMD_MY_ITFS; +using motion_primitives_forward_controller::control_mode_type; +using motion_primitives_forward_controller::STATE_MY_ITFS; + +class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +{ +}; + +TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) +{ + SetUpController(); + + ASSERT_TRUE(controller_->params_.joints.empty()); + ASSERT_TRUE(controller_->params_.state_joints.empty()); + ASSERT_TRUE(controller_->params_.interface_name.empty()); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + + ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); + ASSERT_TRUE(controller_->params_.state_joints.empty()); + ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(joint_names_)); + ASSERT_EQ(controller_->params_.interface_name, interface_name_); +} + +TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + + auto command_intefaces = controller_->command_interface_configuration(); + ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); + for (size_t i = 0; i < command_intefaces.names.size(); ++i) + { + EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + } + + auto state_intefaces = controller_->state_interface_configuration(); + ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); + for (size_t i = 0; i < state_intefaces.names.size(); ++i) + { + EXPECT_EQ(state_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + } +} + +TEST_F(MotionPrimitivesForwardControllerTest, activate_success) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + // check that the message is reset + auto msg = controller_->input_ref_.readFromNonRT(); + EXPECT_EQ((*msg)->displacements.size(), joint_names_.size()); + for (const auto & cmd : (*msg)->displacements) + { + EXPECT_TRUE(std::isnan(cmd)); + } + EXPECT_EQ((*msg)->velocities.size(), joint_names_.size()); + for (const auto & cmd : (*msg)->velocities) + { + EXPECT_TRUE(std::isnan(cmd)); + } + + ASSERT_TRUE(std::isnan((*msg)->duration)); +} + +TEST_F(MotionPrimitivesForwardControllerTest, update_success) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); +} + +TEST_F(MotionPrimitivesForwardControllerTest, deactivate_success) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); +} + +TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->command_interfaces_[CMD_MY_ITFS].get_value(), 101.101); + ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); +} + +TEST_F(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service) +{ + SetUpController(); + + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(controller_->get_node()->get_node_base_interface()); + executor.add_node(service_caller_node_->get_node_base_interface()); + + // initially set to false + ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + // should stay false + ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); + + // set to true + ASSERT_NO_THROW(call_service(true, executor)); + ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); + + // set back to false + ASSERT_NO_THROW(call_service(false, executor)); + ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); +} + +TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_fast) +{ + SetUpController(); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(controller_->get_node()->get_node_base_interface()); + executor.add_node(service_caller_node_->get_node_base_interface()); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + // set command statically + static constexpr double TEST_DISPLACEMENT = 23.24; + std::shared_ptr msg = std::make_shared(); + msg->joint_names = joint_names_; + msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); + msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); + msg->duration = std::numeric_limits::quiet_NaN(); + controller_->input_ref_.writeFromNonRT(msg); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); + EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT); + EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); + EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); +} + +TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_slow) +{ + SetUpController(); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(controller_->get_node()->get_node_base_interface()); + executor.add_node(service_caller_node_->get_node_base_interface()); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + // set command statically + static constexpr double TEST_DISPLACEMENT = 23.24; + std::shared_ptr msg = std::make_shared(); + // When slow mode is enabled command ends up being half of the value + msg->joint_names = joint_names_; + msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); + msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); + msg->duration = std::numeric_limits::quiet_NaN(); + controller_->input_ref_.writeFromNonRT(msg); + controller_->control_mode_.writeFromNonRT(control_mode_type::SLOW); + + EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); + ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->displacements[0], TEST_DISPLACEMENT); + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT / 2); + EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); +} + +TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) +{ + SetUpController(); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + ControllerStateMsg msg; + subscribe_and_get_messages(msg); + + ASSERT_EQ(msg.set_point, 101.101); +} + +TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status) +{ + SetUpController(); + rclcpp::executors::MultiThreadedExecutor executor; + executor.add_node(controller_->get_node()->get_node_base_interface()); + + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + ControllerStateMsg msg; + subscribe_and_get_messages(msg); + + ASSERT_EQ(msg.set_point, 101.101); + + publish_commands(); + ASSERT_TRUE(controller_->wait_for_commands(executor)); + + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + EXPECT_EQ(joint_command_values_[CMD_MY_ITFS], 0.45); + + subscribe_and_get_messages(msg); + + ASSERT_EQ(msg.set_point, 0.45); +} + +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index c63549ce49..0ea3c40b54 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -14,258 +14,258 @@ // // Authors: -// #ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ -// #define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ - -// #include -// #include -// #include -// #include -// #include -// #include -// #include - -// #include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" -// #include "gmock/gmock.h" -// #include "hardware_interface/loaned_command_interface.hpp" -// #include "hardware_interface/loaned_state_interface.hpp" -// #include "hardware_interface/types/hardware_interface_return_values.hpp" -// #include "rclcpp/executor.hpp" -// #include "rclcpp/parameter_value.hpp" -// #include "rclcpp/time.hpp" -// #include "rclcpp/utilities.hpp" -// #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" - -// // TODO(anyone): replace the state and command message types -// using ControllerStateMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerStateMsg; -// using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; -// using ControllerModeSrvType = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerModeSrvType; - -// namespace -// { -// constexpr auto NODE_SUCCESS = controller_interface::CallbackReturn::SUCCESS; -// constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR; -// } // namespace - -// // subclassing and friending so we can access member variables -// class TestableMotionPrimitivesForwardController : public motion_primitives_forward_controller::MotionPrimitivesForwardController -// { -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service); -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_fast); -// FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_slow); - -// public: -// controller_interface::CallbackReturn on_configure( -// const rclcpp_lifecycle::State & previous_state) override -// { -// auto ret = motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); -// // Only if on_configure is successful create subscription -// if (ret == CallbackReturn::SUCCESS) -// { -// ref_subscriber_wait_set_.add_subscription(ref_subscriber_); -// } -// return ret; -// } - -// /** -// * @brief wait_for_command blocks until a new ControllerReferenceMsg is received. -// * Requires that the executor is not spinned elsewhere between the -// * message publication and the call to this function. -// * -// * @return true if new ControllerReferenceMsg msg was received, false if timeout. -// */ -// bool wait_for_command( -// rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set, -// const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) -// { -// bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready; -// if (success) -// { -// executor.spin_some(); -// } -// return success; -// } - -// bool wait_for_commands( -// rclcpp::Executor & executor, -// const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) -// { -// return wait_for_command(executor, ref_subscriber_wait_set_, timeout); -// } - -// // TODO(anyone): add implementation of any methods of your controller is needed - -// private: -// rclcpp::WaitSet ref_subscriber_wait_set_; -// }; - -// // We are using template class here for easier reuse of Fixture in specializations of controllers -// template -// class MotionPrimitivesForwardControllerFixture : public ::testing::Test -// { -// public: -// static void SetUpTestCase() {} - -// void SetUp() -// { -// // initialize controller -// controller_ = std::make_unique(); - -// command_publisher_node_ = std::make_shared("command_publisher"); -// command_publisher_ = command_publisher_node_->create_publisher( -// "/test_motion_primitives_forward_controller/commands", rclcpp::SystemDefaultsQoS()); - -// service_caller_node_ = std::make_shared("service_caller"); -// slow_control_service_client_ = service_caller_node_->create_client( -// "/test_motion_primitives_forward_controller/set_slow_control_mode"); -// } - -// static void TearDownTestCase() {} - -// void TearDown() { controller_.reset(nullptr); } - -// protected: -// void SetUpController(const std::string controller_name = "test_motion_primitives_forward_controller") -// { -// ASSERT_EQ( -// controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()), -// controller_interface::return_type::OK); - -// std::vector command_ifs; -// command_itfs_.reserve(joint_command_values_.size()); -// command_ifs.reserve(joint_command_values_.size()); - -// for (size_t i = 0; i < joint_command_values_.size(); ++i) -// { -// command_itfs_.emplace_back(hardware_interface::CommandInterface( -// joint_names_[i], interface_name_, &joint_command_values_[i])); -// command_ifs.emplace_back(command_itfs_.back()); -// } -// // TODO(anyone): Add other command interfaces, if any - -// std::vector state_ifs; -// state_itfs_.reserve(joint_state_values_.size()); -// state_ifs.reserve(joint_state_values_.size()); - -// for (size_t i = 0; i < joint_state_values_.size(); ++i) -// { -// state_itfs_.emplace_back(hardware_interface::StateInterface( -// joint_names_[i], interface_name_, &joint_state_values_[i])); -// state_ifs.emplace_back(state_itfs_.back()); -// } -// // TODO(anyone): Add other state interfaces, if any - -// controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); -// } - -// void subscribe_and_get_messages(ControllerStateMsg & msg) -// { -// // create a new subscriber -// rclcpp::Node test_subscription_node("test_subscription_node"); -// auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {}; -// auto subscription = test_subscription_node.create_subscription( -// "/test_motion_primitives_forward_controller/state", 10, subs_callback); - -// // call update to publish the test value -// ASSERT_EQ( -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), -// controller_interface::return_type::OK); - -// // call update to publish the test value -// // since update doesn't guarantee a published message, republish until received -// int max_sub_check_loop_count = 5; // max number of tries for pub/sub loop -// rclcpp::WaitSet wait_set; // block used to wait on message -// wait_set.add_subscription(subscription); -// while (max_sub_check_loop_count--) -// { -// controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); -// // check if message has been received -// if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready) -// { -// break; -// } -// } -// ASSERT_GE(max_sub_check_loop_count, 0) << "Test was unable to publish a message through " -// "controller/broadcaster update loop"; - -// // take message from subscription -// rclcpp::MessageInfo msg_info; -// ASSERT_TRUE(subscription->take(msg, msg_info)); -// } - -// // TODO(anyone): add/remove arguments as it suites your command message type -// void publish_commands( -// const std::vector & displacements = {0.45}, -// const std::vector & velocities = {0.0}, const double duration = 1.25) -// { -// auto wait_for_topic = [&](const auto topic_name) -// { -// size_t wait_count = 0; -// while (command_publisher_node_->count_subscribers(topic_name) == 0) -// { -// if (wait_count >= 5) -// { -// auto error_msg = -// std::string("publishing to ") + topic_name + " but no node subscribes to it"; -// throw std::runtime_error(error_msg); -// } -// std::this_thread::sleep_for(std::chrono::milliseconds(100)); -// ++wait_count; -// } -// }; - -// wait_for_topic(command_publisher_->get_topic_name()); - -// ControllerReferenceMsg msg; -// msg.joint_names = joint_names_; -// msg.displacements = displacements; -// msg.velocities = velocities; -// msg.duration = duration; - -// command_publisher_->publish(msg); -// } - -// std::shared_ptr call_service( -// const bool slow_control, rclcpp::Executor & executor) -// { -// auto request = std::make_shared(); -// request->data = slow_control; - -// bool wait_for_service_ret = -// slow_control_service_client_->wait_for_service(std::chrono::milliseconds(500)); -// EXPECT_TRUE(wait_for_service_ret); -// if (!wait_for_service_ret) -// { -// throw std::runtime_error("Services is not available!"); -// } -// auto result = slow_control_service_client_->async_send_request(request); -// EXPECT_EQ(executor.spin_until_future_complete(result), rclcpp::FutureReturnCode::SUCCESS); - -// return result.get(); -// } - -// protected: -// // TODO(anyone): adjust the members as needed - -// // Controller-related parameters -// std::vector joint_names_ = {"joint1"}; -// std::vector state_joint_names_ = {"joint1state"}; -// std::string interface_name_ = "acceleration"; -// std::array joint_state_values_ = {1.1}; -// std::array joint_command_values_ = {101.101}; - -// std::vector state_itfs_; -// std::vector command_itfs_; - -// // Test related parameters -// std::unique_ptr controller_; -// rclcpp::Node::SharedPtr command_publisher_node_; -// rclcpp::Publisher::SharedPtr command_publisher_; -// rclcpp::Node::SharedPtr service_caller_node_; -// rclcpp::Client::SharedPtr slow_control_service_client_; -// }; - -// #endif // TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ + +#include +#include +#include +#include +#include +#include +#include + +#include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" +#include "gmock/gmock.h" +#include "hardware_interface/loaned_command_interface.hpp" +#include "hardware_interface/loaned_state_interface.hpp" +#include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "rclcpp/executor.hpp" +#include "rclcpp/parameter_value.hpp" +#include "rclcpp/time.hpp" +#include "rclcpp/utilities.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" + +// TODO(anyone): replace the state and command message types +using ControllerStateMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerStateMsg; +using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; +using ControllerModeSrvType = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerModeSrvType; + +namespace +{ +constexpr auto NODE_SUCCESS = controller_interface::CallbackReturn::SUCCESS; +constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR; +} // namespace + +// subclassing and friending so we can access member variables +class TestableMotionPrimitivesForwardController : public motion_primitives_forward_controller::MotionPrimitivesForwardController +{ + FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_fast); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_slow); + +public: + controller_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override + { + auto ret = motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); + // Only if on_configure is successful create subscription + if (ret == CallbackReturn::SUCCESS) + { + ref_subscriber_wait_set_.add_subscription(ref_subscriber_); + } + return ret; + } + + /** + * @brief wait_for_command blocks until a new ControllerReferenceMsg is received. + * Requires that the executor is not spinned elsewhere between the + * message publication and the call to this function. + * + * @return true if new ControllerReferenceMsg msg was received, false if timeout. + */ + bool wait_for_command( + rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set, + const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) + { + bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready; + if (success) + { + executor.spin_some(); + } + return success; + } + + bool wait_for_commands( + rclcpp::Executor & executor, + const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) + { + return wait_for_command(executor, ref_subscriber_wait_set_, timeout); + } + + // TODO(anyone): add implementation of any methods of your controller is needed + +private: + rclcpp::WaitSet ref_subscriber_wait_set_; +}; + +// We are using template class here for easier reuse of Fixture in specializations of controllers +template +class MotionPrimitivesForwardControllerFixture : public ::testing::Test +{ +public: + static void SetUpTestCase() {} + + void SetUp() + { + // initialize controller + controller_ = std::make_unique(); + + command_publisher_node_ = std::make_shared("command_publisher"); + command_publisher_ = command_publisher_node_->create_publisher( + "/test_motion_primitives_forward_controller/commands", rclcpp::SystemDefaultsQoS()); + + service_caller_node_ = std::make_shared("service_caller"); + slow_control_service_client_ = service_caller_node_->create_client( + "/test_motion_primitives_forward_controller/set_slow_control_mode"); + } + + static void TearDownTestCase() {} + + void TearDown() { controller_.reset(nullptr); } + +protected: + void SetUpController(const std::string controller_name = "test_motion_primitives_forward_controller") + { + ASSERT_EQ( + controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()), + controller_interface::return_type::OK); + + std::vector command_ifs; + command_itfs_.reserve(joint_command_values_.size()); + command_ifs.reserve(joint_command_values_.size()); + + for (size_t i = 0; i < joint_command_values_.size(); ++i) + { + command_itfs_.emplace_back(hardware_interface::CommandInterface( + joint_names_[i], interface_name_, &joint_command_values_[i])); + command_ifs.emplace_back(command_itfs_.back()); + } + // TODO(anyone): Add other command interfaces, if any + + std::vector state_ifs; + state_itfs_.reserve(joint_state_values_.size()); + state_ifs.reserve(joint_state_values_.size()); + + for (size_t i = 0; i < joint_state_values_.size(); ++i) + { + state_itfs_.emplace_back(hardware_interface::StateInterface( + joint_names_[i], interface_name_, &joint_state_values_[i])); + state_ifs.emplace_back(state_itfs_.back()); + } + // TODO(anyone): Add other state interfaces, if any + + controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); + } + + void subscribe_and_get_messages(ControllerStateMsg & msg) + { + // create a new subscriber + rclcpp::Node test_subscription_node("test_subscription_node"); + auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {}; + auto subscription = test_subscription_node.create_subscription( + "/test_motion_primitives_forward_controller/state", 10, subs_callback); + + // call update to publish the test value + ASSERT_EQ( + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), + controller_interface::return_type::OK); + + // call update to publish the test value + // since update doesn't guarantee a published message, republish until received + int max_sub_check_loop_count = 5; // max number of tries for pub/sub loop + rclcpp::WaitSet wait_set; // block used to wait on message + wait_set.add_subscription(subscription); + while (max_sub_check_loop_count--) + { + controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); + // check if message has been received + if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready) + { + break; + } + } + ASSERT_GE(max_sub_check_loop_count, 0) << "Test was unable to publish a message through " + "controller/broadcaster update loop"; + + // take message from subscription + rclcpp::MessageInfo msg_info; + ASSERT_TRUE(subscription->take(msg, msg_info)); + } + + // TODO(anyone): add/remove arguments as it suites your command message type + void publish_commands( + const std::vector & displacements = {0.45}, + const std::vector & velocities = {0.0}, const double duration = 1.25) + { + auto wait_for_topic = [&](const auto topic_name) + { + size_t wait_count = 0; + while (command_publisher_node_->count_subscribers(topic_name) == 0) + { + if (wait_count >= 5) + { + auto error_msg = + std::string("publishing to ") + topic_name + " but no node subscribes to it"; + throw std::runtime_error(error_msg); + } + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + ++wait_count; + } + }; + + wait_for_topic(command_publisher_->get_topic_name()); + + ControllerReferenceMsg msg; + msg.joint_names = joint_names_; + msg.displacements = displacements; + msg.velocities = velocities; + msg.duration = duration; + + command_publisher_->publish(msg); + } + + std::shared_ptr call_service( + const bool slow_control, rclcpp::Executor & executor) + { + auto request = std::make_shared(); + request->data = slow_control; + + bool wait_for_service_ret = + slow_control_service_client_->wait_for_service(std::chrono::milliseconds(500)); + EXPECT_TRUE(wait_for_service_ret); + if (!wait_for_service_ret) + { + throw std::runtime_error("Services is not available!"); + } + auto result = slow_control_service_client_->async_send_request(request); + EXPECT_EQ(executor.spin_until_future_complete(result), rclcpp::FutureReturnCode::SUCCESS); + + return result.get(); + } + +protected: + // TODO(anyone): adjust the members as needed + + // Controller-related parameters + std::vector joint_names_ = {"joint1"}; + std::vector state_joint_names_ = {"joint1state"}; + std::string interface_name_ = "acceleration"; + std::array joint_state_values_ = {1.1}; + std::array joint_command_values_ = {101.101}; + + std::vector state_itfs_; + std::vector command_itfs_; + + // Test related parameters + std::unique_ptr controller_; + rclcpp::Node::SharedPtr command_publisher_node_; + rclcpp::Publisher::SharedPtr command_publisher_; + rclcpp::Node::SharedPtr service_caller_node_; + rclcpp::Client::SharedPtr slow_control_service_client_; +}; + +#endif // TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ From 9fa58b485f96f2ea7395bc595962da9034a10a0c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 16:46:49 +0200 Subject: [PATCH 024/128] changed msg_queue_ form private to protected to be accessible in tests --- .../motion_primitives_forward_controller.hpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index add7ad4ee0..8357c39825 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -82,6 +82,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle rclcpp::Publisher::SharedPtr s_publisher_; std::unique_ptr state_publisher_; + std::queue> msg_queue_; + private: // callback for topic interface void reference_callback(const std::shared_ptr msg); // callback for reference message @@ -89,7 +91,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle void reset_command_interfaces(); // Reset all command interfaces to NaN() bool set_command_interfaces(); // Set command interfaces from the message - std::queue> msg_queue_; size_t queue_size_ = 0; std::mutex command_mutex_; From 3eb44c26e5f9c68c2ff98287eb060323fb8f9668 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 16:48:40 +0200 Subject: [PATCH 025/128] changed test_motion_primitives_forward_controller implementation from rtw template to fit the controller implementation --- ..._primitives_forward_controller_params.yaml | 36 +++- ...t_motion_primitives_forward_controller.cpp | 150 +++----------- ...t_motion_primitives_forward_controller.hpp | 192 ++++++++++-------- 3 files changed, 166 insertions(+), 212 deletions(-) diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index 573eb4364a..d01d9bfdea 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -1,7 +1,33 @@ test_motion_primitives_forward_controller: ros__parameters: - - joints: - - joint1 - - interface_name: acceleration + name: motion_primitive + command_interfaces: + - motion_type + - q1 + - q2 + - q3 + - q4 + - q5 + - q6 + - pos_x + - pos_y + - pos_z + - pos_qx + - pos_qy + - pos_qz + - pos_qw + - pos_via_x + - pos_via_y + - pos_via_z + - pos_via_qx + - pos_via_qy + - pos_via_qz + - pos_via_qw + - blend_radius + - velocity + - acceleration + - move_time + state_interfaces: + - execution_status + - ready_for_new_primitive + queue_size: 20 # queue size to buffer incoming commands \ No newline at end of file diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index 1f31006fdc..db31b27dc0 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. // -// Authors: +// Authors: Mathias Fuhrer #include #include @@ -24,7 +24,6 @@ #include "test_motion_primitives_forward_controller.hpp" using motion_primitives_forward_controller::CMD_MY_ITFS; -using motion_primitives_forward_controller::control_mode_type; using motion_primitives_forward_controller::STATE_MY_ITFS; class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture @@ -35,16 +34,15 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe { SetUpController(); - ASSERT_TRUE(controller_->params_.joints.empty()); - ASSERT_TRUE(controller_->params_.state_joints.empty()); - ASSERT_TRUE(controller_->params_.interface_name.empty()); + ASSERT_TRUE(controller_->params_.command_interfaces.empty()); + ASSERT_TRUE(controller_->params_.state_interfaces.empty()); + ASSERT_TRUE(controller_->params_.name.empty()); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); - ASSERT_TRUE(controller_->params_.state_joints.empty()); - ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(joint_names_)); - ASSERT_EQ(controller_->params_.interface_name, interface_name_); + ASSERT_THAT(controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + ASSERT_THAT(controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + ASSERT_EQ(controller_->params_.name, interface_namespace_); } TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) @@ -54,17 +52,17 @@ TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); auto command_intefaces = controller_->command_interface_configuration(); - ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); + ASSERT_EQ(command_intefaces.names.size(), command_values_.size()); for (size_t i = 0; i < command_intefaces.names.size(); ++i) { - EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + EXPECT_EQ(command_intefaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); } auto state_intefaces = controller_->state_interface_configuration(); - ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); + ASSERT_EQ(state_intefaces.names.size(), state_values_.size()); for (size_t i = 0; i < state_intefaces.names.size(); ++i) { - EXPECT_EQ(state_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + EXPECT_EQ(state_intefaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); } } @@ -75,20 +73,9 @@ TEST_F(MotionPrimitivesForwardControllerTest, activate_success) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - // check that the message is reset - auto msg = controller_->input_ref_.readFromNonRT(); - EXPECT_EQ((*msg)->displacements.size(), joint_names_.size()); - for (const auto & cmd : (*msg)->displacements) - { - EXPECT_TRUE(std::isnan(cmd)); - } - EXPECT_EQ((*msg)->velocities.size(), joint_names_.size()); - for (const auto & cmd : (*msg)->velocities) - { - EXPECT_TRUE(std::isnan(cmd)); - } - - ASSERT_TRUE(std::isnan((*msg)->duration)); + // check that the message queue is reset + auto msg_queue = controller_->msg_queue_; + ASSERT_TRUE(msg_queue.empty()); } TEST_F(MotionPrimitivesForwardControllerTest, update_success) @@ -118,102 +105,21 @@ TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_EQ(controller_->command_interfaces_[CMD_MY_ITFS].get_value(), 101.101); ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); - ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_TRUE(std::isnan(controller_->command_interfaces_[CMD_MY_ITFS].get_value())); - - ASSERT_EQ( - controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), - controller_interface::return_type::OK); -} - -TEST_F(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service) -{ - SetUpController(); - - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(controller_->get_node()->get_node_base_interface()); - executor.add_node(service_caller_node_->get_node_base_interface()); - - // initially set to false - ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); - - ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - - // should stay false - ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); - // set to true - ASSERT_NO_THROW(call_service(true, executor)); - ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); + auto val_opt = controller_->command_interfaces_[CMD_MY_ITFS].get_optional(); + ASSERT_TRUE(std::isnan(val_opt.value())); - // set back to false - ASSERT_NO_THROW(call_service(false, executor)); - ASSERT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); -} - -TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_fast) -{ - SetUpController(); - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(controller_->get_node()->get_node_base_interface()); - executor.add_node(service_caller_node_->get_node_base_interface()); - - ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - // set command statically - static constexpr double TEST_DISPLACEMENT = 23.24; - std::shared_ptr msg = std::make_shared(); - msg->joint_names = joint_names_; - msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); - msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); - msg->duration = std::numeric_limits::quiet_NaN(); - controller_->input_ref_.writeFromNonRT(msg); + val_opt = controller_->command_interfaces_[CMD_MY_ITFS].get_optional(); + ASSERT_TRUE(std::isnan(val_opt.value())); ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - - EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); - EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT); - EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); - EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::FAST); } -TEST_F(MotionPrimitivesForwardControllerTest, test_update_logic_slow) -{ - SetUpController(); - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(controller_->get_node()->get_node_base_interface()); - executor.add_node(service_caller_node_->get_node_base_interface()); - - ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - - // set command statically - static constexpr double TEST_DISPLACEMENT = 23.24; - std::shared_ptr msg = std::make_shared(); - // When slow mode is enabled command ends up being half of the value - msg->joint_names = joint_names_; - msg->displacements.resize(joint_names_.size(), TEST_DISPLACEMENT); - msg->velocities.resize(joint_names_.size(), std::numeric_limits::quiet_NaN()); - msg->duration = std::numeric_limits::quiet_NaN(); - controller_->input_ref_.writeFromNonRT(msg); - controller_->control_mode_.writeFromNonRT(control_mode_type::SLOW); - - EXPECT_EQ(*(controller_->control_mode_.readFromRT()), control_mode_type::SLOW); - ASSERT_EQ((*(controller_->input_ref_.readFromRT()))->displacements[0], TEST_DISPLACEMENT); - ASSERT_EQ( - controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), - controller_interface::return_type::OK); - - EXPECT_EQ(joint_command_values_[STATE_MY_ITFS], TEST_DISPLACEMENT / 2); - EXPECT_TRUE(std::isnan((*(controller_->input_ref_.readFromRT()))->displacements[0])); -} TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) { @@ -229,7 +135,7 @@ TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) ControllerStateMsg msg; subscribe_and_get_messages(msg); - ASSERT_EQ(msg.set_point, 101.101); + ASSERT_EQ(msg.data, ExecutionState::IDLE); } TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status) @@ -248,20 +154,30 @@ TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_update ControllerStateMsg msg; subscribe_and_get_messages(msg); - ASSERT_EQ(msg.set_point, 101.101); + ASSERT_EQ(msg.data, ExecutionState::IDLE); publish_commands(); - ASSERT_TRUE(controller_->wait_for_commands(executor)); + controller_->wait_for_commands(executor); ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(joint_command_values_[CMD_MY_ITFS], 0.45); + EXPECT_EQ(command_values_[0], MotionType::LINEAR_JOINT); // motion type + EXPECT_EQ(command_values_[1], 0.1); // q1 - q6 + EXPECT_EQ(command_values_[2], 0.2); + EXPECT_EQ(command_values_[3], 0.3); + EXPECT_EQ(command_values_[4], 0.4); + EXPECT_EQ(command_values_[5], 0.5); + EXPECT_EQ(command_values_[6], 0.6); + EXPECT_EQ(command_values_[21], 3.0); // blend radius + EXPECT_EQ(command_values_[22], 0.7); // velocity + EXPECT_EQ(command_values_[23], 1.0); // acceleration + EXPECT_EQ(command_values_[24], 2.0); // move time subscribe_and_get_messages(msg); - ASSERT_EQ(msg.set_point, 0.45); + ASSERT_EQ(msg.data, ExecutionState::IDLE); } int main(int argc, char ** argv) diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index 0ea3c40b54..9e3beec17c 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. // -// Authors: +// Authors: Mathias Fuhrer #ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ @@ -36,10 +36,14 @@ #include "rclcpp/utilities.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -// TODO(anyone): replace the state and command message types -using ControllerStateMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerStateMsg; -using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; -using ControllerModeSrvType = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerModeSrvType; +#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "std_msgs/msg/int8.hpp" +#include "motion_primitives_forward_controller/motion_type.hpp" +#include "motion_primitives_forward_controller/execution_state.hpp" +#include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" + +using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; +using ControllerStateMsg = std_msgs::msg::Int8; namespace { @@ -53,53 +57,38 @@ class TestableMotionPrimitivesForwardController : public motion_primitives_forwa FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); - FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_setting_slow_mode_service); - FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_fast); - FRIEND_TEST(MotionPrimitivesForwardControllerTest, test_update_logic_slow); - + FRIEND_TEST(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status); + public: controller_interface::CallbackReturn on_configure( const rclcpp_lifecycle::State & previous_state) override { - auto ret = motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); - // Only if on_configure is successful create subscription - if (ret == CallbackReturn::SUCCESS) - { - ref_subscriber_wait_set_.add_subscription(ref_subscriber_); - } - return ret; + return motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); } /** * @brief wait_for_command blocks until a new ControllerReferenceMsg is received. * Requires that the executor is not spinned elsewhere between the * message publication and the call to this function. - * - * @return true if new ControllerReferenceMsg msg was received, false if timeout. */ - bool wait_for_command( - rclcpp::Executor & executor, rclcpp::WaitSet & subscriber_wait_set, + void wait_for_command( + rclcpp::Executor & executor, const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) { - bool success = subscriber_wait_set.wait(timeout).kind() == rclcpp::WaitResultKind::Ready; - if (success) + auto until = get_node()->get_clock()->now() + timeout; + while (get_node()->get_clock()->now() < until) { executor.spin_some(); + std::this_thread::sleep_for(std::chrono::microseconds(10)); } - return success; } - bool wait_for_commands( + void wait_for_commands( rclcpp::Executor & executor, const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) { - return wait_for_command(executor, ref_subscriber_wait_set_, timeout); + return wait_for_command(executor, timeout); } - - // TODO(anyone): add implementation of any methods of your controller is needed - -private: - rclcpp::WaitSet ref_subscriber_wait_set_; }; // We are using template class here for easier reuse of Fixture in specializations of controllers @@ -116,11 +105,7 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test command_publisher_node_ = std::make_shared("command_publisher"); command_publisher_ = command_publisher_node_->create_publisher( - "/test_motion_primitives_forward_controller/commands", rclcpp::SystemDefaultsQoS()); - - service_caller_node_ = std::make_shared("service_caller"); - slow_control_service_client_ = service_caller_node_->create_client( - "/test_motion_primitives_forward_controller/set_slow_control_mode"); + "/test_motion_primitives_forward_controller/reference", rclcpp::SystemDefaultsQoS()); } static void TearDownTestCase() {} @@ -135,28 +120,26 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test controller_interface::return_type::OK); std::vector command_ifs; - command_itfs_.reserve(joint_command_values_.size()); - command_ifs.reserve(joint_command_values_.size()); + command_itfs_.reserve(command_values_.size()); + command_ifs.reserve(command_values_.size()); - for (size_t i = 0; i < joint_command_values_.size(); ++i) + for (size_t i = 0; i < command_values_.size(); ++i) { command_itfs_.emplace_back(hardware_interface::CommandInterface( - joint_names_[i], interface_name_, &joint_command_values_[i])); + interface_namespace_, command_interface_names_[i], &command_values_[i])); command_ifs.emplace_back(command_itfs_.back()); } - // TODO(anyone): Add other command interfaces, if any std::vector state_ifs; - state_itfs_.reserve(joint_state_values_.size()); - state_ifs.reserve(joint_state_values_.size()); + state_itfs_.reserve(state_values_.size()); + state_ifs.reserve(state_values_.size()); - for (size_t i = 0; i < joint_state_values_.size(); ++i) + for (size_t i = 0; i < state_values_.size(); ++i) { state_itfs_.emplace_back(hardware_interface::StateInterface( - joint_names_[i], interface_name_, &joint_state_values_[i])); + interface_namespace_, state_interface_names_[i], &state_values_[i])); state_ifs.emplace_back(state_itfs_.back()); } - // TODO(anyone): Add other state interfaces, if any controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); } @@ -195,12 +178,15 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test rclcpp::MessageInfo msg_info; ASSERT_TRUE(subscription->take(msg, msg_info)); } - - // TODO(anyone): add/remove arguments as it suites your command message type + void publish_commands( - const std::vector & displacements = {0.45}, - const std::vector & velocities = {0.0}, const double duration = 1.25) + const std::vector & joint_positions = {0.1, 0.2, 0.3, 0.4, 0.5, 0.6}, + double velocity = 0.7, + double acceleration = 1.0, + double move_time = 2.0, + double blend_radius = 3.0) { + std::cout << "Publishing command message ..." << std::endl; auto wait_for_topic = [&](const auto topic_name) { size_t wait_count = 0; @@ -215,57 +201,83 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test std::this_thread::sleep_for(std::chrono::milliseconds(100)); ++wait_count; } + std::cout << "Found subscriber for topic: " << topic_name << std::endl; }; - wait_for_topic(command_publisher_->get_topic_name()); + auto topic_name = command_publisher_->get_topic_name(); + std::cout << "Waiting for subscriber on topic: " << topic_name << std::endl; + wait_for_topic(topic_name); ControllerReferenceMsg msg; - msg.joint_names = joint_names_; - msg.displacements = displacements; - msg.velocities = velocities; - msg.duration = duration; - command_publisher_->publish(msg); - } - - std::shared_ptr call_service( - const bool slow_control, rclcpp::Executor & executor) - { - auto request = std::make_shared(); - request->data = slow_control; + // TODO(mathias31415): Add other tests for other motion types + msg.type = MotionType::LINEAR_JOINT; + msg.joint_positions = joint_positions; + msg.blend_radius = blend_radius; - bool wait_for_service_ret = - slow_control_service_client_->wait_for_service(std::chrono::milliseconds(500)); - EXPECT_TRUE(wait_for_service_ret); - if (!wait_for_service_ret) - { - throw std::runtime_error("Services is not available!"); - } - auto result = slow_control_service_client_->async_send_request(request); - EXPECT_EQ(executor.spin_until_future_complete(result), rclcpp::FutureReturnCode::SUCCESS); + msg.additional_arguments.resize(3); + msg.additional_arguments[0].argument_name = "velocity"; + msg.additional_arguments[0].argument_value = velocity; + msg.additional_arguments[1].argument_name = "acceleration"; + msg.additional_arguments[1].argument_value = acceleration; + msg.additional_arguments[2].argument_name = "move_time"; + msg.additional_arguments[2].argument_value = move_time; - return result.get(); + command_publisher_->publish(msg); } + protected: - // TODO(anyone): adjust the members as needed - - // Controller-related parameters - std::vector joint_names_ = {"joint1"}; - std::vector state_joint_names_ = {"joint1state"}; - std::string interface_name_ = "acceleration"; - std::array joint_state_values_ = {1.1}; - std::array joint_command_values_ = {101.101}; - - std::vector state_itfs_; - std::vector command_itfs_; - - // Test related parameters - std::unique_ptr controller_; - rclcpp::Node::SharedPtr command_publisher_node_; - rclcpp::Publisher::SharedPtr command_publisher_; - rclcpp::Node::SharedPtr service_caller_node_; - rclcpp::Client::SharedPtr slow_control_service_client_; + // Controller-related parameters + std::vector command_interface_names_ = { + "motion_type", + "q1", + "q2", + "q3", + "q4", + "q5", + "q6", + "pos_x", + "pos_y", + "pos_z", + "pos_qx", + "pos_qy", + "pos_qz", + "pos_qw", + "pos_via_x", + "pos_via_y", + "pos_via_z", + "pos_via_qx", + "pos_via_qy", + "pos_via_qz", + "pos_via_qw", + "blend_radius", + "velocity", + "acceleration", + "move_time"}; + + std::vector state_interface_names_ = { + "execution_status", + "ready_for_new_primitive"}; + + std::string interface_namespace_ = "motion_primitive"; + std::array state_values_ = {ExecutionState::IDLE, ReadyForNewPrimitive::READY}; + std::array command_values_ = { + 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101 + }; + + std::vector state_itfs_; + std::vector command_itfs_; + + // Test related parameters + std::unique_ptr controller_; + rclcpp::Node::SharedPtr command_publisher_node_; + rclcpp::Publisher::SharedPtr command_publisher_; + rclcpp::Node::SharedPtr service_caller_node_; }; #endif // TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ From d9d4c67a3e9fc971991b7550b1b3839575c9151c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 16:54:33 +0200 Subject: [PATCH 026/128] uncommented test_motion_primitives_forward_controller_preceeding implementation --- .../CMakeLists.txt | 16 +-- ...imitives_forward_controller_preceeding.cpp | 98 +++++++++---------- 2 files changed, 57 insertions(+), 57 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 3dd291754b..b19a955925 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -89,14 +89,14 @@ if(BUILD_TESTING) hardware_interface ) - # add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller_preceeding test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml) - # target_include_directories(test_motion_primitives_forward_controller_preceeding PRIVATE include) - # target_link_libraries(test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller) - # ament_target_dependencies( - # test_motion_primitives_forward_controller_preceeding - # controller_interface - # hardware_interface - # ) + add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller_preceeding test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml) + target_include_directories(test_motion_primitives_forward_controller_preceeding PRIVATE include) + target_link_libraries(test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller) + ament_target_dependencies( + test_motion_primitives_forward_controller_preceeding + controller_interface + hardware_interface + ) endif() ament_export_include_directories( diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index 1182c14ea1..ac3dd3f305 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -14,64 +14,64 @@ // // Authors: -// #include "test_motion_primitives_forward_controller.hpp" +#include "test_motion_primitives_forward_controller.hpp" -// #include -// #include -// #include -// #include -// #include +#include +#include +#include +#include +#include -// using motion_primitives_forward_controller::CMD_MY_ITFS; -// using motion_primitives_forward_controller::control_mode_type; -// using motion_primitives_forward_controller::STATE_MY_ITFS; +using motion_primitives_forward_controller::CMD_MY_ITFS; +using motion_primitives_forward_controller::control_mode_type; +using motion_primitives_forward_controller::STATE_MY_ITFS; -// class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture -// { -// }; +class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +{ +}; -// TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) -// { -// SetUpController(); +TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success) +{ + SetUpController(); -// ASSERT_TRUE(controller_->params_.joints.empty()); -// ASSERT_TRUE(controller_->params_.state_joints.empty()); -// ASSERT_TRUE(controller_->params_.interface_name.empty()); + ASSERT_TRUE(controller_->params_.joints.empty()); + ASSERT_TRUE(controller_->params_.state_joints.empty()); + ASSERT_TRUE(controller_->params_.interface_name.empty()); -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); -// ASSERT_THAT(controller_->params_.state_joints, testing::ElementsAreArray(state_joint_names_)); -// ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(state_joint_names_)); -// ASSERT_EQ(controller_->params_.interface_name, interface_name_); -// } + ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); + ASSERT_THAT(controller_->params_.state_joints, testing::ElementsAreArray(state_joint_names_)); + ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(state_joint_names_)); + ASSERT_EQ(controller_->params_.interface_name, interface_name_); +} -// TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) -// { -// SetUpController(); +TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +{ + SetUpController(); -// ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); -// auto command_intefaces = controller_->command_interface_configuration(); -// ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); -// for (size_t i = 0; i < command_intefaces.names.size(); ++i) -// { -// EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); -// } + auto command_intefaces = controller_->command_interface_configuration(); + ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); + for (size_t i = 0; i < command_intefaces.names.size(); ++i) + { + EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + } -// auto state_intefaces = controller_->state_interface_configuration(); -// ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); -// for (size_t i = 0; i < state_intefaces.names.size(); ++i) -// { -// EXPECT_EQ(state_intefaces.names[i], state_joint_names_[i] + "/" + interface_name_); -// } -// } + auto state_intefaces = controller_->state_interface_configuration(); + ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); + for (size_t i = 0; i < state_intefaces.names.size(); ++i) + { + EXPECT_EQ(state_intefaces.names[i], state_joint_names_[i] + "/" + interface_name_); + } +} -// int main(int argc, char ** argv) -// { -// ::testing::InitGoogleTest(&argc, argv); -// rclcpp::init(argc, argv); -// int result = RUN_ALL_TESTS(); -// rclcpp::shutdown(); -// return result; -// } +int main(int argc, char ** argv) +{ + ::testing::InitGoogleTest(&argc, argv); + rclcpp::init(argc, argv); + int result = RUN_ALL_TESTS(); + rclcpp::shutdown(); + return result; +} From e76a8d07fa0cb470464e06f84bf3e78e22bdb4fb Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 16:59:58 +0200 Subject: [PATCH 027/128] changed test_motion_primitives_forward_controller_preceeding implementation from rtw template to fit the controller implementation --- ..._forward_controller_preceeding_params.yaml | 38 +++++++++++++++---- ...imitives_forward_controller_preceeding.cpp | 24 ++++++------ 2 files changed, 42 insertions(+), 20 deletions(-) diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index e3113c2042..d01d9bfdea 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -1,9 +1,33 @@ test_motion_primitives_forward_controller: ros__parameters: - joints: - - joint1 - - interface_name: acceleration - - state_joints: - - joint1state + name: motion_primitive + command_interfaces: + - motion_type + - q1 + - q2 + - q3 + - q4 + - q5 + - q6 + - pos_x + - pos_y + - pos_z + - pos_qx + - pos_qy + - pos_qz + - pos_qw + - pos_via_x + - pos_via_y + - pos_via_z + - pos_via_qx + - pos_via_qy + - pos_via_qz + - pos_via_qw + - blend_radius + - velocity + - acceleration + - move_time + state_interfaces: + - execution_status + - ready_for_new_primitive + queue_size: 20 # queue size to buffer incoming commands \ No newline at end of file diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index ac3dd3f305..348f10fbdb 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. // -// Authors: +// Authors: Mathias Fuhrer #include "test_motion_primitives_forward_controller.hpp" @@ -23,7 +23,6 @@ #include using motion_primitives_forward_controller::CMD_MY_ITFS; -using motion_primitives_forward_controller::control_mode_type; using motion_primitives_forward_controller::STATE_MY_ITFS; class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture @@ -34,16 +33,15 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe { SetUpController(); - ASSERT_TRUE(controller_->params_.joints.empty()); - ASSERT_TRUE(controller_->params_.state_joints.empty()); - ASSERT_TRUE(controller_->params_.interface_name.empty()); + ASSERT_TRUE(controller_->params_.command_interfaces.empty()); + ASSERT_TRUE(controller_->params_.state_interfaces.empty()); + ASSERT_TRUE(controller_->params_.name.empty()); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_THAT(controller_->params_.joints, testing::ElementsAreArray(joint_names_)); - ASSERT_THAT(controller_->params_.state_joints, testing::ElementsAreArray(state_joint_names_)); - ASSERT_THAT(controller_->state_joints_, testing::ElementsAreArray(state_joint_names_)); - ASSERT_EQ(controller_->params_.interface_name, interface_name_); + ASSERT_THAT(controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + ASSERT_THAT(controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + ASSERT_EQ(controller_->params_.name, interface_namespace_); } TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) @@ -53,17 +51,17 @@ TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); auto command_intefaces = controller_->command_interface_configuration(); - ASSERT_EQ(command_intefaces.names.size(), joint_command_values_.size()); + ASSERT_EQ(command_intefaces.names.size(), command_values_.size()); for (size_t i = 0; i < command_intefaces.names.size(); ++i) { - EXPECT_EQ(command_intefaces.names[i], joint_names_[i] + "/" + interface_name_); + EXPECT_EQ(command_intefaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); } auto state_intefaces = controller_->state_interface_configuration(); - ASSERT_EQ(state_intefaces.names.size(), joint_state_values_.size()); + ASSERT_EQ(state_intefaces.names.size(), state_values_.size()); for (size_t i = 0; i < state_intefaces.names.size(); ++i) { - EXPECT_EQ(state_intefaces.names[i], state_joint_names_[i] + "/" + interface_name_); + EXPECT_EQ(state_intefaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); } } From 11bec4d2c835792087dd665951863d844a11830d Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 17:18:33 +0200 Subject: [PATCH 028/128] moved reset_controller_reference_msg into motion_primitives_forward_controller namespace --- .../motion_primitives_forward_controller.hpp | 1 + .../motion_primitives_forward_controller.cpp | 47 +++++++++---------- 2 files changed, 23 insertions(+), 25 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 8357c39825..58aa43a996 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -90,6 +90,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle // std::atomic new_msg_available_ = false; // flag to indicate if new message is available void reset_command_interfaces(); // Reset all command interfaces to NaN() bool set_command_interfaces(); // Set command interfaces from the message + void reset_controller_reference_msg(std::shared_ptr & msg); size_t queue_size_ = 0; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index a17ee48a3a..5e603ba82e 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -43,31 +43,6 @@ static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, false}; -using ControllerReferenceMsg = motion_primitives_forward_controller::MotionPrimitivesForwardController::ControllerReferenceMsg; - -// reset the controller reference message to NaN -void reset_controller_reference_msg(std::shared_ptr & msg) -{ - msg->type = 0; - msg->blend_radius = std::numeric_limits::quiet_NaN(); - - for (auto & arg : msg->additional_arguments) { - arg.argument_name = ""; - arg.argument_value = std::numeric_limits::quiet_NaN(); - } - - for (auto & pose : msg->poses) { - pose.pose.position.x = std::numeric_limits::quiet_NaN(); - pose.pose.position.y = std::numeric_limits::quiet_NaN(); - pose.pose.position.z = std::numeric_limits::quiet_NaN(); - - pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); - } -} - } // namespace @@ -427,6 +402,28 @@ bool MotionPrimitivesForwardController::set_command_interfaces() return true; } +// reset the controller reference message to NaN +void MotionPrimitivesForwardController::reset_controller_reference_msg(std::shared_ptr & msg) +{ + msg->type = 0; + msg->blend_radius = std::numeric_limits::quiet_NaN(); + + for (auto & arg : msg->additional_arguments) { + arg.argument_name = ""; + arg.argument_value = std::numeric_limits::quiet_NaN(); + } + + for (auto & pose : msg->poses) { + pose.pose.position.x = std::numeric_limits::quiet_NaN(); + pose.pose.position.y = std::numeric_limits::quiet_NaN(); + pose.pose.position.z = std::numeric_limits::quiet_NaN(); + + pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); + } +} } // namespace motion_primitives_forward_controller From 6c98434de963a93a05a0a849a7c55ee387f2ff08 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 17:19:23 +0200 Subject: [PATCH 029/128] changed get_value() to get_optional() --- .../src/motion_primitives_forward_controller.cpp | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 5e603ba82e..92d3f57a80 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -254,7 +254,12 @@ controller_interface::return_type MotionPrimitivesForwardController::update( { // read the status from the state interface // TODO(mathias31415) Is check needed if the value is .0? - uint8_t execution_status = static_cast(std::round(state_interfaces_[0].get_value())); + auto opt_value_execution = state_interfaces_[0].get_optional(); + if (!opt_value_execution.has_value()) { + RCLCPP_ERROR(get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); + return controller_interface::return_type::ERROR; + } + uint8_t execution_status = static_cast(std::round(opt_value_execution.value())); switch (execution_status) { case ExecutionState::IDLE: @@ -289,7 +294,12 @@ controller_interface::return_type MotionPrimitivesForwardController::update( state_publisher_->unlockAndPublish(); // TODO(mathias31415) Is check needed if the value is .0? - uint8_t ready_for_new_primitive = static_cast(std::round(state_interfaces_[1].get_value())); + auto opt_value_ready = state_interfaces_[1].get_optional(); + if (!opt_value_ready.has_value()) { + RCLCPP_ERROR(get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); + return controller_interface::return_type::ERROR; + } + uint8_t ready_for_new_primitive = static_cast(std::round(opt_value_ready.value())); // sending new command? if(!msg_queue_.empty()) // check if new command is available From d2ef095c66fb2e948456d5e36facd77b9945b17f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 17:33:44 +0200 Subject: [PATCH 030/128] cleanup on comments and commented code --- .../CMakeLists.txt | 7 ----- .../motion_primitives_forward_controller.hpp | 15 +++------ .../motion_type.hpp | 7 ++--- ...imitives_forward_controller_parameters.hpp | 2 -- .../motion_primitives_forward_controller.cpp | 31 ++++++------------- ...d_motion_primitives_forward_controller.cpp | 3 +- 6 files changed, 17 insertions(+), 48 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index b19a955925..9dfb4ccb26 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -5,7 +5,6 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") add_compile_options(-Wall -Wextra -Werror=conversion -Werror=unused-but-set-variable -Werror=return-type -Werror=shadow) endif() -# find dependencies set(THIS_PACKAGE_INCLUDE_DEPENDS control_msgs controller_interface @@ -28,7 +27,6 @@ foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() -# Add motion_primitives_forward_controller library related compile commands generate_parameter_library(motion_primitives_forward_controller_parameters src/motion_primitives_forward_controller.yaml include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp @@ -59,11 +57,6 @@ install( LIBRARY DESTINATION lib ) -# install( -# DIRECTORY include/ -# DESTINATION include/${PROJECT_NAME} -# ) - install( DIRECTORY include/ DESTINATION include diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 58aa43a996..1014caeb2e 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -64,7 +64,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - // state and command message types using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; using ControllerStateMsg = std_msgs::msg::Int8; @@ -73,9 +72,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::shared_ptr param_listener_; motion_primitives_forward_controller::Params params_; - // Command subscribers and Controller State publisher rclcpp::Subscription::SharedPtr ref_subscriber_ = nullptr; - // realtime_tools::RealtimeBuffer> input_ref_; using ControllerStatePublisher = realtime_tools::RealtimePublisher; @@ -85,18 +82,14 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::queue> msg_queue_; private: - // callback for topic interface - void reference_callback(const std::shared_ptr msg); // callback for reference message - // std::atomic new_msg_available_ = false; // flag to indicate if new message is available - void reset_command_interfaces(); // Reset all command interfaces to NaN() - bool set_command_interfaces(); // Set command interfaces from the message + void reference_callback(const std::shared_ptr msg); + void reset_command_interfaces(); + bool set_command_interfaces(); void reset_controller_reference_msg(std::shared_ptr & msg); size_t queue_size_ = 0; - std::mutex command_mutex_; - - bool print_error_once_ = true; // Flag to print error message only once if ExecutionState::ERROR + bool print_error_once_ = true; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp index 9074f4d45b..e4f779db6f 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp @@ -25,9 +25,8 @@ namespace MotionType static constexpr uint8_t CIRCULAR_CARTESIAN = 51; // Helper types - static constexpr uint8_t STOP_MOTION = 66; // added to stop motion - static constexpr uint8_t MOTION_SEQUENCE_START = 100; // added to indicate motion sequence instead of executing single primitives - static constexpr uint8_t MOTION_SEQUENCE_END = 101; // added to indicate end of motion sequence + static constexpr uint8_t STOP_MOTION = 66; + static constexpr uint8_t MOTION_SEQUENCE_START = 100; //indicate motion sequence instead of executing single primitives + static constexpr uint8_t MOTION_SEQUENCE_END = 101; } - #endif // MOTION_TYPE_HPP diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp index aad3111815..28078ca83c 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp @@ -11,8 +11,6 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -// -// Authors: #ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ #define MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 92d3f57a80..f95887168c 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -13,7 +13,6 @@ // limitations under the License. // // Authors: Mathias Fuhrer -// #include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" @@ -42,7 +41,6 @@ static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, false}; - } // namespace @@ -101,6 +99,8 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi ref_subscriber_ = get_node()->create_subscription( "~/reference", subscribers_qos, std::bind(&MotionPrimitivesForwardController::reference_callback, this, std::placeholders::_1)); + RCLCPP_INFO(get_node()->get_logger(), "Subscribed to reference topic: %s", ref_subscriber_->get_topic_name()); + std::shared_ptr msg = std::make_shared(); reset_controller_reference_msg(msg); @@ -138,9 +138,9 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr { case MotionType::STOP_MOTION:{ RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); - reset_command_interfaces(); // Reset all command interfaces to NaN + reset_command_interfaces(); std::lock_guard guard(command_mutex_); - (void)command_interfaces_[0].set_value(static_cast(msg->type)); // send stop command to the driver + (void)command_interfaces_[0].set_value(static_cast(msg->type)); // send stop command immediately to the hw-interface while (!msg_queue_.empty()) { // clear the queue msg_queue_.pop(); } @@ -149,7 +149,6 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); - // Check if joint positions are provided if (msg->joint_positions.empty()) { RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_JOINT motion type without joint positions"); return; @@ -158,7 +157,6 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr case MotionType::LINEAR_CARTESIAN: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_CARTESIAN (LIN)"); - // Check if poses are provided if (msg->poses.empty()) { RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_CARTESIAN motion type without poses"); return; @@ -167,7 +165,6 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr case MotionType::CIRCULAR_CARTESIAN: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: CIRCULAR_CARTESIAN (CIRC)"); - // Check if poses are provided if (msg->poses.size() != 2) { RCLCPP_ERROR(get_node()->get_logger(), "Received CIRCULAR_CARTESIAN motion type without two poses"); return; @@ -182,13 +179,11 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_END"); break; - // Additional motion types can be added here default: RCLCPP_ERROR(get_node()->get_logger(), "Received unknown motion type: %u", msg->type); return; } - // Check if the queue size is exceeded if (msg_queue_.size() >= queue_size_) { RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); return; @@ -203,13 +198,11 @@ controller_interface::InterfaceConfiguration MotionPrimitivesForwardController:: controller_interface::InterfaceConfiguration command_interfaces_config; command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - // Reserve memory for the command interfaces command_interfaces_config.names.reserve(params_.command_interfaces.size()); // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - // Combine the joint with the interface name and add it to the list command_interfaces_config.names.push_back(params_.name + "/" + interface_name); } return command_interfaces_config; @@ -220,13 +213,11 @@ controller_interface::InterfaceConfiguration MotionPrimitivesForwardController:: controller_interface::InterfaceConfiguration state_interfaces_config; state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; - // Reserve memory for the state interfaces state_interfaces_config.names.reserve(params_.state_interfaces.size()); // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - // Combine the joint with the interface name and add it to the list state_interfaces_config.names.push_back(params_.name + "/" + interface_name); } return state_interfaces_config; @@ -235,7 +226,7 @@ controller_interface::InterfaceConfiguration MotionPrimitivesForwardController:: controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activate( const rclcpp_lifecycle::State & /*previous_state*/) { - reset_command_interfaces(); // Reset all command interfaces to NaN + reset_command_interfaces(); RCLCPP_INFO(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -243,7 +234,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_deactivate( const rclcpp_lifecycle::State & /*previous_state*/) { - reset_command_interfaces(); // Reset all command interfaces to NaN + reset_command_interfaces(); RCLCPP_INFO(get_node()->get_logger(), "Controller deactivated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -253,7 +244,6 @@ controller_interface::return_type MotionPrimitivesForwardController::update( const rclcpp::Time & time, const rclcpp::Duration & /*period*/) { // read the status from the state interface - // TODO(mathias31415) Is check needed if the value is .0? auto opt_value_execution = state_interfaces_[0].get_optional(); if (!opt_value_execution.has_value()) { RCLCPP_ERROR(get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); @@ -293,7 +283,6 @@ controller_interface::return_type MotionPrimitivesForwardController::update( state_publisher_->msg_.data = execution_status; state_publisher_->unlockAndPublish(); - // TODO(mathias31415) Is check needed if the value is .0? auto opt_value_ready = state_interfaces_[1].get_optional(); if (!opt_value_ready.has_value()) { RCLCPP_ERROR(get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); @@ -301,15 +290,14 @@ controller_interface::return_type MotionPrimitivesForwardController::update( } uint8_t ready_for_new_primitive = static_cast(std::round(opt_value_ready.value())); - // sending new command? if(!msg_queue_.empty()) // check if new command is available { switch (ready_for_new_primitive) { - case ReadyForNewPrimitive::NOT_READY:{ // hw-interface is not ready for a new command + case ReadyForNewPrimitive::NOT_READY:{ return controller_interface::return_type::OK; } - case ReadyForNewPrimitive::READY:{ // hw-interface is ready for a new command - if(!set_command_interfaces()){ // Set the command interfaces with next motion primitive + case ReadyForNewPrimitive::READY:{ + if(!set_command_interfaces()){ RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); return controller_interface::return_type::ERROR; } @@ -386,7 +374,6 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } } - // Set blend_radius (void)command_interfaces_[21].set_value(current_ref->blend_radius); // blend_radius // Read additional arguments diff --git a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp index a7bb555bd0..f80bf960f0 100644 --- a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp @@ -11,8 +11,7 @@ // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. -// -// Authors: + #include #include From 7c4f1674a032ddc8ee3541f24d0a7cab18926ada Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 5 May 2025 17:44:09 +0200 Subject: [PATCH 031/128] clarified motion primitive publishing to ~/reference topic --- motion_primitives_forward_controller/README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 0d5215e491..0426f7839f 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -26,7 +26,8 @@ For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobot 1. **Command Reception** - Python scripts can publish motion primitives to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. + Motion primitives can be published to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. + This can be done, for example, via a Python script as demonstrated in the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives.py) package. 2. **Command Handling Logic** - If the received primitive is of type `STOP_MOTION`, it is directly forwarded to the hardware interface through the command interface, and all queued primitives in the controller are discarded. From 59ecb5babc13d8c28d711c0638372e54e53cf1d9 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 6 May 2025 08:56:46 +0200 Subject: [PATCH 032/128] pre-commit fixes --- .../CMakeLists.txt | 38 ++- .../README.md | 12 +- .../execution_state.hpp | 19 +- .../motion_primitives_forward_controller.hpp | 14 +- .../motion_type.hpp | 29 +-- .../ready_for_new_primitive.hpp | 15 +- ...imitives_forward_controller_parameters.hpp | 8 +- .../motion_primitives_forward_controller.cpp | 238 ++++++++++-------- ..._primitives_forward_controller_params.yaml | 2 +- ..._forward_controller_preceeding_params.yaml | 2 +- ...d_motion_primitives_forward_controller.cpp | 7 +- ...t_motion_primitives_forward_controller.cpp | 16 +- ...t_motion_primitives_forward_controller.hpp | 117 ++++----- ...imitives_forward_controller_preceeding.cpp | 11 +- 14 files changed, 284 insertions(+), 244 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 9dfb4ccb26..5c11dd3850 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -63,9 +63,13 @@ install( ) if(BUILD_TESTING) - - ament_add_gmock(test_load_motion_primitives_forward_controller test/test_load_motion_primitives_forward_controller.cpp) - target_include_directories(test_load_motion_primitives_forward_controller PRIVATE include) + ament_add_gmock( + test_load_motion_primitives_forward_controller + test/test_load_motion_primitives_forward_controller.cpp + ) + target_include_directories( + test_load_motion_primitives_forward_controller PRIVATE include + ) ament_target_dependencies( test_load_motion_primitives_forward_controller controller_manager @@ -73,18 +77,34 @@ if(BUILD_TESTING) ros2_control_test_assets ) - add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller test/test_motion_primitives_forward_controller.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml) - target_include_directories(test_motion_primitives_forward_controller PRIVATE include) - target_link_libraries(test_motion_primitives_forward_controller motion_primitives_forward_controller) + add_rostest_with_parameters_gmock( + test_motion_primitives_forward_controller + test/test_motion_primitives_forward_controller.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml + ) + target_include_directories( + test_motion_primitives_forward_controller PRIVATE include + ) + target_link_libraries( + test_motion_primitives_forward_controller motion_primitives_forward_controller + ) ament_target_dependencies( test_motion_primitives_forward_controller controller_interface hardware_interface ) - add_rostest_with_parameters_gmock(test_motion_primitives_forward_controller_preceeding test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml) - target_include_directories(test_motion_primitives_forward_controller_preceeding PRIVATE include) - target_link_libraries(test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller) + add_rostest_with_parameters_gmock( + test_motion_primitives_forward_controller_preceeding + test/test_motion_primitives_forward_controller_preceeding.cpp + ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml + ) + target_include_directories( + test_motion_primitives_forward_controller_preceeding PRIVATE include + ) + target_link_libraries( + test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller + ) ament_target_dependencies( test_motion_primitives_forward_controller_preceeding controller_interface diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 0426f7839f..e301e690fb 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -25,20 +25,20 @@ For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobot ![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png) -1. **Command Reception** - Motion primitives can be published to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. +1. **Command Reception** + Motion primitives can be published to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. This can be done, for example, via a Python script as demonstrated in the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives.py) package. -2. **Command Handling Logic** +2. **Command Handling Logic** - If the received primitive is of type `STOP_MOTION`, it is directly forwarded to the hardware interface through the command interface, and all queued primitives in the controller are discarded. - If the primitive is of any other type, it is appended to the internal motion primitive queue. The maximum queue size is configurable via a YAML configuration file. -3. **Motion Execution Flow** +3. **Motion Execution Flow** The `update()` method in the controller: - Reads the current `execution_state` from the hardware interface via the state interface and publishes it to the `~/state` topic. - Reads the `ready_for_new_primitive` state flag. If `true`, the next primitive from the queue is sent to the hardware interface for execution. -4. **Sequencing Logic** +4. **Sequencing Logic** Sequencing logic for grouped execution (between `MOTION_SEQUENCE_START` and `MOTION_SEQUENCE_END`) is handled within the hardware interface layer. The controller itself only manages queueing and forwarding logic. @@ -46,4 +46,4 @@ For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobot - [industrial_robot_motion_interfaces (with additional helper types for stop and motion sequence)](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) - [ros2_controllers with motion_primitives_forward_controller](https://github.com/StoglRobotics-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) - [Universal_Robots_ROS2_Driver with motion_primitive_ur_driver](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) -- [Universal_Robots_Client_Library with movec from urfeex](https://github.com/urfeex/Universal_Robots_Client_Library/tree/movec_movep) \ No newline at end of file +- [Universal_Robots_Client_Library with movec from urfeex](https://github.com/urfeex/Universal_Robots_Client_Library/tree/movec_movep) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp index 38c1458365..df8ca79f45 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -14,16 +14,15 @@ // // Authors: Mathias Fuhrer -#ifndef EXECUTION_STATE_HPP -#define EXECUTION_STATE_HPP - +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ namespace ExecutionState { - static constexpr uint8_t IDLE = 0; - static constexpr uint8_t EXECUTING = 1; - static constexpr uint8_t SUCCESS = 2; - static constexpr uint8_t ERROR = 3; -} +static constexpr uint8_t IDLE = 0; +static constexpr uint8_t EXECUTING = 1; +static constexpr uint8_t SUCCESS = 2; +static constexpr uint8_t ERROR = 3; +} // namespace ExecutionState -#endif // EXECUTION_STATE_HPP +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 1014caeb2e..e7f1a4a01c 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -18,12 +18,12 @@ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #include +#include #include #include -#include -#include "controller_interface/controller_interface.hpp" #include +#include "controller_interface/controller_interface.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" @@ -32,7 +32,6 @@ #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" #include "std_msgs/msg/int8.hpp" - namespace motion_primitives_forward_controller { // name constants for state interfaces @@ -64,9 +63,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; - using ControllerStateMsg = std_msgs::msg::Int8; - + using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; + using ControllerStateMsg = std_msgs::msg::Int8; protected: std::shared_ptr param_listener_; @@ -87,7 +85,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool set_command_interfaces(); void reset_controller_reference_msg(std::shared_ptr & msg); - size_t queue_size_ = 0; + size_t queue_size_ = 0; std::mutex command_mutex_; bool print_error_once_ = true; }; diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp index e4f779db6f..38fa3cfe46 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -14,19 +14,20 @@ // // Authors: Mathias Fuhrer -#ifndef MOTION_TYPE_HPP -#define MOTION_TYPE_HPP - +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ namespace MotionType -{ // Motion Primitives - static constexpr uint8_t LINEAR_JOINT = 10; // changed to 10 because 0 is default value - static constexpr uint8_t LINEAR_CARTESIAN = 50; - static constexpr uint8_t CIRCULAR_CARTESIAN = 51; +{ +// Motion Primitives +static constexpr uint8_t LINEAR_JOINT = 10; // changed to 10 because 0 is default value +static constexpr uint8_t LINEAR_CARTESIAN = 50; +static constexpr uint8_t CIRCULAR_CARTESIAN = 51; - // Helper types - static constexpr uint8_t STOP_MOTION = 66; - static constexpr uint8_t MOTION_SEQUENCE_START = 100; //indicate motion sequence instead of executing single primitives - static constexpr uint8_t MOTION_SEQUENCE_END = 101; -} -#endif // MOTION_TYPE_HPP +// Helper types +static constexpr uint8_t STOP_MOTION = 66; +// indicate motion sequence instead of executing single primitives +static constexpr uint8_t MOTION_SEQUENCE_START = 100; +static constexpr uint8_t MOTION_SEQUENCE_END = 101; +} // namespace MotionType +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp index f8054f3dbc..3a487b7463 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -14,14 +14,13 @@ // // Authors: Mathias Fuhrer -#ifndef READY_FOR_NEW_PRIMITIVE_HPP -#define READY_FOR_NEW_PRIMITIVE_HPP - +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ namespace ReadyForNewPrimitive { - static constexpr uint8_t NOT_READY = 0; - static constexpr uint8_t READY = 1; -} +static constexpr uint8_t NOT_READY = 0; +static constexpr uint8_t READY = 1; +} // namespace ReadyForNewPrimitive -#endif // READY_FOR_NEW_PRIMITIVE_HPP +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp index 28078ca83c..c2ff279035 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ -#define MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ #include @@ -35,4 +35,4 @@ Result forbidden_interface_name_prefix(rclcpp::Parameter const & parameter) } // namespace parameter_traits -#endif // MOTION_PRIMITIVES_CONTTROLLER_PKG__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index f95887168c..a32993bc03 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -22,8 +22,8 @@ #include #include "controller_interface/helpers.hpp" -#include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/execution_state.hpp" +#include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" namespace @@ -43,10 +43,12 @@ static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { false}; } // namespace - namespace motion_primitives_forward_controller { -MotionPrimitivesForwardController::MotionPrimitivesForwardController() : controller_interface::ControllerInterface() {} +MotionPrimitivesForwardController::MotionPrimitivesForwardController() +: controller_interface::ControllerInterface() +{ +} controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init() { @@ -54,7 +56,8 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init( try { - param_listener_ = std::make_shared(get_node()); + param_listener_ = + std::make_shared(get_node()); } catch (const std::exception & e) { @@ -73,20 +76,24 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi params_ = param_listener_->get_params(); // Check if the name is not empty - if (params_.name.empty()) { + if (params_.name.empty()) + { RCLCPP_ERROR(get_node()->get_logger(), "Error: A name must be provided!"); return controller_interface::CallbackReturn::ERROR; } // Check if there are exactly 25 command interfaces - if (params_.command_interfaces.size() !=25) { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time - RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly 25 command interfaces must be provided!"); + if (params_.command_interfaces.size() != 25) + { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Exactly 25 command interfaces must be provided!"); return controller_interface::CallbackReturn::ERROR; } // Check if there are exactly 2 state interfaces - if (params_.state_interfaces.size() != 2) { // execution_status + ready_for_new_primitive - RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly one state interface must be provided!"); + if (params_.state_interfaces.size() != 2) + { // execution_status + ready_for_new_primitive + RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly two state interfaces must be provided!"); return controller_interface::CallbackReturn::ERROR; } @@ -99,14 +106,16 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi ref_subscriber_ = get_node()->create_subscription( "~/reference", subscribers_qos, std::bind(&MotionPrimitivesForwardController::reference_callback, this, std::placeholders::_1)); - RCLCPP_INFO(get_node()->get_logger(), "Subscribed to reference topic: %s", ref_subscriber_->get_topic_name()); - + RCLCPP_INFO( + get_node()->get_logger(), "Subscribed to reference topic: %s", + ref_subscriber_->get_topic_name()); std::shared_ptr msg = std::make_shared(); reset_controller_reference_msg(msg); queue_size_ = params_.queue_size; - if (queue_size_ == 0) { + if (queue_size_ == 0) + { RCLCPP_ERROR(get_node()->get_logger(), "Error: Queue size must be greater than 0!"); return controller_interface::CallbackReturn::ERROR; } @@ -131,42 +140,52 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi } // Function gets called when a new message is received -void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr msg) +void MotionPrimitivesForwardController::reference_callback( + const std::shared_ptr msg) { // Check if the type is one of the allowed motion types switch (msg->type) { - case MotionType::STOP_MOTION:{ + case MotionType::STOP_MOTION: + { RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); reset_command_interfaces(); std::lock_guard guard(command_mutex_); - (void)command_interfaces_[0].set_value(static_cast(msg->type)); // send stop command immediately to the hw-interface - while (!msg_queue_.empty()) { // clear the queue - msg_queue_.pop(); + (void)command_interfaces_[0].set_value( + static_cast(msg->type)); // send stop command immediately to the hw-interface + while (!msg_queue_.empty()) + { // clear the queue + msg_queue_.pop(); } return; } case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); - if (msg->joint_positions.empty()) { - RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_JOINT motion type without joint positions"); + if (msg->joint_positions.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "Received LINEAR_JOINT motion type without joint positions"); return; - } + } break; case MotionType::LINEAR_CARTESIAN: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_CARTESIAN (LIN)"); - if (msg->poses.empty()) { - RCLCPP_ERROR(get_node()->get_logger(), "Received LINEAR_CARTESIAN motion type without poses"); + if (msg->poses.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "Received LINEAR_CARTESIAN motion type without poses"); return; } break; case MotionType::CIRCULAR_CARTESIAN: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: CIRCULAR_CARTESIAN (CIRC)"); - if (msg->poses.size() != 2) { - RCLCPP_ERROR(get_node()->get_logger(), "Received CIRCULAR_CARTESIAN motion type without two poses"); + if (msg->poses.size() != 2) + { + RCLCPP_ERROR( + get_node()->get_logger(), "Received CIRCULAR_CARTESIAN motion type without two poses"); return; } break; @@ -184,7 +203,8 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr return; } - if (msg_queue_.size() >= queue_size_) { + if (msg_queue_.size() >= queue_size_) + { RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); return; } @@ -192,8 +212,8 @@ void MotionPrimitivesForwardController::reference_callback(const std::shared_ptr msg_queue_.push(msg); } - -controller_interface::InterfaceConfiguration MotionPrimitivesForwardController::command_interface_configuration() const +controller_interface::InterfaceConfiguration +MotionPrimitivesForwardController::command_interface_configuration() const { controller_interface::InterfaceConfiguration command_interfaces_config; command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; @@ -203,12 +223,13 @@ controller_interface::InterfaceConfiguration MotionPrimitivesForwardController:: // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - command_interfaces_config.names.push_back(params_.name + "/" + interface_name); + command_interfaces_config.names.push_back(params_.name + "/" + interface_name); } return command_interfaces_config; } -controller_interface::InterfaceConfiguration MotionPrimitivesForwardController::state_interface_configuration() const +controller_interface::InterfaceConfiguration +MotionPrimitivesForwardController::state_interface_configuration() const { controller_interface::InterfaceConfiguration state_interfaces_config; state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; @@ -218,7 +239,7 @@ controller_interface::InterfaceConfiguration MotionPrimitivesForwardController:: // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - state_interfaces_config.names.push_back(params_.name + "/" + interface_name); + state_interfaces_config.names.push_back(params_.name + "/" + interface_name); } return state_interfaces_config; } @@ -239,19 +260,21 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_deact return controller_interface::CallbackReturn::SUCCESS; } - controller_interface::return_type MotionPrimitivesForwardController::update( const rclcpp::Time & time, const rclcpp::Duration & /*period*/) { // read the status from the state interface auto opt_value_execution = state_interfaces_[0].get_optional(); - if (!opt_value_execution.has_value()) { - RCLCPP_ERROR(get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); + if (!opt_value_execution.has_value()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); return controller_interface::return_type::ERROR; } uint8_t execution_status = static_cast(std::round(opt_value_execution.value())); - switch (execution_status) { + switch (execution_status) + { case ExecutionState::IDLE: // RCLCPP_INFO(get_node()->get_logger(), "Execution state: IDLE"); print_error_once_ = true; @@ -267,14 +290,16 @@ controller_interface::return_type MotionPrimitivesForwardController::update( break; case ExecutionState::ERROR: - if (print_error_once_) { + if (print_error_once_) + { RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); print_error_once_ = false; } break; - + default: - RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); return controller_interface::return_type::ERROR; } @@ -284,27 +309,35 @@ controller_interface::return_type MotionPrimitivesForwardController::update( state_publisher_->unlockAndPublish(); auto opt_value_ready = state_interfaces_[1].get_optional(); - if (!opt_value_ready.has_value()) { - RCLCPP_ERROR(get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); + if (!opt_value_ready.has_value()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); return controller_interface::return_type::ERROR; } uint8_t ready_for_new_primitive = static_cast(std::round(opt_value_ready.value())); - if(!msg_queue_.empty()) // check if new command is available - { - switch (ready_for_new_primitive) { - case ReadyForNewPrimitive::NOT_READY:{ + if (!msg_queue_.empty()) // check if new command is available + { + switch (ready_for_new_primitive) + { + case ReadyForNewPrimitive::NOT_READY: + { return controller_interface::return_type::OK; } - case ReadyForNewPrimitive::READY:{ - if(!set_command_interfaces()){ + case ReadyForNewPrimitive::READY: + { + if (!set_command_interfaces()) + { RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); return controller_interface::return_type::ERROR; } return controller_interface::return_type::OK; } default: - RCLCPP_ERROR(get_node()->get_logger(), "Error: Unknown state for ready_for_new_primitive: %d", ready_for_new_primitive); + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Unknown state for ready_for_new_primitive: %d", + ready_for_new_primitive); return controller_interface::return_type::ERROR; } } @@ -316,7 +349,8 @@ void MotionPrimitivesForwardController::reset_command_interfaces() { for (size_t i = 0; i < command_interfaces_.size(); ++i) { - if (!command_interfaces_[i].set_value(std::numeric_limits::quiet_NaN())) { + if (!command_interfaces_[i].set_value(std::numeric_limits::quiet_NaN())) + { RCLCPP_ERROR(get_node()->get_logger(), "Failed to reset command interface %ld", i); } } @@ -331,94 +365,99 @@ bool MotionPrimitivesForwardController::set_command_interfaces() msg_queue_.pop(); // Check if the message is valid - if (!current_ref){ + if (!current_ref) + { RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); return false; } // Set the motion_type - (void)command_interfaces_[0].set_value(static_cast(current_ref->type)); + (void)command_interfaces_[0].set_value(static_cast(current_ref->type)); // Process joint positions if available if (!current_ref->joint_positions.empty()) { for (size_t i = 0; i < current_ref->joint_positions.size(); ++i) { - (void)command_interfaces_[i + 1].set_value(current_ref->joint_positions[i]); // q1 to q6 + (void)command_interfaces_[i + 1].set_value(current_ref->joint_positions[i]); // q1 to q6 } } - + // Process Cartesian poses if available if (!current_ref->poses.empty()) { - const auto & goal_pose = current_ref->poses[0].pose; // goal pose - (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x - (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y - (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z - (void)command_interfaces_[10].set_value(goal_pose.orientation.x); // pos_qx - (void)command_interfaces_[11].set_value(goal_pose.orientation.y); // pos_qy - (void)command_interfaces_[12].set_value(goal_pose.orientation.z); // pos_qz - (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw + const auto & goal_pose = current_ref->poses[0].pose; // goal pose + (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x + (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y + (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z + (void)command_interfaces_[10].set_value(goal_pose.orientation.x); // pos_qx + (void)command_interfaces_[11].set_value(goal_pose.orientation.y); // pos_qy + (void)command_interfaces_[12].set_value(goal_pose.orientation.z); // pos_qz + (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw // Process via poses if available (only for circular motion) if (current_ref->type == MotionType::CIRCULAR_CARTESIAN && current_ref->poses.size() == 2) { - const auto & via_pose = current_ref->poses[1].pose; // via pose - (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x - (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y - (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z - (void)command_interfaces_[17].set_value(via_pose.orientation.x); // pos_via_qx - (void)command_interfaces_[18].set_value(via_pose.orientation.y); // pos_via_qy - (void)command_interfaces_[19].set_value(via_pose.orientation.z); // pos_via_qz - (void)command_interfaces_[20].set_value(via_pose.orientation.w); // pos_via_qw + const auto & via_pose = current_ref->poses[1].pose; // via pose + (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x + (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y + (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z + (void)command_interfaces_[17].set_value(via_pose.orientation.x); // pos_via_qx + (void)command_interfaces_[18].set_value(via_pose.orientation.y); // pos_via_qy + (void)command_interfaces_[19].set_value(via_pose.orientation.z); // pos_via_qz + (void)command_interfaces_[20].set_value(via_pose.orientation.w); // pos_via_qw } } - (void)command_interfaces_[21].set_value(current_ref->blend_radius); // blend_radius + (void)command_interfaces_[21].set_value(current_ref->blend_radius); // blend_radius // Read additional arguments - for (const auto &arg : current_ref->additional_arguments) + for (const auto & arg : current_ref->additional_arguments) { - if (arg.argument_name == "velocity") - { - (void)command_interfaces_[22].set_value(arg.argument_value); - } - else if (arg.argument_name == "acceleration") - { - (void)command_interfaces_[23].set_value(arg.argument_value); - } - else if (arg.argument_name == "move_time") - { - (void)command_interfaces_[24].set_value(arg.argument_value); - } - else - { - RCLCPP_WARN(get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); - } + if (arg.argument_name == "velocity") + { + (void)command_interfaces_[22].set_value(arg.argument_value); + } + else if (arg.argument_name == "acceleration") + { + (void)command_interfaces_[23].set_value(arg.argument_value); + } + else if (arg.argument_name == "move_time") + { + (void)command_interfaces_[24].set_value(arg.argument_value); + } + else + { + RCLCPP_WARN( + get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); + } } return true; } // reset the controller reference message to NaN -void MotionPrimitivesForwardController::reset_controller_reference_msg(std::shared_ptr & msg) +void MotionPrimitivesForwardController::reset_controller_reference_msg( + std::shared_ptr & msg) { msg->type = 0; msg->blend_radius = std::numeric_limits::quiet_NaN(); - - for (auto & arg : msg->additional_arguments) { + + for (auto & arg : msg->additional_arguments) + { arg.argument_name = ""; arg.argument_value = std::numeric_limits::quiet_NaN(); } - for (auto & pose : msg->poses) { - pose.pose.position.x = std::numeric_limits::quiet_NaN(); - pose.pose.position.y = std::numeric_limits::quiet_NaN(); - pose.pose.position.z = std::numeric_limits::quiet_NaN(); - - pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); + for (auto & pose : msg->poses) + { + pose.pose.position.x = std::numeric_limits::quiet_NaN(); + pose.pose.position.y = std::numeric_limits::quiet_NaN(); + pose.pose.position.z = std::numeric_limits::quiet_NaN(); + + pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); + pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); } } @@ -427,4 +466,5 @@ void MotionPrimitivesForwardController::reset_controller_reference_msg(std::shar #include "pluginlib/class_list_macros.hpp" PLUGINLIB_EXPORT_CLASS( - motion_primitives_forward_controller::MotionPrimitivesForwardController, controller_interface::ControllerInterface) + motion_primitives_forward_controller::MotionPrimitivesForwardController, + controller_interface::ControllerInterface) diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index d01d9bfdea..aaa5ef1638 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -30,4 +30,4 @@ test_motion_primitives_forward_controller: state_interfaces: - execution_status - ready_for_new_primitive - queue_size: 20 # queue size to buffer incoming commands \ No newline at end of file + queue_size: 20 # queue size to buffer incoming commands diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index d01d9bfdea..aaa5ef1638 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -30,4 +30,4 @@ test_motion_primitives_forward_controller: state_interfaces: - execution_status - ready_for_new_primitive - queue_size: 20 # queue size to buffer incoming commands \ No newline at end of file + queue_size: 20 # queue size to buffer incoming commands diff --git a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp index f80bf960f0..5024c67cad 100644 --- a/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_load_motion_primitives_forward_controller.cpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -32,8 +32,9 @@ TEST(TestLoadMotionPrimitivesForwardController, load_controller) controller_manager::ControllerManager cm( executor, ros2_control_test_assets::minimal_robot_urdf, true, "test_controller_manager"); - ASSERT_NO_THROW( - cm.load_controller("test_motion_primitives_forward_controller", "motion_primitives_forward_controller/MotionPrimitivesForwardController")); + ASSERT_NO_THROW(cm.load_controller( + "test_motion_primitives_forward_controller", + "motion_primitives_forward_controller/MotionPrimitivesForwardController")); rclcpp::shutdown(); } diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index db31b27dc0..f9d71b55c7 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -26,7 +26,8 @@ using motion_primitives_forward_controller::CMD_MY_ITFS; using motion_primitives_forward_controller::STATE_MY_ITFS; -class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +class MotionPrimitivesForwardControllerTest +: public MotionPrimitivesForwardControllerFixture { }; @@ -40,8 +41,10 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_THAT(controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); - ASSERT_THAT(controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + ASSERT_THAT( + controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + ASSERT_THAT( + controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); ASSERT_EQ(controller_->params_.name, interface_namespace_); } @@ -120,7 +123,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) controller_interface::return_type::OK); } - TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) { SetUpController(); @@ -163,8 +165,8 @@ TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_update controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(command_values_[0], MotionType::LINEAR_JOINT); // motion type - EXPECT_EQ(command_values_[1], 0.1); // q1 - q6 + EXPECT_EQ(command_values_[0], MotionType::LINEAR_JOINT); // motion type + EXPECT_EQ(command_values_[1], 0.1); // q1 - q6 EXPECT_EQ(command_values_[2], 0.2); EXPECT_EQ(command_values_[3], 0.3); EXPECT_EQ(command_values_[4], 0.4); diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index 9e3beec17c..b259d3cdc0 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -14,8 +14,8 @@ // // Authors: Mathias Fuhrer -#ifndef TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ -#define TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#ifndef TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#define TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #include #include @@ -25,11 +25,11 @@ #include #include -#include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" #include "gmock/gmock.h" #include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/loaned_state_interface.hpp" #include "hardware_interface/types/hardware_interface_return_values.hpp" +#include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" #include "rclcpp/executor.hpp" #include "rclcpp/parameter_value.hpp" #include "rclcpp/time.hpp" @@ -37,10 +37,10 @@ #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" -#include "std_msgs/msg/int8.hpp" -#include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/execution_state.hpp" +#include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" +#include "std_msgs/msg/int8.hpp" using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; using ControllerStateMsg = std_msgs::msg::Int8; @@ -52,18 +52,20 @@ constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR; } // namespace // subclassing and friending so we can access member variables -class TestableMotionPrimitivesForwardController : public motion_primitives_forward_controller::MotionPrimitivesForwardController +class TestableMotionPrimitivesForwardController +: public motion_primitives_forward_controller::MotionPrimitivesForwardController { FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status); - + public: controller_interface::CallbackReturn on_configure( const rclcpp_lifecycle::State & previous_state) override { - return motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure(previous_state); + return motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure( + previous_state); } /** @@ -113,7 +115,8 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test void TearDown() { controller_.reset(nullptr); } protected: - void SetUpController(const std::string controller_name = "test_motion_primitives_forward_controller") + void SetUpController( + const std::string controller_name = "test_motion_primitives_forward_controller") { ASSERT_EQ( controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()), @@ -125,8 +128,9 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test for (size_t i = 0; i < command_values_.size(); ++i) { - command_itfs_.emplace_back(hardware_interface::CommandInterface( - interface_namespace_, command_interface_names_[i], &command_values_[i])); + command_itfs_.emplace_back( + hardware_interface::CommandInterface( + interface_namespace_, command_interface_names_[i], &command_values_[i])); command_ifs.emplace_back(command_itfs_.back()); } @@ -136,8 +140,9 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test for (size_t i = 0; i < state_values_.size(); ++i) { - state_itfs_.emplace_back(hardware_interface::StateInterface( - interface_namespace_, state_interface_names_[i], &state_values_[i])); + state_itfs_.emplace_back( + hardware_interface::StateInterface( + interface_namespace_, state_interface_names_[i], &state_values_[i])); state_ifs.emplace_back(state_itfs_.back()); } @@ -178,12 +183,10 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test rclcpp::MessageInfo msg_info; ASSERT_TRUE(subscription->take(msg, msg_info)); } - + void publish_commands( const std::vector & joint_positions = {0.1, 0.2, 0.3, 0.4, 0.5, 0.6}, - double velocity = 0.7, - double acceleration = 1.0, - double move_time = 2.0, + double velocity = 0.7, double acceleration = 1.0, double move_time = 2.0, double blend_radius = 3.0) { std::cout << "Publishing command message ..." << std::endl; @@ -226,58 +229,32 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test command_publisher_->publish(msg); } - protected: - // Controller-related parameters - std::vector command_interface_names_ = { - "motion_type", - "q1", - "q2", - "q3", - "q4", - "q5", - "q6", - "pos_x", - "pos_y", - "pos_z", - "pos_qx", - "pos_qy", - "pos_qz", - "pos_qw", - "pos_via_x", - "pos_via_y", - "pos_via_z", - "pos_via_qx", - "pos_via_qy", - "pos_via_qz", - "pos_via_qw", - "blend_radius", - "velocity", - "acceleration", - "move_time"}; - - std::vector state_interface_names_ = { - "execution_status", - "ready_for_new_primitive"}; - - std::string interface_namespace_ = "motion_primitive"; - std::array state_values_ = {ExecutionState::IDLE, ReadyForNewPrimitive::READY}; - std::array command_values_ = { - 101.101, 101.101, 101.101, 101.101, 101.101, - 101.101, 101.101, 101.101, 101.101, 101.101, - 101.101, 101.101, 101.101, 101.101, 101.101, - 101.101, 101.101, 101.101, 101.101, 101.101, - 101.101, 101.101, 101.101, 101.101, 101.101 - }; - - std::vector state_itfs_; - std::vector command_itfs_; - - // Test related parameters - std::unique_ptr controller_; - rclcpp::Node::SharedPtr command_publisher_node_; - rclcpp::Publisher::SharedPtr command_publisher_; - rclcpp::Node::SharedPtr service_caller_node_; + // Controller-related parameters + std::vector command_interface_names_ = { + "motion_type", "q1", "q2", "q3", "q4", + "q5", "q6", "pos_x", "pos_y", "pos_z", + "pos_qx", "pos_qy", "pos_qz", "pos_qw", "pos_via_x", + "pos_via_y", "pos_via_z", "pos_via_qx", "pos_via_qy", "pos_via_qz", + "pos_via_qw", "blend_radius", "velocity", "acceleration", "move_time"}; + + std::vector state_interface_names_ = {"execution_status", "ready_for_new_primitive"}; + + std::string interface_namespace_ = "motion_primitive"; + std::array state_values_ = {ExecutionState::IDLE, ReadyForNewPrimitive::READY}; + std::array command_values_ = { + 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, + 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101}; + + std::vector state_itfs_; + std::vector command_itfs_; + + // Test related parameters + std::unique_ptr controller_; + rclcpp::Node::SharedPtr command_publisher_node_; + rclcpp::Publisher::SharedPtr command_publisher_; + rclcpp::Node::SharedPtr service_caller_node_; }; -#endif // TEMPLATES__ROS2_CONTROL__CONTROLLER__TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#endif // TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index 348f10fbdb..c83f658be0 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -1,5 +1,5 @@ // Copyright (c) 2025, b»robotized -// +// // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at @@ -25,7 +25,8 @@ using motion_primitives_forward_controller::CMD_MY_ITFS; using motion_primitives_forward_controller::STATE_MY_ITFS; -class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture +class MotionPrimitivesForwardControllerTest +: public MotionPrimitivesForwardControllerFixture { }; @@ -39,8 +40,10 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_THAT(controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); - ASSERT_THAT(controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + ASSERT_THAT( + controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + ASSERT_THAT( + controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); ASSERT_EQ(controller_->params_.name, interface_namespace_); } From a2eaaea7404e5880d97dc3e5e1d7c3e07f793412 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 8 May 2025 09:21:03 +0200 Subject: [PATCH 033/128] added ExecutionState STOPPED and MotionType RESET_STOP --- .../execution_state.hpp | 1 + .../motion_type.hpp | 1 + .../src/motion_primitives_forward_controller.cpp | 15 +++++++++++++++ 3 files changed, 17 insertions(+) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp index df8ca79f45..3557c56101 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp @@ -23,6 +23,7 @@ static constexpr uint8_t IDLE = 0; static constexpr uint8_t EXECUTING = 1; static constexpr uint8_t SUCCESS = 2; static constexpr uint8_t ERROR = 3; +static constexpr uint8_t STOPPED = 4; } // namespace ExecutionState #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp index 38fa3cfe46..3eb70221f5 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp @@ -26,6 +26,7 @@ static constexpr uint8_t CIRCULAR_CARTESIAN = 51; // Helper types static constexpr uint8_t STOP_MOTION = 66; +static constexpr uint8_t RESET_STOP = 67; // indicate motion sequence instead of executing single primitives static constexpr uint8_t MOTION_SEQUENCE_START = 100; static constexpr uint8_t MOTION_SEQUENCE_END = 101; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index a32993bc03..822ae6c6c9 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -160,6 +160,16 @@ void MotionPrimitivesForwardController::reference_callback( return; } + case MotionType::RESET_STOP: + { + RCLCPP_INFO(get_node()->get_logger(), "Received motion type: RESET_STOP"); + reset_command_interfaces(); + std::lock_guard guard(command_mutex_); + (void)command_interfaces_[0].set_value( + static_cast(msg->type)); // send reset stop command immediately to the hw-interface + return; + } + case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); if (msg->joint_positions.empty()) @@ -288,6 +298,11 @@ controller_interface::return_type MotionPrimitivesForwardController::update( // RCLCPP_INFO(get_node()->get_logger(), "Execution state: SUCCESS"); print_error_once_ = true; break; + + case ExecutionState::STOPPED: + // RCLCPP_INFO(get_node()->get_logger(), "Execution state: STOPPED"); + print_error_once_ = true; + break; case ExecutionState::ERROR: if (print_error_once_) From 558de3805cba36f3bba1df739305199bc24acaee Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 12 May 2025 16:08:47 +0200 Subject: [PATCH 034/128] discard new commands while robot is stopped --- .../motion_primitives_forward_controller.hpp | 1 + .../motion_primitives_forward_controller.cpp | 17 +++++++++++++---- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index e7f1a4a01c..623be1b52b 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -88,6 +88,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle size_t queue_size_ = 0; std::mutex command_mutex_; bool print_error_once_ = true; + bool robot_stopped_ = false; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 822ae6c6c9..9122d72cf0 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -150,6 +150,7 @@ void MotionPrimitivesForwardController::reference_callback( { RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); reset_command_interfaces(); + robot_stopped_ = true; std::lock_guard guard(command_mutex_); (void)command_interfaces_[0].set_value( static_cast(msg->type)); // send stop command immediately to the hw-interface @@ -167,6 +168,7 @@ void MotionPrimitivesForwardController::reference_callback( std::lock_guard guard(command_mutex_); (void)command_interfaces_[0].set_value( static_cast(msg->type)); // send reset stop command immediately to the hw-interface + robot_stopped_ = false; return; } @@ -213,13 +215,20 @@ void MotionPrimitivesForwardController::reference_callback( return; } - if (msg_queue_.size() >= queue_size_) + if(!robot_stopped_) { - RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); + if (msg_queue_.size() >= queue_size_) + { + RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); + return; + } + msg_queue_.push(msg); + } + else + { + RCLCPP_WARN(get_node()->get_logger(), "Robot is stopped. Discarding the new command."); return; } - - msg_queue_.push(msg); } controller_interface::InterfaceConfiguration From 29356d52c2ae63d62e95cb43b0037b565e399a95 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 21 May 2025 09:41:26 +0200 Subject: [PATCH 035/128] added missing test_depend's to package.xml --- motion_primitives_forward_controller/package.xml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index eb107bd920..506d4ef4d5 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -32,6 +32,11 @@ realtime_tools std_srvs + ament_cmake_gmock + controller_manager + hardware_interface + ros2_control_test_assets + ament_cmake From 48dd4f1d8d814e1f089ce14f752ea4479e22b5d6 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 21 May 2025 09:43:34 +0200 Subject: [PATCH 036/128] moved test dependencies to if(BUILD_TESTING) block in CMakeLists.txt --- .../CMakeLists.txt | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 5c11dd3850..53588db555 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -14,15 +14,11 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp_lifecycle realtime_tools std_srvs + industrial_robot_motion_interfaces ) find_package(ament_cmake REQUIRED) find_package(generate_parameter_library REQUIRED) -find_package(ament_cmake_gmock REQUIRED) -find_package(controller_manager REQUIRED) -find_package(hardware_interface REQUIRED) -find_package(ros2_control_test_assets REQUIRED) -find_package(industrial_robot_motion_interfaces REQUIRED) foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS}) find_package(${Dependency} REQUIRED) endforeach() @@ -42,7 +38,6 @@ target_include_directories(motion_primitives_forward_controller PUBLIC target_link_libraries(motion_primitives_forward_controller motion_primitives_forward_controller_parameters) ament_target_dependencies(motion_primitives_forward_controller ${THIS_PACKAGE_INCLUDE_DEPENDS} - industrial_robot_motion_interfaces ) target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") @@ -51,7 +46,7 @@ pluginlib_export_plugin_description_file( install( TARGETS - motion_primitives_forward_controller + motion_primitives_forward_controller RUNTIME DESTINATION bin ARCHIVE DESTINATION lib LIBRARY DESTINATION lib @@ -63,6 +58,11 @@ install( ) if(BUILD_TESTING) + find_package(ament_cmake_gmock REQUIRED) + find_package(controller_manager REQUIRED) + find_package(hardware_interface REQUIRED) + find_package(ros2_control_test_assets REQUIRED) + ament_add_gmock( test_load_motion_primitives_forward_controller test/test_load_motion_primitives_forward_controller.cpp From c96da9769f0b1f339584bd002434257aca44a082 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 5 Jun 2025 08:17:22 +0200 Subject: [PATCH 037/128] changed reference topic to action --- .../motion_primitives_forward_controller.hpp | 30 +- .../motion_primitives_forward_controller.cpp | 384 ++++++++++-------- 2 files changed, 238 insertions(+), 176 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 623be1b52b..b71ad4064a 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -29,8 +29,9 @@ #include "realtime_tools/realtime_buffer.hpp" #include "realtime_tools/realtime_publisher.hpp" +#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" -#include "std_msgs/msg/int8.hpp" +#include "rclcpp_action/rclcpp_action.hpp" namespace motion_primitives_forward_controller { @@ -63,32 +64,33 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle controller_interface::return_type update( const rclcpp::Time & time, const rclcpp::Duration & period) override; - using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; - using ControllerStateMsg = std_msgs::msg::Int8; - protected: std::shared_ptr param_listener_; motion_primitives_forward_controller::Params params_; - rclcpp::Subscription::SharedPtr ref_subscriber_ = nullptr; - - using ControllerStatePublisher = realtime_tools::RealtimePublisher; - - rclcpp::Publisher::SharedPtr s_publisher_; - std::unique_ptr state_publisher_; + using MotionPrimitiveMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; + std::queue> moprim_queue_; - std::queue> msg_queue_; + using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; + rclcpp_action::Server::SharedPtr action_server_; + rclcpp_action::GoalResponse goal_received_callback( + const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); + rclcpp_action::CancelResponse goal_cancelled_callback( + const std::shared_ptr> goal_handle); + void goal_accepted_callback( + const std::shared_ptr> goal_handle); + void execute_goal( + const std::shared_ptr> goal_handle); -private: - void reference_callback(const std::shared_ptr msg); void reset_command_interfaces(); bool set_command_interfaces(); - void reset_controller_reference_msg(std::shared_ptr & msg); size_t queue_size_ = 0; std::mutex command_mutex_; bool print_error_once_ = true; bool robot_stopped_ = false; + bool was_executing_ = false; + uint8_t execution_status_; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 9122d72cf0..821a8ac0e2 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -97,21 +97,17 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi return controller_interface::CallbackReturn::ERROR; } - // topics QoS - auto subscribers_qos = rclcpp::SystemDefaultsQoS(); - subscribers_qos.keep_last(1); - subscribers_qos.best_effort(); - - // Reference Subscriber - ref_subscriber_ = get_node()->create_subscription( - "~/reference", subscribers_qos, - std::bind(&MotionPrimitivesForwardController::reference_callback, this, std::placeholders::_1)); - RCLCPP_INFO( - get_node()->get_logger(), "Subscribed to reference topic: %s", - ref_subscriber_->get_topic_name()); - - std::shared_ptr msg = std::make_shared(); - reset_controller_reference_msg(msg); + action_server_ = rclcpp_action::create_server( + get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), + get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), + std::string(get_node()->get_name()) + "/motion_sequence", + std::bind( + &MotionPrimitivesForwardController::goal_received_callback, this, std::placeholders::_1, + std::placeholders::_2), + std::bind( + &MotionPrimitivesForwardController::goal_cancelled_callback, this, std::placeholders::_1), + std::bind( + &MotionPrimitivesForwardController::goal_accepted_callback, this, std::placeholders::_1)); queue_size_ = params_.queue_size; if (queue_size_ == 0) @@ -120,117 +116,10 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi return controller_interface::CallbackReturn::ERROR; } - try - { - // State publisher - s_publisher_ = - get_node()->create_publisher("~/state", rclcpp::SystemDefaultsQoS()); - state_publisher_ = std::make_unique(s_publisher_); - } - catch (const std::exception & e) - { - fprintf( - stderr, "Exception thrown during publisher creation at configure stage with message : %s \n", - e.what()); - return controller_interface::CallbackReturn::ERROR; - } - RCLCPP_INFO(get_node()->get_logger(), "configure successful"); return controller_interface::CallbackReturn::SUCCESS; } -// Function gets called when a new message is received -void MotionPrimitivesForwardController::reference_callback( - const std::shared_ptr msg) -{ - // Check if the type is one of the allowed motion types - switch (msg->type) - { - case MotionType::STOP_MOTION: - { - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: STOP_MOTION"); - reset_command_interfaces(); - robot_stopped_ = true; - std::lock_guard guard(command_mutex_); - (void)command_interfaces_[0].set_value( - static_cast(msg->type)); // send stop command immediately to the hw-interface - while (!msg_queue_.empty()) - { // clear the queue - msg_queue_.pop(); - } - return; - } - - case MotionType::RESET_STOP: - { - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: RESET_STOP"); - reset_command_interfaces(); - std::lock_guard guard(command_mutex_); - (void)command_interfaces_[0].set_value( - static_cast(msg->type)); // send reset stop command immediately to the hw-interface - robot_stopped_ = false; - return; - } - - case MotionType::LINEAR_JOINT: - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_JOINT (PTP)"); - if (msg->joint_positions.empty()) - { - RCLCPP_ERROR( - get_node()->get_logger(), "Received LINEAR_JOINT motion type without joint positions"); - return; - } - break; - - case MotionType::LINEAR_CARTESIAN: - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: LINEAR_CARTESIAN (LIN)"); - if (msg->poses.empty()) - { - RCLCPP_ERROR( - get_node()->get_logger(), "Received LINEAR_CARTESIAN motion type without poses"); - return; - } - break; - - case MotionType::CIRCULAR_CARTESIAN: - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: CIRCULAR_CARTESIAN (CIRC)"); - if (msg->poses.size() != 2) - { - RCLCPP_ERROR( - get_node()->get_logger(), "Received CIRCULAR_CARTESIAN motion type without two poses"); - return; - } - break; - - case MotionType::MOTION_SEQUENCE_START: - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_START"); - break; - - case MotionType::MOTION_SEQUENCE_END: - RCLCPP_INFO(get_node()->get_logger(), "Received motion type: MOTION_SEQUENCE_END"); - break; - - default: - RCLCPP_ERROR(get_node()->get_logger(), "Received unknown motion type: %u", msg->type); - return; - } - - if(!robot_stopped_) - { - if (msg_queue_.size() >= queue_size_) - { - RCLCPP_ERROR(get_node()->get_logger(), "Queue size exceeded. Can't add new motion primitive."); - return; - } - msg_queue_.push(msg); - } - else - { - RCLCPP_WARN(get_node()->get_logger(), "Robot is stopped. Discarding the new command."); - return; - } -} - controller_interface::InterfaceConfiguration MotionPrimitivesForwardController::command_interface_configuration() const { @@ -290,9 +179,9 @@ controller_interface::return_type MotionPrimitivesForwardController::update( get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); return controller_interface::return_type::ERROR; } - uint8_t execution_status = static_cast(std::round(opt_value_execution.value())); + execution_status_ = static_cast(std::round(opt_value_execution.value())); - switch (execution_status) + switch (execution_status_) { case ExecutionState::IDLE: // RCLCPP_INFO(get_node()->get_logger(), "Execution state: IDLE"); @@ -300,6 +189,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( break; case ExecutionState::EXECUTING: // RCLCPP_INFO(get_node()->get_logger(), "Execution state: EXECUTING"); + if (!was_executing_) + { + was_executing_ = true; + } print_error_once_ = true; break; @@ -307,7 +200,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( // RCLCPP_INFO(get_node()->get_logger(), "Execution state: SUCCESS"); print_error_once_ = true; break; - + case ExecutionState::STOPPED: // RCLCPP_INFO(get_node()->get_logger(), "Execution state: STOPPED"); print_error_once_ = true; @@ -323,15 +216,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( default: RCLCPP_ERROR( - get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status); + get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status_); return controller_interface::return_type::ERROR; } - // publish the execution_status - state_publisher_->lock(); - state_publisher_->msg_.data = execution_status; - state_publisher_->unlockAndPublish(); - auto opt_value_ready = state_interfaces_[1].get_optional(); if (!opt_value_ready.has_value()) { @@ -341,7 +229,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( } uint8_t ready_for_new_primitive = static_cast(std::round(opt_value_ready.value())); - if (!msg_queue_.empty()) // check if new command is available + if (!moprim_queue_.empty()) // check if new command is available { switch (ready_for_new_primitive) { @@ -385,32 +273,32 @@ bool MotionPrimitivesForwardController::set_command_interfaces() { std::lock_guard guard(command_mutex_); // Get the oldest message from the queue - std::shared_ptr current_ref = msg_queue_.front(); - msg_queue_.pop(); + std::shared_ptr current_moprim = moprim_queue_.front(); + moprim_queue_.pop(); // Check if the message is valid - if (!current_ref) + if (!current_moprim) { RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); return false; } // Set the motion_type - (void)command_interfaces_[0].set_value(static_cast(current_ref->type)); + (void)command_interfaces_[0].set_value(static_cast(current_moprim->type)); // Process joint positions if available - if (!current_ref->joint_positions.empty()) + if (!current_moprim->joint_positions.empty()) { - for (size_t i = 0; i < current_ref->joint_positions.size(); ++i) + for (size_t i = 0; i < current_moprim->joint_positions.size(); ++i) { - (void)command_interfaces_[i + 1].set_value(current_ref->joint_positions[i]); // q1 to q6 + (void)command_interfaces_[i + 1].set_value(current_moprim->joint_positions[i]); // q1 to q6 } } // Process Cartesian poses if available - if (!current_ref->poses.empty()) + if (!current_moprim->poses.empty()) { - const auto & goal_pose = current_ref->poses[0].pose; // goal pose + const auto & goal_pose = current_moprim->poses[0].pose; // goal pose (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z @@ -420,9 +308,9 @@ bool MotionPrimitivesForwardController::set_command_interfaces() (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw // Process via poses if available (only for circular motion) - if (current_ref->type == MotionType::CIRCULAR_CARTESIAN && current_ref->poses.size() == 2) + if (current_moprim->type == MotionType::CIRCULAR_CARTESIAN && current_moprim->poses.size() == 2) { - const auto & via_pose = current_ref->poses[1].pose; // via pose + const auto & via_pose = current_moprim->poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z @@ -433,10 +321,10 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } } - (void)command_interfaces_[21].set_value(current_ref->blend_radius); // blend_radius + (void)command_interfaces_[21].set_value(current_moprim->blend_radius); // blend_radius // Read additional arguments - for (const auto & arg : current_ref->additional_arguments) + for (const auto & arg : current_moprim->additional_arguments) { if (arg.argument_name == "velocity") { @@ -459,32 +347,204 @@ bool MotionPrimitivesForwardController::set_command_interfaces() return true; } -// reset the controller reference message to NaN -void MotionPrimitivesForwardController::reset_controller_reference_msg( - std::shared_ptr & msg) +rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_callback( + const rclcpp_action::GoalUUID &, std::shared_ptr goal) { - msg->type = 0; - msg->blend_radius = std::numeric_limits::quiet_NaN(); + RCLCPP_INFO(get_node()->get_logger(), "Received goal request"); + + const auto & primitives = goal->trajectory.motions; - for (auto & arg : msg->additional_arguments) + if (primitives.empty()) { - arg.argument_name = ""; - arg.argument_value = std::numeric_limits::quiet_NaN(); + RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); + return rclcpp_action::GoalResponse::REJECT; } - for (auto & pose : msg->poses) + for (size_t i = 0; i < primitives.size(); ++i) { - pose.pose.position.x = std::numeric_limits::quiet_NaN(); - pose.pose.position.y = std::numeric_limits::quiet_NaN(); - pose.pose.position.z = std::numeric_limits::quiet_NaN(); - - pose.pose.orientation.x = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.y = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.z = std::numeric_limits::quiet_NaN(); - pose.pose.orientation.w = std::numeric_limits::quiet_NaN(); + const auto & primitive = primitives[i]; + + switch (primitive.type) + { + case MotionType::LINEAR_JOINT: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); + if (primitive.joint_positions.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: LINEAR_JOINT requires joint_positions.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + case MotionType::LINEAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_CARTESIAN (LIN)", i); + if (primitive.poses.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: LINEAR_CARTESIAN requires at least one pose.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + case MotionType::CIRCULAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: CIRCULAR_CARTESIAN (CIRC)", i); + if (primitive.poses.size() != 2) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: CIRCULAR_CARTESIAN requires exactly two poses.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + default: + RCLCPP_ERROR( + get_node()->get_logger(), "Primitive %zu invalid: unknown motion type %u.", i, + primitive.type); + return rclcpp_action::GoalResponse::REJECT; + } } + + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } +rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_callback( + const std::shared_ptr>) +{ + RCLCPP_INFO(get_node()->get_logger(), "Canceling goal"); + + std::lock_guard guard(command_mutex_); + reset_command_interfaces(); + robot_stopped_ = true; + // send stop command immediately to the hw-interface + (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); + while (!moprim_queue_.empty()) + { // clear the queue + moprim_queue_.pop(); + } + + RCLCPP_INFO(get_node()->get_logger(), "Waiting for Robot to stop..."); + while (execution_status_ != ExecutionState::STOPPED) + { + // Small sleep to prevent busy waiting + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } + + reset_command_interfaces(); + // send reset stop command to the hw-interface + (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); + robot_stopped_ = false; + + RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); + return rclcpp_action::CancelResponse::ACCEPT; +} + +void MotionPrimitivesForwardController::goal_accepted_callback( + const std::shared_ptr> goal_handle) +{ + std::thread{std::bind(&MotionPrimitivesForwardController::execute_goal, this, goal_handle)} + .detach(); +} + +void MotionPrimitivesForwardController::execute_goal( + const std::shared_ptr> goal_handle) +{ + const auto & goal = goal_handle->get_goal(); + + if (robot_stopped_) + { + RCLCPP_WARN(get_node()->get_logger(), "Robot is stopped. Discarding the new command."); + return; + } + + const auto & primitives = goal->trajectory.motions; + + if (primitives.empty()) + { + RCLCPP_WARN(get_node()->get_logger(), "Received goal with no motion primitives. Ignoring."); + return; + } + + size_t required_queue_space = primitives.size(); + // add sequence markers only if there are multiple primitives + bool add_sequence_wrappers = primitives.size() > 1; + if (add_sequence_wrappers) + { + required_queue_space += 2; // start + end + } + + // Check if queue has enough space + if (moprim_queue_.size() + required_queue_space > queue_size_) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Received more motion primitives than queue can store. " + "Current queue size: %zu, required space: %zu. " + "Please increase the queue size in the controller parameters.", + moprim_queue_.size(), required_queue_space); + return; + } + + // Add sequence start marker + if (add_sequence_wrappers) + { + std::shared_ptr start_marker = std::make_shared(); + start_marker->type = MotionType::MOTION_SEQUENCE_START; + moprim_queue_.push(start_marker); + } + + // Add motion primitives to the queue + for (const auto & primitive : primitives) + { + moprim_queue_.push(std::make_shared(primitive)); + } + + // Add sequence end marker + if (add_sequence_wrappers) + { + std::shared_ptr end_marker = std::make_shared(); + end_marker->type = MotionType::MOTION_SEQUENCE_END; + moprim_queue_.push(end_marker); + } + + RCLCPP_INFO( + get_node()->get_logger(), "Accepted goal with %zu motion primitives%s.", primitives.size(), + add_sequence_wrappers ? " (wrapped in sequence markers)" : ""); + + ExecuteMotion::Result result; + rclcpp::Rate rate(50); + while (rclcpp::ok()) + { + auto execution_status = static_cast(std::round(state_interfaces_[0].get_value())); + if (execution_status == ExecutionState::SUCCESS && was_executing_) + { + RCLCPP_INFO(get_node()->get_logger(), "Execution completed successfully."); + result.error_code = ExecuteMotion::Result::SUCCESSFUL; + result.error_string = "Trajectory executed successfully"; + was_executing_ = false; + break; + } + else if (execution_status == ExecutionState::ERROR) + { + RCLCPP_ERROR(get_node()->get_logger(), "Execution failed with an error."); + result.error_code = ExecuteMotion::Result::FAILED; + result.error_string = "Trajectory execution failed"; + break; + } + else if (execution_status == ExecutionState::STOPPED) + { + RCLCPP_INFO(get_node()->get_logger(), "Execution stopped."); + result.error_code = ExecuteMotion::Result::CANCELED; + result.error_string = "Trajectory execution stopped"; + break; + } + rate.sleep(); + } + + goal_handle->succeed(std::make_shared(result)); +} } // namespace motion_primitives_forward_controller #include "pluginlib/class_list_macros.hpp" From 53147b9f42b57ad4a9c3b3ee8e1fbe52269f8aad Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 5 Jun 2025 15:00:20 +0200 Subject: [PATCH 038/128] modified tests for action based controller --- ...t_motion_primitives_forward_controller.cpp | 44 ++-- ...t_motion_primitives_forward_controller.hpp | 202 +++++++----------- 2 files changed, 93 insertions(+), 153 deletions(-) diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index f9d71b55c7..3af7371dd0 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -77,8 +77,8 @@ TEST_F(MotionPrimitivesForwardControllerTest, activate_success) ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); // check that the message queue is reset - auto msg_queue = controller_->msg_queue_; - ASSERT_TRUE(msg_queue.empty()); + auto moprim_queue_ = controller_->moprim_queue_; + ASSERT_TRUE(moprim_queue_.empty()); } TEST_F(MotionPrimitivesForwardControllerTest, update_success) @@ -123,7 +123,7 @@ TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) controller_interface::return_type::OK); } -TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) +TEST_F(MotionPrimitivesForwardControllerTest, receive_single_action_goal) { SetUpController(); @@ -134,32 +134,16 @@ TEST_F(MotionPrimitivesForwardControllerTest, publish_status_success) controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - ControllerStateMsg msg; - subscribe_and_get_messages(msg); + send_single_motion_sequence_goal(); // filling with default values from the function - ASSERT_EQ(msg.data, ExecutionState::IDLE); -} - -TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status) -{ - SetUpController(); - rclcpp::executors::MultiThreadedExecutor executor; - executor.add_node(controller_->get_node()->get_node_base_interface()); - - ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - - ASSERT_EQ( - controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), - controller_interface::return_type::OK); - - ControllerStateMsg msg; - subscribe_and_get_messages(msg); - - ASSERT_EQ(msg.data, ExecutionState::IDLE); - - publish_commands(); - controller_->wait_for_commands(executor); + // Wait for the command value to be set + // This is necessary because the action server might take some time to process the goal + auto start = std::chrono::steady_clock::now(); + while (std::isnan(command_values_[1]) && + (std::chrono::steady_clock::now() - start) < std::chrono::seconds(5)) + { + std::this_thread::sleep_for(std::chrono::milliseconds(10)); + } ASSERT_EQ( controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), @@ -176,10 +160,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, receive_message_and_publish_update EXPECT_EQ(command_values_[22], 0.7); // velocity EXPECT_EQ(command_values_[23], 1.0); // acceleration EXPECT_EQ(command_values_[24], 2.0); // move time - - subscribe_and_get_messages(msg); - - ASSERT_EQ(msg.data, ExecutionState::IDLE); } int main(int argc, char ** argv) diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index b259d3cdc0..31fbae6e12 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -18,9 +18,12 @@ #define TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #include +#include +#include #include #include #include +#include #include #include #include @@ -34,16 +37,18 @@ #include "rclcpp/parameter_value.hpp" #include "rclcpp/time.hpp" #include "rclcpp/utilities.hpp" +#include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" #include "motion_primitives_forward_controller/execution_state.hpp" #include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" -#include "std_msgs/msg/int8.hpp" -using ControllerReferenceMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; -using ControllerStateMsg = std_msgs::msg::Int8; +using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; +using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; namespace { @@ -58,7 +63,7 @@ class TestableMotionPrimitivesForwardController FRIEND_TEST(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, activate_success); FRIEND_TEST(MotionPrimitivesForwardControllerTest, reactivate_success); - FRIEND_TEST(MotionPrimitivesForwardControllerTest, receive_message_and_publish_updated_status); + FRIEND_TEST(MotionPrimitivesForwardControllerTest, receive_single_action_goal); public: controller_interface::CallbackReturn on_configure( @@ -67,62 +72,55 @@ class TestableMotionPrimitivesForwardController return motion_primitives_forward_controller::MotionPrimitivesForwardController::on_configure( previous_state); } - - /** - * @brief wait_for_command blocks until a new ControllerReferenceMsg is received. - * Requires that the executor is not spinned elsewhere between the - * message publication and the call to this function. - */ - void wait_for_command( - rclcpp::Executor & executor, - const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) - { - auto until = get_node()->get_clock()->now() + timeout; - while (get_node()->get_clock()->now() < until) - { - executor.spin_some(); - std::this_thread::sleep_for(std::chrono::microseconds(10)); - } - } - - void wait_for_commands( - rclcpp::Executor & executor, - const std::chrono::milliseconds & timeout = std::chrono::milliseconds{500}) - { - return wait_for_command(executor, timeout); - } }; - // We are using template class here for easier reuse of Fixture in specializations of controllers template class MotionPrimitivesForwardControllerFixture : public ::testing::Test { public: - static void SetUpTestCase() {} - - void SetUp() + void SetUp() override { - // initialize controller controller_ = std::make_unique(); + ASSERT_EQ( + controller_->init( + "test_motion_primitives_forward_controller", "", 0, "", + controller_->define_custom_node_options()), + controller_interface::return_type::OK); - command_publisher_node_ = std::make_shared("command_publisher"); - command_publisher_ = command_publisher_node_->create_publisher( - "/test_motion_primitives_forward_controller/reference", rclcpp::SystemDefaultsQoS()); - } + node_ = std::make_shared("test_node"); + + executor_ = std::make_shared(); + executor_->add_node(node_); + executor_->add_node(controller_->get_node()->get_node_base_interface()); - static void TearDownTestCase() {} + executor_thread_ = std::thread([this]() { executor_->spin(); }); - void TearDown() { controller_.reset(nullptr); } + action_client_ = rclcpp_action::create_client( + node_->get_node_base_interface(), node_->get_node_graph_interface(), + node_->get_node_logging_interface(), node_->get_node_waitables_interface(), + "/test_motion_primitives_forward_controller/motion_sequence"); + } + + void TearDown() override + { + executor_->cancel(); + if (executor_thread_.joinable()) + { + executor_thread_.join(); + } + controller_.reset(); + node_.reset(); + executor_.reset(); + } protected: void SetUpController( const std::string controller_name = "test_motion_primitives_forward_controller") { - ASSERT_EQ( - controller_->init(controller_name, "", 0, "", controller_->define_custom_node_options()), - controller_interface::return_type::OK); - std::vector command_ifs; + std::vector state_ifs; + + command_itfs_.clear(); command_itfs_.reserve(command_values_.size()); command_ifs.reserve(command_values_.size()); @@ -134,7 +132,7 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test command_ifs.emplace_back(command_itfs_.back()); } - std::vector state_ifs; + state_itfs_.clear(); state_itfs_.reserve(state_values_.size()); state_ifs.reserve(state_values_.size()); @@ -149,88 +147,50 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs)); } - void subscribe_and_get_messages(ControllerStateMsg & msg) + void send_single_motion_sequence_goal( + const std::vector & joint_positions = {0.1, 0.2, 0.3, 0.4, 0.5, 0.6}, + double velocity = 0.7, double acceleration = 1.0, double move_time = 2.0, + double blend_radius = 3.0) { - // create a new subscriber - rclcpp::Node test_subscription_node("test_subscription_node"); - auto subs_callback = [&](const ControllerStateMsg::SharedPtr) {}; - auto subscription = test_subscription_node.create_subscription( - "/test_motion_primitives_forward_controller/state", 10, subs_callback); + std::cout << "Send motion sequence goal..." << std::endl; - // call update to publish the test value - ASSERT_EQ( - controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), - controller_interface::return_type::OK); - - // call update to publish the test value - // since update doesn't guarantee a published message, republish until received - int max_sub_check_loop_count = 5; // max number of tries for pub/sub loop - rclcpp::WaitSet wait_set; // block used to wait on message - wait_set.add_subscription(subscription); - while (max_sub_check_loop_count--) + if (!action_client_->wait_for_action_server(std::chrono::seconds(5))) { - controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)); - // check if message has been received - if (wait_set.wait(std::chrono::milliseconds(2)).kind() == rclcpp::WaitResultKind::Ready) - { - break; - } + throw std::runtime_error("Action server not available"); } - ASSERT_GE(max_sub_check_loop_count, 0) << "Test was unable to publish a message through " - "controller/broadcaster update loop"; - // take message from subscription - rclcpp::MessageInfo msg_info; - ASSERT_TRUE(subscription->take(msg, msg_info)); - } + auto goal_msg = ExecuteMotion::Goal(); + MotionPrimitive primitive; + primitive.type = MotionType::LINEAR_JOINT; + primitive.joint_positions = joint_positions; + primitive.blend_radius = blend_radius; - void publish_commands( - const std::vector & joint_positions = {0.1, 0.2, 0.3, 0.4, 0.5, 0.6}, - double velocity = 0.7, double acceleration = 1.0, double move_time = 2.0, - double blend_radius = 3.0) - { - std::cout << "Publishing command message ..." << std::endl; - auto wait_for_topic = [&](const auto topic_name) + primitive.additional_arguments.resize(3); + primitive.additional_arguments[0].argument_name = "velocity"; + primitive.additional_arguments[0].argument_value = velocity; + primitive.additional_arguments[1].argument_name = "acceleration"; + primitive.additional_arguments[1].argument_value = acceleration; + primitive.additional_arguments[2].argument_name = "move_time"; + primitive.additional_arguments[2].argument_value = move_time; + + goal_msg.trajectory.motions.push_back(primitive); + + auto goal_future = action_client_->async_send_goal(goal_msg); + + if (goal_future.wait_for(std::chrono::seconds(5)) != std::future_status::ready) { - size_t wait_count = 0; - while (command_publisher_node_->count_subscribers(topic_name) == 0) - { - if (wait_count >= 5) - { - auto error_msg = - std::string("publishing to ") + topic_name + " but no node subscribes to it"; - throw std::runtime_error(error_msg); - } - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - ++wait_count; - } - std::cout << "Found subscriber for topic: " << topic_name << std::endl; - }; - - auto topic_name = command_publisher_->get_topic_name(); - std::cout << "Waiting for subscriber on topic: " << topic_name << std::endl; - wait_for_topic(topic_name); - - ControllerReferenceMsg msg; - - // TODO(mathias31415): Add other tests for other motion types - msg.type = MotionType::LINEAR_JOINT; - msg.joint_positions = joint_positions; - msg.blend_radius = blend_radius; - - msg.additional_arguments.resize(3); - msg.additional_arguments[0].argument_name = "velocity"; - msg.additional_arguments[0].argument_value = velocity; - msg.additional_arguments[1].argument_name = "acceleration"; - msg.additional_arguments[1].argument_value = acceleration; - msg.additional_arguments[2].argument_name = "move_time"; - msg.additional_arguments[2].argument_value = move_time; - - command_publisher_->publish(msg); + throw std::runtime_error("Failed to send goal (future timeout)"); + } + + auto goal_handle = goal_future.get(); + if (!goal_handle) + { + throw std::runtime_error("Goal was rejected by the action server"); + } + + std::cout << "Goal accepted by the action server." << std::endl; } -protected: - // Controller-related parameters std::vector command_interface_names_ = { "motion_type", "q1", "q2", "q3", "q4", "q5", "q6", "pos_x", "pos_y", "pos_z", @@ -250,11 +210,11 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test std::vector state_itfs_; std::vector command_itfs_; - // Test related parameters std::unique_ptr controller_; - rclcpp::Node::SharedPtr command_publisher_node_; - rclcpp::Publisher::SharedPtr command_publisher_; - rclcpp::Node::SharedPtr service_caller_node_; + rclcpp_action::Client::SharedPtr action_client_; + rclcpp::Node::SharedPtr node_; + std::shared_ptr executor_; + std::thread executor_thread_; }; #endif // TEST_MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ From 7a8bcb2ef9cf212eb0bddc27879baaef63555b73 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 5 Jun 2025 16:38:39 +0200 Subject: [PATCH 039/128] updated readme --- .../README.md | 47 +++++++----------- ...s2_control_motion_primitives_ur.drawio.png | Bin 458182 -> 0 bytes ...motion_primitives_ur_integrated.drawio.png | Bin 0 -> 374313 bytes ...n_primitives_ur_whiteBackground.drawio.png | Bin 441153 -> 0 bytes 4 files changed, 18 insertions(+), 29 deletions(-) delete mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_integrated.drawio.png delete mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index e301e690fb..be910fd651 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -6,44 +6,33 @@ Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ) [![Licence](https://img.shields.io/badge/License-Apache-2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) -This project provides an interface for sending motion primitives to an industrial robot controller using the `MotionPrimitive.msg` message type from the [industrial_robot_motion_interfaces](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) package. A custom fork of this package is used, which includes additional helper types to enhance motion command flexibility and sequencing. +This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotion.action` action from the [industrial_robot_motion_interfaces](https://github.com/b-robotized-forks/industrial_robot_motion_interfaces/tree/helper-types) package. The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. -## Features - -- Support for basic motion primitives: +- Supported motion primitives: - `LINEAR_JOINT` - `LINEAR_CARTESIAN` - `CIRCULAR_CARTESIAN` -- Additional helper types: - - `STOP_MOTION`: Immediately stops the current robot motion and clears all pending primitives in the controller's queue. - - `MOTION_SEQUENCE_START` / `MOTION_SEQUENCE_END`: Define a motion sequence block. All primitives between these two markers will be executed as a single, continuous sequence. This allows seamless transitions (blending) between primitives. - -## Architecture Overview -The following diagram shows the architecture for a UR robot. -For this setup, the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) is used. -![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png) +If multiple motion primitives are passed to the controller via the action, the controller forwards them to the hardware interface as a sequence. To do this, it first sends `MOTION_SEQUENCE_START`, followed by each individual primitive, and finally `MOTION_SEQUENCE_END`. All primitives between these two markers will be executed as a single, continuous sequence. This allows seamless transitions (blending) between primitives. +The action interface also allows stopping the current execution of motion primitives. When a stop request is received, the controller sends `STOP_MOTION` to the hardware interface, which then halts the robot's movement. Once the controller receives confirmation that the robot has stopped, it sends `RESET_STOP` to the hardware interface. After that, new commands can be sent. -1. **Command Reception** - Motion primitives can be published to the `~/reference` topic. These messages are received by the `reference_callback()` method in the controller. - This can be done, for example, via a Python script as demonstrated in the [`motion_primitive_ur_driver`](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives.py) package. +This can be done, for example, via a Python script as demonstrated in the [`example python script`](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives_hka_ur10e.py) in the `Universal_Robots_ROS2_Driver` package. -2. **Command Handling Logic** - - If the received primitive is of type `STOP_MOTION`, it is directly forwarded to the hardware interface through the command interface, and all queued primitives in the controller are discarded. - - If the primitive is of any other type, it is appended to the internal motion primitive queue. The maximum queue size is configurable via a YAML configuration file. - -3. **Motion Execution Flow** - The `update()` method in the controller: - - Reads the current `execution_state` from the hardware interface via the state interface and publishes it to the `~/state` topic. - - Reads the `ready_for_new_primitive` state flag. If `true`, the next primitive from the queue is sent to the hardware interface for execution. +## Architecture Overview +The following diagram shows the architecture for a UR robot. +For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver`](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) is used. -4. **Sequencing Logic** - Sequencing logic for grouped execution (between `MOTION_SEQUENCE_START` and `MOTION_SEQUENCE_END`) is handled within the hardware interface layer. The controller itself only manages queueing and forwarding logic. +![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_integrated.drawio.png) # Related packages/ repos -- [industrial_robot_motion_interfaces (with additional helper types for stop and motion sequence)](https://github.com/StoglRobotics-forks/industrial_robot_motion_interfaces/tree/helper-types) -- [ros2_controllers with motion_primitives_forward_controller](https://github.com/StoglRobotics-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) -- [Universal_Robots_ROS2_Driver with motion_primitive_ur_driver](https://github.com/StoglRobotics-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) -- [Universal_Robots_Client_Library with movec from urfeex](https://github.com/urfeex/Universal_Robots_Client_Library/tree/movec_movep) +- [industrial_robot_motion_interfaces](https://github.com/b-robotized-forks/industrial_robot_motion_interfaces/tree/helper-types) +- [ros2_controllers with motion_primitives_forward_controller](https://github.com/b-robotized-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) +- [Universal_Robots_ROS2_Driver with motion_primitive_ur_driver](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) +- [Universal_Robots_Client_Library](https://github.com/UniversalRobots/Universal_Robots_Client_Library) + +# TODOs/ improvements +- Extend the tests + - Test for a sequence of multiple primitives + - Test for canceling movement diff --git a/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png b/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur.drawio.png deleted file mode 100644 index a33053b6b206bfc0cba7726589a8d7c79e1c6c1c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 458182 zcmeFZ$?o%BwZZj#lZ{og>Cyco$#5FMI8W=KW z?Y#f*)Tt^cffz91m49y%H{08Luf3XQJ2WhnpVzy0t2+rRzoZ~sQUiO;|N?Z5gT z{`R;3@_+wt{%hFtKmSkv+yDBv|Kfk?7AaWTBd?n5Z+|C*Ki~d-!ODJK{!WO0zg(hW z_~*2WiYaR6f9|pccERze$hyByc=Tu0G|}HLGWpLK9QwBbj{lwD;hP(;-Ln4qu2b3=YO_D*TF~i#f@V?wtMt#l?fFV^U*s9Bjp}21 zk0JH%{^QpE(Pn!nQ#6#1KFu0vB0c^zf#VeUr_uEL*B%URf$maF|G3Xzw?#W%)%jP4 zaOmvsw6#jJ`LApL>{|N1S*qbb+?n)UmnDA<`(G_a)70<(;c0o_{PlEyoio6L{|Bw3 z9j_#6{?omFl`iFThy$74X+6j8~vUlnv$|wU<%hMgNK^>`SR~zQkSVm&-hR9*Y*pN z?F%+cRa-6926A!1@_yQ*DTQx;o!w*;{P?%?k`3?)%MD3>KJ_hp%*j*@3#=$4TJ!S# z$1E?|0RzsLOWVK%p(Q%QjX#;tH~j>Ay1s)B^Pmcv|7cg#R0UdZ35*-unBd`omI~yD z`|Chkr75}%zoW-{4N-y~eTUTo`=);F(hNx?EKL4iBn17);o1LM4j0s+-|xSA{C_fA zf9*nd&;GIa&}07RrRd+wl9KgpwoG3bmw#N2;p{*EwR-=tc{Ie-}$(DYR8Pc87# zJp55Ad3B&^;{Q4zrqL3CWc~Shk%zAM`$ecc-hA%ZT`77F{uwW~l-vToz0pre61Wh3 zQC`aZw})3!-f<<4(-ljA=RHc^hT{TXzhuqeIG)nr>OzH`7HU!8DEL2h;6HOf?NTlL zClf-lHWCA0Ilk5OCuW1h%R3k-nX~?W;fpQG&^4S8@Twm?;M(VZ9?Xdqk#S>4> zaoroi6*vB6*KV=|^A30Cc((?BhARDb@-sE>9ENMg-YL^;ep%N};e-St#v( zFK&jGl(hr@wF_?>qz^jE<@dkLKf2kcLQ?(g1(La*R}3J2gP&biI+0Q@YbvEX^` z*H2gGf`$_+`*$83D78NaB%TjEIKch&Jlt~UWCb1%8VEdIcyaJ3aHBi7!U5^eb2~2o z^3ehKsR-)`V#lFJE^U|3T<)&HFhhImC`g~*fx?#L6b``nqw}g>z+h-1coaAF+eGtAbvgh%pgM0}_}XwYKv<$efK`}%IADNCOEDV|UHaXT%sGK(*#Ud6(^5B?p_ z^zKC{%G^&@9(&DfALcQ99?A4c(4TO8WxJ3T{e{^)C?-vp;i8j}l4&9?e)-a$QR&{x z9oAXSSJhomv-)ek9qB&dpj;w51wR}^yBz>nh~wS}5`sZ?Pk<{|GTQ}H8Iyk|5 zw%TyGQiMEd>wNTd#_UK}JWBZQ?JepWoL64Zy=_+ejJ!XRHwz3aFJtB;x94;82hSGk z)hOU;4y(SJ72|zZmrZvM7GTIHoalb3&~Kk3Ja$#M!g>U=S4bx`YRxi}9`BqnIAQdJ z^1PjC`3%|)kK*2B%7LA|@`GOkxMOFLkGv;7Bz80kh5O&jL@@1!U-nY_%;ISo(c)iI z%$#vb>C9Az_C5Jj-lvl&B4as@gFW15z0wG?Ur8A-&ecZ9xZ&GsIq-$MXSpkKNw|&>|tz&eFNhfQpQEXQCcjGx4_LH|o zDu3@Y7+N`@kua(1B7hi#%q22{8pGW5xLz@0Zz;ln!%tE~XE6_J+a8zP+)eAan)S0k z%l*oUNnB@4P(g2Csxe)clW#SPx}jrrCt7wlf5epsUrShI+%6Do$j^wkJ7+k!-V?ap7r0<# zJI)8S1OvV`9|`6$hYnt>U}})2l+(b&VUmw<3wqqFXPVlt|>!=%r)v8Y$hjeR^a<*NwGq0b|+)?tfUr<#MN%>uv(hQlHcS0c&Qk=NygJ{n5_Ya zLvV!9!ACqUu_Vu9dw>8@?tb>-Lz>Qmsuu4UU*DJGPu_Y%^1hxH_P~@jurAHFcoX7D z&V)?`HlBOQ_4bGj0}b^fCWr}{l{z6$lEB`qrSZB-2I@7?kP z-H=015nOT*lu*n*5gT=A1YAox>MMD^ye=@LE$V3f{_e<}r?oeK*Ph(HbUBEx_zotC zhY$$~9a?Do;Bga~>*QSBk7s&Ii7Q3X^n9=D^LigxQwv2w#Zvisbi-(~B& zA2^-{j^`wx2~FrNFVaWlGTa@h%MX4-i>iA0M7DV&anp7ET>)5l*Q9SAlKL$0u~m-6 zr_hFncA?*keNy>E^=W4l#O;&kT=6;``F`@e@Kp^@6zRQtB1`@oRsv^&j zdrwwL8A{Dq8~e@&t$rW%V`!zX{}RyfDdGHH+vH&K8ONjZ_o70DEEe0d^(!R1q6);=c&QZZ|c-WtG>PRPWYF?96}%T zh!W>nR;@~TO@4k&?Y_?=#dO|Y#qm3G1o%+M2jf$%YVh(X(@Wk>xzc6FXpRd6yN@9&yA zmFavPF-jxZ4lQTOMcN`iuMtbmS2VeM>z?84KW?BdMXX?-4`E#)1Qbl>0p??OqRFSm zX~J@eN9&@H?<*GHU(0h$y+=QZV=6Ytw%?Tcxs|Y{n5!0Y3 zKYNQEo@0);`FaiGc;?cS{ettSJ@JIyZ))P*@!0JYT<&oN4K!>tjkG$_IgCRZi@|k+Nt0+zwyb)d8K#2OCV*v;a}fkz z4u0R0lWdq>5q4esIpjBx`=z4FBlaeo(RxF^9xQg__w_ysf`EO$*}G)iM_cly#^2{- z!5+aaPt&}D6wF2Lr$x^Qh$$sc=sg@3+c0Kb>m0iF^Pi*mh)HC$$>9ru@SkT8xNi%t z?_EqYp?->~0sk1eopBF8HTARm1%~2a+&b9jmC24wEL0c?ZqPMNxgUzDA0~YI^5=5h zEb?mQKTm+_=yiN&HA0SN@M|aPZ9G9|bfd&BUQwRdTX}xM-E_Kl^MKB$+wFt=_4SP& zrFetais3x84_eV2ps%+hQ=+D&K((w8>3|cT+@TkGVkl=^48yXH{iLP(r+hs%zyUlT zLOCNA-!Y!Idf!w*BBe2i@O zPcJHA$#5Hf=eRCkQ+#zK+%PitoY1twNm+LiE6d70KF8SFV7SBH`~=x4UM$cUC%#*N z*9UObo<-nUg42T*b2#0?Vo_FVcMWcf36@RWZ5+S~!$BOdi0*;72CzWZC zAs*{!q;}vW6x_>5GpPd=ANG8^Q_+B-pt5gpO?|X3m36~V_|Nk_gWs{_aM5c38R5Ox zBuU+xJS*1;dsCYaYI3Oe5+VRP^|E=8;}llA_2RB2$ZX zbfQ5jF3Yn08r618<{I@>s;hT+;h(iyQ( zEbt>BNF*i&YUoXY9v8rDaeWt`N0_7CdgU(p_#Xp@azft&<+sLa-eWCFuSfKRW z4|(p6o?(P<9xM%xUv#Z`VFcUuzCc)60u!+DF5u+4^#<6%LxO0T=CxFM>bwChw6Lx@7Pqz@@p>JNU@C9DZfiqry(Bl4i~8o$u#diyQhkByuCrcpvg;769;qw={E{Zr2wAecnLEB z0Vn$1kS{%VoVRNVUJY{|(=w$o#DJwC_qt`$cfdv_^~t4vP+hf$;({+~!|_f`tZ1M+ z$);`(=R;N*z0!RMZN3gp%B{Q8F=&4Cd@aBo;6JOMoBo%a=OFG~3yqkyY81?p*fE!z z)zx?dQ6L^}+l9`n04canKv@Cx^b|o8rWM5nkVnGL;2Mf*6m8%%$Z#F8XA^dMw`B;w zuZ~_+$(%3UM;5w^e=1aJLLYa9d3RRM#S5L`O-BS@QtB8=Ldl)|GjE&y>M-h~-i7h1 z-Kmk2HA}qOzEHR7J`V?>ed({iU#d%iRSjSp05yuRzI-coLt@MI`-@gflhVJi^AdJ^wm>hESlJ69fs56nr^it@+Y_mZlu^*BeJMfBHq! zn7QGnyt1yx+p!!D6q52@`nKLUGk-8>3bK6o(u446Bn@Ou(lbyOJo`c<@Pcq{Vb;$}Gc zT5mgk3y$^Xc{nSBon0=oW@hcI6uabCyNmvmf|3SrF76XNs%J}|8%Kk03y3LNqtf{t zJ`(0Wk)s^XdyYO~12^M~hKLd13D(Wf?uM)I*vjID?*Uc;fL&*)e58B1_dd8P?gr#v z-0uOwm^aZ$+82sxtj)n$kGQ-$fNJ^fnmbhTqS9;~%`*Jf;}EPZz?L-zk>wF|>L5HY z4hFVwKFnN20V%7cBJI%69+y5JtouM1?W+wn?-c5(6PIIF@!v~pE{a|BYhs6+!`b+ic}Ta}2TeK+AG~NjfROMTicc;H_G~wKX^EIYE(Pp5;DhDB zO7zvNX=m`t&oi5(5i10#YTUZSD49=p!aQ$CdHyc?qy2*T-9m-|b`m!Tiy>KXgU9H} zoKfEDI!0)1N?`Aj%u%JR#MZ)vJ^0n-^jvqH9z+1Km)$ z3V`LQ2mAQtv1*d=3YU?A=R~@asZ5+My>uKXMgTw9x0R-!zTw$OoqKwiX_WR1pTrZP1l~h2} z$yL!ymP4=?%NrZFhX5_yh%3uOk5sM{Tv~UDh0IthzFa4eAL-XYHu$-d!V!5@K&A&T6ZeY?ak=7vC4~p*u>>4* zB*npQX) zyziO70W>a(TmziqCf+B6SW*B zxjT8+2J3oB&;zHlo6r|s@tz(>0kCh}m(BhV!mHtIa7F;zz2zXRw;OSB@vwnJ1u66) zIFGVJ^dBFs_$-Q<@E5tNsuAGV`m2rd7T#}a@em+xnIA`4hI zuoC$qD1&bqKcbE3M>>98mIa^zACACDum$gw{HC4y=$h28RYuXR8GsR#_k(jDpc#4z zvU!DARD40D_eLNzR^E|j{44agfzrpX{W%k?jv%YF^BBrvV{OhN&0f3LmjwP#LSvai@b+x)^^=B zHUQ4~euTIf=Yca-h|K^30#B6EIr%dcUkPBX{vn2!vd!}R`Oe{H>=cY8`T78q?^cTQ zeF^dD#1FR_zi+NJZ#5o)&$?T%=J@>FGYde#4m-R0qINIyw6XHGZCjj`Az^|M1H8T4 z4r*LC{ZpI)5Kh3ii6;3%FV!?i8{kq^Y!#kS zg=zjs3I<{Y-gtKk!S}fCLlclwX0pc04{&#Ad29ntn3JWNy;=lJ zNKOG$y4<)uF?VIZc(li1kb$sx3R`0TNXP&+0c-%&Nf=d@1!kRmZ>HR`wt0TaO2VEb zZw#AEE&g=LXvQ6RI#3uc%UVQ_<-<8ReEpf$OIn}buV6r)L6zf)!0{1Q3y)p)OURgt zm{xmeTXd&AItTXaz~g#c^SsAIK=%r>8=??Y6W9ZeqyfjY8J8Q?cuHcV5Ul#5dy@>- z*~S)KAOL-Z9^dE<{)dfbh>2~lkXcYi$WsG~^K4digy>Atn-T8^NQHR9+Rvh=W~hj@5#s4>2b6C=y^%~Rz~HE$S%%LF_Qj@Z7m`Cg!qxd`06S6$J$UUXp@OjY z)-#&cx!d2Q(GY6Q*U%MJ^rDXkv$Xj@#u1V3g*@cuy?W1ss4hq&ryagYY2?$9ff*-m z`}HAxrNSdoyk3IO_3o-9uhVpE^!k-$Yd<&=Y2KISCK0m7x&m5b zH^IKVVQ_q50L;R3qCsDOiJ9=L%<1vEdoP7&@{YB>-e^6I2R>7^iB`7#t-$Xzh8V_Q zC|n2z0e%BHV6)FA&%@?jmvp5Q;caQDA*YYRnQQ;7B^%FZZGe3-*oN_av z2}ZW^O?7@~E}#e9NKqc^q(n$S{56{_dz>fcZ+D+ifExf;tFs;0lw{{ybavnF{UnXU zvt7GhO>j$`0iC6YfS_z&9SxyQ$7^2l?L@sA7l{@^0I!Q&g{D z1!XM>It@tZ23QE3aYfDxY={>tn9P^#Q z0n_$zb4Be+FHhuQ#s)Z4ek(MjZ)=bT4^&!S%KV%K8onKhdRRaL`p|qdh0CSi*!$smgb{siZaZt^@nI!xsh2h@5bb8xC@!C z#CvhT(_#HEk7)w;7K;gcl#1aA+Pi)RdkcuFdL_H%TozL}ffznwQV6!@4tWSK)PebU&pf5p%KKq#kD?NWH1@EwJI4eY4zX1LWhetcwxt zS06s*vaa{r*gne_G2-1zz+P1*HVw}DER?Va+C;mzK4-4xqyx#f2@$cKCLderP*n-8|Wh zDWG!^0cd(Yz%6ndsPC16(K;aYs154{hN&4KG7GMg+!~Mvdkdk{^U}!sl`b9r7*>7-Q4hi5N`E?+-^iD;9F)6Jp z@mIjtzzYR6#V2iV#D!rbB$*qerWx83XnSzrhGc6s@U>PcGi(7tG=Vb;PsU#@Imj>Y z?RF&2c^nWEun_gE_rAqK$>Ld}e@Epd@lXGu$YAr<799Nvnwv;UQB1ER6jE_C3@QdX zV9f%HPJ3^z?nX7BTYGi@$?#iF`dW~-7F=ugQETa#C-+1X(^?pUT(}wtl zV6tbr9rGb!IP$aA>ct2VZ7c)cWKXGL8u!5833bqFmK+whTaxVYQ@el021Cvg0w$2c zzWw>+w~0~#+C&`Y2T8rgJ=Uui{k;d3et0?#3@yMJ7!z_?v2iS>9r#zOP}SC*kl5#t z4k)Z261Ry5c!XqpeF%G0X<$CU`9bj*@ldLeXU3gL&He>JJur$&jJd|h_R23<^59zg zo8dx@Mjm@4co(6=g=3=<+6w*;>qP)g$XRLz4~3@B)0rQcK4X&LIpFlPSHdR&o~MNC zS%#4JM$8**nPMTFWDa;!{x=E%$!maPto)dLNWzMATaN8kAGp-Z765Q)mHsxl1`uT3 z!6eBnOe9(=-Z#2I%FRnI&qRLpo9r(BaXY~p^Ec$IQsDWAv;5d|x*oZrUZ`7}O=r8r zOk_?t8j1|O(SkGs1@aIoP({^}Q+wS!6D+EI$R;3Z6u~9CW-vMzx`!YaavAgq2>KQR zXQzhDXVP4$GHQZ+Ivo-MQdu4hYv7&WwwBM{eI=HZjJwnWptVRnKX(T29C2G-;!71S1jbAfZ51B&zt?^B+G&v3)~y{Tp#r#jjhHj0;I(z;J>pJ zRdpA_o?01)3atB;VDREm5z0c+pRgX9dy-lX_JvmIhbgZUFnxDZtfK}^G{AH_gW=M* zV;UcKVNZpvfZu_#gZsrW#UR5DKqKL@F5d%=J5=>~Z9|M=OB9!uV9-uTNZ%wXF;(!H zfrb^za2!(Dco6|FSJ4j}+`Qh82Aq5%glZ+N49T-fdt^% z%&m5r=r4Ajk9Xa7{fg_KOVx}UhVKRV&h}ljyCF!&s2D_m`i-2;eL%;6PNf9Wjb&D1ZtZe%Eb7!;Cv5-5+Fu*i&`gv>f zW;uYW0fmHO+YfkVR`~q;PA|83|kLE2A*isSLHasUdT7SN$5c{q77(? zS%ay-e+zQ`)Z7+$KPAr7)4>ElMw)C5@mFl1hBnAog+$Z_CaeK-bstdf^$N~0STgY;}*6b=ErqBOjr~03G*PEQJ#uP$=n&gE0ffgC4JKf)4Pt~rw%}OynHy? zLA4ReP9}!Da8e1+@wr#)JzP5BDL-SNqdDvfPr5Fv^Z-!(qcS&0%kk7oFWv2Rx}Y`W z0HP!&|6wS749Sbt*OLdtL|+l|g=}LJ%4z!~Q(a};U3r8;%i|>vATI=9%$3O@eCHED z#bEz86mN0zOaQOy{qMZ+2SnyVU*Dj1=@LITEZZ*3yJUZw=7N1XJb{d^XFUZ{_N&EW zA3Z`F#P?>TizHV~8R7VGI;k(ld`?dw93>7}?#3PucW@1XR|*#@aT2En=z-1a@Ue9H zMl_$dd%Xz%K2J)%zZV1Gml2hgq8bOJiP0P*cfd@=f&B)gg6bZAIz(E#U>a+^>OXuO z!-H82?xi_!K%XH(Y)d5N5aFWyN5fvCON2AC+-_q5wFhr-r|&#>3h8cicEt}kDpI}Jxx}ThsYoJ`|#w<5)zu42GNmMD)z*DTl)*aO)DT& z#;Bf_Q?WHLtcn@AVc0{HufYr0bZkDA5U|MG^R%P4L$?qhL;cY;9j5_yyRdf2voNiJ z-JH+3Jx2=}BS5GW_@GuFmOAhbqa~O~`iYUk*&^MD*m$TOYR}G#_r;UUI5DhCFu`4 zlR*dwd3+HYJspk9xPsR}TzizMhfTP-Q5PV@Dg^`r=r`4+T;dQg;3NjN@;Y@JW)b$6@a@_y}9{~L^P!aG2ve%7y!d=JX1ktdH2V|+_B~}QC$11RoB~%h{cYgnI)hh82wGfOF=i8b1HNj62 zv)0EqD0d9$4WfG}5Q8?oF)T&Dg#scNFB8q%n>JoQcGwIxy*&fgjPJhH7Go)5(ydn4 zw!7jE`ctE({wb@AjABf09SfZUE=%-vYsCM~qY7h|D?;zyvqay%!X`m53z>1qKMJuI zS+BMEvAW;}d0Ydmv`xf{iJBdJTC}=gQxMkiXR9WC`;@~1ydA_uzNWv}sD-Z&YuD>W&aC7x??F z9&=*xu*%&4pozV`uwH{K0||ck_${upEHOwG(vY`}m*e~WVz}^%{mZr%v}qD;(0H#G z`L4~B#O=t=ru{;0vqEkL)FfVv)Bo`PzNwEZlu6M~+KIfEZafMDtc;A`lMVcK_P59jPR+ssq4Rw-kC~_g7fXn*7?uMD^^>oyGpN-_ zN-ZFcxe#jckY~q6$(Dc^wd0uRMq)}b5PN+fV2YqBY~$lLSnwkYf%GMPfZQ?QPaMx6 zQWA&MsLnT-E*YNp1?USf&M&_1)KC+JvN$^AV8>x(>-fIa!*MO1KL#_qy)W`o4n43; zdaU?JANZ^PupJ!Q>T@V5-VD%hzBfU%^*IbDzD+Je973gQ@O05#2PAgoL#jI$=?+Rs;r-#$9LH~sA9taOTyA9B< zz{ubBML^XyKuk8fX3HQTj z6+tOraI5)Q#vLFiB@DoOzQM8)cGck{O*BzK%g3qgR|UA#OR!&@)^{yN6`>2PZM;i? zUZ~9vu8gnroy7PH%~FOZ47lr<5L2ii9jF~6*uHfn%3ejs9{@v?d{v<^7&80}(_c?1 zd7c;)D#O)uns5Rvo+}-KRz^N}510$e5~0sof!fh=U{4@X*ieBj)=ic}f$Ez=wS zwMWpe9lLr%PnC&L4u&zX7St_2U6-1GB&u!3Y;4PE_*PxRdjRfG1*h=WOsm00a_80m z<1O%bm*m^Fc+Thg?HOx?yiLet=FLk1#JHVU(F$a|o08r7U;$Zv+!>0DHtBKbPK;6zmO!La16F)igJfGB_$cN~9lGSP+1fAr8)6f~t&i zdZoGs?KF z&q!C_ka*LGBfim1J~270r|4m49t{bv!-@S~X!{wXnLe>bR3&9b!oxcrTPy4n2v zHZ&^%W+vQ+Kxk`k@^1nwLuGj}#Xt#61*Xew#F_W`Z#?nUYhXH*)-b!)O^# z%&|(0!Lr}psUDTtN9HM_bUqYOyANTS=qswfu!-er4lJxB6oFZwYJum+Pi=ph9w?2H z#l!beKt{f6nqNw0>OJam?-JXyRtSC-Bb9~(-Urev3-@7*tlrahK04r0UuIHpEO!Bo z{?LK9V_ol1ZHH<(6Nuvx`Tna!C(S7x6ksn0b}`GO`FsXHAOYq9dWt{3V;>BU+zCqx zj|npjRi8UktKY}2a8TRWdb$U-D!ZC~k?Hb^lf1GH3Pz!*SMdQ5*2=~wQ!4F0_YIgI zUj4Q_0Uu9?QlD`i&O5vVV*pM^EYHjlCHeY+w8?SyPyv6-Xs`k0Loce4>uI`~?-h-` z2&l5Z5T6gT-P{xh>Z2Uhx_lS}O&)x~T~$=yCj!BFe%4HWob|TtK=H)er#15e#G8h? z0b}g2$*2RLnnRWjMN`}y;Xt}X#>rBl@@Brt(k$0tc|!SWaU?JC5Rt;b$d{Gvgol=M zH=L*7l?bZ=ai-`%N$EwpwCD{4H5Aqb_*0KEvaSIQ@*#E4AHa9}La#Wj=mED@2jI|r zZU8XA9ditb^ic#ozdO!JX@I$0cAwi-U`7QS)UNT9ZxSrz#CRSx4VAU`#=(IE+FvKQ z{*Z^HiNw1%@=*A$17o4$o;$K}cpVU~3wADt%8_3U!uAM=%h4lmdjMLxN$u)8*LQd_ zX}_|jl^1&&zksVUg%tp3<&aD1s@o!Sf6~cA4`9IqtS&KfFi*9Y+Zww-UKd`C0=`rW zj`|m5T`GUoDnQ^YVKe}TaHl#42Ao#_LM>5}vj8lk=v|O% zS#lpDbV>$i391NA8qhKM$J_h{YaL-6AKrO4vgqubpEopy)`|R@<6UdJp4VH+Y|n3OK8teGmbW zHvwoEuK}G3!-+v~DAPcbr?yCoo?%~5ct?K#fpKEmEiOOS2P2{;Dc!W7+UEv5b?bRR zE`x7@HO85S66l! zCN(N>0I(pg<4r*nPwsfwkejXNZ671!I)ZS)TRT)hPrx$xVf!F(Zr~*is{BqUsk8lz zgpxO&?xJtx>7&?C^s@i;ZWY8Xf+V>;kmUzBq<0|oBSxkJ?>6~UEia2uWB*X3x{a&d zmLbk6P__m$w%EKFrAKWZ>RV<()g;@wc@0z~Xp^`SCZt9vMq)vB2n*s*C(mne3Vkc+K8Mf{KDAK`lUoF6b%5{+;FsvpBhaz; z=TSB@0T*4N9%cA)@C})C2~vfZQqi>w2dt$1qkY5nwdHSugG^RoW(;-HWq28vf=R$m zf;v+!9bfwfZ@{2r%Ks23OWBjy_5|3L%ba8l3=gN7;BhItbcN_7{61L(>Tfxrv`qipQR#&)+FSu=QYi~c-&J^;x#LL5f|_>9H=ZTTRCVyF}(a_X>k>- z9L}Ef0}6e-lO@c~S%2?ELY@y))$>LT@8x++kjQ(#fmba$z%u5i{8qaM#b^2f>Zz4T zYk{7`95br=^IAAo0#fuAIc>X{n982cN%DJB(EPpBljYADBZ zw|4B>1!vde4e=OM4L%>`cg{fV@fKv0Azw15>w-L7Q6#1Iu6Qr%g~y^yYCy)wVorwC zA*yZjbFMSr9u#fYYXX?paR4T$Dv(WtG{u$zh{xxsk_LPX83JvYMJWl`e$_i$m_Q9b z^@fpptT*j|m+_$YXjKVdZVFIqIVf%PMk5nX^D)mNztaU;QRM?~Ie6dH*9^X~YQ1n! zYvn;wk|lqXddc%cVkUZunZS&HP~ z@;rFME#Pr!zsYEvO=&8l^@q5Cc&tS+Tvp$Ydd1&mS!F(eOY|fTYQ; zKzw;$Xrtz%4W1n0;tFsY)B>mcA4Hwmx}r$et#1hs5Dw`P0YL zP9m$RGWXD=^lyv99IiMqe{h&1_LaQ^+s>Xbd~*Ef+Zh3EhcXla$uyBvXX zKt(81*LkBa$D{X1Xc<6BQYE(Ik<{x!7UTRYpsW1XRz?>F=68Ahou0pm)UaQ2%9)dxPnhkH8Osls`qU)f3xv# zUiE|)8rv(5FM6;MT%CM`be0gK8sSn&gd>H8A89Ocxf*+$M;aG=Il zp4pQ?+#c$-gG}dmRuuRMp6YIQy+6oT6VE*~X1=D*_Y37gf%~)G>rvYDthB_``-JY) zEw1(vb{$0FdoXg~su?t>d5(WG6jX2@D!NAE-Fb@o`&&L_b;nD4^rOfk@^JGVue$LR zJJK+0S00+6Jl?E)DzzrAJ_n2XDsNS`qfMH9P8H!F3F59!Sm-l}wO^|!^qn4H5|Zx3 zGG0tLStA*(8&{A%XVSR{+0v_KqK|kEIW8LT#{S(?9^poO)Jx;()im?e+FQVTiO+!| zqccxl@p?G?-7Cg^`o-x0)$ZL>Wmxx2^IC>4v(t&&(&rUZUBsR#?%mh1TYBxIpfS#Y zqdtU-?EWz1L&p_rfV5TENJ+Cz%LZqkWDx34jsPjvh*oVDMWSo>U5gboeSTRSmS)(I z@kl_~#=)*E?t3%Yui(QRcicy6>(0yft1e!j=<|s*BwIf;A|8bWUGMJa^TMAF$08TY z{j5knnX~|Mh5r?N3UIx>(2|Y!NyndMPbh6Vu4b6JP0}O4UqJYvorzK|_m$h@4G`6g zZaK#sBscygfVO(eP8(b7W@?A^n*7^>VOZ9J_iV&#gM#OIHekJjF45)h^;?DSgcXV; z=Qs95<`uob7@6wx39mgl?50XMooeW7YT^!Lg|Ff;d<3(DNt7=7v_5xIS9}gU#yj_Y9qBlIMU$#fu|m$P{&WX_h_s&botw5UIY>S7XdQFG z2Kf>9mwxI+xD#>(rFolLURTopIrK^0$8FCtDYI$RMQec*`e21W9A}~kSRYr2l*k3RI8(M0BK#Mhypruu zW=~Q@_IBJO*E?l`s`FQ7U9!vb8opNfW->Jmq)(pguSo)09a-bAsIsqDmobe?@FU-) zg2Py8Fpu*`^cWAD^9BVx0aNPB^WJnqAC{A_RlMQ`Z-2L&N?SASE#Hl#|M6V}3^NXO zXhkK>!=fdw#(Gie>#TS82F+E(fIIhdNc@*Gd-uuo<|NBt{MwEFF z!uaCw1TFPBO%Qzk1`a^S#q~VklZQe*7)GE{?k8&o)Ccia{A5%F8I6gEoj@o*;hX)b zRt?H_IsA{ajl(m=PkaKOVgh^*UKf~d=;lwT)P!M2r{60VciFu*;Jd1~g$5L zLeA1?1^~{SMEg!`ffz$o$Y9%%?gVjdn~u$T1l_JGz2mpfDzZ%rD--to~Cv9pgQnyq^b!TIAe zZM8mY-vO8BaZEn|hY21Y9PQlt19O=V@8t|eG*KZD@8|nS+`Tw$mnW8=@X`lZPi0bT zoQY-^hyh?U$5DX`#Bt$P1#3i-r%jnWg_qJcuz!MqLJGiTVR}g-uv+aZ7li# z4LoGres^JSlB=F6-`Ft%eNVl^?K9v1&RUp}9t;k~R5EtUJ>ewi>Cb9-{v{i0Ngq$-?(d=I=468t*680hxFcg<{?|M!kTt5T&;n z9EvNdO;BVA6XG8`hG-~~Z#-WA)Rkm9n%0oar0AynPAP-BQO0a+BeRc`DW1fWj#F*oJ02TZv4A)PsE8-F;9x^f1id0B;ufv{p2gsjKOD5AWa$e#d)rLmh4w*Q3q;4 zW#eG&Keuq~zz@9wk_xSuD_0Ab{6>S4^kSpQ82Mb9015u6zkUqauRhvb-}}cP@KZ{q zdbrSNc}V2n4Ndo@{eB<~v@6KT)T{}U2B&n=NdrJ4ul`%cWd}{3dS}9m{_IcHJ*)<} zc0y~)aXI|WuciU?qcFj}6D;IeUW*m<$rJ9(S5i|G)l$5LK7&=*<6V(enj9Z-XOeYg z130q%9`oQG;$VQ>1WBne_QlPOYyjcCH+Rr-Ur!M^2DQigk9W^Kror|3b$wqi86gFc zdnSU>Yu#W*?LFu1zHPJC!ByfOm}0iH$_O{ZD_{O=kCsf39xI$PKZo~#btfA?{dnpQ zo4fzu!uevjy(c@5Mea9zFgxfPiGEM^(32JQqZ}xIH54At`*>s11S$m&UhC2^3+G!Ol#Sq#ymuY=37=2B-oM zA``X~Xs`x|e;72|-~T@w?p2%@imD__eM#0oh^+C?K=2lSxHbIw--rJAZzIP4eF0ak z6fU-u>K)&*>hS1@ivaxZPX}>02a$6gy|tA4D*2zVtiJ5YfI&aiXvy8=)I6S3^?A?J zOOFytPjVG-8a2flivRoL28QcdkTb$4GfBb!96}ubN!2iI3t6^>WtxJ{Ug4om12I+u z4pzB8!VL>O{3^V%@8RKz4_Kzkde%!dzQjE?=$CC*!Dmx_A0n`BjH?dgmv*kaH3-$jJ5$Bd3Bk|5J+?KPp@Dc1)AP0}U%1oI$qm;&?Ychh{HN7m z*E-L+*3aQrTvlZdnp%u+Rgv%a_aX0j9cs#_RmthLRv7baQwWe|k=P!J|a^yhqPqJEwuQ8ol`S`r2tcZYxVhY)}S3vk9K_5lZ9KdX;M2z7N7o zC`pzvESkhP{F(pi;k?E#G&k_*9?)t@ujsghIZfJ(Ee1^b(>O=#ko8r;YO(*up8&g4 z+UOr2a`WoP7#>yq*lk9#bq!eKZ|tQJmhMM<(Bw%adL0lw|Jv^xG^ZkL7&)E`NqyL> zUT4hBgGy@FbJ#F`71LGVkiO>Q6Ce+L?BzbqZ=RoN$xG$szmrLpV(1cYgxiGe@b7Gc z^AjxCdP?f=J7!yCiPAB|)9zGp;7)2n-3)MfxgU<{pK6@TnV;($>TT4E9`2GIjv8e&_S(+Q!{@ffS4f`=JPnkOE>fRpY z*?~4x`R&3ZS;nvUON2%2o*KK;NPmnHJpko37hS|RPNBsKKk?$G(Rlnq8`>TJP6j}Y z$n_t=ycJq1V;ze4RBt9s?Z%U-t-VQD#@ID6GQP|)u{W4d9>^^rvXMPf5Wn@qhLhM9 z7$^rpqG5^!htHVWyD}4vBVH?3RBOtrciBw|xdTpmO1gg%z1Cbh!dW-9mE8a2`J)AU z)sY%^ze%LfgqHDRpH9_&mHjyUp2j!y8}Lh=_8ELyGf`gNF4sXg8?>UQ( z8%yR+*}uK^Gsv03S65f1#7BV(s($XsRAf(+6&oKy^_L8A`Ju;mo}QnX)?F;?(Q%B) zizG~sE+?OtT?s`@TOt<>Ex-{ESNC$r0@L5!D7P0V;}hlfy?Sh?@=t4)J`O*taRx~3 z)Yld2vi$V;@GP)ROpzavsZ@m$Ts$DlpkJ~%la4vrl7!{k6t(Pz_BxpT7$mtYe>6-O zerl|hGP**L-w|7uzJ1(9U!eLPRQI_(d_fiSkQd+1vkDOJfo@*QKLLrjkUMDediI*u z?`c38D)$ESqZzBY{V)TD9@1nB)uvg;P(K!$JD02ec#d`KQ|%dRG^OZ!i0cpgv{ zI|~Rczi;`D?ER?<#6|hQ$+29%kHk=1oif!jcW$H_N+0Oa=eRTc`McjZTE^;q28|gU zRev>Kp$wif88GB2|Tl(j@J6=PfK3A zH(rw!Lr~C@1`-ea3LmgGY_wU#j(B|XtRAlc9?2{2@}H>or(_;Lx#L`RCZEXs>EB() zWcfFN7U&|HJ`i$*WR>@VCw^VT;CxO~l6ICb;M^AAj zXC$)Wt1qJM-QTaDVC>19C$08L;McVz;9) zIC&m_=|!OP?3Z6S74*gkpQ^~9JpWCr$H#T8zK2s^V=dRU=bLOUCq&wO+U$on>N@ix z{zMF>;(j{0m|N8yTB48m^q_7{7=OGdL-TN&5^_tOv=YDeMp}9)I?aXUoxyu0jALB# z=#SXKvZfFE;FRR2nJlG~NyFH=967!Gr#XU`h}=_T!K5+Ou0JR_-Dd_&?dm($8yBc` zvvhP8JWK1E;xXD*`AWeWCG-Xthk`rtIy^$!23{oNp!8H8n>PUGC`0$!wG7P7G^`9~ zAhbIv%bgc#WbiHX-O4|{Ao6W80ZtJgNgux*8hPYNRdppFFCSVOX0Q$X3?c@6)!W2d zs*tsxJlq>$sOcVS%QNs^=6R@A7G^ow0R3EE(1r2$Wf-C(_gcx( z5g$C%sDFVN_`P`d;FJ=+R2^`Ps$MX_=^!K7-ygsIFRw7AW3=stmqTAUjH8Jrn{u%r zUy+07T806rVLVBa@Pmd-Ouy=%2RX&AUVW!;`moo_ySTuQ2>pNQemQ?1-uWGI_TfAJ zp}T(X{G`*<2B$M&Xo5p#L(hdr=3)Bhk%@K)%>wBz*YKk2%>%Bbl;a~178(ry$&}@C zz-XLY$wD$EKU2eHP6Ar+YekrsDO6mf6XSJ!zr!CQIb%m1appr(3Fw1T&J*pC+JW{j z4aA4g**7bFGZg-`)iy|g&*LF6mtJ+3hxB{IpW$x#-2+^PM?m*lGF`T+K)6qLd`@f% zb8u@6y_55UL3Ud7%Hbt*(^pG?S?Q~|e3J6%Z;b$+Gx|LG>t14dL8JS8sez4#+GOuG z3tm$A00}=$fV}Jcd39@0!ZH|i#279Yud8r^*Zt4g46x|Sn}#QO#3o_dTp`8(sxdvL zWL4`wwqu34a_!(@^V`6PqwH&Jh&}`PqFnG9aF71w6ZDTGI4#D195cw)^Xj~AJ9lMO z2ObULw7R15N%FVxzLV?wRnw*An2^j=4(+!Vcfs4@OunEzi{ApRwGUcNg?3qm{D2D6 zX_75=ZiH)sjS@GMETrZu7|1aS^90=?&-s+O+3$=hW;v;K;88T#jleu6`%XOlnnXyCr#B6*6bUXl17ubG;qYKhFc|8q)Ii1+zJhE}WZ$Sbkti{Kr1BgEzo?-0s(dw# zllj6n43(?cgQW6~l5clOb8_EKolZ-3m*lJ!+_=N|YUAg)cP^y5BRnyD3c6)zG5KoR z%FY&lvloL9L%;nZ7wS1^6eviq5K!I{yQj`UVwbEC(Y>uphY+zDnCJla-qqgiUICDy zTzbcAaDL})e(|{leo^?T2!XMHRgvZ=bhYp!`&&2GqgN*~sz3{EKd3qYy)RNk;{B#H zguD+*5=E`ANB?iS#|ikV0vTLrqCm7u^g(V%cLTIkz}du2qHj1n?X26!cq>o=sslti z-#n_h;*C2lYKUKbOJ8n}0i2G?alv5u5~&ktO84&(j>-g}-mOuv24jk`U6Lm~W@$=Q3$d+P)Kb1X(vT8EvU+tg^h zU&R+%?x%IR&xI-9eW4F z0rR=tUF=w-1*2Ab)u}B6abZAeykyj=@`d zN3j3$V?aGdi6M{Gs5hK<)@&_%PYQ-JjzIYJ7dTqHZ% z5~`JqHQ@i%*OE7wXnx*7k>mKs&q>m~aLxcTt$^fPQ|Fn9pM}hQ$AZJ9Bcq)S3goFm zo;?y+uiMhlV%ty+eek~S0LqZ^E-y_+UI8(iSW#cWooKES)HI;SLz(^=^ zIziqAjt08O6=cOFDoc{aHyYE`{%shr3WQQnz0O;3Nb$lWW)nnOl61A+5kJ(_1iq}E zGfczV0#-v=0Wa!y!FN1eH>=A&-G!96WO~q><_$? zCV3>*WkZ=;?+HB=9c~vXo3~%4m9h=9?~Jqf$kGeZ03+gk-$USqs;ZrN!|gtA4X9*5 z97wFlitr9-gY3Q<;JZWF)g-x-lIxt2DAJyeUYDMGgHP*9ON<2fz5oK_4f{Q~{h_Bh()9Zq{Bm*|$(yPq&; z($rl((3(&ay169x-F3BlGH7P=A)C`IP; zbyIaK6#ZlPbMLE%yC&Qk#@0azg<}HJ9TZ=@XmofyH}`R!Q5g11DM|c*Fv7a?)!j$rMsuxE5y4?va}Xl1sUXq9*f0ThJ!-D z9!;+DZHqtM&PMh)m5&t7E0b6J^@YtnRy9@$B1uTs$mB>8-*)=6fW3n*^*KdI8`o|B zgK*h~c%dGqMql}O{H5=}h4~GP7`s+*^xae7n*;uxyqY*W1usV|OZ;FOZtaytn2Gy( zL-e9v!ztn>iXl56DKno(Qo^WL^0~V!d1sHL;n}^g@0SoYGw*0KbH}$TpREvZibV>Y z7q$3i_wGnB+>fYR-9>vLsR3OY2|VB(j6%0!$6Y@MGEI|_8-pC)5)(@$V^9cz6Y^8V}WezG%_In zbiZ3RrFrn3mfO4WogSxj>+L)uQR>6n8Myc!oa3>)lSj}#f6plxXWFK~0mE$e9wFY*2&MTy5@WQ}ivn;l#aGlWLu`HvJt==lNt+o##9nGVNmj*d%|dqU{~+MTPie$Wc$P`jCBKba6CW;oTwC zj#p~TCZ69L)+vIW7;M%uOLx?hgC5@Frr&0WeNEJRaE0a9zZeAf<~(t<&>2HYB_)Lb z>ON!2U(16{x~6yi>W`?^z}0CojxtP9W7o zP8P`}J=ijPgdndP@t!s|DI;AMcL3dH=Y7a0r_?umHI|PUy8_eX%#l6lzDMvv7iaN4 zokQm9vf0NI?vK}yTrPc#A)1BOQ6TQ+I8F!{G4t&Gv`; z++VW`2I}-#+G7YcYoTQ^FY4M9RTyN@>anA}TbtiRI=1=(OO2sW?5*PqP=`L{wWvm| z@+SC)@qD)OFG&`Q4%f_5Ix%19#p@& zSz3Xmj#M08X;svt%Z9eo>SH&OO)g1z-$dUsO>(i9%0656a{U6ji5zc8gAx3AR_#6$T>#l@+~KSA9QW>{0-mtFHpZSgl5(*0 z1}KD(&~uY7=gfkdhQTT8c}B^1?-FghhDU6|n7xv-9d#?OHF*at{)UGK+2L32M53MV zO@H6ru0uS)(v{`+Kmd0EpF*6+Sk~hzNrC|K5!3ah_q`BWa|_BXfA2pRSG3a@==Bc< zq_!fRVnKe{N9%Iyb*$>}G@268yprd>uJZ$_6pHcNYtWv_@9qs#T2zeMfOHf~L$`{CcNrlU1!K!K=*f`BqDbtZU2}U!<@Llq{o~XZ z_XDiQcuxOZPH8HKbu8~xKmU;yN&Sl+T4Odl#Ie>S32OfbjOvXMFQu6LvTcW}4H4K= zhy)^{HNTV6n9S2ix|ZId9@51fdC_$ERZW&?Av`iK&;!sRj2*an{7dia+OH~r>BoNc z1BEEH!X}X6dt|yw>Wj$V+KWL}&vQgrr^+gg5j+EcMt$?-+P=8^^!m zZxj>N!i#Pz6u&bR(`|9w-Qn{9OH2MRu!1U5j@HxT2mL{sqqPl_`w`|q;;ns)q`R7h zpIC5_nO2j02i!OM=gMuN4Qrv)Dn1&P&SQkRWW>pi{7d#1nU;56t147@+UH zUk94ckgl*J4wnM;o374iKQ0@g1K|DEvxGBZiLA^Rk>d3u`MwC=DMxn|rxVhSq`T;L`esFC;X=`0D^A9_ zS#j?sj>^;pz)-(Q_A@aLQGvfduy^#oIVh3N$kX=mbQff;TD&2IS&0gO_*EH@1+2-$ zK?=b&3GbA2F>K|+^uK9ApF9xND=plA$4HlnPYgVboTSx!K2Kc6$?`!@=;e82Welm* z{;vEjKn)A>(=s-hDlEoRk#mapL(U=S3d%kzUj8Z{Noh7Rm|C#xk&kvse^3Yk4>73K zgv8H2E)fqQk1bY1`On*UZjqz_#X-COU12@`VGOvK2dD|y+*-pY7&;lTwcgx(%_Ec+ zh$oBWvo3?zVb#>~1+|6lV&?(KByl7XO=FM+s09Y1iobVH-g{b#{J17ks7y5RvmO=X zbO;hK)oj|-TErwNLgm6sy1U$noA0#VuC~=G0lLO3%JA%0K~B||=@ZEh#dc>fDqGK@ zPPMR$T>Av1v;vxzpMw2k=ho*6wj!2S;Hiha_yYQPK; z{m=)xOu&NOiJ9K5eM#+RR#Kry=`O^#AitcKCYp68 zaS#4L-oyLjyU(b1tNVyommP;?`X@pNA6Zj{E~14n z)gW=9_9$R&yYvvXA%5z7yqR#GfvYFqli$zWxB}B;qtla7 z`cdQn5 z>(Y1qIsC|d!V}lza@(Kel4k>gI0Z>Uyit3cz{kd%^0HTN0Q6YBDS^n#pe1FR@7L#N zD=FH_f61_&wa4ng@m9L(OG6I%!N`{pAN}_2NrLspy3jLMc^J$t@8@>PRLzE4%V{nF zoFT-s_xTH)_WrQV!sLj2&GX0~c$!FpF?eZiZnyo;dz%Yt2BKaf9r{1=B{{1TW+#nK zDJ|gIMR$u*+X}Rd?e&ScBOVN{0o-v>vVZNBp1dBO4A%%`0vOW$(W%eauVzqdvd6R9 ztxm0>iwPk-xzl?E{G{h+Zyv9)k$;jsZYI3PBf92CRmn=!vuR>njibC`mXbcm`_@x9 z2_9^3@yGy_{5<0P1AQW?M}-*`KLzJ3*3Ra6F8`|S@3=>>8Jai)+mO@vt{M;hzDwr~5Z2bD=yVqt(ICrfqKsoL(UI2$l4V<}tlX z6>_4OQuq*Uh@o}TS0`=)u?LXiGQ7@JY4Re9t#kuy&+PVk@uWP<1d{XuF< z?kjxGxx2OYALm;n&x>TCY{($0g3HP3zKrD-vWY;G*h7I}YdcUh*-~;?Zl6};Ro}n9 zFi;(ACuFt@h4zQ>dMge1O$v;P+64j67(GC_aJ`n1XMm2cHit1cVD4rv$M&0(`s-t# z(N`rk({mQ%H+PMMW5<{BTnOxaNgl3?R_YXSp2ikCNznlA*j)PzCX+y zdbpsw1&IS41YxZZWf@~!_GF$@Kzb0Pf5+#C0Eg-8qvVUDyCRXtw5s!%a=tH`!9nZ~?({Uu?hLKDKSDonK!>*xtWJdFDM}=D;d^ z!v~)AUKG8uHto^_`LYUg{CU58-zWwN6C@!COUXW{Z36~y{8hz~CqcCQMCI2tt!$Olk~}5|Xuaco zEgg4ZHm16tk#7O3)>;uO#r-0nQDA)10~;ZSYQ0`GDeCS><~;kQ@#XK@2e|_FQwpUs zxaVgWbu=_Y93w9L}p~;9U67 z$M3HUvGE-Kl-#6j`Hf-Bv!-w&j&`yJS|^#@6V8572-EV383}?9;$sT1 zV99axeiU?&UGSO)$IE(=O{$$Nir(G^LUv?Ssq4j(e^34#NCBaR;LJDx2f7_Iid+vk zhu=sQM!aObCm8SB+wdER*4mv5slk;2A016mhU#y@hWg?tT;ldoDqt-`nJ(Zv;AQxG zSQR+}Pbtm9f=ddMpm#=`z1$xtJy@=&GvL%@VLrmq6Ei}!J;HDK723jM{J5ea&!5VJ zU2LY)jX8c6w)Z}}9sf4J);qM}1;tZw22q3tj7O?(?FRx5>d)6w)QWs)gHT!C8cD&q zT%b{crjGKLYX-RYyc&KXm=8=;F#8(G!~VJWg|kdcM|J@10~R{q`urr!`R0fL zOj0F~ZkL3P(de>U+_$I8#l($2ZqXj0YFI*cp?(VWI^(nkTDzg|ckUB31^9r`Lyim!D;o= zi^VsU%Zh`m08FiTbxtAfLD}A)H`0tNH~#c_&p#+Ugs-7@!MlA`BY-D?tZ2;j9%69( zN0_aCA-MyvE8+?u9}_#`8|ZrniEfnU(8tL1MUpnUQ}(-HsXjVH?T>$aR9MV0gU6l4 z+%-KtJ~8u>ubG_^w#@ww=u3^X-=_;5cMotMecvB;hbF7VZtOnHklImx^37v$ULVH@ zv+tlfKzZQ5rJePXU#KrlZjv&+st}=*)Wu_P@eaSEca2HK*^m?{^lHcOmyMwFWlvci z`?z^gcQ3UM%p+T11H9vO`8}$K9j;RZ$CG~Fgk6m-q~Ua4ehACEhB!1)_X^(uG)957 zD+Z_tt_l4}@@;Jx^hXO-#NYmb|2VH7a(u{@<#2~_*$AEDKua@Bb4u+*FOnY?q9&=|V0T><_xMCxFY!?^E{$R5OR z+EH7?V>bu^8VlPeTJHxD=Ma#0&`mvB&QVu>*`q8yge`;SNt{1N24l#G?Y~seb{#ST z$WsTgQT)*Fr8XF)`l>B)O^&+-V!%ftT-A(s3^bdUV1Rh4F_W2@!MeUE3dQ%ulP>alMZ zg0emZASo-yszxT+dadc%B-oj|ngoKq0T%}*$RPIOp+O?v{~B;wq!g|mUmd`!Ll`9hJa-=q(r)i>9CaX6-Bnb24XkY{p|_G* zWtw!?_pqCq3VA>?4f6WAJ}dbi!S z9fpv1)??YRNMT8?&O(;37;nl;eClT~atj4H6eKn5Z<-)Q53Yn7UP9EKHr#dn9-nfY z-mpzyB=~S2q)#bat71N_YJ=X#s6bU&#b|%@*%rSJ$WqLjpJ!U=Wb67M1+;qfoWD!s zEYXt3DSU7@lBbrTX7tLZP;48wm$6r1V#+M$soU)_%jaIeO{-7`>EsB@&d(3(ia)jD zR6!vl3F1>yeEEeFkCo{`>f>1$R074RE!D7)qN}S6cAclZX!ip}uw}*ZP9dTrkLO0VxyA}K+Nr4j~0wjjGTxWb9l+*dUd#~Kv z_;^ZL`*?h}8~(-wZNNg(259mMe+1DGnZx>v?Vua9dWD<@h{xv7i3eYp0{ia)Lhr8W zva7cDb3&ml)JfdCXNkkwiKK=K-4m20vix^08nbT?qhnuDYx`-17k(~DNj2cIFqxdO z7ksAoKZYkM9iUGT9|m@-wZpU;4(tdUeqDdhvI_eD@CuJ3GA59D(Z{XbzQ?x~6%uWq zxi%9)8b5}_Plcp;cpP@$6@HHmH_zWhvDukL36+bo$C+97e&_^oANxh_Xqz4mPvl@D zgS5g^z!yZx%zsjK0n9alQz7c2^RG~L<=H^Nf?f9zN|8YgPzF>;S(J;okq;ECtB_CE zjBzjmQmKo3r>xeIEvW*_Y2i{i+ZIo=F8-?q}48wNQ}4 zxo)LO0+o90k71KucykTIA+kGk(>cMM&r5cIKWNTihQen@M^qDT#P!<384`Bo!|oxe z^`WiN;T%LBnWpqWu0}AnzAgQWkfkLZ2BsmW89b`ncu!;_s7AEGAKZueVCuM0jp#9ufA=`Q%$h!Cnu zlv(_gH73MyW6IM)7Q8$)c&UkGa8+g<%p`NwcxtPkRZn-KZUX9Xd64FsXd+ZwYc zmVuu6ax0|5$HzeaI5i{D_-zrW{fLg4)LoUq&3{->v!s(-Kpm#fjUAt7;&}n^U z2opIF))anelYJDRM#RIfoJ+YKvL~HpPW{5XMgkplC&)V_3!>;!at8^6msWZ9ET-~_ zo9zLvQ?Sv(5ZlNQuAox~5e+uRFfl7$!L2cqL#qbD#uXXAniU3{+q^-6MyK!cNmP$q zOyp3DiDgv(rSMs)^~WoqO^|=sS03&)GOLCw;B-583hD~#&=;lk`9+de^_WcT4Opn< z${?}M^7Pqf(pVQh#Md8mG;Smv50>^PaacjdP3x?FVQai|vc9RG3B(ZM1qIv;~A1h~EDIL#sr`Mu6%TI^s z20H4=q^RvXZJ}`Y10{nIy znHSC&g_R$q)<;8!9B)bO*3=iy2c!Z1SMRlmm(anZkfLf_7=t!pYiU`3$QphI0wQMl zyhJ~u;By?`8jZ=Qi}$`EtFQnXbZ36Qx01YQ_JRowL-T(RY)f+C8Cd%(kdX5a3iLzs zy$+>@S*aahPbigrJMTt(86i%{5k{J?GgxqXHRyyp=4T!hX@Kk_$-Ia3R3rTW9M+{D zqLgh?oWQ8?I?XXCr{L1E?9i1YQ4W7V568H(+)J{%#a0zW_MZ*|I|cc@{E{(dQyFkH z$UTe?w!)D;Fm<%rXW@bn@NkCl0r4kjy?Lgil82{aDqQMM-oLt?1%3E-rX^$yDhKx6 z;1Jj*y%#n|_=iwQQ5XMlBqz;C8tNnegB6|vxZ7S~Y#XZJr1204Kz(!o(-$&u&L%q- zK1L+Y;ZTT~!P$t9yPLl70H4gd<~vP$Yet&$9>JT}ky?$qYg^lUal#1+hA4Zs74T4o%poSc zKQi&a5p?KQRn<$r>HGd?A4>>hN*lw6d?9ljGGY8p>WhBu@u1F~>J@r2vhBGejDnm{AdZjslmHh6I)z!I@|= zB6)(fJL3EUb0^7hQf}XRaieJQlb<*Yj^65(znk>$jigxo-2bpCDdYERF4V2_ao^q8 z?(Wy)cOHL88e8Dq3+q6f9NMkDeS4LgisvC9B&~}b!(aVP`$>xD ztHyDr#aPx!43rD}^ys^chMInt<;+m>%Qar&4ZXvKFmD)@(CwG$8eNI1p0MpekRZe< zHYb_uH=4rGQcu(aI1#AzN8a4PA2ZFV9k0*ND+(89I-HnqqlL|yx5XPiXs&4bJ2c4J z+!ofX9i*gsz*l8S#F^@zPMk18eelJs6+iN8pPiXGSiW^ULK||&&^I14XP|g>Bo`UY z4Dj4`YP=7!9m8S9tsJ0a2Rm%O5tlglr(YFjV6sHq$zc~CWik5!JfzdDs&~j{3>$<5 z?S#8LILN&$E@bKzAfxNzb(vj-8-9+i+@WxJwDlt#IN!d43VjSwNXRmkGjDj++LZPz z5E%~OK??RvUB7%&r_7jvk@XXM0VPI~x?yMQW)QnbOuAxp1eG3(P zE0B&+6;$0>3@_404m%sx{B@VWa#G-gjax zeVE_(6EPrfF(h;)7W~JZkfA%7wfzGyUF@fuG+-|r%fAWbAG7lGr>9=R;zeb3dx-Ad z%&Q5agWg)wBD-v$50S8|l+z#1Ec~1<$hMBt*zbH)TE2aJSK%+LgJ{sI72dyRRKxh= zpkIteF8m)R`X6qtCN{|((GjP^{+59UpVY${!6A(n1j+63I~ELQ;a}RdKO^5b|K1gF zfl{mZo>M zKG~h~I^Xu2aTdyHui80VA~o*-eIw>h!JNN8w*ukc{eX1e!o@%Mu_giv@Td)tl0})E zX8!J8Z#=_*mj@QI6bJ>dT_cjeO-^`C{r)1T_;fN-hq)(46fd#iyEla4VAFu20!ByG zM@Y1ro{<@0%SvpMpKzk4FY7s+wqMb=GaZ)=s1S9U3(++qN`C5sM{|0yZTN#8Yni0l zBIiSfg-^ zv{N2jv$lQC_&@vvp8rca!~?>IY9moV@bH>16)c@{AzZ23A*e=3kU+Jo`bT&Vw8t?~ zAIB3?`z~{tjwk8hNucYn{PWB!pSJrFKIP0`B01dNVLRqd|uh=D# ziGE^H{E;6_jtO`$u6Lc7#H`s~)!$^=wTz|N2jOds%i)A5jdh!^oQfV1QkBTLlsVDN z&AjareEp99>nqO{6fUzB#~l`!XPQDQ@u24>g{tY{^qscFx7Wmd)F2>plF|KeU2GnpH^nCd+i^y4wlq&C(;Uikqo45x8k&@HMY zDGm8s%3%8(iZ;qtem(W%Iyb}&?QWCPSLuTF=v%l$@q%n?STc^o>4f z4(W}(;b^uaQ!c{nl}?I%#gCgCNtMh$oe}<+2A3h7t?;S1w_8y$KX^P6q{e03^#I~N zVF4N{p)axb5_R8;+LP|bdY=7=2gK!)C-LWbr%-P^AN0OA=3{et2hK4TKIWUF`)}>s zVfU&c9zDnYMf6k=j)CDg`0wzIZ1khQTq5Og%`^=D4k;cWJkO!xT7wtGqTR4__6k&- z7X{mpxf8r-13Xj;RwcZf4vIMZ2hS4L(O9?>*e`dR5Lp$s`Mu_8PvIZoWzeY>ceShh3lr zLzIHiiod;<3ow_MhCGF`DKqAoDx~@2Di}BqTc(CLJWRcJu#U>j@8c8C-T&k1ytWn9 zx-I-lDiXXTC&@wKP6PpwtO7p$>2uZoPiyX7RZEuvVTLh!|2lFQH0hXtrht!lLlU)0 z3XEMrd4n9?&HC+wG(rXzk|NTN(4fKbAR;kZg`z6Kz#X#}ul^x@1EtXApj`|WjZ@Nb zqVFhqpC?kHfa2x$m(qiN7tzuSj*7YvNDTNZ3VLJ_f*X3ZvBXalyC=)m-#`YdBkb4I zt&)IK5F8Ls^eLO3tAHJvS|#3Q_!Hse|K*+T!E7?>BTaG;c4BsF#xFw6k(NOY+;{!w zKD^@}3Q-2pR1G&;zZ$RHyXnSkJX)bVn%swD4`1;bRJ9)g_nmw(Ga9bKjRx4}Hh1n0 z$4d6PcU7L{<{2|k*Wh*EjyDLayz?%<_6{lU=_7>lZG@H$YZ@g3F=H;7!faE#hhv*B;fBQ|+oSWL25I|ZNiw)0qTIFndy zn1=oKJsI0}an9kbhtkkP4T#0wy_uh|%cC;tNt*mns~YP7rGw}LK9P923M~B<4(XGB z-!e}a^V{!pgy#PmSR>ED{7x97gz4U9jbY(8VfXoNr7WKt!~$3O{)0r!t3unpacIsR z2UszOM`=~(8=@jOm_v~I(SLb;xqT~a!19=<#-gf1q@j>l2-f{=h=5LuRDT=K?*0TP zNu>V>D%i7NFl>0I~+eqNhs=f1_UsU#LDrc!10Av ze|n84KBVq0L*{)i{bQP_gjt{cLVZsm-sb%gRrNrZ-Lr{yjwg-i3p6X2s&~zOe3M^G zDl(AWsGsw{-7ReDKdTTokoWLn%XxTG47Jy$EO`2!$aokfuK@Vg9dr+ytP41GR8Rq7 zmZ@id;jS2`Kc0FQQZXJuk{Y5-DfhQq^E@AUUQkxJIS}qTm2v;Zs@8Ah?c?tXO^G;e z{!92a15gvrUcK3Sq*?D#-@wiZ4sTGq@F6v%+;UH~r{LZ~W%P!*!w0-4MW05=SX4%T z7vfF({`OZqnuC-6o89RCtQVOvA`a$Yxw&~}IXd{ur;uBOyP<}EA-g~T<-qRnf|AS* zlyFoYWD7eK0?nhH%irQT@?69K;@-}`lzsDH$kdL)VU&lU#4*C@3p5EJXX$`IB+kU6tE`^M~{#w8%Bix(X@bn?c*siuuzFEg?kIXopGi`;}O9`tKsL%#^ z8b7D7h?reE0Sq!5rF9k+zyuu3Z3^*`WOfZw>v+jKj}}Ka}Nr?fg8TOPrF~Hpt@sGb3yvtEJVc* zv}?buWRt>bdm$|=JK#0Fhq~W0L`(J(1DY5Y-KX?29^Lecp+&@NVg41+Wht7@6Jf1+ z;uj%|&vss`?=SCj6kodcwf-V;VA+uogsWWc$dh(r;>HIkyB=VF{IR%54j|B6+AWAf zj(_P8jR>#}VVOP&bjF5|BeD9$NsIGR#M`mBT(3LQ*+0AV!7_&y<$$SWUe}DjmBNVU zf>c4jLk)+BQsg8er>Ef6Baipnq8Cg%HOr}a@p7L09Xb-!vIbBEbAX~@(%pad^(U3M zikgsN(m4&+-uLakUf;BJdH*D&jwC*bOne!wUPM++m`*Ve9MS)+$zpC+86w4dcf#pC!$I)#|TO6SY?cLmROIu>9cRSNB|EKR&{os7L zaC5;;JY%ScY3T7Nsz!Vq@ISybK}ABniu(%)+^{IFzal^o;g8*?TCyi=v&XxhS3Vd* zj8O(Hy|q41#fH=#ks6nnUWwugblOMkQf}CB^Ipz_4Qv9Raq>IaW6qKJIu4o}Y}hPc zg*%Geny}9%!#&fQ%d+HzK54+fA}+D94zDZ9=%&$>DHI1AO-pD8k|Tf{%NCCLH||KL z$#Bbt9&As)_QP&uQSnk>Ef`P`Jzv;EbA#g@^<4CxU%%T+S#+LU2GpOuN&Bbb`%}@| zH{W1U%!*nPdoUhm`pR?EAOAK4IY{a&QIF0;^q_eRKMJd$0cJuUk34W>V0KQ=TonN+ z1mA6yA8%lM@D(W&ggD@Uhgkh3DA4(%5ySl#Yd)tOdqvgH-fy?L=gS?RN}%o;yoZD( zO4QQrkDN-HbfwZ>0>u)n8N%B6e=_U|-@5;UZLe*;9+_Gs^-Pmq+h1f3($})$flXk2 z-gK5?yU(fGmNiusn!K&ok1Ptvx(KvE%qag(D#8pk>F$M!Ja{T>P0qN(-x4T-qc{5px8CvUx;|6G)2{jh?TyEWaV<2v9>5WswVF4@$Vygn2iFZ*QX zUkech%oI@e!=4Y88SGl{PQw0^-RXz(}bcG{v?iZSrl>UTD193|C)tt;xnvx#wjdY4=C#N65o7X9v=w*}QY*o2 zJS4RCfC~2Iy_hR!)=kj#4zO|d@%^cc3mtgfP;lIDr~ZBXz% z5t|350DFX0JV8*po*AjC2ix~-Tw^&RzE}HWkwM0tu3s*tzF&*9WF4fG?0`emQC96W zB!yNCFVCL<76s-2j=43G{e=HuorHa&*~>uJliAocp%MM~!2pEkfVjB%_WjM@A*~0R zoCZ3+&$-{-T;xCdFX;fn&?T^p_qgY`3ETRh*l*U2@fRu8%r)zk0L86R&|a2?rW zQJ6lSm)Y9l=aan%D)L*BzK)js}7sE6HFixphcA zhA4`NLt<_&H$3M2#mM~XMY8rGE1~evpay!lM0+cOs@xZzf6aVSr)Q;UI$a6%>mPly z#Jb$a&ddzH)h--lxj786KEwv$@tHwwi!R%1Hua}1#{v5y;RHZ?AoKxWy}d8r^?zKa zMr?u|#aH4TvEEmmTwb{SvHzA0Ny&&=KIKoc>ndDozo%O_fZb3MOXZ0k3j)}H=eR9JV)*1pQ!<8H@w}IRe$QKn7d($3~Q)hk=ko{l?>%Y&l5t$1dLI9 z)S6RJk}@av(zQqgpQ{Cej)`>a;ML@p8MIbd+oOku-5{#BPcLdd5&C&{>q{c+ zu1E&1_SxwF*aC&|r3a)GJDBtCce5hf)_JQgY5Psq^z@=M&>hrhdY>^XVH-HronxL+ z)8^#I8R8pIct1b~HwGLXcWkHDCxV_-LnJjK_zor95Z{Rr%xg=e+XBLKHVrLBUOp@jv$Ph8ReC>elck$yOTD54|3hcrjzq zF?=7H5e6wR;b$;?%?@@s@6uf7A5I25Q^e}mff{14xIT~bO`EKgC9XY;GPtG)PHp? ztRX}_4JP|iO8ru>NE-vcSB3LWxKHUx{hS`(2Odtb_6{GfL;4YFI-q8~>UFq~8Vov2 zj=aP-n|5J%jyP++V0(8@-`UMY+ zcSFewLwf#O_kQ0P-tbcjlmG4g@7sFQXi+(zlm9*D{Z9W|oyU!6B2CPh0yp*q@>~t4I_(bqe)k5A@$$<*;N#5Sc9mz47 ze4J^DRgvJD6a0ntECy&tQQEk{hzi2&4Rb-uyT#^4If*h3iMlexGg!3yg)yI ze|Ilq^l81IiD3uNOY7aj|ANzOLN7-hd{cdTJ2U_>DCZ`gHTLdq@vL=pB7UU4#1mg4 z$*u!r|M@|F#9J4M1${=wvx0<`5|VbXZ*OD<$W((I+^&dind3=ks~`vDFN0i7f7Gv? zain<&0Jy^kz~LJ-r?1O{$-WI)HYVGRdm`yUn0}l9p2WlOINy%?=sI?PZm{ic0(8jx zXiEgC4r|*>oF#kVE-D#B;oqd*2jc$>2hec96(Q#$R{kXaqk}L+6*gdLws6%c{@Xb= zf*W)wm67NMu;pd1+(>T4$Mw$)-=uX<{D%7<@JDB1?+Z+6?!MapQq9Ojo_gj+vK~JV z*5_6I^E$XwgXMNdT=MmElf=v8w^`)E5i|fZ@n$q~I1mYopGf5L{IFj{_qk9+BZq;0 z)pNa@rXSLH=3{{ZMn*2)Q~pBYN_Hjr66Cajr)R!GXZXDF!H#)zl=dZ@rXAJ%(6#x0 zj@-dIL~)yESQH5IrmDwZx$AU<;AjUg6_9mVIp=N&HhB+F-A8+!G3MezK_^~4e+uH}l?MrAipg240hQNtu?jww&3%X#v(~qz3q@?)uXZ=1f zbOgygxP5ndmpaA!Qx8nu^hmq8 z8Oe$S?hu+DP4Px48cwqCHu>n{O314dQg`!z?ZZY>nLac?F+%tHwlZ>vnfMo14D5jS z=XR?Q09PC$u_H_Q=fFf*t;rtv=y$MAsok@vMtH{GENaSA^n<;OrLOH~>72vufZy03 z{N`58k^-N@K){)`kb4%HV@ zAGb+L0amSuXn|Byhr4xd-tB@j@n5$IC`s?o^GAbmG>eYR`REYYUdo#bt zZ0S-I<`lFdo4yo8s060_V`*O=hy)T3A;j%k!zf}z=EnvK>^a+AQCahz`i9V);hpMU zbIf-eo{2gfQ3~zSzvOUKNR~IeF+P$^$sXg`n+~{A*rQ!!+x!**3(bt>BVH4CqWVtM zG}5qeMSAuNEabbGOtRhak-6Ss|EUm=vJ^P?@I!O;*T}3-=DZ0b!lVFS6~MK)0Y*P+ zz`;c-x!SB>duy=%=z&=8hQ|h{QwZIF^%MAK$F#QI^np=(ZTnC^6zE*E6Sr-y?Oy$4 zX!;-B7fqA%35gveGolHXsn-u#tHg~CIb5^PB59JZKlJ>(KUO$#Nnox_momkfo6k!1 z*o80N>jTt^WBX+{(`g5tiF76@;kb|z+LwU{{6kV`ezYl@z^!4~rLaSU%JEW#qdUqj1 z5H?_SJzvjTRrF$pz8F02i}6eAGxnrX{ZBc&uH$~z2HuG}M}U!R(jWAhJsiNF&h{`vp6N3+%pv}ry!09o%? za6NZqnBQ0450Y{I=9BXosihaE6JjoyL0Gk1@K7 zS@39N$L)#@y#%{g4V@Kn~vmZAfrEM~8LY%=j=vWDqO8{~FYzbQ!f$+R;F2OicB1l^Z4m-SczCxa3 z@+KO>XSF~qgJ*Kf-*19K)A^@q{xhigFZy7UrbKpuH*F1n7ldqCLlD@z5^E@7&9)A) z67Sh6BO2Q8XD9J`E0d$q(+LW;U@o7D5=Ogqk@)9T!IND+QOsQ&>%bSK+Q8A_i*2%! zB`c@?5D?}0z|2EaS3}u3y5+~ZPNsGr^l&wxyLm@4t2xwlRIulDTJd*4pgUeLuJf2; ziu;7Wdw=zlU$o98zwCGD@-CPC=c}kE3l+}e@|XR-`uXE)mA`1(mikgj_V`f^Ij$_H zs;o~7F_-uGn#&`rDu9&(1gBX1OY2{L6`)^KUWR1eX2<)=ige4N4>ewxlE6tTE%fCB z4k8pnpP6{J7_ESOSIQ1qs|K84VUJQ@)m1LsuxkJb7vt~yFJXA$QU5MeEX+AJBSX`5 zoqOg5moVg>W+f~9sI=NEwhmbKU-~^!FAyE*AN^|~+YA$ZJgi5);U18k|F|0aKcxqC zp*t2?l8W2sp3)9YGwtw-599#qP7Nfh!q-MZdI{KN9+Ed+9k+*H7TTO3!F&^+{!ASw z9BT zz?~$)A9eOhH9K0Rp-6?nLs{-MK7CgkZO4C0NCI^c4aW2_nPO;230z*fk-pAe&o|Fk z$A9ZKOzlGRjTBUX;godO%&2J#WX4cx?9K^t}l@tmwPm9rlF0I&eZ7q-`t{=3sjl&a**loZ&$v_BR?dEI-&_5xJNf$^DQqZ91N$HZv z^RS0Ne3AjVBxn~Y@K(2{FDP;f3M#igeKQ&%EyAH8B*Y71L+)3S`AJf;d`RYD=3qGHWYe| zbID?~=g2wrs#OMO;DskwXhKSCqXwuG{im}nP?XT6JZtm)7jsq(4gar8??|hnHB(cUS7C!=x84lcTn_)C)TKoQ#!eVW%?H#F&c=;KN2mz zR(F3+!TgbpQrG5J7vW7KA`Ac5EZH)%kxre{79rxzeQVJOH6~t5knq1;q&iF?>4Y|i z5bQsH%ex#RYST^LY7_o>Pu@8iBPd}pZrxSb_qLJ$ywJSeel%V6_!d1kC}k~J$F||Z zAF53ut1#44P^Z|U=3>-wG>f3-=s0IABRl`Y);N~PuPK~z0%MMct@9qRG%VfL$#rX`fnbc}bOTm~PBe4+7p<840(8j9>N zNZ(nQF^K-`^g$uyd&S=6Svn)CPTwp~aONlExAH9z<2zzMpbY`_ZLc?SwY$>Kb!YMi zPkkVO@@(?=YV6SZ0f@+_D?v zrN6(UNl#7n}`VbZC!MUeIUy2Pea%J+6U#I350I%_r1Jvim}cD2P_a zg3aWqj`Q`)8}$a3FFP$q5JS^WfCbA5rx&%XG^tt&MiANOT3x-& z|CH9f4y&i=j^I;D;CSPL+BqGArD~+C0B7E;wa@BS~Fk6U~^H^=|+s>zw_Gv_P0rk)3JQDAYGPX376`Y4qs zF{sc7XWW9ZRe|lHk2O<<{Q17$s$QiAuwe#LFh;&ip>oT^N?&I#?%()J^gCmA?PKB?)vAN21D92;`y zR0ngafF!Rc)~Yc=00nyFFw84@V&fSV+62Slz-ShY%Fmsg-KO=;+ts1%|4)1%VH0z(j>x2Oz#x_TY`5NNdr5>;fnHn|<6@8;lRDFxD|2$R%8 z`w`ZLEkMc)8iKdJUw7;|Wy#m^poaU-$6G<|&2_H^-nQZL_QjswjHa{ttJzWK%NvyN zW_zBWlb<^R*~KcyGc^Yf%S>nvG2w?E4+!<=L_YG?_^pO5{m(lx>NURDOL=VWZ^Qtu zyBbSwO&9D5hzNdvDK4+~uGb}3r0(QG!Hv$SuB=1$ILpr;d%gQ>-wY{@@G{?^%Mvw*IN>|3D;|tr#4!uD3S=rC) z2VU+ak^rDM%bfU~m>FUm$3EQKkQ*BHrG}iG{OW#vu`TH9tHJbB7=#;oV9XsI`rKh` z?z7Ejvh97gSU&8x?PN1e;-S2$*Z>l~~&F6*aS5#Xf zm{dPWKh?=E43HbjihhW+&dO}vP{d|urMqT~U-?5%^T~hp9=+J)JSr-={i*QfH*J1L zZ;3M}c{Sp=+n;GnAWD~Ds+`1B{1{mA;(Pu_t63fs`QZJ2)iV~+9I<)4Ij%bas{3GV z^7a-KHUF19M!toAx6YlR#KFBA*f8HrZx!Lk}J09^#=219Cq(Aa_Xn11b2iI=k%m@b&^1^v% zte4ooI|ZBp0#BH5XfH7J)GfN1Khw=!vf6JsCs|kH`SAg{R^SMEVmZ>z$A8T!K_^%3 zLIwofIE?iO^1VFe=KQ$g@A<|?#&3r6rXrIXZX5Yi4N0+Up@5s0z-}lV&`JU4R6gp_ ztTD1u;%)#ms^Ga}4o$H6&^Z5T?%`8dcvRpR=+bX4nZzUxFG4(Zs0C2 z!3v-{HV8Ag`LylO>KUzwyv&xy{B6FCWg;GQssZ9O?8Q;7umV=l_%x_$vp_YBCVLhdrv z6xD21F|OqbR`0zBg!Y8PEZE{G9Hn3Ig2FCXXbwkjHl-M_Mq?7!LWlqQJWT?x0BoaPXg)U>93+#sg(Qw1Bf$ABeL42UiG zOTXFSL8vGTRl|kHqV5EXJxs~_-V>sMu=sD8oFt+-V6QE>MQ$bW{&TGh2p|`-EWqtV z>X6Tx)K+l=Q~L1`;Z(ujQBu(~XGMM#sYUa*8}mazN=?3;k|?Ig2eBUPpYec0>0iGL zsSdUIH)p4lgo1-|PZjH8ME3D}{A+k=w&q};uwx)6;9n&uL4W=7;9v3#=In=(nR3rl zK$Y?spZ%NAr5@7`hpgcNQN%QLsLx_}qL%DF8+6TPuP{r4F@kMKs|%oa$wKRJ!Kgs% z0TVu?HFiw;VmijtxVc%l+dEwGuv$P)+-O4N24rbU&Eez_sw7gDd^p@YE5tDoGPbJ` zn9C&w+aZE&3aIMu8qRtE8+h(MBrSY*y9Ym~-!P-V_+8+oyprjftnPkGh5vK>wu72b z@&z<Loa^TF#)ho=kXTRHE;1NpG_d@#Qnw!Q%ELYf0P+m|k_&eI`3X{QwOPP*n2X z;gm5EvZWsTK$io=DGCTv;HS!@(%04iAt&AO8KC$@Qps}0npsT)hZ*;osQk0(obi`x$2q4nGHmT#tCnv$y^W=5op*5}gO3iva=1_pS z7{19(TgC5K`bp_$I2B8Kt<_YRM!t9cPTPMc0Sqq%_>~ zU@&UhdSSwlV$Pv{-+9U~Ter6}p|1Da{{g(k-F(?sDDYfudssQqFAo}7^VH0ffad-# zq+fP8eaU6#I4*Z5Iu)gol;j1u8iu3W%Rq<;euf8-_+zDR5C8ol0HI%uVVE&K0*;54 ztu(iF&TnG)>G}3zyb$zE@!iYc&o__AQIm%X_|IVlAl_&KY%wF`7S#jl=)M_NdjKF| zi>EMVb_RV5n$N-DYyZ-OWNbLT?0lG-ia)*YlL}INtCRTvXO(cO-nHcC#Tcd2vn~+{1Z<6HKk;CY zVTxiM&$CCag$a?s^p6uG)B0#|BJ&(<8wSwz0@L0iA(rC$qCFc{NRHvLrtkZmMGmtg z-Ahxq=JUkF@Mq%?$VID9Tl=@< z$v@G%o26uIqxnDAWTNlJ*gj_?+n+UttL?VNq3)l?NBBgWMiAK?=^Pb z@NUI^${m~&nY3WRiZAMCcutPxmbEaXXZv9Ec%31u zGGxNu-R9lb{ox(N{zdT`@FkC^PaM_wbJ=OH>st2C@qKS9Y*O#MWq)rw`|fwyw=44J zost9UfQ8jAdv@4)O3;lQog4vu*-;O#e;!|zpOr`ammoWZ)tIb>Kr-z^{w`Ib?3T5w zFHp6+-Avt*x<}3z(PfX$K!xOKfvEVI=QHcYL8q>Be~3Q$`vXS)}))rUt7+favXdc z_lhGdOyAS16J@n*F#gu@q2xi^u5?-~4=v;aeXghWpqJ13PEE1v-%TObN=Ola&Gv@r zs_}6>)ltuIn0momr6q(GdXBE8x1#wcdr0YVIcxqfxl2WRarjGQ4BjQ0oc zO+v!8wPtj9u?pJZ5Z5upu@}+w`N^)~3 zNbZo?;jE2IQ~R@F&~lbwCL%+AK`$?+?(mfeSkXf!YW)TIk#B;daOCGwINw-5-Z^!A z>`FRD1LA1QV)A{Uy%U|fVT(&=TFnF(%9XDxZ&sCnUSCq zX=&75qw>~Gu%3iHQZl-Eoqnn4o1vFRT`g&Lu-Eho=75-dhqx79_|>L;Q2yjeWi0Ni z$jOZ!%yM}y4*k&(LJ267M-Gf-$=nh9N(g_?%V2qE$m6HnPtm`cX*{Uj9IOs*!giis zb6fvW(8d8E(Hmz$*e*=@%bZ`9kAy-3IM1PcB!6O)?k}wR;04LlM|Uas)E})FRddr7 zIVpZ%aN9K3KT60wUpyT!k`(1MvC&^!coUCebRn2Ep}I)O6$SFrM1T?XEM9N3Is>N> zUWUS#PvhZvS4tg?zcI5vyD~+5B6Y3`gw2SB2P^rb?{|{HpUJlQ?;GzfeFJLXl@X@-Vk%uwrlm_gayk=(5(m&TfwEdd+ouOJd+t@4GNiili#l z&-?I^CpjpKZbrJlh3sXDCk%^^Y46IZ`;A2$QsqN8|(Wm zDOvY!d@1_gveEk=dS}ci@7e=U@+52lwGDho@hp$)> zFMQusqw$^@E6S$G;EX;!C`V$~o1&cLv2dlD9V!fSX+ zy{8sn=QF2C&xH;vrxO#$7o}~XgcAIScVk9_m(pf#{^Q9er8zOTGlbL9k5i2Pz_(6> z4wo5c}EK+>)Dk$RmIzGA33Of-MiUH>*{a}p)YG0rzL1um=1FOWUNLWU8#!n>D z4-6ZMDTV1T)?ulNK!qZ7*RPn4S&?F9I|G-{Z8ZrJLbHEPqIX>=X>?6vSImS z5WM;MEN=SC|3DRwmGsv@@9zh8xq4a<_qLS*;@rDbkWbVPuru~lqJ>sD@A&hEdqtnA z0UzC=>20`%!h7w}^!c8ah)js%q=a->KvwkV-&cmO)ew=E%fib3daS*K(9DHQSxRXl{#rEwl&F63SwZN8~H?Z23mk8>^KDG^m zt4fKt_*M9US%EmZ_*3IL`s~89zZ(OEjw3(Bn(>GiRCTzNdg^n%r_srMpYB*L{s!)~ zD}fV=jXL{GWCVOK?DO{hXx?)w(-h#cKx}2+GQ&<((==x8BWPG6r<5ORD+`yK&d7i^(ty>SE+6z?U`It7!yYfIr0{RD;qXPBfCFl_kjIxG1ljkQo=B}LWWn=!Ok+fm z)wKjFUw?Vov`hA*{-`Y{)JOm=rQ}c_e-t}2iGuJf;`@9rns~oFqm_O3_1z-NDVNO4 zh)}rpKO-nO<~^VaRBUT9)<=MDk5=2g(=&VcoNF*6k?q1S9@K9um#Nh#eQ!uWBiELd zkJ0)&e(vo}T+KqK!#3SlD|?hVMpn&;g4%xprf2FAhkEb@KaNG?lmm6B@|s&PQ>eAx z{>t9Y5&0@ujFti!DC8p;o^cR7_d)D+xi}oi76d&x`y^HNn&MwVmHWPM4yKT++x!cz~{m^+W~=?RRL9!;*k=lKy}56+##a*S@LRV2!H~xnnb+df(TMAgtri~>w5F+-_E`nV6%p}cLS(#Fhu$_b7DpuIe*QG-@ zFO@tMB1R2o-xi0i(R^(fN(&`9a7ZRbm4i9IRb(yJ@aA)Cs3x|F&1?5v@3G?LgD!dc zibJDJag0+=Sy9h(H&&PHLDd(i(fE#~H*$}2gmb<|e%w?oV?4le{=B(zU7Ab@=ewubPw%1ri2I%$@^ zT*9*@`2I@)f_s!snS43|C(=!t0jqhp^U5o-0u(v!E##-FSH6Ia&v|(q+xa(f(K%Xj zOp}8Eo6H0X57@fC-w=|kOd|Qar+-IPik4G-Dkt&l*S)tNM5&ac!@k-BK@(kRteu}h zkO1b0Hs+SxR3TLSaLPTv1N>i)cr&4>0&>hm005!-G@hl6{4TujBm$-288@nfEL@_8fK=u8E;0=Fd6K#>7ed;awzC#E$o%3P!4SfAjYQFZR z#x7(h%6U85%pYV_z@(^n@D{1zHm=7|9sD9$w3mUiUv~7mImYcpHXecp`w!9 zSmjI~w#U$68;(4p%Gl=u93a&Nbtq&<_jWv%PZ_7xFTTkxz}=qKzHib{?tyEH;dDP- zPT_7hk!jkygUhr-`73pUz`G0TSRqd46CcOYgvc$y$p)d)~0jw8mJ- zsxbxbh;TXk=~FQ489iCG2}l&DcS$s$@}5@@?Ek*_&uJ06kUYDWE=KfSPmSLNhUKb- zCHQyGT~-5poaM42 z`?~&sq1ieZJ0DlxyilrYVdIhjO892Eo|d)7F+oMRC^LIj{z&Y2iXZ}!n%y4cG$J0U z6!IICtY&w3CB1sEgxJ1l@T$H~HL{69(nwX}4dsB`>CXyCt99XwS01P$788h~>s^$X z$LKbeVQ?%tK|;PGBrQc80X|#AlykijO&;&u^Sgai?!r{*vJu$acMLpMt`4sQ)=$s7 zal{dfc=P4Qb@ z&VpS7A1G|2IK@V>-6UN*^}YEzHEN@Wn&SJK5gNrv;<(#Drh75w zj(vy?Sx?ONU>;{gQs0K2@v`0yoWry$a!*xxR0=qSB5$*P@fLkeVhDKM$g)LBzDl(t zg2UMVQb%gAZ}=S}*p@9VkyjO~^5J?ft`UbIhd~@GRHq_zoRd?|i<}Qg&-Hhkr37ET zd$ivb+j&>=GKeC)4tu@^B+7`dsPcR_F~c`S{(~cYUY;fxTxjJkKV?$s;s!Xf>5)ys z?S4eg`<}700)bHt{oD<;Cyxee@`@KldGz>rBZBnQ4mbYC{rt~*1MKbfcI(_4n-*TP!JMxbN;8|`~p=6;3D zjUSv`yQEE`Odql7M#N<<*b$Jy&fbFhruuE()hfdvIKG2%xfYDg7@HX$R&;`B}WEv-Q9j* z_MCr1z90w5h6f>m(qX!@{O7K!F2tgTeX@VjD6Klp4%e|zGK;mWl`K2GQ9i(QGRnL_mzTQ^?29L8abiY+I~m^int(|{8SJdDYcPD zz=R>~5`Pj@qE_{zP_TA=(`Fe>V;ps&93CqwM1&syDBYr0iI=|D7m&eLCsKiEm)3`m zG;aEGIq_<CIU zU;Y=``sK3x;8?+YynA}~^!ciQhCGD9)v}9HA)fPv)+lS8cHDZavvG;|~!XMpep65Te_5N$A>?$HsJhF&Az_DFUW1w;jWLPy{rcL zk~9C|0)T&ae@{+G7+mQRm7FSNF4jW5CqB66yazdUVb5xEzqk9}a3^edoO957&rTqd z#f)JG5oL_GL;MnMELukKr6~H=N1DvW&E*~bbToQy2F0ZHh*kgW9K2o%W^6QP3O3d?z7OBo4NmI$NfykH0;$J+UMONj_=FXq=PG4K)*a}n z{1qf29|-*#n}?fif3XLP!l2%75~JC}?#FZw@-#@$R^k7S`z7?C+nMDZncbNVVnAQ8 z=0s8qe-3Bw*-l)msP9#_6BMuIi}g85{9CvM5xKab#qb$YQd$sB%I7@xfm8RnLoB6u zK6GN9Y*kN{Pp*D-K-+X&uA!^nP%c#5mp47IDZPo`t4Hs5z)u2BBIYeGxQ2K+-7fH) zZzww>&$4ujIHZ|ig?aIl1~H+zD5$LctpOj~Fu$=@5h0tr<~Zf9=}H{5Wcf9cUaB&L z7Qq+qXNg|H>MJTg@bdefp?Amz{C%gx=}G#Aw=Vo*38oaO`lx|pjL6FVZGUj;D4WW& zEV2?ER|j{vxxfMT*K{tQ`)BCFk$=O{llwDznUeRs`FTW1x%@1@xMEhaN}bsG?l?Ga zl#s;MX}bi94k3rGmMnV!cZ2C1Kmi{GNiNrL%?gskzcAv|6F;J$qSh3qX3HYqU3Q*b z^5-hXk3%0IA5z{%exue%F?PXDCR;E^U~k4ChlKC_QRySnKi+E$vWU@oyG)-YFoO|L z{PGK%KhiX;DnM~!E;it(IkjxWrl8xw|KsB%pWct@#F&$HKde{{+ho-2OWR_Rp}ii+ znyZef!PCVBXdn3ZgT$Rq!(@Iey*#=l|5lLI$niU+T+lj}^gG6VD=bmJqJDRtR>hmx zg?Tw1C&-wsYQK{gUqrla@lB8JPp`a}c8cZm+uj6@4PzhOsd0ber3<8k+w~mW5RSNN z(=X81Fq=<`*`T>Aj1K$-iG*f!WS|Q7c5gU(Kvy_0*0g**HJi7~T#Vx?Ir zZw%gWI*3VH;UW!om(kv-%l5Wsfb?9Dt{&y5Le)*lUNHF6a!M;o)Q3wKTsWS)#Z}=Zj@?t8dta5 zzE@xNO&F!VEA_GimaAffuuz3ymXF zBjUcfAYYqvT?Zrpuf$uNr{IF>_$!hJ)W1HCuGkmOU#F{`zl?Le%mgiiJjQHgeRX;x z2o=wRqqc$9l^n`(Z;cgJbs*_R{9fYSG*fPfLpn2kZV&zGG2vXxN3r(+&aAF;_&aM= zAvG{(XyCh9=?1n5-iYqG`@|$;pBy-L@yr&gbVN|}`((LZFEYg3g;TPsqM*&Qe}paV zSE|}3^iw_}?(Qkxo!)O4Nz;Lv_q{LNu`(4a=E=oV9=YlLxlLzL`(c$GqHxcZMwZVP zuSL%&67TU?yjn`jm<@jK=K6a7)R!Nj2lV zA${lhu;4N2a{wh_VMANYoBS2i!2Hu(Cov|; z+$`@`z2F19e;m&`z#MmHvxD=_H=}2efH)yGLc`JTtp2v<-g^ze<5a=X^19Gs^GEt7 zlWE6h5g=sT7!NJjP{-q`I{a{cauS^UCx435=S4qI$pxhM=-?*&T~is zEVs+U?`Ezy!^2pJT{(h;8~wD~YJdxh?_{ob8D+N1kx~uxDHhBLr5E5eGawzJBn6?Y zCi@#WJ8QyN{J<^&puJ`9vcz*lT^3K*?zG)@m%`su*C-fK$hl|REn%Lu+df~ub!Qv0 z>`xA-IjoMEW|39jPn|y6WT;ku49G+kXvLZBFMbSi+>(oV;u1v*Tr=H9_1_^#9zqe7 z6gD%VJV9TPLYRV9oD|(ZZ9SSgbeGu)(-}~Wb&k?h0RQ~@*6uZJ@cX6MGr1hrmA2v| zGdoUIHsSklb#C|E9-Xn?Z_4LY&}4>w)pf|I9GZXvTUp6(F(%GSJk*YA{>6sZ_Z_+c zoah!)p;9m8T|~|5`Q!7OVr>X4{;{}n{;_DT`6Xw{X82gh_qjjo$8WLpo;icgvP zCBOuI6*F1~?46u$lrKgHQfot_55ISkBijE;Lxnax+J2-8&>m7d&S-z8^%^dA9N(|R zb!AB|R>tnjBBLctpgqq&Gh*gZoL|ex`&63z^pmw4H0Jw>PuBK&OGmDcEwd{n%W(SL z^KyS8ydygciK5)UU|7Ep_k!fmUjt=}Y3#6F7;}eva-Uot<@_8=FeQ`@`Qj=v^9yGR z@?HF?OUf8J6N+!S(6J7YC<>N z6+=WuO$yh+0G>mMe3ZkLG3Az>J*V0M>AaS(^HGm)EH96N-8x)9*z=%^=cm^07=H1> z2aKs5e@EY+r@zY1Z0;4&l`EQQvS=l}uL#W%Kcw9p)Mkm*;}=r2xxnL{n;j=B=Y8?j|A1d98CM` zfVW~n8R#?Kc%vTkc$wsvFCU!`b2RU>?G9)R?_!7N+nH)#$#wtc;zrUB80E;k@~EHe zI2l;4C@vJKAj!IeWk23|6Ri&kD-Dw5icYAFCyKb zx}+`QGOZtw+3;HraD;jN!TTZc^%OvZNJG)WI#={OBo0&4^e zxl#lED%>L!DuJ(;=`uPS3F{B?^b&WS0Hqp?yY<^`TOGuQM<^$;siG=i%->&x0v)^W zgf2I;&7Pj-d0X>P2v3p&6BBV=Ub?+9!2rwuB87yqSr_j|D<)d`0 zLZATv^c^5kHm3f5@BO}nhFTP1KR*FZfwM^f`AZCVisRC~EeI#&6AC4SyVJM zy~g{*qDE>dA(Gm9V{%1LVP}Ac%(F<1thpjWnJ<)vy`+bWgV0IfQ$RVlsLIVuRgdi4 zU3qm6K(B!(xxR4j^t=H-<2u6I_OU}U8xxl{b7{9q%U|EMGDEeI1l-`|seJRO-wWcE zDI{tnI%PF-gl3eGEq&X;VggVNUgWrkU{k>{T#@Pk%#-&1oi{c2{J_!}stoHF(C

      0D{9bUbWV94L)!$jK?)Dhx|#24J)WeoN#-4QLI3cVlMTi+p*vk9rtr zt?rwF*kP>_-$#!qw>TTBnuV^W!$8qcdm^CHqz3rDH~0<$bQHHwD8h1runqcWXa(}U z2OSPBtp`1E*%?ZU^qglZ3t^lJ3<}}Ezu7fm6YprIFLrr607j;<02^(8Lv6W7O@Qh+ z&_86Kz!r@8ZsE7)Wy|$f%w>2d8P`03>(0E1C0&c1$6^< z$G!*En7Lu7JktZoK!vk8pt2D_ELS;B}_> zcCKD62Zi)Vf$urM4g}DW1|$!I4?GK@KPus|GLtn%?Ld`qLJ=*Db zw*d0>(NALz?do7(f=h@}s} zoJ1M%!$rJ906O0ez?<^1rpmxDYwCIj>r2K`msmXkew_(yCGzbF?*PFIkxmKlJ>d00 zS7pJB1HkE%axtz!SpnLEzdkK~8rEWp0dde7!hlfU4AeIU+SHJ$VQFIV+@M2$2OLZB z=DS9IKtf0FF8m!!FMS>WfCd20W^jD&JHu-ah+T>V>8kk{AtT|1e3Daq#e7Jw0>KDG z)()|A3@8nNM)ijcc&A)U#`E%eS0Ug9+%E9+suz%u}3 zsT&~UlHpiZ(S_Jl8iS8d==gZ{RshBgf4mC5gq9=lW})H_T=Cc`ZxOD`r|jC_kUGCW zEwa*ZR;Z@fxqZxKRn!2(au(uqL2xUs&tM+G8Jw);NAgwC8#F)%M%x4NJ#;eVBT$7k zrF=_O>jHM>Vo;u0LjN3jk&fyk+JwV&Jpm_nd|_gKxE_o2W#gbcgsB3w0f3VRYw>i* z7uC#r9YV3LKM&S9w8R`A?|d*{1lNbTE5s599W9(XS5O!0KFajzDj7tVp~8#JRSv?o z%t6SWz$hgLd;z5j_wIQ>wngLf&@F=O@7zja3VId9?g5lE9V|A;ID#LRg_aJ#iU&C{ ze5l4%#b=h9Ew3Mtk;?_lk%dC+2Om!i_hf=N6pGp~yNW+$Mvk~P$5*8T2Wa`4$mR7q z5YUGiuX{_w^8zR&f4)PxUYo4m;xKd$ivz@VnF%t4*4Y9y5p^NS1j1dYu5LLWVW{x}~pu zgW=nb@9)<@yP_BW`*(+`5v6Jc9-s0L_x#+Az_Qo3i{*bmlnXF+bvr;wje+Aro!Z}V z3Z^2u_%Loj)c5h2;@3Nd(w&cAAy1Gt@1_pQ)6b(q-%Rx@M(4%h+5fzc)->(sU>*bh z2|)aya|YAcz<$800Jr^dNW21*DSXC$qG1F2?fJtNAa#RHpBs+oNq_uO!`t}bAoMFb z>if2z4?~;2A6Eup3<qY;WfMWK6hzWKH%J+JAK$(h*kQl1TU@_>*l8I1rig#*DrnsO6eJQ(-?TxL zjpzxG=xcs^RlgzSLo@YI>i+Tie)~Nmft-_H0km406` zzfGoJ&6_?hgE5O`n<`1m<&IQI(h+1nvL-tUJBZM>4O%=eh}*+ z4PGB2g7*E>atGj^NRWPf_XLatW%dRUJ4T?=Vvtw?sj@5z%ERY|Dto=qB>h2374C(jz`b+Wq8$ogy`VWr$r}FhzYEhB|E&A85KlWMc+U0-#!&acnBs;hzW( zye#Nyg+D)><4YVyqYD+tCPNm-=M?)KJ|Ym z{x;fO7vbia4J5i2!fn$H&fp89G1AXPjk!LfwYHp3*q1 zY#)RFPEQ`3fq$6N%!eg_>;(|8=+lb$8^J(a7nuk!HL;IBKMpZ(w8^&a8AQ~+od9Oc zw{v{k_U%GHSYK%4m-hZRCveY-aFSnZ|8LX%YxMUO$qyRl`)cwJ%gYbzSTl`fR)dA| zAuFIve!Z-~jfo$B;KqKrocwGvz5C#m!P@opWj>dpui+!~bVi?QuSO>1_fvftKxh&C zQk>Na$F=ECbv!OjUkpFB5p4bC;{1!%_uF&*QRVy-Yv*f{{RMu)uce&<=FqP{zvT}6 z8%q9{Zu~u+^Yu>t|HTZgvmj{y^^*0eY#Ht+V7mFV&%f3<@HLqq|NFG9eh@|$`w8kk zzs-mr7rh_H|BbXS{b~69pcH?e=>JKF6CM8LZvO0i{_Ht|C;HuS{Dsksez^uCSmMY| zgFD2~ss4$X_8<2xKac$IH$Oc_q%T%OUx9ngw8h{1Y1lvUre1{UK!YWrKWLB`Cbr zzr)~vfn^0h5H!Mm^V9!>HY3XgLq^Bnlc35<&?@Ngs;L{e3~HbMahKsEpo4b65d7%p zrto`kcI^ruv3kQ4?-;cpx%JAoY=U)r^cQ4`F zEdQDr@R)y?@C4F^A2vVC-yaP3e=zEQ`6|D^NHCpan9HADAezQ)lhxx#Seh38Mx&5A z(g}YY8U3?%_Sd5R`R>2PeZC$1SG%Nt$9}@`&-LX`hamrq2aMzho)shquIOpOFJJ3L zlOzK~RX-FqICy^$oc}rxilF?QXZZa)_%8_k)1S}i2RjRi)%{O~{*l!DXF~sQ_@A}J z(06TeQEqA!C!I=rfC2Q_xo)4)Ftp$|NL3L&h_)$`ZCwJuN2j%!vnU*r;GDv zXWB3C_K&ZC^9UIcy{Lcf3LkUy+r#)XU;J}Qe@`_2{xSar3V`_&`Hyb_#$Qhh6q@<7 z)8fBD<3rmQ{uBGFqymptZ}bv>@Pu)a`HB7(ru+8y=M(tRE5_N+mxiyhtO4@&*Z!2G5+|CJQhj|Sz>=H!pYBwEMG z6NCN(k@)lG#}CHENBZmI_s@j~Io7|_!oMMIkklW|KT^!U9hmtp_J2Xh?@LMHKm90G z82$OaeiS`|{_-;a?WOHAR`i3keVa)?2-QDHJp7AK{4dN${2UHrJ_GUSjUY^^U+Dm( z)zQ!|-ojVH;@@e`e;NzF_ZFZKBx?thQT&5x{SRruUn+%PgwB6C>wnH`{KLFwuz<(e zALe}-Cn(?XYp3H|ssc^%uUr6}^m`r?%>OZfY{Qpf_lHye+w1$|&_44e#(%*)|6wBk zmi&B;{TqqT*DCgV;?n~`K{$ce_ebLMS4az(ZCH#F*I%o||GCogsf)hyJO2ZP=TmL| zp78wd&^Rv+!vMJM{~{UsDtP%HC_}KwqILH7WN7RG=>Gjt#PkQ^^jBygCcvCegp+lJ*&}`aOyIN=}a-1y}za>skN-2?CX|eo58$5{qBk zLEj7Z{!b92kI4D|P&tD91iJGd+?oHzz~{e`g8q*tYX9{h=WqDae>TAL$Hm9Yr#t+| zaZiM3hF;D8h`8r(L=rjrC!QpD7Fq>Z>{DHRd8Qmk{KR1d#qc;u!-r4z?gdTCmIc4R{iV1K^saCmXfm0G7q!a8$&@6aE!P7aF4A1M|Sj)6D^t zesklGA;3s_^$gNTVpYq<_L|=T&Jp^bl<0Kfy(=5V=b*UQt_~oY<=h=5gWSDZd;>kv zjH5;==dP9g1@)x+_f`WyqmG!L!ll)?cXIMwEt8x3vpYuQ^`XC$OMQ7MCuQ^7^Q5nj z=(_5t+m7$m*dK`GO6CUZ&p||3*GgKbeSnQg5Hlp+U)_O!>{oXhX`y&SWrOgNR_AEf zN?u9SazER`Ge2IAdI2yV02CoLj2hUje80vEQ8mW;|pH!@URBMN> z4Pa?Z;s=449P--p`dbm4?wX+8Iu+<3Hqy7ITbf!l^iK<8Cs=@BW{p6rAg>@VM|IeE z1&a_qq;#54qc!xyJ5)@(CqTSFqu+k!k(37g?#6zK*d+kp_F4E;3^PR%pI1GHhB{f+ zu(S0LUyQrmvOtDuD_!rfFBy5RIMR}9U^@9uIivz$Tq>{A@wOR(D&8lSjm6poT#75K zZi1o0?3b?a|A=ltn7fFTW*!fYH_M|ZH9LpZrMq+agLkMUBb9P#InRK_Pl&?!<#1HZ zF~?@NQuokP!|oOLEKIr+NjUXsr7WB)s+a%Nj_u9rRp}U61INumQrO%0NVHVuQiQ?%@kmxSs zwykFO#f3qT0jZCmr!kP^Ya^fbFl*Y;C#H$L3;RiB?DZP**9ASFeAfZyL%pw>8fl3J zY#LLbk@q|2$tKX?VHA#@Ec)Mrv(k%jJzlT|IAzESJ7-QMVf7s$W^~V#LthX8{Dc$c zUKh-`+BfpGBdL?`H=H^~M*qm*HxNK60cekH_ZCLjlZCOkl*?YG+0-491dp*tl{PQI z)k&;ozZ*yq7{JT~2g9de1R8m3+`6YPa$~qF0tH1ZQa|R`s<_-O5DEYbuc8DnEA0jN zv0)?pP#(b!eDY2~7Xlp4i8kg#kjPARLo5`)phv zM-db$fEGvsF!l_}1--gdJ==K=n*X=}-a8Bcu{;H53)p<&iPNhuTJG{({n^!>NOO~S z4;`vc`Fg3l?E)bzfoLvjrE2?Gs|4IVS&G=4b|Ijxi|dxhJJ37DYe8v-3z%%@qYBi* z^{wxv(u){fbS!f5G`yLM;VJS-TfTwWjc)w5x0^|o7w-g!FqQ{Mu|gR?lI4{10ko8N zej!?rSA+`|!46n#TeXwCYX#GD9JLgh@;B0>&Wt4ljtEGHHz&fHl@0q5-EY)#;6Oc|;$yWFB?ZwziZn zM^zyO*{XPPYZ~CbA z)(NSRpkid_=B9_+%6nAEDPX3-uqUrT?)^+H06c4@ig2GYo4E<*EVKzs9d8SsjXL{nZdKN`8%p}Z<-Rl|vNa!VIzu0J-=k4csC2s-(6b(~(>;!d zX^iNOaWjcz={=9*bH9}UV@r3J9ly%ACFM5t^1@FM)%E1de>pMx?gf#PX3FES-R7yB zB;OTqrshE>vW5a=Q4X*!GJZ#CI$78Lc~r5)xX8;g$Vbd1Pa56!q}}fLv0yZ*!79a_eV1@2_9$G8BGu##~-<^0`iY_ z@vZu1`_gAr6LprZGcA;bKv<^W2 zn5a3mIP9+JA3`zeE!!aQ4dwPm(um_|#es4LLA}yXN4ny7Whc(~O1?N^c><(sR#kEV zYn2Qj@%_Mn$%xbRm^o`YhgO(ouY1RUqXG|g>KLeyP7*9gjP%d4OKrQ#+7X4y`8g*lAo$ZtSUB6ew8^i2<^;+tY zb6V!S0gCvgO$QOo{`6KiCC**)zMT`lq`Or*(17eS%R?WypcqY$cMb^wCdmElgX>`I zTvs7{!>UinJbmFuJ>XdE(zYL3`U?CQcXt0UOgv;}fQKL?(;=heNUEM`endWDku*T$ z&@`U)G=K{lFx*xJxYGw%k|$5DAUPcm5#*@J^Id-M?8#+tnS6nh2GIKHR@GX?8q)>$ zW`3douv+U(@uZyh>|u)2&A#>vzcmrSHa+OAKe?fl0lU+X&?(@4s#Kkc$pxc_TEz$E zqvXD?YMNurgX!@ zp_A5Ya+T2!y#+rOpwzt@fHaFl9Dx)SmSA79r%Tnt@c{5t6APumI=Vao@+LGk8Ca|U zIH_|0#|Mz7E04SPfCNgl{lEjpd%IZ*`zk}h6V7#np1o@BfXC}b#1$41c=5!gI)~+) zUD_@ZZEmr{^NkZiA*_x0sJBlFFj6DHY`;ul4?v1NU`ucA18GS>r+35W>153%eF#o3 z=j3A8HpJkFI{k&CW2QKR+y*=g%z zcGxQbx;q03^N8=ja1Azz%XJ4o-x1*1FcQRbONd#rQl5RyrEPeOJ zHvHa8GW1}r+yk?{apq?~>NjI6pXq5EfiNX7t#`>p#3^H=hdTiGl>?~Dquc2)sV5ol zvKt;e^*#W^Z4War$vy@Tz)9C__x%_WLcJK9bjx0_Zp~r;1kUjOWZS*n1+bt>A@E3{ zt6z#o$k-FCjStt1M-l^~}%tWyKxnjA6NbJ`MO={I+M!Aet z;Z*ocl5W_IKJ`Ity@EVKvJhWvz|fXj)>~Apw8dcZ=Iqu=FE>+}n^~OI7J`~^dg&mH zSNSyBd0GYq5aP+;tx4BDY>%P(Hjh4*Cxh`}D0LGloozK|+HLX$Z9Klcr^1+FM*uCx zOkFm(F6+O|NdwnF5SWH(_gD42M$N78)fVu_&N7 zg8@IwxWT(5L5U$pue@YCFZ@!pX$X|mYWu|LHj$1=s3Dg#w2h%<0~W|Z0k{bmBJDYA zl>T*I9al9>z@;fAix>IBm47-|1U5g@Brq|y;+>ULWL!C}Xf!xRmOwY~j(>}v$v(6- zSawDx(3E28X#;3#a4qd32Jw}?0>9@}L@NH|&|5S-n|>1@Hqv7SOkR@$PWWLHJXZ>I zVqE&Ltn*x~fqRfY@}zNheery4=#R+4YbgS?1f>0>xq!y1_}E`f2bZ~bZ@G>K5Vf7A zb_BrV*96|ZrlUPiz%2#SHkr%)oz<YI)?Ts~w2+A%=DYnLRD_E8vc zfa@xdXpMJQq1CZ%*DJZG5s1^WwZ)z9pl9f1ian#HO@KlVpD$g?h_L z*ss5q*R8E7NlV^V-+PbpY+uKHL@S?@jMMD7-AV+&B=-iGzE=msw`0?p*aM(!5a#2P zEwA7~+5C$nsclhtn_}#<-U|hJd~nJ%_N|zx9ZTCw90*r`FF>Z!Q8~u%5K!Xm9D}fd zZm(llN>^e!f<^um@)_u{PU~AAXRy@>B^OMGICFV$i;#kH6}i6MGj4~tqB^B#M_Y6` zE{N#f^dfW2&0AO*j%TJy$2l}s0Q5K9_b&Fi_`OX?DS1J zbULl(z&LiVl9qT*BVO6^MaO{f>3-K|g%=<`)Nn`R1oUOFa!R>ykyB7x zs2`7=5#6;7x?z6Yj`A=!gmogp5BFnlP)}~s=5$Fgo?8IbH~{=JN6JfN(*qWfg%tw0 zgg05?QsZ!TprNE+)x<=)nW@<&X~=iCL(IBw%+r)nZB(hp2kE#knE9mt-6V z$of}*;vTgm>m2zq9@Ro!FPsxAP4>D4s?K@DGa>jsO^V(;N{XhRw2TAiLhAWjl`DJb zNbIRMkzCuyZm1ZW4$8R*Ps_la$}0e!YrQbpcm;=uF_nruOES?sPm(42Si%6W$la%p z?{g8)6+S=GYg8r3pI-1pSU%%PR2NDIrtio3~9r|j);{Zqp z;8AQyH9y|K*l++d9IaO|d6Q)qa9vf+_i0P1)H*#?VwGp|vDGRJC!Z(zG&k9Sy=M$f z(tx!FBu{mLEH`6d%AN}W);$h~qjfDIWKQ01x^%^=`whr#jf8c;5GiEqO{o#?yCUyM zf<**39rCbFzMRaP2n;hNf9HYQ@)FN*Kc4IiG6R!B$W+Rx-vIDWC6~wokAqST9t(Pw zG1Is|(z|*x*5_ncw>!ITb*`qj5Nv#Rf1l{_#XuKn2g9gZqJ#mINo) zQZY*7Lvy~jf)-R9_|_P4hpD&NOXos<;xIf;v#ZoV-{-h+ox@>8@0W&Xi}?m~n3gDj ztF-tN{d_AhH|qO&0}RaFcpVP-n}U=G6AAlrcH;xb0PcO>CA*D;uu2>gC=-&91+ooY z&o7Kr%Ry8P$#llMi*}Y3-zFJ{h@g+LUQxpn?hvs3b8#gzjl}V z;+D7J=DlNvm?;yK@2$Hl0kD}6H+u(q4|MZQ{2mpSO7V%a6yt`Xw z2OMD18Wu0D7o${c^6*NlvpK}68e8LKKZb#B=F)QPZma)1W7Ff=n*9q!tSd}8Ke5ST z9nXg>*?sk=a(Sy6(5uSjQ~ z2q;H_0%8Y>?G+##^rV%ZE#Qq8O|^BY)fxi*P*KN+Ous07Wx6Le%<-E{TKrMx*Aq9H z-f-UiQ~G>?k0}h%^=cuvW%dp`kM1j^5}=fU+=WVvryXbV(LmSJmKR|F!+Qx=7j`c- zDG$rM^GksMqD~V5&`io#-s&E-5j_Woa3QWO34nS7yZa~%7q5BsWF>=YxO2u|(-1KJ z$8&#DG?d5?R@)tN6aqR+U_1(?cJi(*htungLhB%?CkgpgX^;7SZZm%Jv65F7Xh3v! zAk0G1$wnG^WMUnPgrnRJC3%s-qHP_k*5m2@Nc4AjKnY}lH_`|o|A|H}8%{t5*zE!m z1pzDwZ;v@SM65ANpc>*8)VX)?h3#Ppp}Gq@&`~9@KQg=?r;FlkRTM$Sbs1?=7CP)j z6Qd50@N78G7;@nv)j*0`3(=b+6qP`hlM}k!MQ6{s6(wF)&~dOmBVbp&?p++=Bg8u3 z9?jPq0TD_|7hFtql<@KtnA|WVvnzZL$=m&rP8}MSV=g~AeVboQ;3KF#YXiXgyuO_7 zo$`{#@C0(JRM=?U-x5a=qltvL0s? zX{DTVck%Dz?X|C7ap0Onl(h$NujnlGq`X1#!P8YPKx7Nm6dkZ0F7L?@Ijv1GRy}VX z=T8E;4BHBj`$tcfRdWavu4v(Yl30Ea853sO5j#J}4+m~GAv`R2>~UXrPE|u>P$av* zETgbMSciS3(LR!iv>69Q1O7cFghfw&zRNB+2N~y9a_)j&z48;*y?RHnBY@l;u#~Hc zo&-;-VLx1cFxl_Lnh-$r2RCwlEHB_mf=`kcL-3DG!vs>k5CG-?!CTf>1w4nJm`5vcGK$=r%o3u9W5dSo|S7I!5Sl{)Cly34<5~`4RADucL~BYioOojwL#4Mc(@i&ri1&t zZEkEv#p?>5?y2?abJ4{+3sph6m~mQZP!JPwh(YQaUPt29${cacvNBC2s0#?`ZNF0w z9ja)GYHy`j2LsG7fkHcG99DL`vGxKry|R!emF23$`2i1;CqcgNEFM}lM5)e8>pt3! zHwhrG7OguML?IwD-=1_>vCvG}FdWE?Hw42ZaW+Tu zwNp?wVRVy zd_n_J#dJwmkq~K!I>rh#?%Kh5d}%A?cY;IW{Jr2;dVVUaoWtU)xLqo1NBq&M-s>gK ziweJ<;A9rp?z!w34T5PA-~jz3l3;^vo7uY`Ug8TG6Vf~j?R+h84V*s+YUaRwxMOen z^7djVU`y3Q(p zzTtfLmUB_v;|;!~)STZS^MWL#p@FZDhj@X!gwwx*3CL)(hgrN+Ox4vudFsuALytmhpL()X z+eIhZXBN@75)x&~n1bVJ`@*9$n+#(ERJKEeYzs&` zv*a1EcX9pHZ|>a%HU+PL(B3lO``usH>T-O;Y6s;Y%Dq`~Sr%b(kk*v0so4+jFTOSLtv$zxz>!SXK1ix#)$8)^4YUiYQkaFr%rrpl6u z`vfLkaJMh&GAe?j2J%QeLm|QZJ59wkes11;G&-U%>N}8H$HYd_iA@6EDOs-yDu{n7f6BBxXW%=B-^gO2E^jTsI=M4Z}K`$lN;eopi6?Ja^6?t631K;fVZG zysyg3uTHeZL>G*kPmah5z^PXe&6pS)kX}lr+>hehQ~lD(gf|KiS+j9C6$6?}a-YAb zaEuq%d4&rPNq>lJ%}ttMiEes{vJ3DMr0QT~gx5e$=oPIMhQ-dnH#SjH{zBFiK-_Tt zTHCnUS#*BIF=oK06+;35KSHeUImHoWRRjG`p&uamz{AvOV^CCYa-r#b1yZ?j0FGwZ z9cvd#t$<3nX4yLrJW`ixNA??oTigIQJR%}ZK?&r+o^SnAG1(W(TCtAZd#NL``b_|f z%Gsvb5$>OgS7 z%MsFd0xUo$wlxkMa#;eX62#D2JSr_Sl5qDVK=8m4vOQni3_iG=*kFl5^cO!~k3e6-3x;=bYRx&J z(0jft3$S#A-7-VkoLvAj<;?Ts0Zoqj-fM%!?^UT{L&?tY>X9(P&hL)o6yYK? zgF5=GI_D&<>LokQur24EAiE9>4l(~(qTUHq83-ktBkLO;pL9Oo%>MWypz0y+CECZE z!_afEa8VW%iM}!J?)1EdGwEgRB6E0jsaJ`YgRNCF4Sd=T{|0BGq<}TW!NdiB+YHl$ zFAunP;NmA^HkR$SUU&1!aWSRwY&`O--Ih+nV(D5HWw;_h6p2UcIs9;pN(V)Tf}{7* z1SVwo@P1P;Gvq4K2S1d!UN2_?M;UmoO08+7g~n00EsJ--q=hA zGg%Y(=oJM`;o3HLb{wW!@-p;!E|C15i-D(SXP6hNlzdfv3-i?E+da747^bsU+0Uk) z-X~KN=361&=kwc_v_sF8RNY2kJtmL*u1sicnN2?~-NnfgaVc-qjV86nQGT&LfnC$; z@zh@~)RE90@197v*;-x(>e$wBA~?1z>}9Y4XBr70HEQ z>3X>9h9t5qT_A5iA7m|K&fpb5qT?AtsO7vur4I|W6sNFF>Us|5$@DyHOPu{Tj6Db$Lev`*qSPo?5rbS9u~-Y9jb{T-^C z`t!lF)@-%?aJDC&g@S(04->x*-+qZ7$sTy?O(9&z_0m&%>JE{YkUms7s3Dt?Kzj&RiDZZA znH9uWFp{B2NNtq%923`A(2ln@DIiZjh$B=%OcQ-pdh^nHD8>QA%Vmh2^%I&|he9Sn zpd>NqBtd~{r0VoU(Lmz?)$4-9-Si9cZpahS3eJI3k_#KHbk|rgIMPN7BzFFb!xK}q zyrT@|EHf)TBml!|GyCItPIEN!z`o)%KspuDkbZMimjCclyrkRR%JWFwke`Qo1ULK<=IBQ2|raWm&V^Lcm%B`&~Ar z7LId&+L5}U7?tPqp@7FN?bZ6C)#~-6?_KnO7ecBJ(9B3Bh2tGAR;QYx-c=^L(oK02 zCSA+nNeh-}lFDem?l`1ZdwzD$2DzSTpb%7}vwxb{P_xLkQ=H&B-S1SMT4BD3V(_ps z4^OlalB`cLQr-^nct6i?Cg1zHBp$~Di7GiG4VXTKI8GbTOOnnR7^ooWNM2(gosZXr z)Q~w1ir@u+6j)`9IENwzo=NtFm`HN^#49a`^TzRV5k)WraTbbaZU8ON-8|q9qdiLV z>|~@Ryf}-uY3WFroEwW)ueeu2i~Hc51Jk5auusarbZX8;|7ec8A`NMAaazKyPqu18xm|&@_ObdOQQ~6`MGQuWkEP&bM#-ESP5nV&WAZBzNeu_EvqH)p~f zE(zAA=lZ5WP8uYD)pwx%6;_%lk;xOy5ym*je8g3~%TxERDXyVD8 zqf0^q@fMtfI>YzR{F3G6OqrqR!*^n*h#59eplJ0;amOB)%bL-P(m+8G0ncrP5RcVz zr)IUyQyOYUsPS>^j^NchW|K65<@tth7i&*lxlX|*pn!kN?3ryapyqZ5a%~)WCey~b zZ8|1Lo@Ce?^c&>y<{ln3YnWoAi{z?dzH6apFl2$@DpB0uQIzuu9NLgR5i7Up-Y3de z2%R8-!HtvMlaqM&Dn;xJLPJ6VEhGGufv1t4U+%3J436RCW9f*)74OD@3hHgbAUem| zFJ@}qaiw=YX(-CIz3MRqaxUe!{!se2!3dw7VnB&7!wsbi)i0;F*QY05+b|Rq+(Dv) zBNCu{rUrs_J-((_>D7sYLACGL8u-~RTRnQ?^K@b%Y5I`D4lEfgI6cVj#j%8Z+#a>* z@ZkkN6%)Y(?{+5!AXAqo^a#kYq~H0`df!~{_9oy>!OgMw`}V-%{TxFi-?TG*#2fDp z)uHi9zg4Yd)#x3!m^Z(`qkBYTK&%4qTyApYMuG>FLlh3cLP&?K|VGF!uxhoFu|4PWMN>FR&#ku0N zKtyM7iqqN_)!R=;&Sxr!QF=UePK=QYQ^MOV!<4(907A}y3 z_KY?53v`TeBYv@fQ#7JiEIMXsM_PA>aXd*jf_uyAZ=g&gFZC*6CiZR}zrklnCl|T} z9folVaZ$00wQL)kv*{1>E`#%W3?Yo*zl=$JJ^WsTStjjo|AYtYxzF@g#Np1bwkeUT zicKC+$EkCXU4YWQGNlwkBer>NDhM1a{RtWX57@BMhmz54=a?GgNy{Nu>||0#cD1j~ zGlY*NDP)wPh{4>H9*jF>eE~G0J*ZQm-hnUKVb(m%Whfa6E04yr6H+&q26G^i>nV+| zIp=2vYFH>{Z^3!ufFtF!$flfO?;*LsI{-n0lUw-ugyn>Z9S3_6@FL}P;6!$or;7=; zArNm4fz+-KI6rhZu7jB8Z4HgFlxP<{lsW^zk%5a zy+LRpSm}Yr(@??PfGgDHo;uf64y6jwau>> zvUOImdf%WQ4h&KptcHPTz#QajX#n!Iu?~@QkIU+F*ag#`?^~)!u3hNJC0s(_l3Ou( zY{>D(_C6RlXkl`oklAJ+czMMIU2dCGmA?*W4~I>Z%?Yy)JqYIN0kLwSG^U-Vp}+S# zvXpS4Qd1r}#F9w_w?Q&y=B%cVdf|?c7L>Mk3q@`u$y0oGj-jilpjGkmh76Xy_kvs4 z;hb{R*#kfG#1`wGXeW9wR1&&O9v9*iC4C@_r)big>Ut1jr?;ahM}dIyB@wQ}bmr9= zCDnd3hU`8*O7%M-e%l6g&8ah5ZD`XNd0vptuvago4 zCRowL6D1`4ZOsiG3V)5sRKRc->b6nVbsq$&%}yujlGPME3SoFJtu6pR@mod zY4)QsC`t#)`QnPK0r(l-&~D2MU5o9`p0dqRB>J9v69-64QKF4MRs=OK0q^P2DCmxW zRuPF`V%{)mWM;^wpN|9G$&)Nh0u+6yT8yqH?WxU@BUw8)U)8~g5^%FXE=_rbNEv=D z?Tyi$*XcIHLr&gT;GN7IdLBux-huP=u;P^Z*fuG6<2#gtsG;Ry_1sV#!yFAoCQ19| zHcWOPazA9Bi|W!hv`!G(GurMHjhqLn4r!k%2Iy!$Bn2MOIH_)@nw@t&O4#=TLG+wC zPM4FIcyGq_I_3dgvJ?1`!T~=>?Y(eItBy_(I3XbRNQT@0$KG`SG<84!R#9=IC~gI} ztzhO$VsT`WKu930gtlsS0@;HkSQp~JZT0_C>#SO>{ry@+t*f?f)K;rjTUYC()>##; zRz>~aOWuPp1Zq*Sg<2&qFL}xP-uLcvcb~iCyOPM!t_*6lUN3YD(-XyXhEl1AJh6@| zjyCWViZqyp%2lz`AQCDkGm~VA3BVK=dw4E8FO>>Zd=raJVZ$IwF@tYZnW-5nwgHkn z0-=K*7oAK?k|InxQ|nSAE`FxR1oNe$;}M!lE0D+7v=Swa<>7h6Cbm8e=m`YG3Mp7B zPo=dY@l?LZY;?0!LR&J0V}yR4OcLEljArS$DkeEyD$EeV0Gk9INi5Sxy9r#FKCh4v z5>Stsl_0iiShjdIkRmuKgcP|#Aa*4}7Kos6!kkO4l5FH~EKp)hg%TNhv{EN>nR#lC zDlHWlkG*Vxg=L9%!~jnVtN=C6BA3O-ThlBKnEOdi z=RsMTImW_frAE;OZmm5oRg8kJOfxFT%&2$=bcrLMSwZyaz;|#W45S>5@>Bg)Ar+R6)T%%@qTlpP0fj=oM;Pn%iS!*)1$NBPE&x z87x+`%M;^ew-OjOD$~N?r9cU(JS9#W14S`3lUlD3lY!x{f^o%WC(jWTr$yWj5lU)c z3GAL|uEh}_XU-I;guG~Of&i)m`3Z_7PpZ(xho}sJL4h)AK20m2YEq*FN~M%2bXZcO zysXy*K+Z^pi@{THNbw1#453~W!;vSaCq#1%6s^dm7twTPnb36mAqN*(hI~(XJ5{1Dg=Yqy#q1Fp(l~rPA zie00XA*hqWh2v2+L7FF1$Tb?pDnkk*kz%uDa1~~jQX88VOOT3mDK^yh@nX}#KUK$a zsAAa8Jf?}EC#0K%(W!DP;GB$fxjBh$v_s)PI4rCL9K*DLgY~q5uIy|r)9crpsdWG)mSupECuD6)8i?rBE2wK>Qr0I zi3w4O8Fm*zD^6iVOF3Hjbb7jitaK~&^61oP4&BO1u?cO`SV4TcgGDm2sR|X7lI-TH zzB#iNMTGtk=_gNUfWmf5Pxo#KCu^DAUwJk;qOI31c%^ z9!(;TtVv+n__1oGna?81lVD7|f~axC^C100%YgCh6JH6UAi1F3A_}J!QWAAQ@RcQm8V9h7z~MaF0>Oyy(uM4>y|qZvpiWOr5n=e zI(cF=KbDdr(m>@DgjPf(5#n~~%$ZhtI!xY%H%p<}5EAH9xkVvO(n9+HU^O!fR)b`im0Tw)ks?*tHA0S%5kn{2^{zyPn*lXjR#_C>PoA9? z3!gTb>!C++(m?REJV6Sdo(LfpONvyIo~e}qsTpWODIU35W{b`gB$yy2OCd^Na4Uon z6zn)^yuiW(u4HlwNd_p{Aa=p)gc4aCNI%P(>Pm$IOCkVFtEHs5i4KCg_Man zlb{nrW)m0%=0p~BKmc-`I!UIFw<+wbWR(MqK`MvNNtUE}Ea39SK#5s8Pi9n-33Mfj zG%XGTmt_|x!Yp4f!VEDdjUZ1G$qNo*4}2H`8yQVcS3Dmh-Ql%-}uvyj9Li^>omZ*sFUm{t-+mMkY_u+*ai_xiLoP41?&8iS2NM%T-&BEcPsbNUD%xTPI z@uf^of`cOCgJ+ViC)$-JraFNNcFhFp$P0RmQ2QcGNu`lu#a4zi!$h~I(vz%8nS%ne zrHxXGG1DxSi781MHn5iDI>^WJ8B{5esGvF2TCR|Tnw{7*0g`B^a0xnzimc*^RL(Sx z0T{X&NGeTlRcqs2&U8ks#EQgP5TMZNp>&j-?q1EC{A2@j5;dKtV!WAWyw*ALOn4# zhG0iTIs~#WhIp>Ut^i)WElCjXaT1fHzyPvS8D7!R3DQ)VB8x#S6Br22XtIqLrFY8} zu>{1zC&kkE7DKAboZwQ$^HW_kI&iQoQ5tb73Q&@H1SrKoC=8}ENkw!esI4?grh^2@ z_CyroyA+8!I*dqHOH)lmy)y%hrzzc#szFtVK`kV>-RVr=D8rdzh9O2&IeY=sKRAhJbB972t?P>nn=^D(j{8(E%0a%QFhw>FJ#P6x?SW>AHxF>yM* zmMGP$CBPeJXCx{_DH*A;P|TBvUP6&>Fh>c+@;HXWVoiuoaag?|%atr5vg528hm~M8 zxD!+Do+PzLYqjv>l+p|p%j4uGVsc`Kl<8=~8{1)&%ii znKK-IV?@=D%wdS3un$7#k|kDlkUtqCLrSIn~!xtR&{6s0#V zu7PSEXS&R2S4vXE5N_hp6>^(UsyFj2TB(x_oiIF7D?t~d$W(GP-nvhKtZr?(CDSUT z+mp;n5`1eKWUUysbaHaMnC+sbCRnWsGmXm?agD5a5tNWv;T&Fu%fXPuB2GSy4YUSL zv_^oq@e&mopi6O)Kq?qP$iKt zP$kNe5#92{C_9w8X)TKAv^ZdV$y5T=`Siq6L@{z3%i!QB7((Fx8`b6%gp|av0#lok z$W2!0O*Ut26hjPEg$RYlGdrX_Bi}64O8HWXTM-@afTCf9E~R?8@(7K|<#C)qK{2HO z?OEj1smV#KBooV?zz~oSC{t~O#*^i7$axN{mo)FOOXW5>At6@7bSLsDTDl;a;Fc*|Xc9#j zOCd+ak!TVqyO#=6EUsj3g3$t#%QAo=Z{gBB?nLN?Vo4;~=}fM~st`gYCQqPDiAhUP z&^Rm`Uy{a`M5O{Q5PG6%iE%~`%NE6g&76iPZ7GU)ml>K|*ql%vY7kQtvCyH$B+_Y( zv597Dn zU`dMRDF`I7nySeJG{&+fp?B9P5O7pRQ6eXn?C|Bh(vWC6L=c5M9>LDFBB=Br9z(no zV)M@Q6b3YQaJy+*Ljn+7sc90U0N#Ygj|H8>VoP;wiabd#fKUL@DKZ1ql93^Ea~*7( z$($SwmxD?^n7K;x$lP99t&yXl8KW(74r+%rsq91>iYp9Oo0?>yI=Bj=+McK;&`~8Q zaO+~6CNw0?i-m8?;Uw6o@h)I>zzgDuY%YVWLad?;gCLEsQkyJEay!#4PJ`8g;yi|l zA5V94s1_tWHq(~MN{Kd$(B-Blr}8*DU4l@;P0{N)VwEIQ#7(lPWoo-4ipq*3b0|)^ z2wZ2h2!JEG6$5*W|*B+qA5{CN)*YH=)g*Ma-0gARtaC<7)6$)F|9}(U!#Doc8o+awCu6z zs7WH|9+N8N*(BcNS-P0chHMv4t%F7!ycn9qf;zPqan!+|Pp`8?4Zh#8DR3}3l?X>Hn*hx|~RUOOVKz}li$PI=;LSWOiBCCkR zR14#!u1pHqW!DQ8g0wVH$I$m8ijVde@lc&HA~gf@LK$pSP90KP0^~)^IyTf~E4Umx zi;p;r0u9R=ooS1Sf=$4pM90Oy$mRGrkxg^!jXw2C0d=x~GNL;g^h5uL8F(}X0Z zSZ@)q=^Uvufx(~>!4=U`p&~hkrl*pX0);5X;W7}NHnu{TngStOeiT9#0bQ0LhpKOl ziRtCsCnT^1qG*rCE>uHP4)lJafYW72Wu>`OX>LA8A~d)K@yygDMpC?lL{~-Glq!zM zV~>+$B)C%)P7RkWOQz|fDBi6tiBC}}c!`X}bWIE$-Y65*?3Hfu1HrB#|WnyJA z3F(;v#Ab`q#Il9fOamv@ofM^!Fce6JRhDT@6F7w6%&}DV#P|eCazd0t4xfYPwlkUN z28KT(YKAshr2&EBrN={~N+vTQDOoIup|YWG9gG5lCd|I}vHrs$0Be9rCzKgORPnf_ z;x?s4^O;Blyi+NSM2Ub@Y|#&VO!N|1qgS-UtM7nc({?(+cgTP02!0Hz6TI{AYQUf& zv^vLox8%?!%=f8$2mE>^mu$seN#FJolSQgLF4sE~sO%t+s(08f?p+KG^h*vd!KS{I znC|Pll;3m`IsyIfWyuqP$iQa<;mv|+@VUJ!;U_~RG8I3~UyR7)nmE6f21){zq;ds^ z2zT~x%nn3fUgg<==x9JGh%&mG#d8Aj2gReG(esLCKmRpJ_3!774_!rPSjlY;Xvz#T zTFD%R!K_SA)ahY*wC@RQy0iDIRPS`>5|WKRC_A^hczeK%k_wb&<*mJO9p>v^?b8^~ z7y^YU#aGta8&&C*jplp-v)gExb?|HN3=0CBJA%a^H<^H3Ucp8|SLd&2*piB@SQd-N z|JLk@Z7;xB6JWeIg;Zp#QQoAVu_n@R3HDR8MY9e3)hrR8Cs>orHMXbxWGg{!gLVkD zLIqP1VMMPNSG^FS0uR(*j2L9>!0RYR_!jUJBWRQ9op21K&@{EuVYY!UPVk>;{!H6m zb5vGY0ErrEY^JprVtOC@jh!rI7t0xn;al|=>|c=a`Lji6u$-YiL^7p3G>ETd4boC{ zd;?bCRQ#0zEUz9t!i~qk;4|J?rIRam5 zOFUElD~F0W5ULz1;xhcopkh^G1H};nY-USQcz_5~U`m+>I)xEY3_&2|?j&EM!|q_dH7GM55xeMvw{!gTchXrKp2273Yt`WCtm>Erh{QZZIhoZ>p?;c z00mg6wlCq4B37pveOdVI!y&rJ{i^ zKhs7+-y4052Q>Wr0Mr2b8N6~feAyjdzCTx_)k}|8t;V6gSip@CL89W9!%Sj0w#+uQ z0lFGxV6iI9(BRw3KcH5zAo@1*Gq-d&5sQoASH~XW7cy%!b~VTrDtMJUnfPVkOr!f1 z?i5J+l-emgvkk_HgIE)QajADeIs$(E$D_V-HbGUbUUf#5%b-36v1|@ z{bj!@Lir+8F{NBZi0hx?03a9CBX$(>i%ydYT7CF5Wbrvdv)O_jOjA1?&;b-x*BrSM z8nTv9s%T&kjrXBS@NWhQs}JT?ppr|33I7Q&4~t1u0p?)}=#{~|SG6xNELILgf&3Z{ zA*utjR0dOu(2L)7QIk*;p-VYhy2?-mQ$%I7^^1TiL^9ge1HFqlSb*Qrhc5@J5V5Oa z7cb>#yq-V>LtB1Q`C_aDW-*F=dN3tLDWURbv3jkHH+6(!Ri8`#T#2NrT8Jtpk}yM3 z90))^TGayqRmDG*d;N4Q4_LW5z_aH6I&*;CAwP3~M_&^hatF|-2!M*@Dy7`+P}|Bt zs^YDHE^*CB7L|-Fk>GRrxu@ksUcLJ9B?nbW1eEoPDrWzX{p%A{Et^&>BO3THbbM+o zYX9`mliwSPDDv328!s#2oV^^=TSMs^G)zLP(K<6Q{fj|W zBCSFmQ&qMm9$70J4yO`J1;FX#k^yi`o#Gqt1w`Z#*!u{L4)fuObUMUwN& zPI=MOr9RN>8mc-vwyr8>9mGw>zmtor!~HOm_=-}OhcQUE`_PZlGW5;W3MZgf#- zI)Xqz(3b+tk)iN7f=HjezA)anJ_)<<(qe$I$@KR>rxfIPFmS|C9**Y~(s z!IW@~UYT0JgrFML0(fEmww=g$scHfD)p5K1LVyGjb#+UANd`6I9|RdN@KdWA{8R(3 z3w(wisSGlB;Y4Xuj{^q+aJEWm2*zJl5T!uL%YhNqp6Vr%O6m&|;YI3;Qqcn_fh?6+ zdlCAARz_by%=#atFR&%_%Y5LBI+Z>H{JdgCg0t}qdXqXFkDPkRdMHT--Bj?(Qj9%d zGocNE35jN#6{;CYgmTjSY#Ro%BygvOvk5MXuC4JOEg{WnWdwsAKrQ zIwR$!iB2RUl;~jlsS3H6Qai5(5S?&3ub;r6z$gJDS{9R-xWz~R<92U}$O%Bdr&)@kvx5!b3A&{HG+77h>_H^vMgbf-(xGiAmns79_%3__CKN%C(!nzl zf%K1ZhOvZyO>iQ7i7hnJ{Aw6EH7ou1QrrfdC;P8-8%XprYNaT`_Sf8oXS*ilT!TQv zyt==3jlbxcV3k#`uF#KxG5KCRL{CG@QilR*&Y=bh=RXgkm(>K%z~eYM_hr<^zFIs^ z1@8)VurSv)oLGvt_BtYR2uS+AREZr^%8mR>Az?pP&kJQs^~ z3YA19VA6p{?9qr2fHo49h7bWbB6Knp*G@QieD(2MZ-Yy8wJTbFEv!GveD_<~aL5u> z&`j+mIOjwdvl;;tCkP0UM5Z7FO36wzSU_q7@NZ}cNH~#7q+om1Zvg?!!;m5pLZ#5i zbcD*llhghSNP=?^SbrLs0#=$p!=n#1X$5fwTtUm3=iR{JM7XU`(V{mPaKbngNIcgT zF4uY#i(hH$QI$Yw`PB*G#0WYAA&?j(3Kir7`k`Ta7u(v@2m%!$(TF63hS11FGPd#k z1%nQxH8KI>xpXpxLL_6aFCiBZbRvmPCr}A=I!x&GX{?$g6y@QdYSQZAW%`WPe3>8s z^@KzqFlZDY!xM-UGG~{sj#dh3W-$G0zjyS4ud2SSZ*pTJf4Q|+vi^E3`U-Ukf}77(~fBZ|9xK4fMZap z2JLgaz^bApRT~U?iyb;hR8}!rrn0S+-lq{6YM63`mc~5`x>W%plrJ_#vRMs=p!5<0 zzm7ttKq?-kB6|^hnI$fJN=;g13|YRMMb^;Zzj78Cl)Uf9`<#EzrJ`p*FlvMVppiUS z=rTY6%S7TzAH@kMG$&EXG|(UjcANdg2i^ft9|9ejh!li~Ab8};Uw)o-PE8UZ%$!vu zK+g>ks|^jj2q%vQ&4R!Iprf7uG^@a3V7LI#fR9gv@-!G)1z?Yij!#7~lD`0yw)&Wi z_zM831Qw*Bw8at$?;7Cc;dzs46M#~dp$Z;B6%@mZ5C9-)&>1v36`>LVsN=zoA_1Tw z5oCl;hn~qaIt2&%{_Br`2A}~h1k^|a4MBaD0jbeWKIAyO5?O7_@3)vFdNnzSFJkp+ zj0jkDSU^DaBu43K9N4N6L=p*{I0PgBsS4{?8x5g`N?V2pWS76(BG!2=qHpaJlXAi;Dhh}feIzNwgs^jm94(9lS9v;h&ocnIs`P}hI4ArJsh zLJuquEbrggRcg|5x<>Ma>NZyr~vjwM*N+Qu1K$=AV_NlR&wD?ts z#`(N4FCMIlt$hKx6$Sx`fFZ8n4$&cL#wb-4N~BRBj|y|5@E`0p`|VU%OB%#isj!cs z6&#v~^{vF~rkODnRnbsh^5j%f5Y+u$SP-5(UmXf zoSL);s}K>ZzE%A@&ep3~Z_Kv>1prBNXeS3L5+W6X=)TW_X>0UZ$fQ#szy=z*Jcbl{ z29Zi*5U30Y&(MjOkK(TYo^eV|k`&x$tuAEdXR3WHs+tPb=zzURbjW&9Aw7bWL26Xg zJP;so4)Wm>3_mqdB|BZ?eJ~7vRHXWAfT5;C1`=hb0hNtF#|Z&NkctYfF4%Bzl)diq z^DPyT5^;)c7U3QyRq%4g|3bCJBgLgfWTBou6; zd1VU0%S13~!{=W4=`zSNQOXO3Vfw8GsWLq4@|@-O=1K3_F*SRu@U!e>QSFdYhq zfao~rl3KQ;HuY&0uQnxfIp}|=DlIFWn8EY4gz!<2pJ8pWGb`<(0m|NYnZI8uk6UFz z=^SfuL%Q-rv?^JARI!3kl+%z3i1#p=8E;1gVF=&1!8Q@3XG*Ex=k5)Ke}os?@(Y3} zCBFd7x9}bKYgP65r!CX*2fFH)yaJF`G1vXCUEwd*?N{)Ds1Txk_6kzaSE9%nm!0SC zhw`dh2LQX!_f1|0t@z@#ThSbVa7f8QWfa!@UxtFx2n6QWVF!x4rj(clP;P5q-~BDe z&8|j`i59GS1@d*(n0WjJ(~;1#4^sg64y)CXrF10Z`LVFtE7Fm`BlpQ1Zr7lo#CHH+ zv)5QFV&9}{0UUyVXa+2UFVdnwV=h|M-^7o=LRB2E(G*Q*N1aZa**h|^{8c^g!#k7E*0WWrUQIGa- zI4x*5dan_LMqx6q4TP9FY6Gj#I4r_9=>oNn*h?#GjQ=`!G%T;5f9Yd?0|?*+Se3g@ zcpT+51p*YjVHdtVA(vN8M&;RPA0d>sWVo%xE!lIUk5`ZHG3WC|sE3lRIR9ZS1^xS% z7Z2I4dWaC!lP_h*=7EGFP^yQg`1TFRj(2AL#gO{c!N6V5_sRy z`v_GO=%d#Zq`nkOgy*mSF_x&bQFtMis3gUd1U-97Zraz^65*<<97}|zT}v=e@X=1_ z6XAA!CS*vx!=ES?*oSBYrPSyr+(;?l7jKXSXVVl1W8nRjW}{JV0!l!UT`D@?@0jny z;IW!gj2KjyYvM48iWSi__j?)R^a6@#p#BJ03D7-~K_n9>P2|A4y zbz;SV*GsigMtUYq;dT?qN>+5N-GU?|3Qst0#w(z{ze36j5L*y}oZ(GQR6;dym{DYh zN;l4DKuI#*A2|LzycYb{R3l#sTGXIpmc6k*9E}%E6!HT(c*@Nm;NZtnel#9crmz%U+epw~L zQysE`$g!U0Rgx8z-lkS!)U&%E@3=iL9#3~Kn~2tFsA zQ7-qGh_^7Vbjx85Ts3aFGVOQEOw;oZc~phk^6b18l~_b(!8aW=dWDfK)wJ)PePx7- z?QQ(JFdC-hMPG+FX1SaF1!mAuf(;$DdPM{q=sSQtF6Nk`NeuM1zQ*~7B4RE29lQ@@ zRWkYLjj28!P1V%^=A2ib8h}>ZzU_eR5BMlJ?X0}$RrRX@`pZ!RI1#x>4M0=F((326 z)dW~(y*jb*Yj47fQM-3XHrugSvt2@6bZv&&ufbY@aB+y@zhweO0UtYfp9>8M7v#YHoXH=&$fP(opj+2mFGw2%aVK&o|>iTwHYh9e4CScs(lqSXkJK4fKIZ&osKdr;!MH zXmIfCzy@9?=O=_^mKq;&QL-KfE$pcJ{jPqR2#HuqH9)_`vg=TkZSh|R27??yp%fQb zW4OE~ElU-0EydXr)WTJgt}BuLud>tNEwUhvSINZ;!)t9Q-VQ=|cPa`Zh*Q z5~%Vj5=${l{&mT_7cWm3K7%g(Q2y=rg9TLmgb8iY4r4hfWV8n`LNBlHGo0f07Vs-3 zqBTj(urF4TIr+De-(H%u0h_E3Ge={HNr3oCQwn_-x^V-W2 zZ&Cxn8D8V(Cvb5PW$|^9Ev4I@9o~6H6U-uZ-3trul;)$94L-bhiE;a4DKI~aK!mRG zROtK+O`!2{9)21M&s6w3hBYw!Q%;Fhvf5zwy5ZiEiYi6?YDEI3GnFqAcz_DHxe6g$BocR=x4t$dWDIY45bM|lwONw0naLdPP|HCsT6IG%pm1Fx(0cDf_r z$pbiw6>xj8M$scU?ycUA#bzP+S8o^9Y(J}MUX|Y+|4bHGv|>P1^ogLkdpLfh(L^m2 zCmH3Cp@Z}o!6>(B^`>xdDJ}XO!Q$)ahd-e(I~Q1@DztXnMC{C!^wujnrlB;Rc-a~Q;;{gJiPb@!wP;N#0puo zTJfkAkMhOic_iasu6juXD})}N=f(jEvlh<(^W8ox(BW#uqgLaVuW<<$vwf($Rze_v zRWh*gFE=ZGkPVd(PpyR1N{AVo(BhlaQc6NHYbB&sLMoIHYpt2_w&yJ|=&07r;DIC5 z%vfvfOs$AGE7l^lhNf0TDiIM^Ef%T8A{A-8HySPImlr{S_x@mWP$sp8X$ zF;FGv6&b=x&a3KmYqvzL)_k_s#AO^p!sR9WUrXu>^jv^BO*XkokCO0eBcQeMt!G3) zGm5GJYK5d$NS+}ia-~uYBZlR^3Zhy;sTGuG2#V31p&shc8*4e1wSeon0TNNF%Tq3c;?J+X=#Xrb+grmDS3kSH_#*`;S}m-3R|Zl`pN@Ih+Xf@x|TJ z=yd2g?iCcgyAc(u^YW805-|cFERC1OpiSs-QLRBDhIgEGYCqw)~6Ej`n#k2Y-Xt2L)%f3IcO&|)c&Bm@Rf)oA%Z}G7Hjwq)Zt@I zXz*HV5+#B`C~n3;DZfVz0~1<*@kE<&;m2!`h*I&niNzx&xo)-6>GQjw)Tp+mvfOH0 z-@#|pR8q=XP9lXC;olaLQC=qy%t-o+4L(Egm55BaGbiwp(2A5=k+pQ%3?7zEu1r^> zT$V~ST(QwayH08hdJ7+v0{XkRt7K6_5i-Z7*XqzWM0>C5m2!hnu238No-gVcQi<*= zIHMsuFn6MD>?P#J=T`i+f?PbfT%)NR zco8CeSTFwsEl!6J1wnvLkki0iRfv%jG&Z!wG9gJ44iXKrjDNFdqy?VgrNZG74pb=& zi?!RSWbajVqm;ssHDX(M8(2YP4oXRIsU{E=D3-#&C6Pf_Dk)U}mqiM?l-w1KipF$G z>HfS`$Bz}a#jeQAgYQE3_gxqStg#>NyFl|V3Khqa@bBy4%9JaLWn278)N&Oh%?TQ` zVF1CThJ?3&hlKK#P&qB#D|1?3a;T+DH}{tzNvHw?|FuX|$k^>J5+oSLRs3wZf`r?9 zf0c$Gt2r92th4b?(P$ctoGd55G>zuHk@auuvR26#~$`pMol$3l~8|;3@ynaR1P8u;tFZ@$Jx317=EU zMQmI9Pp~Z4iu_%vCE)$4aK(tc$k{Zg?MKa6(H1GKPoH~6Y%!{cL&uZAHL&K7L1%10;<5l`M-Uxj|z+oo3hg@ISU~b}!CUjSii-q}7hB(B3Cn zv~GMTtJC7I|M&R8^{?Mnw5ivMS#Rdj(B6}l-raEbllyCpmww$Sa?3ZlPK9KgUvTrg zjqAwwFZF!7U_p2I|5|+4tkI#Nfq``@`e#C?I*WFF!IOkB2L}ZO1iV?%KRxnS_a0OE zJBHO^J?T7t>RU-ID|tWW;C(}nRCq=2r)kCxi0=Ae{{K#&e{12xYmOZggi zIWnVGE@=64@{f*_R>D#rew@4UgSqJ-&Z5@M`~|LyuA{?|=5>tASa=CwHd*3GQ4=$#jTd8oDKinVD$doQn-_PR7j{0ePh=O6TXm2CE>|D7aBnUvKwa`w3iSMTf@_g){v2a}dg z{Uzkm-P2#yZM{|Sbi|&|41%7c!gj8S;hBzhSrl=7eBZDKU7F>at!sAd*)gz3y-RO3 z{p0N0j!YV_Q{U)FW#6S+hMc7*t~5KgMEoSo`h9rJ(@~%N@yqdt_QiF+eZ>E6Md<#a z8?CFx*LThnHSGW8@hkVcHC3%zjSERopE^Bq3e~jEk~JSDZT|A%9oE9oasQQ`WmCR9 ztT!(o+-ljiX^91Gnos_%?u|8~r_}tqoEf+C&$K%B{kUHYgRVAM(8?Xyzh}N#HSr>G zS60J*kB99)Hgv)2;Q90kvs!)fMXP#5ckk0Z6BiE}(&m8sk?4oT6S{nx6>?$SFW2SF zfd!I?JSt8#1 zq4?H-QP=uO2Zg$4k6aymHit8P^y#+2BSg{T+RwT5@axo-SNgY`FjcxJ?0(TkoIpkI z%7}!G0p~jh@dx)jIY|1secF>q;Y!k&o3{ubED6|fW@hx0E!6*;v8_i;PO#G&wtwn` zU!;#cwqdN18-5(cm=rx|;Cst^xA``T^kDd=%Q4n3qCVwjSR-7YuKn@HK`Rfu#iiRwD~zhzM} zKio#2eynkR`E)$(bJ-hJ}T?=)>S zM6hD3@QqQ*8?WA7B)Z?=8}lbm&wO&!+W*I9`ExpN z8c*Nj=5(zmc*1)qT+~6(Y18kdg%d~d&V1siL*9Bb^tTZa&U3v(HWB5$40VljRs?@_ zm$%^R2>ZD$1!E>lm;BJoy{g@zVIvhSEV-g#jb&5j)X(j>ZA}5Ki>#xyUuUy>+VvkA zlFn`GKks0`U1OF=UH5_YrfA`l!>cBXzIN_h*E;OUW$sV*pHDSk=#H?w|Iw32%q3Iu zC(K!#vw!cpr=JI(Z@Di$M|AUAwwB#}(e-6_o#RzERt#e2Noc3q6i!_;T4CkWCoglR zejGgOH?8v{{rlR1Ez|1#eCxAMR|bdC>Acv@Qun+KE6pE0x;^*fr)|UPhlR<4wvNg< z(&@jPr4xFZA9f!SroEDVW@+7Htq;ZD{o(F_FIKKT`u#rD!unTcuL%A_!<=fe76v^Y zyz@%5W#r{%#H+U=ySH1YJbHD}cKhL&y9-DoR|MZM$HdRrHtcBlt+-RS>Mzv2yXKLs zSLEQ8SF*pj-C=}zvS|J75&i28&*r6Wvy2$HK-+1^Z|?eI!#aPqAY{job(Z|)6T>rx z?&wVUso`nf`?p&D+M76{`vO<`ngRTy_am1kq%1@(Q@Fj5Za4nibpCFg`T4CLEo>TF z5Ophh?6K=BgBN{%IXr6X*`IQ(O)mTvu<-CGLpaft+l#kgT7H2rk94Ztj!TCJxtq}g zCXCqr-x-;EuI<)}E)9Eo>XOFCI)#0(d&YLHgC5)K+X;_%)NQkM@v%Oe7EU}gdFsmM zM|nX5gD6u@pFs9~5tlWBH6eFh;D$+CPF&SS9kljFM8-PBIa=Nx z*_cDSyRPUGw*GD9IM22>&)ENPEN%YzPdT1Idb_n_hj;BXG*oa{@0gX_{L!xW#vS5Q zh@!$vrxkC_9`V*?hI+~VW`Ei@KbiiZd;jm}cKVq{-=E!S`#@3~_TneUuB;k8 zWTtEr@n9t32Tz+j0}42EX9csy++NHGwAZ^dz2~&A5*A*+dDydZ>in$GQSFAWS$(3R zp;^|#H@aNX&%BqbyOdl{e~2w_Blzm{eb=$4L87_?R;>!Q5BMo|N}qe~wx(~cgxm{D zT^LA>D>=hk2U=Q<`L%6vx45}J2GspOqDx0qh&$X zR!*Zyg;Ouhi=@5RX>OA{tR?pMuM$L~n&&oPrXL@(r$OUK=axxl+*u#2%6j+fn}-J# z?mh46J4F`SZO84C*S`zvK;K~4`qA9oECS(UXUjzm<_-R8-S%c7`&uI{3Syo}M)q83 zs1tg*UVcC8rQYOh5 z-N=pmhfa)p=YP!}3=a92O}nZJ`L^e%Z@=R$n5nzk=8HoUx~8o8<3z?vYtu(aT(9f1 zTYR;8@K3qKwtd$(ztJk%FnsW!vAwAyPXE03!k2SI>*@~8KH3;*w{zw;(GAwUpqx3E zTNPgTg8J~CeQns^_YXf1HhkgEF9!!IhiAb>hpu@iJg#4!=AGr=sU8pFbgM%=MBmr5 z&cokZZR@nQ<5r_0m^C~ubo#kLU;WW0sP(-+b{rpeXL$dg&3Q9*#sJy4_WkCi-+CvY z|KorTb=o!PquTq9c2?Fwa)517X6W5EhUQzYCYrtob8vet3|$d)dc&5f{mwNfD)_gy zf9_F^ZD?-Q@WI>2i4lt~X%;ui6zNYz{MoO=7wgv@z3s}oEH}}v-i-a=oJHAQ#v$Ka zn=|mzmKk|F3bs7ix%C4Qr^THGO|I697`ALb-MMMzwganrzpXelX2GKK$i2Cqq1{LH zJ+=A&VxL?(zUZs-A^NZ8KWfLG*We<*Mc)Iz&fD0*eA#m6Ab;OkzN72Un>Y;F&3MyK zI>VZi^JjeQh#nan5Z$WI?ISHu(jcV1 zdv@52mVHxKy`A5@-(A++t>m1I*S6n3_eZWscrLU-OoK19l7aMFCqF;)@y>yVH{^ZQ zMlz1>8rJ;0eqS5DlYNXWVND7(w2bT7Gbd>O`nt1tA;CSrnSVNWZ{dgAcu}FLJL(s_ z*)?EwZ)}^bVXn~sgu0p%8$B3H>)W_)aMbKa21(w%Iuy?ExmP>hwNoB*;+zuZ`! zv+BQ(4d3jVHtgNDZRo9sO|(B88#Z^>6>j(ZeuuL1&#M}5Q3Zd0*K;@UQJ$vmkO})j z7aq7Y<@C;t-Pr9; z!){Yn4%>UFOaJ|Ccb}NFcguhc@upLa4yAoV+vz?{1&GHp{xX_vhyB zSkbogK3>-_FfUQ!Cn0wi{E)WxahH>ZC6DK_mmGEf+5Y3F%hnmrDGoj8B$;(E^oxr_ zkT$tV<0awb3qE8$VRdbrHIv&lIEprA zv})&=bK&~HhCR3RrMDILe{h{T3Kfb#Cru)`M|?#tioO!C}F7mbM*udhh>DHN}}u?RSqDJa_GmF3-51TK( zzxP6eg@b=^t{vd)7B*^g^RLE4Z3qj!{f74Zq`{fDBPVJC#Dmwh)i6aP{`~yY{X-v) zZMbe{haY3#VTY`d1}L+iaJR7zXa@KFWAeDdFQ?aKe>!jKTU%S@{@49W*S;HK+t&GN z^_0VBkKPmxB6fECOy>7u&#k|faZXHl@LkVF9byB+njY?QF}CqZ);kT%q=0MV-tBN& z_2%;4oiERxM`-Sz+g=71P5$ld< zuhl&iwRp-JDQ!L>=#%w1v73f{b)pHGlsszt{QrE@bS7t%GniID3+b?fymRWDyKScN zyA2aRKA1-tF?Vx=Oy-GBm)hp#ZCyQR9W(l!+y`TWChb1Qf4X#W*o-F~?L5PR1$k|T z582%?0HJMfdYXSmGo&SI!RY-9HZJ*X_L!c7E>9mY4fIMn5ciM;>DQ z>U6V~_x6WhZ@uB`v?VvB%3t*XA$S{p*+M z!z~jdyW8j=Zo5b9*K=XsvT5~JGrl#2DEm?l{!UmPk>BRy#-WXaLeky6+vm0!A{;GS zA9jyL=(uXn@`n8`H0w{iO^zbm{&d&aFGBa79j0z{|A56g%z9`hC7|HIZZ2|2F3+vH)HqL0sCtTTnv*-0Z z*5h{KxaDj14V@Ml{PvF_!Ky7<7Y{llhGu=l=p1=IX{1daR!SDR=%}@81(m1mp zbP^BPdTs9Iv7aA_9e$_Yg*F2o^Lj<@y>8p`e+~O3Pi%jbcP~#c@w1M16V_+y?wePR z`{e6e?LS*wf2OhDe+;&9I|rL`kBt6h`I!w344{cld^~IXtzP2m({3MLJAKUjZ%=pL z6f|J=DiCzO`Qiw@`QDm0cR%GxZ+$c}yVEBJm8*uX&+nHRGyHJG^)J?L-pk8rG4b*K zF{9Sp=-GYTFDVBu&ELFti0;(nVQ-&)+{IWhr|GAe{pU4hM`RuDmLH(t%icY-;BMEJ z1#|X%9@ch$hbEW53f!W9xZ=jV7+n)PX~mL#Ll;drzU}q}^Y-!f>7YmMP!d7s=9&?{McvQ$G8H`QHdTF?PJ^ zVZC!id*Fy;_{HtVrZ#PY^lRtZd?+Y?LxXj(Px?>o=U&=D5#H9d^~k}wZKf5r?$Gg6 zefE}*V%v!34LjO+xJZ9@_q~1UZ^$RFb~Gfi&a{&++7+2KGJ96`(Y&0ab3<-yZM<4G zzmRG-Cp1GQt!W*ozQB2ZIqZq=wjRsgxOCe2otoR%`H`a*K9u&gzdgL!heL<|p8f9n z8`ENmy}Gp_%%M-wWyuBL07emVGcvJ-jesep1YWYqu{i z3Fr3hu}5=a)@K%ZmnX}JlRdtTk-{B{;{V#tgJXVwN$GZu&+d9wdEdMk21ER=Dg@0$IaEjNaZoSxh~w{`vh zo*UQNb850W*naq@|L%X-{&d3P;i0CmG0Lz}H)aK{5bf?Z@a?>%16=-|BDEpJpe z(VfM*-`+o=o?pm4JMYlxtfOyqaGUHcS8geIzkB}b(_er5&GhU-=T&9yfzJ&Ev~Bl( z{#-P3!#m3Q#vNM^pDAoUF3F2b%**??X!sz#W9tR`9!MR`-&+JUYC2}m$Wb4f-xm$< z^vTA_QJw><_OXU9QuPHTyQk@!PkEhIK8kAH<*EH*bZ2|lO@|xHB>T?(MrkQr(qdh2 zN8JV={@`wVAznM}j{WPf4Re>D-?4M~YyoL9U+M00Y;n%f$(H|}y!S)nkv$tT+72Hc z)^EGzk5y-lHIpZI)%A>a9}qyB=tzRsLN-~I);zWXV1OP{Ak>VOG8J6{kpyN zj%8!p&M{@JOrR}1U^P1$O2QYk3VASpMVBdy+Kmx%j^Db)T6|z8e`P`L<#YTs^Rv6I z-?Z1wTXQ(;gTOP^wY!!bJGyOtx5q(-8T`kNtR;aVk3Jo+?c=dQI(>g;_Tho&Op%XR zi97ySsrw`7kT&=~J97&6JZisnhP?lIwRCR&P1V9tgn0+L?r|^eKXcoL8y%Lf-g9w9 z_nF&rkM&C}XwzX@6y*Zv32VFj> z_mk@b9}hk~;`89Wd)r-Gqwm-wZ&_>kt{uAxzfCmVx-@IYlo^BbcC}Vayu~++wDi08 zLx@6RYt-vl+jG1pd5UiCj8AX>FuUoY=<7Y4D$&jl#*#?pB_rJp*t47e(6D*t&Ww)1 zo7(N1Gd1AWZk~Nhy&swk=n}FiZ)#!e(QT(MHlB0wef`#ZhOBvKw;!LvIKOXb?v9U* zYl0uVd)WT%;5%LJPB>c6usuwa-CjxBkn@e;Y@;)AO9m}ndAaok%F~>TGu+O|gP13m z*M|3X_ilVhyRMg{-(0rf$%-qs`uB6Cmy)^6C%jX?FIc{P;5_<{nY&vzrJbDuvC_m| z0LmHqeLUs*FiuvYSlnz84z+iS*tpjoO6S#|U3p|N!iy~Qt}ozhCO;9&>k# zZ!od(yHdwF{ek?27e9dyZ(DylXx2=3H+ILlZMHEBKROt2b;oz#HTn49=@Y#gywwKO zex1c}O?cOBC*|RWn~NzUthaW)IbhuEM)!I*&FX)B+xeas`))nZc;u}W-hdXxUug<9(J@1R3`poS}>!-fpTF0LRO0dI$6G(^Q?`&9> zFu&F8-^_qW|5HenM<0%jY=31evPu`6j4|zsR7;q0=3LLd0S^8P)*oQ@kmy61?CA)kMDzKY{WiAk|FXY*Oj}E%-A-gn_)=k zjwodRQMZv9G`Fp1%y-TI3^tKW{01iY=wXUK7a#8K4(WDmVQj#MId4yj>SB$YI@mVv zVC&P3502c?YA*X5Zp-vTs|M~k%Uw2M_wjL4$hn#CUOhDax<<~P7e)>WL4qRA^EdPN z4ShFd=dTTN#?5Jz^;^^3k-Oj7nQKNlzJgYO#uB;|LI7gDT@BTI9Xau# zynnmX4dT@kTuY{g{S-tVnYxE@ZdnI?`^i&7FIq14IDX>e75A<_J@RJcgH<#RAhnb(uIox2I%OIV#Nu0T5_xWRy9?m!=_nUk(bH=urSF>ZE)Sn&`dFaes%fkVZ zuRpvNFs4q_u;1&CO8fATYmxZD!7GdEj2f@%4JLU)gF2bZdhePu|B-xM>i!L5hm1-3 z0t`~$(6FP|m+|{9eY3vu+xRZs`YyQjklKAx)47jXb-(%T)3?q{-mo%cvM3}fu(5D! zTUq2pw&sZ3KervzU4G%$4VR~nzm;=u-t4fS z6+hkUdx73>vNUq5bl*qZ&%y>Y`mm52wPUIv^2`VB`4{Rnd-L1;W4p8&QLI&(M5+09tPwsiWx6@9^K?Q6F6odZ1^cIbF4xaHZP z9e3*mzI&B>R@%CEn<1^wjh@hK`RK(LC*oXyKB{`Tvs?6h;NEg%kgmhnrkuKyR}C9; zJx}>gY7VdY{`qT~U+%s0yO_(P){__I%y=vC585ArQQvN!xy`htWyB!MPGw+Wi#5N_ zjqIP-_2-TUdt{Gqc)!Ke@QEQq?IW08>z}yT)os+3UYAKbm$n+AGK?lrI?tYw9Apc6 zk1wCO?Q)=TpMA|8je%tS#FIh)nm!xw=gql?>t>6(UT?l>eAiKZ$Q!=9JK}22!Te+6 zTCh5=u{P?Ny-2RinfuL@ajq-7$9KvYpP^W=et+2Yf&Wj}TSrCtu5JH{ASERw-CY9G z4N?Mw(n<*kNJ}>(4HAQdS=z}XR|7UKdj0|#+ z8|5h77T?Wd;2kI5wop1f?zw$rwle(m8Ia=1yevPJ_?-UwXC_CB52%%pj$knbfcUQj zw^O}^>%K~lElFubh9HE}xi?j_s@#{4#46(<X+>f5&8IV|W!&<1K`*w7?0dcmEgRjbIm0r)p428!}N;VzM0BWudb> z&=b`DJ?87|#;wDc^ht!CyVMm&hF`E&e7`B@P!PpLe_RaUQH5w|VpW&a-0XY;Pn)%i zMT_@{yLtp~zLm z8;U0o!QL_u6dFSzIi@bLX8i2uC3TsQ>3pHk5-+YIQpt|VOQ``ROS_~iyFH`j;?%Ya zzDJuyh}oDOSF2Jr16J*X1?QH2n#?VuhCAMKCjK6oVSYQ!s2YRXbQ2&LVujDfNnzX7 z_TNr(^-K<}0nBpZFMA0&do)DnyI9klL%#eoqOEK9`jO^Rkvh^6Sf$L=6N4x?M7>>q zch`bt4&nhDTAZ8(Iksw5UDOa0)!x_|q4@%|WUn@U6WYeSh>0Dj4U!$k8aCc4Pf1z5 zOE$e-ZU{*^|3PJ;@bU21m{uVGPFDEyK0Yxqaj|i+$WHTUnGTbING{ueVfFg9p4n&J zwA^$#!Q?H*Um<@PR>3ID+DCF$)1453ft#73&S+pS_oo5-`U~?kmh;%*DbcpCfsm!Tx{akY4Aa#pHc7Y{oBD=&2zcT3^v=_ZB_V(cA%h^jblC+fW$;0v<$xe&bH z-V$5em(AS8ofGu#dy*8%k|5V&H^OgS#`PJNys@;3{tjQP{oSj67j4#lUrEI2(R*ZoHVH#;O=`R{t6vJxM#=R^u0p>gIJ@$ri)NB|`JAR=3!;;neCcr7 z*rs($Qe-)bbsX=b_h+zaz(hmK0j4x0=Fv($CjJsaYdi>RSt zdxUi^`vO;@!ADeUGzQ^5ne^p0Rlr3?__32r%UEQga>FA@wt0ifg8c80M5#2mbE{z% zfg;icS`=9K6U>0W7aV7Jaq@BO4@yqh@Cjq8wzPu=m_35)YC+WD|9W?Wn6`RmHUeWE zR(Hj>2$Ycv&W`hL8{M(qsVSvha~U6O_5+{56$c$uMj`Ny$!AmqIica)Y#yHt z5Ampc)|g3dhg!$yu*yK6S~kVgyL--;q;o>RTmDb6a#RlSMA|kIaTy{FL zTU;H!?9YVT@=%;T3}wPAt|Z_^UihfJT?oC^rqfm7tYXr)xs3&9_{>dwdt=YmIUUFW7j)J zCiq?`&jgEd&8-bEPO~)v2-#nvZ(Dw%B`$2y_e$)uNoa1*WTH?EZ@+(N+n&>00S*l} z<2N+w6iuWCmqYyFmkK9aZfOzpZ|w@Y#}%rkIS*j++m23!NKUeyD_NkZ-X{w zCs$-yO(CmMz{m(-4JRr)1coKoPV=}^w)^M|zuXjRv6A9C!7h=__h)cuDu~#T8AYy|d{b zp)HJZbApK<-W)B^-jM)wR4s(VzEzG!B$*F2x^L7g5C@6L!F_(Hi%2VgX2joXHIQ`IUO(7XEZMdD?J2mWg8Zt zAKIlzoKG7hJD~8@xMY+4o0Ph#uQ$o;P(hIFJ9_#}r+3-hV<>1bP=$zIPsBMp^4(a} zr;#WqV=IKdoJ%FQoPLPKn?@WRM~f}OLgV*=lY5%SZZWf_v=)&;?VzcxY0!z)y?MRQ z)8M5H>dVFQN$mjenMG2l>yFNcT66C=rA?Q0La1WsdKU{8p`C4;tZVQ(9|SXzHm>WR zj7j?y&a^5#OqVE@)Nv`tJYb|VGGdWvq9c%{w4@Ji8~d~?Y|oSa_lEup|N8O>4I3_F z@+$bWli4Jng%PEVQFLaujyGPAnV46{QVw%&fz&rlv|QqzJequx+t**;5~vCI&BCPu zI%78nc8TbwybytlO^(Y|k;zu#Z$iH%d9GZpYHN>5JAFKjieTa$|7NN72E0(T#{v*x zW@X*dDf-cLG`9gT@PDuvdnn5yN5IY_vWWLWY0?T!HqUQcAiQ&@X1{!&f<1j^_hbO} zu%3o28JqdKR_}THd=SUf!PW8nmc!()by7G(=9vti9|W)rcZtt_OO!l(9{h;5eM{<0 zv*4#shRN@vwAwhxt(@`kzn0a10ZIdz&>m~Fc>VZ2)+&#wFO!K=$Y-pxKbl@Hes*nI zD6;x67_+Xs6^32xH{zvRXPdE5%dhWX2+kAc8PQAsf#~X~bAZ~+12cW?KD34@E7L$G z;~?1B*kX8;LdH(A*9T}vOO>@#VV4J5F0QVvNu2u2XGfYqpow&WdCv28z@`(x!-IB= zBr8t#8C;TM6eTSVmTRX|qsT`~&i*8n`?;>MJbZ9}&0eij)yzTr`Z3uYDWu8~l^5dpwRLL*O`E z^2o4I72f|B102Xi5!h%~wZPo%UC#f)NUGvQHKC1eR{s0$7K%IXGj%%GHEjYptpS>MXCDNOOo#VhBx z7(4q9Y6m(p@!t$*B}-)Z#`i42q8=Sl0uic8*-jqiUS!ULOZBH2bf0&qEWevKwFI{v zuz(l(+&tYx3igH~BPUtEexF=cxJcG;Z|YdkunYawn@;<9schO}@-o%fTN!ab7Tma;mw2 z;eO2pBfr~PL0T_FkC-CP9MSE|49I)R$W7eG5LnUg3^q_%dJDIaG|P8{zp?(l1bDQP z6La8S#7#0C?D~`cgAVw{S96t*a-cF+b*=pwy!B;2l==Rd2nr0s5A5Q5_e1c<5JOj_ zO$|%;NKU_L#TEv=&*?Dn(i9UNPgnAdwEqCP_z12MPNnGE!nb{D>Wf*~<-W{+u2{eb zyfTrLU^!CSA_@&gv?dO@O^gQNBO^I*_Sq07VAnF8 zE<=|QHIAuk$(~yME+0+;;^_Ceb;1^D$?#gm7e?U0{#_9{)yv9n>7yj*jihQ)7NyD! zcZ@aR(80HJIQck=1(XxUpKL zcgc~IO%SCMJ&1pcnvl)7?PW?N1Qhiu7{ytERwgqco<`7WkL9OSY@; z^x%KC3^gB7J|;&0M*H}oSD@{t&vxqc@FW>v$sW1MXObF+u6$6#^_GL|Rf|nR_CXwk zu#PY)?6ku$#m>NfW_*tZeEK5fWmr2xl}!@pttN3Rd!aXhtsrK=ws=misTV;gzvx#s z2@V{~feFoJ<;$!d4VphSJHs>6XtZIM42+%J(*z$+MBYfo8IA3|(qL;*<^P#D9S7xR zKcii5n|13v7ty)*rlqZ{-w)xpdmt!2fN{1 zwTB=IezzPY!p&rF@#QaD+q+J04$HLZz{r_M@zsv|RKUXowpL1&6lFsulW+}_H(&<4 z-2O`*c)~r`I8M{OiT<=P7m1td3q}Pf@FpWYvPVD@doto0Q;~IrWrT6M?wwIY8SJ=~ z-%e9L6cUd;Fr1Q`KdO4tArbj5>wzJ2kOQ zP7RD8MZZHj{9BA81QZvP9Nlxv=Wb$W9|$G~iZpl2udi9$QmQ;Bi*f)L6ma&s@heo< zxBT|{JfqOPlgwwjN7Z z_;$rq*AQhwE=b|x8$AB^0^k=;OZGzd6SM?-T#nv<^qcq40n=`sKP{Ro#fJSq>jS{A z&1GIB2W1`1^zEw6eb{E4`+Uf(jCmV(&Q!#aIsgfY#g3 zuX8qg*z*}f%r-9b*bw5q-Rod}2ba)}C!>-QTwH=VA8cbvh3ux6n>yF zTn|!Ifw7!f@$uJ;V(AF*s{s40EMP{8IN~T7pi=bK#uJJpzjq(5JQBW^vThe=gL%TI zuu01yu+Eic4@W-5wjv=r2g7O?%g`9AnSw;kqKdoAwLFNUFCx;LjTP^9@pRYfK#$i{ zi>1Ik$yg(eCZW<{XnVr-0S;~~^f^ow>C1E-&ldV_Ze!|s@&{OZd)Vc`YiTH}q z%_!df-F@N61N@8ldXg**Q9#?b|H&6Q0f?jD?Rye51o{u_0T(!op*h=jJ%_OJyRso>=x@m|H>(k#SBn zQn;RjqYs;O+;MqvNb7waH8xffLgU>MLr8GMlf_u^aRT}vnd6%$H*@X6bO7Pvg^;ileINt%Zqx;fiaq>^r9ybtY~%>8+Y3f& zsc_~>_ZKaH@D?y&FRJ?RFhx*?(#90DR6S?E*lCEk|9$(`+%XL*O}VR&_`8d2nk1@0@}gA>%|`fs*wfo=#jd zJN^A`8#H?%f9}MXEn2ut$jq&{oKIy=H~M^OX5l_GqnAvW7ks$V%uu0Zs_-516ZpN{ z@I3`p9tQ#3>;MIj0~?%woKh3!Mib5X_u_6d$1OYhpb&~{Qh2Q)?S<)=cD=7s3=*I1 z;2i0xb19DEismx=7*ZlSbUjLf9uqUes(;82Sw6ADmEQkivo!N7h*?HI$<3`YOvHE$ z%v8IbQ+Z^{){Nodc;8h-Cs-&ymYN`k6xgl|)RZw(xAZe7jy+3;4)>y4#LfSaJ6Rsw z#mPndyKCCS4BRrj=a^6RUZXX*+ls_4dD~`{v48zcJ8kaM#UBk+u`s$ENGZxfb$cA3 z&1Y<32n`jLVVk9V4A)V~Gmb3l*(;iXgPF48l=SqCQiI09Sm%Uozju{ylI-t|wZ@1I zjUq6suWavsT4%Y=x{h5rEUuSR{%LLwP&Ja0Sn41pzuJdQZk}n>DxZ2L8+qU3oJU8& z-Nd%)Q9Y>F?tp$<<7qswQcvP5LTFYj)E}kl#&##F#wHZcOH93&|70CEJYc)p>MuW> z*n#dh??pgP2yD%aAO@h_BTwEv_jYa(b#eKVNdE*qRnnzh^i0P^eZoDn*7* zb!L2OGw~&E`<{2x>GjJ2#hw>|4Gj&2RC;Ia{9I z7Va07(0TF7cK)r-yT}&)Vs7LM-BYcDpTxNISgd3n+gOmJ+XFq|;J`YuIW9;B-8?aL z1zGR9KemYx5Q8>*ifQpIjL={B*3Q_aU72iUb!43=@ME}Smm4YG3$YaiTXQV^EyVOTf?;e<*Mm3BcG!mAh-u>}toz4Wn1ucT58F<~jIG&O zG2)Kl^ZaKECT>b@l)Vae!>4+y$=1(`4)Q(Z@b8u#6^+^LBJtGJFVg zG%w#P$MT4~n`?0{DO{Wj0)MIU&4E8n=R$QclSq5ioH{Aybz$XbspQn;E^ZxDyz`Hk z*Km3Z!YhJ|jvvm`8hn+@9;Rl*BRmAX&lVCjFwi^cw0_jl+Y@=v8Lu`1{0C<+gy$HK z@{IbdSjGe_G_tY0fpdf*28E;c+hO1QjS@X@{d;&PJh0A*x9Kj_*qTX;f#}y3!iD2% zWVQCsU&ab3t-T-4O+v!-Rt2w~nA7@pDUqSj7@$HD|6BW8rhld(B;06GvpXgws@mHn zcUza_nV)YiEUqs;f6=PicX@&|s2rF|t}C&WIo7UUx;-VBUGXEQnl?ifGXS}dBrP!X zO_FDwWZm+9IPx4;K5aKW;Ckw_nVD{A>$DWRW8!xEyD!t9xUccPN-Nx0bR(ba$s0Od z)`UNJh(9M&8@}rrcl#CJ^L#E2ae;AcdurrK6K3>-w9A_*V0WrlgBv{dW2UYs+>DQb z{neS@=(vXA?|UCumgqMcdMR=0WvA(Hmb&UGSR1z`*w90c>L31Zi{1!r$9q?qEvI!S zEKJc%AyR}(lzLXR3e>Uk2sIvHHc}BS zW*ye(0%RZv%18@t-=zLe}-@`k(vG2avSBz z)7gm&(nv>ywr2z4e3aPfUdYcVzCl*SeR>>wnw-*&^69xFMn>sED6iM~r%c&eLfB<8 z%QutiH$G#BFdjV@xM^U22m8*$cD4fMfvb-BWoJECoE>&w; zG{e;lq~jL*pVZh787xlqgerexnLWaG>@=_V{)gwSrnVCdwNTGq-z#i^0u(6U@wP0B zapJ3*#a1Mco5Zd52z3OWD(um0@-;mPz@oL7>Om=LXrr{w`&4SYNo*MT^PZw5!YU27 zTvJ&SWC5{BO5LhinDoZHV@Tw)d{&>=h8x)7t7qz_&Wym0*ZN|uW>7dMvComt ztjfV_I^mnJ17Z(TG#O!e`Vc~ehViUt*hBOiRw7vMH#{I$`Tdia7gQ7MTK}^;({b0Z zib6joR6d#eWN7_I?hx)9crfQ?_WNtLo1MjeWM)o6$MfP$M+@9rv3V)s+@*@%y2VYt zZdP%{`}W})nL>=EK}rYjiY_J7io5U8)!a(#Z0XgBsd&OIZ+D#>>nH`LkGTlv0N%3n zlXQFKUbl=g`ypVfNfI=dDnRtk_c;Pow zOIT~kJPq@k(I=0nN?dbN$#coiXj@(Q<|i44dcTlFOQ3lj3u?1Tv_-u6s6HVB*}-6< zm6eR{9H&ZE^G?^Coj8b%+2H4w36Os)`9Ow>&+apooGW(Q&+pFt58Dhu6j$50;IwPr z(pZ$8H9Gfc22)}hYH{@|FxgaO1KDSaWnw61Mag>@JgJfP>FD>sj8%DC;lR@5gXVUc zop0t;?nxC3uD12)kXNC6&!8Be^yTU}>g$Wh`d;11oVQIgv3U8B4{VP@JS2D|cypPS z>-KK{93NI@U3!E^GJVxFqAZJQvzjTFA z;I8>!Mcr!jL+38u9*g@C{`s^v8>77uld$rbl&ffy50||~>Ga0Z?CUIT6d9^JkLPgO zd4v0!v>WeJ?3s!{W*)UhPl7NCz>+-k5Oh90T{U}$7D&lyN_D|}Pk?JoRv04tHR3A? zi>V3$Q``sc_|vyRtDzzCqG$uW88v6{ez>IXlgh84tSy5n~L(wX+X@#_XCd zg(s(_ugHcKg_4iX_GyNxH_}E_p-pr~cx^dw^n|fjVD*O}gd*@+ zK%80c%0eazM~QN5UIsaS`Sv6SqWsMgMfxU;nprdKs{1xz zCGTjzsx~db3BIVT66hwo_ekWKcr~0qa{uD)wC|fnuS}C}DLA2k))yY*ykp`QD&|it zP;Jl;t=4n^_O?K*W|2MeWKZOtAz|CL90e(1Ub6&cn&t5cw_)>txoCbLP!jKjpy zFfmG48%Oj}LFHK|zHFP8{zBGO`{Xw{;_{Cn7_620BWHFhzE~eJ)xhnfG}x@bGcOkE zuNqhJS@$w<#TS^F*zi_49Gi7$ti|WhNm~UjaZFiy%=MCzA<%S6&_u* zTHL5Tg#6LMW!(VutphH91a0LD+vuqj zFKbR(g%TdmVAi)khFXI$E=_d4%5*R5=qb4^Sb$=>vRQe&agiZ39Z!f|NHl?Yg7#l4 zRL3>g4hh7EIi4RH{}Q&+er{iZabbOk_WCfJ@Y0RSuy@Zlg2$YWJMZdbx~75O_N?0xhJ zru@%AHta9Z$;yUoPtLqj3u&3D1ZG$>-B1I&NM-M-ubwHCy{vS`ZE}`JXC*ek-?Vxx zLPATC*)8GS@<_@t=xjJp47NGxLr3ysuzSUw6Vo}cP@P)ea=S*gNJjm|;-~Xoye;?z zzn$6pFtRME{0v<#!sn7p`*WKxN^V^n0CE$rN0;{%P)BXS+Z<-FwQ z)-<}@|5;XpYGVB$7db7hF(?{or4*23haOD7W{<6i)bd!^+>@2(KRXUZdo9%4x#RGW;!OssAnQ6W4J-t6mIUw6tfeZ`mRJb2AG0sAje=-0gOL1}%vWY_&Uo&?Tjmdj5jNfKiTzGjZ&?yD=m|HfyP=QlhF_rvq{FOdlbWNn3c`Do0l4b zime(bq^w8cV5>ko6ei;;<`hJh-J9uhv4{7@R9@PU;0zfInA)>8$)*$QCrV>DMl*GY z2b)yQ%TeX2tv>rsUTkC^{m%3d_lhRyxfGu6*jtOJ^kq~jYhmYl{mB~~?I?zd)mU0C zMb=5qJu)<9q_D0`|2X!PI6WY4Ga7rBbTd1l)T(Rpm}_c`hd`K>3Hy#P@*aye+gmGHDc(L_2((o_;m)-^4i+>^hvQ6TC z&~)smY$IKlro!Rihk&sodm&{8x)33lJF5<52$?l=W@(vSm*Wbj5f7OOMusB%Z!*(A zv^`u6(TqWEzM0Z_!|`Uocb1pM7oTXZ)^ayDwdSkI9O3OJ=S7BP6mvO7x3E+KsoVX> z_$Ij9qa3a?9DR7dO!8)a3_y6S@yP^lCARLIlQ0Pm7a^+EKkRzd(?&kPABmM(Ojb`O z^A(A&AJ}BoIL?}d$3e_=6;SpyjPR8G;W*Fl?0V+c8b8~+Cs173AlWndN6#N=R;=Fi zVZ3|O5_<~kI{$G>;Pu;OlYCwOHKFKpBGKn}=%1MQyqHGW)5*sUx|JB&XkMd84CP!C zGJ?$ll7BQbiq;@2Kd(Rab(wE>PYOS7s+`6=X>*Y`w*l>68(HcWOSV1!uDZ>eMd>}s zn$$Q{&g*gJ=RU+i2J>9rPf{)Plz!Ux=<=|HE?S7sd9l{jcS-jNJOgo8K1nrK>DgRU zArk1Q2Q`K&J z_}S;a;BMfO~)`((rXs4RNC))nmDa~itkJM=@{-3D(RwL zzsV{02;EQm;nz>0=jth=l5gLn?UdJSu7PCD;vv1w1ncAk0xb<=OEk8=yYo-=`b}$r3SEd@;Uy3+l6g zfOfJAHyC`ClJ&edEss1@_cslPxSWiUYgsi}9%cjCUv zI0y-{ppec60TU!RsIa2dEk{`cmP1J>v*0YqR-(>{YdQPfWHf5*cH5-0H<59ny=`ev z`2-l;t0Bm#U)E$dv>l_&W89MMJ69V*XzR-aH3YudKv48q1DpMi#C}BS|B4sF031M zLe+6(4QrmXfBDwW7>cdYU0-BIp-F(#58~UQdoF!$O+d3n|Ct*3NJ*3TWUot7iQeK$ zjdw|Oc&69wZ1J?+F({aO(@E4J5sDG`geW2^%D2gkbd2%5G!Bx>@W0FH-(%tb14wl< zRlHO)Lw)#s~xPrP^M=|&qr6Q00{IG$oHNnDsZNZ*};ul(Vr`KDIa0V_j? zx!=d6FJ|Bfi)s7IH<~?Q37w)tZqh8HH{eB_E_OXrW751?MX{Ri>FL+B_fV z3WYBZs~@D^j!O!hEKp49gqAD&97w@xPQDt9zO!Z)p$@>h@t2`9mU2!hN{NGnn-Z(V z{J##>qkn@=X1Tdf{`$^N*>y3@-R`+l>s5S0Kq`Myvg}TzzQm)#saX9*y)AaSa(w*$ zGd8#PuuZNLjY$T4FYjU%emQ!X%@dwkFA$x?f~&n&{Gg*}5b!;?$=1-Z3|2Pw)-vF3 zTHA9LU$-d$HLvrLFT*cABY52634+x*P7QwPRxfhp1+$Mq{S;?ywdw!oPmx4Zn>j2xic*`}bh5Adc$^_%(RTA| zba*epjxR-~&`Qrr&(B=T9588BI#Y8p$EZbM;Uz(3((B`IWPt_)(DyPWiI4Bs zN6QUVj}U%F$G<+f6ZnDpXLvY~ozl*&KlpUvJstt~<`SkWQAe!Ny1L;;6rNW-$#>S9 z;fN#OZ}qcPikUhLz&wXDrVSquo1?*oZDv*|LP}u4(3az$QRV-&J-tK|MWZ3y(WZZn z9{UMB7w?u3r{wpr`q-EZ;P+IeD`+HARdr(QTcdf;8)VyUuI>1NyFGK%M-q=kHcN(6#Q^H2S3$ zr!{KYT)un1;Of;iEdmG1L+T^1a2%UFVv2Vs zGy6G6r^-BN5M0M^&PU2j)FOAh`DX{vI5J7$a;VT6`n!SG|GBpWn#Vlit7!V|cKgkG z`_u8!ZcG$tXmrU_$4H*hS=rk1X!$-6DN$xHD~rR1MZ);6`R&2=9f+q}S!Je&1 zfxEOgeVX218~UK0uJ(TJ1|+_ z58IVWLzmmZqGI))K~6Rc36!SzY7!J6Go6e z)`0i&nPi>k|5SO?mlnRH??QxXu?u?d0q0j45`Ef*e%}_BYr}zS98&%zO;>NJf=y4Y z^3FGzR;--bHutEhuL5s6T&;XwI2U{-T4;aPnW^61 zpz$y~hASCNe(ZB=OektZXwWncbaQk({?k<;tp(a8>?gP#8d{`nT3p;-^D?7u%7CYNhvYd7^^m4O8NW!6Fid-g@Oa1@Nl~s`jXjw)Crq5iyhx z|Hs?exbWdun&hR+af)7Fv4cluvq$lbt8b6-+q|C(u&(k(raT4JGTunkfdUWJtVP(w zp$MMHQZ`Gne;<1G&oP>E^dx8jkV2Ou_<56wo9?9e$Oom+=}pa*fu$Dl`^%(rWD7?z z)t0$jb_nC!xU&E?c64R8%5w!I<*M5a##o3`i!LzrSnd8!)2WsvN~f41*s%Vx5Q2zx zs=~%yQ$or!%iO2f^4rK8<>66qvS|BWF5qd`w=KL}+gTdlmOw?|mBSkXO7wnl=1}VR zvRES`UGz)C(pf z#P6%Yh9bt4+D}~)=-&nr8np24_(7B}+2s^}fVMVAfm#7NX`DIBCvW0KEqi(KErtScbSdh0NVhtPn&T;yzcRg!%DYrxQ~ybJTh~R z^B56Br8B7Exd|xNns1&ZVlCI&F+DUi{z~{puZQF@&4ksvgnevH+*?C+DwS_6|78>9 z#$rz9xc*Zq<@3wT+N*_$j_q|a`L>lFNQQAep)FR2m$p?4hF{++}na%^1hQSG!5Mx#1EFP6Ef6?w4H zvXX?q`4auCH^q)g1P4v=Yx{ciVIN{pyNI5ymY<2K@{O&np4>KvHz__EDswh#ynR$- zUsQ}h?zB0T(YiBU>nV4QGG9si1+AkgZD=_e)h+^AKa${a<50ob-M~_ zqYk7`aUP=YXfN+|qtjo1)BB3Gc~eD446A?iIO+F)QA(nTSk$_0>z=J;6h0qHSuu&5 zyt_}9_KN-Xn3LkNm&XtRwZ13PNfgPypQqQja$oUTNbB{@tdzpD7WubrZD9JPV>f-S zUabJTS^I(at+pF0LUwhZ$JUM_@2)IaY+bxu{aQSA9m}AR)FwrAnN+TiHL!oAyWaP5rDq^sM~k<;_Q3%l%I;i(2oT`kjyoy`WOR%L41m^0$=} zWvS;gKoU+!Kp_p(^*951u;kVkoDjC;GPbUg)#`XTm|u28X*AO`a<<3RmMSehacACm z+*3#^2}gY$do1&KYBt`+hGVg~_A~3jJTEzu{8VL}PJ~LNlH%iaXDS`0zS#;PB-|Ax z4TbHrJYtJ$-J=TCd*0aYEYj@+EaxVziwOCI6g%JHIa}-f+J#OZa9?`HP_`{UDc2dg z99kG%Y*9^;xqS9uTDo{6%x$=@L2+HMlXBoRa=%xqzYz;<(@1JWP(IXTwjxRl>(5U_ z^VE#83Zir_iJRf%Gj`c^_$^EI`D^30W2EFh&4^d?lQmkT53wuOx7$BB4o2X2nwrx# z+Byj?ThqsyZG-n!0Zg?!agTWkc(u?akqzV_2p+BeEwlg9$dJ&Yokgk|@&OUGi2|gY zv=?#17?9#bFH_nxyP>jW-|03NU0w6iUd&~|>%x;Hr=w@?v&;85rGGj$Pn&8DUG&Qr z@(0#N+VH6A*bbKyQh!_EJH>!NrW@yXKMv=U#7xPbj+t#pwHN_^Y+Q!U$cKCOx{BOr z6Z1TOO5=@u~o5W&X4;?w(7fYUqFzf{7-bD(+z$07Dp5{7V;d+tMr_3~WM0$D4g2>%c)b#$W>4mW0k(hgKY!$KR#J~NIeqAvXaG{xDZx2Ux4PC&iqvg4QuH3N+*fyA z-f|uQJ-MXh+#&BEeLMq;$W@jN_x4fihvxPfXa0?%|NowstQq~Ps>+)c{>>!K!OyVG zuLysiONi4I0cY)-t>Db`)YPK7gRa4W5rV5@V=<@L5BKNR`;~osoY63)#2q=*1LJ9% z<~r|RGddE>sPOf)D(ddOp}~$kv#XUjpIG)4Bxi>rs0RfEk|eX|w6HY)>Hlua6eff9;$6)Jfk-Oml6XX%o?PaVh#e8wNrYYbR^hZ|;cI z<2BaYqZaQJifcMY`mK$Cti`u3kL||x<|^yKJ}AmjFB;*|>p3o2&OQL0E}2N!dAL_@ zv>Guy`Gq1aO+KTw{0uh=IG*<(YrMJs+sf;`vK$+$y=4HNpBpvm6S6-?Z$T2EWY+Wi zt^d}clSre{mW%9!%}Pf_O*)a{{8$$3EuNavxzDYCk{ozGsx;`Gs zC~rNQxZJQmS<~Q`HgV)y!{RpCaaz0HTuI5Y9fo_`4knRbi`kuIE~^$_VZ5pJ*QG-c zTvS8L-q}tU7VGTg2|$rwhLexPJ?6;{s;$)1jn*by0b+bQyWwi^Yf2**al9w-nthX27$8q_WGc^e~; zJgld@b@;A8ElGT}-a*2nc&YeON4~ZRwYIGXJvq(Jo%W&iS-R##LDVMojwK7(8+hj; z7BriuKm8A897m=rBZ#jK2h?G`-qp|7rP5to5WefrpSNOjvyvwN!vd%lTpiBWS`^8M zTx%Pjfz<4`3RcaC3~Iy=3`kE}g%3k{$q{09R*iDx839+v%gyn+mn&~*WQ>R*D-Wh4 z6o~i1Ngo8YXxw#D{kx>^9o-H*Xgs>%ExZo%*({rdR9LR{U5BUQ@y3`k|f+*Z&hidYCm>R6@b@&(P3|KwPX}Zv2q%aIMv8uk($C;wX z$8w%87bW9~l{z;AV&7XLFZ0AXSMuBtOD*JWN6X1Yex$`kHwz=wb!X!$HaK!tu_;f9&qOQ3U_l{mcEyHKF5%y>Egb8~3Hb z?;F+ub~_`uGrhob%RJqoWW5BBlK{$;PD|}Sp!fY3hN`(zcx`)sQ!`E=T@e6$lx=(%;N7=iggY z$<||?BUa>Su0}4#{|J&kIQ{v{U~X31ogge@YcT$+?C;H!+*=@xPz4ZFUFWc@rKCHN z&chZv(e0G$o8%7%hfH2X5sPT*bC7Z#!#{3z^MM>^1ojQ4fJo`;CGS>1O9hHPkw9T6 zqU~JwX+v=EO_!&|hozg78r4~XR?kX~;r8lg&j-uiDJ9FnBjfn{UWe)GA-3zMQbJE=Rv z-fN|r)+yE+h^rD#g>WOErwlLMxS<+1AIpCGg#A^-dl8-RYn{>XZ z^xN~Ped692$N7B4l4%+Vcfz6eZ>0YBg__U3m0`x`CB}9C+jdt)^3XH_D{T<@%B#l7xz zujifSpePxhtGAlTtt2170B*emWDA=LWItPXN^Q+-=9;TY<%KkhV&A}?frP!&TxLo6 z4z2U*ki~48#lKEZ9VTRx64HVpSNB@Z60HvRQ|t*^zCMTq24(TGOQic$uRw{g;dT^t zUcqghwfofM^JE*%y{Tuo*32Hk;=yFHhqk-w@uOa3(}tv1tU{Hs{b0 zwp1tl1Ck@_t+IYWiJA5(M>B264*ceVa$R2pRw2=k-`b#Dp-9QAYCv)E&Hx)1LYTjl zBOQyhnkg-Ghvtk#LJ%kWnkS_#UKj3M!X^8=r^saeoAl5O3UJZ|86gw+_b|s6?Ei#H zcb8((id5d6hYAEw-Jq`<4!3C`3!I4uQJ4zlq$dJ8T^m5~wV`ZOjBMWsH^A3$E{N#Y zl1_;Tvx&OZXys$ZSZz)C@I0!(KDEwsU)<-Sdk z(gpi#AR3!&T%evh)swG3Z}owNs}l^L#(;?t4G)toG)#C;bUbBcDo(gy6en6jYHFm3go_|2Xy=={jdH$;Cd zdfBT?X`XuK@?f-Rf9+CMDfO(ox6^XjWk91vS+M9Pdo?3E!y2S;Me}?6=dhTPh!anG z&)9d!M1fN2`<>ABc{iPlf^u;thJHwqn!GejP`wMSmH#mkj_$hB)HC-sYQi8u+Xj1%?J@~2jB zL^IhKGUOI&*I;wxdq4~K+2CoVP)z?bjw>%Y2o3Ydt%v-&=(ooEQuW{YW1Y1MA{9zU z`Rc=*Q&~AoO0tUI`cqQB6Z_68~-Ez{u{| zodAgDbaJ4x_YBxTYE&7C1n$4vxM&f!M(0Xua)7_1Zl&hUK4(yd@EqMnRA^I|M`if} z6t=`pUrRSN$_sFW7oOY|KqmkT_uqrfvO3t4@cwIJ%CY}E(`)EA`U6!{vdT#Z+omQ% ztP6x!Q%lr0lU=05-P^e&iala`3oS`S*j{pp;bQ0u1ZR_pOaqqd6j4?^p$_C zR`o8MkC)e|Fc?zDM#sU&_I1%|)=!iq{r;s9%L zfQjkImeozyP0vqT>h2ZRPER-PEmyn1S_A^tfXqsdO;1M|k`e&Ln=%h&ZN*E)cj| z=?Zz-9#&S@H9$$FdDP_uc}jqQRQ3ZEto`7w=q>3 zd$af$)+9Itd+2ZcuVZ z30Wg_by#JX%-TjP$~O_ATa8-!h`kNB5_Mix@@#VJ-l8UNr)j;g1LVorCV|aw+lW5K z!>W=eCsO&V&R=!Ynof+5G-l0s)npXytG6ST=wg3+FR?Hyug`9xn6cMd5wSn<@yww+ z!#$c-vj!>(+o$9d4OyDK^q)UhgX+hzLt`Hknl&`czE9J)=AcUJm!o=&yU$MLOMFTu z6RC$vdt1k&)?Aa&Zg_Gn6vuhab?ZY)jA!byKz~abcX*U4Lb!de!=NlDU+f1C**C@V znCwuelYl3zG3*Dg`Yc?A`w$yr@DGh97z+3q#yIUbmO@;sh}!lQ4E5{uI`Z|IFEz`K z(h{My;$GKXiv{l@SEo0vmtA+q?rA(8fnQ%W@n$GpK{f;3-yAzq1$>`I+zy$g^l`pD z=V9A&-Dp#)r)ddA|B+$m3Mc0c_2CYjJ&z_`xNzN_lTfX_2T^MM{*dvy)hZ{yEZutE zXKylpDnj4v!_8uWODN~1rtLiVZS7(0z;&eQl_vL;0NN#v;ISK<7K^def9Ux?{LPq^pV`B`YhTm$%#R#VF z-9&4?DE;3<{Ck!pEvTPXE1r$5%W|!pY#O>F1gXX+ct?re5Lh3UW;GTt)L4EZc)Z+7 z+>CpxpVC|W)%}M6YP*qEP^T>!S$=xJKk)A+Ujz$szr@wnyiu&G=ZZZFvTu;W5OE6X z9M2BvghgwkE-~NZZ)xW7CM39SqbB0vewWYt9+!$AP$GbBa$g2>wb;h|+6-pp*w`H) zs+zdYhT24BX5wy;BgdQF?5+|#ArR#Xck~#QR$|HZA#A_uz5p#crZ+Hx62CxB@mduu}J}=ey4VUh}PAm zBK1R#M1$ABUSQTzlj>?yw-s`EqDld#6^FA}{&5P)Q;{P-a_us=>MJeNnptO2R1{<6 zGw*_r-=JfGYl;!wUAnTkVz*6$hDu((Sp4csf#=t0qB_^j_3Rw_fzoA1d$R#o@d~_R zhE8Yz+n>AhPbe>Mr?wvn@oV~#BD7FKAm03y|3%>6!z;{@RDx@zwHDjF@q>5}aCBpC z2pxk3zs+?fvg+x7$BpM5H{oPu-Q_1EW3q6)Fd0uxv&rQoJ$#jli$chy>x#NI)RHN4 zN(k%9pz+4q*kv{RvW~Ax+3Q9lf-K;AQ)Wk`E0D2}2Iv26XMnfedk*psXani!ubh|U z$r7IIrX?mCVn*$3E|{aWNhGcHPqA-2n(0Mtp2hh2QFv6^4a@05DoiZl z?pTfec}a-dl64t1cJsx##dtg&&k#(roA>n#@!hy5 zAsLlMq-f2?#cc!$JRxk-(Mi@wc#fm-h2kW8>VO=3!+a70BR`V@ z4p#GA0#__>>0MdMa9fmEz2W4@z-hSh6{6)-woM87tkJas%XnG$aYAb9g>7+-PL4f; zk6LCXJYm|2nuDMRe}9Z!h;@vF4Ii}-asV~Cj>f`XBHSYTSyUnbgDzxRlxW*nz+a0_ z*64TkGkkfS1n(oC81cQ1hjkwG^x%6Z-mGi!jiiZh(ID46gwFm9*%xWEnw~Yt33w4b zOSb^U5Z~tU+}|22ZAyC~i^(oTXJzQ)`-|?|UgR7R(w_EJmpZA+oTbv{zhT@__%!Bv zLFk|zchol{G1y{kX&Uv0>Q^uX_cs-jFL&YYl!Doknrh6qf}z{Pjg=>~A;nS3(?oGL zq8lv^THsp~xlI0=S2%FDZOwKMB$Zr5qB+av20l;0?U$ySEb8d2dtC0@se7?C>`(q5 zFrFb#`X0*9|Edu1D>Die6B|7B=_fURe^4ixrfE8p%(!LZ@15|Z&Wrqf8ONH+w!zh3 zQo-S_TiS`kj9h|LXB#iQC2WYb=NlzQ#SPN8+q;}0zK>2$> z@f5M%&&pBf{U9~h3foZ$l=lYEbXL|rrj@9q)>>bbhI3L)96cOU(=Ceu{)73MQjOkc zof`5I^p_S#Q@k6yIVYjR%ku{xYdu@TH%;{Ad{<#5*xVK$Wrcrz<72!Q`<}Hei;Q9? z&pPnem&*Hex(SS-rH)$0Ro{-!DhP`T;S379X)QWdpxTM2(Sv&_b;wUo60fr!b%O3@ zv7!P9;>U1I7nM^qrZC z7d4g|`aT&opj+q|40PkZ2n^5^=UhA!DF{GNG!{Ht6X2k=(vO-L%-p#JRa zjk6YaAHt`On=8bNnhQD#pK%f}_+5#OlXB02X<^%h#x3RS_&PNF|d5ggPhxlc&ULnW>7b z&3aIDDe0WmkbC0pV5iG**dpQE0-SfEo~1OBUgJKq-W4*{4#q8Nk_+$zGI#q+{?H0$g-1H??pOKx#~|xqcWA(G zDZWA63w$uj=Em#Cr2|q@fj!}7YCf9+RQhxp)&i~#qiY8^a*+fgq+l)(c5OK*zQL$z zWmdq@_wr{DuB|Bzf8As7Rg^X5((#N;yUBoOm>XQJQdtp&SWWG{)2W}nU-wtgqFYlrAy%JplWs2eUMAjN$Exi2V}vcF2pEPztK|O3=X_Lq_vccg53T=a zAim9^iyW0K4)}_;BBtTI*%SyvIt;{l^a$F2wIb7;WaZLuX>S;=#o)u9oJ=7h?tCCi zT%|R*U;lXJ9=+VagYopz>y@FAK$s%yJ00iL4>9Q|WmQWik)|s>o@IWVD_k51jei=# zS_0LQ4Y-yi19Y1X1nQ-4Ts4cd`woX@phE;TZqC!il1{?ULU~!mwQN&)ScS2VzW66BxEUhd2et8!^}SYfGhhYaicN zcI9j6zI!|`+SRBY$Bc=I%|C$rUQ?_h_k_=s3Zbjr$LmSt2ai`kzXX}d3DfEMEEJWj zwU(ucUcE~+3|^mnFNZnNT|(-$;P%sOKK_> z1@~39E7I^yMf_*yhm2?8-@a=L*yXruH*x;M#1wGcU9Ga)t{rD1pl zAymxs=|~UMKb;Q8GFbLI?OWY)DMGW<$ct&BKiPRF1n$%H+h*&8qJHhw|AeC11}9x1 zN)LgAHlzOU1UuFJpn)z;cKBeviJ9^KgUuZxVPR1)O>wJukc(u zc0X|rlw4K6j}q-E#=dZ&sMggC3iR7gGadNC3NH=M`6==(`FZQ7u`qyKaBgHn73hg; zPL1S$dL1H`Fk5$s?v`NpU7sW;(|UHRHW&7h?4ZnWPWTwnuIB)%~)cis=_qTu~8!f%C<)Qw$l6NC#@{^4q|_~F=no%71#IWum=LahZ0wLvjH zI{^X+&LdG6sw7LHVkA6&*bphVAfdhm3UX^#QP}KSO1lSZmlq5aec}n zTL~&Y_$n2ER{l@R9)aPn#ui2*%>D&hEK(Q+&&OY| zn!l*JY&fVW_42xXEI5?HVFL?H>WJW0L-1cexs;apEX(|L&f$IC$PsO!-sJW_4#^p- zb`JB326#YWG%p1VH>v&l=>IU1`8yO}qUrE&LWCXg`nK!m6bh?{z%H??@FOuEWob`) z!S|ax(qWeax>Nq&_+8p-G;AK3HQkR)IifO(5`=Oh_JdJJhS5lhfwRHWux&~Gpas9| zAea*#`}tPSy$Sp)fNQa<7m1QK*ABgi%=3}TXqTwqo*R&%>F`%J+28&61gUf_h?hApViJo?Gh;04wyino$HOr+`;G%+lU+dpqIZmBp-qcbc+KNY zu|0mMst@h|fS>C(X^yc65RJSz-Osq-+k66Kxc~JqnL7{d%`wfJHX7-n51G6=0_sJ( zgvV*mr7Q;Fe8q>yUDEX^Y!WayMjlZ(Ci5Vkm9Q|iPNBUfi$$02z?`i2@X$C{o zB*^z*i%dllw%G@_8y5Bw1@2vgAT{3iP1Gk96%Gc+5z%V=Cu4yt_Fo_?u3JI5!mY@D zH<}-J-Jja_*bq=xc|^+nk>^(&vV)WPP`_or=#Dy_|vuqG>}QtDhF~e!lK7v!UKQ_LkZ!Wj(YVx%Z9* zT9m?A17Hg4*yQnco-q~AA=mCGva-#j;0<%@fX*|uGm&ANP%uKiu*D@X_c$?{l)M#b z;9Fro9I_^$;NS=8Q7x*mie*xyihy3g!{7UV`-XotRic%#S|O{@NRJOzxTa{^|6e-& z+rCPQ0o_z_L9Bd9c1 zoZGw>eXkgJX+NmD7d3E*3qny`g)LHmW&|6&QWEOu59h5`S}qeu#sAX+*m-X+O-;Lt zMs4AGOKj!{FYuRJPv*c@C{Gh?Pt@Gd&-(Ztx}m3UP3g((7hYWumr+mF`bb7E8riM4 z-yS*5u@yayL_JvM6!f`E%JmY`{R(wZsq5_~ef<{J|8C`YUwPcMQ6)pbe?xg$kim=gr#Ch?Ul#WH0vfoOu?a>yvS_X^L#&sWC2YUk!V(O>&^qjv z=I+@IkYIT?_JN+5FIVb}n{SEERi)ppdAQkx1l)Zk_e-0Cr=Ugnx2I)2{^!p9ou+GQqNf%$VT7iw69WVHzK5_S2VW2Lp5vt#6G$Qh;^0!3}2Vx;FzD9PG z!QOgV=eROPq?tlo9@&+{#uyenYJEU*yyV#j(}{mNeuOT6z?B|sxl@$#wbG?R*W`Ua z(d|nwj8|*|D=u&1c4yx?G`Z?ul@z=UIL~T{NzU+o(NwvoY{4)%Ui+NSz@f@X>z(!? zW;o(^>q@O>QjJjiQ5`iY(cma8q93F1pOu+{rnTv84ad&{{Rhhi)VVDkoo)HW1@z5n zM4~_P0_~4eyUv%X3nkk;dX46upe_*|1x&4^kGE1#(AkXX9AnR%VwQbd?IV`^RFe;{ zsR@YlDfl8nmG%gvarGw}wHp&jNXcJ1J($FMY?BzhmMf{JmwMJq3oadkU*0$MCqcS* z54LLme`hB0aAx^sbZr9sc}5p!mv48VThLayL^Ii>mfkzMt00L#YsB$C9~Z308Vb}2 zf2((U`n_~8v#bcm+Cq!S+V>ejkBI_GkYR)z-iz}s<2=$Xy#r~3HsxcPJ`QV~tU1ly zTo-^%P$@){&U9@xp2zgBq_CCpU8x8Qvj|C%)ff~Qxk`jMcP152wH%jjGH_u`bL#q$ zVS`+)Cu^o+6`PdP`b%064RtH9<3K~0h{inA7GGRljcRV`a_OvWWjt=y9glLMt2vQ6 z5m7>1{0q95aGe7GH9&hhfX3z_Y5GD?kr!-15VyI1Q!!#2aUg7%4Njr1hn-lb%R?Yo7g?Kdqu&7nIozd=9^E ze*_gCO2~d7d3L|SKH2L1b`813w^H)L&&T7P-u?v~K?%CD(TH9Z5y+Yh0Oh*aLeUd~ z>J2$FN9=w(epjjHZ$>yKzfwV8+&jXn_xekf%IwqvsO8+#OHlB?a`#a6PRbsU>krjC zTe^Hfl>GegnL&hsHAry>jfpE8MaB(H(1CiK2;`6GHB!MfvNint`k=k17rqr;-|Sa5 znML(Mc2vZq->~x85n9Zov!5+UVYLqrrC(Th;B$vGDcz67ShFuG7v>={V~)mU?B79% z8=N=6%9)>9*FWJV7`@QzC%<)Zb_^4ue4O1(l@T4lUTL>Y*2~4*JkvSQM59BeH&7$V zg7_nf%C2&T%d%SGf4^?>p^hl^O81O8mXjVR)_58oA2cxVZ_lFzV*eu|xwSF8eS8ws z;0R)B)vM7u;CoMLO^)N&Ioo00N$g_va4#|40w>amr(mGPO&RxsflQb`)L(DP8n4~{@mVSc#=*f$G z`TglJ)fzEzdzAy0V5Pf~s-hQI03Ur+oWAPNsey`?E# z&<7kNy;YOUe)|+f9uzx?&aJ2%^7Sir z;ba~8LF&DasE$P3M=+yp5gvv->aCdDUg6Lh)O6B|=46tIm1k_Q@Au~q>!xKHJ_26t z91OJL4dCv?K17OzfZ)&jzZ^HNK07e* zb1CDF9{CSIeW`c^!P>tV1U&F(YhaqS(P5rM`>R*DnTP+pS5A0qa&Vk14g7S;u#x3rCtC~l= zuTRdj+%}$}Y+#NtnBLu&`mVUf$D?3&s7d*de8JL7;#6dL?W(%?RqFP_bZty;iE+Xa z?1$mY_u|_AYngzvtyM;JyA$ApBaXNB`o@9gBHbE2wEbTzsjU5Fd2EF`p`zz}d;)5q|V%JjCOi(BSUAB5t9P^eZcsfkE}>-;;*)MK*x*4Z)$ z{l2K6i~EfJcF5{bgh+pROTWTM6lGy}s0EXq1h%n&{D#lRoG3UTTw`}^`T;A%39Cp9L( z#fcteIo!0-;a>q7yT0T7B(97vVlL0lY!ITB2*`3v{mMxI2Vpny&?^HR=~ADfNHB>G zduh}0%AbPQ^k63Z&r9#eXm=|XfeSJMfJswH+`GpACWlPe-^T3dF%Zw^?`W6jG}t>f z?wqO~FX;PaNpvhsI@`Ay$TiL;z1Fk`4~MSoZUwy~)CxS%d`u;;6qw$a7|}bahaw#W zVPeXsu%*$6rxR#0Za?8D5G&SHPUbswf)SLE3mi&(nLN+%1yN+qUtCoiR&#PRhv;bQ zrqu6Em!>&g38+t(2wB(e=lU)NAUnur}g^}BeL-Q?3-}?S;5t)X4Tpknh z?TjKWnBlw`vWbFeQQr{wLczlUQ%T07+US0|(=OCOh7FVPOrjT(|TV1ip(E>1-Lf>Z8$ zSu?~<`7J)U7A*XHXCI{D=5~o06&00NTY(*IzJsgR?0$?6%I&4Nm5qPTTS0Bc@5*`WN z`7BPO=7fR&1S$N#IoOXGOP;3sm)Cci_fB`^ONTz5+3kHzvfE?^Vj1EdJND-WUCF;T zt$F`J?2DKk|H#VeG1JNXZpIxoRiPo0aZ^%9C7Q9&3{s@h0FOW^_v`m3@5)oW;s*zf zszz4PM8x{oJ`Y`Vis;lFeI3EQ6Z)scG5k-9W9?T4@}r}PjITmZHRQ_rP< z)d~YU<@Nw$z#hH;9pNfYnzO8tB4D>nXqU&PUI?#yRu++;sag2 zW#7_Yt8hC5plqu-Fz=P28-#z<_(J=8xfnXP8H1?QGhIblFIyuc+*PkFNeV6jzaJ8B zZ-Z0dK90h-Svgnkv)(K!sjGIdD1xTNCZC)R{|NyBtug~%o)XcW)dl2rZ3Inq<4M!2E|+Rh`EcR0#axqh%Wc3HH3+J^dn&5HTO6>u&Q$ z>pT}yi7K-vMO^P!Py!Qwy&;c>DX}5OnFcTy5IXu`$E!Ab1i}4K_^z|+`_DMkGWbkM z3Es%5wfqZ7#KOyjPt390L5H69@ z*YUW-_H>3GuMJhYxDpat(BJB};w-o!>hF#Nn+}-2QOq`Rn4WS%E4M#SJG>sBhz|?? zg2iKTTPcHeX&)UN|F}n0 z6&1Cp$Gou6mqj%hik-OB50bWv&8&~&ug*@w5pAwR9qiBgL_Q~m4hcFEoDrfP>h0W8 z^IyXUn&4%K?H%Cs|e z@`X?p4{6}db@iAw z@FufMla$?Xz7`>2{-SA-+jr)_o3iAr&X`yTgGfgMfKaWaqbJIGXc<~dI66T~X;zs0 zuRB3#3zZ$X39EKStV5^&X2^$0sE=9nJg(~QkGf9rH^-Kv=p-^s_Mexe+#S~&Ux|se zpw@X8MNrqi31lF?d3zIf*KU65@F%eaWw`sLq?i6+w=vm=hwlvv5feDK_~i8UX&v(S zZf0Uw3Y=f*x_y+!2JM#fHxZ@K(H@Zm7fvp}P&>%edXg?2U*v znnYQx#o;)Ujfitgz4t^bo)@j9RYf8Tnp*DqJ@bOJ2F4xL*-%iNka4aj?_Ov*s8M7)iRl z!9(sN!0*Y;SrE+h{r!g!Ky#85pxi5Z+Js!Vo<1JHrFe;b)Z6{0~K@3KGrNmI1Gh@q{~i-Nk}?a=R; zvRl$OHTx8IY}wxeb51GAwdxZKzb53R2cyp=RB8UN;rG&N8p_;U8VRk>uLWi!`{b zfc*mi$?=Uh~tUj_LlnVdx zsJ8>u**mL{l%?G!9c};_Ay-B%7>-2o)h3WjylSEsB4r}A*E=d_cmQ%Q=ae!8&6}K& z2cB6Yfi^Kui9b-MvG=^On%kPINy4-JpCc+iV1*gsdYDqJ-AjLD&{qfUR;dD8-Y%! z+lHm#XH(y;PLS3ow$BVG9|l)X!aCs_Cq@mB7u4h2yl(4HR0g4hMLjZ=BEp2?y~`DE zp6caQ(Y58yA93%uiB`6iel|bF>0-)z`_B4=A7bn%vBYNh9oH*V!;_59+bmJ|)GxIR+TjmF(Q6X9nS<;1-}#f1-zMh}ch#JJ6iqs- zy=@I+{o>na_-v0Pg9WfdM$4<8>_!OPSM?edWG0!kqCm=>`jjit4rJqumX-H_umGsP z_-A5*u;5)eJRsKQzKZ4l%$wJ=86DiP$jqSU<3S<$^~R#p(0OQhWdn#LluMbME`2dVr zKa*AlAA+#Q1lkVvZE!yjSy@v$%)i0dpEPk_q}%HJ7c|A~P>9aHJ-ke7iW)xVQ+cqg zDLk0N)-39+R0mq}y&hMhgwIUVtR>f~i)!er$p~Zrc=EJF#9xJnkMvuK$J^QToL|!8 z;C=MH2=tfqgdvcZpHm3je&B-%++g@G9RXz82cJ<QTZH%aE_$BHU75X^uRDcyIcl}6w2H*HO}*yWM>p_x-^g%Jg>c1%s;y#y&bZg& zJvk#c*9(lT&kKw$7b9KIrZ4RX(6$sGowB>3ET>>ZKUHfZzH#hH5k@8Zm~z_zvI!o5 zYw5~wfm3M#*?6tTVTPjT8L)$c99KMho;CgC*`qux=Xk=4;ym}(o5b6%I%#KxKloSd z${HX4TCeH=sSl4`7mvr<9XnC@zyeUfgPN3EQb0A`YNb$} z#Jp~gU9EVL_9gfkdnZ(iB&FapkTOu&4Krcw7zS=e1V932$YW1TY7_lUbscp?*wN)n zS6hdQ{cb&Uj*{-Yfi{8)WaWk`}LEv>kNe17KIkz-1 zy4+=SZuL@-`pKCT8p+WGYGqiMZmx5t(|MbS^igR&ov4y(TA^dPAKU(QN(@2Id)XBq zAvM>1%IHG7h{fFexP7n-eVn~P>g@X^X?^IOaf#$%N4o!~rk?T3J-(oV45c3!gI90O zpP#6IR*u#v&HZ}4YStahHbsIn!GsfeTQ0vC^R#_(ns80lw-7!u)bkc!dj_7cmBdHg zEKnN5Z?k}N#0jNq(pLAgY{MX7j3^XQhT0&a<9Omp^}F~`?--#=bDSRK1sJa zS=KDdCsC;K2&Qv36r9*5b#>aZP200(0{ zt^FO$`l|PpL3BlE;M{k@M>48s;SEIGHW-W;vW6)2Bze&=&E_yyLK^K?N7Dl4)I1Gn z?^C`7x}!t*j*mxC0fXYb13oC2zS=-Jh8CfK*WY)MrO%KBi%<#UFg?JuSz;C`YDDm# z2P3&UUv83B#2oI<9zxe*jIs=;%W9n;UvJ8fAo}>{ge0E>S90|5<>nOKkAVLWUQnZR zbydy3FzgYpJEv?B>9uo0S4JJb!(=ZX`9w#=B9EZFMSq2P{{14#2Tc>g`Qs2aM`W;f z9;WgkPz|8kK$HMRgtjeqm>~w>_0KYvF+M#9WTS;z-)>&ta`dDOC>TEs&n2ZFxM&vb zi=ms(TQHc3g8!WxEbvqG)+6o)vb^J}#0*oEf_DQRBxaZpTjf!Z-UO z76n^nq<{)LA!Dd`sMI3hGGrs8MUA@O7u%C2p4#p?Q2m6-Z?$Pqa{G(DC5HdNl8!) zevzth{fwa#=U2mVX{N~#0g?DPl*?^{3R zJk(p23S4Z1Bg4k^H+td90c1KEVOXyoT3@op4Nrlr@)g*W*DpSkfxG=Dts8E@vWcF> z0-<=gh{DVOmkH@-q;=Ny$-9`J*%Ia0V0|{WY-RmeSU(|>6Ph_YRTnF&V~OPt9#L=hLItZS-UVS^LpGN&MY-t)@QqoP)OOhgz5xaqzVl z^5^6T>w3K+ngs;TUHS2l*C+pA*30}O`0sZ69*?6YQCkB*!qmK*3_v?9eEx3RX>s#(# zT*K=|+o*jI1}+}bR*$1$IF;!bSfp_4QO}yruZ>|s3uV1E9l94d)zX5yb(m-E9!o!k zRb{XYD<^Tvnw=gHWo(V7x4&J1Z+p%iU5Gz^SLPT9>64?Yv7@Jk3**XjX_wE=HBTKR`AqkELZFTo|im z(o`+Os3Y|CQ)T1uEh+C0tI42IG3GC!)oMEraA@kSFuJnwTTPX$sghDjz ziZZn|ndML^y-k*@-&H3bl_DeX-T$YTFdt5nN{R=H#vi?GW}eX*3E=UsONTs;0YOgJ z!?0LdwQXj`O{hCUqL)H-G2|(GCrEmZHA;<^WEA68zscHvfeOkcqLeIrIw_l>=#x#f zzws=b2C0gEn1byiCC%uHr`3PqdW4chQS~;Ok*q}o2d$`b~oF zo@qIg9u7#rH?*#(UOfl6qM5e)<6Gb%4hA zuQe)>Hc=|~?P6iZs;G%cNpF+AOu9>WXxoQueKwwC=Le&JEjR;e@O;TEuR$0yg)DNr z-<-c^D@x116nLi&Lpj0f>}{(qy(uNU%@fDl#?c@jNvLtKS8o>b{Mf2i6Ujoj9hp_? zzgm%XppFv>V0oM+gp^*Lzc2g?Lig+T*B6T2@R{$f5ymEfccb|b@h3(aBdoY}yZ!h4 zQ2_=^$xll1n3s)hZQ=fW*4wU` z*U#dk36g#H{Qjz!YGlYNf$wME>!8&f@z#^O)ZqFW(%7u%SP;T$XMYQ!5CRZCfcYs8 z*Z|OSFir7ct8^w>-^%v6nON{r|Os$fFK$6<4&X> zEbMB}rB)eY^cYA?zYjyTj>f@-WJI!|LajsOg7V^k{z z*3S*Ooa~4v|wP8rVRuv2BYiENCBSi>UPxXfs|?zQ%}X` zTH57I7$6!<BDjn)T3=x*_ zm{-1ZO4**Ml73D*ckgy+%CR7!cX>HhJ^!_DwAT=@qR5})?f;l^&2J+BafuIh@$sa5 zh;@*D#xqP|aR4DL2@|44Z?3NR!lR;W&8@8VXDW?4t%AiQ zMhd7g7@x|$t*)yj1aA+g?FVoFG=VL*(DK5A> z_xS+4(oy}5?fq`sl1XV9FYfcE)(f+Lw{9$?fm%AR@}qY&32;eh{Lj^jVWnCr>IT6! z5PET56s^S3+TPxC0sECUdlz)Q7EhNvEFzj&x1&X&LZ6$93XK~^W@fwya;|cw<;%UP z64f&i-?1NGHJSTA1pQ!;6|btUR?srztQu+$#5#m6HJPbFeDD6a9?o~0j|()_Rhx}m zL`6pOWr%v55MW_pMSf=8S=>7V9xh6LG33Fo{9}N!4~?lBX_h}^$s|Bfy5Cvu`itq{ z|7069L>I+!svN@SB>ik8CioVUv9n+C#MhyyBmT+fsYy3)0 z!>ZkE6qW2&wpaoFaxv&irNlPpJ9Q`*HT&0}pLoHiXy6++i|O6zNUQjN3W2rdoMAUR zEcIKbC18Lga{2A)Iv$SamniwdGj~ zFz>NO!}{?sn+6bJuUTkT8+573O~i1zR9{Lez@kVsPt|g!{H|EH-nPPA`PaO-Az9^N zm2vN)n3!06bZAgeT)ccxi0M z4;_KK;>vAQRbwoEJ8nMp0WNN~nktT$tjf#Fle1q^BBB+qk&~0-sjI6~I+`p}GfxwC zSw;fp=7TnS7{4fAy}N`$bgNB=x&{)s5`@6WW?mEYiQ9NKjc{siL&?P7zkiF0iY{(k zLctZ%>opb=OlQESkaDXDo3HmorWX|z$(ScOP?qt=-TxD@KM>s#{EXNPu#*S>rD(k*t& zW_d&FkjjSEa++|#tpmiN8)jOohxrZ?&cZM+{_6U?w>ZK#ZLX)Q>rIZ)#Lu?`$u;

      DUJx13NuF$NJ$R z^;oe+$@`#OA=9%hOfb$r#OS~Wp7WwNI|dB@{Q1+uy>DUR&!6|~fbw?W)9U}j)>lVG z`E}tE0}LSD-Q6M~Akqp*cQ+ypO2?4Wr8J7PbcY}?v~-EIboY=03~*n5-|zeGT6f() zSk6M$yyrdV?7g4o+57Bse0jL=wF<}vzVRd!78X_nmkg~oa^ZI^6+T&SaF}UfJmFQV zZv3!2$-!sZTHSZ2>5qW@YMO}d0?n)>rKj74kP>!^z8cPdmB39P=|@RHF`)5X-+$yO z8#s2U#|`X87k!fULGGI?@@nnLY6RWV^Y>e^s3^AL8fvlK9|k_LG)zo0u9j7`x1=p= zC9S#yrmP17R6w2hkqZ3DOXM_r{}eHj=D1iA#;L9j7e8uS8d0MYU(rGBlcCa2%8!1# z%Jc(!C`aS7u9`5=Y>X4?{?N3tpu!EGmO2b^c|376VlNI&2w$}hykeTkGScU8nr^Hx z)37-EXtN}Zcl>-!$6K>ytZ!7Z{ry$oRng78??TVivl$upYm)@Yb0A}Y_p?J_N9kXI z{KraGb-seUlUdiWW0O zq*aH5F2*qL3DbM8l8p*>TYb(-KYLZ}z>L%vFa!isYhwg}ENq>pATFJx;}zoiOjEyr z_fxIw)zM$0`>t^8N=pVY9r!|<-&Oza@9!e?>9>bX%S-jOwV#sM_(Nuup4mR!-^p$d zXK3NgumiU)&#MeBvVh|$hBn<0>Vr>5?QiKTlgwSycun&9f5Owu0%5F3DjA*RR$?~y zpJ=Dh+v4*%m?*}6PJ-fSXlT}<@U<8WaLVD>S8+X#s@R>@?07(U(~P8hEQ}5Km*j-L z{I#oP+{;1=&`ujRADZx7Dd`m#eY;45U#!{Pn@^khsk3D`Tt@^pnogbw%i0Xzr*K?m zpDgU{>b&x~$S8WH3s=4q7rHp0Aw={9BHk{4xwYIY$7qgwe!aemb9Fqg+a#U8C2e&1 z^+iU5ld)s@#N6kIgGy70L)Sfcr+rnvY0A-r*Gb&9vIuYxqb#=`2+Hi@y>45t{+Gzu zdb^ENfCr$PId)WBqSaLp7G3AxPhF1(&CF1erKP2}>P=CK&fgy`Hk(dNOr!$y8yIF# z^R7&{qEvCN3M}ms(-PT;0SY7dk$F5<_q`NspyNc>7fV4T6VStLNDym}eP3$GGA_ZU zmR;|IfY)5?&s6c82z5UZbYz+9G^?+OEIgP$xSU&By64G89h<2#J7%#xw4LGQLdd5Z z(+TDkrk7Al@n_zY8#Prj&MS%LnDl7z@l|<;K$EY<-){|5m0AT}{q^$r{rh)ZG2gu9 zkNhGVY|CpYD?tQL`CEapZlI!OUcIB^WvHDj%GY=xsrCKzbfxzVaQ=9C>?QRie7qg% zpclS6jx4-YGOXxLN85#Nx75-l>>KXs&jP*ICv64`M$@mhRsL|$EwNaB{e>+@KDn7~**XTsK^+n9kt$ikj|a!3@JtC?*jrD33;_5jarb&Gagc zvalStoC{utWvJss&F?2dS(k!#zEY7$gXldt5&>Cqh*JozpJEi`m_dNVpc&um2Dk6DM$UcJ-~)Nx$s}rh(WKpw;wp`SsA#&qRiQJZSJK z2%PVJMOWO4UG30us5WmOtEd7sBy(+^ZG8+7x)%K$8IR1$I{t-y!uvs21|>WkAUVpY znIqS2c5YOkb0Dm9xckXA?AgH1t80{1CC9)^d2UB$+n<|nW6J|R2-upsmDpYzG7-YyOG8p~dkIQg#xA;H4yT&_~SVp57> zPyqn}1#1^6BbkgMu#X^regm&f^(UR+h=^D2x(gU#)2SeZT_M6-)3Jd|X&SgPMGcL( zXYA-Hn@|$+v_O==+76o1<|uv2N7{ z`R7=u^k7dZ@o%(VX%))>8i(-@&xSGYHPMd`j@wU`Y6A_JP+GnFY51)GQI2S~kZWVS zNhF{nF$wu4qLo?QW9j8Xy4Lm8^W_Gnm}gg<*#wP^mzY3T1nyAUm#)vAK27B@IJ;_} zrfJ!_dD&XDKmPr)B@B9Pu>DvrjF|g$8Gz1-*yc^X-G2Mzs2eL17_vNE87;c{Bw^Aa z0*iRn=Epf>34J=fuEp4HG66$$=~yAJR0VI}@cuigIR_XFR>Y(b>m3rFJb7kc74z$Y z{9bANq5c*QTTdBMKmrwO1tV8CK4U(KF>?%R@B3ciVQ=;26Bwc>a$ZrE`dChe zjz^0?T0J)MU;3fJAp9r9Wdj*8!1isiXr^;H@OI?$7X6Rd@M9SPt!2w!@ic$H(LY;S z+8Oqv4zSv7Fd*;fdK~R<+Hz9yo}qV}Ikj@0kUwGz{l`_Vm;{(`8DD~FD{(&_LdBbk z&1uWTLQYBP(*V*5hPe8cZm~y?`COBeI#Gcp(>06>Pq_Ip1F!oFLb(Zo^a@l0MZTVY zKKTe8FSV~y)7|!U^-OWoFt|Eymj20SRr^Y!Kag+l?s?{9@Uwhv%R||LfL>&9eqx zBi>v?oa4x-&(NO+RT^iaDwfac8?VEm5GP{eBDJIsIwnl*}h{XdwxrA!Dl~;jyo5E(fKB zhK7funQQQ{JX1g_n&K)ul(n`lsC{{p!Fh;cSZ{|650_&C8RJZR{*!=}{Pl$&X&`(R z0}KYM&#Ri-GMaDYx%*S9UF5(Go19hVKAwz-EF;N?Zgvx6*t&BRQjp#w9byB{Q z?dC-+$>k`wt}^f*WK~DXqSY(8Ev?Pl3LLEJw8A`%#oR$??SW3g=db8D2f( z@9xq+rh8~#_)6&AbvXdw4Hx*S%U`oOM zsjN+QugM@5R&@k2K0G)eJh>(g*yty~3z^?3@k5>23Cn0x6P@?4;S%$Nbg^2%C6wkGc zwk)?0Q6BEygST#pP9=?7-gOjfP`#Cm{L#Px^X}%t@1v{ANAr^QV!=-IR?wW;!7@Pj z)IpZI;IB$VqSE68j3}T#Z44dmyOV{{OG`@x;J8?hZd_!oXwJm`%xmTBulh9YjJ6pD zgPZP{$WK~h#bTe%Xj`D()9fA}9|uWw7i$(Oxh(k|x8V=&Y4ME8)r0}`xX^L?ksT8w zN0lC;zFBOvg zLO6@cZbz3{kQ6V`{bYdkfb@K1fSsw^mz#@y5lUf4a^!6XQ0~Mn>B)7$6b5pxyD`cH zz-N3g?k5-5T8UBPBG7&&XXbq?C$!a~G9-#)qMh@;7hAWITiRW?N_$weJoR=a2GTee zi(I@3F7x#zGUnzv`J9M9-y2pP6ny-%f7o+L0{trLe^Ngl%LQOm8Nh<`{(O5Y!i@$T zz#34*lsTKP?B>6nX~i54K0SG0##f1d{R2yHg^FK5K;@;!A~wv?`{Rd?R8Oa1?VUnjkas$sZq5m?-7O;FIhVEw+)mLQFsZC(S%LzKWiyZ-|88eP$iU3{@(1< zW-;YnV(v1dOz7*tI*%e2G{O2?q>_a{*hsX>*C1{8RXR=i^CsHi_$#`A4>4QAxc6Ja ztd&|F$^&g2ye)62@dQKWp1CN7LJOFDqq|O4yHieF_NOb9z_DhO?1v0sxiyxJK{k-h zFrlb+IMiE}gNKU!rw1T)4tgdlMw<~n>pJ-R(L1VzE@aRFM9xu`TpNpNXW5rasLObu z*)>$24Nadb8D1(p(66shk5`^6OV)^?{WHjIMPUBc1obX%E^5#RY(5DGtEL$IViX;{ zc|yiurz$Wh#_=;F=$XwVAvekP_ho@P+7oPCn=L+?2wWOXTanMCF{C`2GKRzB+P3SO zMSPul+(_u@HQz8H^86JoyaL#n=E8?@#TaqQR_d+9L@yMaijn9@*0e?tEO*6pHur=b zMWOTR5dUnB85szXH*3xt^Ne`ol`0|0H*??JTa$hX6F7%-R@LoALj(~c3d!YO6J%a+ zL%pcl4-LDWm3>n_!ns$J{)b*&XPw!OY^-Y8{zTu*&>Ckf;91|#7ymio8%&rFY&^oc zKdtIK>_9uZuj1?blx1n7F1g_)DYEAjaN3)eN(9u+# zk@&XJSm`XguQHlSw?n`XO!{@3{ooHJ{3vflhRy5q9nFWQ11hl~6YtMPmLU%&1i^Zg zw#*+(NXccqN!V?73E_o8>NUb3%Ta*udi908*07_&=k7Aosj{qbC6GCwH+1j>^7{gK zv=Vj+>J^`UIDu zd7uM;JrpN^-}QP-idr*B3*%Y!#cIq;B_5*MMsxmRFxgS)&>Qvy4rqgkQ-acP5h3y! zn<_1nl0-W?adAP-cHK$X2$lytqSmA|QUfXV%PMfl09~{>f3P_rkZ_}PDNfdjsahu4 z^>Cgl*1&^(na*;=x~Ywg-kTr`gtx}`kD$oL71|10z{{cx7gPVy(AO$}UAoo=Z52D@ z%)vwy=Gn{oHtgb)UG*6oY3LiID*bJISQOZOiPqa7#G8=cjsma-;@;f0m6L1HcWOY7 zlO3&@jh{R1DrKD>ea}kNK9ip8sM2fij2pP&y)-QHKg&lrPlvcLVSt@@zou#51vVb+ zoCxfY=eaxnTO9CiLIGwzB7FVa*Y4ar_fNPWp<0z;^fu3eOeB5K+B6P3WcN#fy#bYc z*OJw#$z}XQQx4p^e*AovAxdOkR{{$&b++EV418LQRdbw>5>Z@5-!%31Kj8H*J<4~R z!DPj~@m$&B9ptFMq{4Br&X2Xh1HY5#E5%Oqgnqx_-V03|xLt=2x>)o8XIN-yX{!Vl z1S5}Lnd^8iw+HC3*OBGUc9&;BH@-#%4bnZgC6%vq6TB+`p^%g z9}w?PsdP{j2P0XAK(&$d{9Lr~UMZ3=dC@m1zh)lH!yfBqU$EhT`6scZQ%nuMF;k2HXlGuD8DpUiY(k0XRrW&G_{B=uuAj!lETJpQ*ny zhoA@MQgj44+fBQz@3p1IQ>l>@mGO^gjZOuzg{Ab*_s=k5*f^ai+@q6jtfYAhP0*wbYfJEv1@G?ntDv0Q zc{0vGNm>C0vbPwxL#wZ*IF9us&5^FSn7Z==WkfqMeHJDsw{GWYORC_5!)Uw`DG8W2+xQ2?Zo?~!z|uq zKD+5%LknbdJYb=Trb|$nAhis&J3L`Uk2Rc1ZPzQ}W;ShMSx~i#rKbN+wU$SeBcwtM zzf8=z%ZPt(Sx2mYfWlJsdLWsipAm8RLWy}B$<4CHX0V;eJGK)w5HF68dT*nyTU}ZK z>gx4PzR*cNA(PHn2Rc!3MN$k~dolFsP_ObC;yoj*^S}%vl!%Rt>=!;G>uh<-lpI7a zZBS!Q`IX9AT&lggGy@8Hf=T^pn@8F}LL_-S6^UJ1Go;W?I&WC1F!ZU>gsm)Q;KV#C zKA7`(jFQfVk|>fjQaJ3{ib$DiED9TCa*y4rGFq z^xwcP4j0HyVn7{yLRe_`np;)rZm|YugN%NbNuu+3gGah-XKB+?)tU2??Gwuz``olX z9cC?@LH@Jv2N5jbH%PO@f{-?WGrdZ_45)Rmtmm_IMdzqX3f2vw_-*GWH*aD(46Bx; zcQ2x_Jfo{N*BpNCrMdc&RA+YP9Lib^_p=@E+&+BBb#$x6CU7|?r~79Q?1ZDBn|?6l zdp67i29!IfJarB&2T-+;AeZP*C*2_06+nNub&t(~0Dh9K6hahMxB&7ozZ% z4Z{6w5vr`|Ra&(Moa}X1f(NlcWm8^mDJ|eq7oB7YnFWR(IV|hXvz=4SZnCo6pnpe~ zOsV)T%!v4U9=8V6Z4G@Ro*+G`7t{Xt{9y&D|4?Z|DIH%(WmCG30eZ~YYs{&&!Ud6j z7qV5ofYXLv=!qUTeni^E_X&v&@z}I<3{3+1KLP@0f|xHC{WScBF}2EE22KC+FFx>`{D&!(-H_eXkh4RV-@g3~ZcFZ2Y~l`^$);7b)_ItaRX=Lm|HqR)7icgH%m;_rPwna5$yc~2T8a${5_0ja6} zN)gzp@zpe9$0N#=uB4yxUB3O>&-+n%TcK-YR(T@LnSbwpmy>rdE5Pri)Q+0Gndrm@ z8P#sKU2aZ;M(I#GCms+R!z+kvxy1w^{$Q0OvA$x*rd}CyL!*twfG0fqngVmQDLtS> z?8cB}CKYgc>26$3+9qOzL$j})(Fdl}GlPx8pkIG-IrA8^ux%yz0IGhK8QOksTLJ3+ zGj-5|hg9Gf%Bv&x56urRFGo?iqsy?nWslol>){i~b%umQ&RU6F68c>=^*YC9nk&AE zWd-ubgnq|pe#g<47`@TNNw}PC_uG!-we;2Df9E`p&Wy>t-a7jn+hp8b4tsS?QHSu6 z9=V^HKZP}un&Ml0=}!-Q(RA`DrO?+i+yUJ-^bUipcg>+3PE}tHKi6Z5$xHEw)A2Et zfa!JewH9#RTWZqcQyHtr_U zw`}3do3V&HF-(l{=J(q|#yB8Cw$t01d0A*&Zl+9c@f+fuaVyNWfEvpU#|+2H6G$^5 zWL5d27~C)3>?X+jp7677NWT-(z}em^4JJ_P5`Zf?Oh`bXh^X*QJ7w|jmc!%8$&|8z zC~DyMz4+)59KugZ96I3)LbGTc|D09eZG0!G`BE+j+#eql0zprr`4R0$>ttOZezi;$ zdCwCbF5f8DVu*foBWCkSB}VLIDp}3mRZlmsu~B#TFVo3Y8$B1-F_+zbZt>v+Oiqdx zGZD^}P}X&rUchtjY+82I%Kf?`G)w&K2)@}xBr2}aYbJq_@4LQEUbmls)g+DUK62Sk zDZ3~Uy&iAEE;c~uu>F0BYpWvj&&!|Dc<7BhUHb@5>?mjmnB#t*ljnYL=(J{{mwnN4 zqq;R#dCJZFoDP1wClmI8SFY)_-6UjZ2c6z-KUnPmHP)Q8K_zzd^LD?P#Ik0zww0 zO#!}1Ha{AKWXwqm7+UqWIEHHzLgr5!EPNeT;;*^ig?ph%)%)VMrp`7v=w%CmAdE_g zhlM7Wk!q74WovgpE;^$l5VP;-dHp)F#`BcBTI{@fs}ATqLAkr>s-L<}04C9Oj4pop zH?hF$86ekpMI-j1qe0q_Ec@4U1$x;$X)XNo7=etUatIx~#|#nDiEPhQER>T9(UP7Z zlQ%y{>TVba@{7_3ymh zxdL?gIwocemrn1TbelIGe*61sFFR|xq#^xh^@+cGbjy*#>m}i{g*EK;@1$+EKJnB! zOM87J4J}N4q{|3TMGbwQ(FqOv7FD4bQffh*>ef^u&zi?R5-#%%%-dKCcIZ ziE#1~P3`Q8UqrT3(BDgvU@8rCmNMSgYCzdK~Eqr1Ib&2))yNuwt54zN zR8$TqX6$w$g^EwSC7^G6&4~S1D?g%m^9`seEC2o_JU)q@7e5se8v6A_^+~H1BR@Ys z@{36gM6YmXv^>p`usWTHvoX28i@x@sG+hSgIo}4@p^2LqbGbGtY?=mvO=$xb`c0ct+hDjg5 z6!C*KQJC+QJ_tUcep-H!lLTB#&3CSsHixuTS0ZU_C)0)Jhq_7!RkS>fZ4@`At4q|NM-TrDT?$ zRcYjO>vPwkBZ{cw)rqOc&t|hS55XpDNm@}2@19&%EzWaicxXx6+N-!mSp|}1Q@HE| zkwkWnna|&pPgG=4&`(wzp33Z*A+POmNbxuvwKHbp2H-tJY^wVCXz0<*>`OTvsClZf zq8d<95*-4_#4%~U{lr+>#eND*Q+M_Sv((1*X&#*`P>itQ7Ri_pMFN2$EnrkKU%5Bp zF(y!`CQ`w!fGip*P@z>Bmx{Ndao1WqkQ0t82NSU%(hAARjPb%QH~HC!e3SJ6Ur)Hw zhmoP_oG1pyIt9};VlXEOTD}MzT96FFFOOT}qs5-+O*))!0BUVP7c8$4;llfQ{loLO zEBX)jw=R61j^*$eGiT|^wwVU|KZ7K18CU{T(bo8)kw$X!W{vPT11Ew8Ru*&YW#k=l zvDJMB7>e)8t@ju}@d{$3MtXd*Ka7TBDtghh+4 z@nz36efIsO$2Vm!MM-&>>J8@$${Ie~9=mt|sQC>diXEnpAFyxrfzMDu zPEL+o+PWDV{+bP_mb>9;$Bo*s4^ffBA@=M{dtUMsu!*jyZSZe0xGtGgUNll z``{NbEk=~QXlRW_QVXuo*YH!Ffsp~-hvmp6jQBWZ2#YJ>M(tE8Dn;Y{ zKSY13ny|JX>%Ea13zT=;Od!xh*xZHIvB=#$*<~W`PIVMoD)-Z7)-M zK|OMHY&k4h@SS33Z+Dx=q~`KXf}~k)o8CK){;`MzM*CjMoHx-%)i@G*TFPaH1I)dL zW`^5QT=z;25>vbciOk5^aIOJ#n{m=8=+mH4oit!-Sya~e^u*O#?$|%WV+wRD3^#$> z2*tHxGid~EhpEoX6|%yBq9+k4Z1igRNF<}I*i+pn78VxhK&|P8+^Y9ntxazEVJQFF zF`1b^4Bg3HAC_T;sOY!M^EV4|q?>(?LnkRg-IpEpD|ES<#`_6bm;ajn0tOl(#I1xn zH&6Z}i}vtMj1C6p&3!xj+yyy{am?|<JbQO+-X4!|2CEcMD|W=sB2kzh$~8Yk~oKnmJv%OkY_p z9=u}-L^n&wq>l_Vx@?`?U#f%!AzF<`o@1w(kUzIjDEWhgRR`rU+JTKNbD_q@s?@5Q zU@pA1vFcXt_dl8<*jHq_y*!wBdvZtO(D*SL`)79OlHGShUd8WK5p+aNI6e{yKy)xB zq5NF%xF0w^O~q@2`|IFbDVW%H#QEoc{`~nVy;imklws>$E|A#->ucO3Q!QYC&@VB3 zS1=BP2Nvj+8j<|n-cJl7hnu~9yFC>}#Ma)m?s>GhiNikCH5ulj69onC@vIBwlcp}OsCX%j(nVgK)h|1?eCkOUazn^`f6C_n-px%hyoPf9 z%WMs2F+65y1+9TqyLDt=bKv84!n1cz#w@I{6wsF=Zd~-SNdDQ=mW1>$J*9mGU;#Qb z>z*>v$HV=+mm68Xwp{qM-h69o;-ZAtyO~{QOEiud5itgkJ;hB7)@vHJNJWH5?;8bjO>&nZGrlnEz>#m6)Zs_vS0jhj*vL zXnZgvLP*(?Df9i{!AyeKRuEDYlv=8Yw}(w?&Befz`92z&mVEFA-~dTZ{{F4g6Zx-b z7#MOGuv*f|apV>^04B>~&dhK0SZ9e!+pcR@67&f$1s@P&P?SdoV}pLI@!@(OY|PEr^67uX z^iUq+Q{MJ*grB9Q!h5XyKECTC*AZ{?OL&9=>b ze^?RlN~<(BvY1?=p?WB9_WIR#^Vb(Ami(p1k%MD$&vNMmU=^&@AaurlC6u(N5WJ3`F`IKfERbK>Kb?G>7x?#(>cE}H}vcQ~= za0?l5V!$fv#sDu7Txe^fAf*lSTB@H=!9ALr2Vp!(b&iFYFKox8R^fC$Ktvoujw|-b z_DRXe1f9sOY?-z4Cw*vwhstE>@1reyt8dceogtORlkjD?^M58+0!wtnc(j|xA?GD#SXsVZJQP3~uMXJ_v zz!Xvhe|HXN0w%)s%MN?WW>+FoO$5nQIs0?@lM z)xW+_tKL7ScTNk{ExP>`WsTdawC~hseseW8L-uzn+tB6wL@w{V?T$%r(FEB(pg2ei z>4_wGYiY%lZ*0hQ_s@(u1Z|qbTpYa6z4n$wRww6(QkyDGs^=PEYA>|}V}@zlFkX}_ zkF%lmT4?kv*H2li;OG0bC&UPd2nY?8Z?2^#C&4tfM~1*g)<51Im&lG}V&tJwd=Kw2 zQ+3mNOHH%_7^<!`FF@t&+y@YIeKfJnPSXMhB7@+dQl|S$l-wrpr^eo=KJ>Sx!QEA)JvUfaFJb}TBL2GvE_$fd ziE-d;`qPf?@+3PzbInidQpoHd_whF%Hk5-hYIt@h{%)Zl;&BiEvY6?Fj4= zcE^5iAMM2&1zmH?uOkixd~$S+DyO&-Aw_j#5m2AxEq02v{qP+A9bJ~;$Fr0Et! zr;bqJ^65gNrIMDX0$)C7p?|GKk0KYOj6#jTNlk`xeTnX7X&t-0!DWPmvY+ZT#z?hs z@docjL)S))smGQ}Z?OEx?dzS^DVvC1U3vpX<8bPSiLC@r{hE?{zcCT8E>gu9yVUCM z?0&t7sds|Zm|72~^4%}pJ-MgxBO@lZ^Y#^qy1a0p*r%J7TzXk;68({NOhA?uSg{QA z@2bxMpU3wqr-Taj7^`VT#FV{JsQpif1Npn?6xXUw%C+}ib3{WopEm}v4J&8+KS|Kw zM9XAV2GE`y*!4sty~ix7d}=!`ar@u+*bxqondpQi>gFQR(s-+O*vE<{L5*e}OqJEf za&jKV1!_`|W$Bh(+G&52yzn?yU_R_w=OlvU=QDb2t5Qs?P27n$U}2pKb!<2FFLv!| zsl1)p0FDYy0k0Kf)r^XALN`Pvk%qF@( z1oTmkp{$d!^0ea|ln0#JrlDG47ETmYsj0wSgaKF5Tghq^*r1`Mg!KbJ=tK8JW|;}M zbN0ftk0)Ho=Kx4WhX69}Jvu<>3WWfQtz=$ekU@~x2=|M*?m4jdwBpH;JUvdPA4&mo z?u?>Givg}?{9d`4_~pRykj>?#lcrXcXoj(y27%U?1|+tn#ZW_EoAvldbkB0@qOlN! z@3zw*BSS0zBkspc#Z^vITtFsdd}@+2-uFzYDinG<4lMuOPqYu-{*-2&eneZiq!jF5PbiQd-#-+Hl9M^5ASZx4EO-I9DV<(+{ur-i{MC!%0rh<4 z@znrdkDT_9%qo!RJ1ihPzRp0xP}EaIq)bx&4~M?iLc9PCtiI z5^&vDB36wOikp)9u+tEi9fN(W2`@;|97H{(+%-c6E-*BV%AF3C&4@lKdn7Qxnp!}+ z{ywZ7M3Cn{PJl!IN^n+{mZ#2HJaUlk3@M}nAmkb>l>(0z|k7`9&CO- z^;N*lE&_gaJX|zv=`=BY4i6o zCcKUzed5g!m-^&5*V6h3y2?7q1@!feuDYh8KIdqgQy&6$89O$hIu_P{0*n)rTZl^# zWi1+N0u;a^&5CGi%Va#U6*|_8wO}37ceUC3LXQY(uLrJ`N?M@fO0Dl>lZ!(1uBY*) zPn-WLf+Exj^>wa%KHgH${j2U&cewZd!H^R?-_C**|&T3h;jOBDCm zKl8qL>F1*NtohwK`Xd`!HqwTXEwuPte7P=aD3buJ-|h+~+Y+3aX;{-7zR4yYk@*hT zkC^-0*AUVF)&eZ%^O=55A+6U*e`+gr22dhncPYoO(2W^v)QI>P9~k$r`EJ*{k?imn zwL>EV6SZEYDU-SHtI`Cwc;cm!u2-@vaD;>!qK_1qPYHij+&nKnT5U6;VrJ{5@;aJ$ zfJF-#`49}58Y@qSL_QBk}nqc7Aa+V%n`a`p&TRxCb zh1{f9y4YENaXQxLA_<%M)rS5g=5wzCxlpz8%Ei#zztHTuok;*%mk{PDQxS&Kq3CP?Ox*AyTSCru&C)!oj|K{d_zkr0$I2BN>i1}?J0`*QI ziV0y43sUvLQsUrq^gbgboanfg+IziXTa!<~-^DOaqX$!qL#)d{4dbQ;=`3 z6*iyB=yjd5>AfAL;qyJs2zOoAVg2FqeA-=6%Id9)#R&0L% zv-^9YzsG|AQv473%lpGlJ{Cal%OJwnLG&VrsswkAOVaq7KNWO}L~`yTKizV}Yu_IY z9pV&xKcu#Rmo2`vH9=ojifKvgc#>-}I;87F%(~z?)BU7rLv40g%C1FH@)CF^W2c4bCBb14>-KPB?dx+2a(Gqs3Bu)`*m6 zASdc9l_n`BYI35SU7bH6l!LZ6fanl!GIqV z>tMO_#MH#ZWTi7xS2mtx{+qx+hWk5wk(y%MFALCV&-901UC7U?UUw$GuHLNkH@;Kt=Q~pwgwkUn|$Y#Sn+j zwOeP-okV80vbUOs4C?6G91!IP#wqo=5zv;McWQ;$3NVS ze1#*91NbdYsnWPD%NpP4lK_&5d*sj1fDn6Rl7PTv=}oa4(iagga`LMF?h_ugoa~@p zFibsR(Z|X}0p>#ne`UpmKME>S9vX`a_$!5#l7(nY_5^s0s*z*1nW0l^M^yK%W2LFs z2)gu1_UO>iA27g9$Sy90(3SZA2QK8|!0b$b?@MvhNwHI9zUQ2<9Ng9ZXLK0=qW))e zBx`(zFY1G%J@MFEENexE!3hK%x&B(O%*+j}O@9@9ffVk+K1D+k>s6-j|W1pgUX z2&uGZ74RM6ms9W2K*_HVg_{+T9U&R(l!pt=CGTuLyoMJB!1T9Nt;?jd;y+|&*1x23y7TV z(OGAsoY9Cslasus#m6a=Kr?5#h|E!PYQSRHdH!pS$eRDN##9qP?qh*6keuHETVTKi zt@*jzw{9D4?(T=G0>n%M3-Xd2JaErO1pgN93;t5s`bND5ux*gW!<*p4?e^#$X8w9sVFt)Qv8r)M8YOhc;O2MYGuE6 z)$Go(ssbPgssW>)BuMmv>Foyn4vP%RdlY6h^y2$efdAkJUXbJ?Aq|t@W1>V}ZLMm! zF|XC*&01A!MdX**@0n{Z*9JKlF3QE^86PD(cB$2Vlir+#M0cI(w72uDZd=FylKD%3 z%$Sq@xOIj-@->K%M*+JUdhWiL2)H@i$IlFodrBW3zuyK>gLnL1D~-rEWK67q%@U2t;-UWeni;2Em&IeHfbphZ@N@qiU ze~1eD@i_1_>aRc~3}VCwzK=jxG5i;h=)vNXRB3wzVw3m9i9un#W~e(oc$}Q&g15&|Yfg(chTRqX6P(Xh9iZX(#tNxkSj1u3?D9X)gvCc_rq_f09Yh`Tj?E z%qaMRus&4f97BL{bSx3SjV2_8xPjU0r^9YOxk&Jy2r4YOAEK7y226(HWVV znD?5ClvGe|Xeg?mcq>*psfq@E@c6j;<8jrzmoC*gR=xf-b(10=GqHt0oLS_m!&^OK zBUqy{FW2Co>Kaxi$T+d4FfAKivjM9`PxPpw0H(*vrTmo;x%Y7pYZVl6>A)aXfjQuk z;1bhB2WB`0`2)%Rr%=4?N&3C5wY4=X2L}i4xV{pVURGD2dxjT3>bpoN`w!2cXiKhC zxng#tp_UUrBIw6XiIj_=VhFH>!~T(`2qED{SYpxOVhO;#=>%fqBQfSoJ?@yjO&tWF zB$NSX^N$5rRzkl&!`GL}*Dt{j9t5{05>m?Ak>xwC-UK(J=uBhIjHl)aX@C86Z5sZ{ zK#oZnQ$$D^l$?cx0SN^x;)qACjtPbE@m+etMU|CH6~)Cn@U`BULN}u( zZ|uU3w{E~=gLlWrqk^PRGF{~WYa)o1>}bjjB=$}{$8!zmRY&lIMGND*6fUz|NCCU0 z7$o|-MQN?7I7a3d5dao|Cr0y1sAPeQ!T(BA^pwbgqKkN((H;7L zjz(C48ATVTF>sih_evlY12|!}ge~;?{~AtI-)qpuBT9C!20sG709d=X9f|p0xyv6h~q>$8?wfwur!#L!~PeEQ-SG>t*|cS zVaV`HDjMG2XK*p+@uPl;HUStZL)o=9E8oYFSHiN0Y0guq9K<^C~KjPd{Q z^_F2#c75L{-3ZcxbW681D4?W-w6t_fBaI-9pmc|HcMl;TCEXp;-7&zs=DM$YKhJyY zeQZDZWtch7wbs9Wu@J%(C1Tg?jU?fnZlJO(y~%&H?I^Ih2~)5l)4_f=r2_AcyCfTL z*#DOS$gS?5$0tJks_-0wLnk?so-_D0KjG8u`QFX6!LNKF*K>kG(Pb*aunYU>4nBx0 zw-JS?G?@fQbkq-aQnD;%1pM-hcvtE;$Oo<>BLdM6u5r2IC8+~XHz^)-EDM&?dN z0!a>xegLeZ!>a!LMJNPBi?z0VL40^*MrFjFWs(;@owC7UV(s0ZIP>Q?gPW99zO^C5 z)#fr$*0Q3${z(n08!Bq>d~#@Xe6Nvyr1{bPT4px6y-O4H`HiV$Dx zWWoe8crLK#-)F$-h#8)9%!v{F;5EmH&dBWVMRSl5&~sn7NZsU|_bxv^3XWB&Bvxu^3Jd9c4fIjjQo zTIV=#q}9T-9&bQ=hv*(h5}0p)AW(PcM8v<=V-UX-^de6mZfN}6b0G3*rzW&e z@XplZr-e5B#MB?^i~jq1)E~CkGdEu1=Gj+=wtL>b58mS^`iQ~Zt7o&?+Pl-`skJqQ zMj7Loj%t_kUX3!!qasq|$Bk-lN*E*e=d0gjbX;kc%#yy?y>S+KYWUv-C;QwRdaR-J zqF)itK2+tmJ$u||Z316cjE9H(YfK3qWkQ4l!)y}MaAb~|QCG<+WLsvhtmFi&4F-|U zd~O&5=pg-{cHmQOA}H{b9T3(+AdP~vyJzM~7GA(4?%GT)O>?RXc zloL%C&1f?vq!5W(SR}8WGs#5>@x#NFpj=^4UTq3&MCMbE+T6e}krWQ8h~--SDj;4k zykV32=}ScLDIi za10!4L_8c8H;pm)W>OlHelG!s?T)&~z#*bs$Malu|jF(mUc7yW*@hjoF8!OwX zW1rhc%)5G&ya$%2&(Q-@(q2~8ub#-`xUyp=AK-sluVQh>1TdsbuqJIrVy3C@5+Pl? z$>$@J9G7^Gv@LIr4bPz;8+5eZh=B{qwN{Mpl53CkQ!e$mX1Ua6MQq4ZKb>6Mx!ET} zZ@U5*>}d_O^YZAPJtHCg`%*|SKZ4}(B8S4e%`>|9+-AAvY`g+B3hI9CW+hJmpR?H#D^ zWO0(_Xc78f!O{93WSYH}rZn_8wtvlnR#VWP>!8I++R%?<++Rh)i$g<&`EN-^gemWh z2ailgRdg-vG6)A5@5S-lxpg*T%_|}N+_Te6#Fb>u&;1v9CXAE-pq8#aPm&KB9S`i; zn$EW$EhcaEsIM0e$P$KRE{`Vi^Qx`aLI-f7EBk&0pWDn|{y8Wv3+`diX0P32Ff%u` zc+=*if+#(B_-Ynulp7h8UM#RS96E_LvQ>#TP;17 zjVbkcC&p;rg1sHW`2~oJ^RzxZ+tvP z%_4(ly=((=Kf^UuZy5Af@<3IHOq1z_G-xOX?={|pBM$lg-7@=l9`^-C$2Q_1k-+sT z+k}YVGe+z{G$s-FC$VL**Tu)pUl;%nk{T@cfQ)JKJN-5hzYqC=lOSTccmK^Dao$LgSIDfqu|p;@z>WCu8<4_ zS9T^h@F}jYjs`yX>ef}1zN;oGe_V1s4+|}1KKfJgCX2eqRbNmi0*>zV1q`osUYjSeST3qzE6z*&i*^?8%Sz%r6sL(k`yktz%l_s8fm2do_`w z>G`*N8C(rFGnB-gost%)*59MYs5I$%_Pg^8Hobo7>Tt#0Cwr3TYb)s9pw~+wdo9B9 zuq*Lv-yj8t!g{ujmSei>>$&sLA2w0oGfAKLycxG?V6mE-fvKzl+KNGPUsGZGm0dKW zWY!t3bkO}LjeqO^2NGXb={SUukdXlH(eds*H1f3-9c)G^WrgAK zcFoh^H#|qXkOmda46OMiBTsva^gbMfX#06H7tdaqH#*6R(D2c#0|ug!wd_|6K202I zKhl3o{Mz>S(;zPz3~djC%*_cQ|EXOpY9YGuxY%U5AcZm-%X|^%-=Cg@fNMuRGzR#| z^(hysYx_2yVU{VR;eR30Y{8o;FoR4?eC)Eu$*xOD(v7d&&^epOaq)S)x#M5_j1#co zJb&~j^<|Caan@pFf4%>Kq117o3F?BmPxHA(0>@piygc+^zOQ_J{c9GV@7?F=%Cgqm z-ZPHQvQq1`fK8>tU-tMNVGu(D$A7T3n`jW3qaSb7-t3jndabMR!DcS>bf4 z(KOBe=B+Kkx1)t78#`Oml=Xx4f##G_?h|6^rPPHFk*CJuI+9rX6ffI*IaV&pXcIUL z$zpMRrJq%6ktHdqqJbV)lUha&93&|}8edBskSa56kVa5Ra#*w;1$D1y;dc=WPS+44 z&{x1vm5W54cS6-b#8ekI8I%^>peTMZ8!+Y^;#UJ>Nj}*@zC^1pYudeaHXCFtF`KAy zmZH$PY~@kd-K~Tb=W~;&DtE|yRAmQ<^M|{CC0!n&E|x4%h-QwNJx*$qN4z)o_Y9Bb z#0UiYl|lXcU=eol_+P)SZacnS@}35tU3Pht9D8nhUO%bOU6EeU(8#5KxD}|NJf;>M zq7q@SR=a7duCAIOo8o_Vu(FZrMZM8&m%{ zm{!TOtO~?EoR_bMiqUceI5JW`h`DtViuje%vps}yn@N8Drmy({_WXx)qrcU^!AU<9 ztz?h?2=&{==a^7l7avkH&P-wq86GxIEudPpu3`?vY_`U?uzO(PuW_b#~@4vzXF^71rR zLDYG2dySH->0;&r*#1%}0u^MjaYqF8*pi+%RrGGm$>1>D`Br-AsT zDKD?QDT%Egco{x>dyH0lk&WT`ijrT*0MO8M5#x@d@|o{)-r8n-q;-gku!RY!|x3sG2YWE^Yo4-+%efU&)pw9>Leg>Cf1!!bc*hHGJsZ{uz ztD}j|4OhcGt&es_7wFK)??;P`D!OC;9Q&Gw^QJY}#LICyN~SCTHgo8Z&S%DlpQKjC z%$v*n*t9L`hHYgjVPLo@{erp|4H++u0N=TnC4a@=J0z!78n5h~=5Sk#MKygYgE(H7?l~ zX>%W<8(q9Uk-4cQuD@f8(_bs}WJ4kQA23hPCSj}}pS@j=lmX&*&3?<3wrmMP=;rof z!aB1eR8P~AAqn>@C4&lSZGkcidsClB=6l43#4W5W39H+Bz>uG;DG_U&hx2#y#fFp0 zhml0&QsLGz*gQ^sp*AO`mQ^#;RbzbV?U;&FrZ;3G|dOt`ks9srRhEyrM*$_ZnsMTCAfL zn0bJT*rNJd6uBH2O(?yl{myOBZt|%X6jnlRM}pgYw|hzyljS$SK9X!O{c%00Qf;$k zlk#jhd~0g{db%HuKa`y8M%Z+!b3o0^`!V2g#>jiVzR~;s6S?CrgOK-!Xio?Dd<`I5 z7F!hF1MXBu^AFKo0kil`yw()gR=um?#Fg)4Lm=Dc&oB7L+*f0lDYRy1elWnxbTkLm zufr*jy4_1o5LxTqwS-CSo1nVQ{z>L7`J8`vPf@y5A^asHs309e!u9-=*GIsY%m%4G zDDL8o29(fr(Ad^kNcMjfCZH381ygP$&d&H+_4ej-9f@u!>#M9P^qG&?h`mAREBo>& zpU^2-hOpT7I#eH}B=pe%^)L>Qj`h4qiJyMsfieEw_r$LsE;YybKHB)Sb{CKtk|LhS zopQWRT&O4>9E;m~cS$MoqOMBg7oqRC>UTb2RQ~Ohl(bTEuage3h>3%#CY9-g;jVpZ zt_8=pe!+ciNf~V!e;d(hlE`karS0at*JxPa#Jx{Pj*B^TFJ!_4bGD8SU9W5sPquwR zPTCJkZ&MPJOl=lipkMMe@ms9JLy_eJ+w`EHz2CkAm-aj?*$G77CJFODXgi%iEy=YZ zhORzeFYPKHU2hxMr47?mVy?-~&oc5Mq+;++Y@9alS$z@eyFLTE_IuCw0ujkeEmsqT z$?Rn<%@v%Di;3k;F0yi7_P1Mk_dn4Wz>G(UWU9KmySi5t6`PE>%Hqc0ry$i*n@`qs zagMz~V)$*Brll^|8c+b-Z28mNrZUquorI5x*a0Sqq_X|lc^~2%f^ATHiAE1sqc8V| zciSdU9g-81**5yzjlM3Ob6fQ`@{`>PzS8!rZa2~(ZmkXr%4-X5LW~B&ywW)~&XUee6CoUp>$;6)ax-&4I6R4>W zu=(cLWEf({9O>lid#RHrYbTo9E`8p_py07G+-l!T7;YTayB@z8{chIUvDHbr%tJcD zR*?bNw)``S`vN@mtP=78OXT-WEg|m4_HYz+e_R&uxy5`&B7N@WNRj78@$;4w$h34Y^wND|df8;hGPwHXI@~sze4+Jk z9A>_V^Tqj@)wE+Y2Rpk4;vI6z!ou@XcF|i=o!SS;whlO!Bx%AW_FtC(sd(xS*W_rQ zARh~({9bo8qwDp;HM3LMQ0n74&vRYrvyrhe=EMK8TmCF@)keL!zmCA6bneO!aVYq^ z8&7hx+gMAQ)8o9m#ApMfDA_MJ*zlLUyYuN`$kQHz>a;z3>D77GUPrF>?f%b@@13Rf z9s#f2)Ec&y2SJc{n|*Y4b5@MwlM-2YvKyBE#O|eE&e;q9BDsB{Xrxr2tt^uDTY7x& zv}ien@j8<|Vxsh84bG~{60-WkN!!ocN*leX+N=_-9X+1zERqEG)`^w z-3sojIx@d&^E{bgz{mSzMCKyeYWy`S@tWk|*>$%;L_iw2haNFac281CMPL-=gB1{FSpn4?LHN#N!*v~@Pow`&kpD?VK`YU zO4j9gud_F|co0}ia`LhL9R z2AB6Gw~W!`1qrdK79X^-6WJ5Awf5~a3)1=VfZxqpeJ`|A`XA(!p&2D4Rm*uIH1O}2amK_%1{m`K#n_?YxP}?s{JlZ&}4OH5= z*??gqI0HN=p^%Gdpv36m-FIuG)os0IZM$U7WnGKgfM?|IA$CHs!xFBH%F? zq8$JmIehOuxz;VZg@oMX*Tcr=>^-M=R$p>S^IQQCivJ&MJgiOD0xIQ43maR$tbr9{ z3{m^|?svC;g?_%CoG>d1jN;LWI?RY{V`BU+t1Xt;_t`tc5+M}unaHlr2gD4zjRH9T zqlB;oD3GSk$3i_CDrAJjR0Tb~Rx*-9N`n@6#|nZbAnT$*z; zqaDKvB7s2N4=n_SYs5H=c1Qu<{aZPxG)u^6U{g(-#{mt8QE8p7+O=jR^V^V*VPepf zG6~Gs0`JH1)}oH@zR$$r7GI7f7v0C+?L0cC6#@jBhg^uxEv;OH+~QN2sVufqrPGbF3!B zFBkS}OnY4%u88gy=chi4d7rjdW>Qg>tCKVYR{!o5SQ)Ajl)UmzMqNvofzgYo5K;kd zoPa+#f&TOx7TC=6T`@Y;;CB?FHFVmD$eDd1!qv>`|7^@hP^>7|6G8bf()MbqdwG7o zxhyM-+FFHr??m|#043m`_xbkIxtN8GOkr(j$+dFU0<{b&33&9kI#AQ61RGn$dd<#L zoeK-x!>w(a!BJ)UF$il})cD}&tiWpDW8~b`Vi@~P-MZDX4!mSEML5u8`BT19|AHn% zOpWZkBHRxeVal)1~xWDVP4+%S2L9+ z)9|RFkc^{H5CE43FY6LkY37xg_Sd*L`7+g;U``&Ls*+zKqFy`|CB3PIZiJwS= zt8wq!G*v!yzgM}H~?=NSU-1MF=J=IFos_SWpCB~@mdIg zdk6iy(kV~mlq2?!&<_DtE=fo^1Jaljf*2+~X`b%KC#h!mepkI*jz{=BKK3K%j_AwZGb!Iu;3OQpenFjWH5_We8d zgdh}YBs$4V3SMJu!taGy_lQK=p1T-4j1kaMc)lM;h6dNqN~za^EHg=a0r?HvJcNO5axjqbXF>);ITVT4C=8i?ocBww zA09Oz`4eWn?4sIBz~UvMpnU5%0`S16Wg`5FYvt|gfMi5PBLsNAIAGhvnX_3kfNcY# zGyT&8CjQn*izX_Ch*D_I}U}@1WWKYjQ0XY&S3pFK7Qm90GKrsIV>7Laxrcnw*DX1 zg9pt-b~b*4<2s6r&sf6iPPUJ7_EtBx(ByR_;?9m{%}84s(aM_C<`TQVSB#%E!gYpVo=7Yoa7RwCtOZYkl4hu@?vK80iq0& z`73E4OZK;yB$OTmWRN9I{mym3Yot=H^2Yslc_i@Gj*^#s3aZWi#3!^6|gQxnE!WV)P{$Tx#0`&gTf zKI|sO#>tbu+cTd**{I`vdn{QW6K$~Y`(#`nNNfIv$;A-*@`0(3_4EnTS+|RdO4eL{ zH03$o+PXqG0KgX($XYPl+>gE_H#HS3zCCxh422k6SWL2?|B0MqFFQN|GhR=A%N}R~ z9{Ec?jbJ|}no_3i7uNMu;s)4qmBD#tmQEmzzPf~%fK`tsOOrV87A~90U)|p zJtmL~oVzI+!wpu9pElgJr1Yh9A(NzTj5n_|>y){upZhrc3NfgukWhI^`XY)F+13a` zMRStST>Cvd9c5_DJfK3_`lQuy?49)(lMm;e0IJfJ)Ylbraxv>*4EM zu#-w#_)K%+@c#vF_g}hTU-Gj%8_q|ardPjKb*CExY%9Euw~@H;b|6F!V4EXv0}&Up z7M(U$%&%oDwKwuX@yc8+a5?5&pEM}M-&VvEGM#6ygd?{iaV3$;FVCATPWcy~kY_ou6vff9V8nPGakJ2rA?opU$+=iAr6gF;gBB zW+3~r!f_Ev5`ndpb`#Tx5KvK8rmuh8jr!TTslg0WUX29s{*y(D49=<pGql+|j%ZBB7{nWu`K?bm?R~PowYb=9mP9 z5ZUk?()D;otapv0BSR8bGx@u>x3^j?Uuo3e-~R-7rYFtK&7CrN$)nNo(f%hpGp~}_ zx`2%Sg$Ag*n|HS|o2-2wxp1LxJdE0IaS!g=r=Df|h}Ubq<#_Q?Va1~%C{2JO0*wOu zX$KP=YRw^TrR6Yl7P$9}(AQUAq<*OfqJdIlF?o2i*=k;fhWttnl{xlWS4+A5RLoJJ@Xmekv+;s4=5Cv=Hsztsb5*MrGd)V0j-c?zzn6=*`W zi$sgU$Rs+Zi*nc8XE(T+FxIVYW}Y&vw<9^!%O`hiiLO|XnUGW{W%BybCAq|PzTW0 zB4HT+P%-h~8|?iB)S%@u&tL^>a_>BLEire?b+_WqxO!v{g?S_gD^*Pn4Da-s*^%E; z1stj1rR7K7^Uy5o;jH~{ zb5|8qSG!L$bsmwLuRfGm0ywX!hrvvn;)1Ma=-TWg@D|&d6v%?`yD^Bq{LQi;=u5vN#dpJos=4Bl{Hm;Hy)$=@#rT0wDu|a2|Afz=vDQeV#16e$^nmMPf*>X9X zL*9Z}bVMpD@W6yY`^~1sl+}T3%XY(;io)X9pZ(mL;)tf&a)avC9$OZkv(<Qzf&4`ocWZxIDaku3uk%g*#FJmMy`~Jn$ti8k^h1Ia5`i^ zG%ivx-2u`X=0@h{Q`)&*m!TPCSBI-Kv#@G5=+#eRKV?H0P(vkWoI^M`E9 ztNNJol8f_mr?jktXv*=6rS6tmz#+I`r`eA|1R6`kr;hX?A)>cl7luGA?sl_-eXv-j z_wLHjnwwxJiXQE^B8o-;UJ=GeYQRWFT~TnjsFCklfpz5Tw{0DWJf#=(06 zO%{A#eEjuDYGa+Q!3CNeJJIs%0s#&-2g<}`?T-x&Q;Jx=Udxq6Cd>7SUyhd+Q`m8t zOU1mGV#6QrJeOEfMs_)#&gS@hNB;h+iF!e<6p4t}gY; z?A2V9@(^6@lrkQ<(q@czfBuAPF&D}X(z}r$0~F6e5bDc>33^G z+3Acr7F&t*dxY9QpFDqg+?bG%AoAwbz)kG$`pu z&PYYw4wIhfeGBc@>nq_C`fE~gAcU0%LfAhBEvNg(js}o!M~+0ntkJf#M_w1yO1pJn zB{<8}ua`0{#HRPM6j3V0s$$I^kb2Dg>eo5doQfmJqO-3m&mO*|m(6z0`xInlIsQ2~ zzG_B3DfoR>?_?Nwh&yR1{I4U-vonF?ez)pJRGQsjv;T^pNHgxDe`-)mQN1adZFtP1 z5=H_t(KALR0|(Q&1*(>TFwNj|1f%;Y^=am6BK>sky*uLTRHi}g827~}04LTQB}Z&s zSuE$u+f3+&4@N{cMW)BFIJ*s4|yD}TTP4k zjb9n&H57y-@p-t9ue@$1JK+JfuA*XTXZaSA9)-9IJA=$-T>mcv0#8Rr@K|m1W?{{17j{=EJHpcT5<1<`{Q5Y z#={)~a@&VvKaOWQmv>ehiu73A95%yJMvs9Nl=Rq$d|QOvXQc=I9+9y@Slz$$P8es$9->nk_$+65*a z_(lcVr>CRvQW738j)teuZe%}bn_Bd97}nv?7k)7Z;jYfoiN(sIK0O3;eDXhKF7i1} z#a7XTtjHIZM_N2LU*q;T?ojJkYN^m{-d7vE2r-zZkg|n=OzQ(poAs2t(1)`t+omgu zbHl#|08qkh_E;>hO|xqJcuv8&M(*odQo--jpK8ss_4xbFxJAWw+{nYDF}asRbU_U? zYv2k`kH4MFIAD9MYwvvpcdi~ji3ri-vpPZO8pjZ#r2nJQKnD$h$fi;X8nUbfmN#I!!|3~+>dmU}fq zwC;^oBREk0MG~Wr`BW0CtvM}b++X?*(MF)yZCLSV%kn(_-mZ_?w6yF)!O{O|+v~ce zL_WE3+-9q&CH$rTW#w8qj8gSexctfK8?+p_g}fx|jD{JD@cUl-eVDn%?=T21+rtB} zJLrHOXwW~zFL%jry|b>cUC$Vrz5i7g_|V~lZSy7oySI5o9!Kf8To{t}rDBa^pygkh zl-KtIR0xv$8Fwec_1e82j64qn_mdvlBdJfI2roagVzjf7O+JU~ta$3RQz4C)-W_ns zJ`HHO1ALCV(V&`cgwZ2Du%Tk-C4)Ux%FrJ6&fMG2X~onBA_C3LM|)Mk98n!7?^pMx z6z<+VUq*1^V`e-$e|`COS^TpyFw*29k}z7%PaOBj0px%(^AUYC#27A z*X_v;*B!luZ(O{foHYzAQW(an`cTsx8`NkL%G3LI*6wR8zDazR4a1dz!eprT(5;>F z;CCTr+Cnb{84X&_PQPV79J^>h55{sHbJX|Tf{rt~+Iqqu+1ziU4w5II>D227y7jUz zhXMQ?H)0iRQj7_@R)uX1{a=_`l3=mUdz0TGVV4w{_71hv2Pa-Fc?cZiQ5-k zXRTHLVp0Ws$H@AcvV8U7CEfY<=6s`_Ah#Pc;E8h5Q1j)T&=q@Y<@ms-2#OK&5wNiy zTWzDmjPbvr0*O^_F>o2GtY-!S5eFFw0-zY4yu(~pGKxMD)GoBB|!tCM0kcYH84gQ2XH@ifv{ZT78$n}7Z zxYlIFy~DF#N58I)YIJWVC^om>v)t^LhR_D|gq9}|`vNDcKHy~K(q=HM=WIE4ev_eh z1^utkwNK|&1*<5TAK|Y?UxQ|${Qq(RN~w_IP7ydBPyQO#=>d!Dbk( z?AyBufj&uVYZcxf^&UUkRN5Eu>^vv?ZpI#Bv8!+L@j%FBoh8g+lMu z=OdMqku1c!WlI%X7BJQ=(QwLc(84A=bO*XETfMZx)pc8E?*zl!0;V(x9&IIU`^NYF zBZc!w=7|L2Pu711vd*y91bvwfLii(F8W8QZWfby=eoy1e6#Zx7Mz8*PR-!~6O zmsbN1*Q`xRkq;kpK4`~Zv?fbY3X#z`o@l<`d^v5OA8i|ev#_2+K@mb4XGQ*Yje~J7 zvTq!kNh&e)#S{4j*;Ce1ctZq%nj{Gh{Uzj*Z$Ik_zsvaP>WZ#=reQB>xI_W3y?bAK zls7LE2`9W;op)51N|W9bq<|_MVLJMMz!sRrZ^}F^{4=O~xLLHj&S!yod3{2>qvOzp4mhM=JDxfV7uB zx*D>qEVOQAPA6i8U;Hp-!@CA^)h!N;%EsB*IZ#?$51tVt_4H72-u@u=)!sv`kwwF9 zJiOkVbV>=Q=BS?sgJ6s`KiEm;QuWyXM$vl1hI~DLgOF{-CHTymh1&Ln_>L$@kivHd ziav1ix@|vFzj5mwdFj?4>xfaRHVJsJTw;214p%C3mL2RD-Wjw0Ry zil1o-+el}wx072s4!1R9R>&I1gBbr=&9joiER`D9`563fNOlrm|4<>>i#ddwo^AF2 zbkTUkn=o@gHo!9EZfG=!whHTgsB_&SH@Zv*h7@b%*`*|rn*TyR!{QzQ?`L`c7PRPp z_)#z_BeT{@om$XHm=bq&$zNb}#F&0bTPX+pG7!0frr(u$KC7iMS4eSL{_}_Z-Prfs%LbUxQDW);YHha=98ac(Vi)7}PgRN5mva%lxkXqSuK_2z+>i%={=le<`K5t@PJ4N)A^Z{KGo4 z1Qbo!;78y<%rS=04@O46o=hn9G&eWjc`oYfR^M#ig*Aog+Bv=aA&tx45=ppjUVuHt zTh!H%Q6Vab2+2vl1W9Wk$n%1%+h)NVDzf+bGte`U;l>JYZEjk`{j<&{_|>ct*>)op zmJ|M;e7e-RK-sufxgB)3ss2Ur#*rggpxb(D6LP=HXYro&W-#cQ1;gpNI7XG?t`0UE z`-}GjgM%Y~GkSq}Q!<5cLvf5hV7iv2`z)1KG>8UVVzE4|IRa@gF-?buAZta2eO}}$ zedPMPZ;bY9_WzOun=yA@M8VGs^#!&Jo+e8$9t!gXwZ1;)DOA$CWWc z*QJjg;-^nlHAJ8a5#$f0{&ejLHC!I=xNAk!aSNHL*_u$7R3JQY0Wx>TNsGZ3@?f>& z^lne_8BY@GUIoEghS?qo@s)UG6}b3d9L}Ymlh1(4l*A(ffph8QPi3I3uII9BwG*UAy;yh4-Z(foS=_M$Hqr$q{;*yoB;T3MV8d6_YX2e(DOn{rV*TDGE3z|uWo!<6MQzp`25WCf7(%Jnns&&=lLZ@~S z&uXeDjg<20&-G1p?y9b;5HRNlsj~Pp{2BV~@L)JyY%_d0DChIjG)3h$oOI$yn^HL*iU&{LQ>D;+ zzKU9>LDx?%Lke>47Wb@dlY=wAYL0s&n=ffYpWiAIUWao$>v?j>jZ{ZFq+1tBCU#gV z3`zrE4MM2sr2u^|nYabj=E~d%&%sPkbF&oRY?EW{d;o{ozN)@{-oeJ$aZ+TO9y>j! zbGtsZUX?49u<^}Yfs^G`K~as#v8K94Kx7~@RS*K!gB-Q$y+!AW{k@iXl6l`s`Cu&b zt{?6Pa}DQUU8ZQ2xLsH2XDB1Vb4@B2_(CW|xFTqqzBH$a(K4=X)_GeK4f&&Ny>R!M zRiv01x}?`+H<}Ui;qM2|(P@_(pOcUjM4*{J+b~qLE`ke$;1Pa2*36bFfmf4oBKQU_ zc|89~D{XYiM_2sSIx0Q2?Rh+oGDljbeaa6c|09lBa+^<<+bVRj>XxeC6 zJoUozGCNLl{!2p?h812s9fq&R9;#H8euzg)AAka^!dV=TiJcS_+$}iozPqJ}H+&vA z)b>mUZ{52t!}oZ+F8dK=oAlaJO^jrU7sig>H2Ep|42M;pZYaXG6Lu{J0(E_ z93JjB8a{>PFOG?yHXgkro!af3{hl5&l_qFETe)hoq)>$M@G3{cU#TnOXMS?)$IB4W2`eqo-jnYkYRdXK%!6P~sY1d6v7`)RgdOL&@_mh&Jd zA}GL5s`+&oOzPstkvt8AxYS`CgF2B=yj(?5_4w_60fha1OcsesPl!fesk@D$xY29> zSPjQR)!Wcq8yR+^rl*IcSYa)5q|CoAJ2Kn(R&$s$KA6?vVCb(3Z7UJ3*t5~;nW8W6 z8roN?aU)Ntz-zB^w7-`M*{e98AUH!Ns#{<(aXLhXUobdxY8Yksjjih~IbTdKy^!3( zdZ?@-wsp7~=Xw2M-%hsIa&6D6ial(%rPXc^Uh)e!OPHDj$%E4U$FlZ^z_{CdKe&gf z&LGWuwfLb#=5_*QOymjRUeaMuJEK=C{uag8+Q2D`hlZJq#_0%CbW1i`t?)FaAr=Kq z9+kKVt_iN?m_Vk(Nw3gTx%(jV?f%IRtJg&g@8JXR3uvgHr}sLBtQ=QejUQ}~7MVYv zS(bADP#*DGb;Dl6GkxhN?Uf#zocE!(=;IzsEJLThrZ@6?_y=HQ_!;|0cE-j*g~n7Q;h~Eu)NVb2Y*8?bMEK#3NkmViM~o zmr$pWsrfNy_Fxq3+))NXtXj5y2s)$q#ub(gdUwI$%C5p$+p7{rp`b9iW@6wNEa~m!3iw%})*UvKbaKB)Igxqaz;(Fy(jw4%@^JsDn8LO7N%xd{ z@;M*AV(xcNy$ooH ztOvg0c{O3rQ$+NhyfB-C&Jht#2E|V5A&iB5L3fYu>cHlFf=k)p+wa#O3ZFcvW)riY zwjTszr)%e7?~1+_-TnA%;a1!fB@g6E2z4;>Uqu zmR5QBftn}#OGF=3RZE0_{r;i*(WuuF6Mn_G%2O*f?azH`#?UholKAJM#Len6z8X#w zKSaLIBw91v3w@22l0T)}6wA0fSaq~l2u<*!v!*TvA-=yT(X7t=Sd(WuZYT`w{%@+_ zk$)0|@u^{g-%@&J8i0)0&K_&O!UboqRuu9(h`!4x>nX-^)B~|-w3H*0VgW)KO@JnE zA?a=4BgY(#G0AMjk!mSBPeWiR{dC9AMt>Z7pJv;`0v7%l1()NixkA(@Nul)EsgZ${ zBNXeUOuHX!`2CWZ+gHk^?!m(|J+*Ep7hH5}AYS&Qt zY%42gV3D@?t0I#3cczY%y1L7=cjjz@LWe^*YkY4cXU$Go*`%+)C8>3T!vo`FFKrgm zvT_(02Br|L*-8-pdOm z`6;zUmi86<(lY;NY1mI&y>?`9&RKj`jo7n&jHcTI^=4jPt3~GRDiIQ|gg~Xa`P&p- zzQd6OmseDjm-BuJG3Z_Gov5600RjtdY z_at2i43FzIrn0fqx~tZ}HD8Q4s=^~C?q}IlYJB#Qa5x4MMp6%R%9EuQPDwrpxBaRs z=vZ%AZC{a)TVWdR%khnj=@m~b4Y!XlYjJe2DLnoZlUlVm(hqfY{+Mc_?^#(US*iA^ zStE_&{AihyAHT#R1fdAd*P43gh5U6M^`q33=)BkczoIjWFP}NvtOBSA{51)ct*_-NWrS4tTwGkFe_*qa=1PF(rZ0)d{FH{4 zHhR1U#1t)E@DYpe(>5=#9;Ot;BSn)tmaP(q42Teq5!%J_UOcbF)Cxm*8CIZ2Kv~pg zoGy^L1s4?d_y6$qmSItLZQDNs0#YK4v`C78(nyI?f|R7xfFRvS#}E?IsDz{vg0yrG zA>AO|-7xe3!|-3+&vU=;`|1D5ZM#0`HRrj`wf1%Fzx_C76-s?EMAnt=OT75>tZA40 z?0!P7_xyUx>&?XtisP5gB27&A4_rDtl~4LaC5ot0GwKUsbc|OPbE9Yk6|;CJ%fUqW z1anKvu$6biFaER7=KVkWEFs!@K(Flk?TRaT{NoJaK3QtQ8*-06oY<+*G8Xf8p6VzV z%}VnWd3BV@hb)jzX)xD_!$X7d;-iOP#5e-wlQWcP@lNB{8}$@kU6l+;yIS`HBL`mI zl9TSQ?46%gEWupwvy*o9S4$hGr>DJOu){HER-B^H+2UR)$0{bK?~O)Xm~?b>u&zGv zRW`6l5wdfxcUlQ~m8+7*aJCD=aFK$~O9XKFk@~+$U+^+HK*svQEg;U2kLvsCQAHkv zckz31$Yl=Yw8T3OJ{0Fvd=@$Hh1u~)CusH z>`CY&J*$3kEIjp+3L_>UFoov#GBwl*eL(0e_dEkbfSAXDA`r!YiYySd={9dAH^y(c zmFu=TdD&o1hC?aA0qI;n-u`1X5RQX`lVfgfF58O5wv*ZbCOHr+_!&_h$6cn5v_dhU zE-uF}6{GXwzkj#VG%}iR{`)r@31*1a7w6`(qXLY!U5<$e2nZ^*iw(Avyb>C3&{zIp zvw_$Ifn{Z7gi@EASq1m*-OKSGazB`_w4SRw{W{(7p((u;%B6>?t9yt>l$!YqVkt6@ zZH9N2x>;%;Qg>_fXo?GEXN29wLCDCytek!v)_`3q`;xsG!!tYGYqSoX2eZd6#+e=SwHUk}z+;S;ad;^ak?F zpADQ3C2S?dG=otsP(dScp_6H~7d%LPtqNN^LS6NZSW5JW-Ok{=*A92f-c<~v)VO|= zk0%+%;xp5ZS^RtV*2&yCt#wP9p~0?COyz0r!5|886@>R8*o)*(sp1M$e;eg{Fgz8> zTzIs=1H(Ce}^YjvM_(`579%YXkIx8ML%bI2_>rALj{k3MSBfYB`wy zBLsVNF~2W{^5HaJYNp?wgsS@E$G!OfLeHh<&wf5fDs@v30UvxZIXU@p&4*b~C~^RZ z=Vvf06(N|$Z=v$Fp+VfYdGuB2z1qvGE2(pD9*xsb!ZpUE7A>}P9?Pq)XS7{on{ z=@}T%VNX06)M0MyDyfdSRh(pOZxonlsUiU4Cc3e@O1-_g`E7+R2$xvJ(b@U2D44X= zztk2gF`TeVu6R2WO~PfpkJie{st$gAmVz7A`zD&9Jd#qzCnW5ns`OpFT6Z4@Nb&p3 z%*;YrJH{@rw$#N+e&$ak!F&7r>4Iimv1T6mm};=|IroQ@l$5~_A3o%~^MOuLQSoD* z@;c!BS8}4X$JLMoBGajlnLqO9$!S|gHBSEluW&j>Qyl01-U|vxss!3H7Bh|DY6Vjo z8L@m;O-Mz-5hP(^{b#-?*jw-mpb@5O*hr;uQJbe9E=AwH*3fZB)~A2`p2uRhT{e^c z@d&=-jIlfW2BHo&vJc*YK(!2+Vc$ViQ}Q%?`}r^k-lL`^dkJpTvXq$&gjtdeH-`wS zW^gY!VjY~BfWodBnBOOI>r)yS7!iZ`)gZXUS7;?bLe3ccyzyAHU@|W`uhbP-P{I}pSy0)RoYB=-TzyO?U=KHzjgit zhlr-3c?TOC+v|>-@+?SMn4~qgK~G{N9rrzt*A3V9$nQ3-+gMpSZEbB~n5I5KP+?rm zIKYWo#3A{6dwWVO{qCT>B}9a(BlMXDsiG3b&emuy!IL|mBw!G=v%Q%K4k;-pF$3J} zG*-Hbc%T(=K9Zwke$uoq?v4r!1;)ZCri+8UO@^XiC-7X9Bk`z&`&^WjKUG`H^3boeju)^T`oS)a zIz2vCq8D*A=4E+%P}HM7egg{F-lQE;c0f4j+k}I z91waI?)$UP^s4O*nKA^TLg96Fb!-17=ymxKl*E7txVR%|I>aljFXeCb8j*-QhtUKM zB>omv%mwTW82Un4k!{Oh&IimyK0b-yZMusaMlWdn&raqFe5ykU#)T%G(exS|n6+;N zmQwOIN-SHebCeQ=!&H#Ze!BH8ybJ0N4P2Taaq5p5otO{?xs=z$ zIaA}-cVKbf29xu#wOB+~A{@UlF!4HgH)E;$&+}_ylWfuG?OGZA)Lb$p?8P?`VIEkA zXp;#4Ze6Hh3vO9R&dUwyM`XKGi zine`%U;WbBmQxy^tBFWZ^m0P{w zcl8{y%H%%-TF1}6yt0`n{!VIJDksDJ!|~m_?+F|zJ0Mg#ybl`P8TUMqQ()fa>d#l9 z%nv9#^^Abb!Hl78=ZmWFksrZShAbXh%D$ku&~x>s4{noCm=m=UT~ z*LWt+DX{%A5d0zT&!9(Jkiv)e9~z8;Dx)%mX8FnkaQ`)SC4wC`-L0pMZW3ADBzW~1 zOM4B+?BcKM-gJBxujz$J@ef=LP0v1C+fyZovOk<5$|r*%JTjoVYSMZ4ps~s!hEd=? z?>IR+AwJ=4-^(DX>E}qJ%Y{sqeu_o$1k|eEu{gqAiy{YM5M+_s(raxIwS~I=%%>Vpm&5ju3 zE#AjpwKX-XUvrCNI8bZX0mH(K5?q9^Zj}~v-*!evb}sxj6hWnfMyzA6 zVwaN3_-j}}55*ZCg~x~1a&P`Il%;*K#7+@&NY`LrZoMP%LU{lS)|Wt0x7uypZ+sOEW$?eCqw?m3vCMfBFw+YXC1ZBaM!Gk`<0od6F zgG7FX$%66<#S0GYB+UFD{>YuP)lxyR$b4{a9F3 zS6?Wc*1cFmZ>@wD9(GI>Yn)qzr=Ys&TAbW6ToEvZwT+EHV? zv_K@TaQsXr$aD=3cucGS&UTq4UbHseZr$e2PU1U#{f#zwLLo(~Wk!>K=u=xVj(~SO zjBAR1HJ{CB56Qb1SX!WxJrm>OLNPH63FEgyh|8);VE#?=S3y~Bs+LSlCges2>`aDF zY*TtLM;jYvg`S9QE`B_ND|7L7Rpa?3i%n!~W+pS=Ooi2dSpY+m8C({hl}9iwYIJMR zM95GejmU{>}l`*6l05PDXQ^{|CpA|!&~IF zCn@~hAB1?3Z$ zaU#vqihfm`(EabyCBHEHjKVNNCpbZ4FXSx+N~`{JDWstAzY_AkKdX;MNdDsya7SOJ z3T%P4I}BYS(4Fi)1&{TF9zA*$`oo%Rl9cJegNC|%(9IVg<}lx2)!?+!fl)~Kgi$V% zI++qxy4{zOGF}R@fve-RYiqnit28MHyU3a{odeXij4;H z6cb~GP9ZQPL+~>yUI2<&t~Z3$Jsg;y33U|ZwECZ0fNEvH&}pD$hhfv6|kKyaeU??n8rm6>uf^L*Gg5P>DI@G9{JvU z-n`DdPLB~c5d{Ni9%6+=);b?eN;A6p!`o$pKW?NA5YQVME{Q!e`%;))Qv>-T*E=GQ z!x~XlR=IZYzTnK~wnEm0`;tA*${;i90jem@XV;jM{C+c(bNcstG9Yc7w8#b6aA55O zoOtMw_7FrU9d=QO`Nvl}Ciyg+QFj&m>1T1f<<%8Q4S$_Wy+%;6gFqGkWW9R{?Zsho zGdx1v`51?gI`(diL4#5J9+uG~r64tbb!(U~Gc$8Uj2E^-`g7NO49r$W4=|!U-M@*A zjjjEg2>0iK4I(jYMTA?5e1`OXQCvbCUxpqI zQ{!iPJH2_XHA(Vx2In=beGI-Y$BX-xVqo`<|2;-ChQFY^RuOa>q{*oEH+3YU*@0}} zXEpJ}i{9?B)i{m%`&TpMzJ9^yzlx^>CWrG2Z>=z$&?!lUZwgg7pgjAF%EquB|KA;S zv0hd46->$8_0#p)&$-M&T2qSq@U{Jk|i5?2eTr9`Pi zxZ!?l+rq>`GUWr8v91twCL&5ro#W%+eAk*t&;%c78-*AqpEkH2=NBOSrBbf@&81LubCv7p6xdkF&G|)eyV<>doou?FkW>QxKsJ5<|@Qc|0-&Utm$>ZRuS#Q z8=Q|sj9Z`qrsuYGtJ|xZIKepEXjidVK-{*KYv`qy|2;Tf z*+`~-fcV#-fk)eTO91@WH}9K2SYz@)Rg75_ZI3BDKvBSF!5h7?_|b}(_-;<2_lzI; z6EpQ;T}j>D*WVXQQ2BozjVVJ!#bJkQLBv|RLKq0llT3`qLccvy-$+5I)$g}QY(SVZ z-YTmJM``*rAhYlKrhV%8eE;DKHC@0Ts{c<~@ebfv>G!xKn->QqMd8 zoqb$Bv7-sW7^rf6j)}*fNQLHsKJTQLJErQmKGlzk$^6XSbp>6e2F)0&ON*36f4$HEz?=)bm^2=_5}f(9Kw z{*vnms=?Y2hNzJ@%KZ_`%llL7aT1^8A02#~ljqqBf*$_LNT`R3xc3}(LF;ab=5B7S-MR%$#UVh%PkMPv@-c%=(sZdVWKb6f-T*sN%clj z!}X=uNlP14o_!*cJ?1NjIqf;qrOoj%vPxFSF`BPaViySS&N9yDr!lDogu>f8-_+H( z%&e>FxDN^lpUXY45!#C`1nx~|?Z@gLDvk;s?~RO#(NQ*uvy~MU8Px}~D`!&j_mEe( zg34tTWt=r$7Y1#p27^~e(oMj33>X#3I#o$j94w9bj$gOJ~It;-E1p znXRd`F>5A+Z+P%+9~g7{2d>ijoO~9Qu-7>hZ;HGxLtL7viT%lr0Z9hgG$K7_@INO& za%LGzJo?>(sV>g3EUbC|kN^SNdJalVuWhX8?mHAG=9*41ad!3=BM-qvL>^-@9Accq z<2~m(08E`daE8Qg?v%jSH+h&p2mZl%6JSl=ocOJa_(z#612RG%JtOE!Z}|3YUbRD1 zsODlK6_ZeL*bd*>!>JeFoC^G={?ywHLVTL;d>0@MfgkvtXxa9@2>oLuiB`oMXIK>r zuk~yHXk1PC2p~bE*VoevJYlWS!0by2X3UVbvOs1z;wJ^bi)6kF8p9Ov`xz^gnw zhm4F$$97k7XuNCycrBGs2K4q0?YFlwC-YSlpI4qnr`uuSJp#9uIb zAS0aaF-Y$Bv>r?l6q`VY5>*-D!o^cfX>h?{siWdHs+$e~l#UG#bKe+u?2>)W^*QpN zD0+^J*qpJ$9oS{$-jd%9RI?bjX3;#?%29=0uo-}jf)E4OBPC*Ys zSXfwxot<62`p1vOG4E7OU zS>#5kmD-QRTzvR&2MR_a5sZ^F^mUc>&$up1$b7;6Td+vwONKgi@mo5eon*d#*D9)% zl{wSyr?S@V(0Ho-1gp8S9MAgd2`JZVrnW5Le+FW|Mn@N`8{d)zWhk(-;-4|$!+5Ai z>|#Iq7R8lVR5*VbdF8ldTC5yu|3~TuJ;6B@jjpbIin=yC8%ZL$o_23?TWjd-<{}oJ z5*5L--^ma@4*Jo*qf-gGP{qs{dJ`*B1j9kIY@+E3zYkpMKf+AO$QWo&Y{{OEbWLU_ zRl9)7ZqGC?F$|aR0ez)eJC4DEW`a8#p}p_PV)~2MKT<>CDm?as=vt2(RTEw#jK%2w zMjVZgg{NoNad2Tghq$)31v$y63_5Yw71osI?ZpH63|E0dj`X z$L%I@tXG_JAbnVi+W*)N;y)u~Clc9Qx^adeUzseSZYV!-FZyv_C0&PvIW8dIz zK4atzSLH%%a~t!G*I{ab-iCa%l8a^JNUSz|%!7wvcSvvp+Jm5}Ihbgnd-n16w&oht zjE$Y2A;#}kb>LP1*GTj);v|G|I&lh{b=}84>8Ts~h|TexS01z~u(GB@VZVs5T;^k5 zc~`fUlQwVQUmeh=l>EATVODIGZN_)5?D!cct@0b?g3H$Go+jC)1J#12LxblBqdbg# zNymfri~|j!SoQLEPP`M+-@9$OZBsU@sUww!%D7v4JEZJqYYSY?{j4(CcZS)1KxePT z?oruGTz@Yl?8ye7?pbf!Lah=^M8u~r#pkU_iz9LZ{AXWWBKYMVvA*N^Kcx>HS1WDq z4hy806rQLfbVF&+CYV5ey0%l5MrCh6k6M#{zK|Z%5M{Y=F~B=>?@*dDF!3kUXI4T? zwi$ZT>3!#>>3p?nXq_a`_~&>FPur2R3*n#!E~>_; z5^F@nqfd(^zk>}QHi$mJNRV?owadasxC7hE<_FVtY9R|NsMh$GwjvV0d~^QRpb2R# z;}I}~DEjvr!g(C=UJQdS?X)ia+0YFH5U^3Tuizd%jj4}*u{wH3uRCh|8boh2#x%uV z)ESYZ-wNca$dvAgcns`|c$_(+g6c!&X6{7pPZkXpjnTTdux(Qy#eQ(HI@LRkx!y=k z_?=q4(N<&rz#>ZqZK9sCB)I4kVlOeUS}G~L*2eYt5DX{dgv{rX<8ePv{6GLl=wHKS z_t;d@X)d->9o{3m7SvbRp-GjN6b=z=B87TLuJ>a=hd8OvhKInp;AsbdEZB{HC9hm3 za5FQeb0g~2Y<{$f4zi3gUDS&F6XRQ?)CsmC52fj(g_5bdYMmPx_e0$aRfx=ohonkh z!~a7sCGrUXbniiazCs3&nAP`tLf~dwKa}yLP+jvay0dqQ2noY~=bMcW#XXWwClNNs z%;QI(fS;MrmFpE1^Rks2nqPCx5a;dF5=>?M^l=I2F4O%j8)_1g;e-zKOD$#?KOf)6 zDu;!AIVe6g6&2Oau-)>-{QUd_->b9uUU*?gzTzg+|Lb9%NFnsh%(B}-FCyQDhK3Pf zXGi|EuzvS=k(XyNT4QbRjXH{3=`rtU84^0DHpBP0>5dqt;0 zm;@P-2$lm&trr|DaCnDKJ*dkEqU~54MYJ$e4Y-3=p&!q%oXhF zn=EZ>+Rx{c+ar^Nc?JwGR|MaA-w%e1peq@;>lf-C?2&p(Sgj07@f;hKzkjV?rar0a zh94+~QxJ|aEVmjQh@SJ(39&gg-J0UbI|!<;rhinz>QL(H$Pq`0K8k~noE0b_XWWPG zhNI?CimL|}8c^b^vZm4%b^hPnPeC}jpc#r$hbF=(MsCJsj&6(ofcqI#oB|~wm zj|)u-9PWWHp2FQw4EL)`VhQ&FQY7?h=0N*KPsbhJQ`Y}ZAN$rm#gs8KSp%+O-Fasnnt(?hH$XCTXrM4#7aU3X3$g){BSDP-JPV4M8c@ zkWQ*Yu42mq1(&u5I~$wcb5YR`WSfoh)t@Bcp2xqQc@AEJ#Idl)UggAoh2?Ods*z3> zg$1J8>*6sp42bJt9*yaiWm^X07D&WBl%|~3z!tUZnn8&822FI-#*<|2wB{0gWP~&X zgWYIh$4t#5f;B*+1LW725E7$KqWkY*Z@BmF^rd@ylstA<6md*t6HZ=NGyFZ^6-Ld$iMQ zuT8we>jGQ6iIH~YU%p*#z0{3gDc{dj4wUbg)Vzg8yT!Y7S93A?_YiTJp0!icU**pB zsAXf-Cn>?r>%TWh1->U7B+9cP3FK5;N1vC>Zr>x-3Q5Qm20TM0jYT1R{Z-wr6iFka zohA`lapc>C*Qjdm+y?BzM0nD>xh$yq&mweipl4)jWW+*OT|HnwwVf-5kVeQTRtfXD z&r?s$2>7|3!^p2!I*J0wg{D~7gFk26w=m##rO~N*#qBowuO|?WxR|T3(zu)PufMPF z3G82L+H{Wjpt@e{dzVoprV>ssQ zb%HO3o{W^Vj{{Sz2sqn;GMHwx%Z@wa+%vaMxrW9lvln+IuvIZ_?kW<#cR?adRHdY( zS`H2m4-+=4fsLtpd47=b(tBvHBZ~GOD%xtU&XrkuE%Ko0iszH059O^byM;VlDSjju zS)+PJ6g-xul-vc?l};6P>G)1cLzA48L@w+wk9s{(Y=~X`w&-1X$1!kmgu-3`H#Z$y zHUX}NU4IvVp2vQf{ze65p8nNz86K*TT+iPGWS4uc1L6%~U4fF8+EuF9ZwKT{G zBMnBQvaUDcHd`Oi96#L$i_byFYgyvtQyp&ri*Tvi;J~<8^6#NXZhQxZ)zSL%ti_l% zKaTLfsV|prZYCDK#Wo%Ph*ZKGDeN9MF0Bj}qH=F|mRrD;@yc>=Vx{IQ)p6}ach(u% zGlt49LjE;fP`c3)CEXI;GQZ}P+6c~o>6#nTyw9!B3hC_4{13;|Z4y0=aqi*2zk90B zHtJrb?ml^>$_vk}zXzQK6K`2+%$K-%`}(-?ldElMg?(oA-KSl*(Qn9siZ5YaD#7i4 zD7oL1R+MI1^|ipp{B7&29Sf`9=Acb%Fc5r|jOuXejQnQkJAw8Z0)nFoy*naN+>f6O zWyz$jb@I&5EN`w}zEv9^k1Cj>^f@$1JUZgDV^0hjwB6lxK4_nJ?i%bBWceS`zH_); znH8&+WzYMpZuj;{)tm2z>D^jThs=*eAHCx~`N>gu4GebQwJLic$kx`Hkjn(oU&@>S zKC*r{+X;BJqQV}C#U2%ioYeJ+28$?}I28>|54S;$8iMQtFk9(lb)D~&*8nZQf3()C z4Q59ht@8GgRII1~i=SUqwDt!$v}XYgC1QYFF)+JsCMjIG+u2$lY z78&H5Ri84PL#yO zS9`*Vd3hY{lP`yix_?TTsi2#m7wJ_h(f~7@i~)^_+}_?!P`~43Wp2*a5L^2nM|AHB zr=n!eaxe)O8(YE-EbH*}^mzgxk6&Lw380z{7waj)Ru1|)?mWQijuy^3e<Obj)g;5qvY57P8@~Zd`mH?RWt@y&`MX(gPYLf+=`WNcE?OsiwFycj;V^{wZ2!j zA_tt+`FEPfnio#~avWO_tLl3u=dzq`4KLX%Kha?!N@_InzNP+(g0n|y;t)iR6ch5U zTAL9DJQCMXTD9T-7%*e`c>|t1T&Q+@47Xo7;#HG%eNnVS6az|S@sl;oJQX(*lcP>4 z?hIrs8efZW598pQL8`XDN*vU@4$nrTLgd)up+XTsa1or(ZGK2MY0J0EuXX}a;=b}0 z)sf?NVk~{B=hv?De3*OpB`(p~CPh4{5?i0UM!p{>(9=q;_p>-5bQ1h1@L&ty&n{kz z;pVm$!3*&e-*_0?ytmfgT%kpPewb^C;tf7=)H-UK*Z>UX?2vTw7<98xp*tjSU^q11 zng5#k*$?|TE6?uu13}Z>h=_Wdl(g?Awsxi|GYzg+$OllKa5i5}KAo6C7*=89NBq0M z{5J4-Ele||_nQzEYd2X~DR8^yjaaP~9nSaXM8nfpclY*0g@vmXo38+u;w0gHMs79- ztWE`@yLaz5YeOl^FMr5mdfI)OVf= zv#u?O%lXh^eoBpriTUBsN9*#EHdW)x2Cw(c*LB{qZ6QECl%v6drENJfnXa&M&$oW3 ztD7fiF_8Ln@&(h&B!BB?4S`lfL6%U7+`LRKu%^^ET^16ChFyT zjh0HbLFY%SEW9=L2jlnoN-o68ztj?m@z=&85{PdmVe4Ui^rcuv>c;KDEa{w={Bv~aHFl~k+Rw4b1B_8oCEeoT$s^@kyRYe$8lD?Ok82a#w zbz1w&ldZtJvvc+CE?`qxJ3Cn5#VGL4E@+d$G*a`SH-XNRjNmfs zu5ybwu->iCvhb_azn@Dd((q3B8zbB`>IF&=z+%a1kuy5oxl0z^!2KF_}K zoWa$*@u>JI<4n}e*2-X<*wmmGe%<%W?o( z(#J9*r>!X=x?n*7cut-B=ja z%owvt`~;;NK9Y5Zig!w>kz9m+S7*B(q3z z;?l|*%}TfYOG4OJP>%X&zr`Q&-h`HEYv%7nVfMK1#!p-O-AI}Jc7ls6zZ}VT64qUd z4ib8{LR#Me^{vBJtGhD&_V%PvR0@O_Xcui0cw;jxA2l*zQeu<*0dQqto-Rl^;kH>P ztlX`0ilP;!^dC!2O;toH4S&VF3I>!{i0{d;{B)_0i0k%0LCikZ+tUNN4170{@NggC z2kxB*`oWM(xM1=+arz-$bju(A#xR-=T_K10zPRegKhm0;AS6wteoW10U-qzM1Mn}g z)o^szuhz2C5_zEmjR5)#6v8EDSoJ#HZeJ|6JAB`So4Ivw_S>H- zQXSLd{WtbUiQR#2jh94GXurMjo@^^pVsoPWTY9@nItg=`!Wfd|+x=e_0Fk&y7=P=? z9QHB;76-LUz%gB-L33op3vvc@tAhvFy#hA?2FVPAq(S^4_J?AiXy+-r#4F7m;9lwo znt`wm>h6Q(94HAM!nM@a0sLlu1CYCvVaYj`2$5aLB+F1Dj&!Lplm4g4=H_N`b*_*U zVFwzA*_vk&$k9R4}<)t z2Tr4Glg^FPDUD@4R9OTyvNmsP;i?<>Mmy6s%~4uX2O_!BGd~A%0dkba3!(K7zpadi z^Stq8qy(^nyFUw3DS^nh`}kXyg6uwEw=wInS!9Fuux#&R7?Ti1wb@w5rZ+gTKl z+M1f#GnujxEP5q9pB%r=dVYI)v0L~g?c^W3mylaD>pCUn zjU3CLTb8_;=d&le%=d@attwbZj-3l^KBmGT|2$~ijS-8Vho47K!N3@H2cTndg&!M6okFDCec`msS`Cbqi!y+e;2t3=gL5#a1*}F`;?Miy*^Y!cIbUbY zGm3N8W<2wJ%l;)tCP4%lajbQ#B&j;ThE}m^ZOqOZU>%7(`T6IUT173>3{w!iZ2x|g z9WP)O83kfX5$f~?~e}zY;apPg&YGW>*d^IA9T1nBTAs0Wd9&D5{ zGaj5d`C#BiKM;_n*Zsd5vH)nvC|UI5i>IFko;q?V&ih+Z7ch<)VE` zVt7%Suba$OF|k~f_m%xu1f{4TX*zu$dERf#n)mJTPqnqAMFpL3LJ|rw4@a@$%FzQ>;t_A9WX0E0E zQW^j4+g;Fe4Tr^dB`cBhb0U*hEikp7-JH!h1S**K5xw5znAUts3=~b{O?UOgq|ykN$9UDAHe%C$8;b_S><EFd7;f{1#QD-wlIqr#R=J9i~+fpU& z)0xo!wXC*Xv2b8Jr$^=8w+UM7Oi*mFE>kj)(0HMID*==#^P7miwm>hmfsdB&3QERJ67A7%d2fB>ZLi``?e=q+#@iuW_*QnXO4jJw=(lj|nK!s$Zy;b0y8jVVon)g`s$WV5` zyQ1s)z4Z|M;|3zPg@*TWprrW!_k$0)qF2rI^z?kwrC?1NU$PsQO?nr3gW#uoje-5= zA8vm?GWzxv>m-|)=4U?mYqIB$$Zw#z<#&nxYIMHR`ky#O0zw&*0v;fCSYC@E2*tES z^#1Aq8<}O~{~_NZ|1bFleu@{DHpNBn{0(`Lz)lIz?JN4ZUGSwp2)qADY<^A`;qjI` zi;H)@|937rwBKPn)z9|!_UGR?PU?WALL${MD0L$aBCMJzuyj&~kkyTi9lXJS`EqDd zN(vQ_V4Q!n3bdy(k9!9O#=$T1qfXD|eZ@;lL&JRZP7Qgik}RBe}9xdu0{mRaiUcJ(@oO<`joG1Tlb$+ zQ;M-_yx5}vIGA7>c>C6Mjw6IAK(jpl(*?D1i$Mx$fyL!rIQnSn3YykaQpXOWr6x9y z2G*Azp57bM!+SvCR+TS?d0&=K*do7m!sf%t6;}Q^g-H7IPsE8vI=3R6YF0M$*O z>#*G3~ld?ZES7nDj>HN#?|(tXsE(XorIxa#!Z`Sp1 z7|D5KLjyiBortl#|33&N#ho0D-;7-IXG@#IS@(qPXB{m;;c~e-04w7^k%H*c((>}& z9EG(Rk&R?Qo4}z1082Z_$jRxYK6mXAWoPeHlb6p;on9ki5Ep@*k;q5W{Soy+mgWMT zAO7c$(^jMRd7%^GdX4XuTlMOynM)v-9=OAZ-oksOm6h@AKNq;T27zk?XTbq=^7xw9 zx>(VsKxSilQXs7_XCA^G(7$V+w=CSAAP=LSuz6fzi<={K=Ho3o$8Nh{j0bP;rjmkB zHW940lx#m?keu}^fyI}DHN7A86JLm!O~6Z6eDZT&W|E(Lw!@d%@~`_Z;sfDMPEI(t zr8%Ys*hYVfyR5$cRn9vALt*H6HIn|z`SmNA`F+wk(D2J_o}QkUcl65f8YETUys2Oj z`^$qRo;Vtbe%sQjepD%7U$?j7J`ENM9d>Oa|%51(8 z;^KVso*QXbJL5&iH7*;`+|y(gO|4jS{{H^Cd()LlhV^cC_t%$qcT=_0)P5u;B$zL+ zuP0o9qQ=6?3uBxUzKdl1E)Tc?`?1N?X zZsUML|L0MH45tY(3%j_$=D${NTg&osC*ZP%>xt~FXdgPA-%crG z7)d;TZthcwWV;Z>o7WGTQ|_dqplDh>zv<6cz6yNRTK?A)4eSA7UA}{_%`2hA9=Vdf zwudNBPb?Ru0#vCv30}s)JFl_!vBsn5JTQJ$2Ib-bYyKq_V=v{o>OUGF0Yd`FC)sMp zGEw**p{IcRA@K$ZGw_4T7qOd&-_j}LMYgQsP!F<|bI_nt3|-^2Q9LkrmGgQ3Gl}nv zYpwHEA^ZBq3RTifiOXhJEQr}Gq&+|07AAmOrXv>9>3u(E+8u0u69p*1Fra}jZAub* z&Lb?Y(3KV`3oG)UwFi4MY~JbWtp!(Genm{}=IGEH&N>!#;cNWR11Hi4S{c^c17j^A zcuF#F{0lg4^mcyoWtkv!)^pUbQ*bArBh_4UAKQ}P#mtE0BfbW8mWZ={yGN=_s-q+6@fT7@ws)6I|0m-(mTUkAzTzK~?chBuZGA)jrGF>=KSDaoyB27Gqz<*n&e^IW zbWUAd-i|W@ofG(dc2jh)k_Gxv8$*(b3&JHf`+)QW$Y9z5=$YfvyckD3GNM70!26vn z?t7el-TuTitZMI{Awp`adxhm%dQOk9&m+Nny3TN;Uix9bhGIBDL

      @Qiz1dDFnvG^stLK!Dp-=(XC%)D=`d z)31gc0a!{Un(s>BKh(+pi*&%bSh%{n zzaqLHco_Zeqx!J^{QS10+}Vl?mdIH1{q7O=Y6xLTe;ERqu$O#D6GRPcH}HK84`P=X zl)Lc8$H!+0?(^_yUS0#y^*K$RWt(5bPiedfa5+AkJuV(GKlQu18wMWY%fEgF8ManX zhW+rG4sqS?rMRH)S&;)PunH5;-64ak{Y$o;SbxRL_(RY{=%3YDD^>S2R&?*z zQjk42@mtexM-6NT1pOk6O+JZ%Q_3n`-0aMZiKDBg3L5LUeE( zTn=L7g@q|CTVEVh{rKVfZ#9ty_)h0tJCIq0wSjb<(Zl1dNgmVM{Qi(|#$Hh8=!*0N zfBi~0Xs3-_#rk^q4N&i}S^dbU z{cEE$*7MTx%>1E4?23&R@1O6w&YTfl;4YXSd1{6m5~RlI6Z~KqjSuopE&!z)S-+jJ zZTHpM|HA^{FM+A_%f17`wm^ng`XV+;e90)hh7>61ES#LI4S~yjyf$y=YS6_?oUI6D z0|#COSQojy>#j9F2GaRJK6vQz9vdli1f5jge*g6rG3w<%CvmicbrMG)EQzn2_{4)q zBetW*bV}Lq_jO`Ky-ms!s5#T1O^myL3M}tqezSh@dt~V||CYIB@MqU_G%NyIQ)s{K zhjQri;20aOWW3g3?Bu3eHT!mE+3NCyVksCTou{|ME<$n48=Y%5x?|5QB>VFNK64mW z?yzb>orim8)MjeK$XflKk_$#VqL+nI{7zp;ThY|s11VOk@B|WGNg^b6A}Oje%%XB} z+KwAC@NJ0SxiGxqpEaEZBq6MosC62@ont@PS7|XT7|=TY?%D7MiGj5JV)7Ee-{S$K zywct`2WmL5$N#yZtLL&m?9?J$@4co)4XQTygBr#Yu8t_s`Pn*1AP=Cx8TM$q^==Sa z^KJV2XF?}mZtve@U5foTJwu+dqk~-)bA$ZutG8b`d_1@mLk}CWkgx$W6`8Qoe=ATP zeX`n^_6h5SNPutXo5a7RO9jR z=;ZlSxzXTbFLQNaB2^mC0$hi`*fM#~w>Q&0_l(&9Fa=HHSc=>2j&B%Gq>BFKOj}|Vz|;+w zdwb^s>w=2L1y1%NT2qwBpbMWk+W`L&D5I6`(k6a%Ej_kijS;FPiTUA252{wZphe-U z*w9-J#u+wUz9m%or$mS2n@pk(|X7984Fflrz?5tTj2Ea?D=gh|Y&bgbW#rT#ZK0cMQc{ucF4$cxc!wmDd>(Gzw#C$RKF2-&s$dtf_ z=G%$hHR!raEPV66hzQm33rCy#MTA*8GNaG9+dt>4;d|iy$|QUG>2V4FDOV|0UBltO zfXTywj{|~r!7892wEsOLw^xI`Ga-bmtqAoxrJjFnYhV4A^WuiowOGOiA_2f=itXSnA`FC*oG0QYPe|15|yb6cicKi1A#wm;)hCY_pe#>9d`4ewrB)9vb zvEsOKe7pSqLecfShL@)&^m!}aY*Y-pTjk2HS&FSu5OxjN8w~v6Bl1YhdWE@uW7{?- z0+v@{%1J-c8yN^)DZr!@J#S5h}CII|UesVhtbpTHY%GU*#{OuI}e2OV*QK$sdS&z7cjU~WGf0{KAwmY9Ho z?b-vG`qz$EEeuH?#QU>nV9(a$OHeNcE}e>=?M}7GV#_Yt=@l~gP}U^r!7S59$Hc%% z2YnOOdR?eghs*znj-I}>Vj|c!LY=R=Xhtg6IJ^Gq9pV7V?nlOk$A z5Fo=Zui)V>={{d3rn`CFwIN5=zYq)y1z3=jyDM)wK!~f~wNqFDs*E-n-&s^~&Uk>1 zu0)+^0vU$koY{BO`!%;>AQQa_CXzz&oY?=gMX@)G6t(@`TF2N!ec0UQLVwnMVWy45 zSTLoB{U~E==P4akLdqp`Dxa->r}AOcUY-%xPQC_Pmq7Ev%eXW}6SYm;y(P ztX^x#TRHMWVHE7zs*^zyhJDYyhR|*b<%SQ#p2X+*yDfp97^~WGlRQ(k%ysCDhPfY6 ze==JO4n`2d6gL;_r*xSMEZeU9K?yJj(-C)ApzaktOyXHu81n`{Em0kb#mxr(H5y5m{Y# z_MfW8%|byuy?xOr2~7D3l}<`wxCf6XQ2JHX(BQmt2ak&C2mO-q^W%uYDl1mIIT%z? z(rq>x%s{#=C&zME=Uv0&GU^0yF^h{p*gV7ZUtk36<0CgFoBBF69vLTM+z-c|FEVNR zuS#91$tm0-T}o4)9mF%(o9Ihn_lB90vP{%1%OPN=ja^r*&eQ*2a(r)Y_vl9B@x|Efs9{rSP==HO<;473*gThF-%%O zsM82r$tMp{o#Etx%mb@c@M|^gHK)H-X{onYuUvNaG0*cU(r*(I7NYWs6-^ZC{Y!k1 z`O>@q)xY)I!yO0H{;*$tYrc=ZJ;rbNyW7>R;_+%7xvYvG++UC-v#;Zui(@7AHz)i} ziMAs{o7sEV@E`csg0E4(f>HBit49y3iSJ%-q!+4U_(h7kT+pi@FL=^Sv%vrvB*pYy zv64hWd*+fY-PL97`^UaGlSK1+j;?r}3e-n>04_-1qI{dt$3v@hUzQZJ=ZaLPKqpe> zrq9PLeR8BZ)>iCJXdy6V;0!^Z`o6E{L9i18VP9j52b4_{1YZD!ig)|Y7eA>k!z}*ih7&!$Dd*2USx!;LC-JroAKiyqO z>RX-`P3kbpB1dhVotM9Q8a?o0A^vNciF9N4x;mm#`hjQrxb6J%)srM}K>OWY>!&{$D>WX6)OApWR6;bl>V;0t#_9(TCQ# zmmB-7Usy@lCxeOr)EIp_m?9Vpu59+!jn~)PjX~mM)%Jq=iy}5#WH+(=%}W|KP?N1r4v%R)XxM4-nHX*u73tL>2w${RNpjY};xfr6?CRgf8hv=BhY)yvle#G=#QS z-|H#aK7m^TL67dt+S<@Lx=M=o5r73T=_%JHX_$r>70k7;AtnlyydsON`+lf z6};EmGEQ}VTX@FQc=?GzU5t1ml-1&`9}Xqy%hhL!Sq4aVxnQG+Mjh^mOKi>R%4^zw zq%iz1&+E+0R{*761X71t^2p)EV7Rt+rFkPU05`yI;S&%PIZq~boK@1aeZ5VL!cKj^ zvM;gEEmS(C1y_;UU44qTCLtf+FMv{wEre6&0owmWlw5HR7e2!B4PDkqSOe!+2&=me zIyhEwiwm>)8v_3MzH`X|r$73U$f77=_a1_#1E%S!_~N4t%8pQ>!*!i={j6`(7_=>2 z&{9ywDLnM#o8!Tcw`UDf0yZU~mn-!t!swaqrrUn%zxRt%J}&PCUw*vrhYaroDq+X` z-Ae>-H}*r;&oBGi?FWLEgHo-?DO)_*F6I|mn->Bp6fRs_*(QNxT3BDO-+s@S4X6I* zUm~2HtgfuE4t}O)pCvCE!N=kcQEdRvJzp-`M<6dvTGN3sCKkv(L9a(eo>=&mZ1#Rf zRGYTMlVPv$JIT-4YqY>doy6O};Q$Hxe{W4E@ssALYzX@i56^I!E|L(!p_1pO_ z13gI>n3b#_J5g;Z%UpT-!d0}B2l4QKIjPj{jW{D3WF-i(A)OaX&D|>8opLJ$>-e zpV8qx z(-vw#@|lDdV`Jz(;-Or53-&Q=o30o%bN(-%2531lN*xhxXgito5&ck|Ah!ZTxX$)Q z@q0CwrB5Ob`9ZSfT9fY>lTGRj@3l*v`-BdOsjz)(hUoQ92|<-=EcU1Jc9)t7+&;v( zQ0iXBc6H%0J*Dmww5ZdZF~={6s1wdt^c;$5WEx9mRV2D%3+|EJdrPs{y=h{l6yB-X%L2IZl;-T4WVwHRpG%p9d;^ z%sNGM&YL3=>*fqi6u=#V+4weCC{|{Gh84z_BwR=lTNrSYAAe~au z4I%;}EewcsD$+5OsH8=AiiCr74~@dm-2*5cL-%m@-1q&Q_c`x3zsSt|WAC-s^}DWR zfk&td_P!~pz08!{~#JctFWcNFJ&#|Hj?WI3W zaqhKRK99kO>;#LXop|u4GbtmRxnl#98pKNaaUX*EoA#AGr3H%|HQ5oA$*oCRN-9W9 z(Dugl-poLKmRWPaS*662x2^Ho)RSDyF6(}Vu7n4cGw=^ak&5e_J;O^!>>OyP9&%hMajN-uHyN&}dfpwOZ>@Ep-MwwkvI_`7_KP z26m1n@9lf9G38$f<_ueZM+I{)obc>R-IZ)qFj!qdJ80il4*VFKUh0g(^o`YG7_z_i z)PKUj0PDP##~4(y`~p)H>fxn<^1{0))J+hMdhnW-|83Ty{2le30Li`nFfO@6;y*_gBb1MB&3n|Mu3(U1!O$mMl=rhnXPk_9)c+<`n28alf9o|K_5YE~vTeXSrj z>HA~eo3=cRF_~|}!`};*rH(5^?6Lg!p!pw%s({9cX-Elpg?`Jqd%N+aT^mKBh~F>< zw*^`}@_uA=?A-P9(}bw?`qX(J89e*hI=N2ooqx2BI84!_PG?wv(OF`-F@lD*-Y-4O zN#i~C>R9nBAOcq_gQ&mgvN9p{Cr6XQhkOOz!e&6P*R8PCj_bUO6NPQ4|8HZgw0em$ zj?2;lfB$7x6|((N%Pev6kWLV}uuS+XRf2WgC6;azXLnwlvWW{R zhS9uS^WL;dglJk+xKb8oVy@j0u^YH%o9qcJ7(tVb4GUzw{+!|(v}FUm6NBOc$h}Ve zB4IOM&{M6~)l3z4akd)l1{uRk8AMuOrpzT~+CtDzgoq}l<5Ek69wu4>Z93~NZ^< z{xi2cbSlm@(^Qy~UF`b6{^~%SVDlB;_QN+`np?vk{<&Jom|kZQb>SimgL{-!gLk2{ zNsbbuw$wtfXzPsY-+V6$4zOq+1#6UPKS5FvIhq080oFg|XV0i3Y5608yvcs2Wv>Wn z%N>Ah!Fv9z(uREN56)*ifUd z$H}d&0t{H9X-}_4jl#kNq?2l%e)QX1i2*8#Nrub^&}y0Ly7%0M)4eZ6!f@Kl$#R`UZIhtudA1TB<7qyPiiXBb z$FZWf0MDrxdyIny&46c(@8^mdSMhUq4?&739=f0c7X(YzNZ7p8Yr*i8N8uYH1(;in zNzmGPYTEVR3|fpRQ^QpTCTcm)H=4w$vRYzmd$&KcyI=omS#8iev5(4-97JZC3-8L$ z69Kd#r})JM^6KK5?f?B#(+tZfiVHEP@Vk0IeFiuJ28jS#9f*{1@67@<4(3%g)N29U zNHIcx3G9-ZAxE1N%Rr*{>*0H;Dt)t9;vz}b3c`k(*pTix+B3ld#IUTHP6>$d{gIiq z0pL9D@<-otf^{(O(fvdNPRtr~jnTP1t@0LOCUh1#)&G3T3U3RmwNx5Q7x=7iIG?F7 zYcvOu^FlK-_)}w@qxRP=E1Ejy>YSa31z>>70-Q*7`vg#tOWD?X9c`&joeJv5x6F`k zU7L5S$;M}EDC4;-6Tpko_tfy523#p#jAlqwd`B4Lcs*nt4I4&(Os1`FfsEu;Id}g9GI)7Bvdjr4phnr9 z^3vX9nRFM)<3iek=b_%jo&E{tK#idXoJ!xRuoER^-w+J~_+bQK1Lguj%Y%Z2#kEUU zU|Uo~PIUW%;%2+1$7NR!!OiN>; zK$|f&uoJZDt4LJt}%rcJ~Pb z5&1`utgAs6BFX?yjHDBEb!ggZili4*O;Ztk%ZFTFsoo`n zomPeG7Hhr7>XX9E84!M-(!TmD1f6>$D)neWk!v}|%P1cz z{r*kBqH)p|LP1R(4n%z&y9ZRx;OU|QEB#P%9}wGL@!Sf5Kl%NaiogsDox-07hTqX7 zpjELJ^uTf{v1f@Lbb72+^1PY4O35i#`P&aLZy@HpDQ&{LZc8X7hcr-rlb4xQ9HvbU7Ci${_Ng6vtY{bBssw?rWQbCx~Pjgj%t{3 z8#fK%B+=4>bS(v-`X8o@9EaQy6cWKf+-Dl&FIp_QKCf zp3&FL4-s6kFux>31)S>MZF5R!XZBur_d7Fao054_bEy@q+o)XQ8o&IE-3Hcxjq>LF zTt=Fty*VSF*Ou~+FWq@|0<$uE@4YTq0HQ>&YPv+%j>ps~dJtfJP-C0q+w z7j%P;aM)}`s7OX=+lBynrW^jawJ%88-LdozuS+Rqz(DB@rL z?ecgV$-bCboD>LHWJps9i%?>hs9@I4YE`I zvYf8lLa(u@QlkNb?AW2@`jfvzH2elnxM+`sydlzU{LPmN;LgP?O6=ukuDU?bH>2#u z1wP%geB=q0BKNk)Bp9cha}6nfskticu}tqYUV=%%f1@Zle<{42NJ|^u_O~~2Vvow6 z%2|3CJpMVK-I#%mboq$-G_`~bLe{rvW(KikC(8Sd5vUp2)sbNz+}Iv?vml5B-Zc^# z|GdhzC=dG6!KPx~?A~7cx5udCM7~e0ilHjalm-W#aEm+D^>{g^v>YyKF6>k$Ohv|N2n)Enpt03K~{~WA;!9&}+`8s?rbDk2p z;-RmwOO|p1J6wBtXjWoNVhlY6-(lAlr0X%6H98dy2Ms*Lv)du?h6!OmMIDEUmb`O1$0u>IZPcRAeE!I0_VM07)he=Ku{Dqg5R0X3lA z7Vf8aQsRXZ)9^&cGrpjB-nRFy9|XodIUb|S?7Xi(-~KUsVEOMSYuS1nP!f0+CF;4! z;;}i7amMxQ;CnY=ueU-b;{LG85?vm}c_x@dg3X2uvp~P29qH7kI8BvROxEsQa&X2i z!2PDC=6>wwH8&OT7PArfqsu9tW$MjCFFlU8OrAIS89<-xu7XrRryH~No=#V87hYh1 zt_%GuFeYJ+E^1-#vOqi45oKQMzDNz5tfMwl;{6{Mz!iV^ive{R_N7?ES`l?XMUU$j zNfoS3ULa;)%t=5jC-re!j7FxgN82ZohU1@&?;aVA#w2Gp9}5x{55y2?A#U!#L_!IJ zcm2yU_lwdu$~1u6UQq7hW_u=cwEqtD=B_q+b`jktIhcwRgjM;ZQrM`1t|LpY>ym~2pd*(2__$^LdF{u%N@Bz@0xV5tZPd)5&@SrQ{I}L{*&R;( zrwX7o!qgg~1z@TMi9uj4@VHNzsauf1%xZ3Zdy+ofQmGJvJ+(R5Q9Qj5I&k@s)OMfh*>!$EI|C2lGTX@e(pW}2AC#tjt zw`IY6-V)K^VyD)|W^7Fpp}YZaZW_uW>z8!*Z3{&IW&9IWtjuS?UeN&hr*E9c6t2-t zQc$eQKE_~%p8agsjDTC46(^az_RyE|uX!3m%?WhaAk3xplp@XG1UoI6@PW1* z8%AB}vCWGpFeR|b`>-X9Og>_7H}Go#XM}pm6`fn%m1}^=w)7RnGSkI5FJ@*A2nh`9 zF(}H`TekH<=j#>OA0NH&jYxCo1ki$gZC_9!;d0f0OyFLIW36~+?O+gt^4PTAxnDAw~z0Cnpp{#`_ZldO)l#mwhS!vd#--=gdZUe4m zYj-YK#B4)(AgrrgD7hlX_{{*xd0GmnlAAk;KTRDw?5~{Kv%Bk)*gjtj}_VE)0-2_7m=_I={#=zL&`N5g-xrE@dzz> z=)9Qz_GL&-aRC;}bTFag)RRtgIrsez3TWH2x{ds@ADBYmGu5tL{BvIvcgn@g9=MB6 zx1dj!6EmCDKYY%oE^!X^up6+vnl`9?{g=ps^+JG!`802P^272%N3Dc~s^Sr+UIncS z`A2zq^!!iepF~ST9zMT|Vz{2)J4^YXuveWr6Goq^I%>BCoZGos>Q0+p%!=<3cfG&J zUolirs{}k(?D+OBM%VrPh+02z=_kS7NVMA?Xu+>zPu9Y%LH92tmj8|rxz4RXtoUL> z<#$i!fV5#d>#1eLB<+VQ<`|LVc*FprEu@#0(T2i_tpjkuGOTCHTC`DS4SsK%y&MM% zxg$uSG+>w0@E{~PovBu~lf6%yT1?MS5P9a((zSL(ltkP8G`~((*HgvAV&JWz-b4xy zuZ-7#-b}l9+o6PdQ=YZ2{}T1#wuHjD#qaVsUZXc`p^_fV|SN?BD zlhrm~<_T-s4Mq=!;#6w9>rU2k!@wq~CS z6A-mp&v!cNN|gw;q=m6l+lmXZGSKi^P$zn%D>R4J>6RLDcviSyd8!@JCiUN0F|$PY z$kkp89dFCM&+*mD)lkrU;4pj-kG!THpAxbHPPcu=V3d6FE}InS<#Aw|a@u!`oGcHm zb?G1UZyI;Gn)=Q8@nH!Y2`s|i@;-=uok!pD84qGs`6&7O1*|+#((m*mekGzdP2`Ai z)X80z{ctsT!D^7544E*q)23pBXJyQ|HANFQWm#+?ANy93gR8wc} zP6IZi{T*p5o&Gmu)Vln4#Jrj3SZk$I}#I&{@^W)>(gg`TC;8|>?43x0Rh}-?wRh5kXD?dXtA+99a$4$p3N!vQj9%4= zrZ9f=L4U5g8E2n005`Ltr_vQktphR`azwCsA`|w!8MlUKavsowDD>Au7ul_fyiET+ zG1BTOwEoBBsi9rCsQ6n>{7azGW$v7eOP^1!B(hv`to@ySa=u2K8l-kCz>15AdY+pt zI^$MhyY%zjIWo3kG%WZ#WOHD6Lqc|j!2h(@gLU0s0)2XP|5DtJFh$(WA?j#TP_ENM zhitTS$@oF+MV(89J85Gwo(q%KoxXQBM_c9mWk&i|Z9p}4RF2pCwD$33-H;cTmiceZ zoM0HHBAPH9g|C9aL{*yuMs$gSkXy8&)=}@@E7ZOI`&{}xqu)%Uujsg|aZK3#<-tM& z^YE`tKMSK}FU5#D%$wifz53~oa(n9fRp2Q-7}E3%miG|-u$ZxcQ~4!kARB$ueUt=a zs@4-4yvBdB7=U8$zPF^xCuo9YV}MmtQVFFAaB}w{d%}BKdA5t2{&r16G}y+rdz=vV z&FZ9~t@ z!R`JVPL(!D-b?4~c&&|z>j~%R1}lMZcbV>BxXgT6ka4wFagU02P_3&%iyg!VZy@e= z@)WhF?YF?z8h)PMBrm2)7_u1s-7K+MyG+7%x)+76Ume=Twn3B+)bUBW z04(Dcl}Ls)USb+cYUa(J_gD&HNZ)7(CcvRJs z^>RJyf$Ae-^uB`aTW8}c`Vgr{IZu-}?158gQ#FA_7G$L?MBC7vZhms%4vWNQ(QlzY z?Olk8e?&KmIvGH|zS;XlLhF@aV^X;K6BZ>GC8>CqP5WNN@nUTc`IX=FeV@&~i3hdj zHNJ^K%o!5`;p4bgI0R%(R<-T#s0@ymCEqmENi<*XBvM0GH;)jvI3?%n*l974*)48z zhn59!7;-vIr4@RqUa4-0Uksky5>^XcxyAvR>vEPj*q;IY=1Tnch{s<>Q4_z)13eEV zWwK=g^d)S4hI?LMJHrBnQ=op{oR{UH4(jy@Ewz;;{Fz zUiNM5o4zr{eDF#5`L|#iBn%iq^O32W$5Ds(h)(OV`&%H6uddCT$}HzI zLHH)sJg+HbU;I(nl`^~fq2C{syR;VdAD522)%yXR!w~q!X@O*jaeUfxyt%1iNV3ti zK)KR!1WW!ZBkfb22~9X7ddqT-EZZA>i8Za9*x8rBHDHc|9=5A7Kk!@cw@KWearq&_ zyZdzf1}oP9M7;ex`}Np{aS8GydE^_pp%|{GLDxPc%FveKKA8q7R6f8>#scahDR+6u zJL`LLC2_bHAG$O^X3*J+b|bX1pVIT~36d6_BD!0Vz<`=&%{+H98EQ=B$)YVLA`-zl zI?$2p_?4JBl2Nr+v^L%3ecUp+_oY%*b*#MeE8I2efoR&cwFq+ewx`8)cSfz1-w6Di z1c-t+te=fLL*r$gS{5pA_?@G?zl6dyxzELsf~D%NaNenz#J(|9VxZiW3e@1&jus*V zP6BYo3A~lU8H^4sXn=@u`H!POBusE$Z$Fl<7{p>g7ZC@UqqHqQzco}-qQD!*m{K-t z-U5p8N8Ih{1`l9R%DOJp>-Zi0DoU!Y_w52N2XYioFufQsK8B!tCCUs;w zw^Z0E`9_YGG-XV2M`j(KkOESz2K~J`kh6!#io$Nr z4X!|)tbs#eoxaxALXCRVAV1`e9M4XYOIWsP8js)D!6er6r@EdI`*&=xgw<1WQ4?jR zS#SsGv6Fl)I)fEA#mdb|yoKwpX{5<|)Zd${5Tf&=o|UOK|SEUCwW2Pah$^IchN1M}`hpROEU z)-jlh5GPHw#6GYC4bT*i0NX_o#>CEUxpVis)y|QvU6X-X=1MVacNnH7mY48YNPQ|hy>VQ}_^+i@Yv8Je$Z4HkEY3*VZ? zb>qwCN6~sYj@%@?II;Rtu8*0Wn9=@UW5{Y}X^cCdjM>BkBB=(zJ6!eu7rdLLNyj+s zwgZ=e`3l;%2CV@&dVJ~UyvBX(A<&6PJgoXN&y!y93~cKz`(jj}ji{sBnnBskXa z3@oHe_@MVa{X>oXX9$k%jO7P8t@he{jlt33m|eiM#K%@-4fZVpj(Em-T5#l3BTeq2*(USmPrTQ-`Tu)kDtsd(UB9` zlh$8Ik4j`2Bu@OH^NLIFjtd7EoiwR=I~hKY3q8BKtykPw{W3Ss9pI3tNd>&n?k1H2M^sN2W*HyCYoZz{Rvz-H;IXX z&Et3H)3uB47ZkW{KU@*Wn8?Us*q8Eh30{u_GOMzy1^xELq@>%<({&7;JuB*GkLYLg zU*bchzR^TYWIt}zeX}uX635?%nc1AWcMc}T?OgE>MPc{z`~wclAKWFltCgUxK^xU< zu8%79TN3!nW5&W*&0$AjH_r4H&JOW=;@|NERJaBzn^trDF1Ttk*I#+=crg|{zM94l zCM)Fo-A|N~VK`2_Dc)U7vOx6k;;TvF?&EXZ6W&StO6H$4mD_kx)#t;nsVRqWclylgLqr{uY5E)6@}8?n;&3L&q(d^)Ez;B@%r0dVf}8| zzhT}&8-G`an)Qv$Rw|@HBQ`}e2-~E8GX>zaH>xwcCnq4S{#0FScfIk5X~wf;E5I(x zaX-7?Ox=j^K<>)2(1;4VeQ=X|YijWV}k@thZ zc9-xxDC$JiXrvo==6Z2&DPf3*7t<1=E~+Ho+t-ZVS@+}-*6K_-G+wlhBJLgaz<^1o z$L34c6((yBUBA!0%8xQSR`kPYe~5X@YOE$t!r(p>){5#nkPQ`XB8ZK!Ez!aj)}prQ z47Y$K&wBT#%S|U;dbYohY`9|CQQlWQ+FU8c*wZ!Z;lM%XujWiYX7kTk>rn_?V8(Iy z6Bm+(2w+EcSBE$(yHHkB9@xUV;#39H(bGrp*5w76*ZmAVvQJ-FdF)2PE&MVcNbDBN z5JJEj^w|HPT)6$`fXm!Z=ihfp$r&HGMtmU>>f+LYSPV?I&w|6cCoTVgLt$(&jVYu5 z$=3KPgCN~ROUE+91EkEFe=Skn^m2^$T$??zeT;^$ z!i3e^&qJ=!mz&8we#mOXy|O@A{!^`n$OhN-P|%3qc;RPIJf^U9Tzcx??e+B*ca%v5 zT{cLKsVDOWmC*wU&g0Q6^y%V^;F0`xg@1B-p#MPZ`N3#%>G}sSIbBUV#j3qt?4f?G zU!Q5#6MyerC0%#IZAQf1*UpB(Huh_~?OA2HqC z5bJ0x6qC?U%G^=EI1Uk@{C2EXw@)(~7E0p>bI%+Uog6Chcqj2)^%k(MetP>+2-p%a z`qleK&CqC|OhA@P`gM_RhVi}gzKjyC9blx>oBMo36WPiHq;}?034$Qz@!}-xG_4$u zmcIPnb#fw9TIed0WC#o)+aZmvJ?K)y};E*za#;VGYd%>3}pMuNbl%_ZnN6cbQ4 zppHAZ*Jj)lQp&fUR?|~;#dfLXw`PYCazV21)*sd4g=GX7a!8!+9F?{#Ae#06Yy#~c z99|xSSC`g|ocJv`(TYYXUM~O>mp!W`ErzQ})54MRJLIAjc>cb&Rx&+azfhO$h{s0p z${Sl|-u@?mWH*1VdmGlhwn^t`gm)wB%0p~5=f=ort%V!w7Ee5K6Eaqmc1%fvh`|h^Z3YL`x#h_>M zDr(^hD{kGW$t2!H)bF#AByVm)QU>u>P<8s{zL|=h;u=3{QI31jcEM`bAisVmANv?} zGEZ>+K_;jO*bRARlqaH*cyJ7Wg5dx#v|QidQ%o%7xmqTMSBT~7=|apF8GM1Tznp3E zmjLk$R=pj4d=J~e93NcLH-tXx+=#9LT0Y}o5Po(CFzwT?v%&nT$r>GlAj1s1@G2Uf zXM+j}nFlg{SR=<)25+ccd3*@77wPG6e)AnjtY6|eKWB`3)Y(2%r8R*lSXzMCX*WBK zC${|8zc2i!f1mXK^zXGOqDg+IjxMn3f^qipMiicB*g?bsQ7DOxqdcGd zV>2Yd1OE8zBDX_s)WpM09}qBTP90lT?X^A4T^>Rh3Ff<($Of#>n3bA}F`s^7S1NjUC}poy`D_Dvb+&xzlX5S8oqm7F2{z)v7#Kf1 zxjMy(4my*1es*mpd0Fxa8!q~l%)S3j$(;;I-`h|N85pFB%xFGOF#7g~>7L%vOa_?E z8pUI?5B{!j`oFw}T|GxLp0CUteqbhyI~^U4&x6uqvqy6l1HNE#nCey3)&bxRj22x= zG3Z-kpwxC;UT$aP}pE zs9^EJH@9@DSO-nJ(JDo&l7({Kx7Q`2dwv%`2?>s~6}Nl*7%qLKUCwpZegqih*I9s< z`^Us6qd#V>L@}o@#=F^zS=2?i^Vx|p8g50D0x^E*957(nOXFkDgK{eUla^Kl@Jh~L zS3;S=q~x7?U8WgOC%@qo6!kG_>}&ohe}27hY)fKP^o$SyNfTL;Oz645lcnc=}^rB9dM7&SL^Tl4-I{J0y3*s zF}2A7Dbjib^jDhkzzbc{za}<)d3FHo^5QrvBAba`r1+EhG3`KT0=P>oxB`x#xw0^v zuQe0<+a4dc{g9^m?X8RDiiVU}Qm$COO`j@>DJa6o&Pz z^p~M$S5M+G#LWMONPv&EOp?C1X@vDD=sGCqjseMUVvVcG7}GgifwhA?s8<`K+_Jif z0_Jb<1sJz!*7|zKiwt&ffq|kAufeSN zq2vw>wE;39^n|#`TzTAS44e#AzJEkge=CT98wo%hTgD@3qE(3m!miZlOOVlwg*vU0kqIo3jev!COG+j!B$@N4VZI zIxemopt27JUFI95h^V=;q#;#~@e#Gopw*)4?k=Lj@iL!PP}CQbngI&PZ#N?#%XPTr z&cKOWakO4v2s`OO`~f5w??UUnE4GS{AX`N@$5}5;O#>FLMTY8 z`tWhsW^Z@w+TDGD?ayzD_e)rR$qUNAO5S&9&i|(~6G;S4>sFZH31$rK7pP93jNu+n zLjmej^zA7F+E1VT5*b4jRitsCjrV#5@jYsCa6s3z94Hhv_jSQtD<>Pq^bHRD!|o(D z*Ivpu`Nou(hU(KAT7yIhmYxLu;_GIY8S$<8CbNs9vG4lo7Z(qwZ+^z`W31JQyhi+tF=jp}LYn8UuPnjZzKR^RF5)52&UyYoj$Q#xGEeSt@uq@>#(hE6c&Q zAcd}{s_#nuCaGE)@3DA{kXvG%FC@Bb`jOwVu(iz#kpi*bu#&vZRW_7Fpms8$R*TjR zMoP-hcdZl4zQ({kqDhQ`GU?s$C!s-r2r!R-=r+$7=)r8FH!Vlb#OTtSF!PG3>wj1P z{)g>J;^fCHZLx>(=eOHe0JA!D%ps>?b9tOVicnfflM)~vxjI;&Ins3?=ueZ2o6h#s zZ4U4S##N>31r%@pBbnE+RT$zCH8CyyEQbnj7PB3mZ1Cq|9s;nCt2n#%O2*b+g#C+25(Nc?L^RxP zfF(WIVPWlej}hwZARP9`u7+YB=oLEtwO(t3Y<)YY?w_Z!L59-UjXra2q+9tgZc}(; ziM=y5*Ybc)&~DjYeTZ8^8Aa%Dc}R>&BX}++psQyku?Pah4@6JZ0x{pY+No0|Sc%w$ zgoLza-tO)DhY3yCZxsW&NWxfmlB{LRvL67h@zcGv;A8f6Wwm&bf%gdkNYZ!jVB+Gq zQiYG`B_{P_N>8UBLlYJQofVK)f4=PzUTXUBk{>KxYdYB8*vdu7eiA&ak9!{_cwCk@X_~jUHfVVhK8*dAUZpBFU5ouz3)8* zz_O;{{a82@97DDO7w%F1gkW?TSb`ZRFVSf_c)6}ze>YjT0Zq_4{obPiE&$S`T2zw3}^t`OuFL`YGJTfHf-C{L`u(A2uHxU{+uRv$!p4 zOTuIHV{6Rg6EYB!7S&t_Ik+~%&b|hmK$tl7ekoy3@ zla7{q=Vb(*Mr8T=6A9xYCYZ*SJ<^D{^+4fU0lGQ1ceF5|I60`fre*~}h4 zCb`8TQy5r(X1CBBcpiToNyEFLWU3y^Gz6RT;8Ws{rJ$uP*aizE7hfiES;)|F)xNr1 zunqEK1~5cbY9LTz#Q$TAlSbh{m-FV6^oQ$ks`qNDst&b`OiWwP6vaiGA?e$q+}xVG zMz#qfpE+b%ktNeId315$NNv<}5m$qKnJ(*JOmF*CL$PIba^rgWNR0+bxpUa}JSDa8X8RCR|Pi$Hs(`w|=lp6cjTMgjb7wTq* z;=jT*3dqkei9Xbmbw>u{|G=%mH4TVKfY{M;DvB<0!d+V+#{+Vb;#L`-^t5Ub9wvp6 zee_`5(BrZm1SHh4Z3VH?5ODTdmUel$7Iy-79BgkR%QOCH$}IBdR8NMNYu>C6Gwe^d zLpJI_vy;?M3L2`_CcUA30TL=H_g~BOC!V|WlLRtPY0Z;B>#lFkekW#}h>Rf*0BLLI zyU)WwaOYH>ahYXEkV0#q_I6n`UolmKK44{IQ*}$Obi!I0*Wzk*f>nac%p61l-2?MdP#^b;LrpB zKx>XZZqKp8*srC0R-r&AQsA=gbvCf&*st>UTiBPeMNz(|oGz!Br97tm^NOVHi7hr` zauQTpEooc~sC;Mw2AwV4_ivHGVUDj{3k$WoN|hWZ!OJ}TR9|G%ijCq_3d%tnbz-z$G0 z+?W<+J!aMJ$*}+4?`r%lG6=`XdP^?xc=LPze__RBRPt$&{;X@OmergVaGu$XfP<>f@G1aA13CZkIZ> zKum>iPqpJFg=ZngIW9SpN&!dR?`KnecagL8`(BFN;(Zr3A1Vzl!~tlR*!D4~!bnav zClNtYB)lIGNZ8d5r$V0j4J`V_Z1w|=QO;T0-259Ao`gY!AHmXqN+_JYUFssX%@3wlJx?N*RDL#}?gwUsMUhS1ke~h2dNMb2CgNgf7$dMz_ z;0)$A|J+WYf}+s_=EHvYt4GJwv4zBk7O>nW*zk8?O3s6z-64j%o@!9TET{Ic%Ow%%q^X~{UbxwOD@rps?bj1!vUfCWBJO6h zM0w^%z$4^^F2u|2wigAhxU(H>Q4&?Fuq%)RfiB1p6n#qwIeSN*L}%St`}gwZY+B!? zHZgjbCzO5wv0QG`&%*5D;L~!O-a`ww>B{dxx7qqm{yoC_ zQ=<1n60elg)ma0naqvk{=h{;Z-fmaqN!tl#uB{~|6^%hpL@>m8Jn97SN2kjZnLquF z((v>C@;*}n(Hw<*IinYqyQR zzh1BGMjSZ}HYt0M1nzKXjbjs2VMjNco# zv7uPjkSQDkoR0<7fk4`5uNofzFJ6iZ48wfc<|8;d| zw~Ln4K=y-)B2*$hBK!=uGL4t9LXGhAWGz7wcc0n?Iksyx3gwf z?hTzsV8Y8Tj(55eGohiZ1v(Wpq}4|6f{%arvvdGNI5!kK@`pYC<@RL0G;RL{@$&o` zIhnkOP~VT#G1&K3L1-6~?CZ(Ds0o^by$QMDFgUvC9b)DPV?QG~@obfF3)SqWm3iIt zW;iz)9JRI0%)wEA!4qSSlY3z=Xxyf%bf^6mTkfmqP`7oPUdrKeW5#TjZ06RNes~K{ z+ab-v155VKUCM;*3kmceK=9enog|Z%=w!OI@K%J-y-5+G2Ko&6aWXtQYA|Y#{6@vk zn+#@NB2dv(!EWmU(ZHdb?MW`0yPhBV!YJ^d3$F9^IGYk(?2!J7>9CPs9bSA-rFzW%m2jmo67JUX>(6JK zX%??5{b_y)T&5q5klj99!#S@v;JCPU&8Or;0=+;glrT+!LNB!d7;*yY~VqG0zQ z;jJ&aaYFGP*|!>R|MktN3`8=K-X1V^fVDo_x{MC$M~vGp57_j7iFv!XmWxpH8Sn@V z4SgUu&(e}-_^5P1>`GOQXXNmKdT;*9;VJx8;Z9JJC@*{+WU zkUh!fYm;}WLHb`+%(8Rl>&6q%9FthCqMRX^*tNkl(VqFeNynZFfr~*%GRmodyujRLN8d% zmMF)}WE8p215dUkP~)jEw%0Z!EL$ErUqq}Qlv;4ny22y^8w``ho`gsDUD;n@ERLm##ul$|=6Xcb@vY+1E4RRQ7 zf$>AFQLx60?^mIVBNy$09zxK5*3+PKx_S$xct^3p!dIe=htsJy1@wk#uV>*w>I?p^ zokj}-PYHPxeHN1y-_M*$P{u+!VDbYk!9gblT&K1jwf0l^jSrVhFnqx7;@u62HV`T^ zlXiIut<~eQysF5}S|!xQWI+NF!}#}T1~KKI zZ~77#kNf_dbXy-5w~Ha6K^+=bM2tqn*P~F4OLOrbmFLep%0G z;N4qoUK?676uEngH`p4Q`fyku4c-dvK8Oe-(@pCuswRMgYuFhQt~^=oK;vleD-N~6 zai~m!^WY-9R^$UCD5X;O3dm3W%`-vYs=gyLk^a+hU$gGlfT;6o>;NB4H(%bGlC}lb z<|`r{(v5ckJjFYSziAA*+(I6IqlfQ`Ov{&PVIiR)NX^P;`=~}l_I?x278sv6^_t=3 zlYh-hkVyT9l_hZ=s{>ZsU6Od@#j`h{cKu1Q**Y>s^8pPJexwWz0AGtV($kK-O^0o>C?Xsxe& zZ-1#C04i8M<$+Vk!fF9zFgEZus>aZsxx;lKN7l3WUvBsf>!C9G>;$jSa2dLlPT)g5 zcHSkwPF}CTr5SvK;;DUh_@F=hg<=`+^FJ^PMJz_HLayW2@lLx$78DeCpXUAV6RO_i zIJCH%J%v7C*_lGPR`=~7b`V=9vN{}g_;v65SV-4Qd zVKPF?goWD*LOx7Q%=JL%&LwEP5`5VFq4(r8uX$BW` zd|&TB$QRe4vR)_(4m`a*p;f3Of7v)l7*5c5^JtA4C_QO_{Ust zJ8B}xjfoKYNs2IwllVnEznNjM)o?_rBFd*_0z33aV4+R+7sP!H$#4#vUx3jSQv#45|* zfaxi?DUY*6emF`CxU(pDezx{y*?yGDS~YX8>>_G8vj7Upx!|!c1qgCzBC5t`kMeNW zTRxl7m1S+P&um4o+zp!6q~dE@o->Kwmar(G%V6e5^NVKhx!qVj9L0a8Cp9qN7zp>7 zqd_|k9gdJ)E9=NTjAmgy;EVCu;#P-v@1DmGr*b@Set=jE^H z5cQf*>jX~tYw!5vjRjihj6y9ZnKj6x;lh_<%a2oXbx<|9YpO$4cY7+{4fnEov4||= zOVGa5lS+Hs?us4a8KLw-#1gNqb5cnZw&Tq5@zorNy^mw@Ow#w^2R_Ozs6m5fK*VWz zuscDJ@S_%pk7K*z`ebW5wd(z~`V<>(e*PHIVC4!Dr6B4E_&kT*X)27Yec>Zq*2P<) zp>07&E=ePomGOzh370ygncA!cAx5QFOXgfqLCZ-K+%w6zaaum57qy&ZlTiX+5fF^q6_}>8jpu8TPE^?nUO~*Vvt9)oVGGF?{RE9IKw(&$=i?8M$~dEdvu={)B~J?EKX!Z~gacmj?&kyACMx8c8hoI^i4cPI%O;lkhmN z9r=9Y{a4zt!SeyMGanXVot%76>w8fXm!iP^Y}59Z{RTx4f+#TmGY9|>%`f~_iF4Zd zLGuG82X2SrILFSD2AtMkxVXO}j(^P`enX~m6ZEHxsDuE=Co#;}hrj(+7GMLHBqe_< z85hwF;YbSWF)lx%mNPbG<01jGaH@65cmn13C zOA%OE(BorLlHjVx!FV-dIG1AeYdmxTBX(9ri-N9v$GZ!V%!oP~GhQLLc^SP1EGzZX zD39WVn9U({T41HCsqCX7Bc+3Y482JB*hX1;BrUJz%t;3M1h#2A4H^xil;14K;y5f3 zKy zeVcq7e=L1qP&Hh*DoFuaElF68o+ zUdiw_fnBqSRRZ=dd;3C5m8hRi+S(1nyUK`1i-hPlFRW~u$~7@C_fEB1FyL7>zd#Sx zB*l$pt_*yIcP+W+llXCd%b(nD87lDHXi5F_X|c>5EeLpY%pnU}1e+0HaL4%{7KVoc|AB?-|xq7qx#TAiXM0K#E|YNUur<0Yzz| zbO=qPSLr2Dnu0U|m5!hk>C$Tg2t=d_A{_!qZ$Vms5NGF^_nrBFm}@?G^inTP&N+MU zweIy>_bQG?n({Y7yCD-i%jGTc?3msDbg3vr*y(}9-Fwl^lla{q{*+bdexC6@UEw zMvk&OwTMxuBNKC_C0q(#SHDSzb%{bUrB>4$OMbKhw^X?>xhr}k(uANJ5kvTqe4=pF z^q$$`jdr%|F*V$(?9Mg3-}~-zIehlt0h5E_f3pS5sE{0P?!#;DldUhB>pazth4R>} zyD6D@?_O1h?WNdRK{FZY&xCm~l|FXYFqMWkt+mi->^S9Jn1=9}nSq`c@K zKYXXv9J12uRFiI+ik$a;8h0*E)7H8mnTy3K9i%}qG?(A-ln8F|Vvxb0IifS<6A&y5 zzvDG!|AInA>Pw1eWVO*sWUBt<=5^{KC9vMEr9I!3{)^(wNwjhlpbl{}HdDr9W};HI zzwshQ3}ORFmAgkbw$zh8ciW1Rk$~qYLxQqurGUD78wuRGgM90!r$=8t|6$?J-sV(} zFur?}77-^wwgW@lA_pd(g59Erg}{$Cw>?)PcdE9ChH5OBZt^7)0ADbNydJEZ&W;V zD0dsPD>a1FIaZPGbPlQMoZr`>OZ*c&R;)LB!MrMzUrB1kFxYdEQ`+mbhmQj`U+cDM;R`2I4W2Nh%rc!u5h6#HVJDdG$K@GBiJ26Vk(#<|doo~H z7^i8mgApSPLgb%s^8eDd!);o5MI8etT6 zyffw5YK0VDW`2uXIrM{ptu;9}O+sQ~05gZAMPfM#{NpCD!-;$*i4ns%gW?|97TJNH zN$YnvEL&n`ffv_l{Gt(7h#aAAT!+;#icMUQQF^&h8NiZ!@&jvnmKBF$moT(-Ndf=P z0y|-4bBT@sh(2rPFUzki$*_Moa-6*BTDs;x$E_Ou+iV#{%q_3gysu>oNeNau8#D|) z>0&y-Kkyt$I*W0(zPE$f1-qYMiQW?(&*>M&q87KduFVCm@@r3n&8UCf=vTh?%fPTc zh8nK)e84I^-Xh)k$WHC>c$)7X?hI9BDD8p&k>GD3r=PEQUGOez^ypMY4wfzZQI}iR z58h2S6*NNYhP2&LSuSM`((yZ(K~}$iTatRcuJ8ep^&JM(k^t;V|iNvwd%Z9yi*){O=wtvKzeYUCR**a`Zb?UpGo z#_as`&>8d+(0^FjHYGR^I;lx=H4*+;gL0#ygsLdjyxcW0$)rRc717vdA38+AqrR>3 zPH|E(uZr_`O!Lwa?4kOk+zh~8dv56X8WNyh)rGOvkpLl3BRX75ik4AH% z=u$Ix$1l`U2Gh@JJovprr81}Hq39AOvq4X=%Z17ved?xJiJiR(FJd;>daUfI=%WU_L5?=sq{hG%k5zF2A^U=HVe{Uq=@r`T{< zlTZ5F4dWt9vV*0PA0j%&{!!F}awn?;CuZLnxdZ*CQ?-~mO^ld#G;AB2bv`zx`@T1f ziXA^Sx5GEQ(o6ji(e)*=Nblfsb_+Q>~2_+7> zPNK@>&Tqf}?KKl$3(I*jg5eCh0lh?m{wRX#jEpP|$ZhbL6+-Z!ICmcN8L^6UB;uFk z|1Q#sUu0yNYribj>Ihxy_c((nJ?*JP?%GRrz)+;7%Ba%Us9L?qEttW0b-L>vKU*lcjaV0y0QrgqmTA*NVaegmo7!OD{FYL1D_x>e=S961c zvxtps?DoP3Q~QwzPdZ@`w?Lasch7}gbFbNi1<$-b_L|(EvJCCP@pV*Un=oIWbq8xI z9k-b&e#j9yT>r|fzP8WTVzr01E;&;I0zX(_VJqWc4`&B26dR)!OLqN(4!NwZ@0rCP zEv}wuzns0)&UUeaZ2mGK+Fq;Qum4^Y@&g%aa4TEE=`W}EugcA_O#zW=`=RSD!RMmh zN;S`Q3k3=bWfVJLW)rmjbXbCjaam)5a{!i2EZ=J)v$B;}bsY>bFA2AkJX{-lPuPX= zXT3G@(o^<05U^E1^pAjq>|u7x(Q_JjU2W-2e3TJMxD8j66H zKm9;Pa2aDhrzp!kST6dt+heg7G1Tte^4$N~?x%6S74*3gEU4f~d zMu{745%#Aqky@}ojy-GH(N!MF_X~p578GR?`YzL4p^y271ai+&g>Cbd!z>f-b` z@QU2ByHLgtc+G7r&aW;E(IAegv}7<%{15;mzB7P1;-Awl){D=)vbG6q3cE8j=damTKIrCjma4!eI`XfL9aQi+Ac~TvPDIZ#K{b0jI`WzL?D9`zt<_XpkM`l zBO}UPFcBBcp88~3_~#<`p`)j3XRqs|^>L(2^dqaIg9f|s83FErRZ8m@o;TrYT{}E? z5y*zw+X6W9CNg8x4QfhUsigo7&h@i66Ta%Lhw-{_7wlMSnT9~}c7cya9E{-dAgKp; z-QfWrDVtdw7ID{D93_MiR3|ZZuqW}qkBeKh$EjfE5>*HSc~f+9Gpc|fV@dCrpf{^W z*t+0^)qIVO-$8mIXy8N7dJZint%?}BuKE|SCuC)0s#?h8wm8}pKt(4%xphX~82v`C z7Mf`0!1n-4YlTgRFuu>p5uMVg=j>UhA($^KecUNZSN`V^eanNR)_Jt2AnR`-sfT>6 z=REKn@VJYSf!LP8oX?WpzU8a$-~b^}u4$<$Qw~Nf5BLXLbt@CD(70YgTxP2_%`_D@ zl`=I#H2GvV(^I;ZJ{!uh%jPp;KYz?NPJJ9~hvVE~Zw$tJO(+I(-iC-v9yIJKJ?Qm` zGthB4BVkAFU@AHA^-jO#%hF?3KA43Zg45*qL^@?VBHfs~3nn!Xef#v%ckJ=6?@Xzd zmCZi!2k!+=W!D^s=1wbWWZVaDH*Z#-_qD%xcAjBR_MwywJarkK8P0tHaDpoOb|@JV zkJ57=EEyd79nyR4TUt5#OrbF;T_KtlEO$qn=W%Tv`yrKhbzf1#jb`IX@tWC*Mz~d&S9B!QGGcd52{q+o_@- zxCHb(1*V1iAgpX~XnXknfLyJ}nSd4N_{+B$wcaGC3het1&%p6V0ttiI@s>Wvmq@oW z#@K)hJp2Y^eC!1En(weMtwj80u6p}>?sA>3oxfIpaHZ?doYqE7Xq;8#@rH&E<287| zxx7)p-(aUg6p=jj+$H#kBGOMbe3}8Xmyn3afIB~kghQ`FTOfez*jPp&1@g$^C>&@= zQ=x zOOYxUl#sH!BR8uS2Nko1}2mh6s8x>8`e3t@OXn(#~ z!GdpqXOcUDsmcX9Y1>dqI%YTNs)p0r@JCyVNK34U z+la*?Dw!TGaeoBH_Rk~RJeIquLGsWAF7sWB%eBEW@4d3TUd{XS8-&n#(k^FwoTsT> zPWj0FXrytv;LfvR78@L=OZQ1&IPtA)d)ST<A!Xv3~VZIg1l_i7?*!yv`#vbR*Z zBpsgmf9|i)^uOW8a#M(2b zKTG;%jaBVt<5m^Q z6Uq}sWHw_sx#N1f>0-;SCM{DUID~Lhb;C-T22!I1>1@_eCJ@7*5LPSA98jj@bP%DA-@}G@2Xcv<_%nEl$D(2D7CXL{U+OQ2 z>q$o*h4D<;I?%%RpIzie@w6Yyh7tBc`kKD%2Z+~yF>2tpf-gaupJK9!3Z=qBmBbg| zCf&*>s!n7r;FyBzmqw;jbDL>O2_L2`cw%azn8a1(1ItM|ukv5obwAWpL_xm3xPA~7 zPb$d)wZHiBB@z)KuoHbO_4TLC5<(ebj^29OO8#nxt%j4)MDjBZhN5 zhgM{dsJG8=9FuTOwWQr?c=Nd;d)l|hbM4)ui3A67V6?aLP$Jx!?Q_FrTKJ)1 zsucY2=g*3AalD9p4K86eyDjBwz)l|5bVKZ?tom&Qqplv4+~_46GE=BA?=Rw^oOPKB z=lbjQ`->5FINQiCE6yOJ3|b*kdLa`*i=b18`pK4~<!w8yCMYpBR?DN3V(2&G}5tWJBTP=uco>4 z{5`bAxeg6M+O)c{CSuo{xQr3tA-pj{EL3_=`TS4=r;;4y9_>UL=nu;$|9P!zp7&eL zNd+xDKHElWN)e^Nc_fd%YfO=Idhh=Ii~cHe>Li$_Ka2(RUp>AQzSn*vVf@rX=`qkm zp5iul&F#T7-$%(!TwU|%tN?BqVHDB%AsYERqw>|dNEggkR|Z@LD2SJs^k7i*X`B?# z93aJ4N=Zp+LiPPn8|20+*b(DrqQOSw^$Gx@WFq`_c6J6I$3m;nC4E7x3kGMq1}}(NG z5~vdu4?vYJtad;^$VXoVBdtfw{3)W5wD5DQR&aSDB-vn(<4oTlEN}#m z&y~1En(wnnw1Mv${>3nhb_z@;5&M+$1|0E+zwJR{d?Ie-2@WU)PRE)cc`pnEjODaq z-hWKt#=#-$CJ<{y&Or+&eKOd5mJTIwSUpdpX!2;jMf zH7TJLp>AK0P%FLA#ZcP+*yh{;_X8_el~xcYRv@NWcZ@#f#-FTO6x^Ey0ZO=(=Z(x5 zFq!a?u`z2l7!U1?Ff=sG|6l>k7bCbEFJgh~WYhEIK9-H)j}c5Cz*Iq5C@UH%W?F>+ z=9p{J&wY?eSGSvI!M%lY2IJW$zgLy+;e3QC!pLrFz%#1OVG}*2;n<2^22R zWzYa)1g3oYxyo765xR=tnJPvV;IeoMaI#?p}<0S#8rVd~@y6_QFw-*bZh)zwk2Q8f6A)oH@N)%1dK`tDr z6)-0i`NgcVAy3$gYn2gYN^Xjvqn4N*tkc=yH17Fp2UvU<~TR0ag#P zaBNcx9AmC%tQ?F7d`;y1)(lA(Okt>^+TNo5`Ni2^4KxE*t?xKw?#mq6+^L_dG|`TI zl%tm+{WLnE+{dU4Q4JQ1j4{kZNfiWA&1?w^l{)W{sqh$4s2D2EtsmTw_@86+1EBpPfKJDP+JqkOk4x}~A|Dr*FF3fKUV=awMU^2iBERGF=T+Ac z)Qh|FDyO2da!!&+PIB_qsfYUdY||Y#NVY*5kdwfrpoQDg(z^LIQz944ap_cE1V*p5 zLHmw|Rh7Vz`#ErYu4d?YMX=F@M0ZWIyF#YdF4Dr;38yUymkFn(j~zUEv2v2DR*8nl z^PV3Eoizm_WbnN(OSwXl&kgQFKp50Sxko+(8`jm742Dmd;1{&;y0Z88rr#}iei~@} zw*(eG(s)B;z-AvJKp7VU2Gl6fk>oL?w^vtJzn~i&YU?M5f9wSSAm!xy*_Hq{kpEOzfS2cfp51J{sOj`R-ggsC?#_~Ehp>eb~6L$IoS#ngDU~EPuAXic1UP@+pfzuDlL#Yx zKdbfJ!az0>`z$2q5wVJ+qZC&okS?n-Bwo=S62^w4~o z)M4~OW&Nah!~iMpjk!^vQ!-%<$$76!>MU#uhk4b-CtPTKE^=wLgbwk{jb?bO^d5(s z_$Q@^24ylMEZsJ%m~|>h_X>Q#_ALJfbVO~C0@hg~=`fDgf>}1Y2Yt}3$=VtTeX<9? z3wl8XZ`{yAJTaRo2g5Cyxwv$1>gRj{J%(}H5I8i^_Q8vzpY#~fsc#I_leWrx5$Dw+ zUtd9UZKq$jIl3h(e-ueSi3=inGNY+`EXzQf#)K8>h@=_}Azt`Ld;U|e$`-gSJpVan zGYFeFx(bhyz|$SgI_{pc6U^b^L&9>>o8MB4qT@4!-OCL>%%1T7`LgL?rBrMf%&J;%VuP6s25ksV7ridBp6LMa z74mg>`faNh4cR4`Bud_0&(EjEq)$rqOB~AsGg=(VecHXo?zqf+Fgzf9lPdwUE}mK7A-*EfRp;LErd4}gFJIl3W`$R?6_)OUX!^FhT)O|*`W9Yf_ z&UV-ZTH|1Vf6=2MnYuAvTDZohAuQ)slyWmc_+O=-AJax$yVBpa%g_mZ;bHuVxBkeA z?xyo%45$x71LUXJ_lCnr@OFwyA+XAWmMY1kw1e$GVuCj+ZVXt}M)##v+MGwB`NbbY zq40pMiL2ne|1=>4PDCLo7E={=0(oKP#gMBsRAxq$mMA{bA9}V2QAHQc_f~T+ewiu& z`8#2#Kp~R?qO159_T{nQKTc}92Pm~r@{d)ScfeTN8(SA%Zc|8VCzhS35$^2Hw6}=z zyRuByqs2u(tKQc)yk=c3vo>OF%7~*b$C|K)YIut{|3vtXg1nhUK2>fy2E1WZl)_T* z0P(O3g;miv^ z@sk7_@Qx&G_X)-mfKN_;1EjKZ$b(O!ybpSWheo>!v_@0(6WMx09s3Io=Dx`ltJz74 zSXO_h`kT)qoa%-l`ynfzSND#6rp}k5&N=6rYS{t4`}X~mZy9|?T0yBz`$;5)4-_)8 z{-$>Th=zDovJ3bpdT%b^Wj4P3ptNESzx?q_ z(3AttHKz&1j|Q&N7r8pQj4l663BGB^N~;V1Z!&}(M+O}@>_ZrgO+ujm%zxFhR5BJpjj-$XBzAhzp3$M#fY|mh=Yf+>?;AzK0evsZWl-!*Fr^mIyPHF~VKdH8h$8 z^<|;*V5M8aVH({IUMH%Wr%3M#l37St!0wzb7+%L>%vj~DDk~=WZsDJB@5}aY-QBN| zz$dr@s8Oq8ieVQeIWN06nTKNv5k#kZlAY4!Y!>1~mpVe$1Du6n zHN!;v_+p`f> zQ%NQ9KYAR}f1ts8bphXw2%Yn16vAO2PU+5%&&+;R$NBP&{N#@*F+4X-&Ta)Vyc58( zp5?&PcHmBtqZi_X+~mXX9d}QI`}BX+g?J96tkM(mli7MzbUoW-U(99UF3$R|@@lt` zdTiYnPVMy147g&Dvr@8!Kz`QI{8>R-M58!6R-$V(mC+O>>prbL=K5^}OF=#gzZoWa zi{Iw;M|ub6q9WP6Z=a&2J=gCH*e`JL5z{Q_pq!+R*B*lJ3QkT`&r2;i&r!`qMV|pFfalM-F_O`gqFuKU;6{vM3PEm6~ z+z(Si?cmeNX{?XCwcr`|;qDjHm5qX=9FnMR2;A_XpUKp+K`O$hl;wz%P+?xD(}cc# zy@#wgK8d{?QVP1pnc=<^@Z@Zo32LR_W6?nG6*0W#?_Dshgp1HT!C=6Fon*pm=3Z+g z_7~!IG*(0p?%u-*m$Qq*5kDZ^@~o0?e!|o1XonMbADLaD@16$&P;E76>9S?HiVQHM zq?e;jy1JFP9bKt^7XDx*(KDG?8uviDGPdmvYWE$Fn(4f1dFS#wp{Oo1fMw0t zvBz;^L^f@ze)pjfJVV&}n2pd(VmRKj*<+j+*LQsW(dd2mgG+>P+4Yc(v7+43mA`dE zY2(4ott*M|axl9cq-P~TU3X%+?)siS?HJo9LwG^FudFVKwYQx%{Ci5capUuFep)8Y zmA^+8rz7~=HCG57vkJA$#*B0Mp;58aUMdUv$3dBt#vlTLq$JXiGhbEvO{s?isFa9a zkN0At8?8e)m@^=aco#8G7N+{{#%UBEpD`VXPSS7VF7<6mTcQ`qW3oY_nC+O-+ld|D z=b$VaAZ^b)-kQ{yoSaO^w_Ow5x{$Q}dguxNAScEm#BM;8nhoDg=X3Ihaxf7RD#1Xh z>WE|KZ|#7!&Vj~jlJ-zSCoHQ5ny>B}cucamSg1rY*Sf}(P&tV2cEwWlWZ7DK`SP6I zZ=s}u+v-E-VF(81D2;bwmq@V@N$f*T6x&w~A=7GXTl_T{Pv2GE*=IX@U_phlJ|LZ5 z2mm2ecaU`zcrjaE0(l86YtF5ffjKa5n{FPj^Gehr@b#P4SbI)V1jLCe4k}q@7EA0w9liEBAhn`$fo^A z>B+o|4OELsVI8I%jXr10yBvkE9DpEf>SAN49LsqEESZFBUP?a zlYdt|x+s~q#Y_v|md;dU1yc98s=PaQQaKft!h+NfB9M=|?7_Rq)o5Gv%a?KW`k3gu zPqmGIsvHP*mhxgGw3^9M2-7zWz^X)V^*+$WkJ4mmzOH4M--IuSg+@MAQwrSWqhTLr zdZ&fhse0@MghS;)%>-^Gp}{?yaRi*y`T;JEz&pwY*Y;L+IO;32RyD_+_xXMU4cs(q zG?et%Hqf5?(*w-c{5FN!tiZB`ss0u}B6T8{*HTl?f^UHItF82ZlGNbVr7h6RHIE(G z&OhhHZpG#sf01}TJ zVi}PVnzgk=Lf(DX;VPr$1STKC#_>1#ejthnEo4n}Ez#ZF9yzAhti{UnNorsluM5fj zc*)zy`z?x`gy7wHFWG?oUk@2oLR8sBhp)W+Oq0SD^$hYAt;HRhWMB2G=oJ58gm0cD z#IaZkEdJn(x{I-miF*qiZZ6~*U|YoTew9~O$fnkwY;{jR{2sd&_>lc-`Q3xiYqxP} zmqKZ1;Su9W7UGGZ9+17tmnF*}e-qJ73K`4$f%;z-AoC7n2ST-{R2Fb=EpGq9g+URW z+>^Ld;L*>C9}9UilM_z;;r|t&tcfL+|671MPah*Cs7LkCxd^d0YOjrFrBE|?SIA)J z@52NLbrEarXECF=_j8Q-Cp2)L)?Lwz)9q^w%57ioWlVkLv&6EE51}7{L3Sf!{j;^v zIv4LS7le#d-@AqvG5gBAJp=!ON>LQy7%#|b3lUfvk6^Z{<50q5RMs;qRSH&N!70%* zDrG1;g%VTXitr(V1^XFD#ncB(Wb+5bSGG10!EM}wFSQZ2ajYVjyqK{p;ci%K4J~q1 zCGE)?k9F7l!XAZJ^vfG)d=i$8?Ii+*sCLrd*1gFi_|4NHi8q2gT@liTM%{htp=z^E zwF+?Zzl#%)VJFh<4mbn5_ymtEYoL|#)T`QxYfFD=L(5|hIAcMD&GP{-nV!e8U}tb|F;iUerMOG$&4o>ZpyK9lvJ z<AJ)=P5WhJ-+~4%0IOxaoy{QNd=3<4Xm(FoNF6lh*tWC7)ium-ZEUP*_-aN$AcHm@E}4?zcXo`PjSv`}d2gx~$5{Shjx@ zf$zyQ3>+?;L67n=y+A~|5~cI$UuHio`KPEN9*jhuq^cx-)!|)XKVCBg47g$*HdA+Y zU@hQM45k#17g`NuW=bqxG=v|dgS$J&sMP^0%LN)%b%H_K6<1X*ENAW4nA#>s3EW)d z*}fR=q8E)8*aD8fd<|SApKrh=q`ugd3msxVJRs5gj8#e;a$cv4vtJ5q^p3s>_wvYl zhW5QUzGZiXG`$;rLAk{nHlYYVydvE28A+_xx%SmF5E;C&f9KDNScw_5?BPo!^8DQc zr8{-`N|Op{>Ru64?e)mzoC0cnj1G7brdOf zEXRRX0fiYA9DRoDAtw}J_>JzhOR4cK7WNLTP>#g25}%wWk80ho;oF|C=L@*SKrjih zLb^oCQQ`)3kn3X=y`ZU6>O+H`gYG}hdNgG8S8@5y4EC{G`qM-28O+(@=>^9Y?2vDcy&1BwxAAOLd)qe_vJK zgXr@1eKfYCn?)}#c{zfQPeMXsu{zX&qJ_qc`EDnSdB?!y_gt+rQ->={l*X{A=(S8~ zXFgGGsK56^gss_@hHpm#jwn&(72gW5@2!Dwy62O&R*?QqqdSkAdAqL2f!PL#t}8@svsdv$H5(|5dPAv8$xtwMT!q`O z;^eEcG=DGen2F=ku@!RgGMqHjG%Re83TH+sVd-)8$p3_2CZE$7O*M zh8K1cS|~=#17u~n@`f6_B z&p*44k5)aDvU@`}u3hiZroo)ADDeEO(W#f_J<_~Rwb^|7`T$)}kc|@a*Ln#p<7o$z zGp<9uOR;hl#!Au6&v!Kw-*D(Y$v$rQb{K2=v*jNJlx&OJ&YRsJ|O_KbE+ z<-x6YKvytd2goRzwueG^3UyzsYaYV->P1T=AVNiWg{_S3<-AO1YPEn0?ZSNPrEH=D zZu9#JR9^(+e3_p_|3Tgd&h~~eD9ufW)BFz~a-d?c)_>j}dGw*Mr86F~{$Fw_pnOu& zem+HlKVL7(bsET!0hNS@;J*nq1ohqB^UBp%;Cw5&(eTudEU9?>i*uOJmuoy_mdJ7x z(=*Ba22FF<PQ`81|?7)-HIMeV^2oo2heCQQ)$!@bh4(Hnhrx_^M>XwZimm; z$dS<833Hgs@07uCir#|8LQ^h|96{Mz5Di}i*d!C$CY6h&;8qJ_dZ!Ca0_E2nK5uwU zD|@YYc62*4=yTl}T`I@XGZ zheymKWBsHyQf!T8Q$Vq4iNiPw+4wP@bNXwJn!vn8)fTGh%3z#<02||c1*ovkJ$py2 zkF~TPA9AyG!P;1skIKqWKg8Y?$XN&F5YBgsq_IaWG_>HLNqaUv74{6riNY_adjh^8 z|1v8^)P@}+tZ3w&Kk@bH1E|{=*?iJfTBkP(YM}m>FQ0W27bkk3#~N?((i+dn#*e6L zL`CNEe0hClgdG6g2~}+Fi|RCNq-)O_7sN!%3@>t}KfF=~5l*TE1rcky9OhTjI8FdQ zAsm?>bse|gNeYVFy*1M~CQK65{uh^g0q)&(c~zshhVf0qU(ohJGsOLN3trTo?P z!s-diloTEco{R|65}!JMZBEAv_#(Q?cB z4?yeT3w@2uK8l-O0d;^!=`cARAh@MUc@dkjh>`fHf5gbb1m6rH2uVT3PTKze&cF9;FBWdFp6IN%pU(SsMS;K#Jn zf%RT&^y$HRfqsN2s6LNr8-w!On$x&3cN!) z*@PV4Za83xn(*NEQiu;BJV}(x2Ne<#InUyn|4=>9H;p7P$4289K6 zR&h@D{=fsC$%n*}EGq<@w7+&$Im}6Bz$a4^pOXe9<#sG>qrJ8NpCJ|g$93A7$zZ~W zJ2ylVy5YtD_`JBDyC!y5+u>!WKLweb17=0oW37|ZsuB=*?SYrH9ynHm?!q#6#9~mO zITf(T_3rrxodw*pP)_7qDCe!LQ5%b(nk&t=@#s#+ue!{?x^?{kpT`UajiIL~ohWi! z1QOzk^0Cq;j~>14dccvyJ&D1^k0+BQ)V;|3OF3iEo6#1ymtRF7F*P24Gi;wtK0*#U z{JvCgYqTo^%`qrOa}fN@|EywLcBJghK;P)}>N&SDsC5W5yT~9LR_V;3Qi3+txJ`}g z(LARj{0@@a(+&C#x4KFh*&4Aov^tu+o<>OF$2`NEuJ3~5XPL$BCfOD}Txn7fbPqnB zU|na&{)!=kv?pR8$J0VS0xAxQ#r{gb?f$$OmngwDR|+esY%7J8jT2!tkpon`a~Ub(@k~|E zs3GFR1UWpV+Y@R> zUI$`D-DBKv8lVj$E6_Y~DJdgWML*sj%&H8G`iT&S)bx^#qiYA6g`RnYIxu&)02Hr& z=28qA{#%(Xb|KsKnxV$B@wOTkXm!4$j`H5K2*x)D6Z-7xK`YCpJPxxKMD5>_8=#l; zMcfpai`Y4K1kGdnZQ9s`@a0EYp=?y2G9N^FptrgQd}gG3gP0Q{%I1OV(8bt)BuDwV zXlgABQw#Lv7^{2o5&!W9<2?WWyn$B#G@SImyC)s;rSUQi%rzpFuf3{7%_0u3WC$1h!XbY=w1O^W~VxHb@yd z&o2r|!+ML+tf>OZ2!@sF_o2~@GVBl=sNK`XeY{fGX)T&uOIE@|9dhRZ4tTJcS6iDm zcvzwOpmGeXBIbXL0~FoUa&ox0e5hUEKpk7QpN=5{PvnQjHRpr0aCen%MOA=;RJ{O! zs=N4W|0|$;d|VSt>+Zy)_kg~oTn@mZith$Hs2hbK!Y|vy&Zg8q7)&Z+_VzR^ z>Y*;~TPHp5#7$dB7?g95eJ8{4%`HR7y(_}Q4`H_#B=?yK=aA;8gg-xlz4&zJ5mc7u z66)+F@@uguqWWMijpJ&ZNhi!Nlh{}aCTl;M(6+I*Iff3+fqMRJOl80LJLRqoIc|&; zZ*6N(UN~LYTfjyhI{qImeSRPm)7EaO2Xa=0)Q=@QfM_TP@?v&Do%k+Uiq}aCIiElX zfjmFM@5q*jPCPChBW}b!FNRbmJ^80rWy>oOTwo^#M96iTd(@^vr0np(Z#?bo9i67| zJTZ(U-t~}DRo9e;7i(pH?jxvEIVo<35i7f#lqM|Yb3HZ6QwkpnJ@6)dGNp`ri9}zB zIhK+{EvgoG}1(`JgOI;3}(^|n%sM6+W&dCz}; zO|-&@dDz*MM+@8VM-1J+FbBgSY0K=HZ~p;pB>-{Rnb}7Z5tlpv0lgpoysxakHxH5t zhkTMP&=Pjs>Am8KpotBz2jBmJAR~1qKt2(V6#FXa15ush4WU81WFw(e94>2d1e=Gz znvAWxmk~`u2svgKD)ib`9}hgn&LiQ-Drr@JVN60x@gGQ zMJ*NJBT`jwa{^_|e)sOi6wNbn{9#3Vx*Jbtlb&Vb0CxOgjcr2vf5Ez!7~rE2ELb8x zVa-zrM6${=XMn`?E%#*;pKLZWWz;|ysC3^Y=Tx*DJ8p;WLpBW_-}<1M2`RyG`yOU# z$~u7!;4XQIb$a{PN_kO~7(|=|%aLAqGf{}p4L@n`P26SMisSP&{QMv!HP7H@XX?A~ zx>p&7&=6Xb*@RTB+vJEyF_G%t6iv}q zJ0gqq>t?RsG-#rkZCc8yAt_V+LnN?#R;C{DKLs!8_#>Kk3O}f;NYsQegDX%(HE>ko zmNKln!ff5%60pmfNLW&TLJkqMx%E{Ix6l1jn73Ew~s0JrzJx$N0Z%;MSwK!Kqc(t2pHW z#71_)l!xIyg8177BwEvoyrj(O=@n7Gu^*IMEt7w;J3)jB{>@2-#YeWUH8i6+35i?F zfckdj7y(#=X5ph{ORc)BwzOmHt4g%qTD!iuWx?=#S3Ta*DE|{**q@BGK0P5o^ zraoghyI>Zr%Wevk(a8F2b0m4a?W_yO5z3}-t|`JAex}j9w9^s3-OC9eELA5KMr;6R zV(tVcfDXn~qBzI2bn3EPaOXzjk4GvH0MnZa`4&<|lKc^oEXyEJO!m(taQ91C81$}p zg%My{9-Rfb7|!sl#o56+Oz%0ZGvFP;py-u}&tSf_U8s4)LZxwc8M5tvnq8CrYj!mt zHoNwv{~v)|TOy5IJ1kv1VJ;U}_((X9b~#4@Y-W=0NfM`kDf9n<6PkmCr2b^T_B)X? zw>{3e9Jb&ba2^<1rpilw`6(a>X?87Ue!XCMNsE{R@rU8C$nZnUz}0+r5MrY1HQ$L* z$3{_~+PUq-w$=e2fVXM@E0>h!whfLA(7`Fi61tyyLbK~0h$ZO+tRENp%TpZZE0^RN z&>oLYcRjpEF*}*dI+&?zpBwUeFjqxiOi>|Y!P7yMjJr;g*hiH7I=0qB5+7g7&M+Sc z4uAa+WuHHS#Md0dtT_vO9j~PFLd??B(<9&5`Js@qw{NEtfir_Mh!C(?{tPNg!(b?G z_Egd^8!Lmr6}Alnwjk1C5}XLEJydlTFt9dfkF&Jcmp%n8co-24*T~nf}DA zUuXljdoFgWR4E#H^kGQYL{vDvb!en^xBVj+I`F9W?}^WOJSovPp+qmgBD-)t+I*^iJU&Kc+R{j^K!MU3rRlJmlIxqqbuq0KOF`b=t}03_$#rnn})GCBjtX z0#|l>sGT080O|!WCu|9wG?+}!8{5Qn+vi)!>*8Vo!+u>l?b<7(Y&8%;$H?}}F|NsS zrb?*4SBJsBSM2k9HW73jG)eichM|x?YraC5b+dOy3c`GF@=&6p8%qG#sLe~ zIi0nJM+cFhKP_VN?54g@fVe2jfJS!*kYUPBy`N2pqI^NyRdb|vejT}}o$WTl4HigI zS^(Ize0RieFNf1FXZhO6a+BOWieabEKbn}En;S%7Yc~d_WAtC#i$I#E5qeb!3lqyl zx#1(tAqLZ3JqzzFDmvLBOSd&ZD<73yqa~>sGE>%_dShb8ALI}%pXyzb0FG4TJ6<_m zq8sNBYw|Vlec9CFW9g$KLYOmQ#_Sgmng%}9{Mxo5Drt0B$}M7Qc{WsiT^lq=pVxNu zULx|CLyyQf23jcr0UG4r=xJ<%63C3{ieZRzn~!4?yK_zb9XEGGbfp+?`EM-6Dc`6l zV_sRESbKed$lu?M-u9r6_pmOrcid2WVKo=d>i(&y2-KWRzccQm+W)=IEH5? zrPc?b<1rM3XhE8(Q>i|F8!~F4{|Q(+)u_VWOj;#3fc|dsRwr@7$^PnSkIZyQ=2z z*iCg^x1GQ@sI~KtLS~(~9`r37)q(TJB+mTQgT~VuUeM@c-)edL*bmyHD4V5Bu;J6i zV`(;2F!V(?j#sxnuh4BqQxHxSK4!l`*Mjnqx3Fl{I_*7`6jl(JV+e7NLbRczvhIuc1NqBqxLF~<2!xik3 zVPj#Wp9cH-F2Skm(VSDLH$#Ut3nKkSBcf1AO`&3TeKlj+y0g9B= z^l+03Ik5q#rPwhVxpv#l;}@BTL~f%R`8@3Z*qIhGhcx$BabeiLC;5U+w)PFvDz^a& zcTf(`F~C8SGj)gEewZ~(i$Kvv|#dEjSnqz=1npcL2oQ8)e2 zLS8Pq;?KqM**ovek7A#c@tj7rj>w9jy8j3k9Cy}aiGS?K{bG!Ta)dN

      m83 zp?fw&OeJ;S%QD2VRDC7^sIP%GB)!R8%1O+!QB}b7IUeVIv%D`=P(x5qFyq__s%f*E zl#-$WC!7=+Wg5R|UpoMUuABknoIs$k_(R9G3G@kmhx0<~@z+P&lltrmzYPxmsQ;>W zWrB9y-YN$h#%9;NK{+^PKR%ku=mqiEK#J16l-hlP z+tk?)T9>2`>gOKKnu=!FA44jJ&!0b8K2Fs8uSJarEnOKXgSBK3@yP7vqr6Xlq8E2T zApJ2$JH9?fUXj`uMgCtLfsNY`Y;64c|7=3P=m_NgfpfwynZ@^`o?Xx-Wf*%&z2>}+ z=wAThN1XQir;t`u2pidKEUU;ygF2#JURyP@V(vYfTT9FJaAQp7g#(hoV>mjPEy#D^ zRK&0>6@h#>RZrK21kM+-c_UphSXL#M{X33*v zr{?N^<aJabllug5=V1ec)Pj;GSS%!ZA>*&cE;=T)rX5Y74Q?8Yt|NL9Wx@OpUDVFox2-U*6OIDc-(vN^Y{__Aekv%Ct6N5}e-haqS&IXFTbn-b zGhiOT1jcFLrXyM^)j;UW@$D<7u!xy4>oU*w*ipyJu0_!rl8Z%vDSwse<4XHsp;Bh$ zJAE7Ax?;@!NC2g}&5ax4lDr-QNO)UkUQ+H>ftA7vn_X8oEM>G+BsdF%!HV`6=kv_I zX>n{ui;}@HvJb|cd9c9w*r!C;H1Wr914>E^>FC;F~BPg z{r_1g-hZK^q`7@2_lt>paY^F8 z5Bqkh|9@LSrb6aG+7c2T^gOu$+&B=CK8R0UsQg^`V}$5gu)e-D7;}%fPO*So28e?W z7+6vON`bwifn^-PQS4B}Fh3Het4VSY#aN*^2g1>ZK=@XcIXyp~r!rv3V^cvKNgCW^ zNdIQ7)zbw0qM9M^pKeD?~PK>;Izbt)rTL!@u!uFhE+Rkyh!H5J>}2k&+G> zNSA;}NRCz-6_Air8tIM=kPtyIC=uA`5=IXg@Z9@+pYL!64Y#lBBP)i`vf`j{`(djq4^1y>VEbT73_y^Kt zQle^eb1Vr3z%gK;X?t>2C^veDgp#>)oH_Ra2Z-6D@8|%v@1dqyU3j^ng2QoXqz5Qi zz+9hG;{P$1=zLdMNRlssk>! zZ9kg{ATe-&>VfSM^^ioFRv4olY6TQ2p)p%)K_>?nH#lw4ys-ZS@xd49R$>oV!9*O& z2?Ypu_YCylvQG@C!hQmgD90Gf8n1glg|gRD9A7Q-xzYN1DM^i=uwm&{?h`OdWkq*M z=AHi&{-Sck#yn+6&+N^UaqVxVXp=!O7D)v3j-XMr%&}hs9o>x~vcpJ5iA-3P*EbZc zg!vY4i3%{CGha&8^Z;*u%Wi;p$+R2aOiW;uXoPkCQH0=O6PC@-dn8A|0F2Ar*F{JP zf+l46xUJ*+VI7alK}cuJQ@>ZBEO`tHcoOiJOHSWBF}~D5z7eTK8my^ekDk^l^U=fp zW#O+xG@}&o-zHH@!8v483Pd5=e?FawLz9mi!#KIe_8EO&K_OuTv|E678SVwN3uyCu zzfGNvcu>(=-nde(%ECx7wgi=MS|6)ea8^PN{sj_DA;Z#l!#|+MuzOv66Ec7tFiT#g zDs~!2>TH3ZDn@~`?t9Dv96$5&X$Dx8t6hl=l4$}f*x(~Mk28fFDG7*F2gx)0mGo8 z{#~6WHQ7sp7^3hSIu1RjsqH8nN&Qa|6al23Z~?kf6YB@Q06K3=KAC~UMh8g~t$ z5hb0wwLRbG1WZG`-Lfp;29$VlxBxPoH5y;GK(Atr2fyV7Dkj}yM=^I|0@#)A@yOOQLTmJ(7lHcqfirSW+upXRYo=4bu#zKB`~``hg6CWW zvI8>ffq^OZS#VP_3SFg~<1uFoZohQUwaij^#C~Rb>JJ{B%=fc><7b*~egC1|RH^^J zXg6>4q+w|7Z`USVvA%h2l{NkURk$4za3KlVY{Q9z_AlCXDbEq zpP!q%ce@c7(EK@AbH!`4lK-u-RlP1YuFM`*j=0~FOBWvIy2k4U-0PycA8960pfR4? zdQXC!1v3IDb?HzGs@*x|2m~$-9N&hse~Fed;%)|)OC{JGOTpsNt-b)1Rw4-u{O>si z{ue4`%}v?CquD3a2@-y#^h1fhORJV`%Rh|ZjxRd+f#WPkI>4*Owx=&NQ8ZCDH3gsg z-;u4NCU9WJ*_$HiL`66u3BRHDU&{hue%+fb@HWEs_}IqI>Y%yzX7Xrk4)D1Ii2jV) zuyiFqpIy1fUW?MxcwkKZaj|PGP^JoY-MIpp$80CrmH(FQR&=R{Ss8& z0PB|qWo>hnQIiKY3>k|$KT`m-ffhA&5{Vo#*==1gDLqEyCz!rR6$@h(kVt+1ULZ#O zB^5+Bu;JSy#BaHG6_8uz9LGzGix-eo!sMzlD~p0j-lA?-Fwt>A#ua9Z6N)l2DWzcI z%wGOmQYP`GQjOD$ODFS*!Y@{bElMZr1iUx@3OY(~>|vTh za{)fE{sdUj{!3&!{%5~V21q)8|Cb&_(&RE|#Q)gx{*$GSLiuFs?IwVrte4AC0fmV$ zT-uWw+t-k{Kw!;?Val%Vhmhgo6A})bcai_F>#@Uj5F1tjMWZ5Zj#40xHl{OEMX25% ze`H-pVwIJYWcBqC!gjSZC}8w}`ST6(iX>Li(8^m1Y`YKzTKpL=B>dOUpJCa7gQK9% zTJ3TV89{{LpV98dW|F=imin|y)zQ3ZD!u03Gd6##nj^ZN_$5>bG>eY_!TF(3`@@=n zpJ#s(kMxU`5nZ3|RTHq-uD4&K1@4$jzijXGha6)Sh+?C= zXjcUjFZ|Cho0T^R`^w!NF@|jQ${-PYaXCxR-=lTO7$TSM`EQ9WoQ#GyE1VmQ3sD2J z0Hyb>#DwJ@4nM(v`yC{$zs$+L4GG%*N>0?d?QaH5!|n5LT-8wGNhH3jmi zslh{(Z3-p55GGJzV(!&It;2lB4MP3)LWZj&b%>TM&tHxwjL4oYFgJ}@H@#TszX)}O zZbDu_+4LVjCe3x7ZmCDMNLkT@&e?qKnSj8-(*PrW5>H84B4ysX6pH_e9wLU+3L&cHJe>U%kLVC%xepij>@VfOgS%Lv5-E=IIb?*y2NW})Mslv)_Yz4h05a8X+ zEWZc)Qh7!y;=v@PE;P1NuqNJzsUjts z$#NAzNmJmKF_2&1boieRYvU*r)c~r0Z~=WMUO+|1e-eWh2kiXqx@x8WwYsn1s|y~g zyBoHg^+KiBURN6wsmnjqc6zj%`uQ@=IqtM^Z`6V7r%Lo$tiPZsYVG|eNOCR zO8`-M^dE(%JxY{16(z8)+g+Qz%8^bC|GA`R+DvV6U5AWF=Cck+6Qm7-#)ni|w!hQZf2e0tQZd_-94p@h9Te}RKRDWp>4|V|Dr+%*iUCzF;H&Iir2MA6zsi$8kzI_gu^bDlim_^OLn@7|1 z0&HCWKufczY^hT#*{)h7j9qw6)!g< zfE1T91|9)1RWV9b=aLmDd0>>?4UqK8dgswgl_ZqiXC>gE)$W;HkSvD;VfCqVuhj-X z8Fx6^@S9N2)Jq~DCFw#k z(?;}plvF-n{L8$-u{+^$j1PY;z1=Nde2!Ge%J`d8o0cJ0zRq~IB%~8MeLk#kFAB$( zn2^Vx?f-rD*|yLBlx-q(A<3V@xo86fk(BHB2ag^}_o!8y{$3nJ)DGVBJJ}w*F+5T` zd}}s^&OH&oVz1B5&#&QkJhyFO`?MUmUsUyMvtW>d{;A1Yho1FU%0b7v&!5-KpRa9W zlC}OOk=!>VR~4j0ch2xwq<64nw%lj$T`0NFZq+36lWc-UBB6Xr7w`a$K!~6xkXu{n z3D)VSq*F@=V9L>!-<3n;yb42Q^*Z!Nb95u_+J0JjewNd>ch(nA4DM_G*WXQdrf<6u ze6ar;2LJni@y&n;R8?HldIS6FNaz*+)&27kH{ThTL91p%;?4UIs@aV&5I;0}tsr3M zw_GKRjKubmYtrn^dd~F#F>OW{tGT&-iv?O*ke75yKRV z>@;}Jt3x@q<*72s367y1{YH_#9>pY_-9Ld6;X*s36Un>O?Di@z-GGV6mf4%xlQC^2 zGP>P}6*38msW@PirqumRW{n+5NGw6YfE&!EXZ6sBw_Zn!s1%S8+KWr*3-8IocTH`{%JF(E5a?SsZ&`E zlOVw3r#`54Q6T30qq+NL#Z~CNAIxt>(_k*G|&rlVOfak}Ax%=&n2!&oY z0%=m_Pz#T_=x|1fhfvTQ`?J+Xp!hTrt`a<|V2`0Mt*>F-)z!&(s922Xn=tBy;v1YE zJc+10dJ7N-KmqRqfpn?@&LH2(x)HE(Zz8XeVmt-%#1-S90Z{F0Nqf@sESY;Cx0}%dJ*R*EMHFU4;zGsv(NG2?9Y+gjf_at`gld5 z`LVZg459bOyH&4ZXBn^Vp!T{s9}{R9k?M$Jy#dUM^RLqkBNu}K{f(3%f{R7`aB%V3 zxJ4GEIpbs5*{fdO1bF}gdr_)|;@o0Vp?Vl<)@%^mLLWksbuX3Qs_fR)y~uVFOzDr% zLH^ZAsukfId4D;WZO}A#E(HDvsf_}U2dF^UXp5{TflP=7b=9=xg`lW;LtJT!s7^@E zO-;Mlw2uPtY%UeA3`%2xyLvJ%x^D}$v~rpk$E{xS5uuqaD$r@1xq}>)Y#G3!o%{d# z^Ym)>>|or`?@w+*J-ws(*UB0NzCu1l2Ku#>A}VR?o(&1{;{%rV1f6F~lPBy!((=H| z_b0raX3NM%2OwdXCsJ@(4S%JGu_&tGIA(f(bu)jK@;;twg36rS_97Gq*_k6}?F6A- z%&Ls37XXHOIk6eG276KLcJU58DCGRqH#(lgsuAY5)Y@+hrV!mk+-}4dZ9$e1k=Qxim!NFoO z?yM82s*juoqhl#e{4r=KG|YMyg8u_3IE^2Yw!gqg*4VlEd77_#r@O-{aKF@!b{sB6 zmhm&68bU8iyUP-ZxWS;Y3s&*760x1Ad@nHGjq2-7NJyS|0=XugPI7wsgWAIL`_1OH zCBD(x23p(j7x5JVHLH6F};yl%#OZV+)kmYiAvsBR-*B&{#M zYSR$^0-u@Yn{COak{V2~ru?An{YJ(qNBYH@ya~)N*c{#@8?K>tJ9CC53ieqK`RlXo3|xMnubX zK$A*TQTI@?ltXfdK0j&wQt-z}XvDEfu7Oq zOThL5mDPgB82BPtW)d{vQ7*hns40% z5OpRT1j1rrcLp}hZO2;9ATuxu+ABA8CvM|oK-+p#Dga6k_%@6uvu#ETlhf{K2Zv>J z57~wsWbz`i^umP;JRBJjs0%5jkH7!u-ZMV>X;AmqP%|2Jj(;n5<(9gPuu&m?P4eSa z7@(L}HzLlhh_S_X4*1;x^b}VwU1rt1k)}l38jqzgtSN?vYaPybgbJ003DgZ}#XS4NqVo9_1jTp*WUl!F!5LFvE&M?!hG>l%@}Gt1H+kK`qrY}c zWO|6zHDh~&4Zx_4E9-6VDF8rDH)YBeTwk?B{#xWl=jne@W@sJw&E0XGJYJ6*<6-X3 z7lOgv^rywUOkfW_JOhY;AI)CNU#?d{>T{> z*310-K`lxS;87AJgm$wR`)oaz73zW~&IYdpoE;auX#i;eV97N+z0)ewJv*{CqydzX zp(8}C!cK9H06yyJRiZHgO?mGP%vfBpV*d#2ls87j4b}c(sAxK_!t!zv>n%uGbT~O( zOcXel?-}8MBLNOkC-VSBXrzV&hSN%1Dll1T5Ni$vEhY_{G`+twjqMYXnK_M9_aixX z)F|r|xWtQ|r=8{QwY(1QMA!y0#|S-WHWt&n_({Sdk2i8PardRcULvaGc7@-c06cd$ zqT;R7+`l2>SfVUJ24Xzr>N`q)LL|%D{Orr+57L2nk6%t7>+e=EbuCjrMI)hmv*%}x zs+XH2<^A^@yAD&6Ll3s!#l?O6c(p73yGIY;P_7(21kCu2HdTR+@f`m(!H1ffRO3ln zz7|oa!puvX^xzq+5NAOAKXmn0LP{o4Y-yB>gxPoC_N1SHg~1c>7-Yc14!Y)`oOM-R zXf@^-Q}ZLCEOy)wZm}EAn@i6SH$;Pw4cMT`2Wl->S|! zD(hQ#p9>u9&oAMEg$=CKyJ$kdpxrATm*Da!!j9&4cAYck0jUfcjB9U0Caxiwg8*04 zoj6l!Q~waPtyJ%Uy+ejR&y)bW#k84cjh|vthUXR&R}>=!QSyA3TZ$`;cw7<}{qA>~ z!$++!P}({tciqvJXmdp^MllZPzO_7*D#j%tCvR-O&Ef1!E96(5JZdEQ+soe{HObe0ev0Lr zVz;?y#56DwJXM`G@Vf$N_58n0x+M~aB=mc9&xVqa|7@HMUjO|S=qb%>a<7X-)zsF0 z=ndPgBo0G4OD!`Q0z%a{x`A)_UQl8#LUS5qBB+f`t_>;khVTKzWiNXg44UV zLb!ZCB|diJNeBs>ra8?zO4SVRkUZBIhS=b<0g-ui4n1ZMKQn2h45S=R zeBh7|a2h&z)MAn+josb>h$!QP4-jM2`A*SV({*K|Lcf*11^TKz z2QrL>$>r)=*nu(V|4*0SYYZ3H0%BQaC0>4ZVO$E{Ta%F}YLc_~TAn zLJl#5tnb+n{m)$^`#;C9hPCma+wMwzl!kfe7Ejoh3A&ho_lFN{!!Q4Ur!|E%K6ZtAj#&HMnp3v zlk*0{3{Zh(u%G4oRy}MwTFUHMu6qKL4M&8W*5lr%VKWvj07RQ1?Q}^^Lu1NrqL8f* zaOO^6sEKxVAKoGwey^D7UB&|z0LW#~Y*G>TDe+n-I=X<8k5ScAilGP)MV!ozzaKb6 zp>AFHI`sYyR0lq5yA07g+?oaWkRsAmxalRImHKwue56^9JF6zw4azqfq|hO%iqg7e>W?C!}b?TQP2WSe5L*kFcRPz{(L~dvh8Nj-Vcp;@86qXJl4WILl1gNPq4ik zf1ACiUWDK8M@5eU4@90^O~_Wq$us_tMfPV+p@4x9%ErC=0t5-KYrosr!+AA8 zImhUJZQGTPuzHgyUTy=$+-S(N|4O+!P|BTqTct56b}-JqOALnV4qpqF&mHsp||rzJe` z`UaP_-RZ*@*h{0uSG4qE+WV5<@~`Y2SqNq7X0Bc5{{b|3YCd_D<(B2wRG)q)(DZDu z22cYzvW*6d#kzecsx!XpZ$QX)5A%y*rNf)IF09~>*DLh_U^eZO1yUVx%&@KL*0jx* zb+J3wtEd?k1J)}V2irZU*8mFS)&)51bYRaFJoWv#T<1Rg%#PzpE?c!siAH6}NH^%t zpD#B1{p8W;|6eUYm8{xJ7bCO@F*RtD`^4SV!8N4G8=Mz7;t^rVsf)ylSCZ&Zf;?o1 zI8r>=!FlhW4z*`CVYZqLWY)0Sp<-C`oBoP9BHz;YG?X0Gw;PPE;($a`@i=` z?1Y&e?ufuST&pwWVxgYngYiF$}GE}j`F;;K};fw1yW?9-T z)M4six{OwElZWNp^MxdP(aVb|AI~037+)7OY$-1{LEUwWZboRQX|azzOk4JUh|TYL z($K$Qis<(mR^-v~-V`HI!QV7$pj&u`ImO!krtbx53y_k%D>(`5 z)epeC>7KNkn7U4&Y5h{Tj>L^0z5(kg_}ko#Vh|KKS1dR0dPRKAxX9yFOm zqo#9$9(QEP8wwd$Y$7|{-o**0i839f2?RvPq?8SGEwY~uoP4dKTTmf+v+$v_dtvgk zI9@56To=4)R`5Of3T_1C!3>a;AUN|z7s4QcQ^xt-3()w?_|4Oxyn5i=~jOeYuqG05fZH`c+s`6hdD`x&~bBkQNtcCI!UG-GxEd;kwGrRP5G|bI#PYl!rhc zr)E2y8YCun&gDLR&qxd*l2UrLKg{l&Kv+w=JUg5$su;5Q=;h(i_$QC#r!{D3OgrOc z*&`zit{5rGsEZr-JTzns6gI0X7UgGM`N*`@a_T2CXBiEDn!F_nV}n;mR4*L8(uKuSQ~Kp>Y-O4P)9^Glx_(E}oHY1UBp{$)%VO3sVqzD{xYc{KCd--j9 zW-6=GhoWhAmK`thcDDD)LZX9lpQ-(eP`8$|2M-5gD?7wEayFMFGiSe_M0*v$?2T1B zXW>*#0(h5Ram!>TT@qBh&|k8S&GUpkzX>kJT$lm+2~+_+Yh^UbRi`Fv4+d3=F`mHFqJDcy(x&%5K-{0g&S1x|(r#nVjfrYvWR2~c?iSVX&i+g4*JZmKVMf9` zO#S|sfO{}iDd8Gnzda!Wl?Ob*Cx^_6JRjlN`KJFh-!hj$V)>s3n5=Xm0@K zEJR-pk3r>8WPJ!qub>D?c5{*bd9&P5%I=}%EOhxWsG=zF*3#u8+l{MEA0}o#ebt{0 z5@!6yutOO#USTTuElngT=L+1e(baMbzpLRi-tm^&Z<)j%ghgNB)PVEmf`cZrAKA`^ zAD!WaB%rmWJ(gbh#K!%W+B3j5;73pnGFB3VvKIy!tFiV)pJ1C|iWx@A$2ADEf^|j{f|l zX=vW$p~iGMrnFNQ>cdQ@h*LFa%uPL_nxbMD`H>HP=p8U8{DM>kOQ$fh{RPl`jv_f? z+E!Dz2{ge7ll@0sh*@C`JbT86_+e+{y&wpgoZBC1X^yItDgnqkxrr*8@=h$!d;R$n z)g6PA6MMVe)siUfCOFSOywim6_YP4n)Jo^RTo@=ApHb%_zcfe3{Luh=68J~iksp1A z9qOnYc%R(8kS;d-t#ylz?%SDd0XV}*KNBCYJ(z+(>rLJrs=0X@xA@JtrR@mUy&vX0 z)6OA%$<_Qe4SIneov~;+rSc3IjqY0RbrwsgxP}$%4K!vlf)RS!KRa=EDE^PH_}c&1!7+XY&L5EJdYcc zjc=JP{chj3#9xqe{(ax>7t9q%(aho*F|6~JKu9E%#Z)nZ5pN4hh6e2{JXqGnyo__T za*uqPFJoV}7yD=x%s~^HwT&RYhbh>VwyyIkVZB%$8NTYy6xNBBMIE^(`$o$}@pkZNo-~372 zPFNh5+++2GOp%H|ic8N2w{0{&nnlh%aVQe{KwO0rj4r&W+Zy%>I_U z=lJ_4nL#%X(oo7r9rX-VFoN4mTeB;;i#vaUFf_rF$XniP{l2q7{6LOs)YG#EpRF52 zC~Cjz;sv;sQAY=moO}8cj%$O^LS4t!7<4Fj6_ey<@4#GQ<FY0I zzW@P>+^{=Drg4eQJk9gd6p$Hbe%T!#x;9#-aQg1P z%+|K3E#(nfS$ZET@J4hiI*TvfT^I_kd^nu;c47Z)t3_JD{eXIP=eLa*?hvQ~Qi1|} zzWy9FhwGYh;WDkUQ~VV^sfAG028QVe}koa-iFWk-4V zu0)5WMRec^$G`w3NIA(xWBf#G8PW6$fzn`miUPTtm^j_7gfbRQrROasH+ z?iK+{+&z$cehn0FX@D_jxz*Qy8A;mGY z6mYX|&_R5FK%^ARdMajzRr2jJs4`F1f?+@hvIPH&0;CaC1)%Wx`syMdY-g?g`C?3s z2jqT~12=bHL87t{R|uiH&j;f!_j1QJ#f>^M2DqZjBq6Wz{4zMtcxzc$d$aR_*sS!_ zF_QBv--If7sqT^C>3c{p7!VW2dd7&}5;f2phfOX+&_0x12!)Em>Shqu2bLjxkFePqTc}SSDLM~{%5&s1 z^VcYyRki+nvVBdHDGd~%tZbi?l@`i)bWXmN;+QA7a6WhKuUTdNQ0*0{`3E_RWBT}o z&l#5rH;EWkErwxsKKRb)ojD-0)Ojsz0IA%=x7Gi?=L%TuR3sL^kHS#64?R6hQZ{;i zLzh7iWK*uHBWH&?b_)y(V9f1?Ul+5gL&K@YXvXLu_|0?_gd6!1*-}*s!Dx(0V%kB- zOyA^)vMVFTyqL~!jh9c_EH4_xLc-bjq+#%cFSP0xGEz;tLMZ=J%8y`AY`7A*@3g!r zYknp_c-F{GsGo{C&Pim&RG#apZ&7s3V(OxcR5nsQ_zbB6dmm-p)YG;2Epi*58F&rE zSO#u|8j`<}uS09u1{R4M6epRcO83mavcpqtXFE<=Fg_Eu%&(JnA5~YvHrW0!rWLNg zlAy8-W^*xQxEP4v*3P*l_~~JvW<6UyN4@OkyY^P!{z4iT4xJvmq$ABS|N8X%+fS>Z zLaK0>k!mMG!zhW1|0i;)zUP8E=1DQ6O3s6dC*DNm<6fY-$otR-9~sWrOsS}C7SB{T z)aK4oT<>Kc#5M-m^W$BtobEiQsM!T%exZ~mGz01a4xUwpMw$~CS_^&OudBqskI-n1?`iwD8vA2l*~vqQDxN$OKIm60g-8r z<4T}*EE3ax_)dTaudu;F|Eo~zZ5krjG*nlyqqq}M!NK4WPR`Tj;prJuZtZsjJ8teq z3xS!ky7^Xm?P^XFpC z-BJhZt(F&76~Qr7>J;BV5fW5+8BBdS!TV~2+WtjGZ=skV9eyy4lR(P0QCwDNQJgN2 zR)&5g`%6LRfGJemD2XHMP{Fn$i;!DNlw0{8pP3*ium!7=W4!SJr^hm^dpT!PpyEDS z{h9bi#yqRebz1wD?>f(R&vX7=Li^6H9joLE&;%b733qn^9YD#XZe zC?;7rxF3^J#_ZeB{1*PRvTZa(*tb1_R7Fwin%ugg5^V7j4I2E%rZSK!?!RtafQKoP zQt-Se=`to_N0%h;WxqOJnG@!VtleboQr~ieGIaoSOvs#Ngnlvy+1KwJ>A)s+yBCD1L#&$q1N&3`r7tD~%E zqwXnVLj6(ugPC1AEUxSGe03kEK75uqiG&D5hV@kGpb5#W3<3mr1i48M{A!zPHDV8n zz-n;5yl2M_{cer2X!Fz4&bpb``#RWq95X{JW(kR^-qOvYMKVWXt9+~aAf+-*@ygY+ zRpijzWGJQPWh7!F6qJ|h`;zy4@l-1bQn+!^a)HKl5p3Q1 zop)^sA8_NT-`2byf5nJDzWrvlF+s`tOwOij7M*tXl|RRT>ESVPl(au@v~>_1*viF8 z$f!NiDQeobm00AuDmbfYL)t55uaQ%T>2ZH2`e(OD5^^Xf48bcT5oUh|$$IRU`E!@& zc2#=!<}xdMC^XCvF)yr_-$c@K)c925XOW7ik{k1(Jo%fiW%bOlIObGZq$jJCtuBNn z{cV2}sf3!n07!p=XQ_={qx6UJ@|s^9yVP$&(d!HyyMzpLyli!t1td^^NTf-s?uBH# za$&rI0atdvUop_yS^>9Si7M?|$q70zO|-fFL$b{mD42!HpjnCHzx-&HSy}(P+d|3d zbHMmFSS;jY|7W=3D9i<#OL0PqKbuoxFt}UjB!Od=U`lUq>Q_w_BLqy7R54f1vp}5i zHBS+W=Y(Btf%Os&w4W{9#+BpN3*B@Pzu#P5UFUd(XJok&9IEcgylS>!aGX@Yf$O5v zD`m@A)(@Qm$QRq+ z3s_RLI?{%FvgBCsD7;$zcu#R&SIYJ;{nj+Jj%aW@X;oZTDt2!XbAL=GANGXqPC zXCj9}p`zz$d=C)7Vk)&cnXKW8fT)vNS4!Hy8>Ue!CvgRvm-$&CC|ORG+fRO~qCeB} z1sXy4e&e_5lz~U3iFX-o z|K_O=>E0{5haF^ zsMxMfu)Zg&``@^McyU;x8Jdr&r`d`hsqwG96Tz@jia>STssLF-Lgq#!y`5-8o!8oL z!BJX8m*kh!l?Hwjb6Zuu9?>Y3)4jLv0MKMN(D?`A!-#7RXU+i2v7AEDlFHrGgse#e zcpKjZg%KZ_y7guAkDBf{W)*$hXZ2hbt^?Tv1z!EaM+3nTv(Pis1rxy?`((Ev>pv#Y zzkzp}0v0l@2O?0RAWWMb`&vwWLjcK-vtqW529->=&~sYQkoxI^+94WM7=|J~soqb! zq{#Ds0!iCxkAGZDK*}bZOMBB$MFZ&xeem^Jldk@86jXCy^%KeG$ zD0Uw-@xrqRe0^7d+%+7t(ItVa4p$)wo+46-*i$O5dmv?Xf|)WikKzMah+fve+F@n= z$v4G6`x4dOpkZx#<@RSYZwP`!c)Zz**{tr!4|pf1xV?+@9aUB_kXA(yG7{KHGt z5yMG5?FJQQJ$6x{ceMEW*dtNue|AW-g6zi0rmi1fP;0&Yj4SQ5z`ekKJ492RYHTvp z_#bH6i;=}ekd4u9#1&8sdWT-NMaIX^|KT<0VwA35Fb<4U2E4BXNk z{Qk=Xv_qd_Qu985Asi((z^7WunR4%XA*xzcSd=2S9$edRQXZ=c&9bpkacUc`(~l=bmH$6vOHP5MHsR#*kQw8iUUsLw>|RA0z%b z+~pG#bH5AWUbTypJ5Tvlq}@8$TfBJpAy4tidtIfDXVc_w1=oWuD$Ha!5>d0O&$IO2 zmwm9^^DF3s|9K`c)tBjgf06h6jR@-%r+FqS+fCThuJbW-KM;rYjziipNr?72fOZV` zs38pLudCElNl8MWHaUSi5A67pm4p26!UfKb*Ts)k3KAE9&d=DiZK4~}TIDgaaV@D6 zG-g2XBZQ;!Pyz}ExC=BE1csE>q+2_LZUZUg;TuptCEA2?;rh5jL^Kkv=uN(7aR)Au zzd$ZA=Pq*Gr^^Qq!5WrFe>Y*DAme7Q0YkrbHfo2}1IN2~NtD0!*U=u%M@{IPFgv>Y zNR)zTU>XsFr0I3xBrK)q_Ue~d1Ugs}n$&DsY9KKH}f+IY`LG;j8nu=PM475gA&dd)}iFM1BoM%R* z1`i%kAyjMw`M~h9e32WxtjQ6m-R0plkkWENu_PJ#Y{^4h;8oXaWV7$IciOo1{B^RW zB6!VMayzF>Xy#2I4Nb|Eb1yCFy92(Axy|?SK;oBi*Sg6oL|;byGHU}~GX~tU#C_xO zA)X=7MR#*HVMD@(<|I6Brp@_B3u?|`leIk*rn_gocLlL)Qtuq^&tS==Ui&7#WX1p8 zkA`+T#o5n09b;R5B&?a0L6<4;YKE>Rq`3m`Sz~VGVJ62BA^+aN(t(&eAq8lHZXvq) z7OMUWo}T)@_`8%g%eg^lB+4?V~s#% zkNQNTZc?Je0smY2?6)74ZTY+dL$a)!S>M*#;z0MURG3;!$H}IGjGgUPx9=4cI}4GV z(18Y4-hPi&h(8fA#fb*4e@`tzvVvD9GhgcQi1-&CLg67CiQk2!o&s<=FT+vbk0dOZ z1o~1PUHapWU1!7Mw;gB(tJC-|&(JU@_aJ!fGxc2Gz)7h~X-chqOYz?)S0?VjgMZ|t zW5fwgz_0i39aQb(@!?j^qf{`9yrdlQWj;~mGi8RFR1CBD=M88ee5Uc|mP#!efeem= zkI@0b&VY#%Fcoir1>k{C-!OBzoUSxo>IG1ky=A>&FW{G@5)xd`?2+x`Ny8o|-hsa} z`NH<=8#T_C3m1uPL`|A1M65uCp+7wBMokZHH+NDQ?anI80q7pR^h}@=F|_$5!lV0& zevGsK4(epH^%LNcC@oy77>up}LOcx&4=k;gbDyyw)`zC`&M6s*Oms?nNju5vV>b>I z0$)HiJrzYXtyt%@qVI16=-`-7?>I0}MO;VXH=$GH5bp_9Zp?%DoM{um7rngh$rB$o z!inP_yAWQLoU;9H6rVVAI{2f7#mKfEYZkv<;i{G>U@4O;%Ts!|{?A`XR?CY!w+ z(&gN@txT7K1ziTz%+9R@QPBD)e<#slboeK5EBU zFThL9LgUj%DSeNNfn#}Or z_Eq}VPs%_kd-9Za^CA~l<=(-IS`yP^oX_$z)tCRP1&BJJV2JJ>7Q-}5hpWwObaZ8L zF;ZASLEj}4yTGcB74IlQ4|9fQb_>kJc6H%5dWS*+-Bq970TQ@H08^GGKwU#Xq+4k= zS*L@NvOX&iz% zKy9JUJE+-ZA008>HMbz}d}Fau8>?(x-U7IyL1C?t2b~Hz@+VHccNnJ1E0w!{>)wFT zy>Qff^0Pw*B&Nx+7e7rk0gaizg9lm~3y~}?qQD>zc?3i7yS$G{f-WKG!Y9SOQBfw=!=sBdF$iN1`JAPqSKLXCYc#8wy zfz130r(}5b<@cn=pv-P z33msp3emh$$tWhQUl`}la2af=r{_n*Ay)+jANcRBU_IHnFZ&&AObXrQP|-mCgna6s zP-6#P4TGSk3CJ;!VVF*Zp|^qTOm}`vqj#%d@$BYUo6a5^T#3zw8X< za-0xH+b}U(^|uK=X{j41?;MsT96&;T(25m%+`RzCv_OBt&gOV&F-#5gH#xIgK{k<2 zAyHcY3EWje3apmh$o&45QNYU(jW}W5O}X8(7c)d76bO-OaERbi%pH!X0ntap87^7?Fn&DOdeys=yF0ROca0*hD;js4Ak1AzLbAiyrWT|Q%eS> z13_U53ttdK@t{6D1M0WdHyv`5Vb_*DSs&E0c4oe-zqOZ!(o5KQ2wLf>ikXxVcfq@- zD`oq7(BqUxigFaE?=R+R&~tR&YXXrKg5p|-I5}navoB@}ompG|t`vAl`e(`Zf~lPH zgxfk~ioRJ^FJ|$_x3#}!Q}&5dxVz1LlZdhA!NilX48F>O0sR&-t3UPYJHfXD6Qj(x zegQ^3BAFwB>KcPhcp@j#9N5DRurjJP1dhphNF@X<@Fl8G6dGb(jU4v~g$rLm%iB`% z=`%y|u_EI|+5Q9Rp>gA$VpfthVR|B)zjRc*{VC>QbUjPp`6^ss$hceRo^VB;p{n;i z5N7G9(wsg040x(!5U?_!u+=sX%Tzg9xV#unjc)@?ojw}jmg6^--c$w0iGhT~n!At* zcDZLFnyDgsTh{T(N^YOJUY!N=nl23G+zHH~j6gsG$+!pct&uo6!g|gd&NyK9S{Bb{ z>AHNU%B9Pf=}b}Rcs1gcZ>>x~lC35Nf45BkZcemTRGS1J=i&9m0aPTyr!s*Ia+0TSi$NUu`ZkI7fso4b-V?r|F|WoQIi zUQssMZ$4g*p}f}l{ZZGi%)%dGsN*pA{$u!;o_JoQfe8s{N8Xc2IYKnNmIeiZBw9Zb z<_R4u(&2iEjb#3P1gYsaP$Ltn3H7v&++bI=+K|CRx*gbz;9#b(F9m>nHVTs1RYe0s zJjDo+*t_xhVvZyM3~t>&{|{ep9aiPqy^BsJDUDJpDJUr*1|TgVDcvm~B1kFSDxs99 zfCz$8(jZ93B&0)BB&4OgJLVa$YklAToxS%te=M(SscZ4PPmH+7J??=+cb{Ie`cNPQ zwC#9=je$n>OG50qv&3)NE23M0EuuJK8foMOmQ1bceoLQQwEHM|FGF1`{RkIv(aBW4 zGyE(!1k=RvO$n#1Og|wRNg^&~X2pa%?zS>)K;tbv!^3i=It=GUG)_3l z?L-PrQYljPz2QgSPF3ey;0N9k@UWs@we+F?l!1HVK)V;V-JojH)qD%%*IFqbc;0yH zfcQQsij*=uU>n!(-Y`j%+(z+DYG0fI+#|L^LdeDP_;wJ-B&&;a)t}(ZiM$&>-tY6Z zqII{3<&4&^QRXr_rP9%Af#|6YW(er2V4anrh|{|p4J_e~tKY;@1>H3;sI&EZ;VrM_ zJuWvDiwWuwx@0uf zOsN8uV{G0S>jhK zIL05+@|9d(Lo%H{{sXdUCK8XU_)ch;aCSFnqDP@| zOh6@2HCPb`u6iZvLo-`0QGh+F`!$DJwm8ik8@NG#<(%s}w<_7)J-2*}P+XF!f; zKrUwFHf2O8b_iJ=H*HD3(q&40arYnjh4u49cvNmGAzV%u8r(pAJjc zjKMP~w6E#N=viVK^_j(;-)T@5boqMw8Rql0W#gcs0=SQnyHM5q80;dSckXEU;;tJg z265sOPwl$DOBDC+bH068*gttBt>efM{J^w~zuQF8c+2-3qnT2RB_2}e9Fc3L5#Z0|jMo2)6y3vn5pm)?+fR0wK!K{o)qnl3eKTuq)b*$i> z+ejywe*X1d+jzmf-Iqd+eg@@tQ@yyu*ZP?xNfLv^A?^K@ms7R;l;b>+w*zkX3t~JZ z!ZG&>I=BzTIi3f}JK%A!xAp`YlW^meAt%-Jzl{QQBy|$%Oe7gGqcU&7StKWW=Ku+l z!99Jh@%6A5ONP+AFYPIE6*z05kpRYh|Ng!PNE|PXk-lM%&2tggA}<8R3wrwfC||V` zpZ<9zxs}6`Lviuz4xeh$!HQ9qeulc>9!XV5de{t4RY-%}i>yabOwT8XN<~K_*@fz+ zljo7VpY32OBTWGI(hCh5K4al*{Bx)LQ>&_o{8Mu<@!tJURj4sfv4x-Rz742Z6PBgl z#s;|yibZK~k_EOra9{p?ku&yQka@HaPwwd!dOPB`AekiYZ~0KjrS@}v0L_G>@uf+f zIcD46n$2oS)6VhU|6fcZC6D~n);~Ia#p4l85@L-lG^#nu5 zZ%S>|@u2k7n!GW{c0dX5_txo!uxeJ4b4|YbQy{R?jH4Nt$pxjD>+^$GXhL70b)RAE zbos94>Xa@yYi6q$M78XCPUD}IbVv(l5Hc_<@$8&_3rfcdCB#kd*LFA5;@(I)x!v}D zZPV#KAby1VK{8oDHyHSL?JRdPO^sH%Ug@m3STX!P%UU$?$;~1Q>LY7)9By+52;910 zF8Db{n2G+T)KoHwmlP#HKuXWzSiK&+Vfhn1uD6OEf=u+RxYw64#Z}v8h z?EXXHaKdsrPaY_@L)s@6E?#5{+mnmXu72sgocx3i(+Yfv z6sj~uE)UU96j;acE#dA?n;GTkUPiFnFx973*wt#!%`}7JdwwmaR?R$6c2^$saw21l z#x_%2QDN0`%APyQ__=U!1+M*(Y@g8eoRl4FyLBfung#OsZSOgfbB8L`03$D8KLTVY z%`^3Pk>wCA$C2E}vJufz&o>@0!Ma`IPf7pS8^QJIbo+fmyt6IHWk>7nrPU? zF^|HV&k;-cWz2s{JUpQZY^^Bz7YrZ zUSa)odb(%MjRo7!7sF~_m6s!o1`eLR8C&1E{qyrC9VeLq&TzgFc1>(qQoS^x)JMl1 zSAP04k*i58&r$nq3T0>Vt9>PaoxPHExj&k~AIGAk!G7g+UEDr&!L|YYD0|dp7mLp@ z^2PSG8S@yhNtMt28+0z$nbG5qs}ptePMA(zhS>p{6)x7rq*0RyZ}TexM|wC5U*o1E zz`x6QVv6xoB{=?s=}Z>Y@^i7;z1Ky{aoMQsb@zyug3ssSXBdltNA|CXWiDgVxd-c8f(b_=Sr{^Q?#Op{#68_{tX9Hi5ZJLgqi)`K(fq{M0#)0J*;^N=iE_{E3Q;-0dP_ye1IkP1F8$I`h_Q$y|ZW(0g*h2 z+_Z1a|4gkV;M^#E@QZs|FT^~$ER+8fp%nfru0m*X+dh|cLBI%h@1dM9(?5(k@kKB( zqrNSDSyE{bZo7jxF)@sIbed>jvMAgc5Q!4PNC1I@%7YOGZwLfNy$xpT zFI8Q9Q3Ynt9JiQeN|n=mm~||tiPStq3Vik;K%_pL0YIR}IsB@U9K?B<82on$?lYb7 z?N6jhPzIN;_Qze9f#aF`1R$QEWi#ooi`CD{9uCnuD|1&HN>7lc)HwB7ibO#G%}^wMB3#gAHF?@y$hI|TZRTu-*KHO`a4?Ck7B zVj)zS7f}#^e zGpS7D&YyfDsRkW)4zJ17aa7@L&8^`7yA9X(yjvLELGMilAroytFsumX=~v-)dHe z^Kq-CqG^#ZFNLJVLJJ%W5_8E28Z5GOZQu;5IXgSQ;y05pl+?F7r78(|IwH*LHAM6b zlYymr{u_0DFNf>{G;Se6P8FNoqQ8{m_|0NLBC{QcoV}n&Qo!GOdWV{89XnF)oZ6eE zbsOna{`Giuv?hkb>F>gtDNoHYtayI*g(rFevCUK0ZKAYU-ofpW*Ye#_1=eFZY#~`$ zgT{U4Sc;Y?W;$a$n~qpj>*F5>ti&W1lYGl~{(0ppP=7QoX$>D_JW1&%Wb%*#W)%mR z70svmrS|dH?)TJ*d;m2P#r}K~adLr+Cm6sPVxfQ|GQ@cGUN}lVghzksvT=Kn2{&Z| z{OsnL%13>lk-%XoU)<&n{#|L6{NH~gutNJ!#4h4m5?wMzxX5* z+CJdMs?&adx#8a?~ZE&ed2J?H2BtA5Vyf_%|;6b*pMb9hQLplk)dXb%7IIMhoX;2Gj zg7*~2t%xU$0}N&F-c2d`NF=v3T4N+&CJVL0G|=7R-Jm757$l$xg(h#lN~OK?fn;@j znE}rMLB9U|t`jF@rq7T$Iz~{gD>UDih4PItIs`GYQ05Pn;*>_~xrnNuTo}37P`& zlY94_d%yi&EQYhdEJG4*_@ zZXjV9P9b9D6$BW1{#SSNLokIp_xtnTw@hRx#VFy7LK8U2iNyULmU$2exY?I{ETeSf zk7FM_QD)V4`j=jYO1u?x0knS->XFjDDz-xPRtCBbWM31rR@0SYH0cIHJL9h^KR*ozQv zFog`I-ljM!;ZwdTE@eRNKUD2m?A7(pC#(-@Lp1o^C?AEgOV*O#a^>I9t@d!XcKwP( zhla3yhITc=hTP^h@IQ|zSc!%ftaC9+ZGTzNAyGH{F8tl+2k;l=RS$aHNaqeg$4c~k zQ_vQ8&tA+#pa&4|vN4lajI0!{WJ)Q)Hmg4O;*yM86PiBvy98hSsEGlfQLaL~TjNys zmI+vkyq#ZD*47y!EKX1&!WTM21*75Q3(FLqWBFmWRH57J(|r^HQhVWory(I@at4t!gAQ5Gi&+@z&KO0d7(O1J zzE$-hi^IOIA8CGM^P`(O^Vrhe)fbCT=JbO1otwK8Si z8a4Mg&{V-eld56?R6ONZdsbUYYaICPn*P679Cuentf7InUDslvH>;iC&)oOag}3nR zh?ky>Qxr78zox_D7Lrk)q3@k?>8fM&X{?#PWE~o9&_d*2XmB1ktlAl)g>%Sh4$}v= zj!M2sOsZrCP$BWIoBxjDzRQeumT^fX?m?->E10r55G~G9L< zueNIIpk;=9D)*Qx;1&a7P$2Yc1r~V>hQA0D_w%4io=wSlcdqB-j~qSzxS4a;?z6xi zX%*1$>Z=B;9mktsM#&G@#{11)+>?mpcr_eo3`-S@RDz>;^n;9x$8gU4R?t zf~qt-yu!@^MmVc);Akkh;JUD-UpxGWp83B+L#_WpLwsxQ!*f(W3f%dvIri`0_0H0* z$r!Ho)UqbxH@If@L!{P>&$Pne1r5J#WYaV!*kj5Dvjhh;{KA*3m?5`k_bO;yATuBV z&G{^t*JMEA1JQ3#;+}@K6n7EmnzVzKI#0U85I{C67@m?E>&xE%{CHk73rKf*HCpf? zS2)<&TfwnuA3~Uh5F`|VCvALS87<`Cj)Y-ZU~|}i-80i>IUv@jI%!Dgzn@mI$ah<_ zPMnEi_0Ujl|8XbBM%#emkKZ_tww)KM9MkW{-+~sFz3?wFlg`N5BQHmQgduMR40yVa{TAd)=NCH-47G5qxHqV7-|$Zk78c9K925c%1x1RU zXmw;UJJ3Q;A@9OF5NAv z_(uGHxB$z)`JNIiy}xGr%8N`+dSW>N=3~uXDfA6E#B%3n7u6QDwMHfnAf2y zo?qEBq>3VT9I5;@c-w$;AyMxV#@5U(Lc8zoJ`Y> zFJhut-fSlk^cz+xujL{EhUYrlc2v^*%wcpsBPM+$F!c+{m3JKo% zYa~37;&xQNhGWc{(1No0A`T^}XM2i>gz*SC3=7Xg^HT@!OKDNp1#MeUL*CqmTB)Ls zPc`7Px;1^d23Ha8MTh5}dl)U&DnKRShN|b5SJ;~aY=cob7{TtD+rYV-d7?6%6RGrr z2=!n<_iqGJ`%idecYNG*Ry|OPy70mgnU!B{B;)nFq1A({I`jK3uc}9}CjF~Vift6) zJ~2HC#DFu6X2TvECM~WP4ZG?Y#!Y@pJ~aIkHXWO|JN>FAL@nq+sC@`r0BX1Z3Ab>d zC_GVMpx4YaS@cg#CGJLILuHF^zCWI4{<}4r&15`VbQs9H`E|9@%wC6t0}^#eTmI+; z$RF+(Lo6Y9uao|l*oSRs@1I6O39P&Ym6brM0K-!#d@u4K5W)55aBv9@f{-&AohA<@ zex?(sAB-W~S&i|!&aJQ_wr@4k=NoxIH6PRGf3zNQ%~9LP&3@<)+TU#Xm#Rdvzzu^y zVTLiNELe>u#{XE}kDKapmn2$z_t_bqYWUwMf=8KAanCMmx@g!Oa-lAtiL)gU>t(64 z{&IQlZi%<>PmVU#rk{tQZIk{?$C<@~;AGE!>}U?1LCIeXi*{v);%_Kji+tCAE?&H# z^()Z-YXAz)PwkiT@R32SRUkFLhT*%i2dN9( zyarn_Uz?_#jzq@rPZ|izVc4I`L9gPr*L3zN7ib&`By0N4Hl`52w;|~M{ej}@o}b@#+vR>6b4Fx1iCaL zGvKlU@?>cMg?0Cvw*-)yI7Vw?%{-1$Pz=QNtkA2@GPn6Lgz2>S%PYIwPLIJ7?ZFG} z|66}m4^-fyTwL2d*tQd#lRUOQ8IIrhna+ICu2k4|u=4%ml|Gq4Vblhne(7ihLmWd( z___6HpX;m2`zM`eTYeh2E1aN%kl14Wz^A~WLcRzJBr}N{|EadFn}i1b#GBsKx*_f{vR~=9&O>C z7y>;MBH_B*^VFYUoE|@piZMOqZ)u$_qL#xQ&|n`WK4X|?AW7#jbLry6HoJnFnbyv7 z<(gkWZ2B%my2M<&KXYC&`J{CA{2vI#xn=hD)+ZOn0DyQ6iXfRS=o&cyW&Dq~`$x!^)e{Eu45yP-#m&TZ^j-Abx8U2wA%lAQ@uhMZl>8*df$P zZpa*~4)PrpZp-g(767!^Rulq6I$mVZ^73XgQ8-yMb{F1q3XP>~eHlQ`Syv`DNeVMz z4&;m}Dl!rts?5KI2(rtp6e;LZz>1*p^F~7anU82DWbJLGdl1he5M1}*((e*w^)y19 zFQwun?#QQI}UK9xan4`Sa8J_&wg z5(w~o9*a=Nmx08YZovrfWzpUtg4XRGG?&$}X4KhFr*VnzgFDx*aWVZi@64 z!>o$mmLG*l;MJ>ug9Z)jprAFDN1zXD90Bc#$zDo@1g9^!qT+=O_H4;=VjpgR!aPKO4 zNZovK{7V9w@L*J}!2zlcVE|x*w{dw{?psqE9lk40M@MS{5}>J6%*<_04sW^ZGdTl3 ze9FJ9Zu#_I(6XPU!fSO5MCyX0WCbk6!n*{;uWGpyarf*$HNiD!2>Jo|zH} z)WEt`Zaoi2hP{d=yR1(sGk97LvcYoP5D+FZr(Hw?XBGC+#T~+tzq#7OFO~1M8zI)! zArQzeLTK9y&HxLt{0xhwxM8@)c?akwFa8wUalb_4Z`IKX5v`{wKq&aCgy@jaY6oec zt|43_DbM*vO^_>hkMBhtYxscV-Ujv;ou_gPcT8`dQGaU8Ge7b<_ufp69{|2kXEtbM zp?K>$BICn_*Alo+u8oGQ%N zFvj`fTYi=lF?F5lt$^Xi5Q-e#aeOi0pGRFrL&4fEs9(&Q7?){Mo-Ij08mU>MY-;B+MT(6u*<|PRZDo8-B&}AWnc4?0 z@VDXcYQY^!%b!M)AoIc8ei9f8Tc-ePVs zFop+t#H;CQ$);|rqj@jt=5g1MsAl2f-m1euq4bFT7R|~DhS_iLBQ=+%?E4fN&!11} zc1z94qF=ro?^KcB*#L;GS5@two&Z$s2+=^rTj(|DD!l;Jr2kb>gZR<}?ow)wf2+59 znV(cNv!TQ@xGyM$~n;?nFhrf zxkhDtgP#v}#(AoNoS_)U_x{`Z;<3N;(%MAhMJNfiE8XJRn90G>X8=V{>2d3DDfvwh zGGqs0uEoy?G9<+@#P2*h3poDol6!XAbxUyB-uVUzOMp$%gp|ussrTx9MWJ7hU;v~^ zndAJInL(0{mJuAE99?8%1{$k{Dy0ZWFSiJNd*k7|I;DE8Tr-R*B+%179j{wf;F6~S zsoG_K!`d~GU-VQSt2@@riW*Vq+Ni^&pf~*l!=bWoWx#xys+$~Fu4rVaB|Gf-Fe!i& ze2k>B`6o;7!P)tP(VlidPQ4pe_}j_#`kMFJxb$;i3Pag3JIs=RhA0Li<&T=Lmem92 zxIUCUZhg%WHGUOWZd?qXI6LC(RrwnHL&ClG+4h)@X?3Z72suQ|p4P~Mpsw#7C*VsG z-)zhvT5llXZ-xE`hL@aPL#Gmnu;!f+h{M~5wOq%ZbAG1Hq64jI%aXE(pwq6= zwLg~`(wEfiayo8p1sH?!urc06={sU)4BLy%xG8VqLlJ|!@P3c|86O%um@fa$>%|mI zz&6D)E++pA|raO)9^iqnO*U8fu znUrCJtdI@L9bJk5hlf}Rf?82NlLHM2hP_x`qarELVv;VpIUrLLa=tCcmq5WdGBHr7 z6)8c31P)aEUf-xBYdn|$ADF#IewjI?iq>rjnnw|<)0Bcf!*S;gU;>0LleqWIYgkYDzTAh0$IgCZIqtyp4ZdG#iF_fQ=?J1C|t+<$p4~yU{9h%4OxS_(!hX zc`p6(P#@p>7+zBWwT-C`{*FHTN9?HK^ZKb`NZMD3z;8EfQ-=!g9Xmli>*oe*rLslG z=sz*DZAVw5V*H&zaDyZc^cSkFw;nuQ0lLLiWg&p3o+L9LWl>PSlED$aEGB(-IC1#1 zWynpu0Q{Gy35w)9!G(X*WsLu~6z~7*==MqXlN&v|PxG6J{C381VW(AbM zNs!qeCwcwR!1wypZOr1z>@X*`Kgs&k`fE@9#!g*Sn#tkNDFOs*|F>Mt!pqi^%luMA zCq?#o;a0u8r5=uG{n&tsTz4Yzur3N9bp0@pb}g?ns<{KABbw?o{ue;ho~4z^jiQDO zCR~_fQRj*9j(nl~!2>|KIyRW!7dF`n?v!SMsrWv0%Jwe8IlO_e2>**pEBze>1*cN7 zMM5jyNiO<-+&3i{AY6^G7EQ=(kYKqlFJa@v+p#Ut;3oqu`7C28+5ZJ!8>@B39uNN1 zthMsX8q3U5Ik+3y@n`Zm-|?#2;wou(0P%oKV8BE{?Vqw7ymI}?rkMCr{3GgB(A-l5 z4-+5U^w~olh5rV|sau_WNaTOHSet>9Mj$OfBDD;ZZ(KmUykas^R4i%Hbl@SBT7Q6s zd7Nc|8HNu=#kznP@%Bw(%tsW%AFy#QO9NN7-St&_^G%FasyFX!J07pn9*NRp#}IdM z!Nm|#ksIvf5CUqmTtZ$;oAqp(rGDW5Dbv+^N58`U^CZ>f=wCdsN=@xL))N~;JBC`9 zd@u3u&ha+hj*Kgfa#t@fsn{q^Q}r&}6g44rym;q5@mtM6z;d*@qabvPRR^zqy5p;~ zCe9EyssoSOUxrHfE5I7*dIhGYvjEUOiU(azFG+|?HoAnyi2S1FEfK1HyL87CBj|j6 zaU3(H@jOIWpdVq*N(?C3iK;bzZatBs6}Ui;HA{^9$3MB1l9-cWE&d*29dZrjWBxd6 z!_0X^^5S5uQL{#qi%UH-GWb8@(Ixv|lEnHLTqM`d(v=~o-mLu^muDUoQE#A*lK>S?yVpTe*I<|(_}c!c)K6$P zb#st6`T>N`>oKHf1v7I;>?5*@s@k_Y$?J zs({87oH4U6?*SW?va(`pY(OK8M$@dupt~>1OEZg9qVN#=8qm7*g!rujl2=d4`|=*Y zGJO+gy2w#;SUX+B-4Vz4hU0WXMctUgw=a4-l;DA zTWYLP0JJH>Lo%VRc3q6+9xe69`fcCjy@-mRs5b&ST+HAi*R2Vx_jEhWv~@0xt8DN( zIQ?q$GQFu6+zDA#oWE*m5x+~#TeMlY{|mV}OZ`@f7xQ0T_@9W|&CfN;uRqlu>T<_& zO`-jhy;4ee4<1B%JzPoo#dqU%vKl>4!Op^^E~AU>Z`aM}8JU2;rOna_20z%q{DvBS zIPx{J>1zy@GbG>EI^X7Lf;Xs(qm%nV>G7DNj|@uP8(!!IR9!QUM!A!P2s8l+76|~g2Xj42Z3R}z0rd{Z)#ZJs?fe_D-`^J}c=Ndt3VdhvDV;Z8j+uhRU{!J`HIrHZgM&IoTca zkMj}vq1+rEKebjSDeHhUcm{$^33#m21Rv3t;6({}g_*;b&1E$tSsDZar?C~n<~MjK z4CGLo+%2H?@dTYp!VbX5VMUI*r}(%+iKk}MJiTgOIndNgk7nf++j>R~J=B?sonMXvj3FCqFP)FuISg#xc5 zp6oq3?Yd-mqbJnFV~0>dBOS{f6r@?pN5Pb$dltBXNZ|D4;ZWb=Dd6_MrZe-=sEM+l zU=(#L4=@R^uo{BcL4_ptuU{FJihUWPPd_{h8Ds zCQI>bKhS0D9}jvV4xvNg+sES?pON>hZLT~y(H2{ zQx2IOH55Rkjh+dK5~^|pj6q|Xu&*y66tYpRWB%A0?xJ9n0yLz3s^0Ef=KcXJd3Jf) zLJUz5b`?Tfc2?H4e9_1KGY=CwHZGE+c|89S zdH3N%ZRgSdMJNM_90rW#&^_CcB@64EU!}gcZ%dB|4;I5N~E z=yNGDgR>e&g5}r`|NG;~3TXZM{7gFJP)aXA=nR6o+js_bqqivT5)=bxBp z2693x@Baz8<>1bg{txMxrx^WgM{?#@6ofUG6Bz4Y_B$vOyb6v;Xj3lOX4{MSV|uS& zyY4j{#xT4bJh*N0j#QvId{$g%;3`ddo)pw*tf5zMVfEke*)wLQFVBek5Im2^cpzb# z8OD$M5#Cxkgs(7Rgj>Y#sQhb7O9!;e>lmFBy(l4$~UPM96#foBw1T-4_7~ z4InNDW75!|FiA7tSWYRcjp9KQ)H3A6cE;Fq(hCftZYa{U1waEpeZpqLSf!!TNC@l-o! zC(10bj2y91t7g7bqFosc-F9siz;B~`3qK`rz9}^;;1^iK?dm7MhZ!4Wkc2G&;)pw% zMj#OW#wC3`a)1MIqKF?a4QO0aeU~=+^kE~U&xuXLV()vPmWNb`y-3`MQF*HGt|_{4 zvTVRodO@}|SQVkK9Od8QgtFfA+Dt~&HC}U&vzaUNXF|-0J?zEbI*um7T{8RT9k>=J z$%cd(kb+qfD~X8q1GLZNjxIusz`{0Q_N*OCw|vcESpQ{Lcq?@N*bkMeA_LGJiJ*x_J&+!8 z00gx0T50H;;J(Ej2^-8#-m2qxBTg^Mb&8i4;kq`_y=?r1zM=Quu%rXR63($vP!qYB zunqJPR-|JaVE>y@Ez+RQL1{%@MUA?R~dakI8`Z zg`f;9rAXMgygj>QsRl)^0i#FVZ;8LYf{p+D<#%F^E&S>AdB0y!TOtf^sPF@76?-VzUvrkzvj_ zi06Ho74F zR^cwd3|QYXC44}$YM~4&-f^rT{0-<*j|H-u$Pfn7&h~?2Ks|ritr0@BQi_ywjz!`2 zznouW`nN{l!#Hbu;o}B22*J#Nia0k|{0TZXd98kbW(CV4#`9r>rQuuh;FEus61ax^ zcvIiOo8Yv+>#*>y?V3f3jMQ#f!Ycpe=>*NvBh#&In(bqV@d^TJ70%c3^Pc`P0Mjk% znCWqpL&2oBBIIF64!bRpjz^GMRl9+r_LCVhM5;?rt>qWn$NFt{37w{+n_ca-T3yV$ zyf%}mk(vhQic{8j29jEV{C^Bpe)!?KJNk%7v#aNP>OKi5EO&716FnQLndPu$W_*|*eV zT&cykS1fx){@tykAfP=%H#H|H5tFu;N=x^f{IMB z2x5J0ct~Mhqd#$m%^XH`T}rp z@nR_h;lD+^ku*dTsdwZEHsJ=agNktAjiyP&3x4=#^T>EvC_bWZ0Cv$YAJ&!yoA(l- zfH@Fzo1@{%rIr!>>l@>VJ@m%mOA+|=l6SyRokdS)MX(Kn)1FxYR-$ z>&+O(C8jm1e2vuLpWZ^0i}*EI{ud>zhja#YfdoZwfxAAQ$Sn9CaVu}n!-l|Y5%ZaE z<_%*#`PYpQnc9H0-5uik+A}wj5C^&h_+vp$-|OPfNaFL|NEj}cyc*4p3ce4|hmeZG z+W{srP^3%;GT$rEl8oXIvi%|ZCAka%yP+2SzK`Q6(Jm_pb`D)tM0nL; z`RI-p!g}hJ(2oG*WZgvo-z!M?O3EwvNdf;caz&wJ_YVfWTwR%%U=2Y=NvEds2W`ai zfl{ZW6*Mnz0Ary8Ch5Jo#JS;yj3MjYra^>N;bP{Pb4L%yYHL*9-_)5Gg|Rd9-%~@ZzsyL%vr~viOJa|T+n*gD zI`%%L#lKaOAU#-QeI~%-Xr5=d*oy*s={eD}Ou&(i+uQS~@H?*b;-Lf>6Wd@(KPe}+ zH~zE;dQ)ZA27DO;xLr(90!Mo2!RK7kU~PzV!MIHf9=fw>kwgazv#T) ziFp>G2(DiER0lz!ERQx_h3Vky80sGH^!^&cO8$q{0M-SQosXPu3 zUclPdS?b&vu^(T8w!HRTJ!kX!t-p0IBgJJd&D`?GtLrbm zcx)xFO6i;F2l(FDIkWH5tS#a;h1r-*_E+dO-c>#(P)(cV@nu(z&Fy{|z)_T;a-a>$ z#he@%alZZnlbGDWKWXxLHzQ9D6i%K5p+^OcgdE?{Mu~Awx9hzL;<-^d{4!a{JNU8Z z!j#s4ST-6Z)q;p%~Hz#Y&-9qDFiHrZkY zKva7ES591u)_+)6tMw;1CzvFkC*tqJZ>&E89_&V;HJRn!%NX z)TL!`ta{jvXu`sS^}#5rzxUMy6dY-=`B$hpO+EUqO9zgRnNLZ<*SH)ONdSsR&-UDg zk`PyN_(N#mN~}oUy6#W-Y0I|a2;Z#HQ3F> z_bpz{5nOo9x-dWx@lNS?)oN@ixw)9_(S60&GkgYBo&{g0ThFfj!R)%3ojv)^;%U>P z?pZpt%%M?mN=C_5n(ZoZy(UQx=54YMZ&4e8sj^=Dc>ZL zxgruuT==HvwZ__T(@FjkKxP9c7q*+AW3&y&e^IPgs`hP(`WA+t5F;uT4A8-r*R<>W zX0w0q`bCmyZADyfie#6z9+R?r>7>WwCiC;HC%%O%jW~|XJ}q|I1@GF$Ofky=mf@c1 zvyap|!uc2fX^4&O zhxA75#WUU^sIX-1t{LDRK8JG9+0$FVsCi%y={}+#?DbpP`vD8YA4PWkd>DzAV1o9i znNs0g|2Tg7q3}e9PK4jU;Xd~MPGr(aTN}<7RgF(TQhIEjytIFiHXO%O_Sn0!rgPur z9XgkyFK4yLz58EkP)d^$CrcQokyupw1=A9XIBLEHn7AM%^k+R48&i3m>1DglnKbWj zdTFl32OBE=bWLlr zmTqWK%3qthqRrC#53@(8H>YbSGoXS7I9JCL4W5lD8NmMgME3Mh(QwA``Kxs6h{h-N z;!KV|VeEntuX4Y=4pY^Nz`*g|t%|E15oZ1|#c>Xjmv21!Z8iTr@AV(D>kNGq*X@4A zERbWyept7kW5N{Ra`@de^ui2}SjfdnyNo0cS%`d=S#jx%17lw&iG(a`4tqf8?!|Y5 zeiq|unRRPA(-&(xTiQN^uOO3G_T=>PmJGHgd$3SD&TmiS(?4@X8FMD zpu!qXtN-(G;~o$Xq(`9R;NoJ#$Vt6|vxqMn`1Zef&b8HLsg}D9%Z;oWfuTJAT)|LB zLN^73m5#KqW{8s7?I`?=jr?O%EXGt&KSs!{6C)S-$9Cm=g_dZ%q)kR=VwuVVaeX!J zxXUTTWxkI#Qmndt9E&EE>Dn%$etzOVSr{iSdyU#z8fAs9(Kk9BbR-8dQ*8-mrryV@ zwj(#Jn;HvDkL9e-o4NO<&2JL$avae21rdVwk4Bv)D7<_qZ@p!$xK}m)UDJyA;~ur3 zzH|L4H7QgZ6sxl*U#7qCpS(pab;fMUspV9GEw;I0&z&=uRDjQl720%Uwv$2X>er1E zLY1b}A|mRJhNf%HAt&oMi&EEi74TvDR%%pYDY+r0=d3^x%$;Bgd9vwLpCjF>K1Z7+ zl2F3zzIO=f8C*SKq-ItJ=w9zI*z7HT5TYxQ#5s36oPOe&$ZuiwEiMU((cD+(nBowl ztqLjP+D7wm;6wnX(5vnzGm%g1NBws@1~ZD|(4wUT^BsDP_KX|-TE7Ja3Tud zjQ^n*wrBxsR~RKRwY^v+;WC$3pniZ&i2^2=VzLC**nE6G6cU)`;o8Y(SMPHd2IVTr6k(cLySNIbM=!iUl1ey z;vHXiP2GpX7x77swc;+!1>=gZJGPv{5^u4?n2`&q0oLO%HEf)Zm|+4sxix zws|jT{Q{=DU08dq>hah2wgES}A;RhvYtXrq1K<)o{9PzJQ0rUeg#ZUA`(u2EuX7~7 zy55WGnQxABt%-z<#Ur>zJMat{;yL1vT|bUeq+|Ji|BS*<_D8shcu2}?huGQW?a8?; zsSikTgy80F#}>OaNCB&+TeFlG3{9D1+G%4~YsFa)vEK49QRvOe`{XzLHYzb(S23?b z79{_;Y;LGa-phf5}oi#w8O*09Y8v3tg&|!_k@@%eCN~Sj!rh}*|y3q$$Np)OvFml55lL{ie}=hdO!Fw5t9MP$Y>G_CP~&A+tExDX zkX&|>$uX_*@{@Z)^F2-Rb+2=I8_6M|PjF?+bVuB;*AhUdq{r_x6a{P7WMg*g))NTj zZ(mP_2_`xy@}O}<%}-ws!mq`A#@l!BpCBrhciML93pF;ZK6T$Y<-Rh&9o4J+@>XQ- zZ&gw9tbS~A&DFrF2Zq=^K@*|;j_s(&G%-C9Zz!o0n}4v!zq1NeQT%>cM)PcY%o}xu zH`iLJv)Gli-*xi!YdiC2+woeSELK&1v%?&Y94^&-^X~TU_8gnt_vxNx>>jl%*v@s` zkyxxs+V-C5PO|M@a4Hh1++XLLPuTSn8DEf?S$ZVfyL@Xw}&)xc39n|q~&GaIjs!!LLx50eKNh$f$({WiG znS|{*gv10Vr?c8izeA_>O4+!^nx7Y~0K_RR zFSQ-m=$+hZ)=WPX$LzbMu`6oHuh;wsKN_K1J|e*jw`rcquUdJR!#(dR&ZNGV)5zM1 z8xQ3oc1K=&^o_}PbW=sVke8%vL%LcibZwX{SgI4wt+>)5)ff$*3d z9&^u!kDd?ud@ub(!Z*CWV9#hm+- z2W!(kC-w(t+HB0Og)mg^`{eh}q@{KVlH@UaA9y~xZ#fbXGw|8#R>hW-bp4q4?(k3J zM_t$XQcAB~lJb~+@9q}B!+l1i|AOF|=Xe*qQ>Iurv4A=7KPf*lNtKW2S(+X#EnIem zcG`=jhHo-zP99aT0*KP{i*UrM04Mi(2Jw&t$xHTZI%cP*E$*jHy0A}t_IHLH6QD*Q z;z?d&PO*30|Lmk}J0SI4wpjGHM&9%9Fu&FImvMqH`y-MSxh5Ioj<47qEtc`0UGQZm zF>u~?ipH$Bw~KA}YTdDsXzl5@4y2u|2s*+Qq;%%}d4QSQV}8_mMQ%*vl{{NZRxwj5 zlRCwl_k`3ZvF{7El@AZcJuSS`}z*@~&5ueO>kxA!{)4B%Y zV9Q&@`q0 z9m8s-0wzv(CQkaj4q0jeMZA~H`mq3$zE&_9w`VXQ{BndS%Uxh;EUk56V;7_~zQxm8z#Y zphn89owX=Fbb&>5`OD82*J72m+>6_iOx#4)m2`fwa~w_->>3~7ojQH(Bg6;~23D4? z2VoS&Oe7+8_KYMBuAI+nr9Rre|>@|2KrGzl2 zC4butSFpHtc*Tvg@actoYeVcV(D~iQsJ=Q>&R^Qx#bCu9T(^X`1H4$G#6GMEMctIi zNnzr|1>St#-BiaYC#tFk3pm?S`cD)2BCY)Iz&Zqb1eB@+7KG`uspREMiKh#5|!~=XQlu;GV2fg z*6U{|JFUb?Km5FulJe)iT*grTEeU>_qwUf#=dC|s{FR~RX{-u{nQLV)y(MZYd5%=S zInqqzs??eJzY=0UuYi6R`B^^<5B+Xu0H4m-9F?XKyo9T+_qYd0f3^;o*3I-8b5?C<(Dn~*ye?k4w9o<5tY zktq#E2wDQDkpQdz)m)S&hW zX~nKQ-U1;Q`<)T@u@?e(B@qjOvP|aAcqFgg6t(q(DRlP|EJ7YQF9eG1!owVH7+cM) zo+?Q2ix5}h*7?owG9v>X@YhYL`g*f*Hm7Sw1gJ~J9*Mjo_F)ePi_)bL;7z**SaS4b9D2Jr+7*@NKfc<#oH_i1)bN^Dw8IAn(=!1i17w2F=`$p5GdRnha_SV3nr6|DxQ4S9M`Qt3 znDeM>q!l^!w|dkkGY-{LhfqrJKUN&o?`0FYe~EOEaEe*B*#AeG;!OC}?oi%y`-EFl z)-B(l$kDmoZ^rDw1jISsD#KR`%kaT*c%Q}i<+5MQ*(5C=@P;qBiGM(QvLq+Np7Qia z^=4!f<`QxX9(9G_tj#R)bnT9{j7^xN&X{JjJFLGtnvpsDLcS1a?EU}H^`7x?zERic zFiP~6C?UwG(MzJ25hX;Ig6Lg>NC?qqMhS!H(SuA7lIWrZGts*c(WAE@dN(+i|MNcQ zcg~0RgYVuf5jVIXN?;iEUtuM=rmoPuy;5eVf)Ko>=EnWc|jpj^-toj z<6z`%k_5(;Guxr~TzNGTQnw2A`FLkx*~Z&${3Xi*_+E?tC2$6M1j!Me(v~}CU3n-h zfDrNDjqUQZb{LnqN^V0b-bT-tI>l5|RtEX+uP&aq9y9`WOg4_qeu~JG?G$hkb<2;; zyDQH(0sj)EvQd-X{&MY0dm$o<4j1Owu*7By1lf_fe;}GPDI)igPZ4%rZc)8dc8sI*GV_2$;UH32JxYQ6N8I-)zqd7Am?o9?el4D$%l-=*S|i zE!CvCQeJMFLG`_`G;ik@(TVqqe34VgsQXgJLN`jk+G2+@eoR*LydU%5rrX4e!H&+ zLth;$Ema1sq6U5b=S*n-s_-lJ;|yUx>P`NpPSQ;A0!LEu+o1DXO-k7ZPF2$oAD zT5Q6t+JX~LjDO?6P1+Q6Fy(`VE^YuLs!*x8q$d0~iKXc3xm*EyCd84wJ?zQ_HWH{=6dGmG5?x$}|yrv6F(8 zc|kQ4%`o=vdn`Q2+;rA`MzbuH)OBh8~iWi8BASX%Nv#E?$D$SUo5g{OMC%|qID-*H$oS@fEJ+ha5i`U0gXL4 z2$`=Q&AJbNw-U`^?-0EF3cqap>?!~!f#u-8>yK+og7SRlqF{Y03Fxh8JUe+(YW{r; zqFp@{O{}^^YwBzH5?v}rDv**xlPQ;}dS62#@%EvL0nHnFig(K8L9oIKeH%C0gjyiU z1@m27EeRWge=jh=s&xRFcv=25vP#@5r!TMQb#6#kCjmI_Bk{)y+mySJpc21L3BY>D zZAqJfq95P|b}6P`>SC+Gn$1^y%U9cfp4<~yoED_#b9o`Tx`c8nBj%WX;Es!g!y?> z(*e70qt4&nUpWBqGz0Jz@197Zq^7`pl-k>$hvVq|346fS50uhOphShIrD=$H@muVc z@(ADO)M<2Ro4eXWunO{E30zTL6A@2IDIj>EwK|QrwFQUQ&NX~Brw{$$vn4U%Vl>=g z*fE_Q#>e+?qMQ$1fpmOBmcc>otek?Fg>=2(V~hl_qS>xIUC+FXxA5mU2IkvLb)8#c z0GJ}J#)Y+9;!8|Gcd&4XV|(ghGDM-K%934GXWfUTq80<@`Y3& ziIklDoRAPrfA>_Bze!32&(n1c-l3MT0~V0Kr-wWcnJ|i%&~(sQ*8`Xi$8S?SQu*{3 z>?mqo4R9B|Dx^1(%5`$wfbzWuI2Gd#aP}TF+&3ibH3yPSZ$(#K?z+ea-XhfE1%PE< z46Xy)y5H#=8P2Rz8sS(vI1O2e>Q_+IaXYB7$oBe@{F&!N;w69`q)$azz85r7lb zdblVL7dV?lT%1ljf~PL2z){*5czT__iKk3w?E-d&BnlNG;zI}M8M!MyR?K1NZ@5J7 zQ{hj7{c_>}W~`3$(_Z@wPyzS;B`TmV6=$IsT<4KX(o8QX=m+{{8DThtdmtC=ko*wE zdp{4VGvp5V9auN7_&D%%Ywtn5T!6b{%&q!QB+Ok4t_ovDJHcwlg>a9!N`>K~~ms)?IJXvXluR=u(T6{YXC4WqY~)q7ZbD!)qPHqeVZSGru|l zxawy;*-*{v@>4sYrl$Cyb=E;o@HOWuUtcod+8z8&F@LIw%`u3vl z?4K?>n?BG`YA-7*nkgDMgKx{sSuubA5vZF9K9|>LP6GNC1D4Z3u(J(Q?#J*~a6;sk zC$L^P&b6Sa^-g9BWEfH-syOK?3td6V!kYzm71NH3qju%G6{`W3DZuLf1v{$>!N1uh zF~H7k6tOb$it0@DX+_dax*x9LR1yIJgIavoq8J%*Ih+}vdfcWyI)=PSkVB$>=#>1y2d${ zPiNc#h@(vZZj1R#k(;D5caDPWO?r)3SS&mj@CTYn3yInr-lHE{Y=+VzxZoTbX&ua$ zlLU`Ry7zd{$ns^SR(wlZd4h>XR#<-g<62FX_-aelX*KHNRxJM?)vw+jZu0RO62WAr zpR$9VWr2+$pUOHm1D^64W!R}#5&Gy8-8LLj!#hH6|6Bsr9q40w-07yALX|Y{xXkl`J3wHiiE7<~9gru>B z*CYGNU%-RO_An+=;b7z~8Sg*hofGWnuORoq8yB^%&F>hUGUCTbQO!7^?$0#)m zBaaq@ugyzeW;RqN<(3>TsNUc-dwb|;T3^~Q#rj9hQ*l;|gbA8<3z%ZR-X341eXB|F zjHuxzv;5>vFTl`dvCe@*(6N1R$E}|jYa3renYBxFR}&dw0SgG85rw~7$>Kk{%#x{Y z7&^_1iJ0yd`Q9@G(qYBY*hWZ19s~*KK7rhV-=TcAqr{+x!s6{Q*S`H>SkX-~Fgl77 z)re*`yxo~H%gZVED2Z-tq#-DO14uzUwMMyZSTE+oreJZh{0WD{X6|0syDhosnUA8b zYUIDw65OF5ixB90Ws#=g69UP6xF`Yl-cAhj%QH{zgdwkAz5h z6f|et0aZaI`Ym#nfV);K49jzBHtXJcMCmN}8#)JYuN>oLH@vfc3Gvic^sbZHe9k^4D!R{MEnh!DD($KmtCbw0Tkm}V+ zcIoGtwV)5PTU#QhbP_DG>I+8m{-a6^;FLJ|TG1yUC4SIkg_y4yrjnkd9bE#%a~g15 zU-hS9R`A)H>1e!vG7Al$ynegG_4~gnE&blV+W-tL2Z7FPx4}|&mpvjFyIuz$d6b*j zCDCbS;t~(OER|fek(SI+_snioQsSsxtfJ$1l^d(itt@$=txMU_#u>i}+e1yMJw$w+ zwc(SmAi+`Ombqz0({%ZPPmsC(thy6CQo_t*qxQg#J4>0BUwJ|ie^CTdp-o1xk(rrg=x8(5r>2Z%}{_4i>9x}cv z3B}XBitl9tOkOwGY?_YzdvnQXQe%}*Z~+&8s`Gb59`(fQ#+Hq&IX&BWB>z&n+HIhx zzWha_ulE$p)4EypekLMlZl2e~!9>{2X2|Bf{4R*JLjz(bMT0;?0i zo@Ua$e{a{tfOqJwalLuyPtloNu#hme{bJi_Kt$gQ@%1v;g!{_iQ)P-kwZX0p5^txR zMLl^B8^f*FAZ=7Vz8v7AL@?FWvRqH#j9(M3o}4ppBfK^6&#>QPdvnYw``<#2nD>X$ z8o}|Cb0v66_A-CJq!5{Nayh7*+O<;!_U9UJ$Ym^&^S7#n8s0097=dI;CQu!nGN0)V zK^6#Nf5d5UYFVPrp+0E2Yx_&$Wm-S+2&@ z1G9;&&-trXU(!-i8WNeNy%_H3(LAQH{{bZ?MQBa#%!JU8Jlkyx!|I3)eAo}x4T#Dm za`+^H2}&FNR1T&he`o`*I;wSIO0Klz_0{tqMhX^dnu@f?|0Efub<*ZfAa|ao|GRhx zHEP2daS|`4n|o`){PAH#I(hK4^HoeZv%T6}mzvp>KGV4oUt=`sw`{lO5sTLrk8`=p zx5fk?=Qd5d`peYgcR;q;&LXK3h#Gi7p;9XaFXW!G{qaU!U{xSNY9$YN)~9NV9lx$| zNtfETlD`(>d`GN^!f7sSeYJk+4y2XEfnbsy^+=?y8Z6~PN4+6-RD@1N(T1*c6Pxw2o()i3vK*{JI1vz|?SJ>EvwrEcnx z4*&Vp$I~e7UVm74R($pev-?TMufyDLc5G=JC7q!yf|W3=^(*zusrSp7nGwB?=->!d z_ojEdmN$EkTVRkbD2uPm5r&}QHGFmmq3SdE%$> zSu~(OZR>#2C|Hlmh8Q|w5NN^}JGCxYEw{#9`7D%5TLlp!0uPnLb0f8Fg`Ti^bliNS z=^d?ZNS~?kkMh136;7ILMw2K!KEfR+?c&L75{Kk}myshR7dx8-_(ry*vlEL2@WNlq zzJ7Z|lQeuez!^P0IaoUTy{1jndE-~^2j8`~BR!GT%2J3w4RwECKIfAR9OvHc_}HK7 z*v_b*bDE7nIIfNqK0hdWFw$d%f3ucMf|zJlr|Y*U?OAVduWxC5d9s_YGLk;w-Y`JP zac4O5_i-lXfu8arcg2fyg^Ha&zd@g7F?Thu9aQ0l%PLGrhYdiHR+gbrI$#u zCnE9*5E7#^lo%Xgt-%R>dBIo+?Knk^x?O6gLZDi%~&|Tj-mf_LTP(egFKwX6t2N}b0U#&n5Z zWWJZR8JU&saMJf)=j{H${I-iME_ceN9q@;tOcW*2=FQUq2dV!{aRBCnU+w6$b@>AQ zFT%}@HlsuANI#)ty6*J1BJs~(M0#nWG2%5~Kd zEe&7qNgrAqX$qdbc=&56AN~8Z=rufKbe~3!wrEb3dbIm?X*yPNxpAG^wE95X6W92= zM~koe&S6Zp`RAQ|`+d0Y&SkUATLxCG+)B{ddQFn(#`#Qu>+VX`#B*(mb0ZPMib5g1 z1<_?FTk1+=J)!d0>T2wpeXFQk_j;qhHwhV@*KfCBh~$h&a#-M50s^%Bv`PE27DwHo zqk^aKG2|7<6$a0=%wIvpfnyFS#Jqpz6?kt2)lzdZvdleDISsh@`E0?x@z5aXwqY)oOTrKY{@v{EE%6lKg)7; zfXtkmfZ5H#CW>h$qi#mKnCgmUtw-MOHUTNy3{3TymH%zYiXf-hp(^7DBpj|@{Ps4@ z%=_{!r7@u3jaPJvgfF|^y=%j~6pXt_4^PiMDf@0MfNe1*<0$M$qp z*7bS%>W0(p6sb|WW%~A!38&Z4RLiqP68Vwo%!t6&9pm0JJB^ImitI8Y3zt6^2cs4F zwVyBc^P5?)peR58c|pA%pkXHIzw}_KRlOub4l&Ws`{DbqJ?u_7rjA!wKh~Hg$@r3+ zbJ+0*dJDOknUVOs#5w03rQIIMrE!-MVFHTyKxTPw*ZUD2Oe)1U?x518-7ObV36QWe zPKFmSTmJutziQXd0mW;y(h%#vOT zF>Ib4O!O0w$0KTH->_oz?yRg3+6VKtxKd~g!}#eL;pqaX9@*v0d212|lczKzob)jl z1XRH|@h7doH$nMTnv>^#3`$FeHl)C6FZN8sB4XtLYMG+}!ZLRyf`!W&6iNBI<&KoKQ3 zHAU#QdbZ51Bl~rF;+TO$$c&f|bc>s1U%r9a!8jDu3duz%3j0pL&1uT)TXD-|gJDQRFCRysv*pF|^#=~s zpO@w~EP5(C8G1u+>8H=@Ih%gHp1}DW>$l&#D=MsS+UlUqByTcN_pi{=HJzSHkMWlV z45&M3GCl^<$m4j^xn|9=I<@z@4QY}nXs&YO-F|<5H`~fB)q$~Ri3oiL;u-lbq z{D;3QgWkJ1l3q35&MDz0B$+j_G69v!NN%r9r`H_L>iIbGuvE=kCm>`&0R&k)u=}li zu#I;QJL-IRWERno{9Vq8{v1O_!D)Y!+<+G(W&&Bt$s8YD8Ilj1FLy|sbL)^8OGI!; zFPggNFC>D0`=A}{SMU5`?0zF}D(I*?m@d%|yHrxy0Js1i>zlYC4!VV&I%!tk`9Il0V!+Z$)C zuxE`ZD;6#=39k4%;=Y^W9S}Put~}4&?{i|Xz=1&)A3jlNMz!v#(|5l)7p17(i(g6j z6_j9#pS=veaNjT~ilZ>p!#wgPe|cIpmwQALQGmc-xNWKS}jZG7~r$-!sS^Wk=Cqc4SE28H#% zY#ko)eg21u5+NT7TRh``L9WS(X`>KFW#yo`l&N-!z9#`!|J{Fah4_a23fkN(F z+uBO*_I1r8Vb{zRR-SjhAS_Mm@prF+ysXM0l+O+FP@J-Zu`q^3DJ_6-u_)Y~#jYrc z(P166cgj0V29!9*jF)lhKde@Xo$HR~qEtTy5e!ci^_qtllmcaYUg&<N?9w1hRyqA+xd!Y zb{>q18^R_K#voc(cGWxZQubne))C{M8AsyTXx1m73?18g)rO5luA!SB!f)6JjBU26UC~b$>$7k_iLT8bu$lc% z{P84_+kJm+-3IG)VXx;p))tNM@f*5z(&(4dBJ0v@oUqAOzGmUrdr4e}WR)`Za z5kfo+^M3)D_fOG3^Avc~FMVreE{04Pn-Jb2^W~fnYVsm-_ku)Owpx{eF0Okqx1EXjw!IpIny#HM6+1zYCQ8q;-}v$X)apcK z-5D4a>KMR6p?$OzhE?mp1V-KDfHz4qTB%u$WNf{CPYSnV%qCG`2D>MyF`5;0A6`0-?iEi>rk@0*ryX;NX>v;$|Gq!gDUd9d$enZM1aF%2{) zYjj1iew^PgM@OxTQ zk;TV}3x<40f1t!pM7!$xT({dG z>S4Bjo2hm zHTr|pG0Tl;4ubY1;T`3A{e|0&u#*(ei2Nm=)lR2WmpM_S?2D8zwE(^8Ed|_Wrs^MG z5)Z1JN)AU5;=%Z$$CiB`bIx4~9X`#I-3jc;_L)OdC)+6?z)l#3?_EeM{H^{=i{bY$ zV5{Se(l$Q7$$Ekv8WGg}G5xpc@58E`h(HoeBnVTPa#B zbR{aKaWqP14)aY`ldUarS{_5Pa6N0tNuY-HT;+yHp9ZG{&q( z6&yNH8n|l(GkNJ{9)h2U9wPb-jXR>G1?#(=e5I=FpmnC)T0C5FF*Jae*8Oz0c+7^F ztK6A<{1kB4r_dMdKXog`4?W|P_-}J;xsptE?*;+>`FWXGG1<=rpN$HkzWm6Y!zRao zwzHc8HicM`v7Z-<*DL*Z7CJXP6uQx=NgXRS=bB!bP18C)Wm{bafN^#rM^LycxV-%h z&AY7sO<~w-N*3$qta78#%z;?hk9H%2lu$)uMT6&xmk-(P8?dKSu3w#DMkaTP3^?f= zG(|fbL#`W0lH-j?W@5?sk;(JNW)k0^lIT=Bvoektzmk60A;Y~uhc99Swyvbfn&JbT z+=I8?eX!G95E}3w3d?;O#NT&^V3-?6CQ+8n>~N|$nIq#|KFVDy9R%JEg8-PcW7LN5vzrt?q-n5@D&P9 zOJ2$i>Ix=ulc~6?e{pR6lc+w=yu#8+2K{lv5fW>Qzoc^@DH5lt-BQ0@;cZu zb;*N<+aliwRxi@9H%L$RQ|8T;d@)+RjEHduSXvho(kABYtA(!0NLDy5^6h3-rT?sM$U z_nVE@UCd!z#>#uW*BuX*p;gqCd<;wB*dy|v6cO;(58KG#!DR>kUQegre+=i)j2GIe z7L(3=y5PQT$jEydhb}Y8>ViKbxOHVi*O30|V%{IM5c+M3t;I3ukJS0@O-+u{5`N=|=Hh>Lh3+^uE>(dV_$lm`Ja)p%eokwCLAyoQ+*-`~xn zvnC%>mm_d)S2M!gKg)Ty8?pCp7lj4-B+ta7hZ+*82>d*UUbn%kkh69uq{;PU@9#zc z!GcZufMo)l2kcY6vcSC}=l?K*k6AIFotAv># zfQj$MmbyR)x`BI2kg(DFPSS<%$L2!P#EVjUUzHIO?vI}LP51aHU^p18j9?OHpCdI- zKFlcYyaOGSIR?SZ%8f{HIi4WT<(qxClDETRPv8jRa9>ABX{L!~)$kgL zVsgNmFdj9zQi@yv%x&5N$W7151$0Su4$pNzdcQT$_Pvi?J#yR2y%sA0Du<&c0r zz!`1e+$XP$1svu`CnQU4vv8Bk6mJKxiQ9(CXP$y}+Cgv9jBQb^&<(yx6in zZ8``ge)abk9OE8LO6`D!D z@bMh-3d4kYkLz@AJZ`g4zJ<>dnxUP46Gq&nDxJPlK$@O{`+ccv?Vz?M>LElNvqnUI za~^0Spj+*5qSK;58)9OjI8j)0?KV-b8MgTF4~`%_9DS7>^lG-ieWZ$73NK;WDx(Wxyf%hxP;ONX;kCv1TXf zzT-)XQPUqA6zjnhB4XU3+Rw%YFBWAr-?tWMxfBrvUFQ7lU(c zp(B)d??bp}xPLwab_{9^@egyvABY;98z}?~vcj6aN*dl+&oSPl0Ik zzH5Z7PY<7ddJlxNA@&Sg3}Sto4|2G~XfIysu)SZZnTMwO>~sq2HiuA)-#PgDoa=*< zlv?`P7-27mRFGTHorwwV99CDZ^BG*>-lNH#k1Erh7;+u@=KPB`9au<~h`awmk*(i%k>#B5$K_kHZB9MU z&vqFqumO=5EO%NY&y^?`6)2E9L#l2Sq!3KB)!tBd#!D**Bx>6*( z4o2qQ1gqtKy**+_L6C#M2A1>{H5Rk3yZ-G00mvkAT_FaP3gIXa;Q`PM_&z1dk(i7MDv?F@GKLoG}R-km7t z=O8us&vU#bH*JluoS#Vyay0*>UQc10Xm{n~ulFq~`Mo8_+8N*`G;kRBK@m(~*?9*c zJ;D}8eI>qN%h=Ml^@l;5Tof_R3g7K*Yfl3x_eEchdFBPKCQ9eK4~4UD6#r*@QDvD& z%D3^Rt+G_(o^w_hH{mi~8O)TZU4768!hrrXMI9oh>aO7PERbfDsq?V<3)1I>91ayS zglf6ZkJQ_)WEIu~7Dvu9$ zmr6TacDpUeJMl+YYLom>KC3}!rtqCIs1Q_}4*(!>uXl+Wf))aqp>ccorKCCQ5`;5Z zcO|P^tL9hzA@!1AxCJ{w>Oi>QwAOJ&+4NqkZ{Tx;#dYbqZ zVG7c3O8Bp32f6*tCca05>|KQAzGpY-5eg2_?`QBE7Y4?h82HPeIeF`(72KfHUp1n6 zyH~NO*vgDGhJpKk{`zA)!YNs7`#`wNS53X6*%GX%bG8~0#TAnJ*;sqB=^#J-%K`@D@vATj^G>NC3O$D*Jwc_lz+l~T&I(F9>NwgmX%o&k0qMMS9_^pw( zkepC=75J!s49?2EmJq?BJv2dskj>uKnJAFo>|UOa;EH)c!Hs*?mq#g^RWKR}K^(ho zA74`?4|V$&P=!ts(FS+H`oA4&#IbpKw;Cfm24it%IVbscN+!yfx${2Sl}gfk`h|kr zvWZbG*)3_a6Kuez85YjE!j*GRt0kq4I|E`<9xmTae$DDTUJOr+IXS#sSv&k;>=Gm{ z8gn#`fBjojq>i2HLX51i9KXKyO=1lQ)Mn2g9%YP`<>wWW?)AYxX}tL)`Fue=lS>reFBJd=)QcoM zWegYo6F+3`-VeQ^ACH-l3DCkQ7i)v8!ZJGxGfcuf&yB=F&<@28v)T{dVLu&oS!-7v1$hcx93FtQj+&_z7)i*HMBUqzQHk zF%c0wqUgyzt9;+jH6N^L6+o@#cr%pWiZboWiLSjMP_-?3Hdnn!&=4<<3kI7l2Ws{0 zj*_?AoU%`Ombd7eW9$1D98Ntm0}{3Y32Ym{Fq=d%@)27HWxT=jOdF2u*}O~vgUfn&1W4w9Z- z!IqU}bLe_5#}UiO=)b!XkHi`2jnuz+T+F5kMSWR!B*^Fe=KA--gJw~d({FwK&CF?3 z^cj${$=8zFnQm&0T(mwc+zlUnG`-jDzEo@0D3RT8o_IP*XZlq_u`>smpn+Dc_Hy7UhrK()dLa6cB*w}vO6aMC(><9rxg9uKB2$mtQ=PFKGt+S4TAYi$bgXr9VP}uG`h~KAfl4sBDgG=TRk8qA_p3_7(E~UE| zQQz#dY2w?tdZb&mLi%0?gcvc6U3cpKihK=IIU5)*gdyTXX#Wzyss>JYeq=gdKMllj zx6nL}4|fLo7CLxx%PY7xgc_GpMopF3_LOcl&nf=o`S)GjiWxyNnJ&^s9TX`;M2~Z*k-wt-j;V-Qq{`l`now-^6)(L%& zvyJs`UOD%mq;pJCJ^M?F*;$!5JDi?AmZrup?h2hWs14aB*i*gekhwfHY(%+N*z5x! z4B|61bnEnmJ>p02>$=V&g-0E1YLfyv$Jswlo8U3iwM@Idv@4y<;r(2J;l+|l#2Y)( z%aVFB+5C4gGK&g1^oPof<;WJ?!`s>F-UQiT=cDDu8Rj_3oOJ&~z=k24>K~*Z^2yY4 zR!`vj{@Ww)r7&WNjp;qX5mML=`x!ZYu|j2tZzk<9j_$)W+H#qlAUD4#Q`Mr-GnJ#u z*7YILQMV+r(dH$icEY;O2^?l~oY88*sQTbv@%HLkN*5A&0M$cBsUB zf_RTl@ra|m=TFm&%`z?5<`b)4JL9jC%I-kJ`LgvI*tVdgr8i=?I|;3QgQfq*{%!)s z^c<8LijuWEzoE6efZUlpwk-Jy6#n+pPzP#6Lwq`3B#s(Fra;?q#U3g^NS9h8S<8rP zN)e}5rTcb0sW2Tan;3*{TuhZAtK-ksqF>fPnRTr@@TqhQ<1sOr%?soOaWU&i<1VBN zR0ip8#5m#t;+7VMpEasM75QlbyToqjL2htL^Lsp*k#D9c?Vxa0O>_3=MdSAYH1q*0 z{!ky&C2Fay+uT83vgbgP8sm;_Fnl6nLp_FI=54k;3f`9z;jl{mu%!e?h+g7ZrBMz5 zOF*cHX?uy+Nw*+zKKgs9C|nYhTcgBe&*$%MK^gtBUFPLv&U;k6GL}dq6=^9-tKp{x zD{7t*RpK>eHB5!Dj1%-Qki`M@_8Ro0=8dzCe!D1Hh=91(HAXrJf^5`VF ztT{EYVS!C0UxXi~3tXD$rju@3YED*A>)jwSZ(kglJk$Voh)}Y3hU$tM`a1M`-en zzw*jf!vJ!ceLLmAwwvt3LlK}++g7L3MKEqWzWx5I~(+jbvpWNV#-+f{tH zl%7U7pEv%^&zL;qWE6V+x$50hukMSqqAES%ecIt<8b;UK6dHl^S-%3L?wm+JEm_{& z1}CZmZSC;QCq0+%>N)RrGW!>H{r~_|gz-v4jF;xJS@sTc{63+j2-OgAmbi-D9OpoC zJt>lqT1NXgDL zP9rc01rD31NcAr2kgrI_Tp1+08j}ZG<4*d~`xYgn`fATNh!3*STZ*m^;fB>BR0@cV zDbqyGFy(L#(h4bvHE#U@;d$>Qo(OI9@-b~mKmXHp`m#JPyI(tL``EVLMuL}MxWhqn zu%q9`p*V4ZvR|!+2}S`^(Hhxps;&4OHHzL;VvgBt?=UI za4gbd{JK5zMV2<({JtvhiJ~6MHRAI*3Px%Z6C83Q8qK}*wrP>Qzk&1ja~7QFA(`(I z-*49BItT5Gl${2;-e?QPhew%GO4A~?H@;iYA128h#BW%ob2LsZFup{u7z=WMi4N;j zEIFdPoq6PO0qGoYu(_M-|9yFhUT*qvx*e?%*XxKuZ1DDkt=!q@J7S^PI-$N~xNE|X zlozNxIZNX^WoQ$2WMW0Xa0gNlqK9~d2qT<}3!HWPNI6>uyodt;m>5ux(6X0!L5Ebi z%6uNjZJ)$vSc%Uj<80qb^xjr3(TC*gI1_ufXyM<`7=JaHE$$pX6@$VUZV_kZ1mLdh zknhp)#t%-3Hqy^7$1;*+(wZ(zOGGJyO3eZC?Gk%^yL3&yzG4ysF%Uw87&$uk++Gw2M_A|5QzJl<6c!G}uu6 z`a)Gct^b-^Q?}aD&ao<%?MU1H4pP7PX10r#3BbK|Y@!nM=L0w6n*z?q?r`qh0F#!i zWx_?;B9YD(HAWca`QUQW;+=6^9|X%GA#M90OI{y=)|a_h{?+oanm()o2GsZY`V&-cAR?UPuU-WroFzb9DXHx?^!W*{KC zG~IdGf2z&8v&4?*9{8ChZ{OMXSS5(PY(roCpEi`f*=mm=ZA(mcj*r0uA|w_XA;5XX zid!pzOH7i1`YMDnhp3Lg>KiIYH-c@I^NE*yTlJ-$Wwk)bmK?Ssv1phgF zmpoG^x`7nzkS?6r%uxwp+dI6zNdJ%GXxUGVo4E7UPm$GC{iWoMnpruUGwttF{>zFF z++v?Oe!{LVtdflKL}t289KkUcka2p`KCpT~le<*YDvn!NlS%IBpKIs5`zA{<`hk?ve8iJYxKG8Oo&OBujVQ+7HYb2nuw6b^<1V=knDrKdt zaS%@+^a_6*y?iYyUE-YCih@x{Q+wkUXi_v;=spO2zgkr)me<{4(aUI-&v(q(=W|xJ z*}HSEQF4WhhC``-@BJs9g)s15-@FcKnyzQYJR#eMr(I&rwAv@4xd0_B;GpPP_e5UZ zNX}F>trHY!Vjz;4R>FcAcD;uFuQs=!*#Wwekd4-@i(6QyBALujz|KSO3{OwuL4C38 zXOmugUfwUe%qBfcdKc2f^NhKG?1g=B8a1U8Jq2yNH{l3c^KC+2T&|Of5}c1|`q)Nz z1hT^A3o$1^`mAMA{};3>7}Du$U}dO0o{C;EeJVImLm$?AQE!K?q8n>H0>iU_pI3;N z2D}NT_mtx#u{g4j_yCwR{A&hp8FBeN$o`G_E(e>s0A@!Apisf6P~-2)!i zFxi1o=_K$>ZSEf5RP4!l+agz{|>Kh-&Q&_?PE&q*(Gs%xvKxZ*6Pyr z^p4<#{UOOAaB~nJraqJxlaPi5i59}t&j+7DlyUEsS}`+jas8W(r_X-@>((J71&aa~ zpcNn|$1ykM9exh;+%%U<7Cy6LG>-V}6un_?C;00mxfgw1+wM#9xpfxD!8ekroZW|09KZieD*v-G!)pku znezknQIAac9o}J`^RyYswB?HgH7WyegS&oF$G!&r9cqhFj0uSENIPibtO;wF?2|(9 z(D-`8DxYoJUkzaAncJ9)ky8$YLETb|zDfM0syu^rupu8L;OX9hW)f+H)^Abss1An{ zWP!A`RA5M!L)^Nm$%3f$HAQQPl-o9|gZQ@Qw_d5P!}CM=S1U7|SFK600|;|gr0U+C zpAj9dxNB$n9Dh8zg{kpB9s6wNu>Y#w3Edv2{0hRk7je|{Z#+?oUmll;H;8PS+D^P4 zJn^Up1HSs?G|#K&8mIBCGz%j2ZMmtZx3gJ5hD-+o2||_zB8cAOj=%ns89H7bn02a% zOIDYzD)OA3wQLWhQFPDZo0NnU!}=kB3F?w041B5O)4BXk(`o~nsmd*aj5{TOyiU^{ z?z~_HVa&zoP#Sp-XTg3>S*s1*AyQno=UeVqL)V;pf;rsUX_8nM!=2qzHXO1+rLLMbNE^66! zS3GO*-T$#^zGJ!<^SdjY)Po99duZ#xlaZ7=@_$8S0(ghJ)Xva)tx(}aUpUj|w*1Un zEqMmcc&Qm5RK7|bj_n>xhZ2!`BB3X`>OS$+v>Hhi792zK+*I@aO@VWLHM7hsj*y!y z%ORD)g_8TTPas5SXX?5v$jh#HP4h}2Vk7AN=RkYeu`*ryobMUm*M=!i8I8*4e??Ei zigJUpp>u%!F@hzeN=c$gG(s&ze;HzjIC8pkZ%m7yBUNCVoM-%oeTlq^u3mT77@r1o z`Pfs)mPV}HLT;DZG_%ppowb&TNV;InU8oDHv)?j)FXcD1%oL{|<^xu`*BQJ59I7r= z24BB&At+i!pXkqTR8M~SSzg57cE)y0oP}jBCyG_r(ZnoO)Zh+D(ERs?AzJ8%OS&?o zM-C{?&bi{G_u#7n-I?6Kdyl2$*RNAo%*(i(7nJmdQv`{DzB%iZ8uM650g(6^{g$AY z>Tmey1(cFg&}%H`#ik8iY?TPzU*%r%p1zysj$62M$JRlfm|yD;mfe@;x=&KQKV=#A z{4GVDwna<);?=)>;kTKcOozAqykXg!`NCH4SB1VZtHJ(hF;@*Pbo($}i-BE?1F?rX zKL75nyJ+z_l`DhYu4JTtX!48q9QE1U?nSEKX>Jzw?RCkiS2AE*c=v+h$5! zi{a1UvC)|R~L0_7H%Q9YtSUP6PyH>5G1%0 zEVw&`MF?)eU4pw?74Gg1A-H>CMIYYVU-#|qG5Qxj8Kd^uveugOnT+RinP0-W0RbfF zDPlxzd+Pih_6z$>Y1Re`&oKeZ=luI~^kfdW9qJ2^Uzs1+FR z1WwGfs)QJ&bpuf?s1v;~)mk62Fj(XP-eZ_b5sM#qGeV%5->G$)23<~LJ)BG>waF#Z zWe0bQQT{d~^Cqa|<7eS|v{lY=X(<;rVouL|o($k_-ZK%^1fU6loH!a%fYt&8S-$TX z50$YI3-yX?a#AsD_ib8wB(RYBb>YwSkLKYHk{=U$I-9ub-JZ&O(3ZPUGeHyAnA=?y zbz^ALu6t2JChA>l4R8&L1}Eb#`u^*^zu$0xhpU%`dS|hUe2UpPNi_1czh1kq_)i|G zLJYfZKL4uz1Pva(bF&#)M|d0_BvOo^$;()&YJ28(xlB)tjGQsoIS(7}#Y%5){5Tfy znJqN8fHZa=N3XQ9+})K_@Onfvk5KuThRqhlre{JN0?&X1+xm-B@e~q6L+j#0O+HnD zr_(N(3s|nYLfQo&KuHRmGc@C}tz>yw z#$U+&^vd->C=F1kpB|i@pOljI7DjLsa{kv3WxJ6O;srgX)WbhY{Q}{RAjg!&n4IH0 zWFB=*_G$zNVl2g}i0QEIlY-^{vEb<-dfs+MfRhBBu^$-adl=rN!3aSS55aO@)~6IX z+IXGf@d)^#O#vV86lvf1y@{p3cfy`e@J3KP3pQdVlT&Va^iyn-`utmZn#1jVO&o&~ z$Y61Uk1Vm@85C?ypqs^zN|&O8kE{wL-nBG`A3wXs7)D>IQG`a144^bP&fU%!o~&h- zRmH8h{L0CFliHs5!k@do(f-qAGx!ByZ>VUPKde>UaBzRnrB)~_JWXt;U)TYtI0gdM zdfO2Kt8#Bv)=wNVDnxL8uJ^zq1Ae={9g2TInmYv$QZGJOrrgE%KDY5QEL#rSBCMUd zj3z(cT`y3Grz`|RoX0eITXWA}#utow+b=xVIE@e@`0pd_X+Xm2{J(kfEJ6$a$CFnm ztXXl_O{rh;yQp0jyXG=ujhq1y!}9!W0EMrkqJ zb-2KWKb0^A>IRmq7gqA|xl(@=H1d2^V>1IdnJ|<{LG=J#3Q?_zA44-~{dR*68e#RZ zR!2Q~mjtN*!LL;F8)EsyS8`hW4+diX|BJSV}IXl}U%tpQ`Ocrio?#T)?#@Jy-Bl;jm4argEE1O$Nr zDcr?c6&a+4ih7~bOevw~nO@su!Q0$fwPYhW!sD8&>)|8NwvWmdgX<&8 zlZWv0hdQ4P1pcve*l&1JkDXen68Ehc5OMF(z1VDkG)WcC>ANWZ<-QDgc(&P}wgZSB z$fl-E0d@a(w6~}a*rO6mryhVyPT-`%(8$#Cm`j;Fi;Q}<&F}$3%7PZ#OP_>6n}yPeth+nL%l!c$q*R!jbSk4Xd~z64!gF+_3Dko!mgOs zcHz>G6iI%yri+E0R6W_{^tuD9j{U&*m(R;y&E=r+HBAO-IUp^dr_tNfFl#80BSsOF zqkxzR_!$NJQ`sMgj`T*Eb#Tbt>7+LtNF;DzL&Q(7eJ&?tM?T<){u`t#A|*yv&!-$@ zswUYbXA!AaU8}=gi^>+iuZtUum84-M+6#YU%`a1;H&9VYT zq?EsfC3kCUGhw{`zKl13u5KMf|5Ul=f8S(@KHK16q!s1*;?d|Fum2-MY>6lwwz)_6 z+4bcZZ&uk#qv^+HI7fj(x_CFc!xRT3x#dZbKLpmO*|+vE+y1lm)D@y&6mp z_k%V|5p{pkvkxZ6hhnb2&P6rGS>qp z(^*}~Q;%(Jpm}Eb{X`p|`Q(S~YU&kA4Y5fDamtz6CTr6x{{yOVTKg;ds8pT<>#42q z`t9*v<>6^&i^O>hN}T{|07bL&e2O#b@)sF_Qk6227;YtVp-Q2GD1=B|Ki%;H6fPN5 zlYH?u3p%=Y0qg+x7w;R{9L(W}l+&xjg(=3X&Y#_kvA=)P?BjizPQ@^ce^oMGY4QQB zAdWOT+G_qerCcs?)<^6lt{Y9t_0}-lCc-Lza^(1_*x=v&wOp{co?|aJx*U3bK!;|8OwA2AQtcS_y!;t8!hdHdjHa4 zeCheikQvteu`iNpg~v`Y^`Z=3w3O;?*U)fP%PaWJ?{R^{V%5$lxkB@4-+ksZ+;l>x z%-4%{?(`<}>EVyd>$Rf)2S-EV6`*$)?p4`dtiF1)4gXPqDx|u8(h)(P`lsw;`C7Aw z@RSIb->>9z80%E+Le=&->V0Fk-HHE0K6cLA0Xn&E)c|7nXm zLs|?XKV21H<6?^x1*8(`Bc&w7B#QirE2_Eq0J*jg$s84o;BQ;T{5Niw6ht17Nb*EN zhT))*Hy7dGh}KGsCg{^%UUpaMf{6Cjh*vpMpJbIZBCR&1`Ai+vEpiujM zl;eN2P?-Hnby$kx72r;obYH|sLtZ}z`;Ip{nKAR=nM>Uw9!sNB?E;#!DZmXu(Iw1C^O&B0wsGHvi4+Wq?WU-gH=8W>|u)Qc=l1$FurvyMBz-!sv z(PZMCMGHHD={k#dhZT9I%jmn&F)4*yyZ$__%lv%tB9c)52Q!XhnpQK7yM(--muStM zU(HVfeKS12dwtk&Scr;y-()KN19C|aQ~j)hGw5|eI5J|$i6sq-?4xv1nh_UbV4tk(;9$X0L0gl4uk} zmf7BT+!072Qg7!;_2;wyfxTwgf19NVe}2pVCsv;Zo;&YO(n?MRPMW1y@~HcZ|HlJo zn|WAmLsSEn%d^w?ce3{%i zmb(?lFvzh5@Si=i5N(Fi zp^{jPgt6L-Lq8xP!GKpVX0BQyT1qp-DIm%U4GS}zEr#R_Y;9S3Ca&WO%>)!*S<*r| z0JN&W=jM2HPU@Yi%3#~YsIbAms!L&iX2f?2f8G@vd1kt+GbhLQy_1a^NJBe+c6ciQ z9)g3XbIsV!wGq+%nGN%pq;EZWy)F?bCgGOvu%sVe@DOt?P<8WQD>CnE4_drRla>RF zFVAc5UmDebhYR_By&-HQdPw6##`ZIe9!EQk)9PhwYvXbpIa*N z2#!G6QpVTb$hEXufl#hQ@y&SR?fl!Z)O%(n9=4D6ssCI7+SsRTk!b!0qJ9=!JW^B! zr0!4|j?<_CRPn$fM6XcSc)1bRwh_0$Pylh@Pg^L>jc6UHfr`txA6IDRrK(l0jkx)s z+ZiuSQ3$4NTLi|)sc1C5;~itKFW$Rwgfsn>&Dvh9^!gG% z?Zd3|{s!8_q)b*d!`6iig%4K#5$u~?rqrxwHl{N$M_mN!DlJh2N%cJh~whn_6PGLF_c`tYxM zl46_xqPdb;W9|HUkV88%->6MQB_LIIp|YAWzpvkCLcxQTQCQvN14lw9W82=H-+{r%YaZlb8{?hHl8^_>!! z@{|uHM6=&}0qr%>H2&kP65j=ulz3W36b*t$%;9yhmftssj>_*^6|NXpy&T9HBAiUx1;fn&vq_9*7=Lcpy{wiYE5U$RGg zQ)u;{BLF(gX~BXr7L%>W+0Pl9l{VYY(&1AnbcJ zYs5QH$a&7=L)0}EZ@7Y?Oj{wrk@SI7%YB6 zYtwP^bOD6gELX^Bh~lAAOuEF$$oRWXFP?A!Ot;N|n-vaZ6R8|e>+VA@$gLX(WD!sX zH5`oN8t`$ZVt93$*e{-iB2OsP&ZuhxjOmX>1D<&~2aCg+Moj(OUOS6YBtFbavHjTV zO2PpPt#1zy)|@ z_?4*ZzYYxmQ0@7@d0(HEHt8d|flzloq>6(BiDMbzinWH122%%v@E$0KnAuD5QJIyG zDX@UsIiC}N55>dxzj4=xkm@@1^dD4sT2QL!0sIZ`FMJ!ieVmV^zC9&|FshAGKg(EGO z0XEXm%Wh|72~qM%QX#0)H9}(;35UDhPcjb}d1J(KKS0t$3=}foa6lM^#k$-=0xTSm zx#w~XB`E5upO5tFnNhvf@St$#Gywv2QF z31_yF*K+M^dGx}swk$t92^1a!?(>_b;hk6)Z1Baqy<)&HNZq6>a3!(*-{y^I7wwcj zEPfU{ZH*zl3x+h}@5&Nl6TCGB#E6&=X7^&Dogg!iK%j3L+U_RvosZ;`62p8QoN z%FuMFIvpkIWYG>@a^xoGSYMV-3h$uS6`68RGm+`$j47t$2p9u04mJKx6R~Itj)+0a zrLGm?-?lRrCt7LyDw4rwSahK89*mfVY_YF`hXk)8gk<)6uL2kQ*+9zDnjv>cjmdKA zXuZLZa@D!hb`^ZlMWrRK@-e}9bc6biYC966>@f6r3laOrA9f>z6w;3q`=2d;lwA( z$G{-Szj3K8FrVUE*riH~duoHw`3qn8?N0h{|F`r-tSxbz#Gn}P`n%te!03NYkK`L< z?^0+~GRSf%VH{6iUa5-s^|t2)V`eRr+(mmoK&#t)>wH z(7yi%G}ym56?V3Dn{#XQy>JZY(aEKC!vs&>(vKO0eA)z!a!Hz&jpr*Whw{3 zQ#sp5ZeiOe=8Lo$o(z7s;ub6AW)RiS7xTK*=$;pyId&6@R{Y%K2og1O`3Lt;Se215ma zW*nGL+K&-ldp%Fz0f?VTlwDbyH*FDcy=@c2{Vi|1pXv20b^w?m@!UuIFz8a^N&@9f z0%(TYP9=7K$r<|f1!*1klZ-1fm|y_&G6IW!j|N2TT`yq<=?R1=Ci+`7n6FypnjYu{ z=#I=<2PaU&7G-SVL$hXe-y+sh_of`GPf-3KZ;?wC;U|!ri~5LJQ2ToZwn;jD*hKk) z+K%W0u90wyLxGBG|Ae*8fFHZzG@n}C22Ia)I?!kiv&tEkDMUOSRe9fvp=h5|a|9ka zxw!?iv&U3P82h7T6<`H2s{OtQ{bj1iuDTqKv_IHQ#;Ne+EPCld#*;7qk{O>E7P-3$ zkU!^TzVY!t`)}rY0AR6cj`Eiq00(wt%syv6{J3y^gL_~ZyU67pO1tfc(5~vJi$8{d z9nkwQ!UsUw1`18`PD;?8X~+8#=+A;T|O z_t$&?R>5U(3IqWePXz1;D@IGHPuFcd+U`HSeTZ1X+By(?rlb@Bl#~cJy9jUE=b#lA zEO3zH%L9U^#r1~|d8a(rmbPPG^)Kso_@0aTo0EQ%mXGem}o zgmda0e7+|C$2%$G6Ck&_&KVQBcBF7gUrDflwvTVYqSbEm@m+pPMECN9^ePbgKwMv1 zb`;{Mhs7Tl07?2fbM4sNx%$sw_1ubM5uz$_z8M9nC4e5-F0?F|HPjoERVuE4=A>TY z;kDMG1TJYOeMQ*JT&ow;u?Da0!gu)2_yP#60|8L6unvN;10Z|B#*-&a=>^~w)~tf* zm%+5Sq^HWF3{E<4PxlhsLE4Jd{0QwZ?brd7I+6txx-ajj1yds}sy$u>_3LFh0A>O^ zwX8*UF5FGWA+`oiAilU}{YiDI)yw61ibO1(tu7wG5$7@bXLN7+!y+?n(!n!_(^_En zjA$D84Oy)E`mE}K)nR_s)a8M=a23lQBK;Nf4dV;XaLTSgH0q>kOHem}6n5!5rSt)! zD3&jnsDN!!0nBv0^G?T90Tt2@z=jC+wZWQ3l7DUlJK&3(AIu9F8CfGCDQ-JswirgF z_$0q=$!GqPP{wc7^o#}vx~E~i=}_5rLcF$qtZ^2h)>aM)l}n%89AyM6hJLzNnuKyI z&Wbs#PhX-|W|;PxyJgnk8S-jr*wGAcbl<`h)heDFtn$dAyo`5KSeHMQsD<52ZE^)R zl1Nq&3^%2oR-K2GEhh7NW(Dq-UQeyqQPek7#-Xp%91cxdSW>KD?sfglkpj76np;ge8oEE$Lo2UJT2!d z42Exic@2qISczqO^t z#ouPL`$_mXG;W|Wn*^+KWX1jb8pGBHR#b>yMA0 ztth?))F+yy7esK)QuxP7UEnxb{p&w=gP0Rg^*jby_Pbe;Up|PGKK}!VSB_h7dTW0F zvoAV)eg((kiD>=Jh%0V=PCZ%qF6HTKL|fhDak6@xugUelCeqLB4$bhffO<7i+UJg{ zndCFseC)ZM{47dgzR> zHjd_wekPDvj4AqL#5On>728=iO3E7PZ)nmg@bj&hqE56b1te$1%{(S(8CLn7JMhdf zxyAi7FCS|(YIMv_JtR0&)(bp{9cN4DcLWIGuA*9Z7ytF1ga8oA$<4WLQ0LmT=+Gk- zn{QKQ?&FZlt0J!rmNDU2Na#N`ZJmH^YEkdThIc!_(EFnvJdm3^`)SA}%GqKxZI8G^ zM-Yg#aOEYue%8qPGWR}Ugk5w1F+3O9B+rQ>)z7z3^+lbb{PWWIJePyE9>WC)d&Qb% zU*$@xNBG6{pn5B%hHaTB-Un&KCG!Q!R%ml|OXmkEkyItW1FE5oqSy0XjQChQ>qgJn zFvv9$J6UC^@zU{Q=7|QH@r1)hOqB`f8?Wil<99QGUu5p|TPpg>V8YWFT;K9H>$`r$ z0bOEFMD>`!=tPDeNH4+G`BY3x*WWEkaf*@b0L*PlaDv2oUZ}nQ%{>#E&^ww;1h&wS zd;=xAWRbsEcQNt|exUB{N83S_PvQtmwFHeHpPZHVJCfdeBPI!ZUs?$akc#`aCJTDy zkog}tsyjS+OMgncb79??6kjcLXF3GXo^E>X$%LQy9Z8KqfuXb?|Dx|f4ypb3qXOfwlHB_x{L9JHJ~_`*wqeSzhs9$Trgn~fjJZPC&z28T`G|p z4Uxp2qn+Cx>Mcgdd7S^rT>w~e5=pU0G{PT@=}7xdFY#(6Cm>FA5&6`he!y1P7dStd zz|yj-J-YU_#At-XNTXrB`j;KYk>pJxiTs8fdP8vAwL5?FwO#6_aXXiwN|907T!;V-?Ap_kZPm z4VVSm?tQMJEhV>`^z z(e5)WHSY(HPig1c@SVEiP#GE~6}mHHS&v8v3GvSlVbW(t+iQ(-?h&DRi}TSmB`4xPB`cG#ezGY2L+Ga zq6T2U%*|t;*u)xtF5HEcfr9d-Rav!n7U6U4h`F;@^sF3S^`UiGKe3QQ|M$2cQ$WY& z6doMTublXJTaub*w|JTU=$GvGxqAGv=Be$iUbII>Sl*T*IrJqi2{Jg5P0u1JtxA+& zcTX9$@9Y6*0TEOw&i(s<1|YI-1L0flF{P3+(>7^GxoIj4ToUm@NbrF0RC-Hrjd#fX zJY?dn%xaLeqf`I=K?S%nmbjv&f7i8OpcVxKD@GjGlO^l-%^5al+Gb(JuF!>{5ckVi zSOm8w6>WUF2ozTK5l17AzDg-60sJO<3m|LtEMcF!r>V&D7Ne5F5Lv4W+GpH74EY zSi)shAHG?6yZbWm$;bA3E%yN@umLl3{2;a0KRlQ1WJ_YvKcGethsnCUJBY~I{FMf> zKMr^}=}CCnKC^1AiP*yxlw?W$Ngu(nxlK)Q=M7*hV)+L7#uHgrupg-Oyj7T53(cR^ z`?vdnX;32s*Vup9BQwBe>bK4OW7Ve1Wwy| zPAv=V%jXAVSZs9uzH0yhd9BnWB1;pKqw`909kHBd^P5~nXIRtnt_q4(^)F)(>~M(kR+XV;v`RE6qMDHMHpr|Gw}vW-z2u@i%ydy zjUp%hH=)gAAi!{@3_WQ|U%7AO|qkulgp0}xQ7Q>Q&;sNLsHEP8$s z9c$!RPY^|N(?u|=;LTUk{ErqOY;fA9uG5(2Uhn6Lz_dl08^ zf_AAU3k28;6srxue>-WM`(1<<^q<@F+y8QVM!UgSdO`UENa_Wh{}kB{f@UVPz3QGr^nn#Y(a28vD2 z>ll+F^%umS%kZ-C?Ny$AfSCg_=hL5Zsi&Mr3gB8#KbS3}uo$65*`?HcV@w6skESK*V-pRIN4pPlVg zpv>z%!E-?5&tQ~#!beG)20?rU|skwE%l-X@1{yG(xm2JsU2tqTIIcF&_CnU$h%|5@#}1A!!Pgf<}MJ^=j- z@+iV6$hsd5{c@2qG}Qg1++rjJ>F~rz=jLa8hsAi)2)~|AQbRt9>r!e8UuIn#%caBS z8$@qD>o}M}j^sl9Scn3hK%j?&Ft0=diNhf!qE+H9ma!hd|xaXk2?GWoS zmqOIP?0nqLk=(kLw(uh>z8xY$kU@0s1pGN(0BLBsy8NjKgw|%!Hu8NE6+-5}U)MR+ zH7&IbPq4(-({%Xs3HMn5fbB#h*1U0piHI z7ycuE5d&64Q6UsNHZU8@4rKV^tt$h+D)b%`{o$&;fIIg!E#|x|Lc@lG?RwloU5F>L zQ^+sYc=KPsq;G)a+w}}YTWiM$PqZsOBnR+x@HOhrOfXH)zl%>|t;sPwI~FKA`YetX zpDmDX=hr+>ooPaHLV{TLO=;h3P>JWrgDADGId-y9z9q0~uG&_E(rbvMQ+UB|l#5GF z^6xybE#TZ;iNrWfGr>Jm)S9OrY0V}KtWOp1GO+?V#zIchD-#XtTRXysZ06>fIq#G1 z87S+k(Mp8+=Eey1d3tt-DUdDv7NwF*U4ROH%ID`}%H7SN8p+F=UqA&O@%D4^u9737 z*{CeGQjCDh^|lXkYpaPs&tfBL#U^00{HlmOORAf|(j-IeYeMEbwJ^O&n(8S8PtZ1^lOIJou-sGX-7j&L^S|!%4 z1Dn{tU3$webkj1E(~*-g>NfkL=y`dkV+P1ETGihe7^)dXy>ax>=>sVIZPkJXp->5Ic@D$Y!feK|&Y8}yGMT`=VIyIEB|@-RlCV=GaKwjhQ^fH| zY7LRx9rV*iDPKkkJ08CaymS1B6z|243=8Q*uIR=83xwaHqoa@CN3il24q_L3S`7d( z9yIH@QDX0rP*4!#*;^%5`ZHs=9I4x5pn@=-PM*+qoNF@~{u*drD554IF3d(cKYl@W zz2ac!_z*IbQ-+6!ch=rSI)_QYZ##}6qYNNXsdsxQj5ZI1*YZT%50j2(>uj{fBRk`W zSDq3p+``#3qt-%*@j+?P@BN=zp=*s%06JmKXtf$a70QT$3~y#gbR|ZSLJ(Jnn!|>o zUX%aaZq=IOkve%(n5f<{i;r2qQc*BiOkFEZyRPv?-3yK%Qa!Ji{od$JVVbICR}!L0 z`R-xbmi+jTtu~^-;tS4}nFVUPaz9cm^m4^4ty(M9%ab*u4+HZl1Gx1$SUWmE-XLWC z;Uy3WTf(hEZ--qddw1zU2o)&Z zhvPupv=lCSelFU|v#u>_bR92#5t59Wz};HRjjp#aw^b6JB2sZ4I}GP0v>K-Sgwwtz5jGmKun@xk z|Jn*yF5-T7wWEt$HaJUw*}WrN-y_9^iDNAwPdfT6Kgy;Zh#Jn;t@|4J2Y8Tv|Bg-3 zT+>S31wqli2yn0xN?||dm-SN9aPl)mTt7+=FlwLk$>#g+32I@_HIPLI_Q)6DoVqGb zXp{=vZWv}xblU$441!jFlObd@oX00TlEf%FzAu?ta%C3k5Fs)A{NTWhW zwu~e)=v!E$U*S@NeP^Wyn(58xkz5=89za# zD<1+;@9Pe|6DeJ{_5yhq zS@Q<5Vt@JZLFkvq$=SfC9a(DnK*!#2t@yru#2JoB;iSsh1-e(wji`sowhHeBdlg`P zMuxt)`^ixoE!8;XW2{u0Soc7ZN)H*^!104VBaJe7QV$>+Wb6BKS(`orkr2S=r zY*AFI7f5jsLSex0=U_qiRSi_|CR|l}Vj_i)4e@8!EqkrP5Y#;^{x&0-q|fnjW{_14 zdv3K3A8%oy(~L$Z`z0%XWV5d6NL_>-QsYVF9j?I+mda9 z4w4YXhOZ0OIM`?e|J0!NvIozhA@FZ9T$Qr}QQ8%yDtH13n^V*dECZNnDJ4Q2?-sXNX~`@me{hjF>RP!1xzn zjz@32{9j^0bdnv7Wu5~i6*v-m)mu(igXS;D2qQ&XJdB4E)yE5tcp`)Mr?dHfvu8w+ z*X`$Y5R61Qh#^oUkMny%4@iZ#%~l#zH@Eu>@yjCL8jG0! z6-?Oujc~w!Bq_nZsMkFElKQ8_X7lIEKiOS|yOCL@jE)cUswm0K+1ifs*a4QKMv*CX z2i6vo)lO_wo0EL0s?ADXZS%7u;#oZeb)RZJ`YC1BbWgUm*r+Nvs6weR8()BdR=#{X z%06a5m|e-khA@z;v5GDjkyug1w|+xMlg#r}4%(N$>PnIM@JaU#u0%?K=gF0 zdV5aeBmt4p$~g+15@bN9Cj(QK)5(#-cn;5XvUsY-sR>2r*tB82yxRED_4&J%w_BIC zhFe?ib&6)-L=GnRwi>y#MWGBa-B4-mTAsZE_|qEmYn7DVD{B|%BSD@lTGpAgNq~qO z?LXdnG~~U})%G(M%Jm7UOZ%6Jm|+Q zn1u8#i_h)&K8V+RUjTB$#KtvEU1k9n;iP`wfH_ehWMGS-4T2L0Ikqn5(bI_e1kbRn z!L&2evjd<*i=zXzKm;g|k4}DuO1uK^D7JL;jdM1z;2KNfqMtm^9<-%xp+MP6x@{?= zcQh&TAIW=a`vPzFNMCS@uh^(a4=cxfsM{oB;R;0z{Uf399im0}k4^QpM40f#L9*3i zPThxHoFDf=f4|_0dKn;Ri!gd^j@Na$4jJno<&^{ZCRDQd!!f#OEi^p;d zw5qhKM7S`Dtm7)4&E4b@F0mE;oik@a+$xe5oQ!UIuk&o59ZOD+Yu@xXdM$<;CB;~f zG}*m%-?ta_$o#eu_mE|^L4Byz-+mJUYC}| zS~Jqga0dL2CG}1a9{2Sn@vLcY#YJ!%>`883vvAxu;mqs9ilF)Uc+^5>E!a5w9imL! zw?lc6ax1%PS?vBVPTUq(oI`V8Xb4a#SP;}(hf5^`L;+iN!qI*EowlVrit0hpW4xMU zjInFnz6=Fg9QKH6t-q(#BmQVnZBh>)w%X9CX zm6RmAp=v2>hmG%osj#4axS5fc4`pLH5IWs4&+jO*^LIpS0|P-|EG8@B;4}g?&dc`K zUX>^1O^=g^mWLTG>|lUsZ$Vpl&9k?T$1o06*QefxEL|U1i-XmH>hi!h?K&z%Fnu6s zM2}#CB%|W-VenZ2KdwucJqrZ`&bD&BB*w(=Y zAZ%gSoQn&t+|v$(IMIYdjZzJ3@qfRLmcxY6KRjOjMH%{MRwh8m+%i!D_j#w3)SH*d)E?RU4^do84*oJ%51@8d!_T#5q z3j>kz2mcS$Y-aD^yHtRs;MY2o5}j3>RPTl|lxu8grE|L3s4oC=IRDxF1;?X*;5MJi zTb3}@OusF6O72gDrz9x)-ytDsmmNF{k;e{~<%0!><;G++{^>{5un8Z;mD>H4)XRMm zWFCL8Y`MM};TNSNP#g02F(KGRd^L%l3@JOa>WlF#S2i=>Uu*^*Df&n6seMGJhpkRT zR);pePi;f429id`Mp7<$AKfw+NqGDUk+M0!8}Qo`2nMq{3#k_Y3g$x|8}0m<_8U@) z7arNU%-*NpV|@k_IWp@z*H>@Bi$S<4_{hxs(L3J5&@JU^FCHjC|8P=78Jc7}!mxju7hycqF{tObp3A~gU%&6q%L#ZL0JO$mF)(y*Bpk?J zvti}dIjk9$49>m0I|UMs`3)0p?^Lsc1~nEMRBp^R1c(DJYR~wZfHB@If+O##BGp^X z(p_s(?$z%=(H3$433x-E1|>vG1xjf^X*L|7!Npe5J+paUEJ_a+nx$>n4}PVlM81&o zAEbWaZ9!*aWg1L!B=*9-=dsN=W5l^&xlh!%N|{Zr>MJFG=EhD|>!=7I50oWZtg1IN ziB~sPkW-nb4y&nSaSoHPrH)${%TM)Ew7(M3Rexi11=hX!yKQ@KybU+$(yg^8wnnM) z?2*wZ{P&&h_l!h-=4)eu=T&7*kxm+@_4YqpUHQ#4qU;velbQvdR#s(_)!bTXxzQj# zbhx9xE`Sj~I@Ek=%A?(MLLr*kW4slqF+qP23G_Se9dkmC8h+p%pIG4dT^X&@l&_d5 zb8`%2Kb+jGQWSIhTNZ{-whk^O(s zzLWtelB%G~3ntI&Cb8=DNe*ZZ9@SY!)`V*M6cdfejFaSo(P(6jgj+tLmYBZtAh$f^cPK7tmwu1e-+H@ zQKue9#aq8`(&;Th3OzB_sh_qTmNZq2SN4gTe^OxO&wS>`y-&dI9(`nv7NEhJk+u7F zE>eiqm)=&2*(+nyx>NA2dvI&b>|tJo7oA$%ODN?>eN`)oJ1-X+v05^u#moXuZu4vR zH1THdsyK0OI225Qg8Xmto;!LmpEj@N^|~x(BMKO!36q%hCjfrd{vLr^dWQ4H;-|&P zUG!jz-zS81G{VA`+lnuj59ThTN#PIFHAd?B%@K6c*Togqgy<2h%RLsp{(jlQb+oJu zyIUMM7FqcJswPr`0v?W6^xnGM)DK>MHWbi8(tr$q#R+L!rhsVvthYQCNZ7Tf^U9hYDsb$kL+3k%@ay(HjzQh?;a;x5=Tn=1e1=GXh#4D^+t)n=$I!i8Zxrg zgH=-MGf7=14ey z4#D&psC5ATPsT=}01VU{$Z(WH{M8;#$88fA2+Nx?$rKFlBVUBklC12J2_GQDtwRcO`&n`q4+yWr8m)N|C!g}mZ4Wg73Hge zRqGCWtU!qczIb|bo*h@ZUL7Xm*+onjmn{uy>jZ(39~Y{TO6rePFg(+5Kq`#|Kz0 zCb9F&Me#yYhL@-JP{`BA`;(g{1sOY^XubnUlvfQ!PiyMp{{~fLMpEOyMJZjgbWqzN z6e1jvpx-u%TcpeAYAvfl!kr5}^4}Jo>`aXdxPA2x?hxmmBE z=Lp^|zQzT))A#9CelPdluEa6sS^<^=p&KsTq&vJ}g0~lUoMcC%ekkzf;_{n2tcRWv<1+zW$sVAQ*!$Ok6|qkfkk;8QH%_or z{CT(!%NSq$*x7`h7GUHNId{?rBZn_G?G{6gAdpsbq?`an;LODy_l_XtBc|$V7OY*W z^217*F8K}=UofY8gvZAjmfwH(_?1;l?2!yEM{aMnvJm_@?T6(IK9y-@Iv%dn5SUQu z=6>iK-Cgl8j_28M!Tzc#RlsqFjk-DR7j zCUL3GzSP%W*m#&k-Sz3CN<(KgBNmt0D))3Ll{LyMWkR{g=PmmNxr4ZdW$)3(SH(;H zLsDRZdCNpQ=*0(nny^nb0t1TX~9gC%y$17@;TrFBSfX76+cWjYzGZ2G7~Toq|Wv{cDxpvFf%q(h zA2VIi^sy&wEh(A9G>i4I$!6N#@r3+QPS2Z5ZSmxLtLeVtk(k`YMm{rbBl387@mjN$ zA(BS;S5r+vwo+4H?dNYmOcbtG&3Ud6JVKBDbp37BFFNDLy-21BMwFB4k0}a~j0vQ~KM_LfE!XaN*#fpJaskz7mg3!(`PoH+_ERJ|e<97Z?A?`Gf!y ziUE>Jrxpw6VjN%Y0krMnj=?kE4h399Bkr$n^r!ulX`8Q`6n&uxgT~h^*;shrB<9dSG#G*E^^^Rb} zD)4$UGBi6oo6FE=vDSL?ROI7pF|XC9=UVB847g364)olgKRBQ_1JWqcM4}g`ifUNf zFOfXX+*dE@2~u32nY))ofJ`UcEX4JKBdymy&R%1dt`KTh;-=JFMI?H+mBZd!{CE&> zScU$f7l%&vTsU1HT5qBGQZ!xslO#h)GCEw44Yu%D>bg4d{fMAU2oL{E=Q z$U!O^XJoMZP8Yi>N4Tvoj~N0v?^km3CY`B2fAh=7vgI#6eI`_Cd&LeM5#OKNEUCQK zIg+nlQNMas^T7+rq^|PwA-RnA8vM@2JfSQ_Pg1Vaj5v<|A755H=X`)ZJk?A|#*rMw zkLDBY(JMaonxN!4qEq2N)Fgz+kK!n|_BL4GTRf7zlsIj;wMQs#E;(2_C64L+?p}Pg zWx|dD-ybzEZYn>9{abCje2aDc3MHV1#WTrBa#fbFk^XcgfBVs(@56fXI~SQNk+4c> zf7ic|-r;|3`*>uEi?y}XjiuFz9L3-@&9w`|?dpMAb7IbHmKu)*n4g6O!B70V>Ivqg zF=pZyTPdv;=*G!sU%5jGHg^Uj><~4PjxoHI3(5wDp2qoczgo{z9;20X7DfD&~^jw^fRP&j9A&@PMK9nd+?0Q!4h_ti0=D@1Z;JT;Q$6OCM7O=(g@?QWaL$BW`B3Qk5 zEZ|U$kn{Q8__WY4Nju>&p0olM}%Fye1_YML8WDlCL&CxBK2ggP1TZ zVN8@vWq9Z&9QvSd9B zl3@j2e#0WUtUC-tblVO;-yS&ty;z-=-o^(85Wo^R8U;@MQOVUPQoG~(W(PQ0cW28| z^$5=SD&K#@oNx1KpkAxBR{uX3d-Hgz*YABeV-lH_nPi>`ktsuz3MpicP^L}haT^-U zRK{e8BFR*UOdFw)G4q@{^-@wDfat*-}kz&b**b%OW3%S zzrHeX=hw-2;ajv|BGDUAbMFwdb2s=q*q_^&C9qkb_sdA@2+?#3iFbN0AoxrGD?4O5 z^PWZz^OO*5ybg>%>Arf#Kbeax`@G5QsP_j93+?!K?|cnoL40;~&~YKHWVH*G8w-c+ zS>JNlbI!3&3324m6!t7|7PM-`=uVu8v)L0%-C8y?))ZeXd(}$*E!V2Hz*54A=Jb>( zh9$pIBc15&KU#nVntLoXLlqZ!H~F*KN3&m6`X5C2vhH|M&W=fCmzNsz)kOR%H0FyA ziOP*HX!Kl~Z#%a#?lBhA;PbHJzzM@!N9#P(k!GT%>nlY^_~FzGG0t4KYT|;*`@inf zTe-=ycQguHEk7IJ3YOW{j6-dHBQyW_;E)v!CjUnMc?EBleK=O}o2F_h7yfMW&$^a4 z>=YRl)qws7vV~xxqZ@`^%=IX6oZn=5?+BJ(s=3$FXkSDGHiE`#U>`T12ER{tYjOuH zR`-!ou}6KJ2sD{2`bfO_%m>-vx`gQcpQjVWH3-B6pvVWqGd}rd?`Kr?r_d_reX9%q zVgGbz@ihlU3hxmABs9$UgAGk8Das%?_2wp7a07mmfyzb4qte785xP|{1@|5PSJg%sf{m1)=mOJEr%56z| zKjpewgYD|ujg94!Q?=Q~>Y9e{N?BUgeC%vnsJys9KdQbGXQ$%T-}XCE|$2nI|C^6@bPrMF%;Ieb@UZXD`t7DYdh8~vi{fRWg= zBrOt%TIdj#hlI!aunCvGvS>nqr_~*LF^;!oFscyY{Ab z!JYyZ6Z#30ygIhIu_ifG^Wrg6{)3v0!kRpap=18X45sCeD`|3ADxn-{6rx+6tv+G@ zno_nR@=|CzBLAEj5Sbo{qGdlr{cJ3Rx&|*tJwY+56kS*(Tc9&3Q4n&g9EOr-euPg^ zT^dTE=A(AXCD^$NdWZx6r*q6K$_1(`7QRQSdU3-VLdO_`tsT0vNY0^Eqfw(h2f;Gb zj-c-+`S7%+kNCh>`_kd_mI18S>W?O4@!`zD0-$0>!nG8#RDKA?J)J`R5Oi?zWOS@@ z4K+yXH@2*AAp4RqVr)0hLmozmJ#}zhP5)d}t!wzi@;z$S6oSjzkJ|;;d2-j@Raw}O z=3YN?w!l~6O|79WL4*4OZ!`x<#q>{(c3~q`rE!I{ecAKpK9LXwcx&frGWN}Kkhm2& zute-F@2S;)t@}Qj`#rrg|8U~E#WBtl8`fj7*6S-gDt9glOuehxIz@_O7XPZO1xtA$ z&(E>zY~hDV(`p}^E5Z+&XGDS)I(DSk2^|^lW*cl6+)-%ePWGGGPWjcg|LMJ<*Ywmb z@%#3-R<^EICm&6Z-*VA3?h&$_W$AonsAfP9w_F9iizs5tpa{sP$EgJHa1f$wKHyE3 zMWu^YC+Y&>)Lh>@&;VvC3#VPi@4`5`msyA3xUjOzQgpaQ^uPyoVRCN(I~F?MpOwI_ zxAY>ZCPb%nKbNw*ra5D4Ip z9H)4>^AzS>imSG+gQNjn&(}NH`$aiMEG@J#_myk}Rqr)iwIH;#zm4~bPC7lE zW&WTxeOa0dT6xC@FJMQ>a?ywTUICut?Jl!Sbk1&_psPzee;W~^0N465NYa#Ei;J99 z-kpq#i|d5td8gsCT@m$T{eSa1RGrWGV$0E)lz+x~sPP|Ie;=_R@9?h2*)vm!Es zWWkE7#Gd0)vp>sJ_Mu!o6YXMi;w19qS(ZI!^jh`g=ZHq|JL}V5o^bDeyX(blG0>JE zG+T`Jh9MT>K5IXTbAPa80q@paVqIFWHX1r8%#W45F#pWvD8eh}V zXtQzR-jEQ#nMQig?2NNT1hxcxwpR?SWT}$}c&9d?%Hi?Cph#r>5vd4!dnfsJlN4j8 zg%Drdxd7q=-k3tkeEv9AhDknDvQt~uTSpL?6TZx=ir%7v#yfWki@HEX`|od_Ou9p% zL>0t~n-j+!{nx>v?$NQB$f8h;MeNV@k$OV(w32*qU7+7B?a8bl6F_<%+A=V6D2y;L zD`;R+45flQ`m@q)R+vaThAWc?+nyklbTD|DAXA`JgMUT8QxojIv>P=4$lL0+o(`-uRJFC0UcYiB5oPMYgtl5x=j@nS zbUON>BrpO>^#KHEkEF&&JpyqqAox=RK#T~5M$6c4W|$qrlce~~AtX76ZY_~X97 z(p78qkvf>rpJe|BrUkb6OT)2p8IW8 z5?SlB)7DSxgC(G=>}P zcR`Thl-LE1DPAY$E7mds1gE6Vq)cfKI*>=Ll16a0rxwe~R9=0wBvyz2A<)PC#n?$iI1nI`RpO=xsvIe#& zuy&=uc~DI3m7zn56Z~h^2V|1+h)}V(3M0nER zpjdmS^7x@bcUZ})^^=pLrdsrtT1T|zzADmrKabs{yDo3%e{rHp;7Uu$Z@Z((^Y5ex z3JJDW(^7|&JJX6Y_NK<=68+X@Qr3l!8C)fmE)qg@tSorIqF~#SaZ;ENh3fuONeNO6 zxW%^%Jr)QUCYTWHDl|I}4Yz7X^{TyH)z#I#H}dFbckUh*qYnd%k2tD2{SB7KaL=#q z9X+VAonE; zupB(kGQ(eHIjThVldQ`7gDToURUU=g^3~>RkZYbT_;H(b*LCHA*Qn6;6%!)cPsU^C zXKy=h5ZLyYG8oN?T%~>fn0nxjDBaA(&XCFV2Q|MNFJg5%E%W_!?(XB#`8K`*ppFT@ zg=v=g{7lY_$)O{oID;z0nNi_v3I@;4;-Sqi6I@rwFBYJIWLel6!VN#Mn{VR-zuB>z z_Z0r*u{h&tS&HU2c$ZurZ27_XN=#9s@Imuw7e`@yGocG1dQ2&TURoEfwHA?-I)Mev z3o=6FDw9Q~#0cPh!2l)NHPX;6O5*AV3C$mqIF@8@=C1$zn!T^HL@ePGM(k25$r;7{ z%A<^F@|)s$I~?s-~n-4-{7@{JBf(FbSl}{3)&EyE?g&@{u1u4?I zbbNZf#PGp+r*BNgXYI~|hY#nc@aG*M>EMU@OGqya(7Uonx~|XXNZegtUq8HVD2b+v z7t`=UxSZAF_^aK@%+b4Mvs$30MRy0)YjBiW+n-68EjDKG@P4W(pItm zc#*8-a^J>b8KEF0_Luq9RZ-tXnvkBx{t>3aS}b4r{fne`)@+|LOGPO`kI;61Z@YG)gK!BQgL0WtP1*DRG=H29Hl?!-hXwn zNLJ_aUpX@8J^IO9|B#RnjId=n*e6_YDD2Ms6yyPk+xQb#x(+F0eV)C%WZ7cnK^(zb)i=Uk-Yv~}V}@heRLWQ8-t`5I!Ao~94PH9; zHR{f=&?yTG+iG57rDu}ng-ywMY|?kC$Il6wA8*I}C{vm1Tx@2WLlp}7O59gKD^Vzb zRO-87D|&Hgr@7bb?Uz;rP~HrlYZ{*0*QT=c8i8xmygVRx@ z#6^Eup86eOVN1TC%|_;( zGVkOl5Eb|!snj_0V*5t9zV$oD2W1cXHn==D@oz#aV=9%$qxgP~INT(XqLQ{X{T_FK z0bOpH{KJj)EJC3 z)_$Y$5p9X~!%W=3FABZH!bB{7P8cxIO>(e184}NYlzr?Ra#;k>(zv7&4bel ztg;bmLz=_Ja-nE7TskG0_+hELxWwLYN6?}&^p6Z%aY;zQShCkTT%A$HNtpP$uAv`2 z!P8_$Lm5n$3kmx_*NV1FYh~)B(pryD4}8iAVyW?;M_u8tSdJc0v-DuFBD1ubGPx|`@lI% zmgz`PV*OtdNQa)LQ;>}XACtZ>atf1e%gS?%Y;k8e`PXl7~-`fUBaMM+w7n`ZKxn(V`VvZM2Ki&u}_Q{kJEl*-&e69t%c z*LyEr*Ev6|k}PbQE@%DPM$MfqnvF=Rz()~(u(!e-_<^U1<%nsv{ zbq~K>PwCCY8fkI;Y~u)HqiNaLPWo@f+j7bThddbvTAa9McS940@$xu)s&U$hY8z3! znfw1w#asFRu6SDv&aCk4lYC=P!#E>q&Sq0!t|-6w?x&5zjhAC<45l$^q+x^ynL%yX z0S*}+i3o&Avb+h2qd~$`$RGHrGYHZ6)uZGmMc*mkYmm9y#Yw@gFv#8gh>9Zyi*->v zI*~bA_3_nu_ngvB)OeS{nNmRL45< z?lxr?uhn{CBfk-UkNuCWB@_Nz=VaFy$UZ~G+h_gh(@J#$6NEc7XyK}dTU_NjbPLGl zF(hrO2mj0u`tXbJL*QSz3Cj|P;EgvyV^v;@0#KwQU`+nd!zgSN1e%%Q&+7x1Klikp z{CCP>Vfy5K4*%qN5G=@yU3P=3DlQt8{rm? znrV>R)37EJ1(O`NUQFkfnDMDJNjBbI6G;wyUj?pl{6^Yd9)gnZpSBm!c2RnZN84~cKZ|-8 zKG7agRu^0sd-Gk$is1ouc5I2E_(5etEAf1T(_YZDZv7)E!+JA<=WR~6&3+A@g#1VJL1=f*7}~tSK-T?Wlqp_>ChP}~YO%B170dm< z#o-X+ZFdq+bQE!IEQjW949sRYg-Q!0SxxB7VuRjW#q*M%F+^_XfoBN;@Z3m24teiS zg;cO6dDnSbJ_#8Xs@M2#Dnw*M0`3j-fH%QzeKOSm&ujrS%afl1w#7&@`H$)EoMrGK8T+#nO2 z?vkNxKBmNb^+#A(Sl7dAqfWxRe<={QM%_AZ!vS8s#)lm+E1PEVGE_{Fm*CwRdI8)* zqWNS|r>OQV5SWA$9+07Hc;f#hFLA%%J!|lnzQoj~C0#?MaCENwHMeai&VcCqE@i6v zyaV~?1PXz)%*V_Br7a1^SADhTRtIf~kh8!Sd~crimltx{@h|%X<3D$5p3wY?w|T73 z7aN+=CSt7kQ1GThCTfM z;QkOzc5{}s(Me6>^W~@u&wTrI&+wm8c2>@;tMhHTt}vD(VBhDI8CffLSj&1gld3tI zDI6QD)|IbwZfkicy!b=`a;;@?arPqL|r(?RX26 z9bcU}9S2`j`cB(Q8ET9;6+If%pb_z7rS8y^KF3Y&2ooU4C&;tT6`#5B?`OqQk^CKk z*&Jh7p780gvnu(Yy7gZDo4dq1Xj0VY=?ECRuO^a^+rph+OWI{qX*?iSxLFXLJ8%b_l zx8$$lyE~+JzQoahHH5~q-B|0S)-|UbNq-@M{D)B~lEF+3y*bx<7QdNQ8{ZPINcU-L zpJI%*Uyx1@-14CpGN)~cWosI})vKE`YCZh+v<$Aw|EsFIBS&SD*Q0<3g<@N44}U`d zjdLe|Lse)~E5>j=FW#rN{>;^X-u0hXjyX<_wGO**;esWjxCxZwB%DXj#oE>e?#qXS zhPr}?N>QgXT~Pu^G^0Q7{5!n!e`O&O%B1i0^i+^|f8^%dKFk-Lmg%LByY_K=KqCQg zAuOsLSB8CNPF(o!x;Z?pnq|EzDA%RU7dGW3ZCZaqL=Sr0@7C>E%iI05nCc#&H+2U6%QwUOVXUGRZlzoXfP6M_&XE%NFA6kT4N;{cG z4XH@@^)QN=M?rU}+>Gf5TS|Cj8tcoT5`6RGe)BH#!J4maWM{)?!(1-xfMILfr>r0p zut6-D$1^3YW#vk-N@6X?(6NF>X4%)n%Cm4TrFN)xzM}4vpmPx>mLFDwjZr}|VQRlGkmo(@c%D?uL~oNBs7 zf&UhIlse)mdy&tHI&1b5ng2VKg~~N4zQ%3##PB1T2I$(b+MiM6H!U@~Zf5m9hJR8Y zDO24Dyk&~8IRyZ*Ei!`MiIJZ{{R?BiEcaQTc?lnf-Dx*stwjiM2`-@kHBp<{QtT#$ z9msxY#UzX!7>U^RR6_WZ06&t}g{+_egd;P-`I#|%-Je}nP816R%BsnGdc?+W=AT>va&dE;E*=L&2ZkFyp6{6q3Z%R3IQhAg z_MrAxhEp1{G2d%)ipeW!zBe};Dn*}&M0mFrg>0z7O{ zeQ#Y)nte@`6&o&ha_}*qzl(zJ3;h(^41(R^gqL#RxhEPXgTrbPsqi&48JTWL z?5#=^MPK}^i-0lSr0da%}0Uz3Y{{yNmoNij&Hm`XgA{e<R+eV@aRx%a01v`ZmER|zI6?C!zOxdpuf zo=R-tSLv~}@SSUl@<7KFM!2O1j~vjUdYb01YX^~U+Dxt$W50`#*$}s1~fFrM7p{bl{9s7KOtmkhd_r?BiJWy5mbjI-g zyfD^q67{|^*@k<~E~xGwEkIV#V`P)+sxTo4uNJs^-O{0!_!5VWr!t?}FLkB#pE zXRKF|GYrB;)XE3A>~R^c-EcZScT$h#(XUlcD=-$pbppTa%(eu`&%6Rw?E(GMS>$|X zz}8#r%;hWjQ#k)?p(g}f7W+krNl1ckVGydFSjtP$37R0>Mmq5}#DHbXMY8&U#ieRXna61i`eu0j&2zr66?W;$sJQfX>e6B=B>nQCI z6A%y>Cqcc~{>xY$8f`|8>UbeHJi}$z@#2((74gDA5eLyhvuq2DkNFu?M_fy#xDl5g znO^_kF{CiPCBtP%xA=c{!a`>HV@~h`k_juqZQu~=7RQh9H=4-dd4hfa4&Lfqdmj)v z$syM3GvCyJ-&HhtbfgrNLdQBB-Up_g^at~}u3R0CSZl4QV-)y+-z69K43;)_iay6Iv% zHCHw}jN?x@P`=fHR#z-1Q3%8W24J+>N1w>Tc7$EQTUTu8wf0G;D(slo1ef2|Z}~{s zbLUP$?;QC4qJ4HrodE0xpnq&4SF%x{u|{@|?~JK2N{4p)~KA>)L0D(Tank?`O$W zHlKTZ_nqQ5st6lN>fS0y75_aJJXqs)zUS4|(Cb__T`S+bN?iBt{m1cO;Jw z_Ffcv0HS62oLhg@q+c#^8sVbM>&mb^mnTU^o0O9yLcq)+@xq4n!Y^Ij3xUdxf0j z+kwfy8O?xU0iu4V;m{z{O0!z`zx#{hTLSGL)O4|3Xu3R!E6FC8)KM*&e9C;J^F)V z8@A}*Km~u1AOwae2+I9{V!Tjt<-)z}eIi9vXWIGPT;E>_hM0!?9k=RiDXZ)bKM|pK z^z<80gs5dXadGNSrM-7sv(mEpU?k7PdnGvt=m7g8D=&814vvAyXrMR$d-^m4)OFJ{ zf_j`Ke^R6m=CSFOZ!M_OOwwA~rc^$g|5oz8K6Lu0+IB~$<1i9ykwr3mi2;Yi$=MGBaa?MT_}BZ3^q`8r z96@)mR<=LnDN<~|LmQQfb)qmiUPO{2%$vn9ICiJxS$y>|z%e@;HY@*zg_bNNQ1{Q} z;$f*@$+?>9o)eXeG;D(azOPq2HAz;Xd2!&*{&VTy>HCX$jFL)k32Q}hwzKPSq0RO_ z8B`}&5sLH1Zl{xP)wLU;E*>m49Z$^FE}DE(ayv}v%bkNnex{JJ)(|e=MeGeJ%1cQF zVz)e_#F@Zm+{6V0CDY>Sn*I@&;O{r^w8B3k87qb(HrEXl6GOz2N_3Sv<2WMt1{PMN-NomZ1n=X3KlK9|a z-y=DTEg_lVbgH3q+#NgRL+mrqMi4Oeh5r_D@*&9aFg;?2LEIP z04Os(?cG15``>UsE{vRlL&%-G`nb8y;dxW zCg$92F?3K01E;>)Weeemtxz5#|VSrzi1;3bqADgqZe!z-#`=cNh_m z5A^i(#I^(YdtIk!Z9wfvj>;Tf^4F;922m4A?y2`)$o z^*d<c?sz_F)b0RE^j9zT{ zR&f04bW1jrV_kjsFB)pUNAGX%y7Jurs{ww|1$12tmj^HPK(_Yui*O_)WdM3mK}wN- zQ;#i`zXxkct}fhEdy;91uhK6~wIaDg`#) zIXHkjLU8&c@7BslDARi4)GBkCnYj*98hQus60M{dj-Y%615Af(Iy>qbFEz>24}{@{ z%1w-K`-&_$;2P^GIqNt`4OrOiyr}IyR7R))fnO5;>#aJsEg2F4z6&sg1byLpqNN5w zEF5;0ptv3z*PBD?(vG87M$Y56MsAwXM<3KY%jvi{ZTqCjdMK)Zkica+M`Sa#517$R zsSpkk{S%RiD3wPPOdd~${%7}+lnvp3buSeztT9QtRcK^C_l?fY2w-oDNcy~LttsKv ze>PrVJGuO=ICjAMh+)3DcKuAQwORg^p*2@y>k8HvaCJN8z>}x4g+1VgcYO)+n~7I_ zCI(2h?C_6Dle5AGaY2GU+j~wfrRIgU`_HF5I}i5vwydA|qO zDX}#2b=Z7rdCYHE^W(k9e($`2#V_#!AExhsvDW{Kj-34(DoHM0H~1lz^xJZI^y0we z{!7$+)HpOe{8t~($a`0(np~VQ*zxH3u}wPjOJ1WdE`vDb6re!+0>LolNY-a^I|UIj zjo!>O`RI%T!^;iq-`Y*B45jz><$W{P`ioLVY*U>7b(R|ocTm%!=#7d zh4B7=>|+to2>x!L?Nw8IE4a=)=>{)|jS0}#A%jp(OZ+TI{z{kxn1TmSd9*_;h9LdQ znR+F(gve7MqY?4jznC$yJXBYB_x5X)JI=u-N_m?G2X18Q0H3rMT&)0 zNU_kF@AT@Qq7ed4F8xYuLXs>ElICcZ#}GXi^+2ttytOh>^dYF=tj_zuZ}>}3_N!16 zN-%?v42C(V7Z{g;r1cI6*@=*(d$r-X*qknavv9~dxP*l%eBRDO zK4<|*xAtM(z#)$4a5TE~)B7Gt+x7=QtTheYltdT2;SacubinBM+-oyOc!5U<7>=L* z(|{A?@?^a3!9z!Y!cD-DiX2mGBQw^#b3sWVluj%9Y+|#+m8FeyNRM5*Pcs4fR>d-SYl3+AF=<{&y+w0|qMzqakTx~0ArOya;{LDJV8pyz zJ9M(EtBW7|5hxXJ@SHtc!Q;OCJ?~k0yo-5gW}*QN%%K*Q_ga1zjOxv~s#kg6hVs=t zh7y}L#ghY3X30}*_|y0;u_*r3BsgZE#J70?LY7ICR1z7XO|d?3k}16Z2B3tE_d z@^{8%m-o7#mjmCC#=~L(5-XVqMv(|;RpOR?%PqE0QKM;lxcpgH`hcCbac=-)L8@i6 z3qy;npv_@!=tC~)1f&FBmITFn>Ao7^js8}4tB;}(P@)3jrX0Vq8_Q~V+BMHs*f@C%FswJOY zIsF$Zq}C7iTpGUJ9L2PIEX2Y#s;8W@5E){Wma?#PF`r0P0u^$Z2z@WQ*l*jJZLKfg zP#X6-x&aJ{-`y5>;(#o6hCk#aTRZc}QKBfhPB4BB1}-t=NZJ+!9HNFG0wQdWw%ALk zT7Xlafvlaa|tby??_!6>@_hrfR5P4ZjaUn$DP+ zoBQTc{Xp8>7C~c5yU-I7l#;(H9dg&Uz&D=>r;Q#@JMXn{@0j7O-=Z+P_#BAR=sPD~ zs--++9pWo*x3Hb;SxNeanJ9A@u;;MUnG%~lqcEeOpL3kpRur9CS z6i|L7%Wuh^9fUqDPtqVn;w5zx|%_zVxb#C@zs6o77JY2Pd2$Ij?QzTWU9S(K)SS-dQm|;tm5lIx1#a z=Xa4E0T7#vA!eOiP}(5LnHA#_iyW5lOXW;vq*Z8vLaDhQ5uXR$$We!g^=~xyAaRJR zMly-&PD4*V@>lNg!E-i*RJO$aBdd6MHEz6QOiV7@Me!4%|oSV+$@l8?3-q@{Lm->lnavnTsoiinfU1K>GZtpx68jzlP&6cDH{W^&(lK5QLo+#%Kl0IV z#9Qt24Z|6vWMqM$%mF^mMFccRv{vJlIYGCa@jQxQwq)lX;%u8CsMqP0(im=Z`BW3Bv06R zib(|@E4t-g1i{f8<}K>I(dDY4V$9FxY01;i-PkFqV9S^_v^e`WTy>I?GDgmB7-22Q zcZ$UNlFE>cQG%@XAbA@e;WQjbem3{^w{X`Z9HcP0xI;Wi`(QGI_MwqZD%+%30rlN& zPLX*y390VJZI_XMfz-5y_x#Vu>w)SuQ(8de@=_1{$*(hKP9PjPqT3EQT_udLfb9G( zb6s3%uB}$L9seO-lWE{oJpp3^BVY^J(}@3wSCG<15=p{5a_kIX6PNY5YKbHJ;yZkC z)xOCF>AJ-}A`}+?L$~D3$@+oZ>y=K%_)=Z~)Im9v3->)D8H92~=w9)p!6$fj&EXcp zk%4R;W8s$(tIh`>Cmn$TQu}vGVNGzA@VEByM|k}8I3EgPtgLyo6W!_Apd@+~0ZDJxPK$4tAYx zehK3=e5wA8D#q@CGFtE3A>t2lx%=i}-J?54!Ab;49`4Is8bX?1J|pP0QWREzQ$vVT zHeFyBXR}@?hAc64qXa5cV!O7dJ^ z{z;I9O!rqyei{EGZ8BjCN6HxgagPVbLltr&-fQN)HGJ~F85%8KZd`})y-QFf| zoPT%Mt3<*s_(GpCe}!{jp_J z7O==m;pfHaxiT7a_Fix14K1b(zjZT5(>i936X>H8?M6Xa7wX@bmY;fF=1*&JH5~8v zwY1qI-)c6d;MCclMAf+asFv-+gFO`SFZ3xA!sB3ur|8^*EO8aGrVdF3TC8w>{^lq+ z$zLguKyylTW+rFAvt}76KZ09LHi#n!-`hlzHmsI)b?LTeD02+ab;%g=Fj4sciQ~; z`G2vLbjZ|y+;8;BTgm?W+elKKvudCmFR>nB^xyubPI<-f-NYl9TB^0pp)lzY#kO9u zJo3iX?M{3AF-->XbV*m%p4`qLkJK$rs81&q6@?x>-Bsbt@al2`^KCJAP2CdObAi9# zgtR}?6|Q(iijkTX)BHBPshf9&`T)0o=rTD-(x)uxvl^=$s0s4JzT8)mFRc>nlV$e& zG$~AE4})f+?f((rRkEf+M)?~#lYbS@{>5)0G5u7h`H8kC+(&b+q=dl6bLvySL>_q+>G5mDO53gb zL9;ke*zko$ty|ybu)lBw^Q$dW+sIEi`8-{=az>aZ+kxM{9ivOOe8Q&x2S#DTu1fX> z3p5EBi%~3o{H^A)`gFI_Mw{_R<qf2T?)Q3i63?-LU2Y4%)2QZxZD3O#XQs( z)ciNq?1<2EhfumZ`(grYqqKd`7}zlhP(=Tu1+Zwe5cu@mh)-x8L8JL_;ZUl;_H*56 zzj^eCH1l8m-@ludL-|&<(*5VgcbMAK6e)XWg)c1mQf6xfOeL-Jv%S!<8BfGKDxle| zlx$jG6#mi2;+1t*VkN*g>{eB2;Vu|2?l%{@<^M~Mi)b9}((PlmFZzdcnEB2Xf)hpa z+UrPc)9010(hDB`bqksb23)kvQj6PN_50`C@m3UyrZwfS>i8`Y-OBJ3{TWi^>P{iN zKRqusZ*v>@;yoecLtgZJ*0z+2TUWSUevej4LCW$7GTSMjADVzC-|Q7TeNs>;b^`Z2 zZ3+d2b4-ZG5X7ny66;k=fRxlW{GB%j18hsWWv-u+O2I#!P>n$ z%m<>-9@7F7OZ1a|BzF7>qTVKmVzkb@+Va+;4e}UfmPd1;S7uP*Pq~cpg->ODJfS1q z`1Y4}vEveByoez|_idMr1C2GCrVLrskI@9J^KbuA1*;eQU#o&0j^b^F$4xD_& z)14~d71B0YO|th1!6>p!xAOiS8LA871*fw{l+Jb1u^oU*bK=Q%EDz@OiiC)CAbwS| z8a&;74+fco@c{eJ;%yADFotL9iRd`{AJJB;KP=>A5kd?9kr`K}o<+URoPB4s$Aa54 zY7)c+{-ToDJ>^GYcWBCpm<`gtw~gLucKF9^kPh?>1M5rUWoAR7{xM*h6|`9LOH7v< zwZRc3vvjadTmI?g`fNw0W4H>v7!9q%g>qSQKN@{r|EZw57u$JV7sCdtSdJ#FtccBa z=B<*@*K)Z^klRX(p_m-KlE=y2_Hd_`=DM-d|DD!3N%*g8+BWb@Q8_3k_or<+j8Z z8n@#OS9NW;Tp1e21CCoO?~~DJb_9RAL`U*86j{zjfmU_|^*ced_#~1Bn-?fm!7fON zkV&NSpWGK1H-+d|&-J_l6N`7HMwWVIMYX$^8y$VO-&31xgrHXIEq0ehjZ3vmq+OJJ zi4uhjuieBQG}_?yx-~h1sR+${w?s|KDPom&-}EEnl0RWs%IuJ-WaY_|hbiGsT3S(_|r(C=j8~7h^r4V@DGw zB`CO$Z{+<7xcToqcRF71v>N|g zI<2_Y%XOp3hueyA*cZn=JBk*@Vkf#N>!y;>C5&wq}dNLN>#sU z5caUcT!=>KD_eyOr3$7afz&4w(@m6;QYGBnY~}3O?ZiRbihr%CFl*VCDqB?k%rd(J zDBdP$sDGH75omle!{mc)^rJo?+}!B>tyu}t+2#>z%)eJ-bFLte(;SFg)SX9*VS3ix z67M3_ZW8wJZoYj9ih#h;KovB4Gvc-Pr>pwk-;Su9448H(yBA8jQC}g!O{3%zw$(NE zKT0CGP5)IAQTiIQWV{gK)S)r@VtTqRO$xnp2m^1jss$IycUma#;?$-5&-uPEPtq`% zU*B^aJdU#;&Gp{gBp80G3N=empyEkI^wRldC!n%R+Q)EBURHVNUoH^j-PCGuxA;9TMBHNfI=3 zz>Cwj^XEuExc8WfqaRGRY1((dJSzku?mUv(>r0}iD+piDz5S1!_HnW(O@Z?uqh>uQ zHtX&oE|y)jh~VDK?U)UqDuc+#Pyb?|_a`8El@~@%eme8UJPdN7j%V~;sW~pF_3T8C z18xO{LyiBe__-yTG`c({6^IM^`g^(EYle4dMQQH}#ksjBbsCXLpP_=F_c4$=VSEav z_ng|Bc1fu78vafF9rgVzUeMQ=gnV+BazZ79_*lHIjk-$-?Q5*b94~H%=cbQ4%lE=} z8pF%#+#(GhO?NJ9Ev!&oBsTbo?!0llh(-52yZHTzOEvZj%q!I+1UttWn=R1k z4Ot}h_S~{LZ;KP^YCfTZG`Q+3ytYLH)8&t%&Z3wC$7ERs>JMtFT(+0lge|HlU$@1( zeY$!-h+15T;7Oe=8`HfcYHC7PRk*#Ti9eXClaU3VgW9u4NR{b+B)CjzBv~s@q?fb#HLT{I?O-6 z+Vt2ld3pV26szK~(Av3d_2tmL?I(3ATq5M<=rgNr&bk%XQqP{KztDTr_hE7IELnTX zamv)QEt-nHjT49H)UV@pXsT?@6O9qCBV7;hw?sIw)^|FdlJK0ZAARj7#`D}vBvrPs zv8&!<^2GUD33ZNY=S65!x?435a7X8R?a1mjzN{Rbu0qwS zd~%=f+s5_B(Q{3T5UU^fwrO2feh>s}p{hbgM!q8q@A2?CD>p35Ki{5?&gJ5PlIp422DzoW7Oj-iBnKk}sh2-sHb|xHIzC4*2sQW# zKB?nncR%@@cWr>=?)@SX+JE>Wi>R0Ax27I|Hze^NIto!-L&Z^)F7b8Xj-5q~vm&&@#jE%esxoJKWn3bS`tQm4 z=S~YgJ##4pIPa<140O!(gS86Taqp7UkB+z*#onggHA5M*&GgDMiZp}f1JMzRse?dJvvQ2LzC69XcAaA1vGmS4*kMnIWs0^ z>!oQApT$YM}-0#&$JYzf# zU%bG8wzm7#B|7n=#ZIg1>y1$K>f27~uYZF7wW=Azdf~}wjVM_a`{&Q$JLprzp1p>g z+B2MMvL|l0y@rJjbAxA^X00^Ug_kEqL%rjW(;Zh1?~$5?I9<{25v0PFz^e zH&PZ$fMzfZJPvyBNLc$ZrH!?8XCMRK1)2%X(UaOjOrb zmsZFRlI^fXKYHq?q!>JmY%nG>tYM~NoZy-oz{J^b{j->vwks+|F*JwF%{RHO$-!m) z(DUM?mal-Gmss$i=T&fiFfWh6@6da;BLR!)cqXBXd>tBzjOLXU4MK0ne;I&GN0UZB zT!j;xr=co(RbB|6!-L|#YB=(8;Jws{{_`3#I2R(|f!jne}ILyg9gpg(^ZC^qaJ;^*802&e)`A9`dj~LG0>Nh(FKorxwUW~v6sHi)e0UQ++i5~ zlzx$c;F}*_s!rgd|27FnB>&tF@?W>RkKk}aTeoHOjMn!W`%tN3W!VFvG1cv)NiZ+q z9$@h}fXT5=uM{0Se2w5pFHdtbQz{Dy31Lm=hFFI zux?!cDnzg>X}$jY2skQ+97mUd`L{-<#9uhL;BaL~M}jk?KZ)_adRmYF^E<_%#64;21L1hk16VX~ic#j7+LY z1iqdJ9T|o?@r*nVpF1ps0tQ0ar8(iRFUmiNOC4J;qvNNR%^&2nTlY@kDkXFiQPt7N z$P^B1s24Oo<^SHQitYY;0@K|8N-p0T;?elcxNbk_XWJpxzQe`Y#=wKAGA%+yLOS`# z=MK->tjLb+_hv#E+} zx)D%_P%KLA>`gRoKBiw`$0*uBr-C}9wL@e~h%W%gEDjWWH8f?I^kL)nM;8$hHn|%D zipfS?;+1mPMBU+*%dg_UUXLH1ROnrIdh;N4=T4#r^kDh$-QoM#-t3|P z#b^~~t=y?HgBCx3CPFS#8A6iV8YIpts9oW^8fJ2(_!!B!8RBmVL1Nbf;U)SEM+Cji zi0Kh+VEweofW68cbv)!x`k%XZ#Rlv&%$37zf}+tyna&VgMhu@Xt`O>Jh8O2_;=%gW zFS^2L<}I|8c(%AqVnBN!XsPc`b|jnGu^%(LYO&(?BbgfyT;}l%=Gq`8fkoEGk(maPnRQW9k3<^c}DK2-YhNN7jOeg^0?Ev ziS~^POSGmp!HrKR1!tQvyb#3s|0PoVE(!mToIoUh9pAE*R?FU_C zJLrP|khTV}dSH+4C+ddN19QWR#TEvRuoW_3seF2P#1?Vm+cg+JVgkEzq<#B2yj{)K zqK4_u3BG2Rg>Mus!noL3>+{S;zQgP5q$Fu!chTqN%Rvc78>L?e>b_*N8b6X~fYCiH zZ;vZE3AX(-A9j$aTb^4GfY!HQw?_m-l5<$rAUyXR44UycYmrSfHNWPZYJV9eMLrz; zq`R6?Y?Md7byKbFKVmkA9dP|U$Ug;n@+vX={Ia&pLSresCu_m8@LQBdz!zj6110^6C6>z%AgTOLhS?h@e<`KU#LpTH2?oF!SRNDsz$dloC6RDurGx5a`%)RvMcpx7!Rp z@2H+OHY=Shxt=$uekHZVO{gHKUYf)auL-=2wPC${<&S3tm&5g{t3JPX{h2f}7_2;}K%`qb>l z_U5;aa+7xj6XSj_)M5`NRfOx7OctvzoT{%_vBPHjEalp|iR9X$b_WYru{U3G%L>r1 z4rUd1*Ht|X%%qq+6WM}1SitErgRj9us z0%B-nAS#J~67v~Tgp#phe0x;64V+Whg~KdYz|QXV;|8rqlk6`>lCBF_HU<+^9H`%- z=DL#G`u^gn(N~GNQ?f+gD1TT{p4`rLnIwlclawswj9pnQXm$}F@7d{&=YF6}^!t6t zFXFe$fUJ3COYVDo-ugDpaU(id%I5 z`oMLn1GX(MGqC1`Seq9H;FJ}9UMVI5aVow^{=EEv^Qc>Jvv=~r)Mgr(*_7x&!HtU9 zV#9XHtfclItZb5KXTTW8Knv9r*~$g`$a2~@@O7s4)na$NhH0I=8PflfoBHxv;x?ZR zbVkFde9`-9isX&{RQdd4ZBzf?hE9b@>%}DhaUqwAx)LLQ2e;Z@rT_Eswg(#$D7NlEJQQ>8t1tGWsnQS$1fIp-@4VeT zd;KpR;+&6ieMZDo;(8;`+i&FtVft8hro{g`M+pBKFQX%*{TT_0F!DU+V}8wUpD3*$ zTE(UZa}6Wwc>|8$Bo{F=#sgTj#56BhC>-;YiI5CJn9c>PfbZ{<=QR@q)|tl(3sTE3dp)XQwQn1(zN`5qZKJ3N9ph= zj8v1~71V54CSZ1F$n0FzKBL34z3|O{-WCJ+Ii3H!@BsMwKh7q0`pEwI-cHPs&)vsPSP^}){$5Z@bRJC*jYE=fws>p8eJ#bip$0)HUWZmyhW{s?-#YZS0Chhx_8 z1Zm(O+%#i1-IWnn5TDB!n&o<&hnT+xrOQNru-^LqWsM&^}u+1 z?T|oz^bVIB^4*O9EgGueS?D-{AAK@C`#%NlehbYYa95pxH%+oc%Q=5{M}FF@yNB;v zzF9XC`d&S4J&(4P(cz8f4N5YKR+NAviL2L}GqZDDF*aUQl^p&Z%PskLEBsZAa-+{? z_1wh)ps`c%IO8<=PxO64ZXOOk=(`Eu(Fy1cb+grDat!WO2ZUXjZq562hjnjmJK`m` zTUdTxYM6IE0ij&vqePXpLY7)#yB%7yfds*cD#<34qVgeqSAedSVZ{A#4)7Z55j7@# z5bzWo_;0(4s_m;rmCMNMYIDUjUXSXp6T1s(8Q zp}m+k-qQ%$56II9OSnciaH|EXuzuica4_`Y-yN4Tjq~V{TaolL)U2Sa-YE@Z4Ky(W zd&(KyQUNvC_w5l@%1Ef8X}*Xeu%K=&`JVq77FDiA7b!hTZO|e;3*Q(2}q2;_q%x@=DBOv&{js4 zTGU{=xAmS#GhK)#CcDk5p-q?cwu=H7JCpdNJrVGsLZ>0$l>o=!Pp=M>I>FtAA)?co z{y(lQW{Z-B`Yk?QdHWefGXxwcg0qoS1`x|EX?7%UR!~CE0gkis@-y-cStVvDupUD0HIlI;}|9U;16|;b1@OsJXr@Ozw>rHoo=@t&t zM|+`x576r!L$wqgh>C)jN zUVQs=>e`h0*-88NWU#w^8BG~a!NJc@0z%+kt#~02EUs{Yi!CZ>kFGyQe~8f0Aisyf zvE&tz9}l4+!_bVRrli~>0gI){`r*eUU!Rf6wZbyqRn9*2gP4JzjEDig#A602^H`oKk&Ea<`gzN zdH0V@!NvUF?yE1l#kUvI(!S0J!wt{>b95`^;+VlzO+tj_%^W}&ssIx(L)7iA+t%86LnW%3`70}b=^^PETjkQW$kXiax++nJm|2KSVfz46#Qqj z+lK2?d^8a7>088lVMPB2>lN~r1rT!af=+Hx)S@Jy{1M}3xvo3%ArZ3*yaO-~0zvt- zVP*2fi#)6sBRnc9yXe6?03+>lg`;{C66gf1_1^rt)7(-dQt;rrQkNRqdB(l_Enoe9 zy!Av7ukzP&v(^Xz_h14*3g1a94UYS)@Rc^{;Ch%fOrraD*SX7{r@_TJkjf1Mlr093 zl4sco73j(Y_jCT&x%V8snFjM%9Ug*BP7I7=49>v0B>L49D~A*~(H|7<4q}dw#;;@i zB5!2U5uf^O_yBf&nr!#SSA8;P-giffr+!&gG6xG~IjD!l-CEF=4Aho~(}jsZ1W>Ew zRFDeA?N76W!>7>5#XS1NIU`O&;bJVKZ(ZNFT+{jxVL$gN{(Wj7n7aoA@08OYGxX(S zuCKmaZ1sJJY#hAD#b2l%?h;&`6L1PAG_LjQa&Si>CCZn5-b;8NTYzr&N=Z*ryVmpH zdEj{c$AbDnY5E%Nc8;PQI08=l=~h<+NyOIBJG{hFt3Su5KkQm+p5rup0CyA)f=@Oi zgAeD&@UIH$|12?>4O9_exeSWX-V7`>Rr-lR<*ihHmhPB4-tkW#bU=p^_cXQIdLSlE zm%0T}=vF@Cas^p;(6=`La98dWfV=R&C$NA;y)uHH)5BjV-#r#F4=?P{NYbu{=J!sQ zVpPULWCXyMgMWFL!O#~{lUKZflQ~H!fHGHIch#Z{Vo{(!0BAG#=&l0$i_H%KJIPg* zYJ;gtF3`Fb@P2FTrtw5wH+cMrW9)0~rgg6qb=-1y%LeYzmFW{K`eCa#XK39tgX&@+ z3Hxowtsi5HX=ON#m`bv8ZEWS|%8K6h25rKhmQuwDN;7feWbE?>lGPL!}8IRQ{WV#RrNE+n|QUpxKiX&D94f8!|vo(Nee2(3gDp zxp|&x+l>eV`kU{auvv>2n|YhW5>URYc{57_I#5NO-PSAB)kz#{Ae2wQ`Y7q;(msqZIcT z1I<^1Luj@MJP}r|78z)K&$f6|7VRo$1ac28gY0mwdwj;L?+p;2zx%OHcTf9JlFdiI z#u+y_p4~TXK9!vmHdc7_4G0oh4R-V5q&^Ih)2tAh1##2)ZW!QFhs|uy zzx=mCDZOI6-fm z0D}BG=z$GJ4{Vt}SDw<6ejKYghQyBmTV%ueEmCg7N5bXiUBZ}Gs~spw3VxTnMm299 zNEsX$3HO0~iB_$T`jmHT{M>y{v^opFJ-aK`R%dB+a~!*#o!-q5Myud}nC$cy{dV4j z%d2%bOO&lzW+0O?veI%M1M9`${*-*mzuZyK^Xh22URqu(NjsUU#b$^${NPHXW9hw< zW|qX$)<>Jp8%IxTUQOTKXD>mG&bKvFO_QLo2|AWS=mIIK}lcLK(SC>g~lg{YA&(zW*I$8u~ZLB>&$* zrpWs4B>Rc_RuKheX$^q~~#0F%;zO->9I=}YTs&CSo{_&FZ`W30bBvwF=^^W$UXNJ$qY z+vOP&2Z2x8`JLFB(e&yxjjYOPOk;lmMiSKMDn89s@&qis4u|8J&oppP!;fH4>|@f& zj2(cXQNFV1NhQB>h+zZ0Q^F$vA)ybYu!)!S_+<}Uv}T~wCGz3Z#< zK1DkJ7a!VG8S_|I0B*bfPr8W*A6Qq6qjSyoI@^xmTvd2dp~n@PXB4uJvbH@^NqTcp zX-)M654U$AbVw`j`J$2s_q7{w5B>`sZI8*(u3cZyxm;hX+g|ukVF`I>QE0<-*(ov( z@zkK&Dv!L;SQOb3y{FgnJ9ED3y#Mu=R>Olq^LZ$bLK3RbmJ9KISG(OoCtox+`irKz5y4iBh7^VyoQT>S> zulPg3F1#JeBwc>8t4%BZym`fG z^f_dFYyL~U)7mgPIkgmhnaOH?6N0m8{}c*=DJlQym8T$@qp1ASsgT7tGJ3LSAo(hC5L`;5|Ve|n0joy zC4b?s7ew)v%jwI524@6rp+;tDIdjh?m<1ykK>;=}Hw|HdWSdShrC9I9mvdbB)iP^4 z9Q{pENf2Xyf3HDFMKS_ z)lx`E+mtgU5zW5aLIMuYbZ~b@O?`9TAR?3!#qOna$Sz}PY*cXMG4!P*f)V-}6BS#p z3euFCw{`+*&?^b+Lqs5ByxYN?V6EXp1$5(9-4Je75D+0CiO3ZT?qE z(W;qZwF#}mhpLoRF2N$tC4A4GxNdk6|M7LPr_a}Tjbs^5>TG|TMeo*Q&0e$wy7F|q za)JC{U3oQ989?;UP~l)$V|`|WHHxN=C(v8pijXIMy~lQ(JYE}By~*O(qY8(rbKb)e zR(HhuBNdeWMW< zIwc5}Ofpz970o!mj)h-q!!jg%O(TD(Q}0aKsBZKu7u|GzS{_5ETip-xH|H`RhRmM8 z6b_p1F-%VjhjWwRrTkgBk_ z4a|)?56(nLGH|{V4e7CRS%7UU+g90hY>m3z0?NklNZE4or$Bm2P0$@^4zU|m18NF| z|g9(_YyTurYfGMvUhh>PL^V$AV5U8@I*KE7}v*}79qO!K^`AR1FJuSd)XI5fF znejQxaH~=9lUz&P+?Dh>?fQo4JKpBuR^vENEP3Te`}+I;4z;mj{Tph-e18u?GBoo> zVMl)`EPE^q=fTRth(ce_4 z+#CsrO)J#iH!xU$GfHy^B)qSz0K1$5xU~^d`EhoOO@bghRwR_nr!(8=#@cp$W~>Ve zB!PxS)uj5@nfg+_vb9)gRL4@QZ#+<2>i+vkLzq1cQ-afVVfLYD@)Zu+Nd~T|Vp5>| zPcd#HzQV|s$hYqLO|I7v_7)Gk8x!wRsYB#~>L1$MS!Vozn^$T9`sIB0%~8=rBhyUi z1CPz9g$d-{Vwz5=O8yc8SFPhGU04~ib@F9cPC#Das`Zs+pO675$!9E{JCI<8I;X{a zhIf&PY@y4t!mnRHOepnhxo4-}E5$ijA5Xq&T<*urbb5}>7!qu&sWW3-la=+x8+VF z4h!))rD~oN5Y@m*c@H)%wj8fT$1OF`A|4d~cN#mjZvO26T1Et*hD*w8T@aMB6~&%U zV@lA&9P%i^A(?CT#bL7W9;ijJDg6}wdcFaJ)J*~WiwqFXbo{?YzszS_Z^@SMuJ)P! zX{>6ppO8NWtmvb>(iCyf1w_k(_AN05;VcGuWe zH@^Uw0jl1!<==iwgDQ94QTrWIT4|pskUY)_VM%FrKP-@U zQyZM-NS^L>(#)3X2?W}r2Op*4HEcCee1mV-F6emu2ge$me?Q^7`$G2r4L%fS8Tkk> zH3&`v8%!EHmes009`w^Oq<{G*%bOcyR$Mz>zy&>82xa!GZ5dndNV;$ysC+EeDI%1* zkvQgH&-!%SUe;UVK#Eb(j%u2#v;~TeyWOCvw64_(sQB*Bz2-sf6lG8KKJ&l)`)4;i zqoL)`-w@=%RLO&%eW2ue1=Q5s>5(>{-J0u_jxyTxf&r#Gn|^sl8a@n#U~L0kAIWA1 zX`F#XLNqve7(kzd-9u0S6sp+^Sl71?TTVt*U(@A^V-s!FUaSNW%>-PmVl#KCCbEYD zZg%n6Px1hv_RC!kzoT#17l0lE$k}(%WxpeugFnN!Ur1vU(SD{~dI99owCAwRVz0MY z41vC&a15Pv45;`i*&79pgkNO>n-+un;S$YZ>-mx@gtLM6=+w6rw5ZaqRn+7JDSsl6 zq`m`m#(uWL+Dm&!sxIdIms-55T-Kpvf@+RPDTPP#1428mnSMgI-nKfgzEkPxI6U8- zR*eqLTYDY9UhIGDKSsRbS7G?I@Y3&V%Oa1UkLPfptT)okZmLR}*6L!TETwrr>5`Vt z;LmnY>saBo50kzpHU_|1T@d^~X<9a@(Mt}^55X|{>%dG_#i0NKfJ4TWT;xH?z;f1- zVwXlNh@@Voj68-(PP&bmPCrNalry{dZlWh7A8Er?4vOE`fSgz;#CqooUNx8C13oix1a6#RO6 zlbc(Ha;S!I;UY?c&B~ir#V{+`D#IcAr*QSfA?&6sgu6hnfJ=BX!YdlormTW$3Ijk4 zB^k2ri_zn|{HQ7Q6j1j`%^g|BL9d9OEbjzyP^jH~2}~`iPF;FJ063*YJa*xisrDP& z@gX_t8kED93Cm0r zs_*S@=C}O=@q`a$ecBEsS1X_-8iVl*5E(9b zaVM{%A)W|dc#BftRU8S%d96OFSMbPXREHHW$!oNflLuzN)-a{Vx;ihq?5yiG9a^}M zVVvzAxOEsPJ}C41=re~6O#nrlMwuVSEuS>~%17or1MPm^C(whkS!`iDOO1hlRr~9Z z1Pu&R3A_pf5@e-HytWKiY%mo#+oy{!=Iv&ta<*OJnrF)d@scqc+>Fl$g4c)KA4N^& zNmvSSFnU2$MV5wDOP7B>^WpW0$$g(2CZ40S#FMM6>5>Cm1Cqk!OmPl#VZTPdSwk{K z-ZnfC+s<7g#AAi3&ykyDJLFE$!yKu5yydjygGm2mz%??Aoj}jw3&%qr6;PRO^q7eW zD?8w_B+WR35y<50xozadN@;5i1M{M<9epw?bbz^iC-1?jEM*VQE6D>)9oabUijk23 zgSH!#uZJWQ?rP?W;@gdPTQ(nB?{2!JuB}hFgNkSGHQ8DQ>IRW2mf!YV*4a_&1AhR@Tl&f|KqJ>mUgLAuLOU^K6%Am4 zX-x#X#<|68gVM~DG$*(}s2$Ny5C5~3xZbs%N~E()@Znvo^^i$AF#K9ADYA@QlTyF- zFhgyCw%pW(%czU#>h?8=$s$%kwLF|>bNj#4DYtU3_WUIXuIN|@YRcrU(}aA z!#HlP1qNFbfB3s$^W>%|ZCSS%ttst7KqL@0$=Ka~u_1M(VrbJ$na%}k?B$V7A?{0L z*V9f0;mpU&1sxfkrsIVS>$>#W*+T!y*1MFhj(aT^h8Er2Hb-E^OpjriZXKTr)TP@? zGk!_6dcP00%$>sX1|XWtqLER&MX;UmU)JZrihYd9$BUCNdr1IM|00UK@ZQEGge<9c z0GJ=m%rXW%EDJ$&)XD)nv}-?+!uPEzsg6$&D3K;%)p(O{7q!cC|NU!@DDt~;`AVxI zwMpYA%97|*KvF_G{51gE_yL)-Ft>zF3*vRb&fv7vNQ~PB(WDo$ zl=7$z-I`Zgr(&X;Jd6(@8UXt%&1WwV-p1}rA;P^-5$ub!)})7ikPDgxGWyIEjDzNi z+e)c?HVsIdW|4CdPq;9t=nF?s>;$a}SI z8+EX0o3PEIUl+>Y0or(}j8?_gg=Q=N$a_}6wki5|j8EaQ^gK1I>kD@#X+`)DX>Cg( z7tGr%hTh2xQgJ$lE4@eh8kqsaN=s_6w0LtV3YqdVqWid7MRO5slC%>W2lrxWQ%yRj%emYAS!yF2C7~kaHz6J`547HI& z!y==XqN3RdZ`%)mCKO-i_pE=6d|OCb_{n9Oiq`09517yzLeg#%eZ+mB+E<&Qola!^ zSC^yCKmW~E#`YNBme#u8%dF>v!ZDPva#8jya?zMM)@9*`7*e;^Y~wzf)T$>!<*b_L zHXK3ap}fmBp{Dsq2Jy`=Dk>{qw~$AG0d_jFNC7ESu*JfI;@WXYM1L*9BO1)jWN2B=x@j#^D)iWWk(O74?_i!wrPl$4Fs zB&uoa;?L>xt$mxRSKTA?Y*^l3huC^R@KA;z;YAx2JLu@ANFyk9JLpWv-jqg!#g@#L z>JZ5VgYZDeDM$KeIw>=YBXzDbNN1xcHaN~e3%MSaJet#2dOwOTYy?>Iwje**d!97(^k}Cvg8XTslDG;(ItzdPA021kz^iw&M2p8EdJ> z^ul?^$yV_3=_e*P2%$SOw+0>N-KsTokCU_C1{8WAhJ=1K`dPEXyiHLixoX>&gC1cM z$=SrC^w8}SdL7W7m5~z{2~)9>3NdJK{$wY9Gm?8gKHjwdFW1fO{>q`U38TlKUhh6^ zeKl_@fu3+tABHdC5Rf;tQh64GPOKT@TvQ_kyC`Ty-DOn!JZGGBZo6$k0devDUbE4k ztr02_?=^+M@c4vh_&?Z8w|b=50U;q3$3O*jd}=qyO|GJa$1tb|#oVpnn-4Bi)mDsu z*<|ukm)vck>KVhIX$!_?9XvJ}Fb||qAa775l=t|n_J`Z7; z>QY4S=fSOX*$aeh6hS-)m*-U-#6FuXM%vUc_t0%}>IgoI_$ux5f~_yUI^9~;a*)bQ zQXNO<&NHSRzOi_upev#2lv$gfp+Y|2Wy<&$cp&M=I)&tR;z`J_gHrv9tcZrGu>mRG zwM=Gq#89J3&>%K3+!yZQ1OJr89_*R`1GNOC>o4TJl|PLXLnW(?k`K?MU>U|fc=*>> z)ch*1>Vk=@>p~sYe+&@qJOfQ*@7i9Vauy?%l_q?{=};V6~CDQpZ(l9L{y(difGDR2!4c zC^?vX@WX~{vtSg?XINpIe)be5L$)YtlGvU>6!q6Owz_bn;48s*$Oqp@z1g^NYjat0GtG@#UsyNlKem_LYrKtqF|#Xb6VJI~i}4N)ZfP5{HpXSGM}E_q@2svKU#D#)s+VpS$KRe!yu zB=oDffxn)4lVk{nI-z@F-nI~jv=P536$r(e@61)4o&(FFXjgn{eh8szDf6cs4R68J@ZS zn+tYv#z0EJeI?W*(J(GMh(F~{iPO=h5{gd|!c2~z*9&n*ggMknvhK+% z+fbZ*;xkIr+M_l%i@Y5JRv0M^l-PjkhDSE?Py3`vhg*c^2eC!#j)m7S??~0GoN_W!i^S64se?9!ce<2Ee=k8z*#$3c_D{k>o;Bo#ZMGAaGwrc$8S3$9J+6=W zq0Puq8*d^lnicQ}oL=QFAM?=A&RvWlKspS0Ci2XLuli#s30!yytcV&;bFCP!U^SQC zbXTYh-^6tMo0YxMsHU~MtPvlz z5Z<}Zwj2i08C`k^RhJ$mE$I1JrzMYpp^un;86_nxoT2%L*fc!*iHAsBW!Sm1!%uOq z$(W0Oy} z`DmM-`F;Vh8&7W{(k9|IpCu_@p4foQ@=-ML#1kL(JE-)==MX!?l!`>{!11c6BwI%_ zXgPnHnWj03i|7kDzZ(O8LR7Z>R@mmYV(j21Z`7KthGk*-%63S$e`|Tx4@MzI7{q#( zHo`F`xXqA??$@(-zs5(k6i^A+bXdG$EH>OWg3R?Y*)HKY@{IbgW&Ly=1w$#0Lsx!9WilHZ7^#m4=Ul{ zIHeT+I#*>KHmI-aqNv=7Y$E-Fe3X|*G25wR*>*hkYQ&_`wItq|2?mj;R9EBe(Pu!+ z@i9}IrwcQ{yziO$c83$&&3Fw;46>^Tn4(5y`%&C13PjY*w^&qGnWu99o91X3YZA+&C~{BOBt#9O@z&`I%!(z|qN z46x{HS$c*(3Rd&do*Jm1_0vRo5{c3q3v~qcK9HVD%Sfo-5;u0_ zeiS6G3N2YCYdBN-55WF{KQ0t92e|d%`TkY;HB<}Ylz&$p;f_^oYZfY5)(9|Kdb_6+({QkO2b7d+K^3kB-M35#D zW(HMx9kyte*6gR`7<`QE$G{m`;nBJ8^0D;SAjnx1o2d)?TJC;8BcwCusrK+jHgh%`m{mt zTEULCusUH)5-S6^*LgFb2qCyM16`f@uL4uSn8yFX^m?= zx(SI!-Vc|&y#VL3>J)C_*WEVg_kEroo#j{KmTG>;x`mCA;l9W>XxIkkCt0j zOSdTKj6O`k&P>;;KFnhC`_zIz<|x z_~wrN{n(gwp-$zX$qXmUBHY>mN5b#onL~{767fylxuET?{M(j;^NS-}(6Cx5jthUn zlQOv5TSZ(_W6aUCw?LDf!R)6FwU|4O--%4bIhwC0X$=AOs%1|UUbu1fGx z0DWjYM86#1qH?2UUV+9fTdM2fl4N3bj21i4XLKRfTA=P#pGirt04UyyecC9wuRoYU zcGSf>5nu)CZ^D@|9Z?eisv;wPwYA1U)t2f_;8);~)%M4v#j9$tc_gDO>Zl-O9W(q_ z1S6tMT5V!1p3_*UwrU+nM)CkL*UtbOb~x(~vj*@i1n}>QOI;6Ag`KjD3p{HrZ2eN)_g=W1TF({ur9j~QUKpn5rOnSZfS&1<`Uy3mCR9lcA!em_xpIPl?abb7Ah z80zBXGuZy}SJms7%nF&O?gu~c)tBFpy-q>+qTnB_@AGlvz%r1gs?2Aksb60xEc!%$ zZ`GF``Ib*qF^0YWe_fQqQ_#C)EhDV1ZV3xPv_)>q#XQ&4};? zIewtrX8r5?CpPVT9CUHCvt*71K%MI6j^cL+*ghcMcYwSRTwrRGrCpJ7@Dg-xkz4Hy zMYjn$9Tax!K{s$I{Q^X06#<9o2xL@C#ef#LETCg1>TU)XnTc0qS_b`X{$ptQzDQXuoMb z9Rt=?F|w(JOGo6{@7-g-In?B}3Rnfgc%@Q0zxb?@B!JRzu~5SrCcm#A+iM!rAy7Zw zH3(=Q#Zp?O6`+|8P-B!=Qo<2QI!nAayycM?$j>##;b9f&lZ7#U zfGHyD56=JI#Foc=U0z?@UCTnzlM?uCH{mK%W zfG4osCu8&&m@rZFI%@UVPZI{x@p`=TY+nhxH&6H&P)>?iIu~*%e=QYYioM+ls%X2WpQwU2Ev#@F zpUJ#getY{&$Z!4ne-Ie8&I$ex)v=&Q^fTFoy3a<9q(cFwqLt56Z zXg{`t)>GQ?rY)=6TM8}8+j|3`AJsFM7vore0+3GDSj_(_|FE`j*<>%TGyOrEm_z#6 zH?5GQ0JkwJ9~IofNDJ}1M6}ejG!Ga1HGz(zx&LWm6L0P>3nsuSZbbJ?Vm3E$-{}ZA zX>n@#a~IShl0puGzxuraSr{t39ftz7oMGSv=BiozrDYsKYiyU&h&bN@Qj?1Rm644> zN;z4~YQ#jhA&42b0QD;ZG*4oC+Ih%dUz}I0z?e-P-wtI{rZHz;Q9>m|W}STkJbfHI zJneMf+BdV>4yd}qN#gm$XMY(*k@Y4$v*mbWmM|qg?U{e9+H7Fq-RgTm}r6;I@^5s`8Xlyl76}m2R%!m9HO;|ZhfAiUqnVT?waad2bXVfqRE3&Z zfl`vqb~Co(m$QlOtTA*7%UN{vupn6qF{?NE_U&e08O{!7KV)8MGVtg-7R{0AZ2~!! zPnHLR{cr@?XOnuG673?FA@5Bl*$y_0*dcQ+(w6wGy{@RHT#;oVt)Id%i&kT?uGeTdyqz-Y1286$?+gnut+V2tReK|By*ZrwE7 zjo-)^x7ivgc@@WHD6a=tvx^s71|p6Nwep~LPuO5+A#$_Km+mx_Ul-wLQ7jwwy9R{GTgeYWKd4)tgZu!~m-%icZ>0 z^2qWLWub>f>77CI2&=8+O(Vd*GGtC@G~-)~(`tBP^0A?9PwTTp)*jVN3VCQsNGNIVbnTH8@}m7Gx|+rhUW zONxOd8Yxmtremo`9M2aw3776=zJqNOXxn2-V`{eq17GTpLUAYbK94wtW5+?;L4tKr z{XbRZ6$N7AZ`TVf%F%KwTAZ?;H&y&z%&J0uKdbJMhhka(?%XWaDs#-oX#6{-K*}Ab zt~{+SPE>Z7$d+QNKwPod^3eO_q5J$TPycpK*)43#frx0M4ad!+6QOc_GEh<6x5QXf zd-k%H1Li>WO?d0#CBy%yDeq}$1sePcnRYg{k|mCoJ#z>BWeNtW#J644JJyer-&KP~ z(kj$PcT=>3gs&E!g$l1BZ)wNz*$rz=r8$h68`Ik{$*LyP4Yw*AUaow@JQd@g&)Xi2 zc8qgJsHS$Xi9)fp{+%?Q2ogTsM|(+$#g(kE=wnN9hrA4jNvWTBID^zGG?FC0L2J(E z#O?5Jq*zhAlQvxDWiOi{9|wY5!^Ryq?znoD`X zP_7%?(%BL*M4lHfG4W@fUpEpRsXyvi zP^x+IL5Nh2m6WB_g_UJIF$Itwcj*j9aqJBf~iN8nTu`pgIo0OlEjO=8V-Obye+|2&G<*T%KrhrB0 zM_j!lJ$wuTucH_<6>b2y-oG95Up#62%I}jr zKWXz6QRM64NY36Qlz7AE(q?5p3 zlzLNsAV{GZd_x4n>SK#?9?@<_iA?E!`-VLzl}!9Xu8pBm0E>t^h2qj zoh6E!V|r%4z<*_ih~{V5fOKr{dyg^~(+4%~w8W8;jR$XnDSsWmTsKky+^ri9yB`6I zvpPyZw1@mQZE`!By5LO+p$0kJNWim_^m7v$G+&D2KW7rgbS16b0wDf}?-QHY%v|O@ zHmmlN3tr*J?_BwtKz5)|23^opTB?|_Q(?Y05ftA6Ts9q#+=O;0;^;0&zpJ{)Jsrj| zU!rieW>Ip=nSk=!!%2pJO3b~SSXNXvxOF6- z^}F6%Z$~sv&u~EZk1OOS%Lm|Leh&gW;}ES4t5lQtJgo$Gs@g=U6&Tz5 z%=5v`sab!lrc;`PrQDWH9zkYFBFfCe_8!hKk{5dANW7fGj!=i5?`pLn+qhmgBB*CT z-cJ}*-IYo{IlJJo`Y~Rc`>{Q$ZELRN#&5+VrS4t)_`;jm`03y9c4Fy=e)I2VtmJuM zghx*cNDmo1;2M5ict+*RHH$3YDx7T=GXCNsBW6Nin>VdLURP`r5tRpDx>;~$nYQNy zD6Ys^ZH*+Y(E!8+CfT}E`Zg-}uPg}b-roO5^T0+T78cw)!sGGdc5|^i!np9wohQcE zYhU)l3v{mPt6q%z4VzO(*rn-m>N8}|H5_!OmMMK?IZ!=KbxQ6$U6{U_YhzKKIzK<0 zk1l!8XZfWLm#U&KK~hn}Z|+7l(QPJC_Tjf;E0q6Hw`ih~)o}6QpVN-E6dq&rY+x&r=0#~(8@BogF8Lm|I@4Qm z&=|0?1Aroy<2ZSyz&XccyKDgn_-kp0xXN#Lgx3J}wc=&X(Tz7||0^jK^195Mm*WMR zYSL!^VQhp|(6x8v{pQe1UJt?o&Y9-s^ehT5GO3e{;^?B<0KGn6X4H1FfF}SjZqQas+&tJRAJZ zlzfVx{R$Kl2eNLbmc&;o_w+$`g8dU7CypGlRvy_$bUrL*Br!vR+{DTh`X@8nmNLIz zX8KdIP*pNTI3>ySaD9^b*#Lw08*~_g7aFpDbKenA5%1h^>t;rt`NP&l!#xt3-+dA- z@B^@q=;7D~jO3kR_NP^onS({F-*M#FG(_khzUXh5qC(}?=g$y$51AQKqlqPDA0MGcwaHsGf4a}$Wa1AzOTGkO*V@0 zwdP4f+vxJq*Qk}9b&!&Kxo8!dIQYpp+jXB&U}pNqvo1|&m0#xh9kG4O0$~o*bLX#q zPVccDh+y%hd{qbhntTu^L>&~^5Bh-2;nr^?XI(iQ{c(+LBKnOPRL(9Cf950!K2%r? zuxT>k7%i<+p&H1g@MOo9>+`++TplX#U7Et1+CX=e!k@DXy3v%-`mh9IQHhu2V%;dw z;QdQ4}-!T-$vfjFmu)GZbd{%RP1?nT05Mx;>-Me2zFjY*`=I`+fJYNCTl7?|edA^9U#+ zpG@gF)qsL7HOhAqj|k9~Y>X-072nFiIVi7OlJpO*f{F!~WJ*(z3##Z|O`&$|_>M#V zBq=*J)tZ+!wWMa$e-qDeg1M$$b5lhypI()6|ngu6LWkCCo%YyL3t^jAyvB zty;XZ#ie>mB+FjUIxptHT!5GkAgIJlUm3vEU&2^WTxJUY&uRp6Cx|D@ZcP0!TDHl$ z2srh~cWd{eY9qXAl&5}Mrxx@3t|>oHIX1JgF{CWS|BB#Q6Ezzg$NHL`{R* z+S(KgBzbT^*ep9l%`RFhUtyW?8IGX$ntAps69ft+&~qkn**I(6qE$t%O|6Stkoghj zBQ$4AbxrO}M!||4q1D&+(alki-%igNi~E+6#}draX_iY*W=Ig#XS|Tz_14|7o*fh9D$3JO2 zINs3w7M%1oa;i#$?qUIQD#~a4NZ;Oea+;&}t*?{hHex$Sz&2y6+#WL^rD z$zvXrkaa6_0ir(D_@pN!-Mu>TBnHEN8mP|ILanC5$i}TjLm+%N9^i$ZVzGoc6z%K-Aq^3NZW=Y$*v z#ZCu}dcKsRs77apDEYO^`L6nxq4GBm$LE0C_)5lpVqIm zVP2OIY^|E%9T8V3^7-$!S+s#SU(eo}+&Z2hEbh*dfR1prUb+i2H7#P_E&vaPqinm` ziC~!s@yyJ)plWvT=I*5WE7{okEV+ShdhjeVzH_ zTaIEVHybzeBh{Nz{r_ftI3S^E!GmvA0%gn(ST&0xKjbi(j1l>K?DP4uF9u@>{flU1 z@TJsO(ZA{ibh7!_L5m0HO{q@C;bXP9#kthc{tl)ep!kv7bDbODMY?FuMT<8c`bH1U zkxl%YBGgR1%&?(Ez;~^c`XM6b)4CVeG9sYHY>;^=V$HAXj74ItqoJBrr0(fj{`P{~ zms)u{@81<8LxPX-^geZ$LG; z^nl~KHa>DT5q3acf`aPZu4Jc#9MD~idX5f&Lg)kZn-kXK9W@ke>2Km^v->$w(@P5*!=G*-qsU1& zPXl&aFy;u$jYI21rIqcKpip_czDtQLvw|{M{@DkQNI=AA2RQ=0&{iNjY@xeKvNYH_ zu-FTMRYR->cp(y^#Ck&vS7|%j_^(`m4{hQC%PQ}5WMc6uyzAcrT$dZhFBfk&(hW_5j_(TL5F5c3TamW<+8Ef%!V=CvI z8diiQTN4Nx@bBs>HUT3soCGBO@T@V(!?;jk=hv{9xcIyXkh|!aP6W6 z$&-A-u!t|fy0wBy1#I3psZTrs0mfz+`K&#a$xbHr5sU!S$Lm&k-V0DuP>_~eC;vrF zvGDkvei*D$Z5l`TgFcFC39Lw~l>b;%D8^dYt20AFKFbf1;=M}E-~HwsXfwTp8K zB@DA-Ap_aw(cBzKhlCu%(u5ofLB$(WekyB4wJd3UMmi`dheF_)v~Njl%GA8e__w-4 zV?Z9|e?yXuv`%3DqdxOl7JYm0$}7*EC;-+q8^qv>G%Tyu9UGkM_;>W5C$xdM*LN5} zx%;t*ZNl=lzOuvLhg}%40b~4x>$h>8%pT%Qs_R0$w3|ee zYF7}_k1=RdZ8 z8%GodJU#g_LHoq#TJw%#ib{SduGm?~D;=m=&||boAzyZvv;RGY$G73dG>#gs%!X=VU)S=ggke+(DG8C^6oHFw z1mni_lD`|+P-0HuLW3Q_-Geh;_VRg_Qq-hi2UvI}!&WEgEBknW9&Gv)bL!`_=mzT` zGRC$-R`g6nQG-RBp}o0L4b4l(bLyAGqtN`3@LlBeU{S$|AK~WjOfd1BSXTCFfVFd239|rW9jG3R|p!n{tN*${WL}af!lMXL@BL5Stkm4 zOK1NP^quEhW#P5#k8C_A&GIVuRY>CWalfmm;2z50A^Bciur{oK3=h_KWqg$7XV? zb=@?;dt>kD$e`1Ym3(Y92QT(b9CFn_$$bPlrb8#=MFtjbkZ{;TUJI#&*Bs-;heUnp z3@cO{c_FAB2O& zmg4M2`=!>HFYn5~#AixSTAiBg1c|;WlYJ=4`l6<>iBh7ya9;3R8&&q7N^{R|Ii2e_ zgw&ue-MU*@hl9IhLI$jYSJeM4M&UG@rs?5I(;ZXIQbRl!L;GO!{&}%Jz zlbeXcl9!wmV+~4J-sk&RA7b-VHxTWARw0?*wBjkY&e{DRQVP>*A6)zD2M=LM0kfHZ z=jPM(bjsLs7l%U3=znCp%rh#5P^5I-t@WGjO*lPZieW@L>Iu6%UObOl(Nxb>2mmEaET7o{ z3C5qqsydiuP+&V-VPcbJI08#S#pZqvsOb(}lurl;2)^hle-@?!Eef!rFd!6@G90I~b)44nCTD5OsQ5bM)Lh%D8gT62dQoVrP|2o=#MRt^0ZX&UTt#1*LFljbO3C zmGwMwD^2fXBKA8kH|en<7TpSZ%_!}%jdxy5G507iWH8hFn&cXt7=H(%#g??X@JZR2 z&5uglJ6vSSup5Kp?NyS+?pTEif%%NOD!WlN2H>G_YQz9tH7WqHtj=aI3oteKH!9pM za{l7vVgpRpA{(G^=95a_Gt)##RaI<&Uxa{g_*&Cpt2F%nYs;cfsM+8jt!V?r1$yRU zb6_IYA&ter$Jtt2GSGuf54ZPi&c=GB+#h2Z5D?B8_eH==9cCD!n$O3r7Z14#`41|a z!cY1a?MekUFj{3DrI!`|!DX`#=TViXCTzp?%8y243u$yBTX&xA>nmBMJJlLJWzFf6 zJ3B3|z6HhEww%0;!ixZMD6WnlTAik49qus z-25&}?UzV?)jmSqqSE$7A(kyp&^K z9U9~kMZF;QHppbBobAy}JJVtC##42RB4^7NCgaU7XPF`^`p?Y=Pn-qLPASXW4@f7> zX@oy(v9|$cQOyzt?|hZ^LX(HwmRaSE3h4sJmy`WwZ?<0<;N&*ddm;1Gl9Q|Fefre= zo7N#TvW@bfEn?L*s?t4#>i3j=VI_ZJn^V`2kyZiXdC@9lytD9CX}(^wKrlw{dtmS2 z`*|oQGr&c*z4l-~=4Dp$KFWoVadF8e*szv`kSEv#CUmjFz1+43Op&1H-q4H=fj|2q zuiY;pKsCgyZMJG!DNkK?KT^@<<*=8IsZ+%YZ`5s<_q&VG5`kUqHnF?^ovlQ^v&?s9 zUfZ0(+r*zWyo1_=j%=%%7Jtzvdb6HS=_|k=*^_J}5t<+gyu}0dMeoiEJ-!gjDc=e!PrncHG;Cj*_dv@p>z?n1=fXmxmjXTR&2+ichYFliIM$ z3|ewsnrWhiLJ{bJAeu3wsj+E$7$2K@PfD{udyutNibDJu#NCU!j3}8=WMn0war|T` z+lrFDLzSSzv2KGC10Zq>8T!me2ReW-tA2Ulv-vLMP1c>ccAbsmxmzd$p+U`9&g)rv zN%(PW*!s~7E5h}&wcU4EJK&3fw{VJ4S7~tAy0~{Zz7`Y8AAJBKS<7`jL~PS`PlxA5 zNKFb+y9k&y5pLqr?(D)XWdPG#c72L@uWRvhDl53h9icjpg6ESv4MG9V|5!PyNtMqP84Oj$R3Bk*TbO z1B!t-h9-5o{Am&<2W>=Ky#CaQN*_&Rm+hh>woB0`EmI+fy)^7uziEq?7c>EfxL+WH zXkF|ms<-@uW)VqGU#l$@@h+Zv9JRVtSq)Bd{-8ypt*J0zbk(KxcW-Eadq+^5nX8L3AuT0|0(l0Nr= ze&VJvn8XsU^~~|E_yF?%BM#eDZL~0~1C1Nv!I2X~AyWql2&Yl74wsQ}<)P=Kv(*>3 zS4o^1@-dO!fWBCpT*MLX;-WuMcpYn=Y_d2TKL^eJhT4`bccIh6B&Jdazk84)a`l;j zIx*MFMsfkjp>#(uPr|!`%T1wnQy`a`*_^1Q0FB$2rLDn*4-Zh@KR`()3J5~Nl7haj zR)JT)wWNc?rG~R+lsuln35mq-KD8WGZ8G%fUR>#p+DaC-%{EQN9&f9)?$w@Mu2aPE z&y!@mbIsE!9YW^Z(?r*IqadtBtBs^8cOFI+Vyp7rjY40Vuo&o^9>L`Op>@4FaGqPw zBIbr+>ujmgt$Nt{ewq*y^Q*(znO4l#ZxL<9K1ta+b(nn&GW&L7Vj=z*HoA3+d%_C+ zpJ!G)H5bT46>*UpX*(Uhe+=w-C?Rm>|d$|JrY5|A9iIkU_0ll zj&lxUg53eTjIqHUjAhnu#myf|j>D0@VUs$zaXWm^Wbb=+aT2Rp|2(oWDx`d$b%~+g zg-$ZO+2{kmzH5CwKOuZR(ca$P)Yj3#g8oo4FQw?M;7UdXFEW%k8l8l%;~DbMf~Np;|)7lKJaWfh^5b2wS!H)^J8B1KQTA@3KKIUUo^fwX{11acHmr%6Q}F)V?vX zP#6vRXqJX&*yY7O*{$$fW&!(GYzPMhkQI4(hRz1(nGEK5!D_wR7WS&(T}`$q_z={n z=nb>T@Upkxzf;K~I-=YjW~RMFLF)aj64{nT&^5?V~%VOyFKZo)bR%QDZUu>0#^+-}c*TSBkW8#%O7kHNQj_wgT?B$>WoFk!+f6q=db-P!^U%$8K zg8N9pXJP_dn41s0e|S%lScMsOfZ&=&J)nAG76rI4{z!ltP8q%#=`<1ugPREU&JB8E zB$W4(&#}QH;b{sNjDxQtjd_o^tpF3gFy zQDr@YW*hkm?X)oM)MsWk2L2?1%dK!bmyvB?F4};gPv)pS7HD2LRM%W0Aj7Fdbs8K47}WC zfa;Nu*(LoiZv*OpIs*(rHj0%zPY1`w1eD?c*8{uE|Kgn`U~?=%ysqP@#ALF5k*L*r zGuX`eQbX-NiqZuf0$5LU+n1J%t`@tyL(E~Dn_2}$h6Boo?-Vwi@s4U4908uN?9dFDM{z+wTZrt2;VgW15|3kWM_2J&v;0qF0U= zlAHdR02(0@6pR>jHgX^xFXa>rh>(!`Nov#;F|T|iLc#6&C9ffl=oh&3>7kJO8Tn%C zjX&r#mZK1m_GTehU?Sf!{DasjB{`k0Fbgnm;SfrMPcIFZ4e+^=F-FQTR>o(@a^&6D ze(kh%-yPBc;~nWTBjXKZu$)v=!Vel9a_S8;RO;+r^(Jv;exNa9oGjCzYI%Z0Ydc3Z zc_%F;RbjdVU!qruaK8vevR`WM!IBWkHr;q@+7bZzHWe%~P50%A#6n%L=PxOwK}HB& zjQ!7C@r#2+P>Tzdnzs2_;|WC+^9%hcu2JEVKn2W}sQ2&7`)-}J>-lZqu`0vN`)$r+ zmH4TJAap%(6ag5!+D|<(Me|=^0oK-KVPj@M9wPZ&N@dm=g3ox%1CMu4&a%f04ff(H zSJ>q+1=ogX`&!Y1*{)8)*0K!vb|)$D%7 z82Csv`LoK3w=nnJ=%PX*Z$tm~vvIenYq4Z*>qOcIVKo&lc}Ke&i}1r_Q`}#XZ$Ufg zGji@nMCFUPUfL0ZDVtB7%FzliWnyhelxr=8aSp#TcK7$gRsl6oSceI{ajM)iFZw=< zas`Gg&(B+9128LgYc#|3tRg_j@8GfbCWmao>(a^K`5K#O3TUe8S4Ee}B7LfhiwmK< zOO%pVt;iCV!?6ot(9j@h*1Y?pr-oAI=_O~S8lwcYuCDbg2y1y!o8eTC89Tq5ZG{M> zJT3pBzu$!4(&!?YWJgJS)k_~!sXm$bXc30(tywXFMaG?2X;Q{5V zMI|8!_Jt(;TlfUa@}8<1QT}k5jZ8bU1Z=+hy(nG=RAS|$&R*lkb`r>!_g>jU=LVy$ z$FK7DsP&k=6=-2~9YXHMiKAnBy--id&MVGF2XT#}arXJMt9lI#l>+ zcBnWWtvz%v7PTj2aJr+rw35_nc|nv}jk$?7H>33|?&R8)=DL<>)xIXhrNSw_tp|&~ zH-;p%e@#AW=%qb6Ij`c55w#`a?Ck9FZB3Ixvg+KM;96;<3)6vMo^6IIzhdq3ycr%q zposX$$y~B%@~h*)Z;BXV&@DR%>a);&%^Mq_*S+L#t@AN@?uo~#*{}7_q}DT~hM1Nw zGQ0Yn1>f^~VYaNsr`sF0g`(!6(t3^j0{ z43C+=$axhq@cZ0cuGZYBM$We6WIo@GoLmxq1*YoGVYb#3OxsNLjt(cl1TJO#JFP~y zO3r*;=Iu(}>=8)=ip+@$JbNZT!lP3Q!Q|B>E}Fu<-?4&+i+-tVUK94SUj6$vj&BB^ zA9GV&V3*osCzan}l{UrTnpUR?u8McgE4^u*Df?XAk6^qQbS}n!0TgFA3)p28CYF|Q zsR5%O0OcIU&=f0vC&33AuY=!h5Ee5)96F0icB^f2e!U;bP14%`e45sSk1hN6NKOTQNr+gL_hyP!skRN8i$Zv$$KWJOzC0E+VTTj>?mezM|x2#?rWC; z)8y2pl%#IN=GYN3vx!+Ln z*!M1*hq2P%cw8&!$Qc`)ALuX-QD=^1doG?)DZkbvTu3hQDitJ1kYf{~8-G*t8IDs071yPbl$*}+Ed6KA?seQ zHAL@*;#VEnFzJ+Rn99OYZx@MTCer0YwGv4I%_6;r)`FqFDe|fNLEd+(SJk@QZitu% zOMn40Q}UWP%zm!R)&QPzvOFnyhACbvl-vurs2|zWG^B46FV~&APf?auBwsap82PAZ z4T!8xbHL7`Je1O`zc8EgyRxIA`G7R35{`J z+h7chT6d{v?qO+GsbP#0v1noS^h#B@p5~)fN^#H7#x_si!R9GHm(L!}X6G`wZqJJ^ zjSqQFD|`-lT6(`CDqt-KrTU;#jso=o*0miBd~kVJF;0?GZB56n*Q#Remk80%)_iF* z?@X_rIkKN>b{blv+hj$=il$ccO~WqFLBGB2#d{H#6otFIwle%z4>OzbJ|R6zJo%~- z{;yns%h7bP5ZTk$CYj6~j57%wgQGvkM!o7+8>|%)Le|Z-D{nn%s8uUJ9eoyo%L&D3 zPYY@NP3r=n2@R&WtSo02SW8^$X&nkg$p-x*? z&$K3VV1>`mB21XCz&N>%sYfL_Ha2~M#+HROiKRr>)E$e$7MU`Z1`Y#uTs{4#ji$>G z;C3kf#Nz~dWkU;s{C#tQmze0`r2&zEaGUs3W-2g zpmInNv-z~V?~9MWIqm#Q0ozskdBT_q=lRz|c-Bp_y80GOCWR2uv1%m3;mnYir%5@W zi5TfI)Oj~FeuGTy76a8YmKJmmG=c`sx*XBVVOs3ayYC>B>t+JloeoRL+zx1%e>D_m$%c21+XnFSAX124@5U!dJ z=C5_Z!zlrmDMXe5IyX1B(z9Sm`eT?^rtZ}g;9hxk)Gc3*D2{5O;)-yL*{3o1FEj)1UTCz4l0$pRd$ zwOe%0d*$7kFG^vAAG(ZwKGQQRdD(y-7EGb}1F`0V4)S-_T~vc<3o2X)CCuXyhgr7& zx=P~Pf5+S$ZJli_U6d8yl8{UVvOHAnVBvxibo^fM!b*($5*ogj9~PHk7C5RH16Na= zh%10&pjx6A#>^M%B94x8auuZX?toJ?L!8Qg$@Bi}46$u`6yZQj_m7sCj4(XdlJ^&e zIZxLQhfp*ubChqm*>ZjqsI)i8d8`km6Uo0YP`lonZ+Xa(QvXHqTrW~Gh5G4i98Va= zNf&u03$c*-<0ns$Ry(fv-Yiw|=+*9ox88-lA+PZ+*WOTnGnp&=noHN@$by>hLr`E~ z7byj|@1BE+^}GKPMdD@i=vwwYGH69EH*9S;ReMvK0T(jOY49YDlpu-@bh(h~YkA;x zv#!WKp;7;|g;kNKG5mAeiBBT2Vb!~rd2u`>?e0qctM<)edUnzOAxMQ~(A?n8 z)vV*WvZH{A=^Q(0e)R8vB7#V>>n9TIhBX|DR7N{LZnSO(l0@0c79ct;A6u)OA<(T0 zuIb|CUjcNMV_phxOvtr)}6R(d$d#lQ0%$Qk+jIHMIV|{4ggWFZ0{74YFOd<>D+M2 zmfKOhR|=n7@brwlVXiP)V6EJuW^kSz%wc1VSbay)1S0C5Wu9Tv*E5K-EoQ|Pj?BTJ zBAGS|k~

      tG~RRZ0NmEqIH`XHCd<$pTwCaJ@-vwx%r4kg|;MbR-qjq=9~x8ZvA^x z!}hfhysti{@!7{b&u)%xeXRu3G8?7W=z$vFUrF5>Fm)~M&vK$xGCYeX#-bE|x@(s+ zd6y?~w7T=~gTxB~AuX!{bLiVtE>p>>xVIcJm*{=BEe=*_4*DpHbL!2EYjyNY!)TV#d&@>~W zOG~8&14~EQe2G#z!~0Ri))-4mr`OE|29%s1A9U9xfWOqZJ<7?62aH|TFYxK_UHnFI`)&ceWzX_KIC^ZD|Jy78Ha&Zaf7wq(HQRWs3__n<^gnh`G_AwID#o`% zeu4OPlIuWx*UsQY?l{EZnOx>3vtjz&7fFa3TVA!fSbL{L@QI)ooNVFOH6#CvB(Y%`8(GwmQo5 zd<^=t{VqSfS**_&SCap|dw5vhyt%q+I{AeBIm~&0srg;vJZdX;{a7rzFDE+FuWzWm z`lEkyq)xMhEb>}Rv*Rnp(i@|Lhw2$y(*-A66caG)q9mm3{-`x{#-po2qK}1(Jc@?~ z2EOgdtQJn>zxHyvu+?sTAP^F0S}nX;Fepnkcr)dwrQhmG#5in7z~X8!t%-56H%(re zGCA#aul1{Ot-DyzGY(B+`EUX4y$tfNp2v$pF5#gkE(#LgdjRTCuF+&?O_y-2q>fM^2_+M~z!%VubuJjdO6E z;KAs4Fkr53^)Pj&{Fq@qYNWu*+M0;Xw;tsD1%4|Xt9fR>1kx4DII0N8dO(o*r0NAce34n0XNxcKgF#O-&5J4rQA#h2I=`FrdlpXxM`Ljyvee>Ms zIE;ZHbSD}DX_90*)+qxmcWFVNJ@N%7lfx+bg(?O#(+h+b3%zf4u702EPuk5P9ZGml zdQg7Gcw!l!q`o(dA9HD}p}I~ETShP(p_~OmBHFtVwM7$^yE9kydJwMnjO5+EokQD~ zFI)9E4q98s5x7ip0C90S7>$KNc+AiqLaQ=qU_5_owjqy# z&){Oq`lFXP*r1cxz8l0WP)?%N!zIt~wyIUgEX!bp-CzK7OW4#g@=9HVwU+y(T@V6_ z<|mACS+esR^#`uD{E`Le%Q6B2x+2cpsO$Z&A%Qq@Rog}Vs!p_E8PNfm@#9j5fwL(Y zHW#mbo}kBq@$&(xAYVR;v+tjUP7bdgPVvN5{DM+E1oUFE3a{kd~K z$Cj!iq2Y2FwdN_Y;IEf_^Wycj{#{eQCr(g{t#g;R(5iVcr6yrmeF|T zxT$IwBDxnB4i^tr(!VZU_<;Uu9kcE^1ECr>IGbSQK%UY-B^{dfIg_oFXFbn5VVVV8 zBH*+yen{^M5a|kC;5cwxY!eIp$JYRR3P;rfnjsJX(eIx!Fo#BFJ6SWP{vael`(vsq zfsd?hR61#ZuUZ01Xd~}0G5qT%BQ>|?WI|FVHQ9R4jtjE>SJ7J!W-)lrW{H%Q_J*P9`*F)@Il@L)r&QxhYChxr8}1eU)Xwu)d+X^euPxq4W+?`)FF9x+0* z%Ze|bc670De+0dg5BA1*Dp)=yWiP(wxi*-DE$cs$z!x>bqbnu97{syik(dre7YR)E z@nss7glD)^10T$0nEiGqdAq>uCI`Pn1LT(kHg)k`3^F4SBmx41VE!5G#QlmEIbHOdWI$jD z&%5<{NR!$@G!W|vDR^pXxP71t`q}=%(y3WN#4=sPk|WkGlY(uvJUZucc?W>XX>tl$ z14P{)$Hmqbo*q+@AI5$pqlJrtf!d~Vu>oL1gOJeYw!cC`0T3k+<2b&wY2f>_&pt`o zSV9NfmzsUTSnb4Mhb+UbOoWYt@fv!rf}Q1_>yX`(!|$)%=+VOwN`5UC-bhX`lmlLx#;b&Ple~wbKVPo=4jgj~VMoES;;j-=<}4 zb$}VeK~BztkSP_s<2vGuBpO1roC!VJ-i;ZjYj!+1TY`Wb!+%2F zP|w-CBS9zK^SscYK-|*7j!&j|J)FsRM zd+yLstbCgVP6(@w-;2GpK@HkJ(Wr2fKPaikE%GDhyWq5jQ(9f*)|M8;EQRq^cjz9A z92Qyl>6S{T<)Zpyt7%0a)O|gH9?W~?Ld`spw^OB9US3{l&>IA85OB||e%*T@?brF8 zCUL?KLd``}rJ{X3{dEgfUsUuLe&F$htTRaW|YdDhXWD z7AoFtAhwvIF8yrLAcK^i%kESW1aAWm@>fe!t+ej7*?mSj^UFr|TQ@2-!zE6kR?jQm z3BBt47hUK6#RJfF@t+Fq#9-t9ZLIyJ)WFZoQjsyC!4uu5 zy&_BHQZ6b0-^!}`bM_}ME-s=Ceap zqx;h^ylv|3^!EW5DCuRCqgklQ31pnsd7A8DShV^zQQv1c0RaIazkN7ey%M#oeNH@9O%O>qkaxUnQzY$mdLbrYCmQ`SN^tq^ z28))D<=v=&0LqGX6K&%+7irJlZ~1z$r+?sqpTH{JMHUtH`i1Vz*}REomG+_rwcA0~ zyf35an#*?}nZ!V}wga(EOSi>Wv}n4pbo_F~4@;Ha{MWCndfFZP{-lWG*HSZONAFrq7jYw{Gsmo|0XTyI2}pl+!l9D>UCvC#Y(Cl&*z~z1f)?NOWK4I`gCE@<~2oN=0HW3HALHX&UX;D;kN3$V*^UcxIgrTGp9wVybYySre!I|#Xk$=J z?5-8d0<_NhTNlHX9-Vq63*XQZLkjigSnAa4IhL206w*bMbDD9TEYsFC)}H0$CMZ07ro${{!utyH9tH zhi$#@U$*G`^wRk>_F+{!vHoNd=?5!#4&t&XP?jjl(GmBhWR3(m?#^<7L~9w=lgssJW$Pi zPA=(+t=ih+Qz`qZcGp*-A~Z7Om(0p@tmXr04C=@~`9zpQ)(*r71f+0Mn&bWnIHSGL z{|DeKO(=KzPrR9nbHV$6#+$oe%y4wfv5KNdcP|BGh*i9SvJa)Sk;kOgj)h-l>IlcQ1{bd`0Z-_$wfS3jYb1%BD+Bn28W;YwIvF zw@fR1=7hr}r-2aBy8E!GnZxfqK8W>hb`RV5TXid4(cVtGP9sZeQI|<((a!p<@3~1o zp^Ge2t>$t`e%;J84;fe7ZELBnv6uzQ54_!3fpH)s~xi zSVp^iVV0|cw`oNMoPS=~(`9H&lb%?N3yRZ4bU(59tP*||*@MF@v&W$}dTodXBHzO4 zp|Mn=>Aw(xP42m3Y6)_CAaXDpa$lx_3TEt$#Yv98-ItZK zNB%TK98LSk>GzXa=j1r`W=6M*A>AhKZ`mGQu4jizQfbQmRULA)rlQU(A|hv`#qMIk zB%I+=)~h<(mn*i!9jQ-)TRE$P36)Rfj%hu_-+zcK_?{VzKV3 zwX~Qw3E4+uuyM5}7zKBAuT@sg^8SRfM=K4ze7J)Y$ELzwjQG zfy>-B+Z@JW9sg9MPn@RDWqMP60 z-|v>2ym1U$yaT!cq19+!z@no;qdO%(E1~=*`%A~|u1B-;OgfwIGdeJSYpF$!ht&BT zEj3fN)!61k@XJA@cvh$4ga5yhyX1jyqXvTo)Ox#(VVNl)`w958a(CKy#!2ifv36L4 zxDys1EJuy9d$=egWp0x0Z9eeWkXg;Pwy8v+n^2kef24F~bYCqv12*#G9U%n4d!oXN zYc0wr-S&wyWt;~m9!}=pQy$UPgwE$3y1zn&P!TFqgf}<%YF~PQQ=hf*-JQxaQ3F@3 zq0C=Y3{j+8qC;L4b|pUnK196?mL+Zbzdmd5Og3@l)`WnB3UV7CVgyI)!P zHV-3sQNA4x2j*)tz)}?c8LHP6h69-tJdn7n?ZrwSUu!KRE>hmp+Shnkpl}hlcq?uU zTUQHjU&0B|Cp1`_Iw@q1H9Rg~g>09G*AkEV@tTmShhU48>ZWj$U*+^u12Lv>Q#+7$ zQ1V2$n)zjiYwa@}hf_@7{l`Pwb9psIA3Go>3ukCTQuY9Uy>hRvrPP z?0lzB>NQ_}bT4oZ>Y4WN10@iFCl&303-4TKm=QT<^E^Rz(tJhm^Gne;v$|({Ka9*o zY*)*h??+O_Fq8;Ky6@VX6qsaQ!u&N-Zgdn|+-w&9xtGnkZ6$SF2W@@#>}?02b_PIt46(oi zYAXW`qwRD1>j`kU6Y*59?ncrlvGQ6iDitd=Q<=$*U9Nl*FoPVy(p>L9=CfPC)TCeJ zE=CZ3fh^U5(yadA(;5ion1NUWV-{D7+Xk*tcTn9e16AL~rC&r`inuRnZVAmy;{CVV zJiuO0>_y_p6C$;iaDPIvHg> zu2ZSub-!N;I;k89R)0%igoj+dR4{6|{40-)^rkP71Mf8&S~zKp*NQd%B4!G%Qz2GG zE#nQt^TGu()yQ_7)Y6K&?YS~I#^IL~8{S2UxyH9GE@T}`uI|84T-@_$I2w$X4@@mX}+(+T5VSR9ThjotuWNQ zW>EQvoIW=xzcp>QWJ4v>Q^xC}TUj@DsQGBCwXJN=5_KM_CBPX5z+U0Lm#|lS)4C!{ zMAE%fPvE!I>>I;HW0Wn*cz#n`>#7h>A2D)=u@Bk#!K5&cYLI$M;}D6@lC!6BtfO zy_(EFgevTY7%pmzw^_11b}7#1@%yn9y4oY**4oM94J|K9-L#&tqb&-w7eiE0E1`O; z%@TogCxY6xGzKyMUWb~!och|MVLO)1iT#ubi@R}I|6TEk&!4I105`OzeOs!XMO^l( z@yn@WTsk)eg=o|6ucfiriGq5A!5$H;7YU3UWedLK7JiX!B01*rc(Ali(=TZNZ2h;_ z*6xH{h+59^nFm=Gb$wFUVbnx?_GX4;y+7lTHBs!O$bp|5CAIY@bVZZe@cp5X-R&{! z5|M|3nuduaEm>E9_}}Dnn~8d9n*0s}w8mjh5}zwxes^x|b%|sc;RuAs_P4^J;Jy(4 z%)OfqUAYh{QlvdjhzbsAI)nplcwav^LAQ)g72xRLs28G#rSX!R>Tvm7t$Os)S~b>| z{B&vuwu(U$*)J~UZDC-XPI-7|cSWc*%UGq~RMVk!5yCcyY|8GxX9c!PC<3&|E~HTN zYWw4j<3NYj@783t(MYjr7#t~#ldAWLcrbuChXSuM=xn|8kFn+X^-@=u+V(9H&LMuc zrS6jJVH=Z!)j^(<&zPIg_2rvKFW3WEKY32>i*(Ipr6USVNLQboH#rQoQb?h%RI@Hd1m^rR?*GBsTYyEm zb^XJFpoEm9NQ#QIfOHB1ilj)lG)PGIfTSRyfHa77cgG;9NY?-Z42X1h4e;$j&w0-C zJn!}X|JV0@mveFMqr-jgd+)W^`mNuJZGRKY4Kd)PtK+q+Q2_qKqK)JTu|z@x&L(C@tah;%da5vRK;q7bGwV|j@F z{vC;13W*(PET#lf*E%ciYXi�msP_r9z+Rn&{&6l6H}FRB+O?nBHM_F*uXlIXqOq zR$CJno_Vfphk@G1R{&Bc1^;a`L+z&BWqVsNqybbssv>yI7qv+WLVQSGk+UK~$TU^d?FDQUt`8G-F$Sbspc3e{*+Uzh%K~zzV`#B z-jw!djoC?QGfJz_RS<~-B=190w&~#N&FOqt36Xb;jT1|n%Ie8|(j-;REt-N&)s}NG z22LrEA|Ur+z5%to;;7|KLN@|(7R-$bF>&wdfM_#_R-`na63`B;9DdM%8owXa&~Nm{ zWts@A>VK~hUz^Ak&^X|s(!*l?;8nf#q%%eOeYUUX@Qx0b+B!9dEW@iuB zcXdUBHHAyu_uyP>_zfp2D5`==$;^FcFAA=228&@#IMasVs@oWXpdblTq>7Qz;Qch? z9z@GKXqqh}$#|LB0sH$8H>Sq!u$24A$mzVlnrMp3uwO!DiGxIFaIJzwM{72Podyd8h=p zBk{!D<`p-FpUkhL3Rv0^ABf|Rt!~C8fuf4$JE)Lpuo2gTZyP+Ib_gkR90 zpNi@U`X>c2kC~}-bEuT=5Mce&x86LwjCg3H|B2SFoH@PLq!sbDqOv`_?QK+g?;HfJ zRCN?U-Gv4!Iz#qG?i%LtzbBMm>-qZluE8?U1X?H93H;|J4Wz`1-OEp#3VcIETLIe{<$o5lGVK zza(c;5u^jGOi5{}GL+BhC+(5ZumP*yY!Eo#o05v*x)#bs-QH=im?q?ih)KMIhI_Xe z8pgWSPr(I{M?!OmQ`*l>BKq?Qct8krv_J0H3NO1`1VAExRISSYed_nOiT^LD-*gs( z#{8~p4TLh>OHPmfxG|rf^AWs98hz~0_y`e0+CXgF}{Us>NJ zHa$3wo0DWljB+xay&Ee`(l?ePOhOlah7oqTY>4@So@sfA)AmX-1uCKUK5)fIVJRFx zqhI2yKxAQcy>MCQ+jkD)`(+QhtpARFwvnJQohu|&${L^dmI`jWw6(SKmsnhTkts)` z;wr#_+Qo5rXjWv9RO}CY5NDZrRx);NT=MFYpIIPH^7E6lwU9{nlR+`r)OCqHYmPRA zCC{qCydWe@vF-hB?i(NzpDez78YGKF4?@LzZ^$mJ99y}3cxX80aFTY_gVUsiV(;cS z6!fegT-9;~2{bsrzWKb&RhgR{5u)T|)qHsU?6fX)--POFWe5}vR%9TK*!UL3C)OdK zl3VHwYNG89_MRmPyIj>QU+iaLA3t8$x5`nuvr~DdThb96V>-UMC#T<%y9{Ega4t{x(%QZFwRoooo zZ*~W&v~s$9u@~jD|Mh8-6u);)#uj~>ca}zDPN*WgPk&~kv2zS+;r>1Z%34Q>D89Q9 zfx#MtDnJ_>AD=UwakwiR{d8_751W1`xEcYcZcne)p+W$pCM z)(e`?Pp7*>a@>!8-J2K5_SB4K{pkfseq1DcEa$A8^MA!o=Fg_s+Zctkjvp>Rm3{M<6uJcdBFw zQ-qB~d95`Vq5?`y=M+p*7=j2szd56%;B^;y4i;gYY`7iMTrb*D2ASSN8P<(10^y^jZ@Fftc8klgCnM`w@enW~2}M zWr?%%wYsW|?;mrmDei2iOQ*_}hU+kp}&y;fQon8`pLj!PxmMNP?y{`vw*l^E=!qZgvkeqJ< z2N%DdiIcEI;>F~RHc!~T&EY&@TE(9vDZHRN8cuar_9TDh%V>EXpXO{5CpJnudqbX$b!3J|ij#I9*bMsAS0p zFx-PBq*w_3d*`1XsFJ}CsNOwN{h#=4d9pjt|DE3c%9XowUR$1BVm{5fMl3b<%e~Cx zSm5@F8-cp83!X(;WKuWtCw&eK4Cc|BqAH9A!zE~O<^Afq848I<9xJ~%A2}BNJG-q} zmG{q*_)0Qkm1CBmK4eU3&2V0D>0EZ2QS8RjPYf^sl_w; zMI}u;ik2{=f+(;NR)t+Q5-^_5+y>6;&WqocH~8rc2;@(CY*9p{UYlL7CwRIZi5|W@ z*t{*XZSa8Wl~Gxv+o_)B>2i5&WPGbwmXkOrOQElAoK@{~dZ+IFYkwe$PS_nu^_W8+ zJHkjiIbAz(Ls$LRi%V4c1dIg;|98P<{B6=g~Z6{_E&1)gUR zmYF#!;dD-UoX`(??C3GD-91>FxMmSS2TOq(^XS~>9dKfyJTo?|&>UiHvHd~wl4QJ% zi$!3o7h2=Ei}vx|YqN0>DzMgm)Y5C6$f;PcPG)Ewlk5-dmUthH#v=%sX^(z5XvAyY zcG_2X`+>S}s`SEUEQdZx-~3KY9+vMkK|8Lg$^nI|5WR9qTF31^6G@+ z(pxd8iQsLFFu#J2U`q3aoo&FBic0~s-$3@B@$>5S`Y`=>+$ikLigv6dXuc-ACgdsY zdV$HJS}O@x-|oa{L8liGeB>gXsK1&Z9NByt(QlSRU~|Sn$c3NA#j@H3$(Tvv_Ar&Z zH6lr5BtP}3aN1WYziM_qpYN5xu}gwG{L4*`n=gxB-ZW|uiq|<>5E&b0{C*5nh6~mUIFs|lb$lhH zN-n;QZw9(blc?r1a%t+`M!x;u=yB_CcTteU4j4Z>kr`%m8!_pXM;0Sqetv$+ARBuU z>hkZ|*b>fHXG9!P+1M?EX`v;KSgFS>LXMVjx$WJ3@_5(_s)P7y68VGx(v6Nh9aRi^^4#YN$_|LrgY>?O{-RC_PqJJ532b}U zh4W~4zZK`c7&FS>bj={q53}Bx%QMPm_d|^OA^g>uxS#j%y|h!~G4a|i*4N2@rL@U= zpXe2EE<#V(PG?ritAQVh0oJ7ea1)T?cE3sS zUA_eUHz&i-_+bwsKpw%*rCgS-)l<-^HuOGw&WpxRcOnBXo^+QyPKlf2#sp#Sz@SBO z9e&8Qb!}ehAH389)fa?eDjzpT@^o;*5*~G~VY1v1eH{OeiiG6u=#tO2QIOH;bov9m zviGQ|E+zqG!jsttoS%~C3G`%cY+OgohiuYq}{+TmOFgU;xAi7x5lPo|g*?20UrOnTu z(K0Zk&XYCxUo^Pr>+=81i0U#x@Hdcih9=_ZT z>-o@zkRiB`oE45YNEH^~LPkGhtN0P1NF#<06O8#F?1p19nYRz$3lF*qcnywXl<)KJ zsViF&8q_as$B6aYu38Su*EfdxeM5>=m}Gq=AukxiNex(a(%{=UnG)jduq|A<-QaAZ z?$SVlUUEPt+Na6QI3_LJyaDH@&h^KbDZtnDlRW7alTtMm7k+8SC{@@4-At7{X4dRGJK)3$1DQAyiN|F=ooACFkbBfZ-P z2{g4d{15kH)JST}GulrNH;1KW_wa+S7NDr^d?*IiU#Jj>QbDYEqD{Kp_5>Rm-HL<_ zGwozQO`dmJ@xfW6z{I2cbUty-vBENK7enstX@=8cR_7gYp7=>jTal z!pSloAx?|lJglmlgQgOt6l%~SYu#h556D_nNNL#!RBIqjzdw$5>CU{Kzue5JpMU$w&E(pe zuRQnO!Hn+jgzLHdis1y`-|ILLLKXO(M!;T zQVt!3N2dVl8$wA+XDo+f!wL(jKZ5+4IoJqDU;@oW9IXf8d{QCN%FfwG`7F;4xKY`# zS@*k8R_gB$>)YnKp6d@yS6-wW=?WS>3?b>xg$XODPR!ZILw_#KS=;5o=czMM*X0eWR0e+7|7`xiy+y&LyV`Y9kSONjT#zKh zDkzNbN|jRoJJy8CXU68F6dw8iBcE9ft6;i@0HUB@WavxSl%u7AU6s@N;f!4Fmd{NE zxBZaXr!iF$6?pr{VR-@VUsgyH7z^0j?!O4y??H-qiC%&3pU=TR5-s2|`UE)#ztSD( z%T;1$jTe1dEF!bEhN?UG^&fQyf6B`qqUgk)V@C?0U&P-79?k4M!@_SUU4?Nj_=X6u z{WrIByU8E5_m(ubLTMg@QjE1vq;rw?qSEzFS@jwvADsuz?%JuUST&hO^mfW zsz0RpS{YMfrBqd5jb}Y1wE=6Y<#u0U z{9mnj5Ek{#W^6I_GrEtKtg({%BcMdvh*jJ83fA^3rEHumx!aowxgN z{1DDG?x5c6W3wJsWBGSl2exZEn3BTq<;o3EBixlDhH>5M>9n#NLH+?7x$=c3((s~V z`Dv8k$`{@`jCPL__UJJb1IP=wIn=fT`K5G4sB4xT9nct}nH3ALWUS%7m&J{sb9Bzn zQECpovqI z$N@NAPT7pk_XOzdZY+oL`v`Yk0RvFs`|Sf;`eUmg+P42;2&UrVrx%s+j}6{XptmFV z{rfTjTKJg)+^xCu8x&x;01or`S~$R7ZLh2=2d1%?WbI*r4xfuRBz=X)Z{X`|J^a=^ z2eU=I6KLuB5l}=}r7(7qR(!9zx^W$!SVXPP)Obe>OeCE{ypf6Wvf$|L&Xtiz9{b~+r-mC<@~&nWWIGjNElsM`Wg z-G1U-oW6jiN9rE*$OEnqTlqt8*FaY&K>LIG4_j8>1uk&?Mgm+X87zK5sm;GW3)13R z;*NVqS2^@>2xcC9v`ohN)lyMPWB1g;wrndCuN9OXKAi3(-|3ssdW(VGU+nQ5IZ;yg zm6v#8!RvU1&D~wGJ>Uml`lLf%G*gM)%9SV$k+>U_jF;)H#HdP8iMS-tn5cOTB_H(+ zhT?xe8Z{))0JNWlRlk~ekpt1v8Ic-!rH!2Z7u$JQGlvu2!V3CZCepT$b0v{Zs@`vz8>cP z#i7K1KX!5Qul5UA|Ni*wgDHBx&3C`p`}udJ@MqVOglw=M?(*3jJ2?Ftk6a>) z>XQ=F*()FAqxt7|IOM=HpT#VB5&|Clp?N{FintkA*(KDQ*I_kB%U*A3%d2ZYt zjVa=OD3f1B%~O;TbRp6lOn+u)hp=hzVwvj-P|)?bVKUcJ}H>eM&8-zk3(sIeAaJC1_1WWQPYjKYcg|qE*h+lD|PAd{fM%`?X!t zgfJv|$K{rjj?fRz|`>0MUT+>^d&qhI$uGW|z5Eeo{8yY(?61 zx$%$(zh1s1vQsbCK-VO+8GSo%KA90ayz^9=O(IC z!>-lUfXZKYq?Uox(Aq^Bit00bR5TR=4inQJgS@-Jmxa<>Ol3(ZYjOvrx9)_$d;FU@ zZj%Jfm^xb}=RZAdmOz2emkKsxOWRAM>BT1`97#fcTB@@2RtHr4ZX1C+b-df^I8e|Z zu5G$C8Dw57?;OQR`cd z*3Y8u`GHKX!l}$cNzm^F#mVERHjv~hK2hd=wXg{&+5Ws-tBSPu)ME1A3sg@aUxYCfRk+dh-?=XzcMCAL`T1oFZgJS!F%t zbFqPF1+8CsMmGoQX|Dl+{mdUm3MtmB4G!GT1C9RZ__1y0LF#_GXFGF^fiDJzjD=^a@lZ^us`Vz@@v2#& zD$*)kp@8)kkeIKOr4#V<=jQL$k)c01>tF9@nHvqNBUQ&0%zq$tt6XU^f+>lAZcb{d za5@_3SF9chU4~+cLFn;|ZC@|t&*G*xD=g<^y;09d+C9SSBM=rQR1ZQL))Dn8u6O%7 zMp$C~uT0`W6q1P6-AeqNP}vLAi`}|^2c-TvdUJXdZ<~w%0L6|1ThxxBTnjG{rcM$p8dOKvT4=+*u>2At1RcT&#^7oP!$9(^Ik|A!Ou=>jJ~%B zaNaq`-&^yQ+BGwrEpq~uBN?Sd-MpVPJ3+6I{VlFQ=pK) zC5Q&RS|p4)%E#Gi4I+4O$N!bU`N{=N{0i5sFc~WJ9Y9Oh3fTR>9l5_R9wwp82<9|N z>hTv>jq5z$o|E^bOSk`|^lm0<*B>9RRJfNU>`l@tqbLre@fx1XG}nZx-4k}(!IDwb z4`}qVZ)``@a!Xw+a?yWuk_j3r=%l5bf?i1=!u9zh-fiM|s0w3vJ8gQP!O}Oe+36q8 z8#j8_wfpm}uD4qqRwFzNx@&T~JWe`tK?_s;`kUvXZ%Aa$o8IfV?c~CASj*h5@2wY+ z%trxs4T_NAX^=t6)@BRV_`~5^@=T%W*xkftR6`lNX4WOFMnwR3SsP)Xakw zgkoS5FOg>RZoACyv@cDa@nxFBeZDfZPdM|}K=^o13OiyW2{EQ?3wx2&0u^E)@iq9> zJ=xY;@2eTI$!b`$eI;(Kf;tU$ydTXA`yd2sw=YoU5n|Rw{U>$JXPgj==!3uaw}{`J z?tW7PQK*Rln*NLH*ViE>g2qRw6oTJ~A+%y|4>u9?>KhG9BQA6xrl3rl1k7ZU+alt^ zu*<(xqF~aGF@m-QbRi80B~cM}XpMk@ZP+97>L~>2WG*He^7`kRfPH$X2gk4OnCtA7 z%pu)6iuBImL#IDa^jPi7{7#+cA_gSw7-lHf*4CAqUXg+xP3Qvl3u;K8SdMrCi`Y`H zO=aU_fy5SZ7=PtED80l?vWU^m3@la=Pn8V0cg!P}%pR+wxs`WB#aw9$diQi|J&Dw? zea}WO;Ptrt`FV|DbA30aa-X_9_se)1;!l?rJg6gH7elD@nd&)%g8#a#QK z#PqdUobn!^e)r!eVe@m#B{>|}LiCC^h0N9~VJAglyD5w87pwIQb&ks)X}TjHyLBh< z*pB!12oFA-oN+<-hk93M$bGwwdB^QqJfDIuC%w-VbSygXV}Q9iEq|cvnHd(H9WA;7 zK4jA`Oq)o&Sq1|O;$@shaUUJ4?fn&fVWW;1JtFZdXc&Ywv7nE5&;Rij zqAnYX4iDk<5sWv*9;3%F>yFMHJbKa`iwWkyZJ$C29c!{0%)w@2BtGHg90Y#^qeyS- zkjJ7Uyb5NQ(?>QIi*AMoTsM+OBEt-u=(-5N>gywdiwb69)RB7F_&jm44BBh`qnH>X9UBX)bSO zS0Y{#@8RRO*f)$CGA(M2N->RUz(APLS`bg)3{d>_)xRH(d1yi3M@Im3v)K{Ry&r7k%nG}r{B{v@eUd4e|11W3U z?{BHQOI^;xj2=1?zbTe56$tWcY%t>Yj;{ltL}BN-f~qmBZuUKK<#$c*Q^+*hSBO)6 zJ>4?GhIqMdQwRe2fTH9B5lQoBkRd4f_|hQ)9zl#+#x&-3lOv!C*yg`~lqRL|>fUTY z#A&j*@0)>XgXrll1YSWuB$)|a6nSULquH<*)Z7>idDptl#m$M(L#!%BD=3~ zD=iS?g;ln$vzy@17@jvsik?IfNg3#=TD8s8%Z_f%m#gm>N76U1fP*`yt*K(!b%#9| zWX#?ACC>KdEJWgF>FcX(p=gpQlvZ!OlmML*_12fXw)bYWv#ztQX|nDa%P1uC=Di>O z@wTUG@|CW$!d|70$;>a^S#fM{R@2QSgGrdKWq*%@hVkkd*cqi5Jx0H$3hQ3;rhy(1 zoGmi6>_F((uV39WH1y7pLl$1UXMM6!yvgv7H)#5`=fr3VBgB%kI{JjOS=8C{y$ice z&g&W6tK6(&*j1*_$3rqhD-5SVfiL1|R8|k(GDE{w_5NwNy7Au>Ug38< zvI-bng%u5kHVWpueji*p9VE#b%NaDk}OeD2O~D{aypEd_U` zRTCHYscuMlf7KTpvx022l@J8mMxSgZG@GNC#^_QdZkd1$vOhm!w1#yQ>!Z@DZ$*l5 z_sW^}@~Dw+5>sP?J7Q^$fn(J2f!#Y$&}X4gNaBAt?P^^zP0J&ZDwmKO7?xPqh*6|l z&b^44>)tbQV3yX3FuA{HZPWsih*JBzYaiR7 zw~N2%y?Wz$Z{ZUsG`at#YJ(9nKHFJ-Khjj z&wYPic{UK5Ji!Bd>sG#Zj5Nv9O8=xyYvz5d*^XnZdX64Yv5YwXLDG}1?|uGE1|n?M zve-tyUP$P&nziq~mG++bWleDBZ1IRMOS89aceZqEb( z443MItcI4mn1vGsTqZ1I^(GFca&CPxqlJk6Xzw_)YTU-%YOTzVg02S80~*0x&>|sl znMHB*(aGwH>Y3v~0(f;06H^PTr!_U@ygLk?U+=hI-DHl z*V&ynBb+`c)>v1XthO9Gl)Y77wX0}n z;T^wTrg^;_kMg9h?r_5v;XJbTttXx{;6;X9ZhCf~+umCLtgTb|?&0n7U6(^X#^`%i zRS&&>btTEdigkw~Ajm>+HYyX`?^#T5v_XmUUBr6G>!W(-eR~mDMv9=zW`0_6W2WE; z%hDkNG8BG>aOh8zVR_D=kFt=Jq(%+@5|=+$gx2Uy6z9_LUl;2+)}i;cs*KaT2ooxC zdCj-cRZ?cJi$rs(d`qWcN>LX};xBU2KFr%{m6{4PhzTe;uZ+xi78QsTc07V-N7hkdwH_^}DbN6P<$4VJ$L9dd4%M-Fto0QvCZEq{98iniv+68e#lgoPy<4u$_iWHO z%f>eG=?Jp&qy)db+?ig#{@_ro-s=Y`Pf$0WdSBDkFNrbdgj+a3?29$7UGx2y*!z@Y z@H>uZuJ*hp+A;4gTDHD9p0li z6FTjohx*I!$UR&}K@(7(J}OG}Iyr&UrvBN@302e1^`ZTjnJ04xX|`x+7bAp}f;q*a zw{}ysv4mcKdwycR_rPgwQl)j;mC=~B$UDVy^5xw9o*R6~uq8Snbw;CUh;}g^wZY1* zSlINGQ03yxvudC5M1*=rptv!B2@EXK9>99A0I+#7V$XH!QhaD{V&UMF$!HhriO^E= zNCNW?A)!OY0K92P>u!o!2faAR7v)T|lq4>icGIl)SQR{1;mdB#2U=&`o-%I80q z%Y&vgvNO(iFW$fTjpYer!QWF;#riFb1Hc#y?Ck~X>J^oZuguwzT&kA!NXegV?^+8E z=by(uGTnR1ruhf~hG-~CptK?EHgXidIFjbza!)Sq!LO8lAxI%X!AIOwuai>Kp16W^ z1U2V{O9`O4Gu`nh^R4>4vtB>psy0hG-7T2*I(1^xuX~Ep$)Fv-QYEFLc|S`ri^@WQ zGknVu=&)2#leZ|N<>d;JlmaSEhuEu|;8m_#&*j}h;~o57o^4NfAKP# zg$jVBs2h=TG$_DHhmUzgO%-$`Oo@gu37nGTLkSI`T{D2?C@|W0}?DcI-+yIIW~Tiu9pS+^|EkY+x`|zhqb!a zG=fTpK#cM|4z&D&bk%9jpP^eYs9MrE0K|7OkAB{I_Ar6r63-FJqf^yU%11f^BXh_m ze&m7h7ajOIq55MV$*q`B_mycRV|kZS(9^iaDa`8?*NvOLPk}y^Mi0#bs|f)pbq~s8 zBK;3l^F$f|e=e;GAlm<{Ch~_4NI#PSHwgeDp;zPxLsCb9qk z-w_9G@c;H}jslvkxkJUFaoACIfmecx1dWp8@1Zx*0sMfQ-$ntJDGv-(Ic822Y-(K8 zrf%or`t4WHl3Z?TUDT$g5|NY!oBAerO!kN|J9vy1YUNt8F>@A{hkh)Q`YncLtFvD9 zyR;y7p8+1Hu33`1g~mY&eq}JgPy_r58+g({%Tq@1Ci$o-9*HrUyqw}Db^uEC^&fXc z_*|gOQlAzVF%T>k@Fvj{Wnn@0(|Ss`D!)D>SP@aSJLzmXE14F-^Qz71hg zG>jJDRiBJ%&sxuJW^B{uJ}te;tWqU`WxQ!ay*H$o&ExUa9?@b_;SIc>)z}|h89+Cv zfcbJ~mJ<5CT3^(CB-PVlQPW@-t)M2gIy6+MkqO!8eU@NvB3tMy8I?^aIznzbBRe|42Lg>})17s0yICk~{p{oYk#H{r+`9M7P0gsYAsh7k07ZF< z%LnTQCOs*Vc$A`rDOtsB@1n-mwM1Y~Sw6AbCrTpDC5LUBm84$oy6lH!Qi?fOG)-5_ zs2Ax}b!s%dGU4t-190@|Q~fh}-MKzF-MKJ*uR`lYKJ%S6MaP}CH}~YC`->ceU$+T$ zedI|ry6EQG{sw$d>E6)MzgFRILp>vdu0R0MeQY$o6EpmIfLk{DK`B1XShhtJj~ zx7Mz3fy5npmg(ORq7|Pl|E0$yerVy$0gPL0wfxrZ{*&YrXSn2bs9N$0DXG|FPadzL z7*HEsGzC1QSHyXuFN(f^&`}}ag2$~3DQnfXwA0n7M~dL$zP{TPR-L>(DFUjR-Cp^l zw(5Dq7Hd_r0Z<21d6kG>>lmoGA&=F7mc>vO><~d+D!Fb2xhOn-Z1pnFQSW=lD^j~bn_o`CzV$2Y0o)OK-XFas>Kl4SO5}0EmwQ}I+*$+ z&hK)?!~xY3#-w@jn;H10P#2Ti*&kW0ds^@7NP=Dlk8$6QGI=A9=vR4OKZSTba?hB) zy_=h2H86U9+_7)9*R4{y_e(|o(RsNh{p?&sHbklRCT8?(T2RGm^BYVIjGXDYmxmL+MZO%9pb`cI?dn03T*}rvy_F#;-EM_h z`qt?RFBC zJgyGNk%34v8UatGvr|VNdVBiD{S6r#qg>s_xAA?>)`-(&5V^C4m|T9aH# zhCMhsKh?RJXOI?DX|t+V9a*j1 zxH4hse6@J0L7Mah&xVt-o)jZA?UQaKI+{c zD)Pv1l0rVUT!Y7IBy3eoR2Xp`#kCrIpa2{miq5+Haeg20vgcJ_y04=lNKsBGj*>{@ z&3g(3FLPhWj3Hs%Q1i*o^h(F?=w~}a5%h-HtARpSpIecy!%h#)FFp)8kG~BrQe}B- z98lC({W{x4j0yrv8_jz$if^{*oT(6{hDbq9+1wOFdO2-9&l=s#@vtvIRP`0*ui`)$ zC=*p9TtMT(O2DTi1CO(weJdHZxEq^m8K!j*A&dvPez<83JE7*b3DH%!vp2Fcp1oFf zQ;otpV6X_d%jwG5(<(MSx~cNKsU!IN<03@nGf#oNlVKN%0_z?N;GG-!Z}unnw(sZ9 zbf;gzG3ud-Xj>@QF{6+2_P8@b7C}nHA2O%yh}_Y z6H^c36bZK(2{FN0&B@L5_|;}>6I2qgG3k_}1;^Lj>-a{nA*iPQ&YyEG`+-;8^%h&J zuBR^x&udU?4^x%?@;su+y~4f{D^;~@kHNVXQ~d~@Yh~NGbMmzMK&aYQ1)LhYe(bU~ zI28RV#{fZWpjC_S8!CGQuh;e{w{ra`nkd>Qy2ZX{LM?6<@6}{bE2600EaX)+K6UDU zx}n#iAEEC>d5!`O`Cw`P7vSK-5eOYcGfvSX5RRj7nJD?guqm%PbNJ`J5%TJKvcEk2 zl?~}Mk~jrOE3XpGC$K8E+w#F$@*wwoXzbn4reMuP)~mmA0fw~}d@8*>oGrp~4L!`P zXM$~TsL%0l?|jUa7nW_6ZZNuDby&ASc3$OP^g)ePH)A_WOx-U~vEFGUvr%BlruT-_ zJtVbo^BPD%$`?Z#mkEHggyZOWAz4j;P_=}yva3{~&u%u7eduGj2k2KOc1i$$pxA)N zMyN#}U&`?jiUsvD$)sRJKj)YUowao=3}Jbi%QT`??U(H(5AR_FN%xSM`}Iv@x0ax9~!ZuSSZQefNeLn)VJqd#VO&l)iNfUMj-3ApiK>*BP+rX3&CwQi>r2Uk ztGFXv^LKS(t+F@19d_oKB;rpryh%Y4!~WM?@!W&T!ZG zmbBLpKk0dH;r$!c=z6gEya=R5WkSMkJI-mRKNKm+EC`@tx=K_Nz@v*8M?aSxo_F|M zMnRBIfG_4<7Abetx8`PzH4PPo2!V?|Xo0fi;$EP`2|AuXY1E_2cz=rGeFF5*O1uU=2?PMW~#4l^Fpdg$_r`fauOl%AT`Y?o?YzHVocv)3=s z<~x5oiU%-Iyr*XITqXl5VTsIuUlxH;hB`rLhFlyR2=#!Cb^NtOFQ4*I4V(C0*>h2i zzDo8M#L{uOJO|1f*||^W3Q5ug-^Nk+k{U;#yfYOU#!^MZ2FPPdPX|p=%Wr6({QU zHk?Wz2XN#}>DVuUXB33M8?N+WA;cF6 zM;`A62|b#)Xnor!hTlNYK;Uxj_x8{i{Gnef?hW?VZ`#u4W4%7t`nmSW(KOYzz$E3IU1p%(;1^<@lmgwX$0nYSw@F%DQD#&o+MU<;Q`UnM# zz9<8SoRV`HL`xbJ05h@r$sdj0M_dQDL}fFT)PQmGuTgNn`!fpLE6)wJi$9Dkk)#L+p%7KNB zbyN=AWU*p)hku11|MDFH1q8lnhoWkXVpHDz*NCqOLENr`RZ0a)=FH8>>y^z{(`YnN z&KKAIV@QBB@rRyQXLVztVVtAfQ|rGTafvqhiE6AKqV($)GRttZWYw?vfv3*<8d#AN$*Eh20iMG z%;!!0#|{u?ncm42I3x#U%{$x<)@Uh3R`3dSN}oWHd+9&hLyN)jVfoL77DtMV)Y~Iy z_0@~@Mq1stne_~Wsf7^Io!3qKUL@T9N~FUjv`PYq7D;g37k$}@M#4< zC-T`$80D#+KHFa!(zh7Q3f&7m>w%rVJR5jnxN*AQ!WN*uTMa?joU9E+RC>cj3w5eA zhO*`Qi_Ln0D@>3pwR#a>MsyVgWy9PZ;_$t8D^a?yGjF(mt9lxjyUALccV&)XdSD}2 ze|a!7R5p>lky$P83r*JE6VQvAL4@2!9K?nFp@%nrI{eqXZE2%120>#vbYE<+=Bid` zJUiQmsXA>==^x{g4N4OmH`$;gkeE13Mp@lmX6NTG)6Mo4Q_X=T9~fK-citS9E;myc8P?R#QA<9t z*&M+kE~v5`Rr-VRZ6Txe+Si4S3YGK2En(K5#fhmlCrW!Z7@k+HX;pgHzsOV|&OIE$ z(S=UbX@YLs!!$y0KI!d7U7~ zI*5Iu#5o3Kim|iGEoR>e+@GP&oY+qp{B>(rvV+%b^wIv(Fy)@^P}?gXSU-NdSR&rY0~lu7He(GHk+zJygd~lp7%JPH(zcX=RUt)diL$% z7a#-p(au?^jWwg<(G!mS1CoM7Dl~WM8l-6 z{9Mfj$89u^^s(hYg)cffdd2LIGkPHxP)4f?^5D+4Pi+O=7Cttvjtf350tN70@j?+I zVz469{Bl6Pe44io*!ltUx|LaLM~qH{(x5hfdw_qbVIL!)>Qv&XbCw;CfOE4co_zu0 zp|#~}x~2P+kMNJz@~yRpKOY!bjufR&dmkE|E`r>=52_MB;ZcwWZXqN#XWgmXD#`F_ zCHO(|en$?031)gGO>gGz;>B>9k(q>q5=$_9l2AIAY3~;f7uu@RrGeUH(Ns=NeO6tw z*vOjQGG}J>2dYW|IOHQM@g@ybdjEh`!8dC;T`}FZn~~EMXFhO>0v|X| zUEvPtsLkv+cXpg^pEZy9(yIHx@u*>kRlv8?gN?yb+P)yp_k+J`uzexm&D==;C*1|& zXIk|te|x+^@X5;EYCsHXRhvX;-&S`E1lT3-WxPFos%E9->Tr&^EO!M@<}J|?0DxmS zv;|H2;-3p0c+oBhT$l5jqReXANRLp3HMHli^~v10oiVW4uuR6ID^xM)^R-nT zZwk%1UQ4xW!gpz^2w;?i{$m$KfyoIe5c84c*T|&Ofi0_ugTI%L4e*Pmiy9&Q{_clE+c`|2eYc#?YV}+qk|0p!czb%0J1cIY(Rw6Jg`n|Zp`Jcfo{CTU zs{UGLR5GEd)qC`v0vknydw2T#qumj)~sz)_Ca!8Q2YUHRpXQWLD=DOMPIw$@?cvUupIchu35lU{A)x1xw<)P%RHqxetnhN ze%-PXpL=z>9`en~X?HE*6{Mbsyr z9mXJP{+DM4H1g@ozD$@xP^uPk;am~OrW#T)T@OA|k$ zyS|}ZwuwrgVx6Xf_}#Z_gXB6`Pe8cC*3oj1{6AL(>nIuoLe7Gqqi^*AtGXFRl{WvJ zJU+Q08^mrUP6=xk3Ma;AEnU?CS78a;u{cftqlpX?Ft1;SXVPXVrhI0|lHS_4f`KqU znPyPI{)&(ifvM|*uFXUzSKUJe>;2a6b10ZW#s>ck0v??jM^<=_s3^rBCyClUTOn$6 z+GG+Cip*+AsNen~s{Y2%|4=uV=5>Y^ z4T=lV)ByWr1|QA&d`IwqHZ@+5We@?pOv@A|$}cKb6^g?}V+7Dt&@d*R;lG~l54f$> zQ;v?E&jFTao<sYSOFJJ&%{2M5X-*jeFp{;%Cx!vXf~>CfGe#Q&$UD-VaV zd&3N}eMQMqQQ{*@QOS}l6Uv_K`;3z8W6N5Y38Bc+kZhGgVGvnL%!KSw(TshltRthW zjlu6s%lE1I{`mEmtLu8_J?A;kdCqe`_x+r=D{Ix1D0KYO7po5kbncntwucO6Ut?P- z14;8gQmM_8L9K$)e66e+0zf5Me(gwx_y(43sO>=+5CO~{qK;U}Nm7EPQ!zvBg zc^L|9r<+7$GH{23C+7u#YLy3!OX=JM4Ho>qXGgYzy*ymX5yuEbY=AIU%)2nfPZthf z(7*ucb_}Bk5*G@rHq5%WYLlw-$8RFNXm(km90>uas0J*n7eGaSyidsj{LmBquEy=& zk-!w9sdsegeg_%^hV+8}|G+Ifcpz&b0q=Ucnn*WtNoM!oIUf1KM$y8F0&hu3bBP2~ z)v_O{d?tT*y2|gs=D{@H18<+GzSR`|P~?@~Bakp<6F(tSN1qvha9L;}^ZpHC*yMiw zDWQ9~owep*%(j--erggn84wx=W*l<*${Ix;BzHDU(c3I15TPnHt&A9NADqbQ%1)rA zyu!E(z}G+Qpk)t!Q?6#{1lA;LH?KSp#zbNR6GuPvt!frl17H__;&OJ}?<)n~>vM2q zVQ#s1nK<3BOvG1WGA@lz+)er0)nu$K%d$(2sE6qfcxsvd-Y@>?`6-dA6o6x5C|d>G zHfCBzBWO6rbExcOc=noRYqFT)*nYhN&579%YHY~<<+UIRT2D38)Sski)}_WIPkoQ- zuW^qqwy(*%!opFYzg$NTE$#U}}J&I=CL zqI+@{H+ss+P*1BWn+L;!d78v47!VIgPo(6JQ8CMCaZlx{iDK9jGZ4S_Vwv={S z+-S2bD%u;mCGF_8Q?pY$j96?Z>MOenueG9Kfp4ga-3@4poPzA@bCrF%D1$G z#}(Y@qzuF`@rOs9YPQ*Xkci={=3Eo6FVuHH0%H0KiNd_n#%?7)*?))MI$J2~nXM16yk6wId%#&<8kM;R@Ei}e9*2HOcdIxNUW4me`LyczzRWN>af+3dl@t}wB@M_ziVM|jb;49U zz8i>2qa|0*R%rMLsV&6QN{`^`o%MyQh_h*rEkdn|Mc4=i#Ul>NH{&fc4GDj=+ zsps-`r`GgC7X-;K7So6Kez|_F_RCG>fZ1JQ(g@$1v@!=i{SJMYl0fZIjPRdzD;2fR zGrIFgZRkYW4lc~%aGKF)A>4NR(WuPkj!u~L$RX?JMX4o2eB=1xA!V1Qp4j~-OQflW z;3%(CU&|M&91b=wG&5o4njs8p9!Qb&!|Rm9N`D6<6{KGIPwPC*Hw)}qscrCki3)e1 z%bo2Uewee%8RYQFKu)7Ij~7KFm9{1P;3iqG$X%M>l36ZMdzY0jQ7v=ja)kk{B{~4! zhOsUz&g-(CQMl=(Uw1ZR+_0w)-6}xow@nK8u*I4Eq0Wwb4D-ZGO7nMpJ8j%A-uN#k zNH@fW!6@eNoAFAELw`bL}5w8-Uk_ zoRaIp8~mN9Q(z1A_gKy3>%5EUGK{f%AK98cOO5xy79*=n3Bw^{i%EzEaG)#{ zj!y0|Ik5G@M9Bjp!w=49(@}%aRv^Moe3{Xp+p?XY&N!#$q5! ze|7!#SC@`Jh3hxx0!xnzBB;#|7Do@}BkOEz81~tJ|F)-e* zewxe>*JR@*)NT3>5y6Arcyws>nC&;OxDt!2d3xnm-w$^vI2;f;IAu3QVt~< zz0ybH+qMog#61SBt?8T{8@WUY3n)iq5P^jIt=%c4Y zZUUUwnW>;#`@AxtG#fD`@{A^)U-;Zg{QOSfhiN0RNw6?P3{*Ij1Eie3f1K^0TpYpD znZZOX&WIpp1}x6JJCmVM^uGUfO$zPso2m(@4y%~39qY)_E^Ziw?OrGd!LIn~4A_{r zr~7WN(Fmx2uBJ5K-c_)ma}G!;+%}R-%eDpkMPV&6lE?|>prWHe>8k*0C5*8#xRL)2 zK8y9i)16?{HjW3)m7;-!$TgvXBgmfcvw*X=(8AQO&g$HTk_bQPjZ)#vD}H^#V~yPA znP=L0@Oq*|Eo5+~p70y9t76o#ihq*Q^P0$`)F<~l$9T$Fe1w*wyvdtc#BcJ$LLcwp=Ilnj*oHo3 zB#$UqTMZb9ZUPBYiPCX!}ePZPmp}0u&1u4yt(V#RbY{I z;PcmQ6I~mR6HX^2`zP9KRRpM7_fE2fV+#?;eLi*bRc`jS|(|lXSS62%)BH_vx3|+gubY=v;JLGGbg29@UKA7`T|5jr@i8+xb>M;@=ceX zjD`z~i}`({=|`QUQlw15AgYzx+fBZeMgi(xdie@`J1 z=gnn3f5|=vgu-m+_vV0C3Va$)ma&fhVC^JPkS2t!rPLM`^_A6Zl~lPsS5ItN0F#<3 z=$=JDVtI5VZ-Ek9>VG*QA}yI~!eENEIE~jk3Y&l~d?Y5V_-dwMQizcmt>S}B7XO4( zgt5@U81HHv`8Gm2jjDK>2&pFujOF?<*Rwq|-1}$+WdbdIHn&NO|Fg=;oGIl!TH;_| zb5do;EfN{1M_!rn%fe!M&YGk#^+T8p+g?Q>9hr-k*8(ET5TB2@nl{g+z* zR+6r0BTXTp&KLnnz^6nYZ;{rU@RZ=)>#%BX*tfFW8`-;23JeUatGZez&3Z}|!WJty zb{-UbeAy)qFf`TEYdZi*BPB;q(#+|Mr1n7rmwX#*CRL^*Prns$5R#~JZ@!&0U8wUU z84%U34`=Tmfvg`)JgSS_ae%EfzoiqjFuBrNnEuG!_p(!i#jF&)j43Zg5AFu!8-as4 ztwXU^@|(k2)*Qk8b}Z_jM#Nu_LOnRnQuZrU1oHv@4UNkZ+s78}sCOsq-KF_J|2PZ*WhCPOLJ?a>6tK)nGO}->a6z(u-IiyDx|nNzq3G9?86d-=+<_YwWy=DG zX@kabvGlHyqHnaJxxJClpqem@E6=*J!$*9`dp6i1_9wzsKP@4islN3#orA#G%CMFIrQ>e#jStarczVY}MLg67_J{Zn|fn z!VpH&wUZOYgLupUH_a7?MH3Z*?|mSKc9*DH)x*iwa;LBUYewWU$JskCFB7gM0X8;{ zbFiA%1L6>{(WG>Y3ydLw*(BYBE7q`;)kvluZiIHB?C9QT*w0_0Ue>SEzn>SnL_reG_2@?AuqhTm{ zSbKVv9K#;&7&;Xs{L>zd#SH#$90?iuKZ4DO3d%iiy`+LuDa{bqX?x{j9P}@?hdP3f z{$_uW4?5@mvzY8%iaX?Yy^xoISbYjIGeST<7WIZh@F;}Eo#>UkLCs6{KuRvAtN!N- z2#*Az^uvjGI69GXoT zfU7KX$M8$!>ImM86sN|=g2fXzo8tM+h;wp`x13t9sE=tdfZhSS8cBPF6DUkFw;dP~ zVD=fsNrtHsP+guT13<{|0bSE?-uA$J`2T?Q@Hjr2gti`F;p9zyryX?WqoOY`Z(sB1WbTzUv90HS`i;rg- zm<=ojm2&BpH9B_zOAY=H$qxi8A)`5m>3g| Date: Thu, 26 Jun 2025 14:10:06 +0200 Subject: [PATCH 040/128] Update motion_primitives_forward_controller/CMakeLists.txt Co-authored-by: Felix Exner (fexner) --- motion_primitives_forward_controller/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 53588db555..033507db30 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -54,7 +54,7 @@ install( install( DIRECTORY include/ - DESTINATION include + DESTINATION include/${PROJECT_NAME} ) if(BUILD_TESTING) From e670fdd37c1ddd50b7ecf16388ab9a3b4db765a4 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 26 Jun 2025 15:22:30 +0200 Subject: [PATCH 041/128] removed ament_target_dependencies from CMakeLists.txt --- .../CMakeLists.txt | 62 +++++++++---------- 1 file changed, 29 insertions(+), 33 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 033507db30..6cb6c58f30 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -33,12 +33,22 @@ add_library( src/motion_primitives_forward_controller.cpp ) target_include_directories(motion_primitives_forward_controller PUBLIC - "$" - "$") -target_link_libraries(motion_primitives_forward_controller motion_primitives_forward_controller_parameters) -ament_target_dependencies(motion_primitives_forward_controller - ${THIS_PACKAGE_INCLUDE_DEPENDS} + $ + $ +) +target_link_libraries(motion_primitives_forward_controller PUBLIC + motion_primitives_forward_controller_parameters + controller_interface::controller_interface + hardware_interface::hardware_interface + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + ${control_msgs_TARGETS} + ${std_srvs_TARGETS} + ${industrial_robot_motion_interfaces_TARGETS} ) + target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") pluginlib_export_plugin_description_file( @@ -67,14 +77,10 @@ if(BUILD_TESTING) test_load_motion_primitives_forward_controller test/test_load_motion_primitives_forward_controller.cpp ) - target_include_directories( - test_load_motion_primitives_forward_controller PRIVATE include - ) - ament_target_dependencies( - test_load_motion_primitives_forward_controller - controller_manager - hardware_interface - ros2_control_test_assets + target_link_libraries(test_load_motion_primitives_forward_controller + motion_primitives_forward_controller + controller_manager::controller_manager + ros2_control_test_assets::ros2_control_test_assets ) add_rostest_with_parameters_gmock( @@ -82,16 +88,11 @@ if(BUILD_TESTING) test/test_motion_primitives_forward_controller.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_params.yaml ) - target_include_directories( - test_motion_primitives_forward_controller PRIVATE include - ) - target_link_libraries( - test_motion_primitives_forward_controller motion_primitives_forward_controller - ) - ament_target_dependencies( - test_motion_primitives_forward_controller - controller_interface - hardware_interface + target_link_libraries(test_motion_primitives_forward_controller + motion_primitives_forward_controller + controller_interface::controller_interface + hardware_interface::hardware_interface + ros2_control_test_assets::ros2_control_test_assets ) add_rostest_with_parameters_gmock( @@ -99,16 +100,11 @@ if(BUILD_TESTING) test/test_motion_primitives_forward_controller_preceeding.cpp ${CMAKE_CURRENT_SOURCE_DIR}/test/motion_primitives_forward_controller_preceeding_params.yaml ) - target_include_directories( - test_motion_primitives_forward_controller_preceeding PRIVATE include - ) - target_link_libraries( - test_motion_primitives_forward_controller_preceeding motion_primitives_forward_controller - ) - ament_target_dependencies( - test_motion_primitives_forward_controller_preceeding - controller_interface - hardware_interface + target_link_libraries(test_motion_primitives_forward_controller_preceeding + motion_primitives_forward_controller + controller_interface::controller_interface + hardware_interface::hardware_interface + ros2_control_test_assets::ros2_control_test_assets ) endif() From a49cbb5b0b9bf1afff7cd66a685db4034c8e7e14 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 26 Jun 2025 15:32:10 +0200 Subject: [PATCH 042/128] reference the final package destinations in redme and added shematic of the action --- motion_primitives_forward_controller/README.md | 14 +++++--------- ..._Controller_ExecuteMotion_Action.drawio.png | Bin 0 -> 212574 bytes 2 files changed, 5 insertions(+), 9 deletions(-) create mode 100644 motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio.png diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index be910fd651..921fd3fd98 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -6,7 +6,7 @@ Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ) [![Licence](https://img.shields.io/badge/License-Apache-2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) -This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotion.action` action from the [industrial_robot_motion_interfaces](https://github.com/b-robotized-forks/industrial_robot_motion_interfaces/tree/helper-types) package. The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. +This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotion.action` action from the [industrial_robot_motion_interfaces](https://github.com/UniversalRobots/industrial_robot_motion_interfaces) package. The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. - Supported motion primitives: - `LINEAR_JOINT` @@ -17,21 +17,17 @@ If multiple motion primitives are passed to the controller via the action, the c The action interface also allows stopping the current execution of motion primitives. When a stop request is received, the controller sends `STOP_MOTION` to the hardware interface, which then halts the robot's movement. Once the controller receives confirmation that the robot has stopped, it sends `RESET_STOP` to the hardware interface. After that, new commands can be sent. -This can be done, for example, via a Python script as demonstrated in the [`example python script`](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives_hka_ur10e.py) in the `Universal_Robots_ROS2_Driver` package. +![Action Image](doc/Moprim_Controller_ExecuteMotion_Action.drawio.png) + +This can be done, for example, via a Python script as demonstrated in the [`example python script`](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives_hka_ur10e.py) in the `Universal_Robots_ROS2_Driver` package. ## Architecture Overview The following diagram shows the architecture for a UR robot. -For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver`](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) is used. +For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver`](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) is used. ![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_integrated.drawio.png) -# Related packages/ repos -- [industrial_robot_motion_interfaces](https://github.com/b-robotized-forks/industrial_robot_motion_interfaces/tree/helper-types) -- [ros2_controllers with motion_primitives_forward_controller](https://github.com/b-robotized-forks/ros2_controllers/tree/motion_primitive_forward_controller/motion_primitives_forward_controller) -- [Universal_Robots_ROS2_Driver with motion_primitive_ur_driver](https://github.com/b-robotized-forks/Universal_Robots_ROS2_Driver_MotionPrimitive) -- [Universal_Robots_Client_Library](https://github.com/UniversalRobots/Universal_Robots_Client_Library) - # TODOs/ improvements - Extend the tests - Test for a sequence of multiple primitives diff --git a/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio.png b/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio.png new file mode 100644 index 0000000000000000000000000000000000000000..7425db6eb609de0073086031936b0bbf5115b37b GIT binary patch literal 212574 zcmeEv1z42n-nU(dD5)YACEW}Sf}kJ`BhnHhl0(CgVt|N*Akv_KA}t_YE(%DCG{}r7 zAwww*LwxrGGcGD;cm3Y;#-4M|?zPwO#2x?q{o{U)ud?EK;(bT=ZP~JgSoXp>)h%20 z&1~7SOM1^PaD{9~L&laZybSizm+dW`ubNsQw$SrPt^cCu=Ddcqv!~}dN6*cTurx#% zvm2WlnAjRv+Ob<9?7>CwgnS+&ZISYGsUcvI9RA)xm$b zIKgEeN$?BY;OAZc=}h=x>qyUYmWxM_os$VXaUNl0jszn?Z-IZgz$F<|Tf|kQGq||+ z)cW*}2wOW-q}BQwxnb;F?7ZtY?2HU75bKxu)~^^MZH*DO_$R^oxaoPM={e7Wk)eNi zr0{zKe^?n<;$Kw;+hYThLpwD!UVm56L7z|Uteq6xmJ2R#CV$!1P!RRwXoN8>ozL4E zSYJ~>8Y3*g5XR2yLvZo);FoEPTE8N|k6)#UEnyz~w9o}LQy2V#xYicV&1vFbYK*YM zkG8%(dnD4r-qia0i$+K*D})iALHH33Y;7T~tg#h;=_=9!zdQT|Yq0U}o`5c>{Z7*j zk7<}1+h4=)f)Bqu=;;dxQq>34DBf<}Q<@7e}Y`u3m! zUNTI+4Glf|R~QMN!OOufi_4}w0`o#sZ{U#v(jKx(+?>j`rk19VEJIdM25IYLU~3G1 zNg=K5ZIKohz#gr=`Zr|XzYzcMws-^o=(+hVfH9FYHgyC)O`xA=jn-MZeglZmhI^Yl zu7AocJ-WF>n6X-ELH;>fXKmSwOOtAcTb><#X?yn36{dEN%m>|CloPr`Hhi zpFQ~#aNblzU_U8~8c+^Ev-3y;2z8&?92lt~Y#b0)MhFo3{oolPVUss71kuxX8fAco zt42UMAT9U_$9{8)wg@{@7X!mJa15!6HN^cj~AB{a9UX2N&{m(b{Ky%so1ULL|UGDID%)`geF37Xt zF5bx!*7LXZ1cE>58{P#N7#Sg~?LmHmn-dA*BTid{8Awn;fB$VvKi-!7JD7epF1&)^ z<&}+RolgY${5!e=LJsx20PjcP`!!$izXIu{q##hgDPqCHgMTsW{UcQ8C2*1;jsJY> z{iDO+vo!(!Z~9#{;zudZmi6 zvqoCkLFU~E6r}%7MjdY?{vC|^Ply}8cLLn_TOw|JRJ%bKf0n*qL)`yeM*e>^B`+xW zZ;jvi2+2}{Z2$93JTD(!eeizerz!uw2L9(Vr78ifgQSX`11MnsjbJ<8Li{^e_^PqP z{|v5HI$Q}75_JKGi$9j|KKzPp$+HvQz;u8zt-*& z&cUqTz`p>U3|en`JNlb(-IgsUx5%D5tM05f+N=9Uw=G8CLwW~AgfqpF{qiNx6Zs$V z%O>**kkUS&G`(mfcaiCG8qDT>|yExQOb3drK_WH)1Ck)(dAC;d|vQg5XkaI{2 zCt~aL>rZLCU~9ReIkBYVf}R==%oT4GGoM&KcG!DyJVz`Rqs3@GF(W*pWApVL%hYL! z>sz*N+p*{1$-ngD3Syha1*~pF>D|45@s0K2)AnA#@*VuEv*6#kETKAacl#rkzq-6P zWChN{;(A`*U`HW`f?98~s>k@;jYtnJM;s$ZeSOXD4MGl~qYLUO;d zz@U`tiD-3NwXO^$4qY3>0G$1B&dbV+F~x@UG_A0|%E*&{mwhJa{u0msw}tX@`pcxS zlyci#1!dtsmW5!7pw=jhYrOY<$v7|r^+_T%U8eg>wgfL%7cNPtBC{VibN*%N0Hb>) z@40}DkxQHj`IQBp)CB5N<1O>*mkiO<(;EfrJ)#0zZ?i>k z@Fm~+>#MzR7HGmgmAAWoiGi|2Kojie9b*6bL?h z4C5aN^G~<_!>r#S%ioh(trYXq@2E4W{r!&90vu^aED& zasS#oX}=o1t#2mS#s5zh^CMGPD1%yyKW=&Um;GNAgY{QcpNzxWNz*=Cyyzh@=6?S1 zm;B5gb%2`ENhh6t#Sw1Zb`e^t@s-M7ljLWlL9N>K{S&_?WDg-Bt9g0%mz>&3W%`rJ z`EqYCe@u<%=K#D3bsr$D)8PG%Tl=LzD9rgWG4z+#N(;y${P6?!=yzlN$mbu1e8~wk z?*Of$mh2zd!|#M22r#E1P$Sv{85zG6;s0k_8#wbHZv8HB|BXTz9spwXB9{UCqSU1C zM4wX#h;RZ?@_|E_Ijq0FTP@kPZv%I}d-P{V8wA1X#8(M6fAZY-Z>j-UEqwdT2<=~= zNaDH#1gk?11Xlf$s>y>GXo5UGE$|N(NCxtJ$>kdIX-!2Jf9D0H>fTU*()qRJAEXS! zgRYa8?%k=a@w0hjU<7a4p6W386^riG3WYY5hsI8QPp>~%JGd1d4S4Wc(xZ|>gRcE_ z1L56!N*_K}ez}>exB1&a+1Hn+9wa1KuHSxndBb*J^4UUWO5Q7EBNq*RfHU*8^E-~W~9ZB}wsM>I+|%MV}C z0i3O-P%6bQ{T=yp&)7>kfD{xYvZcP2Qg-;!ZT1x~9Wl|Fx%;CT2ITUxff5fIA~R67 z7VPPQ+RGJ`md*Xvs7oRsb3#c%AWRk0ho{ETHf=1Mai$9RD<_?=t<>u`PbzH14VhL- zt0J|&zEQyPnUWF(58@rkP0}~6pUvI*o*gt}-As*EAvT%Um#Wfew$0yczY`Kn^lZH5MW!*sl@kq`&F zUlvH+JS(J2z9%2~dRx38UPeFcOv~JLLXu_!PW`sW zEAiW6Clq!eesFel#kbq9fv|M>ai|J!oo|wxcOzZo88wmC--e^Y9y6?u6=m29mvZaXN zMF0zkFdVpr5r`vg2t(HOYX{Z`;dBN}_{~RoH$fcm^k2Ih{_OftF&XjFyQ1acC&8II zTEqL+vt&{SpO?vr%LTiT`Q4Wd*`Tl`*Js*3NIly$ijY@-Io0dCOD`WXS&#I$Vo;wu zTq|=m_0t8m9BR9W^_Rd-k%l}~vUI?kSv4?Aq~wE{`qm-Q7+)h=H6#`@oXyga;91Vdw_KI6N-+RIM>DVS$IVIQ_q54HBd z85EGM%y<*TaQccn-+hS@hV`|7FXahjKN~KCoD|JK18J6?Hge zwl+CcABMZ*sc?zuihHiyazPROOqJk_W2kJ)w`k7G7os%X+oH`7@ypLU0Ht*=INZTg zItx(x?)HN!rHSZ0iDDdFriI>aL}~U!Ap)f@14>tJz4J^@6}dw-E-aka z-7M8_eX-#;z+(RqD7dErG=xhA9*37V_`b{f>8j!xRCq#Vg7H1ZSC0!io$Zc~?pONZ9Qg7XldwC@fr*rt?@0hC??dh7O+g%VKO zX3Oc6uvTiX)**TZg}81kez8wa0_FHe2+aucNcU9Q81YmH1yo3F4NTQmMMkS3H6nOR zRXS2Xe|%Dx`D~6-10S540%3Y`Xm|Q%w)?t-E}+%O-9kdlt;`OL?#dqEy#M0?0Ki-K z03}v|S=%4f#l`W1*6GD;T~PE>WpM=mof}e}rhGGx@8PQJ|rW9j-a z2jaD>2)M*W+LsV?dy^>3dNNXKeQo>ofRukZ)w-F%-NC>Nr2O3W%pSayzXQ7dP^L%o zw_q3HgwdxbL!MHfe?suCSAoP;ZQFDlZzeDf=clJ_>*Giifk%g{25kdgRbI@TjuMQa zjO1@pC`nNMkynUx{`aVtbpI-?0S|2M$JakFkJM4a-#1Z*e)z60aP z!T56?%3>8*Wf&9;w>A@Ei7$YqH%T5JAWXS&JWdrb4C7JfUVJ6-AwYV$yxooa9=7%z zLBMuK@b(HY6Hq88P$X{3jjw-00smk*VRpyZ^<17{>W5#vO^i@Xn|ZLsYhX{bn7fec z%EC~N6B@;c>km=N4q;TXdUmZNL)U!Oa&El0i>iFSa%7f6O>9gg7j-I4vBp|xxxHWgvflV@p;jH72m zJN8(1JynQ`q!fHJH&A$7#FZ*M#M>hgqVT(1Xij2ex7U&;{KfL0^F zdG*OMrr4^W&wCV`n%S6V(G}cl-=feJE9#m}BkcHsDLZFQQBd3vK4l4?apb>7&Z`N$ z+q4w$pWg_f-mBx#cF!F*iy#r5R?c%6Y0tPjnj1|bzQl<`&y|J62-uuXK{Ih^C0v)W zZFZmQ4HI3N|I~Gxh)QT!MWAv{qkIvbfZ~2=+?h2^yZ=s69Cgh8)3@muf&0<9z>CK= z-;Cz^4;273WVm$8&RoST6b{8|V>2)7Ikdr_;2fnCu*5$5X@u<0;AZp7X&fE}8kf5m zIUUj9piPEl#zeu8jmMooc#X!oj%&)m;_ISqJMl zvL{QeYD#S$kGR05xTX_^hh&Cs%6iEHJ4b(Lm;VoY!5c|S$o<~092NGt`6z%!_)_MF zH>pyExVZ_AQkOfjrAi`S&ry0D;y=bs-m{Vsyq|Vh_aW_D4b_P>Y|wjL1rbNuXg`{1 z=)64_rrz!Ztr{s5m~?*&OkB(q>l@%53VX$gzAlbrnndwiVv9a2))B!x#Bp6s*>*#X zy6hUN$fVadSuG;=mQJ1Q+wnmN^X!-ux5ekxx47m(JEI^n$pjVve3*T82zv3|RzT)K z1d~qnFx-8}x}afUYG{Pw7-}ZQ2^~Qr?ol$0?M&=^!yM+)HQbVv<2q3a6Glz;54afi zV5EclRE1$)6*xs~%>DLWqj6^PU>77t;z)?LVXPD1woo2ANa_;kH%Q&<_d09|Om$0? zSETn8IvuWBDcqZseu28`+Yo7BootjG+8K?K^!C5`N2ez5AxH#_`CCcM^$^G23k^ngUjQ8sW4LuaSOJE^O zGT_pS2;?A2gH~BkYK>1?8~N1S0I$#Yo{T(f6^?eBY8Xw=N7u%p1|vr6BY19$YE}_z zYgkxP>OCe_(|h4aag)4`sd!;uO$oF!^B4)5!Mev%KG}?MZru6Bed;4~7*FxL@eMb` zQ*OkvAGH}i!>Af3N__-*vfeOiC!y-7vhuM#|_qA(ARABUR+7OF_u zqIn0F?(n<5ww$f%0ioafP^m}0K*h*%JutM%`T7&J-SUxg@hW<69aJYyzk5X@9!(?W zCeUFuHQ3PAm17cOZ&|!0ax$K;=DK6+v-pK~vnKMj$9Z2r?7jLM=1^0=pDC`83-$8; zw#)kdyw8g^YrA{-c}*rib|#{&gFmmyq@ImK8;4~hS}ZgXt!P8he&Nay+0rTEg)gs2 zaxy)aM{fJ1RgQDPu+cCFhAV;PJaRjUFMvGH@|AC1a5!18P7zDod*xME+{n&15;=} z09;{xzzOlP#~O9>s8IIL-3&vr*s;_5OhZ*3*yDcNeZp8f-)bx|t3%J#67p5Vh{{%j z-!QU!v?$)q+9kjT(9vmtng6iO>jA(d+Q{qV^fOjn*@#zSHes%>QM=_ur{78ymNO96 z{wOdJ{kACnW^x6_a5g+@?yYd~!ROVO+wt7q05*hryoM5oYnhtq*66Ze7o|9{n6dYT zc2b%ANOW|JsB2ylx=N#kUrLro8J6EyiRePHJ z+vX&Q9-abdWIr6SS-dE5WdV@CorhfxyWG{}@o)@N?x|}Kw@`1A4SChnM<1{~$Z}C4 zSKb_r&T`kq;iQ}|7%F`Lk56e_xFw+v*udmxccr}~Ty*eGMuD;Kw%PfxJE@r817m+Rf+AdX?{rT)`Uou9a5y@s46UlLra2i3| z#23ejRvIhb7Cg#}qxNT+txAN({70$yN6L_ix|v|XF_w~=QM)EUFNb1Xt;Ra^dP>BA z{~e7q&(PF3*QwEyV**&f{~X<;^{6Qk9e*Ro?fmSJ9)L#0IvVr4?AoM= ziB{SIpMo8vPIytWN&!f7B&Bw%%x&l3>6BGO;KxdJIx%_3J^1(9Pc-?XL>1N`Ar;|LQmQ+ipb^)j{C4|#7dF8y{h@NAijJd4O zKyKbQVc{!HmBeA~zO9XhB2m+{$TGIrEyu;QD@>~mN}BTNr@3A**5_&?OLMtVE*@LR zdrwyHFH^5lkk{62QGB_W5)qG11Koj@31F>kl03UhOmrL?BDPRt<>U;4H5=K9OI(JjP15zp31Cigpka zV)6hM`)a6KO-VG@AkK+@{O)WFl@VWD$d~cri45vjkCAb!OG7zG_Yv*fS-(2Nm^r_; z)bJq`W2BFxlTEN)xDS9*7*4i|FcxgT!>z;Ot4mWCSKVr&${&+Rqj;v`EcNFrsM;st z{FdG1IIa&x+aSo{;|hQ{ycD1%}nLnKv^7gAzYeK_3AxmiC9>g&F59f)}$bdhpg zNHEi^`6%VCzUj7wsF>^^pV#d{hYJe?GKA$TZj8P3+TJzcF;`41ZleZY-A*DB)N9uy z>X2Gr8!RT}dK}e%fAnkhi9jo*J6%#FqUz>{E*CcoBF|_AdGA~q$t*9Mtke!M?o6Rh z|1!rptLNNzyW;hD{QN`uy-gjibG=R`=L3(IF2zMogBab8e~?N^ll>^!A z_Nrv=cOb@+<6zLjr{%tn*}M(|;A!+=#YRC>6o>9TsK zl!*Ojc6to zQ@*S{{+p5XOrw~7g_oX!zQUyXRlrPKcgLmR%y%y`naY|LnJb^AAwxE>vc*Jo0_JOOy=|2NIbsW)FOJJSzIB>79H6`S5r`%JUSt5RN#9t%CWyRUzU3`Ejpe$ zC;Zkx$-H;s*LXEgs-EMdMMIxD6HiFPVhrxxMsBZuAI+A>^8SO5#{>7448XID>RXfV zpvnU60j;yYXV%wKI}l#*DuOhUEL9FmT>fDm1iKk5FB&p)y-S;3`H*C?ARUE_H5g}R z3(JdAjLYNC>;~HS#izL@2Q_d@wAZ@AtkdtFJH;68HeCrMmedD!`?2LWh`CzOOm)me zv_`?GB(-Z54cTl1WIq!lI2wC1LR_R8FI@BNbw^h&k8xT_k`8|4D6D#IZ*!v9BI8zn zd!+_51z7vjluWWH9T~Uwwa|?Cjf~7uVPpYkW%jYlJYLHT&x>lEPgt>{-$pF#%DO11@8V(Z}(AYtP(@nVf8?w2yTg^`X^*B1K6{ zw7|adC2H44%9_+sqdBlKyEt%P@C3qj7&Wn%v5TFdmTJcHp@cZjHB7d2b&_K>+fiAo zrGqt-ZZ-^2hxL_pp{W4qA`q4IB!9tB8a;Hb-oz#9W+9~!9OgtHz2erQ0BcjEgrLVxCD;Y!${TwIz?C=D8)A zixiG>gxE%Bsml1y0<7$-f9|;3bn|(0#t+`+lY>`6Jo+2*m4`kaCW6sp7Tfc)d#sAb zCWkJBkCZPBa1bdqWyp=j1gZd3C-l{E%o?OBy~$YE=r@Z@UzV)#ObYPq3>!x>t7DT* z8Q&?c5fBLLcf1S=a{m1Gaqen6f3i~>F7+{q!fgH3la{k-DWon_v-U=_`9@@}Q&lRR zpXzY*@2xwPJ3nRQG?j(l(?UL|*6#&DbJwYJh(ZcfqaUusfJ1Eb>n@Cv*aDsF*Gj4m zMXN^Pg7nlxw6ddKtfZcz^k>&*7CK(>*-j(s1M&OZ7qJ@Uk(K}-kEKt!cAyXxG^#L9 z%czC+A(1BGm#hqX^WO+?Amf>31sEQ~!kdQf-8#HHtmMfo$|o|5xt}c(%ULD1y3nM5 zoI2;L3fw8?eayU4kd3}6V7}W%=8FZp_>tO6QTb6epfIibJ75b>FQOH6HG2^-7nJz@ zAgYw`MD+7VdtqS!^f&lBb~P2Mvw2_L`7nl+nvz}|Opz1h7CE;MqvP6t|9pG>lt=q% z)-QUffzaApZ7Il5@7q(ruPHkhS>C}Yc}#{>gy=`z^W|@0DR3LNi%XqRubNASUv8V3BkDXSZ!eQHf~sSq;D0 z4~CwVFNR~`nm4Z1`-U5=PJjr9_5FGOt`2_yNs>8$zj|=XhXGl+ ziuX}pR^mBWANXf!#!21tTx^LO49Mj#7eM#tAofpWfppH@4QYZ#?huz(;VQIN0CZrF;bskS1!@ zT~bTL z{nXcECtWi&WqHQWyk068KzUL3(bT6V04>G-20u^W$VN5v3IKJ=^xa1w?sy)_nJDZG zu5|COT&{R3TbewYNjdgg<*3H(IsUF3=8FZXQ*{p?M+ZfRIb~bjaS(9Gu|O7>VJ2=< z={*y%XFg0$|Ap@ea^`Bqs&46MBHE}r03p8E9JtSOIUjrOBli%4Y;4^HtiSBGK*1mu z$ECr6&|8-&=>?jqq(c_?U6CQBU-@SSE0bl*r1ePctvyzk0qZX|8(i;mU!BokrO1st zv5(`f8hl(1o$1;!?5fFrw$06a@(B0f9OM&pHwHm}_VhV3nVOe6g@ zy{M3B(s!(S3FkMc9kXLm6D5tg<}Z5-i7QkwsV{I80Lt>pH}v7=F|HmI8-6;)kPLee zo{!OB^yQqm^`>&UcAXu&k{DdC=G@@}+~|(Vlxt-ms) zcX*Pj+9kc^>xY1h0|;a35I3yFFXU#ZzEeKmcHx{e5LZx}$e zdDDYTd5zYz)K$*C{pj$Wo*jEjrAf#uJdsC3!aZ2E90f6wUDD#2s%=R?__K^&JG=rp zyrY*&UOfCApl!&Z@j!W9|Jxt|RkGbbg;aD%J2*cur@*HLz@I0}ZErDv+&qBhmr$}U zT#O@>{=xBN>Z!G(wwTOop2do!s8Y=@fvJ9mZ(o#j&Q&tVQVPOyhq;sU&F-;kkvH^O z>&olZx}i|GVfey9g+cAEa-J*{IY@#}*@A>5b+Gn`07XM;cIkBd%~32vTVr*~c=9V$ zTrwQDikf22L<_BYS2hlC>Hh>5;B+(Xng{#YA}jKf8)HSO>076tKCjvK%xvqS6}`C! zeVP#{%u(ix2dyR>5)Z$PPkfv0G2oup>f7g59Qpow^>k{gdBwKbH8q2MrfRGg6ma(1vsefsu|l%@a0J1M@^SdZ@<+ zq$ey^SC*-t8mYuv#X7`n-#Ju$LEy_6sPEL}Au+MK0Di8OSFU`ZV7#&_(r6m00m^hw zJQRDO0vkvzx--mpORHUQ-oN^$y6o=Cset7w#TMG>9@dh(l<5j&no+DbrapE*UC}Iw zT#A-Jn_O(!snwi6ni4E#RIMG>aXYVUX|irT#|@Bznf+ZPO;Yww&z87+->;t+WeRHi z>$uB^!{(;s;4oTCahPF=E{_N>-+h(xew+0yoID7bZ`c7t5CkNnk}9gA4@Tx|M1-B} zUYFqbuT;g1T24(VpEX#c7~VAoMi+Nl>7H0EMjsb{%BYE}RIiGFpH zvMOhLlq$0A>_ybraEiFv1uR?b!kw52lwHy2lxqaz)uCl!-PVUq9XhcJ|x>FPL#PcX?>=>y7$SAdm(Z3jx3W*eeMI=ejDqx#f%=dx# z0D}?~;HpVSB_TCp?&#R>b7}T1;+isdRM3mJQhDdm97ZLnd5Yu%HD+GMaU?yzT`2Ln zqP8xM1j==szqv6$c2GrLe(&>X;1$;tlo)}~H(L+LNu{Fudt2db`z3Fql0vFj&sDgN zpg*%ZK2MeYl=i-8z#-PLo)1A61AGNa%qwr=e6cRN>7-)IA)n zxJ?w==FROmfsV08Q4VOv3FD?ObIA-dlrg8ZoaA#$%M@46%IhlBrV1<8bvGxj zluSMa^8etbS{@aecX!gr&0VQgMw;Vt%|j~i2#_yruqqsQ$m(`KaqO`-+(DslVz#Lz zFnfcH^4v;9OQ_8Cc%fDg`*>b^H5|j0nMd>nqE=oz6S4~ygCgq6MmFXZ_SO5rI|eH6 z`IKca;c9$RLQJCQX1qPxBB-Z-kIK4RYhLA_J)4n6zAY; zbVlFEvbTZ*^Zj9rK+Kst%Rh6{mK-&2EBQZwGO&^W-US!QALma;o{mVp{>-%Z$N=} zVba#H7#H1v7D!+ilk=J7R?60!NmHYKAj7(uYgo(BYrv9W6NzuK&-I#TmOAz}rG?RN z>FDK1cXbzySORgcOjk`4o*o^gccB7H;usc8f?Z8LadE7}4o8*L1J9|LA5Eah8tW%u=Pqx^0a!LFlP@$|7=r%zp(R~w)X z2fuEZ247o+^FA2$M9EZR_meocNm;0@KMHCMmuq2}cRljrM@>#k7S{&5n2_*+!a-@D ziEoALtL?!-UwVwQy71I9Bgf&^y96_>HmxG_LbcUc-CjTUw}Jv1tEne{z+&_e%4iN$dAfschRk(EhTSBqWr?hwa(EKn zDr~O*S>wW}`(T7gyRAfINrlM*$S0%Ebi~WL8#xC8NUgH5*}*%wm0Dm@k+Zkh2}xO2 z30u`#8V>!EpQ5HnRR~%6vhtCrn?eI@xTic5CWmWD6?<6EO+7u^F#uP{J>A5g)N=`F z)C2=;_Hk?_l4;1jm{TVV7M9X|WM$0=b(nxuiN7q+v%|=a{Ys$trroy3^m&FB2I*yUXU+@-(E2Fr)+mR$=Jhlx4!c&IF7BzUoewQm&>YMPS zj;e>4*`f^H$OjrgvStcpmr(->!=T)_TJk=!r0GNF$fSJKQqNmQHyFxOz>SS=zHAYj z+7-7lo#epyN+VRmK|;F?mo)2y8yY^Zv!Q-^1Sn`TQ-UAkQ}&fZR$k`;~j8HA3hbvK{Sp_26-SWe%5MDkUkg3*|#>ck4W?o_(%bdF*q% z_5h90i^td!q^OTyBptI8O(4U-fPYPV+^Da=RPXNn2-wi^FO?~QQ$i!DHdXM<&5|I8 z%b_Hfp^g&?*Ms9YqBOrG*-K+Be6sHpOg(e2O>j7_rjF}5>5Wd3;;{aAR*Q>1zdR*d zs=!<9s?@u5GbJ)=jY_$X*Qf-V$2oR0PH1>c*;*Tl2TmTCpq3=Hn4cRS2-9y|SsD^I z;V7FoL76jmSmis;Pe@ssV1-opQMH?E3*>EA7RU9fzk3012G}iE|((J)L44dQG z3y0-rNwH7l#HWoi$VMV8hl@(WJ%&)1+_wuneIIWg$!alDKu-V0XXhd)xyD%b7V#A= zIAHymUI3ghl`s}B$gv9^M-SmwH=VzPUn7API68SCAwvAlAgCdBtt{g@_?}`Vk{G~e z6UH(r{mVP)ii$uS#<*8w%&#&apr~9~%Spc^g$CFJI0mHkxvW(u#CMDYv~c4xK8oZ5 zTh{bpp>(!HpsgnKSybl<;p)XQcDjY*qAt8d{8a2ZoyzVl`ZD9iCzx76cqK_*+XFt@ z^Q~`cKOpkNbo~PL-4ZfIKSdTcTC3vgqh`$l=0?4flU5~I*0j48lU9+hauItUC@rI&G}2xN69}F;XcAaN6{LpI+;9o;)X-DX@t9m zO{}5n1eub^eHsDlD>M^sR+4Cg%MMjGD$!9(cfWi*yhp!keh8!h*SpU^b$51kZnP`p z_AJK;#R27FkXM1x%~mb-yh!6GPS*hdiWX!ozNaALVdVgt^_TuJb6a?X<{K)MzTotDc~X&nz%ATgb0U4{qzC zJ7i6^T-fB!K4)?|1sjR<>~%>kiGtwMqz7eU%6LlDXbQC-6!(wW^*)Dk&J-N!n+ByX z3Xgif~oLnmN*B}xk;Ie&Bx8V zyi^?KDpO@lfn{yeptza$G;2mfwl$QONe zkKR{Rl%L?!3&CL{2dlb4oi}v3X>~~nRADm_P?Y4fgZQYz6z-n) z)`OMLfJaZ#(yMTGMt)v}{EVz2^731#hiNU0<4t82EcLzEEI>jchXx5xi;?#9P!SNZ zvjCNrjx$m~-t`NwJVDq`f(>t9drp0mj2(BoGvX6JCcL|%FFY7??Xlx485F9%8A^stxYKefy_SQ+ zmoer*DvdY7xKj)>yCO?ySENWk)`T#cV_MrZ)zxDj3bCZ7N*hH@-Yru&TANm+8424v z;0AIHO`@XwgH?qM#3p(cMeLc4>MW5QIovnQ=LLPj$*hJ(i1)tg+cgg2H0nq)QZ*yW zYz5ugGWw{w7IHsg3qVuXkjdJQs*G9r*SJnl-;9sC-w8@hM$LZ`GEJ>flf)9ljI(^N z#Ej=DDi@Y>!b?-%V%PJl-eUd0(`-+VWVq<~weE?*#8=QBKux;UB!OvyykX(~!wNCi z())3qz`bBWfFIBz@-?GM0R;DTu|v|ITy0i-L?^#QuI>-$g$4Sn6tKIsmw%}sYToTY zF*fXzeOJ+zW6>frR5yvcpp%g!560DRz-*~hihGLQ)iq%jxrvLx`e8EitvkH zn2e+|eYi7yWD>hSD0@feg6)klsFY{X6f0`Jx6DtrtZx_nlFr+29hcL@h${B(o`U`u z4;pO1f@};($9KV)GMT%CTFHW+PL!{%yhkqFmR_1Gn=5tD-xrS5w%8AP7F&<_WzYnG zBSY4PPo8|s0c`vc4&iCE^RH}svcDV0k!tN7poWf4yI^%p?vRw*um3~Lt98g&~lB$`BXg?~B zO9#T>^;7XOq3*K{XtF4d5RLPlA?3qQqxRX+R(N>4+0HB^!B(=$D85kB9mYSY2VXcV zo#f-wl=nsYR=my)Oe@TDA~vmPY=KBBm$g6^ z#U)#sQ-}-AbQ_qwybATrbGA1{3#xU3Bo2e67_8`+aIM^Vu-2H%*Y<9fhuMMM1N!{V zv($An%sh-KJFG=Yss+Wd&t!6CvBVTqcd#w#J-9XJbj03byIc3Ap&I!{e6FNon`Eegnmg7Yw&$c=bpO!5Rb}<6qjNxmV zs

      l9mpB+Q>^fhp_2CTZzvacYxiji12X0^CSE-{49X%04_NnPBQ6dPsn1&wcidWy zDy_(5UY+w?buv{vJ9^3>OVOyj5zv3n#qa4)EP}war^%hW*XO^$f9(w81odrQ%&`}2 znb<0xDx;N1u@D8So_4z79IMro3=*QUO!qPKP~Rr_z=PiX8tyH*=3&{=7G3#Qiv!Mw zOim7-cji=f*k=oOGd#gwAJ#Hxmyja5A|?;AZ3a~eshcKSp+Y9tThMbh3fBd#p0`7* zq9=u1?RtQdYh(twg=MaC9qJ6C^4i6B7dg`H%z?P?OOYE*hjC}8HO6Z9xPPt80};Lj zhJHp4)WNX210qe-bqLw2zUKuwCQVg}UKJyfh7(ZR+PnU4q0rZ{SB}^2-(Aq_GLjzC zMpK&>BCM9AZ&cO}sPp+d=~TqB6-Rvjc%m^ojw*sg3C*NPLTH#(KId{!TLivfKsCO!vfQba|%-K<(O>Zx~uwoSe}oThY}${;@^ zgGl8UK(KNtma~oLwPW;6$4)21TDvOsu7oVNDLd6C2lo|~kTLfFgJ3Ilq>uaq=y`9W z-eafXBbuKS>te=sR%o`ZvTWW>S2v8R2b_9empIWTs%ksU1Bx*mm(&|Vf^={lUzFfo9D;Zz7Ep%?sjkCs6IwA$?T6`KUJIiKey(YZ;4y6f2EZF zn*1G|Y);zyj5@zzsV+W)W4oH5Ubl40m_F(hr(TDS?tIgzk|JBCMfo#A%SEX!Chk_M zdR}~4|ii!`kA?rMbF|dL5T6<^S?>{C)h%9ffxv^uq zbO2;NXj=|#&j@z8`I327!(=k6#>B7YCb;9xf6F~@%^lFy3hh3Bn@qGEq^V3m$GPX2 zC@y2R(!?83QkaEqT@r~unYK;2*~sgIgBpcXrHxc9hC{OR^`2jT+imWNI=K{e5Z%F> zA3toO{aNG9c_Hf$5(!QDm&3BwN>jJK0|JaQyW&gYM3bkcXt?V8WX3=PdYAA-Nl1(c z%J!9Zg?RT+Q=I-BrnpS-b5V)rX>hcqtmxsE(#}ll1P4GbM6uIEV})rF0Ec%T*Ooq& z4Zf<0&<*P-FcL)WHyUVwVd~L99Y%9I^t6jlBkSwk@}baV>Og+4qxKkecO|yicCUK@ zF#fhwSQMsgBn7SM8To*UNBr)f&7Der7&;s}dSEVY)LI#~RZ>6F&B|VoGBgzUFStR=;L<~f`>opc&(wN>{BkEdJ$*a0f-P}-HU|nCT|^uuL7=bHwb0cW z09~#8xE{Fbgqv^$hez3DEsMG9px@XY+yH2|t-Ig~glW6?n(IAB9653F`~+-Fk-l(l&u8KzDH0-i&KA={WPL&Ljk6eVZp$?Iz5Pagq zbV~V**I6K3H0Qz@dM=El)_ChxZ|0>B7l2{6lRO&4_exSq`E?{`-OklFED)OFcU`IHws9`Fz+z0#t5k2QI{P{QD6jrK3 zCpq=N6rcRZ4!c}+=kq>;B~bUf)*m(KeEMCL4io$o5nzhC*0HA+vZcKOj+gGrwj6nK zLx^-9I+G|0n&G;NC(0mdS*5o&M8Qn-m$4c-#p6XRJs=f*o{!0Ui`OaeQ8yaf=_-ul zNb1+>%OsofB?<85)4fzZ!iNl?Q`#}^77f6aKXEB)OdQ^;#kVfz;9J<>Lk47KG@HrI z6=UH30$3jv;f+U{4oFrHoO)&fzVag%@4>-ox;S%*dY!bK9zdx6nG2$M4$fkAdkkFf z$sGR9%Dfw$Z}flr^G1v00`80Uvp(WWr=TNK;qKtbR2N8;!PLvaK|%}A4c4Uq>wPfRlg|M) za>Oa9gD=XG0oWoZ{#lU_2LHta{$5$)m}SCw@=_TX-N9IpQ|J(a%RIX1Rnl}jOwWZ0 zGTmWqyzC?3TxWg2anVRo+-Oc0=$JPPvwKAhGZqJp%xg8>S=Ul8i8P52ls(3M4iN}W zSrsuaMUk?^wmTT<>pywYo5r^hRLQS98t@gRMYG?(?e(4a*|Cd*b9SgW*k!l)IfpAd zwJTS|J(ipq+bq!~g3t-R5ZO!PiE6&&li>VkW^O+Kfxa)EtzPAg zI1j$M8`zR1PCc4%1-g@68Xm@J==+OV>{_O1o zFK#hRT~M8nxEa$jnw6PZb&v@(K1nzK!q+_3X}~D-+@UxWn*I{SrIH2U)$fVL%z0B= zy~zOe&N})s5K*Z3z66Ka>cF}4yn3s9MWZEZ59nv~vQ7UV;XT9u?Xb0MZhyZa%{55bU>mcEKa=V~Lq4|T@ zO>Hk31z1dA!eK-)JkkI zp5Pcwg_{C`jY2qGCxXHl=*BUx_4)O}QFx5epU zsIpTi?R^Vsq|VLAV9jy@-^=I%XHT^{xSnjIo3Xm*7=ofpb`r_CIy#cdbxscCkX3kp z!4uqDUdTv9`yR09wW5DZcO(mbn+Vx>@gQ;7Xm2shb@)k`P-+S*N}!btJ9QUC62;BQ zH6ox30fzRrZUbADx^osz4P<8T%#u^cQxoepJg`fEKCkC~$6>So-vF=s`_^Z@e?X^K zD+Ln#jHBwjCgM{OO~xSSs{+*sGg7oz7&&~om*z6a?g(4j-?$A?`2j>_&;FKyWl`Ty8^&!{HXb!}7;6hTo$M5S4#A|Rk3U5Y4J5JW=gRRk0W zErcEr1(EJl5T&EiLNB2=Q9vm{q!S1Vgh(g>Lg?i@FQRji%y6@|{g=LZ#0L8C$3W!x?V@eHikS~Jpy;7n#z(0DsvJ7N%kRc2=z>nzs z@u@8v{<}W)#zu_7>h${wKzA9`=ooE@DF8sA%WY-5BS0&~3hMNre3a>U2fnA}EM&&LR21T}?*1_bxIKJ541o|*4ZzNhr zwhE@MMrOV!`Pq*rdxJ%)+)DQze>Wp&vUJ0xNvQa)!um{jK`VL+2}P8yPM<9vWL9Si zU%cB1S%1Qmlo&hx;LFdS8&VG(6EUuED~(Iy4VRnOod<~fUC`CnU7<+!J6ztR^x_BC zU5Z>OgzxhHcRSCe5P-S~YHfEQgkqb|x7d3l-@92q3pw1G7!+LF;{gJ)q+#b>+s^x~ zdFBoI32PHpy+Hk>6T5`MBZ|d?#xrr}0%~<#7^S&}TePVUfUL6Ws1SV^ z8Z(h;F>;-}lUYlGIO1JKY<+C?@9aT;cW;7FK~cYB12?uF*%sIc=l*14;&uzJP-|5O z_$YAz8=G}vPs%hsT(1`Aet1-8F%vzB?Urb!_HqqYp*=U}LD#vWDL&8L3qt_6!M=&w zs!%<*K2Iyv7O&S_S^@VlU8?wg0AP!IsJi7`FQC^_-YWN>10A#I|Fp1To!4`LLsr#& zFu>;{He5roIyjL@AWS5r#`n-=O*YuE)$5F5K3IcYoIx5E@7`(NmCiGg!Z0ea@4t8S z_}iXcW}lRgnHvtx76e}j%w<;KdZfzqAp+_9Ckuyz|4HZ16j9Q`npgOOn`>2T^F=XP zG1>AJ{joFW2Vap|$K5SmEJ>BETR+d{Z0=YBCHr!kB%Qx2IHLId_U(m1iue7r@qWFp zo69up{i;uVlwf|Qjs0e_8tij>b#ichvNqwQ^D_A87sNfkQPPju*?vCtp%egta+BWF z7D-NY?eIL_-h`34XzU6-Gc+wWk%)*e;_z0@I%;5d>p6-(Vjs`N5-VCS##{O6`P$B6 z04mz)R;V7%3)Sl^vWi1#&q}!g7x;pyYQC)~R`kS0&ahi@G_B$D7fg)lZOmDCK(dk= z?T;YW<`z7FxE8dD`H^^?dM26*uW;G-*Y#9$ob*Y$g7Ay8ALDbqxjmM8?ujWHg}sr# zTxmowuw08ne|n?l6Cj_1z29`OXkZRV03H^>?@S_CFnAIMFSU!M4gG)}e6u(l&{!I5 z+ixSNjR16f>e3yY@0!N5%d?R$oh68)I=wBg9>bFey5}$Oeda{ABVk8a4^@B>tEhR3C=2{sajc?!2gkdn??^JcV03-# zJtoW4`A~;3072>*0+zGq`YOl=ikXB-&2>wNI~UdEXdQCp${(iz7K#YwM6UqMz*F+> zU>&-v=Vbvz9M0H=goAIq4B4moVF?EIQQ#I#5Fgz_z!!dlq^oQTU=-Hze?1)QIvgrl z#6*2zR67FZudK076pT_OIu>t9dMJ@`ZJ)a_=h}m*q*}G=DzfiAqB0{b+l%oK=hwtn zJ--w~bLZ)@bGp3$iN>oCd(RxeaE_8&j94XI_3N$kSRVw#wPTF=pX(B5R|Yq{wZ9_{ zol$FvD>F4JH8Ok36pkwbCclus%!Y@AJnF!}VTp$FKw}(wrBwj8S2wlRo|Q4Q6NNN} ze;Z?*tG|)gRB@u>B~uCuH#tj2JEvl{@dP=3R!}k|u00@DanegVU4sIV&AC74*uVx} zhO?68mPVet>KwB7P~HaV@?5v;YB+!1!~qvnQ!uH+N}iA4%F}i$#pV#F8xGwPbSq1+YprB{8eOi;^QzcucVXyvOK&cFponTEW za)U%H+<-!t&E;Y>!FF5;-pi*h@QpCuS_s(^d7DNS1VL7VKh@amZ>_j;n>5V zgw+u~S5gfaq4zoA%#9p|TC(v48Zfu>jVmAcLWe$Ju1aWUr*Tf@5Ajr;j?KRGGo!tGUJ!9k}p9PKP;uf=iG-pM}t>UrJ-^nCB#bLcA0bmZdd;IQr!WWDc>UC%1ROR04t z-g!>S{rwK;!6d>`{o^`lek}IABTo=g**$W$jB1F>;~_#K8<7plVNEZS2xTIISA5JF zDA^RDybZyeihPn>(#51@`5c;8Ntkheiit@mi;SYbQss_BVc6S8mPh1Pe!|rAOeIyK zf`7+eH59 zu1{H4-@fJdannKh!39Tf_PSWgszhmqU&>j`Lo7UroCYz(^(h~L6!*EOHdWUfZ- z&eP61#A(*R$opbPIC0&ti6p;J+GuKptI(g<#faXIZf)wqqc*f&dTDFh9g`~x*O&yv zfaiwW%dFv}OA_7w9_AamEk*ZN-&A0vBg&WOHIfMZiuadRHL*usxe`Pwrj=e?=i*>} z94aCfVbYeZODw{eR{N0p%`})8sV83$BKLoN=_m*e-Ip(TAlkV z7e<=!8_Aj~mgwyo>|64)w%7;b8Cg8PU#nyq${?{u9pLx($WVG*m228DwClpb20&ZfH1c1Jf?)XuzET%8q zvWHBj)4k#TgHAglsHd);nS+E3;v1c6>xglhFA5N4M~U$~88`cIpZb?y3}g!=CKPBQ zOQ#sajh)++KbhLM2jzkQCGo9O&r@A?vT&raP>m`*&nwVjfVD;qEW)`-Mqzm(X#B;XvF;IfAV!z&b@ZQa= zMNSK-)8T$4rNT)&F;k`@<7|x5QxGPFGv>4zf{}D>L~s;4%*!oC@8ibu0FP2Mb)u>` z-AUh481BCw)0oLbb2*ZOIY$Cvq`M@45?qJavZmn}CO%STrh)jap^MM;mx|My^OP## zqz4vsGwCz7%U>=fkg!$Zz3_M!;|ps3;Ys>0iok{KLwBz{wNy@QK=` z3a9VFebB^7atWAR;=rVhU$uRypH*U)aLyfM<-sSfhE1${uF<-KSEkByq(CE>4K+)F zzfdzPli!hDCr=Wg}0jd;AiI9PY5PlqU)K{HfsMjHsdip4*)EgHVY_MC*f;l2^~K(QrH?KW?kK+L zAkrDHl~!n1*Q>SPeN=-bRotHqhNk5AA;OT>G1)KDrwyXEnZwgOk37O?+*Qvl$S|MK zVP~{udLja|>PEv5i0BMy6uh^1Z*2;L}X}Qb z`WBCOUHV;5T0#r@vXe*4COk``mh@IqiVB5*8nn%KAzC{Hl~mgi6je|LOUf;CiM;H> zyZkvI2*eSIKZR%ujPml-X0f_`K8x>%mPiRAP+=rT6!$*{TbnrWVIn`;Qk?|*R+l1A zj4&uxgQvNE_b4xvB_e@}1v{wF$eR7N@`xt&xcB9LW>%r!4_paF2QboHmcCpT_`dOH zxYt`CLm~NsC#J~4HSebXvvIl&MC%4(KTc*ma|qB(naev`vZ`=4h(0MILUL`{x^cb~ z!A5S0JbGVtSIf1}m@TRJB9$6iXV;$J?_SL{gB<^qmQrPUqBgIfXT7s6z5z2C&Mn(@ z-zBv%W86Ucuw*r&F2V=KBS%g4gx4~F!rWSg;btGJE?3@m zv_`c7KsUYQ>qF-G!iiNelN_$aMXHFTp;xpg_F=5Ew^qaq>H%09IEec2SFhi_18t3%JU935(XIvhM+Gi+J!$;g%E7nQUellou;(Jk?fG`;kx_4&bsgsj zo)n{^MZ!Gqa_kou8nLQ27v5m9x)7UZ;-bFL84i95+}wo5@K_jaU9Opr7`=8e@h|_J9P>W4YZYn%+ZkB5-+%-*chc5ez zSka1i=kH}Dt1*Z|HNwETud9OWx`MkLbIQn=6Ma$}9w7DxgRC%N@m9Kn1EvZyQwkif z>yAnz6W*ndSA#h1N|F`fJVyS(`N4DF8x=p!!1ItV6e>`lRHX zbh35bki5>LEGlHPvoGS>jmCu*l3Pl1CoAsB&KoWN(Sdi-N-1B1f~t;uwS`jUlJ*o5)n_(y zFfZb7P3~tk2h>f1ub@VUa#qQwGLk2FY^k3W`;~hlKbm^ApTJ5M(fmZ zZCILZ5)nD^N4y7$o7&Ivb^_LLeIRe}pg@j|YSc07h~kOZDSi7=kqky~oA(ovZz)xl zUTvH!#)Fc4EL;)E?C%j1sxnY}Nlc))@kcV@E3_ZfSPYLcgMV9Nz1^&_oVSU%YVKjL z3R#9_bk+OhFwKJx9lES3IDy+040|^iV^@|g<^26KojFDUf}4VM_qxpkCs_~#2JA#8 zbc|ah#U;|&{Yk~a(|7%3M9L@fhrp2eSz%!7eaEL{s$c9?#2t-fIBC(TJ5Xr7_5N9`;Qhrf|9%Iz?aN>9 zFZ1@HejeQfH2-CAh3JA;5+NEh zN33G=tWNbTdis5Z^!4rl)_zv~o2<3W>8e`$ba!@?mj524Y?Sq&Xh!vD*Gj0p*P9aJ z3xj#vcqSjxi&q6k*6MZM@CVuyz z?1cN+dsd*vV0aCR#=CW4mH(c%$BR4nE}YZJn%1QiOd`lROwsU2Ijyu}ep@J;=GZ5{ z_*JPJQ=6LJdBZ9LoANLL%nIr_0;I7sAI_i>rPrBnO&m6zVo;VdzuYX%{;qzhQ680D|a~D z5|*$mBcvVLE{ew37z{As;Ar)hck&M#;KwJ+s$6%6b-6nW+4o8hU zhl|nx8(;X`nMK#X`GRl~6(9qdPt5PX((&uw_@uDJSNDl8!7vt3RLeIOAYYITTseE!%>sG1E#cb=gzrh*1sDEWu;QJde9hguGf~iZNN_{zj zz&z|l9Un*vDWh*Kr@uPx@Rv2isiX{(HETyma-lVN_Ay)#y}(^!$4Sm&;uKjSXm$>k zQRl&jr+&TZ+yGhk8P5#M-L#^iqu%DbTBhr*w}uXiR6*+H5?W07S&9F!`X3cWuJmT= z6#+S%N(*hRn^}jC78GPRgMgW?XhiP;MQRR^WlYxkQo#r#JBOjeCE`105U1H8^@qUf zt7%jK>-E8KpyRE@CF7hnlX#N>_hNSyTw3LFG+i$G@gRmS#b^{xPv0s{ie*?hVhc++ zx+}46Cx1c@`p|^kZLP@^`1a2|>B5?tOvZyI&JND*BD=AHQSEUX_ik-~aT<9I<- zy^-g$vEJ35I#u#A>q@*pp=v_kV~;lk%!02)SZ{<`2fTP_1{?~l=B8HwbSP3j+EhP} zf|vF9kC(*avC&&DZxV9(+{2kszjgWXn=UU|!+wD2EhHe1s1X;ZVzf0g4a_by9ue)} zBu2eAZHtHGw;=G)?KLNBuB^x0y~*v7OqZ_K%s`3pin#wHD^48-WhjkZuE}OzQZ|F? zs`vJ7FT`+CZvZT?@6d9ag#~Z`?&=BpC%YyzIEu0i{L9ohG5xPYQjQ^PVeD@wzEs_7 zQsyu!w6eP@hx#_O=n0&D9IX3C#8;yw3w-ApUIqqRXgpa;F1dGfTo_G00AR{gSLt1T zB!ECvI8?1NR0)>ZA7yP#cu+UPL53j}Si<9tw|C$$`L|nR@$6s@? z8UfeHnj($B0?KYZ+Sc2Y46*Z1>7c10Q3h0o}dZ`v$S{Lp^P{zjpA(A#qcW7M<^@h7>5irRHL^ZrquAMzA)>@hq2=Ln6ElW%jN2yc^^% zBK35%{jNeBpA%u9Is|bH09$OelPaxfoV8s6>zi!5T@M%8xTi-3n;dDoT zI9+C1eRCjO2}+O}r{T6#gKC;V9kh8M)@$}t`EzIjy$-a?OgK-s82LJZBQ1o`5bTHVKX_J=^ol3Ut;p-Gc9!K4d>uIlVwndEW|!PKuElLEQoZUlQ?p~=A8Sn+`>*P$ zB@w|9t5F5|mS)0zyj+dz#(}`92%svJ-rX;SdTe7e(4Z%31s`EtSfAnDaC8KyiB7i4 zQ3=+5NWR#_b59-DM6PD@ed@+}apZU=LSVU#!i}6R;ex&bjPAxcpM*n+M3!DP!%RUh$1) zn}}-&S6p4q;J+w~myk?*6@60e9YKOBP}H(_uD%GWMJLDfjnxw`0EcB)-i5!5KRAKt zt6p7@puSa2c(I$NVqnfyHSI6b@%R~juC&FoNrQxyn2h^U1Qp?@#a@6b&^pjPCK$Czu2VoM%JK4~?(*}5)wfRHAMdHIt0)7WC|~Dmoc&#T zVF+p;Dj!_4a|Gj6LWMp65xsYX-cwE}_Nwznkwk)@)c^40{k z0Y7MT2nHCX{sbKV9szr{Z6c|SNrc|Hz-<$tbJZ*0AYq^;uH*-JzV_m54U9AuMk?63 zp;k1W*TB=nQcr`cmma@8B~;v>ZzbM$`Xl3ksFst8uHXDQrg~{0{A6;)oCp0hQS?{e zUHK&VoRIdD&_pKz-I7KPifF@)ftN13+qxn-d;z&FO2^JFTBj{c1U;r&2bvVo5(Cr) za5QB%Uhs>AW#|%1@1sUK4E0k8T!r`Watr+hvJDC#j>a0f6bG`G=75C&LtO^;18i69 z1iLlu_MjMPI7@ZE%jW(aQ2WXakgFE_&Y!%8sy||N5R`5AS+_Sc znz*=!f)ddMfbn{tB2U0FoV#cz;p%?T5DheWg?Z%)qZr*wNK-MWdSj)UV(Sf|AHBtP zwC?lo?eqF(01g0Dc0stPb@ThyYn5Q+MTRBx#oeNQn+Dg{>Ji7KMbLVyrrvn#c($%F z%SfqE`nfRO+w(czi|=_4T@B;vWpfHm{63bNU~C8)X?4|0k{c+!>Kc-kl=?zU@vHbn^{hE^1y|o<-5s)_bZ7Q=SO<2Xdrz{R`toTrNUV!=5 z>0Lt}dQuG_1pOSl7KpNrU@$bnvUB=)CJ|;@Y;2tWE5Uow%T;xk@#cm|AlUE@{HVPu zc!PIJm6f;WVNV~W@cw-fS9VS_!|%Wn#>~_Qt*+h3{=zK={mX3NgT}&I0z=;C#dXic zl*$P?f3|J?wMp|_82GzmZ0GL>gsT|5s_@0XR)iwJ$bk6T5z}NsVCbKZEbr|2wIj3- zfXezS|76KnkyZ_<+(72nlF&V;f#sj;BQPBzPlo0vJmk8t_V?{j;L;2K{5F3t5fs6t z_o^z7|FvbT#u*&9nyan)U9Panij=|T$@@uZ~bs7zK-A!L;u;Du{oiy)PXAH z$e)d!a_FF1w+YhJZ9}*&uyOtxHS975bxYqr*?g6oOea4$@a3QgGb7)+WSzCy0iXb?oGIQjKVFz21_?o5NEoSZue~Y6b zC&Ayjtgyd5sYH8lZ|DD7fr^I?%4er;Isj2e{wpBr^wQJ|mS3!aM*ycg8d6mJ(BH%J z%|z<4U1|zpH-7G5ZHCO~_iOL|Zbp!uoihT5)Xp8lb|k=DHfKx{>8bxcu{S=i3%11_ z;R1jED~0%Fjz9hfnt2hh^KKKj1_SZJ;2@U8YHn1rah}}O@?qz%VKpo?;WGbgC2P%5 z<`33%d|8ew;&DIyD6q6nCSZBkb?dDlEpZEc?YRam2ygyB_Ne|k9;iCEO$R=u*!e4J zOBC$zO>jh}g_Z1QJMf$q3JlWsmjAxw_v><_;eYsKKb&ig2XxeO4L^C%zGI*jA3fC* z`%#Ju@2*z;3g51@t7Sgq*P6g#MsVL6^n`xvo4*?XuY&%y|FFjex>E_;waIZkho%1& z1by?VrmB!nN&agCqA3{h+4*KN%QT5VIJ3h4@lt#E-xo%A>x}+>17a5p{G4&=UmJ{X z>Lk)=oq2Ipu@?r`ZSOSsdGJYKvi3y>VokP&DYw(X*nmI9vbOR3)|HR!Ui6Y|{iMD1 z_P&PT1xqzE@ak!RSMn*E``i;#v+vAOf`FLhA9?E^DGpn>l^MNPm260c=2oPgWQQ_?JdXcuj1PDy=Z4WM z_1}7MHp?yj@rPvY6k><}_uu!&f}tdif5>)z z9(!&)_&G+cj_uZ4!LbZ@s1#WVK2eqi7vpyO(fL9L7)!L4LXp+Mt@pFdu8}d8v1_Dt zj^YI5w)Uw016JM8r-HbGe-Jz?llBfQ{_3oYen(~%CD)e_X-!Vng z-P>DRqiPBSe_+Dr0OywUh|S)DK?%fmm;c><(7aj|zdM+2orvB>Ek{WRmHSokx%iBj<7FmZ|`gwSu#U^#96hp zZNCi<`*oGTe|u_r;^(qpu*%mxCzdILbw9AeIR}{NubY}%M`w4V$ZZ<+x4h@a5pPyN zZ2PBIz33h#?%ula+2Ghu*Xq(KRhnP7>Kab@gRRkW>rY?7gLd+1|5l!tp0R_`&D+jn z>&0QL;Hd&9^Oh!|-*dQ}|F1#Xo;%wmPZ?ZXEK~n^$$wO0Td%zvJVxI4(r5au3$If{ zMY5Tl-JV3qdn-2X2z$2MLTu|#4&XtL*fM_i81RDD^cNK*<+h%h4m~yU&z@B<<_1#y zfr!5*eQfg{#5@z?@iO`yQ1hUM9y}(Y=GeWhz@IDlb*VHE+N)SQ3^m$ zwfIA#nj5k<^S@i0!P&1VcY}ACbpO_D&us^f;XB6|z4g`;OyCxr2sw4EL-vKUrJUUj z(Ii`yA75yXFnEx|9roYbhGHnVcqzNKj*=ZbHC6OL%pgk=C^z$Bp8Xn<^%Xkg0L!m? zlr#S0DE~2N?tl3JJcjKsz1r4WyD)%Tz*>J`Kbc!qrhrHC)GG~%EuXlP1DJ_a9@9Vi z#-GniQ~?*S{n3wqeHjFv3Of?mVjrLZ0zr@3r(cyu%^~Iz{@$T?-KgIh>P{Ogyc+9h#XJWQ$nMdG3M`Cpue*0d>G{DZ^(y^`eP&bvqQ`18} zj22&pN|lL}yT8hD(_r8?Y-hfX%lz%`{q@Mx$AGJ+-+75`%P_ze_*ON)JbFKmhG)3U z2DR&_BU-lp^bR~|k9sEEZ{KTw8nE#Gxvf)90d9XuOXUs~e;gze=Ux8oe*W!#{#Exg zcWOFZmSIib#GgN)MjN<~s>t_M&(xV|*?yH}n*TFB(UdBO!p~WNe|se$?(#p|E8W!j z+N0jC9&Jbcp~>mNF}+&hs>z_u2xTMICI8Nj=>FTXqsfE>Ui^L9b+&s;ci1%7AO;d& zxBA`_Kk^d{ln%)LOb6oUK|a6`UhyjC*`Gg`S?$~pvVv`x6Ti)N6ptBzz-ueOxi!VI zgBhfi=W>T`ZGK46|KEN{Qw06GV`_4Bkwg}vTcfoV@7}xBLO84rUih1Baq@_{EVms0 zn*ycEBiGFBhEnd{M4+}37Zj)qnzu5^|Co&HCWFi=qeDk>E3p#+SG&QAB)D9^-Hm+GdINGJC_ByZJ# zH=yz`?Egl2xR_kCMB=DZSW8u&;q%cv$YJEXs^Ib80TBJkz=JM4lU=>;mJEifW*jJ# zRorz?eP|Qgp9V!jQ%= zI;)j&8#4*6>uc3~>u)qDOgmK~f0&5kx24kSzrq_7Sl zu9G%atAm3@jBgLiXbX1WS#frozui;`!hG(Xlc?Z_FdxwJ`d2X)-9Hs+)|J)PpHt=G z2YqJw>iYaV{XKLpywdtH`{Z#Dq_Fq=4A3tez{|m5P|&v z=C+B$nQ7`s!@{6#zT&J>MeVrfU2n6ZOWVM~*w0O?V~|Rf&yR-1EhIjluVM!5REqjI z%?XxoJe-W(Ji=oD(Ed;Xpldb;Z?M1h5VV~&cyks9@S=ku%7ruaB=6ESN1y~kS#=(+ zs{{K~j12*GEaqeGtUM5tHW374T~+=rnX`liuzEpx2Cy*>Lc_i@K*aVCP%?3u0sjZ# zLW-pKuw)R>^+3DY#a0&>e&$_k3sS!*Oj_8Ib7 z4d2K!u!66pyGz;Jjb(jS6^qO!lao5zlXA4K8O50qXqq!A@Ie zcNFz}@$e?Y4{SX1TtH7ei~HkpMYxf}JBHHog?ytWv3ID1K}ViI>ZjFlFxoRkTQ&`m z@i=1Wf0pqB_C2788Lt8fn6uC>&du2!(qiw7+t0Zq$2xYMgJ6;?_1XhPW?v~B4vb{8 zbrS&z>!r=~A#aIOx%_mc88qC&!t;cSRZf(S+Dh<28Z$dKbIcw~;FF5o=Ncx*?g8R~me1C_oF-i0h);^am;B9s$&sbNnKdwv;`fRO>K@N_I&OM(nK6pX{4$Aq z{$f=V@9H}c0xY6X!mp#a!DNb=7UO26p_>j)Ly$O#Y4it9vmf$sKWBRW0<>+PDAG%c z;N9;$UoKtAHp*mXbP+;wE`S#;&QVl%@4rK->c#E97%` ztSd*RU$CQmZoj~fOAgdYsnp1Q@47BPvFx%CG%3EN3ocaz0ol~?fyz2+T!Z{g8Bs_ zhxLoqvz~skGy`@8XlGAzz9YQk#jooF-Idz3ndjdNblUTx*RIS?Y|7w;(B4=vt(~f;X#)SIOc~uxk$Y(BMQQ^5Ur1{nypTX98XAdpc2{;ZNd3uBPZBVSkLIGrJ zTdrpKk&1Qrzyh3nut`UTNXY&qsPtDZvi_p;*UH-aA zrH;F-3svh=Dtf@eml+59u@%CjBqkb*N`~pC|2P*7EauH^d$ckzmKf0g`<=yPmMZ$K zK%7f|<0}qSFb*mNQ3tgvSHS97eM6UC3s0rnFy?PqatFNxkL;WlR@0i^sS0R-Sp~Q^ zIl~1PXnAGh^pDe#Y}%~k%B9hmU?3nceI*82`!s!~94M?GY79)c>I2x`G6o;QfJULL zBTL{c3$J{I2B8DTr&OuB*Oe5v!a`HIJR~;(F~r(al61x=LvpvvhOMm^ZNK}RqO`Pj z>S(|CO{wp6J7LtehmKyKX_dU>?gOHX2O8A;+d+#}vdFB4oBgxG51R7;$=Z3~jHazB;Dv496 z-iKthsr@ODEGzK`%pb=$3YOrOzlcAD62X%0CWlq;trEI0d7zNbJx(uA%xI}0S529A5H^E4=bakpkc|9?cf7i39eyWi4@ zH~G!J4oKftUzAf{*8DO2h{uhrT#k(7Dj@C<_b8f*4*xt20(!yz#lXmSn&&MemEv)|J#sut6LOio6SB zG{E@~Os(B4U}|na@3nhHTU!8lNi%3d<)@z0Uu|eGjIX)9A1JL&j=@)>o{O$T>#ue1 z7`a*T!P4A69-}=rxsvJu8LnJLjxZbjq_AwLTmv929EP~Cd@?+~WJpful2*%mr~Rvq zaeSqY6~*XCl8N7^L6C2~UhNInus7&!>Gw|4u)h~cGK?9%D~1gi@6@H(zo#jFqSB>r zv*RUA%tl?MpKOt(TcRVbh$bz1$r>EcweqbS?==I7ylW6(?RcIX!8fR;74K8F`0>>` zp>B!(1_EOQ0>PVq5(uK1_vC3(&UUaWlzIXEQwq}n_*KwgyZ(JNNp_HbeK}{t!wO>}QdDE(nH zepb?So6mo zO~~|?MeUaN9gQhQ+AG2V>QjI~F;s-N8wa0$!SFho2QJw|6cLYTs8ChRqR6-O4HmvO z87Li>^r1?6%8o{}!~;!~8H*Q-nyTa`VYs$qRSC%2gTQW!kq@5N$o)KMTQ+@r4~h&} zo(9D|;n;*B^x_-dwRz&mY^uDmAIUx5}0HMnZ6%;fy5-*oJIapnNUpGiAt>FH; zB)dL~|7gc;W18nH(|J9sIPA21+)ADQV(&^x{FC$UU|65S&|Lll?RJQ2%tCMk+(@oq zJhvqKiHPY)h*`Vag|$jbq{o}8-n>Jk#@=x#Gl#(rt;_qMIfl>sOo}6|#k$7@a>`!B z8da;vo#!bS_nVE)_Pli_VWq6Xr%;-rMH3^e@Pa)DBjRnM-KH?Neb&)}1xT`JgB^_9 z(fhlNeEs1mpu+gAtWzYdPzK%evPPe2qSEAuH>H`TJiN`S9sJZmI`fr)7#Z3? zYq0C?>oACDriTt*_W~R12zvuSx{YRTxyI1!v}|0gCS7t6KVNx+lDVGYUFzI=D#}pP z5Tr3#4|@@N-c&J;_k+E1S(k}Sb&bD{PA?e6ecK!@THDjRViB+ePIwh#(x>3F5TroJdt{ zKN_Xvj)od=E7vB()P~1XtEZo zUU8!YEkx)TyIV+R9!6JA|11?cen1`6}tyFZPou>LX`oUY?o!eiX=pmQGp_gCx4

    1. u zP7(0+BjZc6<|r&SYRO&`fHtt5Kl%jkIOI4MCwWH_zP{OR4 zYh(8PdJhSz{)R~XsncW|?~$Fs(R47X!ggaxh1zU>TY2p?*WRxPBS3BU^8$HL{tiRp zk|eK`4V%Xv%K6b7y3NLr?xoVSY#0eFoAmyc%fB&!c5jaHmPd!kw;VOJGw578AC?R_ zweGIP7GzJA~fBX^~sd-5!b5y?ifR8#ioKlX!soqwR zK5Xb3`lknP90e>PQyDnlK4+06#S1A8ezNgjIv)b!68~fUz-n^SowlM@P#u(4KY6-h zk!FG8RHF=2Nx9%+eEL%m|8o{#n=`qa<@K85O~C0+=$A98FFiK8`t5xHN13+#i`2v9 ztd&{(YK2Xir5%%N&XC+0l=>^)#Mp)Ml!ci*lKE24b?&IkaXVf}+fAxIQ1qb#SZ?@5 zCtH$ya{ODHGu6OkF{6QA7hkzfb~+|p6d2IXDixZrL!>&I?l3CDRz;z@f*QeJ z%S_EFOK7*lh|t8o-gfbefQlCD)>heud9@6=d2XOnGZMYr+1*2mfYFeXaD_jOBo&+< z_M|W0vFit-f6U+V_3*=ogA#1Qs-tw~5zAvUz!?)A^kF?E7llztgq|Wp@0cZ+{5t88 zD?%x}EezfonPPei6RNfn(wmAYdp%H)a65e1&Kp}-mcZ7!^jaAweauQ;er>M()38|a zs+N@8d=`^DT(9o@2H2}}w(u10x?@<$WD)*Qbi1W@ccp9H$|nd(bG)TH3&1#a@B624 zj|xo9RyV-vs|}uVw_9N%^AWB0Q6`HY_x9uVN8<$3^O~|wvfr^m8sF%IiF05^)jP$N z=Q7BZRbx$j=?)el*LCZenu$7d!>T6BU*eD5Z+GWgD7lX4KIjmJyxy;1;xU$7$1Ypl z6lc94N^6iFi$&sk#auIRX18@hzWFTf+c@qn)OWB@y=Ay8(mSL6ZWk#X=Qv>ED#Xf92aSh7uGQ>J41ulQdmo1BQ+MTH-P%>JZ^`||m~jlaF`an@6R5AE4R6uA z_a8P%Brh!i&|c6W%hmXstIq-m0BYZi0h^5!c675KQXB;Ce?bUSAppiP16%g~-u+8l zImXu`JJ`t>cjcp`_HwYIN_*>A*ZE|noZIXByr&=4CtkHCW&r*-{G0&a$V(=P3u|v( zmyUbrj?f2_wUx(#`)9g+mhk2I4?wa{?EH=UsI=#;!rsUR9Do>g?ex@XU%3uHCUP!@&LzFZV4$^#wA0RNN3XN-b+uRt zRD{kg1lwJq>RsJ5S?moPzxBrBQ(8Wn6dH(!nN`aw;YP}ZMW&2*YL$A>w_y8>% zBB*0+CcI(`Ij7bhDO}^+O$$?S?f4;|ung?G0x+iFVCGQW*6#OceC{Q>nQ1w?GsFZc zZtTv*ZQ%(V>RA|kp^x-j-@!(qs3@jqo&JWJ3(rcETGC`Y37F6N0$k5HYXZwKO6KN% z9{BZ}?(I^pYn}oJ2Tot;KJCVeI12yaYETLv4)7Kc@_HpHuk^+H>kYi@m>TFXTBotf$ z+|MTro__YtgOsPXrOza&p05_No%Ubo`%^YMT~WW&QzNDZQJ6GV@$6`X1nMo}5%N){ zMFHmNR6d1@Ah>FxTcul7xYMWa+f7R?l$^EK!S*3x?lV=MG~5?--ZRQ38`)UCE<2)DvALbTk{hmyTLa zEa|%DI!g~0$t>F5d{Fb2o(vKu3y@Oh#ucv)I8em9&x!&UYps8O&t^#e{s$P`=97>` z?cYzHd>}C*tWFO3aLId>px};ju23=$l(cQSIG8n$&q=5h?0hlUim6(KS6SYpp2|zhm~5;enx`O4 zrBTA^GTo6nU&7INZ^tA|IGps<0tdgX6GOcmGwss(0TIn--r7*MBXeqX=Hp36`#e`l zhfi=;*L^%<{QbdttAXYKQ3LFI&_ChS31{Br5=$AT`K;f%y}GbLSQc`R;BJJR;q4yy zkB<3HFnR5zVeH?!X;(7;Xje5kb~mP^lBTVE=B@bFH;(go?3vj?TVp0_q z0xyMnIJVEVw!IP9W{{nss(67`KtS)ZgB=eNMro~G^kT8IwkWTv-Jfo%BjCpN4g;hf z*dZ47+5*@IK*4PkC8bJSs)TOD>WGv2V)jL2wQng-rf0C|Y+?`6LLwEpqm0_1I3=I) z9Y!{MT7KZ(+Ee0(X>nfs#9$#p-61QSYB{wUHZM#iM9wzul__%fK@=e7 z_(>I-JQ+o(h#WB|0=0?Mj6v$z9WK6KRX2#lF*jwOjcyM+UK}{D0O>_SOMizN6xJOx zM8cFy79a^9qrDYVod@%qCrxnuH(Tl;*`>TtqC~`_cQCzlNmL~sMWpp32VPPx5zETx zXNS?tkhZoX1Z?aiLd!_~JChq?!_|=GQ~mB=?o8#RpYZ{M{WV|dq70q9hy;K>SMsGn z%MYiQe@^Pp@g3{HCnP^3Ge9sOkO%yGm(}!q$4bUI%Ax1q!9X?Jp){tWlH$^IZmjhX zPEl~VN=?DsfF;vK&(XGPYF6$}r?nSx(y7*fDv=&Aln%tU%)(<$uebMzuT_RS=y$Za zrWN;R$DY%Mo4_(o^U8S?2Bx$RBHs(%UOWusTXS_`SCOONe#&1Np1}z3*Ec>Tf<0lI zO~j1e;K28zwcAqVmDGvn4N?IlRJJ}VvLPxM(cQ2(f}?aSVfim8_#7MMss@U$636=_ z@G5AdzRsesj(OC(4;|#U@Cs{%Cm$dojLwWwzpa%bEV@_ z{fHO@K2|3h?2dj|NTg~GV3vprQy2#Xe8rr{*}ZaY9`Bj`Mss^x2UfYX>fU=uWM~Ky z5`*w`;TFA5^3>ylFIC|=m`(>6Rb+G-=#BN4DL`U6@g`|!y74;Sv0h&4r#cM06`q)X znsEXWy+f*JHYMTceIyz&H$^_ktyp>`Zg)WFgn% z+L`6UVY2gn$L^GCEuO(XgeRPZCq0okj?waTx?EIx{9}rIs0?Arj*f3En`~sb0i`0B4drd(>yeKH_=n*E9#L`Bw$%P5!+6zF z1p^cI3pj-5l#5z}!D?lT;n)Gi#sMpKbR)tbZWxFZ=Efrmc5vKe}N>I*5v*cu>l?aBv7NhoexgF{g7LB$$0ig#^MJ) zLX3+Tc1!b0>iDq^8_|D)umSSQCNE^}%sD_!@A{zC^9S~e5!u%xeBi7EfFn*5R|bJ{ zD}c^i9jCv(V^|m7-d7e$8)e=Ym8{mgxV|{dOiQj+ZSw1BM5e1gI5{6!RBx>a7raes z?nQtCS?POv=jkS7w!oEm*O-FJhkjbjs_+1m=bNs~!RG73cCe|?xf0|v?p6!cC z(Rz;$qhJ!j`Ln%uMITo}!J1}4e312rQtRv-FOjkTR$}BS6-J0M?BQ z+7vvruSoqM&_~UvP*FJf!3Rha3OSc%Tn{s_EkJ-)Kvi0#dD$2MYDnf`r5g5O&k#UW zd)NQP-g`#FxwdV|`~Ai7ATD+xn%B1rVkXcLK&L`x!iPth4&Fry|! z9iq3v7Bh@87!1ak@4Cr;-u*uB`+RGC|GppZpS_;F)_%BM<-E@GIFI8v1FDHT%HILW zN4!5hdw4IWEjIzJ&$-OHr=Xwu=>Z;gt~U|?M0hV~n0W=5j(yl3(y;VAXqwIq`T&K2 zbzQ&&$3ST2;o(fiH5}_-;9qsvN;)tlc=E4}n92YYERg$?Uy+bwo*l?9#mg5A*oAvy z8aqag5)KuvXpUw2|Md1}sH;k?z$EXl9GO1&G_lJp*35eMm2?;(oDA}IwHjKs9}aU) zv~Lp~T#xqF9yp)fSKp?gPJ9V^$2U{0a)+SNHu<$)Kc_?GHzljbMYZw2dbui^4nJ6T zt~r4|`guS_}J^8-Z z#v(gp(^z*f{P}ElW=d68ve@($^>i0D$#TT+uCC0&@D>qxnfg!hj9-8#0YT*%x@LI> zoDzL48%$(COF=`;+R!%fTGYm1vr;*w2WO9aBzyGAw@Y0aim;bMR!Xsm_ew81*$JuW z)@FYpBbgEDiUqKe_xndHk65}hxlcn0=5%>}=YuR6>lohgjE>_KL*=7%>DZ4K_y@AZ zIX;XZ(9W&z9LeyHH+x0KC!OHL_dVK2y9K;!Qp96)7RGyPlf11*0*MthYx!feO)#v5 z7#v0^jia5p-TRKawztyf2Pdix-N=d{XU8hiwn?74f6A4tXSR*B7lGVu+DwD1*{F8uF2njbaDN}G zb45X;<)F#4g2D5^5=r>X$yo1cgP4lBpUwJI`>o;g&p-VAf=#JsRm|G0=GNjniG!ay z%BPPpuJLhQG$psE`aBfw$D~#~{4|U+dZ#SBHFUXv*8~9W!*3nwEh10Ky8JbYy5BKP z^8V0gohI!b{_yajNcP?&8G`M0+d!!Mz*O7Gwvuvu%DpWw<)`wQTUnBL08*hc{b6bL z6nq6gbhH6;VDD((o0v?-ZGZ2q9niRPFU!;5?B~5%t!Z~aDsbn=I0cCI7VZ^ix&(Ur zywKSzmrfOy0_Ek;KxRO?x)HD$?QIc+-PF^5e!e2UGIy!qF=yeZ#C4dd>-F;N1wun8 z41~RUzXE@mTp1}V_6@*#(DOFUmyzim84&X7Zg$bH%-#Op>I2P^v42&e;9-v&1ZkL( z>Sg=Jd(%#NF*|Vm^ey)pR?eCIo;N;T|r~hbvOO| zL-E){dlLc1L4mk_tC6SHBc!|YJ>?Pb$d%SA(j;wVyj3_X(q zMOe0TC1`%X0m=HB%W+)Zn%&(gh#!ErC@ZU%WH>~F2|BfiLelT5f6HdIx94FJSv1^+w0 zL>0ZO-8DPJUc3%7Vt8Pk;Tn@=%!M9?zeB>bg)N?C`7_|8W0+^tVf( zBK1vj*N?8Y-zY%YOtn|f_qg5v#fP-OL=SB*9+_|dodb+5i}ofW%-@0n^qcfZjNz$X zAER?+a`^du_s4{4U}qDAkh4j;FkKYw=Iv=fbrJ8pIu$mC01YBy1J2nVY6x%wh}UQt z1PrbLQv@}|o?vB4*!qH;tLZ(t;Cg;yR6HQMd3l$C2W1VkwC(8_b6#m+nzx=(h|4SN zrBFrA4P`W}#F`BUdVflhW@WDh7Li9G$5K^N4o<~pZMxv}((zhGbmt2sZ9bJ+0-00$ z#5MV{3RQbnV%5ip?WQsjviylSqcN^C4qwfQSlG4kUW8-G!m{gkueGvgBXVWA;Zwzb z+7l8Q%CE0^GW*%~1S4p~+H$-~=-itn_*&mbuV3#nN}6nTYFwX@+9Zg}TiUXK>CzV# zZm@^m=>>!{uf?zpk4Ac~m6+B5npjQW1w-bwh=#o1GwM%W2jz~BZ;1Tj*Qr>3l|@mr zEY|o~Q8MIb_H4c==uc3<(l!kg-Cj2#dm7^`o9)K7R#PB&YSrLoSxuFxMcy$z`g?M)7^z(W}0wI zbh?s6P7c!c_Qkbh+@!?>+k%S_^J59$d)Fp==}v60Pdoz;2l zlj;l3i8h!ch(_AlC00dG+N(*)kwLLq z#MY3T`}c?pKS7yvk3;Ab;4jN?*yMFUdR<-CyHzyvT+jtartmHr`=qyAzx zP^Z4qngO184|h|*L|ukUxvHPluhnigXa~Hi()wN;5F-tmXXW;EV%gDQpNQ9kyg$wN zUZ-sk*?)OK4O-+!1!Z0K_SX{jvY$_m=rCM-Sf3zGI;;B-1$tt~2zkuL(fFGqu#q!= zxB}>MVRk&{I@*t37MS5$+;20_d^Abip%9hXXF8db%VbTOlY~p)#!4YL`jp|on5IST z#Bvy#9~ecTwRZ?afWkt#Q=ARx0Il14BXSMxFW;&;$re5r<<((Yp~G-kdpff-+#ZYn z)ZQz!oXzSxQ-K?eiTk8H6V0`EH9>fP}LV?Ha!?o%G z#Zv#q)$@4H`ryGDl&Yh`6@Tz@2{oo=FWs0YfhNV3{$ysmn}&0A2ioXAeVhlIIH<(g z-=c3X&G|JY{JQqcMQaqH{7(2CJN~I7=?jd<05w55H-XXZ#v>sq87qcf_-8uFw$8|$ zKknJ&x$OT26K1=`Ker{*bQgW;&&(8WLW379|B10wmNCdRmW-0LO_B_c2?<^uzm}61yyInzD zxi;b&u)xIjC|{+IM2bY9F6^v3>W!3VQC(Bz`Eb<1X2Qss-s-KQpL=rn!aUGPZDSr* z)&uuZ&*t+&p!cm8x}d&;+T>jq3ab*|TgclRZePSUHTBySUL4SCJ3bg&C(W#r-!513 zs_u3Y9(snLir@6qR$}dD;$Og0wmRUwOPpu9c_;JZX--9JO4G|VsBrRm!OR}K%TT#c zjUw3g5OSbhHwMn@u=?4j)_Dd7ht+Rw0+(Nk>PC@*ILIMx`oZe4`i39J0O-}ynInfM zDuhu6Rc{M!EkVzn^7bUFryl-Zeml?f4Yu>D@(_1-Aw8D)#<#m5CCbxs%RMEH3;r_~7ta{!Fa-^rXHjmpft3{7h1p>Q&`=sb(jwD+jRD_hC zmEY~kZ%JWhhA^jm`=`&^mCEc533Z%=j@tK6C2L3QM%=b>c^4FgKdHYe?Hq)=!%6wMqU4riFgJ3h+cvT8D}A7#j^T&TX|#t0FJy%fbeX-A(Ts2;49#qjNZE&8o0e zmts43JaX6Hc%VbQ*_xo3PSBIK8n{jxXe(OScGm}I=6>#r;qK0vTkS0?xpQ39-R{|R zv%)Uku_{^~IoH;U)X-r_2Bkd=j|Sr+M8kYEB;;vh?J=NcQ$Mw~xrm@5o8N$c=#Bie zMJn>)&=W6Ez+#W=YkXW z3edJ+9}EO6y)OMU8_VKOh8>q?Fh|kOV2$Hj$=2EDP5^}@?qEPC5`od=#5i)Do~nXP z#4z1dQv~OuNYmKKyT%a^-@PsW@bDLD0+yk})F5%+)4A&Q_`8AEph*Z#Fp>-I7Ja4$ z7>zL|fC9)=^tJd5&O^Bkybm1c70v{@0r^5|TnL!jXLH%>=m?*Z?*@I#Q4krlG)5*2 zVznIq&L}74UD1=X5hf<@=0ft}xhHul0q~w&OlG)toH0&ndB4 z8-3cgEoGTwT4EaykxjozT7nUqEW*litVLv4irb4JBH7on)Z7fHIWFxbCH+F6X!o^XA&)UA% z`uJlz+xqvIGH)QJjI)k(i8{oT(fbdr(%Yx_Hn2{OhoS?9q>aP1TD0rE{^kPIUuRYP zV1&-iNwU0ts!};0bzeeg7z@xIirT9zdlirJ_x5>K@-%K?U?<*Bz2TN9duc@a1xwLm zGaJi_s+EttsUw@oolC@(H>YmoagVN+jH}m&R#km+gm_JFpw!%x;jba#re$EN++y5p zkS)VG1KD+0H9cK$badK_*S4TNBJ$C9l#LW&FyrKr`6CA0xthkq zx+#OI=uPV^K!bt`$@{>gdm+!@wReAr%cBCod;DN*Qs$y-nn-#)RC#f5KJyjaw?^ zi`2AHyqCBL;@SnluS1pv9je{S_qa&4Pu_9>ds`U>pSdQ zOVu@!-ZSEi0!k*|_l?Ex!jFI&zwkeBBLe8ykA4N*7x^Hcvlm>zATzxkdbh)R3SJSZ z!u}xnb(J1Bj?P=O&TI=30ia896-bZ9H<+-H4#Z^|wOQV@pA2m1zixyeHbTz$3;FIy zS!H?ZI+jvFjUrk@qY|wnJA4z*z9kWN#%gVOaiWo?eVTH5>M=u@RDLit)>i5JP5b?e z)3R~QT`_vL$x>E%T8_P*z{yuM%s7$rVs)@L4Y9s>V6Zr+hJzX$|M@*PD{uNCrNp=_VV!7)1N{!5=?jBZBA_*7=GCJ zIfLHOwP9Ry@5u4<(5V={gPu4HvW}BPAkUfMDssnu`iY7&-CjLqwaeV&)^DdvRat)#*}M)x&}-g@@s(_ z>24gE6B&oR1Ljibw;CqV4@UtO6Ak&w1d)Iutfmz;T{*mho{jbvWCXuqZ zxOw2V&l~LYSn~l3GFk9Ar-?EE^sjWXZ5A>J?Hj8#EB*NK2k zHOlXOf_5#Y3ecC7eVu_ypmR;p!gnW-9Jnx2VGW9N>vb^DqJY^X0ugyoaKmx1Fufhj zP+RblpL88AFs|06`gzqVE`Q@FfiTN=#P61Jd^Vndi_1E9vPPg58B9Bd6>pryr`ICk z9kw4|q+Rl3bQS46>zk3huEaacOWWpj9e*|uri2eFiWoQ-Mg+W^7S$}@)ggD_V7=7H zXKn;QcybP0dMoKj3T;_sK>^TbFh!HDX2-`NYN(Keq5)5!b1+8fk~y~94`0SejwkzQ zb(hHRC`50X7q!5D;(QO<^Sbvw$gPsVy#7T};4%SRE+4wwaTXf!TBE7Wmu19uq+SDx zHo@Q9lceRS7_qq5kUna5 z0=s^0JbV3u_ufN=F-U6~puybB{$$}?*tNbh5}W&t-IH#c+-n{U{3GBdgDx>Ogg*lg z`?P?bJS1$61q36kRiO9Wnw!jSzFWw+kAe@?B3dUxXBebU|H~PMs#vqv^a6-!lxaQc z#`m7xabGh@0EEEbP3V0tfG})W9IL*UoRZXQ<_0>3PXk_3@c4r!BuY0@*k^Kr>)@eA zRA!37dbINZn9d+uxtB(L76JEXn&6h}2>otAdHv77y8#)k1aOVRt5>%Z=E2nX$FFau z*TX4X?)OUc^-Dy z5MCQ~n-{~UR3E`nr%el}{kaZclt~`4de^osK$?C&wIV$){1ljDH>kiyP|rJ6b$wUA zkN>jyUC8J_69> zfJNCaGJSVvxdOHrbk{Kmza>1*z|p^RVq*NBct^1wI;Vd`1MssQv(-?P5EC$I!+XiLy@w<`z2Hgk+7&`HjNY+Aqg z!Hn2$P|cnjY*mRaW-4m!7?zqx_jt#azN*@tvUpGQRBv_f^u1zIROTuq zryIg`Bu35WY5<*P82ErdZEsDaFKGbnaK4>F(9^3?6BR#7$PemP-~Ih{stog~;vZ`D z!l8TWkdFPv{84`Ik87qoc3x4eCVlT5o#*@tq$kAy-`!LpBC8jx=0Apt8T{;?k>1-6 zC1^i#^$Ci6soMTeh1YCm`N6^1At5@8*;?~g)@*CbkKh#1-h5y0mS~%TcDHcmp5I(R z5aXb-DWi`#4;YY|H~;@~Dntt1=lbp1VniF+Pl9q`2;`-|1|-Fu755w^V<7LrN3Ypw<=>!NsYeI8wN+jAFPeN^}HbMto@x4o$Ii|+I` zyXvXQIYlB|v)q29{5=1=#l2OV25c(h2szQ~;*dsX{)@QZvvN-&*4z`C5IDb0!k7jZ z%$)@v#k4)iZ>7&T)8tS6geX0NJ9KU0Xl|)ABz=(SQF9$4)Kf)+Sh1VCAq& z3omKx4Jd@ygfjD*Seit_p0fh|WeQ&4njt_{?eE+wKikX0G=2GZba4g?-}GAQx1r^~ zFAj#q*WKwjQQta$J5sXqM==z1O(|t%nYWqO5-#uk{dH$R^cPn}r-J6XfG$wE{fFEA z?`xiB88A>I-3Bvr=wr?_t?G-<3=yl`*+c@XtCd)3K$5clsaB z{iD`>w64|y1fN5Fde%eD%6xA&l>bERAour`UYK3}CcT$D{@ddobF*$|^XG@VxAq$4 zc!n51ny*e;fo~0AC6EK89aYBgrz=g)0L%l1?|X^*bCq{>#bS5)5WeTzeLAG3K2>`y zDJwZoC^N1lQ2zIwGX-zwmekMdyNN~@SAgZ1a%!HYo|36M9LoeUg|PyKE8sa+7x`Vc zbJEAyKPdKejPYCjB#h8SD9UZ5Hs^0?s-igs0%M`otZSf$dcE_2yMTd)CC&plsKsM( zv@$~+YK3|LE|8UAvfD!s(4Msfpq1exgto)R@9K8O^;)ai&x$X{yof&IiGDzYx*jI# z&YA0}L{wY{eWH#|Fgltbv(|c!L4Zc3{hel?qvU8qe_!D?NB}`;dUJ0vtIibKQSd#Z z)hnAh!XzQbli)9bRS2_&gA$M9-tU5wA;1!B{j@3HL6Q>L2&+OHuSaYr!w{!?4b4@( zb`$ARq1`GJFiK$Sz*RzSgva0I%P&2~&6;UZ#}+ZrwSAAAU!PV*j};IvhdY2js&UZ) zi-N~jDV88r(UPy_`~tLygcYT&nNLFuTt;ulfS5fww;BQ(Y*fI9-!=f-@N>Fbc5fSm z11yJ>Q(+&#W+zB>TJC`HUEgvBqC;+i^5gZF-$mIA6+-Cy+O6D|=2(8}1;ld%k!U%T zN*y|FyYn!sq9Jf;mq77U{Z!yzK+IER2ZlkqR-9-+0}6?Df=G>=b`Zjh0R|8a3tiG%scL6c$x9jyrdb` z!9em0wR=a0Ztv&-6OEI>RKm90d|_iTnEifQ9?;F^Pzw*SfRuHytv_BP#M%jHoDMXd z?H!5#$^C-_l4kv52OI8ePG!!sta;zqt7v_}X~2_6zXw&MDFx_|F>Mir;4@nzeBukZ zz%4QWw+O-@9{q+wgcv`UUx07TMxSzIT-`y^q zwi(5#Fv*ORPRjdO)H!*e(=3t1C`cMsIE*b}W`wuBiAV%>ZYY9Rz8K@bUZPEe1{SaH zd;@|FOaHquwM4(GLqG4J+mto&Cjzt_W7eim%rsJl6fiFapju7^O=rAGHm2a$I$1pT z?BPS%ZrjsPIoH7Lgz?fYqcp&A5OSYRFS>BY?(ys%M4NT$ZR^Kh@z#ff;k9J+MnK>n zOXp)5*P22r-$M!SvGZC-XB5Ho^F+lr9{d^5aj_3th3+X{6hGqVb%cdrN7l_kjqh+??>q9R4y}Cn-=a-xHOnSiTPSYFhA{lMxoVJ&n zt-)zD=$mG%LxWk4#gKvCPc2og4RAP&T*rYKjW}e^A~aUQB7TIhpvoERdC-rse(ikM zS5%1>Ch^!zn`BoAxg-Psh5}XKDkv4b9lwDcxNnDX{2NfWMx0EzYrP7&>EB@#@us1~ z0>O35X*>I!!U&FUG&sJ;&i^y+9V@%AxkF|RhBsbB!)laP-icJN{*2c1m?ptE4m`UintC%!B=OD4)VAW_*D%%SI7H4uEQ4 z$2q5qpzMBok)dSIQ^L{TYb=Kk@`134I^W-CmejEyx!10`$XJR-V0+`B5PUK9=%R3M zqAF+8R#$XL6DaWh5zGuj-}CP*nZ=P?1clw){yJYv1r;Ke%(op0K3u9cOdfh$RBY(r z^{FMDa>CVsBxk!om<-{s5xNRFH&|;bEZ@kt7ij}Lq}VSH$L6j1Rh|5pu6VcxbHjM) z{NR6XE&1y<`#SA9wq@N)6Q{KljU5od~$XkYMrws8Im;oQv!%Ci++Ky-eMVkJk1^%r_s# zBEc;nu)Ahq;N6?QL0=g$IO#q+bjH@t6D+VaZIvm!46A zk3u$g0D^UqGCWY@aq6gY!W=%yRYNCy1verxPo*@zaa|t(bI(8cEr*)6ug?!fEsR!{ zbmN_S`+t@2;~seZ*_=vI`;)uTcl(#1vaD|tpZ~@rOu1dcyC$bSx;-}bLdYQ!&4S|=w}{9hk}oP8C96yz&FiCGzUPsnb1>Vb>(*slBokTvOnr-R#Y@V* z;wUK09N_aZ>qt6GS^@?g$rL}|-T~*3WxVxp(lJ6Z%o4FXe9E2KZF<~uA$34jcr;%^gm9ycIbOBv6*QlScT|Wqn&QSAYQrBDl&qC zuQ5RP6ZxTf_a1#@P`&NYlcAnl)&1=vIz51mnRzk~kci~v!IM)wfWk?AX^aH4ys@0; zM(<1+xs8E;VdI4U5R#3t8pu-hf(9QivJa!yhi$EceYn^OhbFrwE}i%*S*n2T;h{y# z7dfB2Av$Q7^uc{Kwgr_LI$velvol5*_dz%R;LDIprl-9;fPTpunrr%Ds8q}G_z0lf z1mrcc{LKaUDsVexAVgov=1i}lhf)VgA()&E2A!U>Sq#Plh7x5|;_22TE5eIY&rVA= zqZ2;xAvw|#-&(3g1OX<*)ooahmpBUtjntR?NT0DeX8a6LIVMv4uQKnCg=?~swp;5} zg>eToaKKBE+OFB3J&(HRjm!fERqH0F_Jq>NyFfzh~ukP7sI zeWSLdMeT~l(FnhVnJVB{Q6!NxY?UQL|HTAcmYX5Aq$X}U9f%vF6DNl9*ZooWL$ch& zzLdS;^W^FPpzTB_)9GK$U)4_C>TQ4S3CJl)TPI%-Er$=8S2=OJV43>dgS{Jly?YX| zZWA{KizSK#Uq&n%PQy2P zlsa+j5Yd@`qwWCne)NJ#iy=>&#UIZQW-3#<>;$7c%HqYo(t!&z`d)Su&R654(iTrN( zJj1fMhh)AjR7nnfAL(Z|{RG?0@90p+zik$SCi>YD$HC3%XsMKho;(rN3BU)MOz06$ z1*6TgIBt&2I5KV>4dS`(wDRg~#BmSHm4VSnvUt+c@dksEnibW~PXl58oZB-9t}?C{ z);{a=@q|GjSD}~C1QPu0`fBG|iGpN#PmS{l$GQ@I>+?=M`l`9%jf=O=Shv-^kQ*-D zaHmwwyruit8_akmz0PFi(1PbcWY4cSipt{|#-R8X<>k zMR90cHOD1I#tTOgdFstB)5|8ro{e(q;E>urH}&L^Tk*mJ#irCb6hB+`oT6VpYpM>@ zTKQUgB<=|Z(Zc*7Vk;9NX9p$p2BZ`|tYLF)ClHv9_RP=4^-NOQAPd%xZ3T90DsZIy zoUQzgjRcy}_e*LJ?OP`&h9W~VeyjKUL%f)xwq)T<^aw6e7pRQV^_8~FRM*{z}AvH`=z1GEu5}O7TUT}F^NrT zcEKNyc=t2yYhZhvq>x`aqt_o&H%R$Y*;o>;YCVI=<1izsnyJ|b`2??nG%E7fPSw&! zvj>LhSX9?wo@pds17^U;Ro$V^v;TE!k4E63^gL*Sa>wlV)9suMpCCSb!bQpaeCc6E zcSWGo9$0-ge6=B{UX=Ljr+$6;M>EqngkiZ|3t&{BGQ@i{J+VLRY|Lk`=onm zET$U`Int_QjmHJ?_QxrZt%lUKU)??rk2n5mDd@rWSO=wnY2_onxR-uBL<_j9B<@6< zhqqG}28>Eylv4hzbtTh+Zo8Quv7NyGka6u0kteEFDs4v5@=9iqcbn2!0kky%mw)G6 zmN|>ct(tA-|!ys-OdbJX=#!%~TL`DFgFzDlTuSKAoPJp{SKCYKS%PZ8uwqP!$7hLwY zFMY>#xq78l*tM}N$`zS6QmQqR*Y)_R=Wt7930(;cuqaNC4B{^l-TJ}9jPHZ@f6eF^ zc@X}XF5D73qFT4~bt=M;^ggcga=wS6w$*k%a98K+o}uJm}XZ50@1WOOlDW zOk|&2v%HSBS0be&>`{?0Ap1>DNaPyr%B!To^U&2T3J^Gt_sSt2OMn?642d_6I}_pa;<5DI-? zKWW@3K_u0}OQRngJj}tJ@{^*i96fFXUXHRC+3e7dd#ZLyeD%uQl@VPz>8Iz!Mf3#T za&PGi(8qY*wHPwfGMTYAcvT1h3hcAc5{+SAq@&4&uNR!+@Vp!|yk+rR!DDD2a?T&* zkHZ(_xdb#zMVSl1T%x9aA>wL}zMz91)0##wn{|+j;J9$Bf(6`NO#9`teZ5uSO>mVK z=#nqK$nzq}qiXJ#>(6f#x0Gk`czL2CdY<*&2e_s%Fx&C0VIW?{_=4k@t_f|1tK2&J zLTNnNUq=TI$LeJ$vRYz=6TEasqoBN}O0+8)F1(QWwRcT3Q(Qzogm6HyZIc;X#%Fdc$$(eIe1Ew=1rqHz6p+BR~;uDTbHq;B3=+Dn{qRAk}eJ^Tx6!>T8GrsI!>$}MV-&b@w^Ib%wyNl9&7Mms$nYK&i zx|2$m0;-qS1@;%iG(Pi=ITkOpy!A777b7Wj7I#o6a&)ghQErH0rknc0M2$|IN5ZV6wjM5XCT zbNKS8b=dbOs=Py1k@u_+LW%KzGyk3ix>B>?}TGO zp>HrqW!?5!oZx?zLWAG9aFNmNyxW=H#0I;c2X>z%iBuKr$6r9|M+M=rkrm@flry1D zDc67#tVwfQ9)n(-!;)lB;r|hEg`ThlTXYZco;$1<%_JX_e}7|b5-16LJOH=H$`oYL zx9^heiRY+tw*(`S^%j> z5*4^tPR0U7sY{=2ywBX{UF5gx^?ygK`$FH3pB$b1S)Xc}=agw>0^|plF+lG)@8b!w zxcPTgkjiJ1?o&@)!?>>Oi9Es_LE(W=pHFnz=9;N#_5}%PxWR`1#{@bXz;=vUwE>eys|u30;`|DC+D`$H6(14gMl~w zq~50xm97osp~w@I?pyqd+pv|WfFU5@fN6d_m?<5i?Mq%9^LY;VR#wvYYj0+G=7(z$ z-`u%h2c-D4AxI_6PT*BEB%vLB_IxB~%2gOw{mri4NXI(p4bMP9IL!xi1;%op<(xeN zfd0!6X! zQZ3LM1I*&>pr%8x>!5jvC76gYpD?LzqIYG7?S=w?-yr_3qR(cVX^Q<|;b~!xv{n|7 zzrJ}o<8##+5(0+H#mmGcIW;g1ZLQ6fNOoR5OZj5D^#wu%_2*}kESpT+P0GMEI+;~1 z7B!XX-ufg@??h_cAG29wPOT*8X5NY%9+)Oa#EE zKradGKk@JVXCp{)L96$?t{BWp5wo3+L5_o^>$?x0#DDR?U)M$ODl3A9*~*Ve#S=y5 zd%ijA3{4=F6r1J%H>D;))HV{jDS!z5Uqn*p z0Qtp@+4|Sd#asFOAH`KneUVmxe$H(bGlgEBswmHglOx#m^7*LL?I#Q9aHh53n}W#1 zOywwYE6ZW^;80cm)|8tD0xErO6B5K<7`FZzfK~>tMNr=yf=`Fzn|K^W`gCWs8QuOQ zJJ~p0Ws=<<0@+((wS8&PD-Jb5yn3J0%yKh-EkOtO@ww5^TZcqJuYP@ei}sH>g=`rj z903GX!c>VHSoF$^_M&TjgZS!p_uW;oqm<&G5xL-*`zxsJ1G2T5XuSvfYi!RmI&xrGbqqOdQ=D5Nxyps-Iw64o$B!D7-Q zis*UzISrT~70mV*1ISKAz}8?*(NAFm@s0h~leqyTrXl-RROX9jgEDG+#j=ug!c|bN z!ZR85l6xk7Ze?MzZcaYgXz5v>yIOWtK*ImWX;_NWZkuTzoge!~mswh^)JdSJF|~0> z+AX~}0qwRx=Q7n9YG0lGC&BL%9cZT1z8!OE!+5y41@Gk@Kaa*8TnjeA1tC-m?V2Na zzaSQ!H@a$hoP=L1d6ub# zQ}nUi-wnsydoWXOmnB2I(o-y`A0qpntF(hM8GxE=4Sdz66bZv-lN#b-FLL0Rp;GM_ zi0X?)0}DTNvmgsN zuvG9h4=(~hoaYPAE?0LSoh1GG{ALSyH@GZmv&z(yza4?n7y?khdf(&n)1y0vj8`0n ziqC^4fa`Qh&_pLh5CHuW*AB%DhTxS3rPC7RuIsF7AvZ`b)Zh!#K`&ZU9wu?+9DHf4 zlO-eGp2X!VEM$ZAy}<0%!L!|-+xTP#87{rDbxHJzY=<}oVQ@haiFO)qS=uZuU(w)B z=KPkpHb)Q~NjUaCe8J+YsmTu)1IF_ET~e6y;=LxT3c7x-Z7lp;$#0YJki)eV)P-Hs z>uD$eZ39^IQTa^kj-nRI{ai#mc@<@CX~05Iweo%dqtyKkI79{2rWshJI%ogK$~0EinBs z=3C%L6PP^3t!sy*x&a#tm-8ZHVtV1BEIx1IQs{u{0x9O7KvSsJ*5b|_!b>Z-6a|- z$p?RaPl}LTxI%=UV|_+NE+Ym>7RvWkNerU5LO-BskX+vF4kSfvJ7PF}7Ltf~ zm*LSEQ4SqZ`565HjL$>IuLu)$yq{+3F%fZ#zIDm*Cd#9yXEA2|uLt1Bcux&3s@4q? z9}kFGt3RA>gf&D!*{&zsStzmNuqNk5U@u z$q3pEU-+;VfET*_0=i#6G5-wH5X{}G%E=UvqE=-PO@FzQI(qPijN`_@UEEe9;w1V^ zAP1BmnZI57F7EFPu}${Nun(b+EP4q3VYm5bcV6@D|gLn-VgP=N1#$?F8 z&Xz7Fod(E1lwk9W7UZ*lx}1Q5t|l-cD8+|vIcwpvphN$Ot9jh*%#*{y1z*pMfc|># zork@cXA8kv10hPQ=`hmyD{Qzn@cI=)rrhd2mJQyM-`&fdfhxojN8jTVT zl8<$Se2hv3XzKN;9-Mbv3FH|g@dTPi2BWr9q{vbG;}7ZudpLZZ431ByqIwb=(Jz~K z(b+Xof;FQnWS^yt*N@`?gr=Vf%RvKv+f)3e9Ook7d~?1{H+fTaYnS-AQogj*xk@l8 z&#=7+i7HFvv=ZUa$){+mfiB@QDc%l}(_foa?sK~CiYS4kW2xlE(`v5hJXj*e_xQv| ztZ-uqw<)*x25MO2JE7pmK#Z93_{_XK- zW#yeIW$A54Sc5$bk!+caw3U0SYi&B`){mU6%_-KfCf~*Dy=YRJD@h6G^A|Q8J{{84 zo`_w|7&V(my=2~(%GNauB3f^LM)H!Zw=?4guk$zdM%w05BP)`rCA=VUE%&cbjeCC6 z!lv;6P})&J@Ow=J%-0{_H{$R;j(ewDX8X-*H`Mox zo{N>q(69gTEc0AQxhho?bjZz1z_hl(-le6y9zU+Jn=^>{(L_#(L=U>fClju{Scsb= zC7~>QK|Y6E+J)Wt)sago?XkRt#E_+DwNWNszz$x{B~$34ZpHBS)h^2nodsVrp3!Yg10&=ZNK z9pQ1i2*76{ATO}7tQr8L+rHV@Jb3>P#mNK=S>+_Lb?;9EHvV%%MGdDauds3Au}TAWGe}RscK+C?lqfn}~dh--LL9FuE`vz^pHnTtuy6cZzR|0$V$#L%9OL+s$Nk-g@ zmxRCR^lCh{fLLp3^Ipd#lU~JfnRT)x^-(L$bpI%Ms_GDgW8aHqV9Q>l@1C@Vy|P7NdxC~L1#WG$ z;Ni&pBRb&=jd^nf=CxoCD+V9ywevWiJFr{;Nk2~AlpYt(q&hWcvG!;brjmUgd;M9v z6eOM}o9%62pSvURUKGOa(^<0em5p`7HBJ zIXG5+1xG$4Y_H7&-StL}ilv>I5Iq^Y+38upY{=QC@W|L_p-l2+_!Rl+r*Me9m6${jC9E4^T#;0#Bg&6~Tv>|9b0`6Uc?0|K0;R)6GbQ4f7h1XLg$RTcpp7g9;^lfj&iwkhyz@aS zn_DMbs4FZKK)4au#0J*$B@d$i<^m}ALc-<4cCqnuq(@SqTmMjIQ|VaKk^Y{Zl%6<_ zNQhgguE?w4IDFrq^`a!LfpT}l{8dX-D{1l4mdO=a8H?Im(X+9(yZy3DeV>Zi*;Gb|PzIZSUfY~f?kt{)6kmiGtY1DA z2=4AGfCgSUjMpeqfc0d&;%|hzT;Re{I`>JvOe8?FeSnMLBcZetk|_`PfgUqr-tgtr zis!oOZ~}VlqxZ^I?iY{ng_NK=ONOn%jh9cn3(F zQz3qi?eO7%VhKI$Qn1ViW>ZaR>`k6eaAyeh1g2~gIhD!@KIS5mIz#$`1rcNf$SmAC zF6hw8kbVm)W2%Q5tbak$=|+x>T>l{WMt7vYTZdNz_3=yR$#Y}8@*W5A{ZHcDSN)w9 zEAhC_{9-C!YV(x+G`y4=79RQKsZysm_RW19Q%+1-3aVyNi#W5RMx32Y077>S6><52 zxk4L4e5!6}2DbU8@=*@#OA;Oak~#TfO%Pt(cbru@@GaS|XnvHZNc8VtnVpf` zxd%`f?MpY|_#_H`arx)7BSjZp2fCd2ee=K8<*D7ddO?id2U#Q6mf};eym;S!B0Z#d zK9D1$0%9kGa`a!``;Y%dma^GJA=A%gsjmHd;X^F|bOH*r9J#DBFG2ag$~e8%LaKP^ zEpQq|Lp`JYnb&k5*e*%!k|Ma1&N=))?7at6R9Uk&JR&M0Mnn)4FruOaB}hgQ11MlX za!^E&AUP)y0TZBtf|5;ughp~|KoF4FC{aQql4A=^(?HYoU#Giqbewtb`~K^$@4I(> zt~F~$9XV&8y=&L5UG>!SP%Dm%+8b``g}4t$ttdsy&7D<_CnL#=nZbyPOs{r?ryt zjR}xq-{&ykG6&pwLHbKkV@P@bQ*p1gGTrmZe^#t?DsmI*AeHiDwSQj0Qaa~1Wb*7JLLm0eIM_QV^e(8<; z6!i2~jYr2RA?T=tx#o{>rb%uzFE~LhNOSV}>QL`W-pf{A&wVH_07jo zlJX?`%I6}I)2yWf)CHv;(ffztWK)3K7LS8imE$rjFm#w8sDL-X7ucTc-AoJo*_Y)_ z;_|04`G=(f?jR$Z+pXq6krs`EFH)+_tXqKUOoCP^I&ZRGGo(>ya|fLnOVbdmSQ)IE z!su2Sjq@s+eJA}*{z;_s*EUC_O5t+k0Cgge=j}i^y0y8kNihV;&Y3!XI>l!U`9Z1r zFTm9N2!VKy*~|0OCQjajJ{l=0#nseaN7tP~xCNJe7XbG4_^t^n8LB8p9Rl4P5jgKt zqYch`skV0VSWJpyWrHdTMl*!&BI(=tkZQYX(!40R7Hkm|4W9+unJn4{1#UuR{TRZ8|HC;FAim5*M$%}+2druxYv-g(m)_A>~c z=_%ueQ>BC$5MVM~SFV_ejYqqMP;j^#S*{d&``ZICYRO7vUIiFUs*(p#z^}N@uONwLMV{T|psBpG+ zKfr5!hzMqP?p6oY01>+cirg){P!4nUL#{yx#97k%MQB0quFs%c8L0;sAeF($pq51H zQTT_qFl{&6HPEOz_7}-FkOnM)nij9FqkqrzL_FldmswJc=0^;8ee?5PQkQ{5CZMb* zE19=OI#-5wMHo{iXu@||8O;URLk(K+7>V<_agW0t(eWKB~HK=Dg{bhf?b$0QsR^vm$ z)c+f{(bSDnkN`+ay!v_By&W3y;=cRt6JmcsJu4ni@|-DsY-q(a<4MeClazI?T*iLo zbDSJ{vJHm(W_Pzb-FN-`R!x1nqwI_Haitw6#~JRm$)WPW7Twjem6eFlWs|_^Q)vHJ zgnjCuVkMle;3^|=Aw0z`MN!6rUM^0u29MdlQM&_vm{8g`?$5qK#`mQ}V`(9cz)C9M zyc!wbkAQQ?v;WX&a}L^4a1^wynbiys>`g444e0uihH-}`5dE6RfBQ`*l_6uIO{nLh z`E(QS3()_NjPwiCjy#wgL6XucV7G9k*!_e~Ex^o>a6oAqCkJ*rKasPf)5+k8Wvlgv zXZMKy;j?sZVVdjzK7HOVfhd4aj~lorkgr2;K)Mq4dBR(M>Pq;zcK%@Ud9M*qbsB<| zhK7o--j;14#^TsLjXJUO`t%cf(XrBx8eizKGH_mLPd5{1ecnDY{-7cfavwC(&oW0o zNAs7@sZQN9J5!;dg6m9=GrbYVvM`BNXFr_qy&>k8waEawjsj!rS~!FZU(3%}hMBKz zd^&rOecj-V;)A2n6+%!_Rj<(uB_Q**@0Tu|;)4g2QqYdOI!JO96Rf-y=X}MxhiD^c zOJ8h=THIUT%{|5#8mABVnA3UI!}g_~CJiVWkHUuusH($T-n9R<*QfZPfRg8c)5Q{W zkgTM{7Y&w$(z>OTvw!ya{HxDGUVMJp6B~-Ol@Q{^`Vv58PSYWOvK~S&vA1+8gA404 z`xPr4T9R+M6_Lk27R$-aKt(nN7%CRqpnhH-um|l;sb1KFIsNnnOJJxj@RF5{2eTfY zynt{xAU$djwg1pvV}I%F&3pUc=OLGK1Bn0L_{YZm5-vA5K$d{=hw`dhO$)dI7w z{_>1|aJ^=>zeJH{NrBTZPg)(Zg6qFnL8o>|fhF&^3LiO&<(?lpx&G@<=xmcSkb(8M zcE%lPNsu=FW#Onp^zMgteQ}eKI@*)uCBS0(3Uu}K;84xe+kt{7-D)~RKO~re z+JLRTfOZo7@`Yxs(5v-lLfQ_fSE5<#t6xAM`68h$xBmIdttM2gA6Q8`kgr_j%B4j@ zKRgL=U1Xn2+@FGCIf0z{6r?It-)xbjlgAu@{nOHC-#>B%{V*)5|5*v7A*wMCe0~Js0450xY|L`t{ujAxv{$)SXHs(fnj=0S4!Tfc88JT|1%>OEz zF+FNX`SRLd#KwrYQ$D5ve2|nL_T_TE#_$Ug%Xv80Xp!DtqAYx~xtv=_>mL?u;hlOy z-4#;^{mKAq@i&@h`DwF4cda3Kp;ZDm`ssdWDLnd&-y+*e#q*v2F53z-Z1r$%x@+49 zPdT4(j7ZuBhf=@+r48S!!9UX;(RSwdA$c>xL-^Df_2>@N4;jp@--Chs%kP<4q{{kj zGrxD!Z$I-lLG^DB{7+0^zh~z6%uw0m{>R2M#izXomTPR0#J?G0*9@ug9-w7Izo!=# ze<6e#lJ|9{9(LWP{$e-NX znCew{(!-LTyQAU@{C`JU|Mwy->=Lj5qr(|XdxRM2$^SnuwcfIDtH#+80%+8_FLwb+ zN3yGZt~g{D)m#2|vg(;$_>%jsb8Y13n`HdcV*>P$UwZ?jpEhJ%J%}VUy?-hULvH0e zZR?*?L%TdYxB>fu@ovm2dX`2FX#eiiFS1c;h8+7h*(l|`Z;)xO0CS z@NWbDZNR^iZvR2jjU==_ii>5k-ghmCM|bbi?1XsjPh|2>bo1X6zVu)4E`cQU%8f^8 zO=^F5$3hUs8vFN{E>J7!dC&O|6*dNV&g(_RySoq){yj|k_h5d{%wkOI{eQ@2v_zrY z8oKq|*eiW%vlf{Z3ZUPy;eRdA?M2G537m5@6vZ4;j_o2?*-Zg2h1rP=J8UE`}{4B>(!L^GI2S^M6`dX7C}9HNNF;dojT|{0TnQAn(xuOMfW)^GE)lxMl4> z1`NVY3Y$Kq9si*ywg+?)3L-)mVOopT`a~$Ivxct+;>ho<#y{(s{3R7D&j3{`);%`` z=u4phK56&S{~wI{%aH09mDv#39ogV12^XG|08@A-sr>g~e$UL`-aP*!o0+FXqe2GlFy?l5tziWJXl(p^Uh73csZ>_xiGD)c$>fUPayRfja%GOcqq}nlgy_hHaiZ*F} z!wg;G_g2Wx-_Lw(mhTC-?!p1B4#xL=R+ZOI<)6}cp0(tmW{ah0Q7&u$h&wcyxFG-F zB3<)IRL8M+B>>9o8;Tgy4C(z2@>YW+=c%E8 z3eyvJ#f*4QZcQKy-qQdx$T9tkSz}&<~bqE?oWlt!*GxQZaCqyObukj5% z1v?1bx*b#W(B&M^Ek`Nsdi|?1Mm(a(7VvNKvj4A{nqADJrqXUvil^?BaMK|2f0^bb z3_bw!Su18sZM<2>s}=x_JEC>k*ItS`isG{y4DyTX53~es z=WUd_tG|+{9TIY5_#y3+iq!xCrtmiRJIeUyJbpQ}e7c{0z)izzG2I8iqx+SkYd`FT z9y8WAZ>skzy?NA3qmSklI$8Yu%7X`}zs2d^kberZQ{70gpiNfHZ3vsUYo}}lVI-%G z=ndnUd-g7A+Chhh!~*uq@3I~1-^~*v(|ssM%!cvG_|cYu12BHGA8v6!K-9$fE~tlU zg(jgsf-Qt5jC`g?F6&|96f<D5pC2cy_ zelafuQ%8;#F1Diluy)8OjR9vTc)lf_J{j9#;_jK|I&K6g;MpmqoR;S=87~CUg@61u zr0&^#xAx568Yr*OZulUhn^Sa^CBrN5+a0W~@+$DC2sL%Rt7p$W&Typd5bq;k2|l;n zX}SNu26&8BP|4AMonk^?T}24^*gx8i?E#{c7lV(jQHrNl#&e&#Q7rErEtb-1{6!s7 z?J?Kkkq(JD6Z9GUd62vZU^Lg76s)N4myd*{Xvv*x3e=0w*2Z}!YlX1vv<2BouXonh)H~}wSid(f?Xrx{K4SeYQ#Az7dG(JnRdauXQ5^cU zdD{&1{LX#X^ZScoGHzH0r-}S}dvDraG6h2wU;hS3ev*|WO{6yMlK8Hd6oPn8$$!+o z3Hr7E5w`Gaqw(*lp_YbzPYrdm#{9OL-y7<;uK}fp|5i7=Lko^<*DU2Ubb~N*+U_|5 zP6rP2r$~_3`X1up@6;Z@PX`Elpwr;@!AXs#|C?iq`syLeMJxa{4*DHm{28SF_wM1zn_M&v?vt8u+LV+%O-n(f zztnzTjD7)z{V(60N*iZBo>%n^#TChodW`3K=)CpPzr0?W)|I|)43$7{ zn#fo5bx;|${&eVzNemxG&-oUwtx=x%a1*_(_OE5N!EWK*SUtyUy>4EczFF$!fF{_H zAeHeEtsc$n>w322#%;9ei2;DYLdrW0ye6w$yBDfCbU&PLZsc-(WM;!^~A9;U5RXN$Bt%|Q}D0KqXoql zKnltL0(a1>re_rLkb2=pb!fG`xGORp*vul-1n51wO6;k7_C{(h{dK0`PvX(VPtq}K zyu4~fJ+|swxQi}#>xrgh8&$l2YTWk+$ODPn^weLX<%~=qgX56mnQ6p6oZReYXnqvE z^o}mw6bdn9R~HxIr*2| zkH0BPwMXxd@F_w41LO0MDw<8+mkSDt8@`K!N1H61Jggg!TZs&!UY1#-wlTr zm!7Iu=zbNd&&(x$J)-IBk`-IlJ=w3d0ZSft@&~1wZTmq8u9w@z{Yf#O?8F`GCUuQk z_n}CfyNPCzr-x-Kx5w1Serb~QzOkiieEsaib+G)MlolioU0Tp zX;tQWpWsk^*MvU|w`G15Ofiag3UT2q>(P}#7|!3QCmt6p4v{$$?^MNXc6ghozOMa8 z#qOD&AYvCEo|YfGf6B16!L>cyt7$~Pg#}otXYg;()12oq$Gz?YNs?a_%^3T&A%Cr_ z5hFV$l_36B`=9sOeJx%;1ypYTvs4g!dKk4ul~4dOh9x(btvc=+7>-}rc%V@##f8(s zC)_q?o=s$s_15A2$=9W5~eGDwy9 z6By<9lJ(CiR-+BA8Q0D`cagB{V%IwkzvlBxHU0S98fdAQl>^UY5PgO>41*b*C2DA>-=19iND8dYoOM6^2&QXrelBMHsnV|F~i$VH2AjReN;ZNmV!rTt%NY zb0fiq)<4_1Fw^^(Uf|+;>>_E!B2`F4<5r*GcDdpV#A(9(FL zMO-(Kz>Pd33coLO!S}ae)MNE|L>hRZytG z4ja(m=A@UC8X}g)y{}PcbEY5F{mNeh@1y*J@MR5Twco!6I*0ExZE8kvbaJwH)l*9$ z#kUy{jXi|xp}4-?K%$v&1ziCo54brls)bzO|K>Ch!CFYLYJ3`)3lj| zZpxdi6OlCwk+(|ZpV-)VPp~j2(F7wy)YZ(g_{=2ZXfEh|Z4KdxsOk%26zh!+;S$9;0X*g*6f{&7<_~YDF(Ky-_z>Qp+6M;*r8k2sAcx`LG4(k?L%gh){h) zChJUoko!(|+;AfQW@3S!lck><@%sE{%V>{s>}xe#>nW0CAt~WSiI?n7JVY zlCwzU{d1ArZ{r6^vWTAxc;79kB%!9~iuX!D&s8q4!tJh8pOIsx}6Ye|}M zwJiaCXpm6nRCp-Kpvbcy>nu460wJX!&$$`+!k<1(9e|^7^AkY>?m!?aJvv4hZhR3W z%b8NNF!v4N2Q=f;=ONj{S?Z6718AHn2Z@8mXy-J9`=4C}_yTq7dUE0qS#U+qcGzM1 zQXH_d5f05--5}``?l22{x5yzfDf`@|^O>l5$!N_MGZh5Sp1SGS#hpB}LUhXr zTNe+I2^!+bAF=uc;>&}3NIMECvNP}2_CGt3ES3o5Zdq?3RK1FyAUlBoq(3NmyY-{l zyVkmNIjPt6=tr}CTu8R^Fb4raS)q|*Lv_S!MXa$>s#1cku2Y8@k|&N4XSAG2W7$r% zZ=2_g2=j>tA%nSt`R7m{~>(x-o|)&a18jeBOOeX_=3v~dm*}M zWBa;Qq>*D3-T%yd`Ep^Buj@U=5=1!9dbTfgtpzH*E4#y1`7r8jcgN;8bf_GK;B1NP&2-P*bY$vgGu?k1b zED($2wt#L__uz{lfeS5zJOkM2v39%F;>{v;6NjUoqn;DYWaKc?W_nT@vDm{|937*5 z9804Fi{@>2Yn=@}+i$}Xs}C`V-jQ!ffn{Fq)}^b(MY@WDHw*{##r9ovyfWY!;MEOW}N&Vr%rbG>K)x!OAcYE?c zs?~M*HUHIwO{`YonNeqMIc zC_uTtHv=1(GDiLwBvy(>E%X@(=!(T+ORij}U3@ALz-7wL^X=Qf43$99_@7RVTg4!k z#dD%92Q;=NnX>{R_U1av!QGIJx}Ra&-Z zJ>Ilkpsk3*bCmt4Wpp}58h;v-YKF4DY~nT7#2=-fcct>tQ=Pd?cJq8V?+XL%)(;05 znWCJkQDig`9E!uT>BNW%AjoE>Mi&Q+yn0SyCfGb$;67$9{ZVG&h3|BXt6418rgliW zo8%eoKXIslFiiZ+rMf(jZ+CXl*MS-El2YgW>%2JDby>kZATrmuh&-)4%)`8qyoGL- zC(rPD^5n*UOvsgm)6f`ahw0orZb|ZVc@VCK`;PG#f^bN+=y<~?1(@P}d;i50%U=xJ z$G>0v{R{uXT_g5o9FzIIkCa`Pr+nQTFwv4~vdrDh*T86nlma?3GB6eu(czHSw2;jzKy)S6+ZijH=KIbWwRT?lfnq6pKal!F8QF9n$-cu}qd@66%C-@pei0Ln1ggsS%zN zQ=~0y!&~Qe)CEuz28O2I&BTXAt2rd@N#rqdL59@PyvHH-_ zUP2P!HTmK$24g|b_5HrEw&ks<(hIM;Q*Fm-nU5hR&5)PpSIN+#kzn2jZ5WX>mG=D` zHqd$Hs<$swEA=}kGhejT={ZY$0Xenb30ZF;RDP{g9TpJt#Kr6*kI><&UV2K83D0y%*oha%w7?h(JoP*r1mXvtCZ`x z8uj?>52WYAE*-P7qYh?{o6Ih*?r}(f`R=#>NVI>5nW&ou!hUgoP4Gc=l2fG70~?0P z69yEAFhZ0mT27K8?l}3lC_J~2jBXq#Oc^0{#0jEm{MKMXbRAWEHDphaYJ&ImSJ!)7 z3&$jT*3DZLGp=NXMn)Cgcp zvd2#c4f7+#OvY1|OD#0He@MsuiT5l1!~1@1MxKS=8uU<$5o^lc&VH?(7gF)f+m14k z=RQqmZWpzjK5CG+nz?z871O2ep*Zn46|mny=}h4$&smUb*)(@@jODaEm#u2TAfXlGlib}NmyUb2?zV%*40BmMC?!5FqjQEnq1$b3@;|S2zIQv9N(c33z3Bm^It!9u)2>k6gZ!gSo5MII zbuX3-ZA#|-#Jk}}9y?G*MZI@&3=GaF@eL`i` z3f!0Y4)IE||FKLjfFz-Qk2Q zfh*s7xLR#c0R?A-ymr$YqlXX14y$;Nu?!NJhp%R;?=0T5UVBM-Yx$>F%Hdv@Q2ue7 zZPzV-ZrAu(*{2ZmBS|gnB@t9OTwfoix;5bsSEEc*^9Ju!M@C;$>@t8AaVgF5*{z3l zdEziUK_+(bTujmwj=yu%K=3j|61SVnXf9>nGHm^fg#Doo(ra*ys z?i%+}9pJaN!ZS9k<`SzJRw_C#caIV68X#zOJL^z^*l0qEPXvBC?$DkbxL5i0Rfn#1 zb?U=TaZbWaJYk!XFaP4plXzg{d>|KN3x8bt? z&2LYmR3|}9lA2+Wg>1>t-%8X4Ko!FLJI-+#qjoH|E>+Y0So5{J%eeL0UI~W~zTOk` ztKfFq|Gv0&al2$)?`+Giy>Jw5>?hW~WYW)7s`O5eKu1nVw^p1#2ok5j4WMdomKNWW zO~UuzbeSDiOK;;zhdPO5B&H8ZXWse2(E?2tDGHqj=e`_F>0M{D@QRDg34dMN?cuoK1noq%W$$Qx2hdviNCl- zNwf&&Y*|`n5@B<^h2&mu*8_4o_&P4gGZFTHuc z>pi5Rf+P$>kYyK=fnNI zv>5zn&{YplaBmKjof|CV+aE>0@AG%~I^Q&xj?5rW>BnL#*AmJfSVky}p$?V~M9PgQ zA86!K6$@BWIo6)d?i#dTJ7Z5xv|JJYPQk|Z@V5=er zf>u!!0-arPXT&=WlRIE1xL$aC`%h?0EIo8dQ!ZXBqJcix5?Td2y z(LAjssMhGxwQ|xLG3Jm~W2p`mT#FoVhlk@|l%U9MC{dphxD&M|1uKJ7S3uum7p&Xr z$*tRMi@Lq78E%&tv))^*Dony5`sLUHn)wOJvJXtO1v>Jua^Xv(-^BVf} zs+N~5g`EgYeZF38kLz~pxH1`H2kYexOsG5Lq`jmIQbfFna7Zr0sEvO4!d3Jn=XGpKEeYISxm!#-t1ooBx=hs@D#g&-Z($CF&?dOFYWM zos_?k3soh#%%S5*O5GPd3nJLVH9wYi1GLIu0N*!mkk#oPv+{ClwJIXd`7xhgO>mS9 zT^|+rB=XWb{n-BPDt2VgD(2{l`jP(HaJQ%$38iSbd@tq!6+|QBxV8AqE6Ts>-W|Dt zBndZT1C|i=`JSlg#ES>Dt1TO{X~=0CVKIqYH+*1&`_{N?Q6@5TgD<+_-m=Q)Xd!x` zUHys$Xoc_lO4pE-VL(|X35Q?8o>!^d5~7BiYHT}+?E08O*bIbZkER_^%+q$4cl-H7 z_}SmJA-AwY(^8#T@`q}b({J9^@@_`bm~iNNHTM`<LIHAAWJA$OgR5lXCHVkte8z{4 z1KRCTcH%~(3R3-Hg2wq96FzDVjHd>=$Qs<0&9875I9S9i(Vyg&f$0 z`=9r2vSQ`t)jr*IOo_r#v8=pm$?|1fmWrjDjjvm?k15C2)^mrW4wa2DE#3Hes=6a} zyaB5zp5q@WXh~MybxZBNadW1GS$O{O026XmH2HH9(fy*PwQd}tfA#jOzN`HuW;4>! zo=f_+A3^E!JaSRU(CY3Fw<^q4GnAN)wR4Z$mQ_H`ou8~O1ua%-bInrc>^Tvyh52=q zE6V~ZCV0Y@qcOyzQE~>t`r+ zpq!9fkFBT^yUTbAxhyXEoOHf|)Wkc|JG4C(`nywFdP9% z>%NUYy9DlG%gCsSAyu!uXXkw#7cv~Jagat!-KBL@sFJV%3dv8^z*pT0hyVaJQ9Z%vE&%~{~Y&Txp1l_RQnYz$VIR#SSJ- zr`?QERNY(0e74;4jBUJ=K)+2h>9Ey-%R-d+7lF?l@+`I}6scKV?3^sDNGtjB7Oj7z zGwGZ8M~O&Ljr5xsExrrv60alzUmTJyfHXsYtE7PzuIW-qm7<)6F0BAOynh`LBWU_Z zgmeWH%B5Q8*(I#Oj5y_LJT$kgS?rK{5CT`lmsP?|k$}5ND)`x9|JaDLgL#TMysV-; zrU^>$Vf^u}f?GcGTeG!)V7}S6I;`A!Xt*h{6v`p_8|TP#Gd2-e&7H@>+4fg+Mbt5G zxVr4i-6=lv`Sn6UZX%FAE-eM!Rgb^HpsY|_%%j-JzInvH0?0hEPGbM*k-_O*|&J~N5i&nVZB2s8z=I4SrZ1hr}i4gdH z;3_qGdT?*%XUyeV6pjcAmshAHZiTpp#|M zeE9hosDd>(+_XS790J6Pkpf!9YK;BCm@)U#)F8QqnPQ=l`17LAA|TWLwEM%%s3{&w z7)37IhdoJS;^rykhQ{-Dh}+8_&r2LQ^wsY9JNBZPvcjGrwu6D2giWK^{DR1oUOu^} zv-*{iA4R5LX-G}Xaj58~8Xnng9?=u3YkR7H<@;o=xkydPm9f~|unP3iPsr62FN0l> z4b04k8*2EaS%_3kniINKW}?k_%v6<|!J43qm53L{zdwBte1= zcPGx+gj{;pbVEfnVVF%i5HIQK;K^NXGR6FLt>oDpJAo5LhyYjfKxusR8F~eY(Q~)8 z=Z;3Vsx3DP`fIJQoBJ)@*B%UnBGciGGBhY{O){)hE&+9Z1i6$z`18Z1U~HwfK&eqsme*&dZuWka?(94nfv{Y~IkYiA5rQsx{;&+U5_f zxcsc;n<|i0d_N^zv~Y$v8EzVtzgCs+IwK&!?G%RI8whREYA6tU#;ejcec_PLYVP z|8y!{pb{@3ae7RLPtIw%$%wcnX!bPt zh>7-$W2hLImTdB9#V`_SGGUU;^9@dgtWk5X449>$+;Yyph{V;E1C|!M_HkRFnpHvp zH!Y*I4}p!XOh3+v0OHOp{b$F!VcFM8w0TR)YVe58_?8?KGV>G%%YD8Z+@NZ{ZFw?W zh=tAteck&IRK`32)Wnz9cCR}p8$D(z(>^TyF|B3geY>s0mP^X4ad189+A@LwoH{NG z2`&uJ?g%`*-RX;c2vmK#O(}hXUJ?lAPH+07ErK6tH43t9b_rQGdXn{JMXm5Hj)7sy zoB<_qC>OyQq#8%a*{~q@;F&Kgv%cxszjnaPuHi znRh1UcSUNw;JBgRY4hkaB%VXHs!y>H>YAhjaXszV^A9BHWM98pSLRwYqK9MVfkOUO zUtPEnmcK2Vbr{QR@q_mXxq~2L*vj^-{)_HbN!PPFRMb;tRA(@&;CA%)w$RMg9=2|rPWZKvrwAbB=j;BjUAnB>AeXY<_|qv`-Z$n(u^gpTZdCde zu|iJ3S_7x-q*IWyxj!HdU)KjNRe+F5Lr9hbU4*-IVAMfPNV%q-eWd}I+^S@1Cm7tj zgMi$3=tpv2?+p0rhLj*Ior|JuSs~f2h`rG6vvHZ#XpT{~!F*XH_@QVaE9?gh7hwtX zhco9zQ`6TqXylMY9no_|@KUe-8TGTcNRa3|_SF6n^@rDe*!vA5SgQNlPv zmu31Hh(-gO?mh~uyuIpWF#XtF<2^w6vbLmIS+LfouTEK?FxP^)<>KU0Yi`>muEEYs zsC!)CNJHPvAV6o#r{Fo{$|@>Zf<@BxW^O%q#l=gCCaz%h z^hs^rEpfKqYF7Im*VDL&gbLuhy2m=SP6HiFn8uLCD#8<$h|XeFE-!TTmds==T7Vo6 z^ZDHOBW*5dpU6}IL>K1!sQzOKLj!Lrp&@z=#%uVzhyP@0xrUW{A4YDxRoJF<({N_Sk{_H~Z8Tr6X9-rvhxu}qh@tck^HV>bKHkw`$O?4Hs)(gH%Cmqq^>VfNRy`+e(L z=O|>a?pbAlA+u|tErnv#e5wYQK^JxcA|Ynx7c1$z9%S5dPn~@X7N!14qJ2G3hx8q! z|1W#MQhvH4N}r^kzs9?bd4B4IT$_s$?w(*B$LQp<7Ln3|2~46sWe$LPSq-JdH0X~l z0{!8yY;=S=^V?6_|4B0i`Gp)a#%nUT_G157p&OF&hCCmbcEq*M3oez4-<)aVt_#MKZ~Jv2l%l8-^F6Ri{?;&_>y{6!-^oU0(=OTXWnq2vLHYn zmty6t&~gBXS$5DLPouc{&*^zKETeXtv`)u)aZX={J<@Ix9d&@vE=Rf6lcJ|I+H;sE zQZx|Cbph!sG4%3-5|Fs)A55*l03va>*yjIY%PiW|Pwe0^Sq#BbL40O9JC~v^0Os^n zN9J`1f8I|1D0B6%`!W6^b0q@DN;uPE??vP(AljH~Iqd0ivhHR+RbP~8Cy+oqvbM1g z_;WD3K_fp0X3>E9m@%aWLsR9|7KeVZ#~d! z(~8--CO=VJoAp);$C{Yr}E$1OG_9$knWbB#Y5gt z{VGoOpRC$$O`sXU;maGnsDv(I-Vm5Bz4HbQu1VV}nSK_dftaLb4b9H~x;Mgl^d2%E_k*MVG1B2U1M#z|=QvH+n6aEssFE}=#@sMTZkpK_jtz#REwM7A z;96Sw+v}Zq?=u|eOl5<7LU-;xVza zLbr-{9#GPsuhJ-Sk|TZoR!SH#Ii5$+bMl?Vxkant)@3@a`r9u(hfr%AWt*Zi9NlIJ z&hWybE+gM5f&qZw`!`YttT^Gn-(_&OG42LoQgZusb3d1CuO6=S<2fxw^P%0fYh_#K z^RLY=nBCrx=lj>QhI*2+9uPVp*Olod`>{c7fEHh!H{39d!H1Y>7Zz0=YCeSq$=w8{oyy*i@<(fArrb0*opayoTi>;<+~qzU6>W}35S*U z+e~`du>-k9zW(dV%PZY`6k0f)`K=S!vD_P`$dzL43Az*IbUkAesgBdS$GYKOWl57LM3}6W<*2Sf3F?o*25-~ePPhqRy4W*>jp9lXp;gl8*gYgqhp<>_jS(^#}>TTO!j_2=pjJSbV1 zJv@ByK$k&4>GmcQq)zbkno9$;Ie(YuW!WYadhZcWhn?!oxQQH>=eMo}o!BTGu}{#y zg)(i0$umJ#pRxNgZ77CG4C=RBb+#hCEfK9!&BHDnOBlu=-soRS+cHAe=t~nUhMx+h zTDJYFnm!oEh%hpahMk!v2tMuMuj639_lV=GrJoCwJ)WbY&F9;Omo}qtd6vikhPz$q z18`>mXnT;?d`~x^b@n%YfKIh_Ad7D0r(=Z{?Qm$(Lz-{&h=PDlk*3V!eWON@q4%-@ zQzCyK6&;08+0s|+!qpH@>J`Deds+Wwiu(+9y3h`JU+M10(Dm^8+#QWMVc65aJn+Mw zexn;w;NIm?D}+<_nqXI$vL84=>U6hrCg0(6?39DAT)n#IIDNQRya6uQF12B4VWI|V z4I~4{hPy;tbXfsiDQa6JgP0J~y4%nAFQ)H8F0kuSz$dD|{-`Ub6YrG5U;l9d9O{0h z4c|48{no`_K07(NbnPe$eqlCx?Z?vS&dD|dQl|Bn7eQBLjo_;|SAM9aTgyoXV`Ld6 z`@@Wmx_gpFZY*8HgpnnUp7d}$1S3g%TbZs6(a!#^OrThNfiap#v=}J zi%Jwdg~Y9^nAXAHGH3(YC+pRPtN z&~n+=y$=#GiBnOq|KErt<{bdEMcIlB@n46e8De3OE#OYHi(ZAe$!)G79@XYu3)9wL zvJ0E=F36T`EtbAbbIN=6!02x~$?UYjpTH#g1NpcDMGw`C{mSJEKMcEzIGxyR`2{f0G{)OJ(zH-%l zyR&KJZh!ElR{55rI~E>uU1wV5MRanLbwUuiN$vGAyw*S zuyU&mb3>k#L_)7uH{h4Km8BZKJ;>Qc4)vN1P4_D?<=kh^;=syL@x0f6q{ScSIi22J zhH`(ku}}s(o%QVrU(_IJ6tRzu@@r{mYew6ZAzO!KCf>6m1zQusE7N!)6m?Byd!RJ1 z7OILXk!EohEYijIXqR#c;DESPpb0J&U=g}Kb$O;>8MTh%0F}Ec1*zsSvw_| z!m=Y(x}3mCU-IZ7eQ4(QB&$-UR7>;9tvpPv1ofR3JKvJPeGdv}UcYaI6bDNI!?G=W+#HYq;*~T9v>n?4D_NKK?bRc6rwEU-byr& zK~8)`%`(er{E5!>mD!>THl2Wj%2&A+=!bNwBMrftnP%$a!i2n34IMBV6U{>RSvYtXptdsA`wPSoJ9}>|J%=h$8Jfai*H6u~+j+(~4MZ+7*BI zajK*6i}>TZvi6t2a@1Xl#g4Ei1nnH_OScW8n_IF$mfadEzGC7pCkyr~P43C{gDd-s z{YsuQA9hHU7HsVfu?d>fSQy2Wlr*T~NUg}O?Qn!7D%Hk%+4o2_x_$9pQOEqXEK26n zjORX8HBrA6sGP5Nt!qVFYM5iEx%60G={tTl&Q-{s&=P*{RJAwG-uEaelXd9}I9Cb9 zHdD~z^|s85m$OKA@Nsr>(!hH)q`(~PW+5Dt=Smp1?)GKxXC_WVBid#I3p^lH*Rbo^ zf8@RU6lDM{$F-8#{=uZq4o(fXFNdv+pvC3dLPv~@y^QH~Xsb)neVTpeA?hCX?e)kd zbNXw!%U_ssy&b!R4N8`+5W+!~BeYsZyUV`eOfBXf^f{X~r#g+cKCBk^T=U*Vvr!1= zwo8Lgm&Odh)Tlz+Q3a0Yvo|fx^14nb*u>h&yE0?t{WPzr4ZX0zA3qw(Aps!v`p5Or zH2<@n?`C`O#=}tf3Xf}>a`hNKAI(e|HXtYNB*|LDeJx5U0A7LcaM=kqRmCd&hT+;5 zy_^g~t60+a%vM-=rf=@|01T5d&lm21;6m)=RKwEtr?7XIuW4LHbLY?{ZS3co9<{af z7PS0L7Einv8iuy{W;P~nXQQ5*PFw(;F7$%;N1pOCYE%ssO=rdTt6SnncE4Cx|PB*CfZn$O}mVqt>X^9U!0DSP}Z)Do26*AwGU6={AzE^_kVw0}| z)>R44w|hyYq7hsFBCkh{$QhYJb|a_3NC;N?UG0%0?Htd;p<3S1iQ*s%%327>Qj=u75{x_a7W_dZcyxVjr!td*TWOmx00W@ zsxT`kIbCp!^?<$;9Dc;r{EmLEJs5VFsFaijb)%EcP}N&%E@tXZzF9Sff8LezH6aB+ zK&oBD3lUu8n=NBKpVN$$F%4JnHN>;n4lP{Q^gw1fbeC>RPv98Ug9Zf5_4mPdd-fKi z^(PjZ6E(OdMtoocm`tsj>W@4z=CO6-@YaeMXn{VSknTpkZv5dr#1{4>8rLQljg`=D zdH7kbOUniBT^=hqob;C6h4Pby2*f(CETql4U;K>b>uQyje-?`A7?P9ci`Y?k6 z^ZQ`W!nr0?U7lNaiElasYT}-ak!6<$ackOR`|J0@li78xk7)SsSNfFjFlt@=QC`gR zULGDVX?N86{?6vZP5D(V=A7Fe_XT)aKO7K+xAkpKG^ZAT{_wVCtYRXR%l9G;qYv1= zfr}kL+NE9B?8ds)A6a4ScT_O9_t83qN0D)N%h!G5lbfwf;T?^M(YyFf)bE^;wMb&n z$6+eY@=~_J9$U4+gIP|{x9b#;(6aZf&FLWVLe(*oR{j}I64D##$6;paRhHG9qQ~{M zGA)wt?HV(b!3QxcS80s!%g>*?I9}fO_?+i3l2rJjrP=5EPn|1>U1ps#9V7d zwLpGSVjWtAZCun#$MQ<#maVGjfTD?O&~&1wz`3z4kQfDk0X<@wwnz6WgTZGf$Zcja zFAd_wJssbBeZbD%#XSZfx}cpt!7Tm5-g-szvBf~zbr}-Y8GVN3J;?Q$5$Jlmv_wb) ztcP73o)$APxJ+YCIJ+BXtH5dU*t_@ohChT}z!r!uVaL?1JdH|>&hovftZyrB7qVyseLnDO@G z!m6bzYE}*w5Z*jvH4UJLH)oKrxyMf5eWJ{|-7?!3`o*R2Q|N~SQm8ram__dw(}Qvj`a3$coxoly=PLsPN6hh+=~0KV47JyMu=aN zvjPuLuw<(+Nyq&oAwvb^{c{gPM8zi=mG4d2K!2UyyO9E1Mbg6Rv=3%ht;AE+>97JL zA`{ZM$1|fz6MbZsz1rq2^txUHJvx*{+hwHeNcSpCp9I)DZCl-P9nqd0t~k)BgLdiK zL|3ghWr8l5t=;JX=l8T5oY?Ac;s0arEd!#?yEb5DK@r3v1p^fXL|W+*Lg}wK=_u2Qu`}uvoEL$@3s}t9`u5*wk z0+GpSdF3lm=#MSmu?yzDO|dNBsZ-VircCtC?wTVX_WbT_ z%z0}*Y-Cs9;;cyQ^~EjyowDgz^`_IKv${pe1R?1ycdnr%JD*v9Y<79vwatP@^)e`z zp2D4|nCr9T?eDra6S`b2##fu@29D1cGJMsY>DeI3p2w~Rmj5vPyvekPYaZKfwy^5~#fUi;&atiWuJa z-9KKL9f{e?xJ{Tm$vHnUehnyCL2s1|Y-A3Y@6gw-P`V9W&&&>JA3rky?EPwzW>L?Z z#67gk7|W%J_Nq7o%JJUds_amA=^-@Lm^%{PIad?*Gg-YYA|oFcgYO)%S;FI?-GVt8 z$}X;6=uO$j-nf)J;neQgvIF^? z18|+e8?ttV(~ojDrEF}$4DX* z@B_Qs#>XM=(!X#`%mGRq5|==syScO=N%Y^;=;$}iFJR~oId zc(LTXT6N^;Vd&wKfWHT4<#lNKZ|ua#%f&!)rd?Tq0$Q!;XSHF5;uoGhT0APwZrXEt ziedR(o9OoQF2i*iA)&$!d6NS?v9%kJd^Jv1eIiPoPl!3#qr=i`tX>_*{#DTek2dLd z1=)(c``ODjz1g}$WJAUv88EAMj_JuJWHfPmw$mk+6S7K>bSm=8()LO(SB6G@+K+px zlBIW^7vr+k?U)EmV~zQ!S0Ul9IE7yWCSERwy&n0szsseWzOhj~n%~&RzHqZ^-&_!1 zh8*0Hck*4>Hz;B?t(=C{0_7eCdX!_%tI8}$p#O1O z#^%rjn*iR)U~zT^Z24TOf_oZaJ+pbXnWAYv09=a}h?Vb1>fv|SB?f0g6pmFhH;1io zZY^}6eQ*+6gHpIihlMPckNH2U!VEyK2pp&2sg zYT9ISU}8TYVL4u$+puz=RB@IRbE|OwTx!U#?kpu&Cf?;VTLIS8!bt0vXsEfGNFP}q zjTYp*#LWyKh4TIHN9eqPTObqpKW}>`n4uE_t3A3b0#eqX?_a6cHPT*;DqoMfVEq9# z31p!A?8yVfw`jw=1QXo4s#5h!@Q#_C_PMuP<0Xp{76^FJFqiB?7{Z3Tbyl_=_;V`@^X3Oi`b* zDt{CjZ|f%C`6);K*x75}Gfq4-`Ch5D5`V&|+yPAb5MR!d?&+qN zES*&p&xc-$WSw5n1`aa*fL$lSZ2%qV*Ad_Om3XwEO+9}{@9AkGJ21O^x|a#1~wv= zw{^Be^gqj{zVj%6b_sD}=Su@|5~S^*do9#ij;(6}=FNMLTfKYaGINe*_U;~MvRM_h zHudjdJEzAWP^`}k;2P`CC5@21=x>s07a*9_-a8f(iLtm%!jJUMQ-zy z!jTgSUGB540}R5Ie)I2YH)qSso6T_Q2_27IR>`i!0Y6b6M14h(zC*r4Vhi6dRRUrk z#LnGw`sG=E(tB;P2cDPXPk~z0&>mbieVfX9d2NEXVvGp$K2CD#tb^m zT8b{;YV^C6dfS!Kc~q*AbGg*=jJ*}s$%L+??V;ARQ4Co$b)p0zBew$JT!AafO`Dp@ zJ7mjmZcTmJ&v%K4AmV(An;%ikASO#BzXZEf9$%-J;y7$Ja*+5kOlfjVti9e6gYe?q z{@SLw!vS6neR@_{4rp=J=QI?MyED@ppv<8F#-20%w`azts&x_|MtUmibmk__hv?M$dU;=SP!A0RerpDj=?WtFAoS-gWFq zwR3EL@hAeLJ&%$fqQ^jMqVglIb(;87S@>jT8b58uZ=48 zT#w}A$9o-)u6RrtoF_2QOdr)d#xPY+Ief+>MWDxV=PH+%B4!G$C5<${(N5+$9?3P| z-f!0^#DerDj0iJ6ecZ+PRrYbs%|`x(dasMywZ#rv7kYK#PJ++M9kqhm4}s6(LGB7L zysJ|u)b|e}jmQtW7$N2-s-JQal`prUaubLs;vAb}P^xO6LZcEvmCmGU#k+YGY9Rf4 zESGjwMsI%XkbuWqi!I!f;^bJD$qYS{QXcjLqE}3(&_}5UAl}WDDt#Kuu(|Lm(Cr<& zTW>K}ha%<-Mr&!S348>3fWRRO1&QsY1gVZ~DO}|m^!3|XPN={=HBQY&a{y*D(Cf^L z8A40B?(-jrNgtE@i-3YvP;5N@X|V^1`_UEgowXr-NSyzur z$t2(}@}+HpqPk_PZ-2hjJ@3zn5QThLYrPu)a>57$k;uBq?T7>&_(}LFM`Q#H zpf?GV5$a&3Uo?<|^8}@9KK1j2A8QQ`V+817*;Gl;SuM^gpS5@2y6*K=Lls*%x-qBs>MPRS3m&#yhxyO`O#Aaq3BsI+;|S z-)=c??^U?CWELp4LW)>?#S25CO^y_v7l{_3i=P7&V4^nnspMdAaU@k|Cj&T)wtF_$ zR(T{(cb$2v0|46*C}+gltFzMyjN>0+#SXc3L1ui;ZSG5-XA9)4R~L!9Whs_#Jw58{s+uxrBB|^7b;PGPX_F{2<3_c~$W^a}b z6nE4?3u}1yt${R9ahn2FRa3eEB&Gip44h98u-CX)BV(5y+DSn*^U1ip6-kafKEShE zp?rbeR#^X6`SZ=`ft~5B1LozfzCVq(uY_D&E!1Urngu;YX^lx-mC2W1+Lg-uk&l$2 zJeJ-L0)%juP4A3FQ2w6`1uthVar=L^4p{X#y5xOU#Ji|}Po@u*0*xb~&>HDaoP2Ks zrGLi76hX^Z1_S3H@F=@5;B;jkF#}#V4P4cSHg{ziqta6-Po_Fmm z5+jI%$}98x2UANknWjL{hd)scs`fLG9-Ks0o0z1G)!{#fqB7uDY8SztN)TMt9N19R ze}(BOKC`=N6p^nBYRiaxh)ER?M6EJd6XYv%_Y56{gp+}#xZPD(LybI z`eWsd<<76g9DLj|IHSFb{DtO3<iZSYaihsJU_B)#3&ux5~%BiDaVhcPg^5%?$hv;HN;=`egivyQ# zzYL{c2@t@4O4;SmEby04=P35&XBxZ~F_)jWSRPqmT9(k1xYiJ0v4v7&eR2$aN3^N@ z$tEaEqchZVNBbmb11|ZCx%qa;=%o_J^0@Xm2_~#gNUVLiPjRDs&w?KCOg(9uo+5C- zpVqW7fr@$@RmYa9FP?CKhssqP(tGlUv8rkjs%JEl1$n1rDg{RCwG*DNjRB(cWT%ac zx+z*HH>LSgy%frVox>YNb(>$iT|~V6LqSEX*w=?UuT_^sJrbwq4Hvh8dEB^Kx{F=I270VE#T zJCI~rVtLkYhhuh!yDN0PsX;6=Gh?%9d!X)=&X_-Yx5>A6E9G4;R6Mtz)MY36&M5OZK9E@(m~HTI!t4-mzVjiK8zZwJ zr336$^Mc+14_+KX%LYmBroH7nxp3?2cS~BN4Yin>VPy6c5B^@#E+ditU;Q z)BQB5mmLx^juWjDl{n7IA3G=d>1Pt}w{UgLuym^_l#lbf7v-BN42l683JzcpNGdoh zfBaZY+I&%ce>8fy_(4=~DbeT$At!?7KqSZ>IPJP zru-Ua#<50P!99FKi>G0WC~9s_YhEV;i{>tj|IFk2q$q=qUtJIVHpqI?mm%uvJB!wx z)HQykJFAAuY$Ogt-vU&yUqD{qsYCibZuO%7Wu6hDg|WNnc6O}z2-msF*_b~Q@p!Lm zJxACk1Fl}jsOV6wKF zm)N!b$6faCr7X64A>RLHsOXb4Hv4?EfX<=Jn_vtMlV zU4Hki!0e^jAr*y}9Lj%2tBz~rS+{xM-er!Y4K-}$zgA_{T+Zj!`7BzdTBUnQUsQ!W zx-#;pOxB`8e&dxB3Vi9Ux*EFr_3DI2TdOze(5!U39lF~ct-G|Brk~BHWzV+86usIj z(~Q6WbIX~l()_;iWkzh-H5uH(nDUAgPu~qv*2%Ls!{3I#OT@EQ%+=lK4!sFh`gHVX z2nyn!QCe1K2R+b$_Cg7_J6T4gPMUNc$yE<9rXK2KBWs{XuW7XAg;<0orU+26CC6B6 z7R0-h83?`?bh9$Ob1gtuhGoQEATXLOg zJZ#q*ePz#XI$NO@^5ctich?`BN4a@fbY%B73VFCitxJ{JS z%GV!h<;87eMA9vNEpKm!AdNlqi}F4`ld7C`8xwg?KHW+t&?f&gI**k%GkkV?7K^oQ zLkVz%YxYD}P?)VIB|MY*MvEJlsVUzfl*ev9(wW!S&^P>1CUrQWJPbEwL@qx;u^X$x zt&yZyU^?v|7ayg1GfMTt)-T#}!S$Z5GS&92qPW1`chq6V)ZR%kSED)}bqepa1bRGh z$&e99$}GQf&PZp~jHFThTfh1cN;6Phrd7qarfuV{h>=iVm`Zz8fkS#D*Ywg@ak2sJ zx4x$R0+0t8yc@nOvXQ}_3b#$GN%X8=(O%DM-5i+hvTk1B-IraT^*_19l-257>lUu zG8Cl@lxDBhud8=tue;gOGnYNF#fz!<(pk{zi;ZYb5NyW8l&^TBXiUU99HVr}g`fX6 zGSuk~9`2^E;l5LnhqBG2x5=vVSSStZYrN7DTwlPu&Nf^<6w9Eiaq{7sy2cG-4JAWX z#$)Fn)L#*foeffz40lK~eIpHSevK>rGym*xcb>CXSuNFy@p2e#E@ElVq)|P8nf(I; zjXwOugQ8WZ&c@!2Qf57{Q*R=!>}39UoMkJ-XEUlP)Pp?v!GAuD_i) z6(oV>)ma$x>&o0(e~fz*P;mO746Z@Y{Jol_66T{)vSWAX-T5jo_#o`CH zwR5IkXJ@o4=;C!%BJ=jq3eQ_4Jy#|vp57Co5ZH3@I?J<@pG&-bD<&(ElV ztx=_@A(_I#2t>GClWZ*U^|}WXd^vvPnkbm-s>}E!#36K%R2e@k-=@w2uul|_?&@5o ze1vCBrC@X=Ss9O#6b{*uk<@~o-<3AHnPKKQN#o$tSZB0`lKCeIsxfc=O0_ZFgik!( zUJnQ7AGZHIw-SriaW*m!)23NAroL*@zJ$VafVB$k-#_Ws2M}& zx<3eayj)Uur!0#9_`p>6?y|@PLB*4x$SFqgx^BT$j0u@oR5T7`%a&`Ofr!P zwM^174L3&ItZZ;+KCyP)u9h%1-tzXn{HaEfqH9aL6|`kG*Bausr%Y16g$p~=%)Z7>yVF)=nazM-k&`=Bzl`0(*_8QWX$M71$; zt)(FF=N3L_)|zhKYlf*vqcRK(6vz~l!G+xFSkyjJpE+Q|Idi^g$59=9mUd~el*^q> zo!`M$1Aocg8B2YnTz`)Qd4miIIwf<-mVC*M`1w-%J)!P7p8SM{T3NnFfwc;@Q6kDY z*eVhu$hHhE|80zUYUo4cuJu8-d$>a+Wgn6i?W?IEd-mafjMCh&;_fdJ$G=+NH`$8#lbrLU?9V} zV}fgmQhw^#ZbP{*Y%Wg53nw#wBzq#tx;S;5Ut)i}4(ZiX<8=d$)XN%uZLEygow}5o zI4-R(3uA3-zWk$?iK&+P6H)?rVQ1@D?VVs}eY%S;aw{+rP)_~7>S9D3UzWMpZIS6_ ze)8DfklKWh1D&lCvu>Z_MWI@nKtRd%FvOL%Jx;%uoMzM}^9famHkz4X=1%>*wn0&j z+v&Qi8!5Vi-JN}hQdru`LF2AC<7vy)iUZ0@%dd#(3+zMm0pxkw?F@&u(tfN8CdADX z?&h91B|EQLUo53$#2UH@oi5ai!?~&6;@uV-UXzhZOCYWwL;;vW@7<*j>N|}h!%?gU zZ6Yz@tH7QM0Z3<{PITMRn$c*phTdsh!f7}rUU>IM+BS!b5{3@Ly0O(JvE3%;)iT)L zvkEgRiYz!A=KnaqCi(v2RGRmDTJ6RFl`b2nm_BI8QIyOb=(vi6B@ehYN9<4edP{#H zKyS|b&XEb_5<5c@ocRu8zMy?>i+kxYP+wk4wd}nqjfKLV!nXG7>ubdpX}sQt_h}h; zvZayP5?>eBlAEp~JnM^I39lt|$CV0SUd+3Q#rFb|5+0t2zwu1SSN6(ez{R8GXP%*C z4G;1}e<3xb9^|L^01^SF(k~pvtz=43!bJrsvvZ4_0?a53Y4unbO>ZgDM3TTsIEBj| zGZ&geB|DRb2O!A^Y0Isdt_JiwsW`1qo^_Jq8_p;TIRZX3QVv9@YSW~TmD(A6M>vs; z%Bv{h!<@*#y8NJ7ae^KX)hUnlI$e3-&F%_0!-NZ3y=N80z!hL!e+sofIT_!fME&T5 zIP97a_70L?aZa*O9orej>=@g^>>B0-wU6UeKbt*Nm1ebg?AF$+#aBKKe}8ppjO>B5 z()e8y37eJ8^4-n%n`|0q2d{N0z)sd6@cb}hKAxzxM|5dn@2a$mbYWR%D9($DJ4|&a zI+Ik>md$z9)amXl3?JW}JI)?s8$Bvio;`nYLT{~aOuVoqoci0f>9NJGIVcq6#g99C zM5jkbMy(2;p1o9>#8ontGmI3iZdnw{^UOM7^{2u1oj?1{smyhpeTpzzKGUXyG4gX6 z+i2j6)>H;e?{th7GAE<+NQlYaVICwJBi>k8)t150Eax5h9>?V$zO^oOTn5*+;>(Xu zLf#g0YRpBjT{2QPefk8d>)9g%~)zy48 zXtf71YH|F`=hwgA4o2nx9Q=Y%@SM}`?LDvSZ)QLjBH025J6pse|Yp47BN_e5_%txzrHv8hvy3MT-X7Xc7}l--bBlT>x>)>>|7`{$QomfUYRiQQ`K z)iz6mRjrNnCYC0b<#h610=T(~7sdOs5k~I!V2qNl*?8|`#Be|3|L`o^a!2o!KK+*H zS4BMBM5|mI$8}Aqy|=p#C9Ql}kso_*GjC&I=ZeFaY*liK<0%|X>~x)9Rnj}JZwWP> z#K^RV;o+K)%zO#F4W8|z-RhM|)Ge=005hTlIn7v>y|bhH3o*Lpy(rp2{(k&dMtVlY z8}XA#!zOW?TDBW2y&-W;9wTte{QWmtSzHmu8k8|S!hvgB1s!y@NIEoeXaAP2g}%eY_FEfZD$`0(3T_c(EPVIjNG`a}o(&PpK*aDwYC zcdHmM_g5nx~hAPj=&69c^t^ zEQYGH_uoLY(@}L@R51Dhy)cS>lEcOL*Ox|%_&SvAIRA8jg3_Sfk9F02OBc$P$F4?W z)8a%Z(tE{h>py7Ag0>6`KCN25XnRa}x%wnMTi)YsywfMH+3ZPr=lyl z=(hhTfT{mR9(e*_e~Yib8#9L-ZUW+ca&4+*Rafnz5(%OZIG z`}NZ%6N&$SJ|PbV$^oZ3qzF%pA**|L`no;uqn@a=(t@bpkEVEj^^B)55z0!g(PQFn z%|x&D-Ntjm4@~I1nzS~GnwXn5W_QIF%Mj!J%w}IzBB>__K(D;n&!bU$m;;z}$-}=R zsx9ZkeloNHfbi7C1#-PhTI@#^c73ntBJ~U=LX9-tb?EA`f{WZiuSiV6J{iDBy6DsV z`<)w-*V)`BnTZqoF%J}O^`%_M5txBkZgtP46WwUrR~TJX^!?%JrfJ5Ny94G zb-#^?;uL}CT852iEK1|+nV#B6J3QNG6y{>2b@oTE)C)w+#F6;WXOynDzu`dc@B&{q zVEY9eMfs}*SBESwWNlo(_L`td{`vXw5!T6=ET_{Pdm0e9l%AX9Y^S&I5+~vzxA6iK(VGLhQAVz^H$ID1CmB`HN z9S~&5OxlEnAN{&{ip;Azdq4U9oTzMD>5ib1P&+9dj{tC+3EX)$bxYo_Um40TATMaR z@-TMTLWJnP>J57x|0w*;YyCQzKV6?oqC5-unN44(BsspuFhe5jnN(|1HZm4W$a!Hn z(RfkbALV*ETE`W7*Cf#pjRmYDS2PI~_4^(d8pX)<*(+gGMRWL3M!!N-?rFChw?#cq z>SgD1Ts>hb7e5U)!$hG=?5r=$v2*-&K^IY~Y*mGoNB77>B8u{V_tzmwz5_FUiNat1 zKbY-_=aPHxEl`i=v{V+D!w^x(uft^9)@PD>7h5kkznAP?U(6b9MONj^AtT}I5+)^< z+*DR-YAJV7Q_VZ~4kN*^yYynOEM4wK9XmG;dQjgd_s=fdm^6d}+iUM!B;o!!#r9?h z-T5M4n|9gzk&*jCZljy@Njt%oPv#fw>2CjCPdb&80A;vhd^)UWckq00TVem3ttq>> zDATWDZY#MpxdN7I?YEE>JsZ;Bw|bIakrf?#neg|D)E@3RCbt)~!87C}!%cBa!4kTq z4wc&d5EMK48GuSdlLAkG^^zImbyx__a~E=`v3FHXpUI+ed76T)v@J3 zsJasOMAKVTwL1QXV0Xt+gjYz?v|6 zU>ap_pRbW4fh*(#9leR9sI*2R&4W2z&aX1P^#wsV>$opZ<4h3?rhwGSNGyzT^!4cE$5Ys z7~z5b$F5>n=SUqxqPwppFp&xHs3RR-q(V~3BV*uj)!n%TK)-?yM@>9GH^zvBRQep} zx?eQ%Ml%>jXcQ*d1C5;}A#gt3^l1=!oW6%Fxe1xahWPlDiE5yD3pq@wP0Hrmxraqq z^hCXybEBJux|y3bJ$8Wwn=}4yuo$p_mW;J}d%98A8s;$nov4xuw`zq$=Nym8bPQ4^ z$)NWhE`50%rRjaWQ~~Bdu{p_wkRQMBaUP?5?~|A7p^iJep3Ab+SdLuHYftt@6#duo z;Sw}c?gw8i3l}CXxVVh9+j1o=oNVS>g8LcF_5SxcFKMQaeHz7O_2x$B76z z&FNhlV%O|L2GEVs9BQJtY&8`E`IH0X$LUg`F?Obf6BqlEdeem+S1H49GQL683>_C2 z6fRm#j@x;hI-#{th>a561hA|Rhs0;*3)cT3hU|;ue&1`!z~7Pk`rio`v_Qe z2TgT4UY4eR4(Fk8?DoMBf6WeE9QuxfY+&18~zGL|LgJUneQ()Ro(U}L&{dsmUBzu z-W8S^TD2oWk$rt5ku6dPem6~I*UU*CJf+g)e>~+FajP$gzhDTbX6jrn=fn$2mSCG4 zs~(lnHp{_~;K8!PCJLDu_owK|FqM5_9Ga?T<3?mJ5SRdbi^+`=$SJ%JDZ~h0_iX^2 zlRZF$YSEiALcqFDZKBA=ZqFQxUO0XtT#~U9);O?b{QH(-d&?#49Kzg2`D${Z&(bZ4 zSuiR`q$ZU94nqG9o=88!us+^ShOTDA)e<|8 zY!N(9`lw7Mj0dHoPVsg~r&(;oT>az@(}(VzgK3;H+s`&Dj(qkxc2=Vqt1N@F3!rHb z_{v@H2t3Cc;GbPr@^tvUUJF|eb3e&fl2cK^yK9|=;C=>Tw|b{$Q|1W~P<&k2I(&|9 z+YZi@`di(8wc#(ny8k?z1@>PhhCTQE;wy=4+S}`khL2CE|G0ev`B+}b^6cnCjKSH;vLGot!XtvCq+<0AAe0ySe zH$p7G1Rl2ev*t^CTP_(!q)_j$lE*31zCWU8FICv!+6!D(v6+#-djc=%>S-*D$^4F@ z6P@K3o2UUk#r?+}>`kXOC%xC3G%WG*9Lj@Nv(I(3QRH^6*lzhw*D%R(@syOpTT^0t zqb>gHRzny_2dSXJ^Cvv}xBiA+&%&6x5|U4fXUjoQB~u8|I{f6gTDj-ct`jHOEA!e- zb&n6@`F1z4EW0DhadIBZfjg!xQ*llg&%7V|S95W|GaQ_|!ONE)fBSw<{Ui4*cHBgf zo$VOwNJcEf%81Nc_z98a?=6b={+x%AGd}0Sx~|aVZoRxn4Lq_(}6-@b`K>>52H6uQ&huZ#zg70Dy$R zEr_*$e;qw3FxW>9is@(oj%}7^ZJoz9QKincf0`fvM9F@9CGwB$-M?}1V(>>-Ec5rY zyQB|*Ymz-WGP41}5TQ4J;T=krJ%fHu^QM9XBb-z%UvhXGEq&F<8kJKkD4? zz@c~*7H2v9|I)X}6e(tjX>#lfYdT=l(w&P+${-QmaL5!jQ*I?ozqMb>{J+cef0yb1 zF4LX`{Qs$C%DXc6)smoKk$*UVQjPv#RPg&pUF`pE$wk>1vDVD{_Uj{nOVy`d>;xhR z3r_*ti>oke{kQu45Zoxb>tB{J}hNJj(*q+<{p;=X_Lf zu%h*)6A7P@a1)vdXx1Ry5oGWZlJq7jWdW#JG*>|$0xglR6>UtWhX5J&mLR1xnDWmd z;5}4{{{6dO1wPLD{YgTUWN;sLcf00NplI+J5r?bJpvn#jVNu}J6Phhu42EITg3hCS zaS>X!HOxrx_8P=NWQccmfyLwNKHL&wgV4h38^B3_(jD_8@>EWiXGUtNA<{m_m`xg^ zQ>W~qcQ`Z5_LPGW?rQ5liVlkdU7N`f1inwkr03^=V`$rZ&o%cE%tF5mIZ(P7&GA!= z&0Mhc9^cw5|J5CHTY-0Iqv08vek%Fha~7}xXOK*XK;B!ctWoCXypR)yy9)EpbqPV~ zwJzs??`sU6DEw_(_D6)p6}!jcA~ht97IWo4Lh`}q_<8HEtd^FD*u3LPN=#28Ubntg z40p1OmHvpuMXLMdzo@fQsH<5o>z^R5BDR#fy5BByuf4(FE=)}hKIeUV*J?9yWTWTd zau^@RgeaPFpg%>zqe$qCA_mTNR$uW_OfW<-M36?QOCI%+^!*HzfI^;0^$5qwT_vK3 ziiBQTRQ&}%$CNeOHO<~U8W6>z1g8aO)J|((hm8TBy5C3ZAKT+;4BUR7v5{be_)%`E_NC( za)uomMdjc5=i%%&jyUWY-ivF9yVWmt(FzGmWOms}B z287x)eYCMyDD{Ovs}3e1mnGAM0F2uuJGu*T9s&aBLQoW5htYrmS{vRI= zZksH&orE_U33m;1Us=-`f$TKT@89}*vSBMjC^ccQo4pp;NNzV<9;%sGQD@!`7eF7p zbZ^`*OhMbQ&?>fz6eZC7qWQq~LPY%5ekYH=uR5}uo@L}f{t~MgEes{PfX3~W^Nhc6 zS4@;bo9^5CvBH=sXCLF~fpQ7;BHNMs^4bG%JyMt%u{wSY($~StbxK++o{S3Sx6en# z7yq_$fUv(8rz3N5obFMAOi$$BWjT}70Bql}g{l3`$ z_-e5TFYVfgBx!IRkm*--YGDY_`xqzxL7R-Z>HMLvHW!wp4!Ep$nShpfbMB8R zKot#d6#h2fd`_MSyttfxqZ2UX;xDP>Z_uJ=`0po_XWUi7XfM~qDgS@lA~TsnOTM0>|4=bRwB_uc!1ss_YHhq*dG-+lfgSo;x_f(&s6@gE9W2~ zT4fDSIu#??a}bSk*PQM%be!pnI3w=n)Y7*)I}itbi+F`8{{ROf8T;o}(Q?acxYAkg z?yeXp-#=ArMJ#;cyYPDfstxPDPao$`A_lYwTIDGBHuSaw-CmUHJ;MVC(Q5;guYlWo z@5yKRuUC2LCajgk^I8BaN$Y|nH1?4#zzpEKohnny2cyiYvlB7tR+a~lj70J&*eZ&L z=2y_aZNt~!wxLmvY7zV^n0qgN{TyKB))7}GwS`^9953l9w+7_u z{KG=-yF*58$(_Dh#^zW_!S9px5q#vrtQ#~x(%uR|5hMq$pdk>@YJ92L8^t_eUad%K z;gzJ#BPY~s!A>zB|Dty&9v*3NqTG8~#fO!40iPPcAMho8;;-Z_V;wK2Ltj5f-{VW(s=p! z?6L-nh<*jxmBS>7V3l;$j+w`zXc}9*>&lc+myY0zHFDiGDFhF)+ohQ~;;svGk84P1 zwSqRRaH!$Hr(ZY<`*KXJod<}b51k~-2L3k}3rs=N3`HL&3_^Pzc}{3}GF<3EDC9kU zk^PV80{qJ}Lbfw4iihU}u!{mUh_sb6_CoggtGe^PXr_dpeISuQ?5r?R<%BN0(~o;$ z7N43Y)OI|Sl*~VO16ThhW~29j_GBV{?(#0udEyk_5M3n2W5wE-snMtT0O%dg($P|$ zk0RJDZ&oBLO4s{UC8iYmr?_q~!Hr2ajr{kEEl~Fb9$cpnf4RS|+)Zs{Z_4!D~~{s!B7oGCKHKPee-|xy%CeiSqW}6vxMPqY>$Jez*khhHPHiAyzJHj( zS6Vv3s3qZ!cEdIQ<)kR5y~1$7}K}+ZeYeGsPNuxE^YGdF~gD{ zGa|j4b(LnsL>bCroOUKEREE?p7mDMJ!PG`P!8fbce;ZZV?vubFAIDH)#!v(<^rG=^ z7itnjWG3_WU}9}@Pw_KN-$Z;)oaj};3GoCv{$oa28HxDco;tG-uaWek-qp8E{+810 z&C+wRQm`<#qmdW>N0hH_GIqaB~CN!@grh=4(?LLZ+&F+pm>r0Q`Uc4$HC}VyN zE%uq+D$^@*L9tJ3w5J@4&4J-pyoJR+k{0lBnJwl{_mI=OyBFLvGLj&Dd)ftFg6%u) z{)@99osfvTNTz16F+G(+W4gHhA^11a~GTr(}9xZHt#TjH9x@yBh z=%2`t6()qAYVz$h#9jJYVcHHqirj4Gc3>=1T%<^>pN!M!(D_}bR3ZPd+KOC0K0fja zdfOo`_ldi=cO5pCCWfI`*_nR6@-jw_WZfiE0gG)d?Dn#s?W~OR46?LqLqTJ4P@s{D z#g;NU?|iCY`wEgPF0Dy38Qf6ph4Nhp+btiMoG?F%%uH4q(ANS>!!}h(LEJ+Fk&LF= zrrqyIhWsxTM$n44uwpW@|lrUZC+E{IXwjOh2?T=CTXY?4(1=*h1 z2~%ChVflf@*i|Z;mB#ZmeS>mgx*pCs4%0n`9cd~7$FET(c=y@$P;ZnY!XO(W>rQI2 zCld276yDLi^Oov^h>!ZE&}@{J^o>cRAkrTFcwA(-5ef$Ulb42T5cEBzoOgYG-Y2Jr z%y}(C@Y&N6P<3{_*LdbkT&>6|DuACCucTk^t`Q)Z8dTq1_)Zg!WB?Bt582<_U!(Kvn95+9w2T0K(=l)g z5m8>vs!B?jAC%Zd`7@0@-2P2K8T8}2iMkC);wc%rqfh=B;s1VLPpN|>&RdS7N)0@D zlRu48n9Y3c3(_>7WE#k8Gp(eP`e-Tm{7U)(`yD}PdBNfJwqr3@7Ew5LutwzSV}Z<> z$1b@2VM(X^nmtoIKIM)xR9kAkJUvWnPZ_%j4F}aG+keg3bQYcq6Ot9k2JZhOJ8Hhw zQ>Jp@*4SjHsemE@^W@jY_?gc>CA^gMmF$eFDOD)oU^Wbc+d=6vq?>t?|0)uhjwne5+m?vAj`R<9iK-odvuewxDs7Dm5TWN2jehly2L!T4{W==y03UDlr?lr8)XJ z73@}y&&`H7bZ0cu=tAz6nb2nGyy3`KX@9BA8xg<8*B8HEnc@&;;z&RCR$kw(V|mp7=Omn^GY|<`am80A8-(8%HhLQ!fZ1(+!J6)NC!JK8Fx~5- zoMVl(3<{lWxR5jEs$=bg8Nx@Cm)^W6b$xge01)O=+vkB>^!=gbUuNIerR#l_SmxSw z%jgOgGJ=l&kS(-t;&c(64R8g=(XU{XL`~y!@HN{n)pkvRh1e(>F!^RLLLdFrhvdI} z8ZfID#3q4DBmP*@f(_EJqysk>ng2ZFP`M`RcZ9++nxo5T0V=K&!53 z>b6yVup4U}o*S$r_jvFgmpA4oUknq-Eoi9ux*9T@C`1X8A4-4yGE1*y)kyXbzXzM9 zU**nboSEXt)^4|vx0goT@yrkiu@|@MBGE&$EGOZ941Ca+&M~Nd`64M|G^WcMSq@68 zvnv`HKCBt%W{@0Efyj*hUxT>t`|u%b6w&&t_Zg{rJwRP3_wt-rBr@13Uw)n=qz#AE zQCUa=bwfr8xeN8q(@7(>z_SXr94N!7`sb3p*$?t_J~ZS-yW>68)wi!d61I*+>6Dn+ zA56en>$I2yhl3EF=*REp+qSSq_)nB0$vCAh2l`_q^V9 zF*g548be&h3gA|_;APskumpc4p3DCl`yagx9!T&bf7=9QisrE91I5S{iX0i1$u})^ z5QCSB+G%8E+|#$kI{{!64#~Ok7Y@+q-i7(%ks<+km1&J4v!%n$3DOZw`6`TOg-drf z2)`k#agpqwLYc=5S}C8_eFaVRzox&3z~>v%GfvV36a;jGP3!D3c_#1!YMJ4tz7U+= zMHqxB0U3!svc5KLhlFKa%`n{$wOJ@hYAT;ne_%Te#x43^O`j3~fVWQ`ddjFM$4Ipf zavxj`Ow0O^VruX4N5YBa{k-jdFN&Q;8z8Dv@~JUP#hWuFwAWvupZDAn7tCztujitg z9@RGc)+jTO5v8(uVpMd3+V@4ZU&!LISvmH}nBn#z+3HzmB6~my2`SD=FCjHUNT~+O ztrxSBj)YR(VGpJVl;3z!65Nk2%k)dcUk#~!nmGsm8=0Clb8|2p%iRx=`*o`SdLfX^ z--kEyKD_THqp+u9{07okJNJ{o?6c0itp`z*Q^hH(?WxK&AVH@^nE_Bx13jkiCr8@X z&h2b(BCwq+|eY}~tI|LU<-QP;?BKh;dqxTsJ4|>!jn3Gag zYm6dQh_&*b$FyrQ4Ub7f$a30tsUhZHxArc$-m)bgZXzOk5~&N5fJ6lc1)eQmkS9#L zDq%jPxJ+92Oq4;hPo*4)nEU3S09N86c6%?!8<&Hy3*E}R`H_w7$Ou0X2brNeFXybX z5y!FQ4-j}LoMM~g(7IyHsHhGWkvC$WqyFD^9)iXj@FEWJT$j;1LM){}3!P+s-?_#Zi!>Ga#n~Fz0_Q2lY;=Q_vs)VdmuZ57)1zUnUhItSIv=9}+ z;QwT@Sw*9fK!Y~^vQ?Q(@|zV>gCvyD2k4qQjJ*FHTL5pO$oOVe^9}O z={2Jw{&mAng0HwubyRvHKvGZ$`i9Tk_1GFZA2|9Lg0z-hW9m?O;rX4{1Jo7K11mKkM~-2dKd~2!|~ySYw)`38>pP~Gi#d@{QmXZ6IUUh ze1xch{M|^HG?$U@O~T8|9AkO z;;{Um1GV@t;}F&Mk_Q8d(fn`T`&x7n?qIjU(ab7bHHdqGQR_butQKsX zCU=t}t$NEa2at%_d+h6XV!H>Md%j(L+2HpVXrZ?+RgQI{!`sMD)IBo#`V9xPpJ(jYc zNm2E}qw!1GP6c4CxV^9FzPSI5*~tSyQUydWsO2>1^>)|2(Jt1``YkWM6FGyS$alB` zfk!H5`tQb5z!~sA$p2Re@F0;9T%S3v^_zOp z++}&AV;19G*zK+m=;kR=wA2cTPzhW?CVz?P`|X~WeP^3EvtX)B=OIo)y6TffWSx)p)``ksw>lAi^K+8nDY2%1 zjc)$@{0>Y@2$@T)WU*xDLA0}TPw^Xd=Q*6~>g9B3BHupsTTGqUHlHrXW6`6QI~slc zW%I4x^`AC#UBJvPG5usmQg8OHONA^ux97N51EgK446QAN3_ee5sB`8(XlqpT>5aSqvYY0zB%;i%H?iZG(}rQ3!_Qya~`hfobB zag4*gbEOnmqhsm^SPLJ$j9`-3>PT2k$LgNcbXi2bt z$>jRqplvcz3h#6@CBxlxqfcxP}@x`>?Ujt-NaLMG57N#jvSm! zOA)|C+vDd<+$(r3tB#!&4lP=_%vOQ2cpSV^-2IheM}|~S7O8=R>W=+uh0+> ziH%8e%8oJpd?wH~7+}}maIgD&AGEPfjeAHwJ?7p~tz`pw1I4zH`ZIwoM6Ff9vQVp~ zKQtG+TFR0iRAf4IP4=YqYgGNKOSj3Ag8^u8)3Dv%SoUfv_WXPem@fCEL;d$f{{J(B zfTP`pWN;Q^*@B&_&!Aljl8-72g9-gMWV8K_12Muiyk14l2INgX6|KAm zWYf?7NUQQQsQg^PhJz`&Ce|V#MDYITALqs}Re2o{$;J=XC#_8x3I7j!Zyr!%yY-Kg z5Smb-lnf~vY1B+YrAa8wNh+z`JnaTOC<>tgrJ0IG&C_lWMQNU=T}kt>X*bud-@5nS zIXsVZ-uL~!-}8IV`M&;m9#QT4zOHLsYxu0SK8wZoW(fjiAwl;`rYp_ai{3td*I1xn zWuK$Q7q|_NHpZVWMd~jFNQ#o)S&@A-0BwhwL1x0%uTQdzcX|J|HyojC*=*vM485ME zT9Z6)<8auyGSRDr!~E^VLC2nn#YST@QrtJ$Q5`vyewW8LDPp_UHPAUPAKX~}TZ_vN zdQ$-DA~GuP9_!fgVR4{+9^)hVwf~7hxFpc~s_K9JV+YTN+upl@OIzl-BoL$#^SKXe zs`5@4jX-rB1c4Pnw*x8{23o%MbVh0P(kCYtT;EylBRv&`wC=oe4?33kDj^yh-R>pe zrBJ9ahxlZpFfyf4F8f4Blt?dtN|pDNoR_mYtSaw~li}zuW#`pVy^ozr8Nf+ZJ^s-3 z=t-p7zMhHtIQRZK5k_HETSm;vDw1t2jFz0}AoA`iWosLA4WbXUTwb*5=t z0B4a$%? zBPUCC{>4Zl7ezo9cC5Dy`ze2W4wSN=@?olyVa&RZmD@YP>eQ*eaK2T*+j<`kY`mS% z_Q|xpqEb#_(Eqb3cUaK0`iit>ES0ci=LL1thY|o!jyZ+PbM`X5=Sex^I?-l*<3cJj z;N$el)LfsxKM#K7K*jD(#&*!n40~lFHo$|;@0^n+QyG)*h76oZjw;RMEfj{`{qA&adc$J6_-9+xfQQ_mJthx_#H~x15@#EqOUqXG3o& zf6S2owMOwfgIDFKRgsRn)2yT)`hZ*9DBN9 zJv%+IUgt{q84OfiZ@8vQ#}UTF}1B+*cGZMxMt2&(u?M`lcCPjb{fz8+bAz?%Yz>{S--O_y^GN^l zZgKl~M`=lh+T{t{vehK8XJk$Fs>ln{%9kS~K4DrCf`S_Mi+@D;G`Pqaja3A3b4#_H zSHWD5L#T5`I%ja*1}aBblU1 zkw{tgf;uT+yg*Vx+829ia0v#4k&4?%cnO`?0j}koyG5M90;mvUeV}~u^M!5>93-e7 z6Vpq24i}Or25L>O!||RqTDMCi3w~P@=B4&*e8rLken4}$UDEshy%aQ{v4w8L|DE!M zc(AH=8enc|MU+PZpQD*a8`qtR#EcR|>3173P{|{(2(aG&eA2BTb zh=Iu{*{6-g-4~{!KleTKDMBhzxRZ1CZCa0UP~9|<7w-h!QZdgLm$(^fu7>sKH1Uov z)A#Xv&R2efp-t!dST3_nE&+}@{~_&~(Ufk4uWRU?V3A;LFwd{{3p`&&>SZm+=1g(( ztv{NP&gb0FXJ5_VL50d(=KwP2Cz0Tt{Ux>Y6hyLjAv1jNGoCb=^-orblIkq9fJ^U< zEGHNJA+3}wF^y_oNa{ZL4$-OEO$06k3_;Vc-Pqmu%ll041=g1GxBw*yK`vejOD z4k&fx9)3({4Gg?x%i{HFhx28}4XU9Fmyme{1PF77o!qKc+wuOElR#wh4J6ac+4lC4 zCY6>#xUxqj@ri3JgpcAB#spHfkyOIF4vCkozbgMaUfzm85%iRDiAqEONQ$hLN zxQQD1rSo$~*06RSPqjotZg8E0`lH;Y+CSx%iS|Ku6qHZW_R*iO>37p%3-7^88u2U3 z&IBq|YhT@p4G_%ml#vS@5Nlj~16;8UyWKQa832AT(U4Q7ge}=hSwc_xR4?$Ga&P~B z8Q8af=FS`;^ucA=tXhetTY5JpOlTOZp}wxTuw6-zB-9OjP%$vRRmkI)(s(u-+-Ljp znjzw4l#Ku}SY)Wm8T|YL`{6UWj*1vhP-{V`R9qtJ@XL=m$qM#dw%W^^&&?m>a zDaW>k0UJQ#9VME`wSKknpdwD;mJMY^f+N+q|B5XUq`D$;7bgmuboy zvd|rvyPjNk{caz;x6*+H8Cvk%-nWuGxBt||gOKeH_MPN9KmlO%$)?W(Shpj{{-eir zMa2`jOq_5Pc|@$cIt`Q1g$FN0LIQ zVhH%x(H6e?Wf;Ux0Wm(+ABI#U`7DMMROg95C-sTni*x|Erupu7!Y0xwei!Rw5c3Cb zB!*1v^nMVS@jMz@5koR1#=l?Y|J9udKG(A&Jxs>^(8fp<#Pmz&KzgqIN75tIekXsm z7Jwu#KZJV_5&t(N$#9<+=hX<0_LIEMDa^nhd}krBAxfYy)u{Tu504TApIdPD@^ ze#67Rv1*b{|7T*=zf%fC5d60W{#Vt&pazScj`t2H%|`!_y&H$jUv}T?3#8OXWFC0A z4uYzU+krKuCMh%Sx}tVW6FDoYrVeobzNa0(%x%g>s)N^k>XsIGsrrxDBB~n3#L;S_@f8YO%Rkm0zU*y{N!n+E4YzUUHsd|Jr%GEm7PMRp==^ z87q%{aUigRl(O+^h8&uLctxD9;g|V1r8)_=KC^G zmSB z2kmtcgha=viHr0vYI2dP^Z0MWMCK`Nw=XNEIPA@XhZ0J^iN-%w)8X2oeqJa(v*Zrn z@kjU1-8s1VRLp0N_#=BSoZpJu_Q&~;{4YK58?_TQB%~Io_0sVh7z=e9o>Mq^zaDV z^a#TBm^#cX24^`nujl5huCKqc&|(VY%RHSE@yKkt^zEvWZ~TPrkG)EE+JD@cy!o<` zeH06Wtg5NwB-${JZCV4%^Xzt-g$BHJb+1@oM`7EqRAFm__Atv~s=~Lcl2Z1TR6NG& zwte?S2TBVhpv3I7Jq!sqUHP_W<2&XKSN zudh3aJDw`*Wx}Osl{Xyg_H-5|kMIYvoTki}|YL($~`T zm;c8;I#a&FU!lqE?4N5Vgrf;$Af`SZLrIo_a7W-zRvxku zIz+jTks}-HY9ak8bXkAaZX$Q^Dog_GuC?@b9X*^EPP)770z8KCq62s1C9YhHcgm7% zo({JZc3K6p77j&vVrvRIgo#IThl~D|r?j6c9DmhidV;Yj&&aJuTNcrx7qLb6zt8J545#pR9ej1H$h3+0 z+)(#Fi@M%CK@To^xB+q5URIlUqCK&<3}LT@jkfnc^LCB7@>$cyzTfAR`nDe)UVBv? zVPOFwgJ$-Sef6Jpu-_gyT|ovLM`3gCx~}q5_q0&ddAs6r`W}oyn@RNq^wf-nqbEKh z(@ZlB_bj%SUtJu}HkfIQlNRpCFmKSUcZPPws|fdxBQPDANH|UCq6c6$Z~&`)?eR8f zlzuLSe^&E}7A9anYhmf^=+Oq&`VVX?bLDj72@?;^+thH-KK76>=(%jVyr+{U8QtTx z@v6UTW6Z$7vvAK2%WMr*bw&vn^BJ8DMcxs-TLCk1V zmyRB;DJNhYA!g`;uC&n^*O6CoSE2I^$D?Bpj6}pc8mR%wB1|!k#GUH(lF2OH6MNu1 zvVGY_#yfS&qQtq8s?2M+gqafC z)w)o_kCb_ni}?$KN{(M|DG{yfX3F-Vi0rl9aCt1Xc(2jOVf-HNNw)%B#lZ37rB!C) zcopRV4fIz;JFQC@9w`_0kE1-%j>T&?e%S%Wrs<1b{%XfGaE{!H!Xkr1lx{{fxY0_C zrH%=wxG49ptq{6154=Wup%bV>sIp(~9cQ@n<$iQSAwraKS1vP#?(Djhn3WRUt|;sZ zp?f8Xu&0aF<;$aaHJc#Sv?XK?n7NiqC%&HLk*dUaMg?kIS*~I@#a!A1ogmRDVHGLb zKc1Q5J}%U|>Uyx(x_BioEhjI#4En#OL7Gcs=_o_SBC=)+kh>vh6!H#y=Cuc{;o3O}|H z0t_S(b^Izsay_{_0lU0aR({`1AJtbdM$c!ow;^n zUMi?8<(rrQ=>YGd2D^h{K{j%24&JUbQz{jK2CFrJ3|s8`XPu^N!mNq!nYu)wJXNzJ z3Q?7QsTLN>au`bmP2D&!48D(jH#zMh-W4hyftu(q(1ZHP$0Y?WS(y_;zwIz|Uk}t= zli2h1tFEXpCDXA+iHW2HbF-OTU_W&nit?cyKR~150fVQx-SCz{$2(L#CId#XwV@mI z{KZG&c?cU#64t#-@Wa~GNVOsJ$KGaB#br;&uC23)u*c00Mig14iqPbTTfg1Z2E*!o ztdu<|PPxXQ+E{LlQcu%LOVV%`eZ9^9NyM@}!>S4)X1I-N=hfksdSO;9l4J+h?SX@W zT(zd2L(}kMqt$^=*F}uu-S;$;+b?#2YOlv&)Kfbrn~=%&kKe zINV5tL_1Mm7|yRBXp=E`aSAj9Z++@;Ciu0yy7+m}?&^V!XA3Gx?v|{V3j@b+mA3iQ z*~RV^4{nLGHyQcSZI#~5i1EL;hIf?(Hl9nsN-OR2xG_J=?5V~k7GH1uh8yEZ4YUJ@ zyx%>RL>`utysj2j%&G3c*_Cbe)X5$rWW6}7>gj4GEBfAbVK~m;UBbGKT{#tMDPGu1D@i@%lEg?H1Qjs-TS*j{t9@D` zj5njOu~*{UND4xOZA~`G<&~vKXW#&K98K^guy>jV26<5~N;C1NrLLKM1T}fBp-y|% zQ&OPtV;lv9=PKMkaSNT)s3UVfG&FZ58GURtKe<7$A8lsg+?9y%Vw_ zSOy67sP%N1I)=36Q6bR2j_Ms7XRQq z_^$G%Zu&%3D9A>cP4Y6=P&6=bAi61x4j(HTl1Z5F>LzrJ^+T<9o=N^B;kBje=&D7i zpkzAI7`ov=HVg`6xEQv#s)@zVTS^r)!C0*v9jmKjosO%j+5FAvN^|2@z??!W}#mbx9hZihd`5ZBTc2lZ;aZQHF~r zx14Q|@y{7WVk$F3i(@YY|ojV_431G5WFh`xtQ4!{DgO$ra4P?0mScDk;GW za~0wnWKf5_T_iPE+}M1pq#^oDFU*X<61~k#4crEznx$8XR8*goS;5Oda0R`Sp1eZK zKpSB)>_5-DU=RCr!i#qm`PsP@y!*53{7$nvG@iYU`O=Ox@|f}oJq%+2ZvY;8VE5hyTLfNaqEBcRq$t9n0^haRrJDLi*sw_ zQ9^ty2g0Wc(hO3>8+E=s9Jzg7^b=mNdJ%?gS!FqlHb=dT-SsrwG%;M>u#UpJJMY-e zr`1hnR&lJsp)-YfM*{U^YL1uZ*(m4FWXv+YZwanC`o3Vu(@DE1lmh9zNJqK#vCI!p zPdf^hI}+#hb}`1+%NTffjYgE$JdVN|9vk_KFO?R3fS{gX{!~;rVZR%(3(eoGOXat!sf8k!6U$}I z=F;GK?#{EcHxzx3f8_6WWhi8dspE?FtRS;fnCP^M;5{@1|5p%gqI;RY-9p?VyUS50 z3&<(1H`;VYI@IZebwl*2;;vuTA2~G09`>@t=xY&H>92lsb4@{)R>jU|uhUA-PI^o~$nO;eO@zv$h1)y$2>hR}5o~CpR+l^ku z`sjz;Nl1Fyq0JfADT3WBTH`P##T4L0?kjM8|^HJ60bXq^99%*)<|HnwWl=ChS47jQAN{r(%iml{guKxg#{Rn#e4+ z)uh3dlYsvg)AaHkg9Z#c)o}7V^a5X&U`uK;P!4=sBDqi|Et>8+sO@h=9G^<9rg>!} zgNs`VXEMj2ThGaErnPV?eZ-n4xH4745*0MXt{#x$fD&v;Ia=MIL4N`W9vyt-kz z3KUS?+kBSU)zUS7_U4`?!B`D zrx$3HpnHD|^g3?$5h>C)>En670y4_MZ>VPV86L1cXh&CFlD|l%%K=h5)4IlCjP!T@_VYh~n7{CP2IBHg5s(0I9 z|GD=>lQ1O*O6uw6I@@s`5JS^CiylB=Xd+z?kV0Sqb#}s$Ec2&MKryjB#o>F>0N@lR zsm4X{;Q2a$D1hE0pw!>8aF>|nHG6)bg}pN4t631;Y{bn>n=IHUG3VX(dP`h(ZESWO zt;ea2W`3U)QGG;qImgsYGs0^*jC^U9iCjkCOvnrZ?+%m}6LEtNr=^c7ol1y!jnd-F z;~QU@YEb2O6SNH&%)6$q_nmvS_Fgf<2ss9R@wMfzm3;Y$&*UW$R2{b4>?EAo{zNuy zc0}&p{3v&)xV9t5Q`eyxx9fy5`s})VB$~q)(Si+G;(Y^AIa~WO zav`omG%B}pJtP~GOq&56m;O}|)3-P!_oC|q!ZRlBXT*#mtg{l}Ra>xDM6c}-m&5q% z@o=6&nkJh=VoICMwWh&FvALdNUQm8R;}QE&uj%;clw&7!UQ;KDRy~{=!k)4_=MXQt z{@hgT=Tce;9tn`iW*3%`BnL{pRgX#Q@LD;HQV?GWkpaPLFZ_-6qz)Wp$K&Lj2T@pG zH9oQ%GO*7Y=53nHc6+YqhWGFNep|bkNDJ0)h#WJI3%j_b(CllbSx@>|jXG1 z02#GK`LJo5$ow`!y@I6wX(ns%IcVzdOo^`6$+P-ZWlR&tT9JBR|hIc_?op zF}?bAMoQCtf7;<#PkoU_iBUDjx{lkYc_CJfbxy&|w2!^r!oR!1q%QSM6!va;*Lo!` zf$>P~j#-X&aXCkaln4j*L^BM@+nO6G6RydOlM=<>J9dKFa@;f=@l)|)8cK619V*_5 zp4g8W?F=M)s)&fnv#giY?P{phj6;flaGWI1BRNfhL}6L(i;krjsfygBRXU9ks*^h* z>WV&#jz8KO>V1_zr{|BT?Ce-H9fHmTYN#A~!NojwR_dJ=4x5jQ?t!(I0)zD$zd)?`C(-xtJBO3F4zWNR&ZH-;yM51I%E|_ z3(9HEr0CC;(0N$vxoh-~m&=FCuY2d<SVTxg+_p5(-cm+)_k>s$8CkR4 z)Vy$cqFvmSFuk7qQb z-J}&ayWT2~x}&@!PPAQmHn&D^wizpQYXPCrUYu|$$_Gq}W~gx762;ANSeyU-{2x0C z*ppOZUkW&FeUej|nE%aB1C zS54l5f!vW_b@7J<-^YKuId6(}u#>@VW<3w(XouhYk)+9Jc3FTgNpH|!Dr~Ulf=TUu7(@9 z5mRV}HrCJ*`I_h2kR!U3yzI(+RgZP^@;ppQv}$$un%AHzgPFRYKin>)^6r8^L^muSGLkii{z0j z?6snhIV&{j^dLbwx^Ss%>>4sZK$fO5KKg*x33AfNl_ym@P?9jLTH}M>xN(1Us^pjv zU8Vj^+7pvuTtYkU!QPBKTj0e?i8C9q6yYkg6IRiINSjZZ;$jVg9iNzUDqn8?|$ggU^+Y8aNG z!Yqv$iuUv7OArJ&;mT;<#a%52RGO zL!K7pzy6fp9fC8Ln)r{ z-A~x4=4esVUr{iNDR6KyC-bD?uN}V^S zngP~i{n>%e=+Y<6EJZyU&VwdJq{t*2yc72$rHVURV33|yloTYi=(gby2L~Nj6+R*+us~srk$FB2nTE% zqo(d7!dD*|>L@(?Uve>_Xd%JPFnXu~_GfSEdU9VW{alc2U=+6L)(fwyDJci=#4a%h zgD1PO#WoYzzpfV%W-7ZYLYL(-5zR6niOhzaHyi;Igt0m!gb5N&n(ZhebhHUVtXQ!w zrSA{L#ay7-om>l;@k?BhKf1H8IZ4nz3d^9RJvv#*U-Njpr`Dd?5n;DXH};ouyjD5& zDIuj$e3qq3a}wPc!xltnMiDMXbq|H!((tH}#DA(d#w)>{fL;vio)1$**@T;b-}2o1 zU4y~Rh`<)Oxb6dX8oS=zCVL%TJwy}@a&B}XUx~XYyB_Wl<3rt}JK#?{qvzdn3>^6M zsRP8=LDo>jOF>?NIpmDzJ<2-A9DtO=>UJ1~obkA?%@ZLrkPyAVbcpfCo>etfq%2U`nt2 zqk2fnh)*rslPxF-V1Vd_>iv9j7`)o^K0)Gxp7lk2z1CfSc*hEDg$d4hIdK$5Br*K2di#*!ol0r5y@j7E!}HP8cjpBPaq|l$l5O5 znGZL;%xNaoM~VkoD)@`ZNlmcS`+b-Gw6A2fTS8vykNGV8NQCN}DP0r-E#yX1qMt@# z%{H}Jq&RE^EzYSG7*MJncvi%g)Wv>>PXHJFWgrw)?Sn?;k7u3A_UN=JH{o|K+0xvs z7ARCP-uuhdnw>@DHo+6yy7ikO@x*FFiVGG8lh#Y8sUZSik#gUGW;!cM*Z4jZDsU-Y zJJ9u#_(|;XvKsOqfnNSG-7FRcJKP_0o3g|pVn-G1v+C1*S6avy?5QLflKi@NJ2O$D zwuRJgemw~B(RWWU4ZyY*HC*R;sZ|60v&4==iADCPr7-D@3=3p+2>4jLT6j-o z3Es(hBsefgb^J?}MTTDBi(V{uO2N@Z@J0pXGe%LD0K0 zxcvzdj%-ZXJ`o`rbO%XhRB*nvqnSSS;jJt+F&jkrLrn+IYpyn^D_I`EUh+ZjnSAK; z1vLstWocd)!k52!YxdvZgYTCDzK{)t?6l=I9Wq}egs$gT+_0Ar>2%3I=^7q|J=3Oj z7dg70D>#_+0z1J$nzzO&i*^agPZbsPw;KCb>4QN`&hJ*kHNLP~jfQ@DFi^HH3?`}T zkazkid+N~ge8D!vnByn!%u>t8VYsa$3XZ$Sc-vUcoN1BGmDh~m{DmaAY$pt z5MT|Nhq`_~GV-l}I>o6P9nNfalBN|n#jd#G)=cRDl9EXK2qy{%lEh!CCg_v6kV!An zooFbLYHqI*Et;fwtS4#!L$?j zOWk4jOkVwE7o(Xt5YB9P6cmh|Z*Kx}(sW2rigsjLw6srqyK>j%{#qorFxJW#a235L z>g+XMYrWzL_&fz9^Ov`%A3KT!su%wvkSF;SJ)jH@basn@C*fTe487{ED4YyRNklNC zeb2W1w4(1aX${Wm?Ks&rq&+Q8p^TobNjUf#uJ-E*r(G#fv%+KXmrYFNkw?g@pV7_g zLtJR=^vv72p~Dqdw6eSewP+fsu);DsmtP@iYmHvX4vg$chRGQq$tXSUrUMX!S}(gC%NDmLt$ zt0~_Slz)*YN{YZ7?<2 z_BJAPi{Jb`C2!x+`K1)dMk>R}h-4-aQ!bQLft&1KdSc<$>PaUdvYq`G+0MHdD7jGQ z50(o6o$9d;V6tM^_v=ks<0S%X=xEGhBCSE~U~T5|e2+dsA^S~rVH8$t{sR<+Y}-ew zkf=3YE3e=mfExYNR+GF9D)vZEHug;?$a`eFmSDFriWfXWq~PGR`njzYCZyk!?W6F0 zTy~fDmx^O81qYnlgVml!dD#_7#e;c!e310g#h+pn1`a8e!lYm71oj&@mR)Wfpdu6E ze1J8w-pT@`G>b#ehE-lcp6dxYVS9fImm)J~)-U}f*lVhx2#M8lY6dt4u4h9YyJ6S+ zwSI~S)B>l(=Cf84d_N1x8d%QS$LzNly`;E3$K{C?Gp>9Ph~d}Oex3nW;EtZjA$bKx zjux`Iwxr@xY*)+LuqwzuzuUd-0E{4$m02N@tUGX=+ASj&VnSu)h&++u!-gK5Dz^?m91^*BZf zIGT-T{vi4MYrJ&f)Q+1e0kW=B&)A|Kc>b0xsS1d_HV2N%=JJ-G{D$x1CwmtTr;i-f zp4ncZ{FX;Ecv-UEyU}bF+xi$sU zlPjFrK%culchgw~Mt>4z*)?#N*C^1FdBYxV0b!x~EiC^MI{2R>EKCPeO-=eSOj&ui zH_=mZfn5+d#7grK?83Xl|FK>8=e!dl?d<aVAxDoq2FNoQw*8EC|9kn7|Jb4MGG9NF*qPIkA)4?`ZahI0xC4)-W_rxO%ryjC>Mnugyb_*L~8i|a$gdE;kgv|iZQ?GZIb(=6?tQM zp5hxiD+A-QWEi6BUW&f%O2NOG3zbXt68>GyBd+LZq`FBQ3 z{tdn2I{psKwjONVO@=+hx90*ZK^TZ0bUsNYs?lQeM0~+oC(SQ&B=;?CBs5I zvVVP4mEJnuX|@78Yh|(0+pHdVOX=iB;m`S&m7kC4>v-|P}8OZ9)T zK;X9{@=tO^{$H#n`5zS)GiAfs3Pp5wR>*BcNf_n==JbTyAevM*sR!j$=N*MWFX$hC#V(d!*kC{t&nZ>CEB%8TejAbT2;@%x{x3rMIp=vl1=p#NPF zMRM`JgHFURepf{OGB*7!EWZ{OuL95Ihe2CBzK#0LjJ2iPUzN9811z|0_2Y8I#Ep!s z0eH*3+9Mwga6t0xyC&*sl>@e9qK4YXP>;!BR{66CuIdoksAB!{MC$3~Zx#G{X_GCQ z7niknO$axRrjmc&4{B=-Zn?^|2m#`TgYwnyE#rT#gO#Hg=GEf9Z@=e97d(UK;cU%H zQILE@>SPOn+cSxJR(cLaca^SV(TMl-(GFW|qeN%~i56Ct67U16OGBrrk>cn!sIU6o zqWvF~rhXydO;adsM^bJcn-it0u6AD7)wZif%-Gx;4ZRd%XUXN{g3t+6Lp3y00j=QN z8ku%cQCP?4N#t6evrKA#>)iTFfv^x~YO{=iyAH1ST%}Mav=rtFe*Q?>d|r6#tQSef zKrXTCM{)@%_`rWu(QQG%Kgyn__0FO$g%*T$yAP7;m%VmDp}8rgJ=z4S-h*DX=R!A~ zMD;~-d%{5|O+3hwyGoh(r%*Cv`_7Sw9R*2F*8Lxl4-J*rA5P+lXx|3?5=!mju(M(C zx&P^Ee1S$8eit2_Vf?z%AiMjdcBr}LwN9V3@SBNqLHQUQBI`z#6+YvR= zrvINT$n5M9r=VBJ07H8AbA#E zAEA!>h7F5vFJ$YQc;R^Vx z*FeaA=zIQ$wP3R9D@%f+o(IvTFHuj$^W>>#nMcCJ^~mj3MqtKEUqs`*kkw!Qubfk| z=kg~{*Mak}4V~vg|IZ~#AfXr`tWHSIyVhL(Wp>+TW zTk^3%n2`%9N58c7W&n@wB6RlfKT#NbN6rec3na;20@5|umU{^wd!gB^A$-j&32+qy zt!ZOhH+=?ad`LxVvQ~*f-u%>U5Gm|+(8pC%)aKKX@+&LLxRr2L>*BRZyZxGiOBzy!Z$aP{1<@y3~+cG&XT{c0c%5KS>!P0g2=W{_A2e6NT=$AcF(qm zrH>I;5EjdJV<48=$Gn0CwhcHi+Zo_c@US%YcI_L~x!7!*M&oc5rp99?y~VP}E@DyF z5jbo_i;i&Hp9AH@*`S?w2sJWpP(4n1`pNCUiihe0CCS%7Jv$O{TH?}Yk_niGyE7V^ zYb*|GydhWEQ8Os|#hdqobB6LCzjIIVoRL*eV|T737j0s;nO%z)-5cB6h46aGg~x?C zYR}wNb&J+46OoXC&%vkb26OHj(F;C%H-MNYu-A;dwo;G;=1H+-*F=*HZemxaAR?oG zN%f~_2U2c9>xub3{$397lqZtw+4V1*$$mg_B84*TG!u;>o86})Z9$s)$1GYWaIZkN zmN~F$s1;i)(!g-`5a^S4>42MR|N3ZWf+ySfmAj-{+z5>?DX4)5!=Nry2Af;;F8Dnz zqj=hIlaa&jkEvB|__gvMDZcTN$>*m|MFLwJLN(OpwUJHiig|pt=;?$<_nAj5ZwXJy z(M)@*`1g=xil1@>$Zfx6VM`7K(!f^Fe$HtpQeW9alS@J0CfW=sIgHoiM<-rsz*610 zcFQY#8M{N84Ss&RTHtv*TSoFp8!{o90)?4w9y_G!QlaMDKt1gN^cU636S!r*e1xfY zG^I$I*dHp`fDfO0$9WYY?n@6)m3CqBUBWWp2W3{~$0AndBYc|0zdV#nLx^jQX8@%sbLwpc-Mg=qOCbe zrzKbs?e=zi_(Ke+>6+y^{}nMb(11#2nzo4}#M!vQl>&j%$rW%hiWxUr6wizYoukU+Qcm97n;Rxtq{ftuvJ zk=G6~e#54Nplz0GpM`(vm^l_M)TlFMcf_0yJu~*q{_b~<;lxdi!x8+GAmN9&nL)&y z;z_n)5>mYUp0rO)Hp1mHd94D?Qd3dZ3>=Tr_lpoEN=;c-{an?@3nWvs#_JMg$nFv4 zb+>`P*}~_o(z@pelM46k=ibv;!h}-_%c8eJ(=-M@MKk$B#)(8_v$ywnC+I76TWbkEFMbXM)QN&zUV-vbw zN28&`90y&g3Pwo;SLQzors|c_`GF9;x4SWPX4cem##9c~pOjaZQ8N|%i0bb3<_xm&_)WF`mnVp5b&w!S407u5}$gqZ7vMf?>8n*fPl~PMSnd zd}uchq3uYc#Qj7xa=i=>0d8>;Gkfk7-_WrwjpGrg!JA~4W1he)raPIoLAWu@??K@9 zb{%xnk|e2rAs$F73Z#~&Km!(y<4)rGSEfs#nbsldkYe;zC0)`+X&EMQxeTXx5->P- zT)hqB`+|FmTH?-Y$$8k@6gZawwD+`0!*Q(j zh~tesvmpsg*9>%{U#ct}D!#_N!2`(Yb7qz}rG^!@8z)Vs_+(6gX-suAca8Zv)H6F$ zcyYX57~#mDoy)4WZ|nJLm|W@Mco3tUKW-@I+UC8`K&w+J7GAw8*F(Cy3GePle3)>JT<{cXWyTY@xnHI<7a=zgrHnm6 z{6RxLFl>WwhxRgp!o4Va4ZjWgZ+{>e*vULX=;ygjN0z@EKmmeQ=@6W{1!hiW`J2C~ zd5%L%vYwp9ef0Lx9(myLT}&eq6!SG;Ov7ESI!@J{rXy&(N?d22eC~*eCdBoYtGbV9 zj5aH7@$cxkruN9&HK1zi>D_Ov=!I#*3m3a^)!p~dz!^{N61%sjXnC}#x?Xm)$8@^t zUCeSq%Yi3#qOGw;6~FGffh`K=EuVP5k(+}3em^peiCX|!a<-H=l%k$0o8LTBez(w$_AgD*^n4Qa*<@L%-5FTSqE>$Uk&pu(r@ z6Pns09C$AF)lr3A!u5e_8*Z-eaxuOXQtN+p^4^oW3XWb;#6g8~v~uWqBX#r8aZ~X7&;qSEI}oP>4>EiRhNT zl9FC{iFL&V2!_x`t-yJkWPLxXR>7#sxintGuFoAf0a|<`zgTZP66stgzawb~eNN2g zJiTz`rlJ6qBIQGkKtI&t4g5^TH?E!E>Cot7sC#C%r{v~-8Nnk6aXIMOiAQmz4_vdnM+FWEg`S9?eN)c1#iAv-YU;=<{4+M% z4t={S;a+4&jZpR6CFhA;XSa@uJyF=RFTRh85mJ=R$yV<_s)d-fq0}2{C?7uqeB*6b ziwzOYVQM&`y+z~>#F1_EBS}iyGUSbTLODV^UB*6)uu#6*`(ft?gi~&V;*sHuS{q>& zc*ovSpHhgJHdyUqtiXILV=0AEJ%Tc{F%+S%Zn>Tgs}JS8*M9l~a}MjWicP(Ferd5y z;%uj#su*xpmI6`N4q&)$xdooZy~NT2IgHC6bq+EOrA8f+5fM`8nOjbnQ9UEV!gMeA zA|nJle3htwqL&(Kz*9cwA-T$=R?N$D^0VhQJ_Ebl05pr{v2{pQi&rug)wJWwdVEBj z8g9u#K!5_yYcqM+abzjQ2@ESA3_Fh3=m~sZ?V)ArvjB9Z#cu0IHcyu|T=c|?dJ4W< z`7{|Id@uB6QZFw1)OyQo%MK=F7>?IKxXZw^)T>n?JbF{fyBMieI2uER?@3su#XM(X zV!GHVGSb*bSe#9v(oh{mwc`d^N5al`_r7T%ob})QY;cpNYC3L3KVCE;aP)iZz&Q6T zV(!`3H=f_#45$=;Ao>1E>uHzDCaMaPQU#a!1-i?m9bT7@VVXFH^$|`$#+Z2Z*HU;nBZ3} zK2nnzv*EFDt@ucuS*q*wNGG01w9~`DvXk+;l*f{@7*Kd~X6-4r{`P){Pj=yS(lb?S zHY^A)b+ul@t);E@eNa)VQa$sUre;l zyq35a^zEtHDu-|FX0IohITIs%NR<)ZJhaqL6O+SecXSicxvV|4HVP|pQMl^Zrs;zh zcl=U5Njnm>=@V2tOQ$*?HIrQH=yF43SvtHr4>;p>?RL_(4dfjweP4RKKe439Tp87o zm9*o^#L5fnbEpiMc+)5DTk@#|GvR<4)|Irj&Ih}X z)l2ZA=LC;gVUL&*DvOpXdo59DomQYQKgb5Ur=aCSB<@=)sfc42TldX?>AL846vzwbDz!cX3au%OMg2Tg*AWdp-P6f z&2ALi`57;rqnhoqjtFpJQR9;%5e>Pojnc0o=Uh)XdI! z(YZxVdQ?srHa-m%^H0;uAZL_6o$hhcUzAwKO1E+9Gr!Ne)P_^84a%aoS*&u5-kSg& zr*aNqrX#KkyXfAv_Jc@7qeKl<74(Bg!ZI__#Uj1bOE*XxT-JbIL87C?OX*j?*a=$H ziZqnYEy<_PT$mM8)?=w}&mOcbO6LToXt4)3U_@pdWv?~z z+SiT4E)R|OzVnoM6yA4%RFwm z3VtWdh}SKSeqno=brrEcu`3Gu!5KJ_A5haxU@_>C;e>C?g4JUCpNoBa8|x&QI}N5a z=z`gtM5^T4Fa0-}X=_!)-)AKYe6h^#Vgdw8+%Owd4E?%vhn1;yg+NVjkOMTKf?+)@ z<-5uyMogO{EyL$)kb|6hk^BAzZke!H3Q>;W*JCVBs*;(ry*_)`b|oi|9-HvDoJ$uU zzr@F#8Zmh3`#o1Tlf?0$9Zl;^>axn-x)U4BNNq7)TnTW z=1bfsLgT_+uQ|g^v$F7l_LR3@#a`1+2RC&CXo-%ipYc3LHC@eoDrqvn=F5jiUwdxS zd7JO;wkfF+9~7}LFp)AgY3ZB$*4K*+P-%RK%Q3wapFQSlMtUy&89jE~^1Ou%q5W$n z&YkzJ`FjD}qQ{JTuX~Dz!Q7i2gjU}pZ8ECSXE%_1wxe5GWopj$zug5!!IY9`ai+lU zaoQq(f)qFz2Qo?AmIIuI>PKbJQsl6tYbzIbBg^|!x7qt5RK;B~`K5M0xbIn*nyPkb zulJ%~Z{J|JpXUzC!UzaDId@AqULTH?jKcEpRh|x*ro`@SmjtD_@!(N&-TAA!6HVWq z0f8P?&~PU@2j)(kkkoUWBc5g*@igtjb9swIr1^`!u@t@e{9@c$8;3BcMz{5Pnx3ED zJuBgO4pmo?M_xRa5_`?E%i*{wK018im%t}eTw@VWrcauYJgHBr#Xw>>mfxJNhPupH zlg_1ZeP~_j8!m-h@iGz#N!li@z$-stAxD82b$5$C+7hs1iHp?cvlCr=y?2)rI_(>j zfm+dO=iGF%UjAEvbZu2}_XMk{5;RjL2zFSP!P_kb1H#~X4bQfna;h5?oIP&%MB;Sv%9epj1tRsL$y(z zQFDnad{3t-KTFowBtB6?g~v5#lKn463YVFhL3c%5ya1~E-Lea#st<8)!wp#s1&mgi zp0Guoz}&qcQxkpQO%xq#(BFVS1i}3@illWLpE|?SEP6%e#6;*E^(OY#I>b-Yf zl(zZ&u6Vld1SUr1F00e{i?#Pg@Xt)ccg6R`KOFcf+;H%jFqgPRtz)}b@QMc*8MoNJ zS7lFNz)|s3?D}CJ-cwRFF)Ed8$rplZY<9=|Y0Z~rYX)5uaWDSynnz*HMkzZV$SaI6 z9z_N83$NA!NE0oSfL?L*mApsXt4>z>=0Mhw`+d6@1@3uDAJ)xxTZ$<|W?OnAk$1>I zj_fyJ9~H4qyI%B0y`&}a_=o+cAKX&n%e~Sg)Y&@m0z9Ozqd9MARGk}NrF;vqIo_rI z|F!q!;Z&~gza^DWG?&SlU ziuUV@ZW)bsRJp{iRn|H*1nsgMZ8=FCEdGKUPF9Ry%b^wL^_np-0%N+?zGA{{HDM;h z90I-Hw7P7!NLO<9aybW%$a$U$T}$n()U@Gs7EaDr!!g;_VW##uj_|Cj?gC;PhChJI z|9Gl?lPO{vYCRV^wt;i}R;!NxBg1X&lx~OBD+P`{`IfyCiNmr)5Tu@{^%rBpHWh4P zdFVCq$C~kC)pi)1vB`%^dOvob(3Z`@n^~B>e=CNOT6w-e6`h=G>@4+Wzxy$6n0S%2k@E_@S&mfb z!D+%op5)7xwjmWp4w$;i&B&`9!ak|R*zF9n?!wrOx$J1HWVED0HM7C)eZ2q7#Yu3! z2Hm_=LS+tIT6ag@zg>BQ&u(P6l{W3oGgTuK&Vv($piS>igVZ2Q04Zf`ez_mC<>rTD zBU7)G+hmc6b=WXs1@D6t86ny&D+1n~&j@SijGlUh3A_4mXlUZ@yTNwoBmFvYSRgEX zpL}i-IV-eBZQB^hl-F7A(8}6&+2Q*>FS=Vz9razZ2fFO*RIQx|80f0zGiz5O09~Qy zT#9A*0lGgvU=sTL3ENK-oFBV7W{;Ky?Lovvigp3X;oAA&#xig;;*JC=9yL+edSHv^ z?cJJh*eT)CKi~{i<}(d*XK3@eohG?jnThL4Tlb}#>_h$JEe9`~3A}$)&^HpidyH*G zBqC=G z#lb0WNa%uKb>?>VCT=rvjQvo{%hi`Y^^^@iF-vtOPCuSGT%JHKHMczo7XP8p+aab; zPsyD+>*jdI=!$IhozMg+pN_BxN5_+uso;I4rN;4bmU>cvOrtjl5s9e?}z)K4vg zCPYvpx!DSwV7%Mz&~Rx%+5<;-uR4N+LI38xWtr(in!G1^i4?|~zznyQ%lsG8lM)vO4|6)!i z-Jiagff~i#{sk$-QGS&k!5w8Eg#(GB%Cc#@=caB6vLxaN?+bTJ34$kbYoDds?S_jb z>q;Iz+7qx(nIcdP3m(3#Mng!<(T3r@U@G|=UVO1~@9x_jpX=Exu7QPcXYbC<3O8Wr zX8X&6A*tGiW-V<4iSd+1()Ho51Yg{2J2a7AyH~mY?S@|O{+GrUjBi6_94?vsedgXM z=xI6#?hhJh@2ue*^u&K`D2C3E2U06ZE+$gr#6cXn#;<>f_IZWn)OClx{XLp34OSey zNr8x1kL|nfvwR5Ywx|)-(IN3y*c)VEa%SPssq?a>wjqF4Av<|Xua_pt9cRy*#?ADi zz4pv*6+9x2#wzy+ij{q|OT!WTc`KwS^llGi5bBdf>+0BdyQ0BY)%wtU8@>Rze@*45 z)T!?UxBSd@?%Bbd8FKa0o(xf^k4$mO{ECdLaJ?E~^h`2CSj0tLB_AVd@7Q_Y)E&t# zZ(F4RaZ71itus6$)nTN|QWska)cN+gZ$P5naybxI+)9_Z4tF;YnnthYxRI9L?0hYQ zOqwauhCZB+9bV0gyM2~8*Gguy7w?FfH{$LOSo5kG{jMS8i@*Z0G0Uk2RJYFuL5{lB;Z);B)gUi0yA zG#qH<2x6Zj<4#zViCtfy^Z7btqMhTmvF#WwOo^g=uFcjYXJkOHJ&cVx=^8xhr0jVw z15JpV-9?V}xk}Ho?PVVm+*Pf!LyspTnMJ%6eFJ9jTvM0m`3QnTv`V)|v}Dqs?C7YB zL>I-Q9-h{{6bon>-kq*&L$BrQO=~InLc~?UMy)LF54-Dd%sK$X*s!akG?6`cE?J!N zJBYF4^dDTz>A7<8&YJCK}~) zS8`LQ2fEUJ3FFoD3S?4*SEXTqwV8`3Nm4G>M82Mj!%EcFg;mVp*1K+M2c2E?QpO*`9^p9ijrt!#YoBZ-?M~+wG2I9jQ zjAjV+m(rztDa&V;c2LH>`GvsppO3w7T#keqbbopIz2lX_`WL$EMQ{4LsQDkZD|C6Q3{U!>g=gtebQI`H-(Mg$E>h~O$_K&NMPePVf`Q@co z49;?>^eF8q`xus{YW-q$f#n=Y@oWRWUc(aEp|HMJ>1hF&&nz#|K>{9NG#%7;(x7%@ z6aO8eRomS5otWF|90F?P%2kA^sF3%;Cil`YmJx(MnOr{3=@YCx7$Y0`50!ds2d#m3 zTM(|(@xS~nT*qwo7x<(K^k?s(Bn~t}PcM)=sv`ARvI7p`|0d<>ICgQ{9JAh7m_syY z7-Mx>_KD&`ZP<{A3sn`>mD_}zs{p+6w?H<;1il5b7Xbx#@>G4qa36e}e)Kd!E<)9s zhUv~cnC#0OEB9l1GgYJ0x0>dnk%dL(=-g3$+kNcD?*6a|m7eQXNnyh7LrfDS z1^YL9gk$2X>2+CqpDok6GxxXQ=iuffZrEi=!#m#+{)Kl=v}iYpp0M;>af)%&U09Gb z>bp%qKwziHb0-Dn-tw-FpVG2=`$gxBhWb4c<57DlN>B;BiXgw{B}*_}umLo=#8EcE z@kI8{elp$I$vyFw6xuNc7PPHA^pmKQz%hQ_y7_TeXk;5bq!Y}ExB+V0QuXz4ZO3*s zV%EVCSX@xM{jaahm@I?e&W@VERU2W=Z^2mbroRuyDjxk7jHTL2=w;#80F}#9Tg>vq zKQv-~pDEb}ci|0o(svQ+g(Q#4T*_*AT11+v(kh_8bwt*ryRrt{f?W@ixIJ%s&3D1% zXG`RZ3DH?iOLzG<~@CTTYrCh;T zPXb?kr6}6+{4_pZ;MjoEmx`hB-Ej=E-BK`mSHg@Z4@57`1qUg?u?& zj9f-?o$8HsNA}~@#!`m;$}8s4VNcdHV61gtc~J;BMLYb;Ojqf#j_lNwP(1*9^{y9K zpdeGusg2mi$=es1Y^yXpRn}LTFZb#43ni}j=P^{{B5NC@%srqJ zmseb_NDkRmb8U8V_~I)TZC6NgRyeR`QEgV{*W2NAJa3~>4*Wq{-DF&zg$>!M`*3u+ z4=>*}Zu#5~&nz)W1MAYa=1Odt{J3I==}eoJ@H!QPDb2|! z%#@0lSq9o$3IcC$XtX>WBb8)cOa$s#tc=g&Iyg{mdwadvG|7Scx!}~xKel?&ui9Rtx4c(CDXl{RvNNmKd9AA{YwIwi z7*62_@lS+~4LG!gCboC`TqNI|;ce5mBV1|iWU!83r&@{{Cd+Bw(ABJmF>>QWtwqXT zo@I$f5_*uupJ$xnlZP*M7T>E!+{!S=kQMk!kAQY1P8Un*u+~` z0bA`=){_$l=Rj7+oswOlrxUkS8{t(U9ThIiCif6EOtbl)(l_Ugd~E$1cJO*{s?fYG zVU|}A&D?#ZUXX-wXbKr5zu6l)K3$vOEb-||y+Lc}wE+&go8tk>7~=o9E2O#DGX=r=l0aUrlV?)vv4lL z$JHrVMi+qo#tep;J}`old0vrzvmWsoQz>tu^fVg1!_EADy$^SWzUC~-8FnSeV{oj6 zg`sZp=~*|aHh1`a8ZCE6UvA9S3b~mtEFv&(?1WD8IVG_d8@N+dt=m@alR>s^mWG{e zyr7jFW&E`tJSjrFW6;_;(P#D?8#~kGp!9LXIlzvflm$SKB#YDzg&m;8Zk$C&V7g!} zJZ}?K1_#|72Ct70Xp&D|EnVvwK^R;!R^i@lgOau)qvw2?o-C~vQ$xm+?zo-Zxuj8Co5??bNL)v zUarW!obwS!^N9%7X;VmSbarALsiI@wn(Pfxa&_)bh`!YICLL_`uOV%UtF zZ2khg1o89Q4?de`hs;aZ4DC-#L4f(S!?_;onw~dzs^TF9auMK0Y*(-Bn7dctZL9>C z^l>(|{FGn#85t91x~2}xO#8ql13LaTkw!N8_{UAA@=bZ>6Fm|6HFQ6J>I7a*C8MK~ z4QJQo>pb{~aLGIsovi>_VF;=Y9_R`YV=naG>cPal4uI45j%_T;;hwJYC`3}20Cb5m zXDILVv3wQk+H})#UZ1y~3Ug~iOsCISfTvP-Y0;9iWe9tJS zW0U9Y1gEaOxgvuGxa-;ycSso4VB&yp5V+{>I&oC#pt%yL*2iK7!6Q{dZeP;}Nu=53 zv~%sHd7)vgpTjdg{La@|{H4a9QN)+dLYbd$mqoO;j+?aDmj()+$zI?4;N)^D9F2~d zj~{%y=#UxIb$q_Emw*wzHcK3D9C6kPP@(UqAA6$ecJ_?fg12_TF2`rF?()dH#y2PX zVoESt#{L}E4#vY-DtQ-ydk#rbXR6TZZdW}UZCA4=cX($Lpw3Rz1hb|f$xfYI$14fm zhhf0<1s*%ymi?i$PB8G>I|sAsMty=&zIeq^;)#O}Qm<485%j}W-0U#n6Ef4Bg?Ez? z;1*YmITUdcm|-@1&23(SIF*|F!G$M;>IPBzE16|s4Q9Huq*LJzETSCJglnW#i0iMX z{~$4HVZQN7LEh~a^_&7zH$mf=W8K^Kv zDA(?DPx>%zL$Gz8!^67NdPB|u00!XCoA^nFW=U`9s?8(-S-xi`bM(ZGBr(#SO&ht>7&x}i7u(|_cOkqb=hZmbRm>FRhqToRS^ z1vx7Zxhco7YcO^Wd=Q(mekg@v(pG1MZFY`J3J7OC6=Dbj(RDOBVTc|w=*Yq9a*NSNAaMRh&M zx9am&W4*Pla~TEuBF>Yv9_@o}j$PCCeP~RCr^*7{!Dm7VZz!c~ht~L~;^YR8rgso6 z2tHcl!Zmu2t?+3dM|#fNwmVWdQ{9tpGjggh4q@DZQTt>sNC$i~wVyBuxVjBRlATHUtbwGcPdEb3x-T{H>4WV!0%v_& zlQcl?cpXAL4O1joMj_O!FpX|yX=`@;p7n$5U#cMW;;X-?CWjE0o z#Fk_XT`1msaAyIzKUTfPAi+s{GW9N5H^9J*(!rUT@3-)7lEWHhc-8 z!mj42T2H0uQUi|S%Ep@Amv!%rzy5ni?#2S}1X+|J=P%Nw6ujT98HQ3aA+YSTq83|* zKYyx?)9$k1HJrV{J%pa;@JLx)gY>l*% zl!MitkbssLTvD2YGLygtM}ZCZO0R8huBl#joW3kzU;OS>ox4MHGylNs7P&iPh5Qp_+}8V4Yf2brqYu>lUJ^}#@?js8K<0)8ZK>W1}rVUC@Q z<6*pEY-Y!;u*~gFZDV2G5`@5sIEzOq$B;lo5sgFP@nM1tF4z1?%loPxwa2b+)amH7 zi1jtfYs$Riv|=TCywe|P(3FOpiSM#;Q0m-tZ>CW%FYW7k;SIh0&0AFJuS0Dn`#P?J z;zJ2u_Kp3JU$lKtmkn6fi&GtUwa0~#7alBPoA6X!;~H@e_Ey+;83W4KQ&1A z&K7*;+Y&7iY$K=k(XczGfDb^0yMEZrNQme)5D86Als- zu_Wj0NlwOvBAAYiacV!9`d+YA(uA*v9(R_+ENMr+QFv{ywL@)80zIc;(ze}2j;)E6 z1mXwoD~*`T=Z7)4VK$uTN249m9j=)TU$Dz8KaG{jTby-cKfG%832o0wFT1IXHvMDk zDo+|&%2LBs#S93*igz6R+sxLNH#e?$P<+QSpEQ=>0kyEof`{K3_t&_G5?0DT%ntWXA_4C9qAvaa+MA~kpcok->z zJYKF0D^Q)MtDh)o3<}Qt$v%Y8AChfXVC*oFM2&)|EH&ZpLBbL6Y3FhpAYZQi7O+f+VAXkjRPqfm)dh93lm1^ z$JVil`}Dt9%^ku%;vKaCGyHPn>GGhABlfKjzp>$FS~1_X^T?5wSZ#flc;{EOYrJ2p zqB>p;@^7J@KY=aG_8F1tG4!K(5hL-Jsm>h)bS@)^D4TFjNh?N=bzHilokbo@9w7d` z9vqk9nt-6r*2(LEA{Tq4I5vAl(U&AW0L(^9uR-=zH>llUoc$0DH6)&`+d`nK1-bg; zIHy)OHg^b3`D`&KFb_xbj29Lb-b&MMO5(raMX`_O{6_!1fJ%;!s-v8t7QDLF8w)!q zrIAcBm52Y$qXNPU#K`UU6KC!><>F?k6bF8IEH)s5z+NE>C6?N>hV{?%*tP*gN_ z8guo4G@$j10Eqe^IFmce077|)NiPLsCJPapunzpGnv*%5!zJ8Ib0`e}ZWck+FbAUJ z%C39USNhOzt8}CpM)2Fp()}rTn>AzSgzhj<-6`75LPO_;$*Du}+IexU$s$g3#9M{r zoyO~>0yw}mQNP(WmmQnWuBx{5mL#lep2g*VcyT{?-#ljr&pG>1YEk)s(7QS^04U=k zz>KYqp6LI`20nzpCvNhOkM^Tr^KGmHVOUcEX4FPN?xlUrH(kTU#AGr#^Y&@P9LPwj zUH~KNl!Mr}$K4#0UuU|{9X4~chOw58Ol|%|b0xVx_A%M~OV~v7V@GYFZ0Gl36Vs<= zIr8$#FqN`*UnNZxi<=A_x8(?Ges5n=e*M#!0?v8DbdaQWe+KuiunkA*O(6BY*D0?3 zBgBT#R~lQ3O!pP>ka~=?b1>gJ==4gu&naXK9Rj+EnYmZcr87_-F4(OhHv4FF`awNG zG|c&7K2=4^gR0L5=W-dTMExc;172e$-yR-U{Q1SCv>3*^OaQP~NBoaEI5`6wH&CS9mG znjKjzW}!SxK*pIOQGu5Fv+juy>w$f^xcP^9>v#8&QJqH8O0ixp{BdickPM^;jJvH-ucof91|NH zDW55db!sWV#}Hq-3*~-&&)k(U+Xa?w-DjUGH5k15uPl4*TvQ?I>MCwRlX;Ex%{ z);+9{zIaeVBz<-?`RQ)&S&Y!Cxk~v|*mlALeGkgz7O+DVhVOhn9DvIUsxVl0ak6E5 zwi0lL4(VuJkSz;4r|Ra7hd8bkergjqC3AX>(8p>xh`M0&{$Mio*jD$@ty2 zvwgNDwTVZbIa-#tyQaIYuuX87Iv+^7zK_4g0qP0e5Vx=s*X4C^t>peJaBdSJw)A&@ zNn$?|nw}TKS=}<9R2WB#MXv*rRR3Uvq>p*#VTh&K z-@Yhw#lFFzbG7`6d3t{gz$oDWjWg&OF#@}YwPZ@%1-yt*e6MgCUkpKqiSi*95)huZ zG1HygZV#CH84={qbBVTCWd=stYStB)VN*>V%RL$5LL!oFnkg)&qdKDQzj8k07F6tY znh+J@E&bqWmzH>l)=6WblAD(|o>x~ew)!+GF_u|6Reyms{%CRjldHXZOb-<6O}(*O z6Cxs6-Sx)_rGrFat2?|^CU|~@T+whxC|?zF)0puReKZZ|O)tjs;`2~Qv;hg}u)H9U zh{L}(fw)SZ$d{Y?d}nXtppj(1W{Xr_a>c>D8knT=){U;o6{flvn~>qI)tJc_x9&JZ zYB36w;GUPA*OX;rWi6I_VRHdN;=kn0dFp59i8=Iy8Y#Qy3E{@f#6C*#D>M5xC__q` zFGE@gXef9DBc^?uJ}^u;j}7MOPDzbi9jX>4^$c+flYCpjMBkXZtS1=PQI4^Am|v1V z88)0CvGv*p6Q2V83s(o0=i5Y-3jEe^w%#kaRKT`OPr9C(pNZWNy|0F|WQ$5#E|gkn zGh#wlapEKgOm!3Of(~E60l@FfjUwWVX+Q5Oufe>T0f?u#-&Ej#ufq6spgAAoM4oA8 zx@+jzqds#sw1$(jDZ{3{q2SUiF-2D?&g~n-L~{p(z&2|?Lo+E;kog}C&WyYVR3V!F zcHlW*jMvE`lq!_*0-m>^WP=Y3BNveQhp&qhx`Da^Kb z8zlC0iBzpDQ{mP5E&ZUrvT=ks5bdx9K--#oz0u4^Ej@x&zDnDXg7_ep#NS^)z;{_G z9SV@$`#zW+s`!S`eyzyITPBU!y0Nz)Drx-W#KL z)Nm?9c7@?cw~VbATjXYkiZm3GL@#r$NJlD`q#VDRNkJ98i!I{=q!6f8(Awd6Lym)O z>*kj>#m)mz$c;puMNw`hl>V(*zHiQ9JubS>o$ASOO z?j} z+Lsb{tz4m0UM{a1vKnCJUrR(Qk2f*%J?ERMX%C~9=5FL5_1Tfm3jB&S zqnHt8YQ}+zZ;%jhgTrOh$q~CenRJeq8jfLEZ83?{CE5w>H#TN;o@C{svI)g7MJ*kk zWMJGfO(E2$=4ZVJ;QqFV4vRd92WIYWO7ujab2>kGF#bt=Q)SIgPuK=zhtgNmdl`@G zwH<|$xCCcAMFsiXFRzCZ_c>`RYDbvT5Sl2twPF0cvpIn^6i6 z#u~uE_T8>S8yAQug_jXW&97@s&A?r1nTrpmLA1*NA3>T6U@3ihv5%6!SH*_kQhd`D zI;r0fEJgVhjQSb)5d=G%2o3x${K1LJxIe66a{-4&t@NVp2rTTq z`9DNbI)O+FHH_$_eFo@eLL0S>UusxQ347*~zxc*OoH9(?a}fhl4wX+2F7Ly`MwCZy z(U+Ye=XC4vHr0dRr@UZ8V8}T?JnhJ7wGq>1QgY&G z#Di9q(AhgQV(d1hVM3%2rml{qFKXzQq?K5p6~p-&OZ*p_Jzv61x%(&gLXK3+T`|@Y zdD#6QA7-w0skwS$tT1;%#zqByUm&{!CqSz7j2aV~B^F-j&p_jSi};-uAcHu=14-17 zw-?Qx{xH)mBd<%5ptt95y%UIU9`WPjY}7`&cu6u}q_TE64cx3`x%X}~T_ChBd&nHv z+~p^1E{m|aO&tSe<01w;uZW{Pk%kV6aFDmka`#LidyDz;VGe4ST3+JkL`yPm^uw&! zObK(IZLMA5Uff8))ZmrXOP(ZM&2F#+_FHhF8d8H+oq(y-$N?_zxNln>&jR2blR0Vq zeSovdRq>6{Y`>8!Vkd@?`c%4tTGK|;+;F(o{K_l7o>axSkTk;$fkwt0`zYO~nAwG^ zT#2IsW9R>wzm;_TojRnA)=2vfFp{Sd$hJ@J=b6=d79wC9(gzh{@`?KFzZOW6dF9ZH z+*^L;R+Q!5(I_=y!ZeFuZ>duUkey}yxU-jvZ(a;;{o;0QLN3p)*DFDK5VE#zk}A0s zD;MsDDlSF1VOOIz^?NDjo2VXsbEYe@w*mNUKPD2%-=_b-)Im9X2WFd!PM0W17lyW9 zE3TOJ*NXb8+$T$nQWg$xXZ;qj`u>^Gy1>)5g^g6mA-%W**=cGEf(uBsQp!PsSg}9i z0ytTB9VQJN$uOQ-xlMpH5gpd-G-mDI{BiQy%FCb7_MwYe`UefS|4Ud&Cgi60&o>3x zKL7!&b^eFs=t;q275cRHMQs?ic-P5smgaS)vtOaO_@@s6&m=)z`y*wG*sb`J{b5W> zPNz?AV{$vcmlc|ZuuEBwvhH$tMFn$c?y7pL_y%KCbE}o$EgYRYSUbp&Zk3bDf2f}d z37WrqO85sw+oC4Ezfjd%;%HZZtK)H;{y7WPXuI8cBi3nrdzv*-DT)=v?-xFnN6Jm` zKu8-mS&sSA>eP43+D)7IHSX4LnUo$@i_eReA2P6pYvK-VWSeYln^ZpP^9UJBAqO_;0yBZiWcjjFtd4*JtF?x^>zgYnJ35zfdr8zFL_4 zK6hNcG(#!#QyvtNa!|ln?R{(8Phff*0Q((^UC)S`Hr)smh-bc% zU*OojpH}iOJlXn@H6eU#ZWg`f|@ywY5_CuptqCloLEqB_a%7SOgP|2vWmqT9|a zFIR*H(_m2V`AY|($e`Ox?lX*T2%Lo zfj|yhU)6sfRua>wwT)0bDqG=*f2t7BndX?jnVPz9vLSlk zJ+M->w?4Igbp8%0Kh(lX2^A+%I44#PXk{u#-#{M z%R96e2$y*gfxQB&#wFLH@p?Z5;4CMs%?9Nhf>zpZ9zZ!qq6Hd@;^X-bX`!zFe{0hE z4>|o;OR5i@AU=($;?sgfM@J_*HGkhh#7W^`ZJZY|uXi&yJ8GZJuAyS}5!s;0R~0yD zcep%Ke!mh*t`dk4T9b9A3DIm9zte0k1t4>7uKr0c{9Zr+8{SQUbP@7I{B{r(p3#}6 zK`xLKjR?Y7tEr1+44@zCgA~ln&_~t5Vqqf&3Oj6hB?Z6jg6)8n_VNz=u^Nn!fTr(^ z5FQbbF>Uzy4KDZrp9KQFe%CW}IzsqgAoaFe4BX$%16a`L&SpLT8pe2Oiqzw|3$j#5 zh;7MGol5~DyntzeE$S^npEly?+ndrKpaq}FS?kh=J4H{TP+r=D0xiVYpH+=+7HpYm zI&`G(%%LqOU)xP#{HY!_@hd?bzd)d@+N4zJ=2ov}^Rjo5%amPdcYZx=EtdqT%~sm4J7Fb&0Ch=KdYx zpA|HGB2Q9CXgSSw_%L)OdwuloaCIqSVbTXT-^;}Nl z%{Js*JGmifUR%!npee*$i94m`AdKek9N_YTwadn+_w#0MIeAyWtNhKRG+)7l4IhRN zHXF$=Ns{4_GhD(6oL5PkhoFyd<9mDQ)=Lm7r8Dah;z2$A4Zl98y~d(SfD9AIS`xNjYUC#HufS$fCUh#uu< z<*0=jeHf_zo3&4s3+PLH02UF{)4T@%ycdRLjD8kmG~u`#>4AhuCi?$KrvFba4^$tv z9??u>TB#TShfGy{tDB_VEDVx+c$fGhZA5Vz5AuV4^I;{Vp!)VLEhL=|>FE~9=RQ^o ztoCD4I^d&Atrz$Tk8ogJNJFS3uQ~x5V1KgJAyjES+S@|pZ)y}cyM>h%_n!Nl-Jx!U z>Ib^PXxc{A7X+VU$k>u`O8j$>|9WZBYdMEEIRMEtRUaMC8n~3;Qooc1xFz!_S$3jd`yg|${xx^sKl6B8%zkVLY@Upw#LFEW(;5tH<}Vk+9$^|Arn z|FnwBo&Q)PbBFy?Q#<3OsS#cG?2% zlGGiFm`LXhO`;`UAul1w-Z`Vtf?Us8dC#`;u&& znNoB*eJw}h*NFS`?$a{-dPL*0F8M+~(YVt)kYM4VNU+@3zN2&n0tWYH1JBZIcFRw^ zHcQA{5yt6*xhcZf52B@`n_`Cw*+hgv1 z`c$cfh<$qSyELNz6h&nh@_^8jZf>v~6#SZuiBP}-NFPYnUHwnvPN9-#!A`4$APRT2 zw)z6fJ>pOZ6r}}yrc-*6b}h0fdW6|53S2iLHaE%*pZJXS4O=ZBYBd`xAK zU$CoKStYw*orN1*;v?uv|F15I@>Q67;r42Mg2kukwf73_0Zgs(6U@j@o{K*K#VZw= z%f2-ZS!C5NeTo3HrFQZ7mxlsastCdXHtfXG3&Pk9a&sQnj{3Dl*k#_A$zsP(_igxE z@t2E{aG|G%(b@frzE+@$H|@W|)Km@?ZZB8*JGMVswKSaIXJ;9`hHtDc$7#tp+!D8f zDn6m`8ctpb>d=wJH@@^4W0kNm>75K*YxF6!3h zrS-pd5^Zo2HtH*W$wHv3q4jq>Zvl;En_P;p+>X*ZJhu7$h zj-bvNN=J-r_Vv#7LtM{LZ)EAU3LIc-T}{7Jx+*OuK_`Kh{7fgOWw=o4qrN*+Jccj4 zW@fdo)!D_gSfGzLeRj3dpz_?$j=4Yw2r?-umHk&P56cE$61sc)ThG=d-fHoJ#!p?; z2OFw&z5d1D&TlT<6R70w@i+4Y?~4y+slx>I5o7noT##B#@UKK)l_Icn>EqA8#4qf7 z!)v6+Q&^XTU;k{M-P^-!K6a>I`X#~U#iH8FbxqfEDPQ2HXL5PHYH$CgJqLb?U5e@X z#(ZR-z5165fb#GxI=->1nf@U^BeNyX;tUA*lF&MnU;2^(Fmty4F-p_w?{|*XcNJK+ zjIR3V@4sm-roDN3f&^X?@Yxxa^P-D+Wyx1WUkxt=UosHd#rqEn|M1cOMApip&)GX! zE0ObQi91b$n@ewyK{4$AlDzytA(fvB`ZeRz_&5jv&+;9=a>dJO4uDV#d3!KX>uYg(xKIe^sB8t@HY)ahTNkzP3dD`LX`z*$Rt^gAew$Po91*Z&XunfoXj z?BKfcoPWBZACHF_)UEfW&A((pV8g+U(32ef365lm{UG#%)db`Dt@$t6U(4|Sqb^G7 z_ZEW#@e0rX`gufP(i@CR>#sQ|rsF4Py+E44-!L<)_O9jG{PSfgM8nGyPJRq=U;W%)z Date: Thu, 26 Jun 2025 15:50:57 +0200 Subject: [PATCH 043/128] Removed STATE_MY_ITFS and CMD_MY_ITFS. References to command and state interfaces need to be added in the future for better readability and safety. --- motion_primitives_forward_controller/README.md | 1 + .../motion_primitives_forward_controller.hpp | 5 ----- .../test/test_motion_primitives_forward_controller.cpp | 7 ++----- ...est_motion_primitives_forward_controller_preceeding.cpp | 3 --- 4 files changed, 3 insertions(+), 13 deletions(-) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 921fd3fd98..54a62d5b14 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -29,6 +29,7 @@ For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver # TODOs/ improvements +- Use references for command and state interfaces to improve code readability and less error-prone. - Extend the tests - Test for a sequence of multiple primitives - Test for canceling movement diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index b71ad4064a..6092bbeca1 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -35,11 +35,6 @@ namespace motion_primitives_forward_controller { -// name constants for state interfaces -static constexpr size_t STATE_MY_ITFS = 0; - -// name constants for command interfaces -static constexpr size_t CMD_MY_ITFS = 0; class MotionPrimitivesForwardController : public controller_interface::ControllerInterface { diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index 3af7371dd0..b59bebcdc5 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -23,9 +23,6 @@ #include "rclcpp/rclcpp.hpp" #include "test_motion_primitives_forward_controller.hpp" -using motion_primitives_forward_controller::CMD_MY_ITFS; -using motion_primitives_forward_controller::STATE_MY_ITFS; - class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture { @@ -110,12 +107,12 @@ TEST_F(MotionPrimitivesForwardControllerTest, reactivate_success) ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); ASSERT_EQ(controller_->on_deactivate(rclcpp_lifecycle::State()), NODE_SUCCESS); - auto val_opt = controller_->command_interfaces_[CMD_MY_ITFS].get_optional(); + auto val_opt = controller_->command_interfaces_[0].get_optional(); ASSERT_TRUE(std::isnan(val_opt.value())); ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); - val_opt = controller_->command_interfaces_[CMD_MY_ITFS].get_optional(); + val_opt = controller_->command_interfaces_[0].get_optional(); ASSERT_TRUE(std::isnan(val_opt.value())); ASSERT_EQ( diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index c83f658be0..1a43a6982a 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -22,9 +22,6 @@ #include #include -using motion_primitives_forward_controller::CMD_MY_ITFS; -using motion_primitives_forward_controller::STATE_MY_ITFS; - class MotionPrimitivesForwardControllerTest : public MotionPrimitivesForwardControllerFixture { From 123cdb13098f238070b1e868c16868ee6dfb41af Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 26 Jun 2025 16:14:24 +0200 Subject: [PATCH 044/128] removed static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all... --- .../motion_primitives_forward_controller.cpp | 17 ----------------- 1 file changed, 17 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 821a8ac0e2..93827fa2cd 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -26,23 +26,6 @@ #include "motion_primitives_forward_controller/motion_type.hpp" #include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" -namespace -{ // utility - -// TODO(destogl): remove this when merged upstream -// Changed services history QoS to keep all so we don't lose any client service calls -static constexpr rmw_qos_profile_t rmw_qos_profile_services_hist_keep_all = { - RMW_QOS_POLICY_HISTORY_KEEP_ALL, - 1, // message queue depth - RMW_QOS_POLICY_RELIABILITY_RELIABLE, - RMW_QOS_POLICY_DURABILITY_VOLATILE, - RMW_QOS_DEADLINE_DEFAULT, - RMW_QOS_LIFESPAN_DEFAULT, - RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT, - RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT, - false}; -} // namespace - namespace motion_primitives_forward_controller { MotionPrimitivesForwardController::MotionPrimitivesForwardController() From cb2e1d648445ce50510cc6bb101e16075b98cd65 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 26 Jun 2025 17:06:11 +0200 Subject: [PATCH 045/128] changed ExecutionState, MotionType and ReadyForNewPrimitive to enum --- .../execution_state.hpp | 29 ---------------- .../motion_primitives_forward_controller.hpp | 30 +++++++++++++++- .../motion_type.hpp | 34 ------------------- .../ready_for_new_primitive.hpp | 26 -------------- .../motion_primitives_forward_controller.cpp | 32 ++++++++--------- ...t_motion_primitives_forward_controller.cpp | 7 ++-- ...t_motion_primitives_forward_controller.hpp | 10 +++--- 7 files changed, 55 insertions(+), 113 deletions(-) delete mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp delete mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp delete mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp deleted file mode 100644 index 3557c56101..0000000000 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/execution_state.hpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright (c) 2025, b»robotized -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// Authors: Mathias Fuhrer - -#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ -#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ - -namespace ExecutionState -{ -static constexpr uint8_t IDLE = 0; -static constexpr uint8_t EXECUTING = 1; -static constexpr uint8_t SUCCESS = 2; -static constexpr uint8_t ERROR = 3; -static constexpr uint8_t STOPPED = 4; -} // namespace ExecutionState - -#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__EXECUTION_STATE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 6092bbeca1..80a4778c6d 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -35,6 +35,33 @@ namespace motion_primitives_forward_controller { +enum class ExecutionState : uint8_t +{ + IDLE = 0, + EXECUTING = 1, + SUCCESS = 2, + ERROR = 3, + STOPPED = 4 +}; + +enum class MotionType : uint8_t +{ + LINEAR_JOINT = 10, + LINEAR_CARTESIAN = 50, + CIRCULAR_CARTESIAN = 51, + + STOP_MOTION = 66, + RESET_STOP = 67, + + MOTION_SEQUENCE_START = 100, + MOTION_SEQUENCE_END = 101 +}; + +enum class ReadyForNewPrimitive : uint8_t +{ + NOT_READY = 0, + READY = 1 +}; class MotionPrimitivesForwardController : public controller_interface::ControllerInterface { @@ -85,7 +112,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool print_error_once_ = true; bool robot_stopped_ = false; bool was_executing_ = false; - uint8_t execution_status_; + ExecutionState execution_status_; + ReadyForNewPrimitive ready_for_new_primitive_; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp deleted file mode 100644 index 3eb70221f5..0000000000 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_type.hpp +++ /dev/null @@ -1,34 +0,0 @@ -// Copyright (c) 2025, b»robotized -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// Authors: Mathias Fuhrer - -#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ -#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ - -namespace MotionType -{ -// Motion Primitives -static constexpr uint8_t LINEAR_JOINT = 10; // changed to 10 because 0 is default value -static constexpr uint8_t LINEAR_CARTESIAN = 50; -static constexpr uint8_t CIRCULAR_CARTESIAN = 51; - -// Helper types -static constexpr uint8_t STOP_MOTION = 66; -static constexpr uint8_t RESET_STOP = 67; -// indicate motion sequence instead of executing single primitives -static constexpr uint8_t MOTION_SEQUENCE_START = 100; -static constexpr uint8_t MOTION_SEQUENCE_END = 101; -} // namespace MotionType -#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_TYPE_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp deleted file mode 100644 index 3a487b7463..0000000000 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/ready_for_new_primitive.hpp +++ /dev/null @@ -1,26 +0,0 @@ -// Copyright (c) 2025, b»robotized -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -// Authors: Mathias Fuhrer - -#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ -#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ - -namespace ReadyForNewPrimitive -{ -static constexpr uint8_t NOT_READY = 0; -static constexpr uint8_t READY = 1; -} // namespace ReadyForNewPrimitive - -#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__READY_FOR_NEW_PRIMITIVE_HPP_ diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 93827fa2cd..8bd156955d 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -15,16 +15,11 @@ // Authors: Mathias Fuhrer #include "motion_primitives_forward_controller/motion_primitives_forward_controller.hpp" - #include #include #include #include - #include "controller_interface/helpers.hpp" -#include "motion_primitives_forward_controller/execution_state.hpp" -#include "motion_primitives_forward_controller/motion_type.hpp" -#include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" namespace motion_primitives_forward_controller { @@ -162,8 +157,8 @@ controller_interface::return_type MotionPrimitivesForwardController::update( get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); return controller_interface::return_type::ERROR; } - execution_status_ = static_cast(std::round(opt_value_execution.value())); - + execution_status_ = + static_cast(static_cast(std::round(opt_value_execution.value()))); switch (execution_status_) { case ExecutionState::IDLE: @@ -199,7 +194,8 @@ controller_interface::return_type MotionPrimitivesForwardController::update( default: RCLCPP_ERROR( - get_node()->get_logger(), "Error: Unknown execution status: %d", execution_status_); + get_node()->get_logger(), "Error: Unknown execution status: %d", + static_cast(execution_status_)); return controller_interface::return_type::ERROR; } @@ -210,11 +206,12 @@ controller_interface::return_type MotionPrimitivesForwardController::update( get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); return controller_interface::return_type::ERROR; } - uint8_t ready_for_new_primitive = static_cast(std::round(opt_value_ready.value())); + ready_for_new_primitive_ = + static_cast(static_cast(std::round(opt_value_ready.value()))); if (!moprim_queue_.empty()) // check if new command is available { - switch (ready_for_new_primitive) + switch (ready_for_new_primitive_) { case ReadyForNewPrimitive::NOT_READY: { @@ -232,7 +229,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( default: RCLCPP_ERROR( get_node()->get_logger(), "Error: Unknown state for ready_for_new_primitive: %d", - ready_for_new_primitive); + static_cast(ready_for_new_primitive_)); return controller_interface::return_type::ERROR; } } @@ -291,7 +288,9 @@ bool MotionPrimitivesForwardController::set_command_interfaces() (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw // Process via poses if available (only for circular motion) - if (current_moprim->type == MotionType::CIRCULAR_CARTESIAN && current_moprim->poses.size() == 2) + if ( + current_moprim->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && + current_moprim->poses.size() == 2) { const auto & via_pose = current_moprim->poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x @@ -347,7 +346,7 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal { const auto & primitive = primitives[i]; - switch (primitive.type) + switch (static_cast(primitive.type)) { case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); @@ -474,7 +473,7 @@ void MotionPrimitivesForwardController::execute_goal( if (add_sequence_wrappers) { std::shared_ptr start_marker = std::make_shared(); - start_marker->type = MotionType::MOTION_SEQUENCE_START; + start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); moprim_queue_.push(start_marker); } @@ -488,7 +487,7 @@ void MotionPrimitivesForwardController::execute_goal( if (add_sequence_wrappers) { std::shared_ptr end_marker = std::make_shared(); - end_marker->type = MotionType::MOTION_SEQUENCE_END; + end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); moprim_queue_.push(end_marker); } @@ -500,7 +499,8 @@ void MotionPrimitivesForwardController::execute_goal( rclcpp::Rate rate(50); while (rclcpp::ok()) { - auto execution_status = static_cast(std::round(state_interfaces_[0].get_value())); + ExecutionState execution_status = static_cast( + static_cast(std::round(state_interfaces_[0].get_value()))); if (execution_status == ExecutionState::SUCCESS && was_executing_) { RCLCPP_INFO(get_node()->get_logger(), "Execution completed successfully."); diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index b59bebcdc5..55a17fe03a 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -146,8 +146,11 @@ TEST_F(MotionPrimitivesForwardControllerTest, receive_single_action_goal) controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01)), controller_interface::return_type::OK); - EXPECT_EQ(command_values_[0], MotionType::LINEAR_JOINT); // motion type - EXPECT_EQ(command_values_[1], 0.1); // q1 - q6 + EXPECT_EQ( + command_values_[0], + static_cast( + motion_primitives_forward_controller::MotionType::LINEAR_JOINT)); // motion type + EXPECT_EQ(command_values_[1], 0.1); // q1 - q6 EXPECT_EQ(command_values_[2], 0.2); EXPECT_EQ(command_values_[3], 0.3); EXPECT_EQ(command_values_[4], 0.4); diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index 31fbae6e12..d0e06ace19 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -43,9 +43,6 @@ #include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" -#include "motion_primitives_forward_controller/execution_state.hpp" -#include "motion_primitives_forward_controller/motion_type.hpp" -#include "motion_primitives_forward_controller/ready_for_new_primitive.hpp" using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; @@ -161,7 +158,8 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test auto goal_msg = ExecuteMotion::Goal(); MotionPrimitive primitive; - primitive.type = MotionType::LINEAR_JOINT; + primitive.type = + static_cast(motion_primitives_forward_controller::MotionType::LINEAR_JOINT); primitive.joint_positions = joint_positions; primitive.blend_radius = blend_radius; @@ -201,7 +199,9 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test std::vector state_interface_names_ = {"execution_status", "ready_for_new_primitive"}; std::string interface_namespace_ = "motion_primitive"; - std::array state_values_ = {ExecutionState::IDLE, ReadyForNewPrimitive::READY}; + std::array state_values_ = { + static_cast(motion_primitives_forward_controller::ExecutionState::IDLE), + static_cast(motion_primitives_forward_controller::ReadyForNewPrimitive::READY)}; std::array command_values_ = { 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, 101.101, From f19e43ead0e7a4e5dce85fe2e818e667b6dd8390 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 08:52:08 +0200 Subject: [PATCH 046/128] removed validate_motion_primitives_forward_controller_parameters.hpp --- .../CMakeLists.txt | 1 - ...imitives_forward_controller_parameters.hpp | 38 ------------------- 2 files changed, 39 deletions(-) delete mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 6cb6c58f30..0f5ab87f9d 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -25,7 +25,6 @@ endforeach() generate_parameter_library(motion_primitives_forward_controller_parameters src/motion_primitives_forward_controller.yaml - include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp ) add_library( motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp deleted file mode 100644 index c2ff279035..0000000000 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/validate_motion_primitives_forward_controller_parameters.hpp +++ /dev/null @@ -1,38 +0,0 @@ -// Copyright (c) 2025, b»robotized -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ -#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ - -#include - -#include "parameter_traits/parameter_traits.hpp" - -namespace parameter_traits -{ -Result forbidden_interface_name_prefix(rclcpp::Parameter const & parameter) -{ - auto const & interface_name = parameter.as_string(); - - if (interface_name.rfind("blup_", 0) == 0) - { - return ERROR("'interface_name' parameter can not start with 'blup_'"); - } - - return OK; -} - -} // namespace parameter_traits - -#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__VALIDATE_MOTION_PRIMITIVES_FORWARD_CONTROLLER_PARAMETERS_HPP_ From 06ba279d78c420596d42d4141dde35ca227b1a66 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 09:29:19 +0200 Subject: [PATCH 047/128] Changed some RCLCPP_INFO prints to _DEBUG to reduce output --- .../src/motion_primitives_forward_controller.cpp | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 8bd156955d..72a0d3b763 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -30,7 +30,7 @@ MotionPrimitivesForwardController::MotionPrimitivesForwardController() controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init() { - RCLCPP_INFO(get_node()->get_logger(), "Initializing Motion Primitives Forward Controller"); + RCLCPP_DEBUG(get_node()->get_logger(), "Initializing Motion Primitives Forward Controller"); try { @@ -49,7 +49,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init( controller_interface::CallbackReturn MotionPrimitivesForwardController::on_configure( const rclcpp_lifecycle::State & /*previous_state*/) { - RCLCPP_INFO(get_node()->get_logger(), "Configuring Motion Primitives Forward Controller"); + RCLCPP_DEBUG(get_node()->get_logger(), "Configuring Motion Primitives Forward Controller"); params_ = param_listener_->get_params(); @@ -94,7 +94,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi return controller_interface::CallbackReturn::ERROR; } - RCLCPP_INFO(get_node()->get_logger(), "configure successful"); + RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); return controller_interface::CallbackReturn::SUCCESS; } @@ -134,7 +134,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activ const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); - RCLCPP_INFO(get_node()->get_logger(), "Controller activated"); + RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -142,7 +142,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_deact const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); - RCLCPP_INFO(get_node()->get_logger(), "Controller deactivated"); + RCLCPP_DEBUG(get_node()->get_logger(), "Controller deactivated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -162,11 +162,9 @@ controller_interface::return_type MotionPrimitivesForwardController::update( switch (execution_status_) { case ExecutionState::IDLE: - // RCLCPP_INFO(get_node()->get_logger(), "Execution state: IDLE"); print_error_once_ = true; break; case ExecutionState::EXECUTING: - // RCLCPP_INFO(get_node()->get_logger(), "Execution state: EXECUTING"); if (!was_executing_) { was_executing_ = true; @@ -175,12 +173,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( break; case ExecutionState::SUCCESS: - // RCLCPP_INFO(get_node()->get_logger(), "Execution state: SUCCESS"); print_error_once_ = true; break; case ExecutionState::STOPPED: - // RCLCPP_INFO(get_node()->get_logger(), "Execution state: STOPPED"); print_error_once_ = true; break; From cd95fde7da13d8ead758da5b4aa98bb22234a620 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 09:49:39 +0200 Subject: [PATCH 048/128] renamed robot_stopped_ to robot_stop_requested_ and changed it from bool to std::atomic --- .../motion_primitives_forward_controller.hpp | 2 +- .../src/motion_primitives_forward_controller.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 80a4778c6d..2dea0b2955 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -110,7 +110,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle size_t queue_size_ = 0; std::mutex command_mutex_; bool print_error_once_ = true; - bool robot_stopped_ = false; + std::atomic robot_stop_requested_ = false; bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 72a0d3b763..4a5f2d9836 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -395,7 +395,7 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ std::lock_guard guard(command_mutex_); reset_command_interfaces(); - robot_stopped_ = true; + robot_stop_requested_ = true; // send stop command immediately to the hw-interface (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); while (!moprim_queue_.empty()) @@ -413,7 +413,7 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ reset_command_interfaces(); // send reset stop command to the hw-interface (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); - robot_stopped_ = false; + robot_stop_requested_ = false; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); return rclcpp_action::CancelResponse::ACCEPT; @@ -431,9 +431,9 @@ void MotionPrimitivesForwardController::execute_goal( { const auto & goal = goal_handle->get_goal(); - if (robot_stopped_) + if (robot_stop_requested_) { - RCLCPP_WARN(get_node()->get_logger(), "Robot is stopped. Discarding the new command."); + RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); return; } From 14adc0efb2cce58feda54456800289dcfa5e848f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 10:17:53 +0200 Subject: [PATCH 049/128] removed queue_size_ parameter --- .../motion_primitives_forward_controller.hpp | 1 - .../motion_primitives_forward_controller.cpp | 19 ------------------- .../motion_primitives_forward_controller.yaml | 6 ------ ..._primitives_forward_controller_params.yaml | 1 - ..._forward_controller_preceeding_params.yaml | 1 - 5 files changed, 28 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 2dea0b2955..875fba5100 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -107,7 +107,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle void reset_command_interfaces(); bool set_command_interfaces(); - size_t queue_size_ = 0; std::mutex command_mutex_; bool print_error_once_ = true; std::atomic robot_stop_requested_ = false; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 4a5f2d9836..4cbcf62e6b 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -87,13 +87,6 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi std::bind( &MotionPrimitivesForwardController::goal_accepted_callback, this, std::placeholders::_1)); - queue_size_ = params_.queue_size; - if (queue_size_ == 0) - { - RCLCPP_ERROR(get_node()->get_logger(), "Error: Queue size must be greater than 0!"); - return controller_interface::CallbackReturn::ERROR; - } - RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); return controller_interface::CallbackReturn::SUCCESS; } @@ -453,18 +446,6 @@ void MotionPrimitivesForwardController::execute_goal( required_queue_space += 2; // start + end } - // Check if queue has enough space - if (moprim_queue_.size() + required_queue_space > queue_size_) - { - RCLCPP_ERROR( - get_node()->get_logger(), - "Received more motion primitives than queue can store. " - "Current queue size: %zu, required space: %zu. " - "Please increase the queue size in the controller parameters.", - moprim_queue_.size(), required_queue_space); - return; - } - // Add sequence start marker if (add_sequence_wrappers) { diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml index 62db1ccb09..cd100b7be4 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml @@ -25,9 +25,3 @@ motion_primitives_forward_controller: not_empty<>: null, } } - queue_size: { - type: int, - default_value: 10, - description: "Queue size to buffer incoming commands", - read_only: true, - } diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index aaa5ef1638..916a6abbb8 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -30,4 +30,3 @@ test_motion_primitives_forward_controller: state_interfaces: - execution_status - ready_for_new_primitive - queue_size: 20 # queue size to buffer incoming commands diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index aaa5ef1638..916a6abbb8 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -30,4 +30,3 @@ test_motion_primitives_forward_controller: state_interfaces: - execution_status - ready_for_new_primitive - queue_size: 20 # queue size to buffer incoming commands From c47834cd80e204a3361b57b04fe5b0b4c13711ea Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 11:12:22 +0200 Subject: [PATCH 050/128] wrapped moprim_queue_.push with start and end marker into a lambda --- .../motion_primitives_forward_controller.hpp | 4 +- .../motion_primitives_forward_controller.cpp | 38 ++++++++----------- 2 files changed, 18 insertions(+), 24 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 875fba5100..199dd0466b 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -90,8 +90,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::shared_ptr param_listener_; motion_primitives_forward_controller::Params params_; - using MotionPrimitiveMsg = industrial_robot_motion_interfaces::msg::MotionPrimitive; - std::queue> moprim_queue_; + using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; + std::queue> moprim_queue_; using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; rclcpp_action::Server::SharedPtr action_server_; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 4cbcf62e6b..cf6b0dde3f 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -242,7 +242,7 @@ bool MotionPrimitivesForwardController::set_command_interfaces() { std::lock_guard guard(command_mutex_); // Get the oldest message from the queue - std::shared_ptr current_moprim = moprim_queue_.front(); + std::shared_ptr current_moprim = moprim_queue_.front(); moprim_queue_.pop(); // Check if the message is valid @@ -438,39 +438,33 @@ void MotionPrimitivesForwardController::execute_goal( return; } - size_t required_queue_space = primitives.size(); - // add sequence markers only if there are multiple primitives - bool add_sequence_wrappers = primitives.size() > 1; - if (add_sequence_wrappers) + auto add_motions = [this](const std::vector & motion_primitives) { - required_queue_space += 2; // start + end - } + for (const auto & primitive : motion_primitives) + { + moprim_queue_.push(std::make_shared(primitive)); + } + }; - // Add sequence start marker - if (add_sequence_wrappers) + if (primitives.size() > 1) { - std::shared_ptr start_marker = std::make_shared(); + std::shared_ptr start_marker = std::make_shared(); start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); moprim_queue_.push(start_marker); - } - // Add motion primitives to the queue - for (const auto & primitive : primitives) - { - moprim_queue_.push(std::make_shared(primitive)); - } + add_motions(primitives); - // Add sequence end marker - if (add_sequence_wrappers) - { - std::shared_ptr end_marker = std::make_shared(); + std::shared_ptr end_marker = std::make_shared(); end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); moprim_queue_.push(end_marker); } + else + { + add_motions(primitives); + } RCLCPP_INFO( - get_node()->get_logger(), "Accepted goal with %zu motion primitives%s.", primitives.size(), - add_sequence_wrappers ? " (wrapped in sequence markers)" : ""); + get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); ExecuteMotion::Result result; rclcpp::Rate rate(50); From 1e2691a3bfcefd20fbd6ea4b3463095c8772a17e Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 12:03:48 +0200 Subject: [PATCH 051/128] Moved functionallity to cancle movement from goal_cancelled_callback() to update(). Only cancel_requested_ = true gets set in goal_cancelled_callback() --- .../motion_primitives_forward_controller.hpp | 3 ++ .../motion_primitives_forward_controller.cpp | 49 +++++++++---------- 2 files changed, 27 insertions(+), 25 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 199dd0466b..ec6867469f 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -109,6 +109,9 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::mutex command_mutex_; bool print_error_once_ = true; + // cancel requested by the action server + std::atomic cancel_requested_ = false; + // robot stop command sent to the hardware interface std::atomic robot_stop_requested_ = false; bool was_executing_ = false; ExecutionState execution_status_; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index cf6b0dde3f..423b967a30 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -142,6 +142,20 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_deact controller_interface::return_type MotionPrimitivesForwardController::update( const rclcpp::Time & time, const rclcpp::Duration & /*period*/) { + if (cancel_requested_) + { + RCLCPP_INFO(get_node()->get_logger(), "Cancel requested, stopping execution."); + cancel_requested_ = false; + reset_command_interfaces(); + // send stop command immediately to the hw-interface + (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); + while (!moprim_queue_.empty()) + { // clear the queue + moprim_queue_.pop(); + } + robot_stop_requested_ = true; + } + // read the status from the state interface auto opt_value_execution = state_interfaces_[0].get_optional(); if (!opt_value_execution.has_value()) @@ -171,6 +185,15 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::STOPPED: print_error_once_ = true; + if (robot_stop_requested_) + { + // If the robot was stopped by a stop command, reset the command interfaces + // to allow new motion primitives to be sent. + reset_command_interfaces(); + (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); + robot_stop_requested_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); + } break; case ExecutionState::ERROR: @@ -384,31 +407,7 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_callback( const std::shared_ptr>) { - RCLCPP_INFO(get_node()->get_logger(), "Canceling goal"); - - std::lock_guard guard(command_mutex_); - reset_command_interfaces(); - robot_stop_requested_ = true; - // send stop command immediately to the hw-interface - (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); - while (!moprim_queue_.empty()) - { // clear the queue - moprim_queue_.pop(); - } - - RCLCPP_INFO(get_node()->get_logger(), "Waiting for Robot to stop..."); - while (execution_status_ != ExecutionState::STOPPED) - { - // Small sleep to prevent busy waiting - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - - reset_command_interfaces(); - // send reset stop command to the hw-interface - (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); - robot_stop_requested_ = false; - - RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); + cancel_requested_ = true; return rclcpp_action::CancelResponse::ACCEPT; } From 5e953407889607277897cb03fbbd16c436bba48a Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 15:07:15 +0200 Subject: [PATCH 052/128] removed execute_goal() in extra thread. Integrated it into goal_accepted_callback() and updtae() --- .../motion_primitives_forward_controller.hpp | 4 +- .../motion_primitives_forward_controller.cpp | 101 ++++++++---------- 2 files changed, 47 insertions(+), 58 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index ec6867469f..3a6299c0a0 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -101,13 +101,11 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle const std::shared_ptr> goal_handle); void goal_accepted_callback( const std::shared_ptr> goal_handle); - void execute_goal( - const std::shared_ptr> goal_handle); + std::shared_ptr> pending_action_goal_; void reset_command_interfaces(); bool set_command_interfaces(); - std::mutex command_mutex_; bool print_error_once_ = true; // cancel requested by the action server std::atomic cancel_requested_ = false; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 423b967a30..525a8026e4 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -170,6 +170,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( { case ExecutionState::IDLE: print_error_once_ = true; + was_executing_ = false; break; case ExecutionState::EXECUTING: if (!was_executing_) @@ -181,10 +182,34 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::SUCCESS: print_error_once_ = true; + + if (pending_action_goal_ && was_executing_) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + } + break; case ExecutionState::STOPPED: print_error_once_ = true; + was_executing_ = false; + + if (pending_action_goal_) + { + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::CANCELED; + result->error_string = "Motion primitives execution canceled"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + } + if (robot_stop_requested_) { // If the robot was stopped by a stop command, reset the command interfaces @@ -197,6 +222,18 @@ controller_interface::return_type MotionPrimitivesForwardController::update( break; case ExecutionState::ERROR: + was_executing_ = false; + + if (pending_action_goal_) + { + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::FAILED; + result->error_string = "Motion primitives execution failed"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution failed"); + } + if (print_error_once_) { RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); @@ -263,7 +300,6 @@ void MotionPrimitivesForwardController::reset_command_interfaces() // Set command interfaces from the message, gets called in the update function bool MotionPrimitivesForwardController::set_command_interfaces() { - std::lock_guard guard(command_mutex_); // Get the oldest message from the queue std::shared_ptr current_moprim = moprim_queue_.front(); moprim_queue_.pop(); @@ -348,6 +384,12 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal const auto & primitives = goal->trajectory.motions; + if (robot_stop_requested_) + { + RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + if (primitives.empty()) { RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); @@ -414,28 +456,9 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ void MotionPrimitivesForwardController::goal_accepted_callback( const std::shared_ptr> goal_handle) { - std::thread{std::bind(&MotionPrimitivesForwardController::execute_goal, this, goal_handle)} - .detach(); -} - -void MotionPrimitivesForwardController::execute_goal( - const std::shared_ptr> goal_handle) -{ - const auto & goal = goal_handle->get_goal(); + pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - if (robot_stop_requested_) - { - RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); - return; - } - - const auto & primitives = goal->trajectory.motions; - - if (primitives.empty()) - { - RCLCPP_WARN(get_node()->get_logger(), "Received goal with no motion primitives. Ignoring."); - return; - } + const auto & primitives = goal_handle->get_goal()->trajectory.motions; auto add_motions = [this](const std::vector & motion_primitives) { @@ -464,40 +487,8 @@ void MotionPrimitivesForwardController::execute_goal( RCLCPP_INFO( get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); - - ExecuteMotion::Result result; - rclcpp::Rate rate(50); - while (rclcpp::ok()) - { - ExecutionState execution_status = static_cast( - static_cast(std::round(state_interfaces_[0].get_value()))); - if (execution_status == ExecutionState::SUCCESS && was_executing_) - { - RCLCPP_INFO(get_node()->get_logger(), "Execution completed successfully."); - result.error_code = ExecuteMotion::Result::SUCCESSFUL; - result.error_string = "Trajectory executed successfully"; - was_executing_ = false; - break; - } - else if (execution_status == ExecutionState::ERROR) - { - RCLCPP_ERROR(get_node()->get_logger(), "Execution failed with an error."); - result.error_code = ExecuteMotion::Result::FAILED; - result.error_string = "Trajectory execution failed"; - break; - } - else if (execution_status == ExecutionState::STOPPED) - { - RCLCPP_INFO(get_node()->get_logger(), "Execution stopped."); - result.error_code = ExecuteMotion::Result::CANCELED; - result.error_string = "Trajectory execution stopped"; - break; - } - rate.sleep(); - } - - goal_handle->succeed(std::make_shared(result)); } + } // namespace motion_primitives_forward_controller #include "pluginlib/class_list_macros.hpp" From 55a59a312ec53c0ff26018a409e6729961a5759b Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 15:27:27 +0200 Subject: [PATCH 053/128] updated action draw.io --- ...Controller_ExecuteMotion_Action.drawio.png | Bin 212574 -> 77709 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio.png b/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio.png index 7425db6eb609de0073086031936b0bbf5115b37b..9b12b4ee2ac5520672245c2cecd6921fa3ac9e47 100644 GIT binary patch literal 77709 zcmeEu2|SeT-hWB9$k;*(lU-Q`S;{*0eM_l?8GH6EBU>1Z5Ru5f6e@+%W?u%8qO>UM zAWOnn%Fh3~V>+GZdEWEB=l?(N`+uKv&QqU0GxvSXecjh}{nqdI_j{s^3^eIz_S5Xx zv4c)qOU-1*4s!I49b{ot6yQo)VTizv9a3-~b#otAjJ=bK-3~rU)vZr_65@{T-adSi zYJ3tBcCKhUTTxpll!F(_)mzlf&IeosBTx=@Zrelj-7h-1xS;qXG>(djgIj{;2n3%b z5_~d4`?~q~Zhh8sa`VN2YZzH+D`}~%YhD-lBvlZSa-!lw;Etx9jk7y=ii9{q9Q;Lq zOBzmIcJ}VzXBt07ZB2c_&db}$-EHgrBxFPpqEcHoylqe}cH5V?uAtq$Z0)?ZFM)TH z;FDD66ITIGhW<*bZm$b`aYMOo|I`R9O$1C1t$h^gR!2=$yj9J-5N3Mk^~}A{ za{j-48tIv?7)>vfhoio`t(^;age_+45whaaThFxh-?|`mRBr2ngBNLLLnNc#IY0)dwh zH?{F{^4QiuZy$e>w0pVxy4l)6#|eZQ>F4O=V`u7tvVnf>2V@akbM$d_0pB3K1nT4C z1ddh3#mNCuA|H2Xz}8WDp#HM1?WID)?Y3q3$ECl$-=w1fT43kyYUkqx^hA97=Th5S zwXFaWvfJPN{vu8Y==YH3IsPI_KL?_=CBxz8qoJYym4gIhw&mb&zy2SH%O9Q*m=~J* zmow6L_koO(gt(EHldBUX%iiFNhP#&^%F7mfQgwIp@p5-@0p{q(Pyd9+_fK?w+aBYW z^W&3{b^*o&Y3pDCP(LciSmgW;xjUO-t$H-0-D5|@9}nY%jK+CsXI z1diL~hsgwb%qJnK`s2_4ls1zr|F$|yl2rFsbtd_Mzfxz(Z5{vLqs~Wvr_Q8f{N>31 zPH|9mae{orwpjhsi^D&WG;9ZIe`OqgqrP@-wkl9e1@z9w1?BDSWCOJB7bpAI9vR4i zm%lj}D=sQ7E(b>bxNv&wf~+*@f*Rx}ArJoJwi={YKff8-0k>l3^COsrE_wrJ;%r9> z#6VoTedQNxAP)Z105Q&g?Av`%UJf9j{}Jf_p_|(_lXkX$6&n6+7y5@0z%Mp|Bq+a{ z1kyDxI~Nq>I=5bFI|BJ5Gx1+}g}=Ork-HP5iKI9LL7I+axk!$UG?TZxua}M8_OGCm z2ip6e#EM&!{fARZlBU?6QtG!haO)`kFQ$}K1uyqYwDq@lW_$FHi11*d^V+Rty->Mc6Ha!#?Bu{^(QK;>3)dnaBqy@i= zV}CkDFFS9iizxJu;22UB59suNM2<(1d`H#56?+hiZ6{bDyZR#q`NO4d+lB1}YkLOp z{@d>C9~dc%h>Ic+Qrla*Ei&8M@IRy?+jEmN!rk89o0R(hSC!%aw`9uxPBMQlYk!{^ z$2j?HS#dd886Y-x;QMLFNQ;Wg%5H!Eiwy@i|6;URW2jCMD;_hDHA1}M}0HA`t|7lGBwk`QrF#RHkZ3Wqu zR}smrb0W#-pV1YNFw|dU^Y_B{_xXbVFCo3EDiqZJVZ^c>9{iJ8@85>%Qlyh4N#j4> zdjHm8NQujdZsP-_N&mDa8W1zT#Vu7)ZZ;rP{u!@(L4i47fBrnSnIsbb3dR}nPY{SG(B#!>p&i><#`)`wKDGBM{PWtCH?%RRdFM4HS z=k4L{<_(#58^A~ZnT-0jk@#0I>c5M)x7SVzH~y3n_jXqMi!lCP`u@I%`@hS`|BpiQ za&rID@%vE{SW1%Zf4qs8I=Zbs+kWMDQ~r4k{O@T>6H>GeKoxIaKw$rg!uD+o@vmUv z|0%-ue>^Sv-(}JNNAdK3F^evBbQ?n;nODjG0X+S$Glip)zsZ9CycT_XA-_aPAY}iO z+41f3|5vc%zl+rW8L;tx^Q3=JJR_q4{rML{+J6Uo%WTJI|9z1>&EsEpr)X$qPMSQOUgTTaPQDoQ#paL{F=F^*G+Y~HcG1qdsC2Fo9{Es z_?R%uF-C2JfgN7GKv-(RhqUd{5i_th!YQYK?exJ1s&y_5QvkF=R}@-zrl zhp%+Mx$$F+GH(uS82S5Oftx&sa$u5&I{P*L=&6GErxbtmygD3}AU>9={K?hdy$Etn@3CX_jSj7P092> zQb}fVMu}`6tuj4XP3_Yoyqy+g`u@Qz=(Nh_ug}Q&vy@Gx8=@(lC`ppR#=djFN+a?U zhjz||t&!)mFLGSFM9vsm;DUXX`qOR_*PD)VhmJBiUS7|Ib*()brQ#JYBTsw4U~okF zIREynbT|6!DhyY`$BNF&TnU1bldTIBBzEV=v8!@u*J4@fsc98u`eunodWVEZEqKj%3t2Pmt*& zM$+0o1nXL-lBdnB3FB$KS-KySO9*scixZ!B@>(K2kC|#|W5_E(*_&GG^RgMvX?p*| zF~(F3w0i=aHxGh!|4>S6Tk^mVcJ}k`yrG}AM&1tk;%Y?3s0FR~m<{Q1T6K%8A1;xn zf%pC%h18q>kj9fxhi7zb(~vFOG4*rvcmxJlUp&7Wpi2E#BS)yC1gYn0>ZZz=pe*xa zlQVv9vKE-uQ$#E0+14sz9pl#5XF}-XL)L~1t9ooW=TnKX4)Q$3&qmWwGu4ZG4FiXm zqTW1wOTRMrq;}m^aFISPD3N~x!xjb+J} zKI~9D?o$3*BZzW2F{O&v!soSmS-+;z%IngZn$_>s_6aoUE)TS2hhrrhPSviwE1f7v z-}?sNd4GB3LoKItKW12{$I7dfukrHX`)ro0pFTt`)^4t&LU->gdYi&`-TY9mXUjnX zcyZ^Pd#G!70`I=((#RGld+DiIYlacTpU6ELUZD;jy&4~Ao9fr^KUOa7{Jxl2w~M}g z`8WqrZY+aIJwoM$)y7;3F}Wm=?=n-md(Co&eVQmEp0qt>LEq_2 zQ|Zftc{kF@sLiCHpUuBI-Wb7Z$#$X7_k+g^ktgKRIOqG%_>Vjt4BOTB?ZFGtJz|*p zJwseonkG&auz9dgya#+bRYI*yC^<3K-Ci$58f~~%yJf4CHkUhIOMXtuUb9{52-#rT zd;DuDF_b>gnmgD|H0-dI@cT2)_lS`)Rk`hartjrO5>y*F1HLkBiq|~82DZbMFeOX! zUa4}So;9`15vl6?PV@E#uTF)=KQ&FZiC2)m=ul`91)ER%P{p4Svavkdu`*erR5&FT zviySZ$+?8iJ!tZ5qww8g3GdFMj}x$Lc{EGh=Z*v})O>q?cGr5#+3}6lnRuJQeBX}` zHaAvV;%fq?pE+O_^104^f1vZNV5kSbTqH$II~+g1d`|+rfN;6J(UWXgQd-Si+u_Fj z&czIyE15Ha0##qkO7@T6cV$Ks_Yb8oUH&dpGaE+)5?Ld_floc?*NZq(MQjKyAz$-* z6N7BO*^#hLa=+ZHWW!P;iLi%X?%a*c-dr1dts5LpC!NZu@VH?&s|5_G(<6^}W~bf_ zF-Rs8lv?MNGGV4)Ww_4!^|(G^%T%W7&f%)oY|V?FN9ZW_E$$ziKWo=ZgD`V^nd5dE z9(i_<3^V^yrloT~nvGH@Nf@7_>=$L9d~l#6`1?b)ipI!ga5$3fG6R7MV(LYN6t)IB zf}+^P*D-DVc_*qXrz;L0sTj|@^~HqxTVQU)zO=_RNIj>FlO!{yOs2{wZlEekjlcvC zQ$yPt#bh9xJBINW2x?%;f@RHJE5xSMu6-uNSgoOLBG{03F;OLHm3*N>hw(74Z{>vw zB9@UJ5rap~>Kn5Zlh=z@f!KRU)r@7V=lI_)S{#@OA#7QZUV`?jl^yAX{TGs4c|UkaaE`$87MA~ z5N{g>30wH}`FeI?UU_FReFuU}DOso{CW_<3Bw;J&ji3?aF*59x!(RS7qf z3@-cDe!J%$F+y`j?|nKs3mb#3P7!-6mI1wFqSDWW;r*6bQ&(D9&bQM87*UfwojN2V zYO7+MF(ampQ{m-yA6%R7;A%`-a`z)tGw0d^GenP*s0#T`qu(&Ut8%DCX~T1=Ni3LQ zAUAupcdWT8#{FVf`lwX;9M^>b0lqQ5jHu0-l5Qw)oNNG??RZaoVhZ@Mj7?ByvyMAh2^g74Q5x_ zxi=p4)0_AGstqd2ossdN3CAl>_Udk9Vqmec!b2>=F6-8y&GuaLe^Cr{aCH*&sC;{EM1U zDhfRmGCekXLonAxXC!4pRDMBTOa6$hgu`$J@GxjcCJqt$UFnqHE+c6O{mSFksw$_&_Tj0p6w-pybXCa2!SHU+PfmsER}UqZ!`&*U9us=KJK~0@zi}=; zZE5PdqLtC4(Udx2Rofs2XAY5eQOf{2IKMOWwvODlx2E~r*P5fvk+p&y7vDc@kf~jM zS=vBz7+)&@k2E(SXX-vwMAV&pI(#MlB+h@BV}Pv(*{8|f7$CsMG|I}Q6!66~d%ukR z)43R`y^x9zuQg^_De8-X@FV@z#|_=>gwBWyGO4`qNWYDs?;izftZaA}CETnQD?T*E zhqEo=#H+Dv{V0aBn2thg@%b_dzLL-3Gh>R2&zA1Dttz#KE-z_kvGi;D`)L|+&y1Wv z>LmxT)@m)sn6`OHd=IgvEj; zbQ>WDg}E%km0QM8z=R%L0D*|oWv!9rwU_R}OarTBDXC0frJC_er4DaeA9dT~9B=!~ z-#f;ov{X+&l!5B;jCY&e`?%Yr*j;f%ta{yv~=ghlDBmQQ=jvJ_>Yyu*4uH_LmD zSmFkOGvknYP^vMk&|Gp@csMZlZtQ7z0nI)3w^IW6Quu=jhRfJH&sC8REIE0lb@s{X z$WR<_zF0Q+I<(?kd-@wOsp#EpkpUxDH8lv4wMpV^h%sP(PQbM*7# z4$I$MU_ph~@Qf05dH9%hIS#qh zmd@AvE`RrFZ4cgD9cZD0JyDr%8N)?=``jHu}H$9pIQ zb_X)pb>n6!4y`Jr4@Pphv4waRpdC$ae0*}{XOzdL80xv-3&b(N^x9!wob6{EsH8qF zyw8PFQE-kj|00mdfK*sGO5c2w<&*`(X24LifJVt~lil3JL6y+i_T!?Q`)}*9&~)kI z*cUjpaiK?N2%20$K5K)m0mmA43+>00v~(4u$QUgOj|`B3Rm#OGic&Fg%#(9k`1NEcAuRpe)#HgmUy>sY4a+!XotM6$qk)x z;p1F5Vcg;FQ`KH^=tY!s;wfCVDXu~})+TV|BVME4O-1j}82@*M?@W*FA3Q8oFZ*12 zOA8&lqp8Z%nkH~|O>;z8(!CLr*0Q{Il06=&$8tup=qxk3+qNRUq-L={V66NKV{4QblM>#(RxQ9Dx**CxvcSE&)bu~AWU`Q~qYsZ?CPFiV?D>%N_K`+PlnesK2E zgR7;{Lk${2oIFwEb>ZiZ$QN_14N~sXB+S0ZaUrBoWyvoTnh##CJjij_@~}3+z;{VT z+FF{$V*T>&t1)pgaW_0AH+b!;++PS05)*!ndY&Xm%LPsc1XP}4Vf2w*98aSYe=@I)?7>dW*=1;ajv z+xks2y6kbG?GN>jH(Wm5wtu6&A!ktwNy}xX&6<$f#s7HsV>&sw|A5#<8@;3RP4snr z!#5T1g(rwQV_Bv8eAI~Q71hiMEZZCUPRrLdjW4J?DU8GEC)CA)O?U>KkU>>CZ>nCM zz~yEOS$yf63HDp?5#FaL>;2`h^sCWycTOcK9{IAz!60l>I8wr|{9rSrj>^Ndgsr1F`}1W)8Gs-`rm|G-|K1TpO$R(cDnOyQsz|S#7$umOh>a^63fg^jh2dQIMYqVXs@E`K~o z>fquCLwEpMN5Y~Qgr-Sz-xkhuiSaU?W?^y?!Y>4n?I+Hk&QyHWbt(9hItf-PfP%*R zXK~tDVmKDI8s>h&>}Zag#Nz-Z`q*wNM+e^(Gfj0 z>}~K$uBpN=jhSqvXR@Sg)mj#UH#I5opV0X(VU(sNp!BGF zJLbGWgXm3L(r)lFx$cZS`#dJhk8((_Y=H^wu{f!CI(jmI8ljzFEveEsWk%c>R2g9< zbHiTa#q05vpI|{7#R>Hd8T*A$y++Eb{(<)Cq6Zz zjhbo3N2vhWdy6O)GQ*~-%v{B$-o{?{1YtR$^U1VC5lppcueM+1i&8AxbP|>^k(l@@ z6nTtX(TFud%*%%{+PHwZ+8!35wOH3$iM5^eqv@bqlpD_pAJSa&Oonpf=3#CzH= z@8S5s)t-SXt!O#XG|FfrZe-X+zDnRlJH4Fc;_A*7F_70ty7^w}B3r!qI2 zwa4YdB*UX#=#rA+1m!r$B>L__(C&G?dv&{u+N0)~$hgx-kn?2j!rf^Orn$Ovf@gA`tci=!!+#Ugc ztBO5^2!?M}kF;K^8OsWY+_hJh`+_Rmo`OCl1wc_-q7b^D zI<_lek`I5=&xF=qar|lrLkF9@ZDJut3?AvhZ*X?#V2V6{U&NwK|LiQk0G_KP>JG9! zXAuB{2973aHdt0Q2Kg&gNewk{89q5-Q+Nk|uIWg$ir$17?&8zs(e(U#+UXe&UR*?F zGLo4cDHc#u-Ro5Eb{xc{&Vj-&WR3!z2oyWcsdn&G-p3j>rZZ_|54dWM0g1ZWkYsd+ zn(0t)HQDRVE`7jj25eC7lw^mzq?<;QSC_s_ zlNt(l-X$2b-!Tg zw@=9GiaxWY{W!Cc+NLcFQfsp{xtStfk6R~ZAuB_JXkPvlMNQu)73;50%HFunyn$x(mCn~}{h}Kpi>)*U3 zLOzJ#6B1a(xSKUB_&CK}$T8W2_rj67IOakvhKh*6`j9Tfd%*_5b@_~ukMQ_CwH{Qj zhsG79Z|9XBHHAl7-8``8d8>ZlJ#Irf&!zq!G|XzlKrgq_6#1}Pl$+*W9vR}JdUm& zzOPSUHy=E*_ZrpF+Y86uIdld9+>907)~=a$7|S}ECAed+h|p-k5k-p$*j3vn2^8V+ z{T7Y0Jyc=`nvv57_9E*!BD+$|RRg}3X|9cD8ss!g4?Xpf_aycr6WBG`q41z;J3Kgt zq>bTJU*pEzCi5g!CmY6R_MhPF^E~%%|a2y`m7e?16DJ;Qpwo4b}-38u{H%Zp{ zttPaArqqbmfC%Hn`GnpBRq=%q?+|a;I!8|8Il_=bR`PI8%wXt}-+i7YsXID<2kqE?`GS=dsX2DRWMUu#W!hn6nc~uu)OA|v1#NdimJO1T(QLSRo5lYmWv?L z)G~tJAG@&g#tKd{LoX&LDpLb>j~H4xu=DUYg);9aQjpI|W!{4HDzI!72@lc@ebWrT zjD}KjvQ?kzc9Hv(mOo*C2;V8H-QW?9uOw%n2#tCyXA@l3v@boTQyiP>6aMhkvBUhG z>aqk@hV&g@j&LdqmSM%=!3)Cpy1b1%<^h24&6W!wvA9f;%V#7R(9dmDA6R?6>(mTh zuD{HtXFeNq&wRRebEA$wriCd&tz9Ujo%VWPx0owHtS=Z{_-V|d;o`3rQ*L9~6dTaY zHnQ%|K3_)+SeNPX;f91ST#W~OPh*2;^Cg1!jxAbAw#)M#dM06_?m43m7W zz>IF&g9vY@^bT`vtYS)x>}&p%b|-->EdNc}Y$?mS2a21-Y8-oZUBZ4Shx~K z=bw*gB~L>?*OyRT)g}o6#L($j`7xkZ0I}5do@M+gulUX%6x0sk zN)ppqhlMCIB!7dOmi3M;8K6kD5CbG_8?-)iH>vlD+bj<^C0S!&i2tZ$HoMzXLZk^> z_S%R*)LFM@w@&o+3cEghDNVpL8ODY@{&fDXPU9w^Dh}2FXf6^WK`a8M9ua0jHUltk zlCqeuTLmu@=Td6rzgEq^BD{_d_PHgUZm|p?LmGfO`gWsZL>gKJvgI8F4Ff)PHE?YZ zqkb?m51e$^N9WH9?21S|=Je@0Ij=Y?#0VLr|4eJN$Rn3G60xZu01zWOR6JOCqpQi& zJ?B9dPJ>VaoJ~V||3U!~Kz2?B`R$9vr)|%spUWa*1+b=u3P&$X3=3Oru6)R+nj4j= zl{-@T^?~YCB(mLT*5Kn)WIN_*z$t0~O{R)ToZjJ+Kr))K8Fk_VR*A5A0Jg%bh7ZoL zEq8zNYE;3dLR>>}_4iMN{(zY{PR@XtYCm)5dyfDBRt$r%-AHHy3He;>j!PgBW!+~L zI17Q}5q8&4+aGyu377!ve20?K#%bV8qdrkaq~;Ep;n?XdXM{tmsA=cb`Q0B}u_PTh zih*r(H3q4t@bIJ=4#L5ivLHOPR9ya?fztXyDcDqnV#&pUkPvf+Oy33wq${0m=4iP% z46^lbQ?AkZpLw+VJMaVl9{D?B!F~h<#@S*QVS< zVm9wR2d;Ewb9%QYY>q%^u^uwu+q+XyfMq&j z;ZeVv(8#snf%$gV>fo#6GgZ&-uh&s3!mh{;;g;O76Gxu(dU*#M1eEW|2ZDK2em2@L zR*7e<4KOWSJuQ>A8_Q$#yd1&nlU7{)^I3~nz{#QS2k3ox0IfhMt=XFYH!d14b+;%=N6jKy z4luR6KUV{Q`bY>>30!_*bw%5kIv2e$&V_7)0DIy+_aNt2c4jNGI9TJ#DqcX5;lmI_ zfR?^B(T#vOx~nrfhwn+9T72>S+5Ll#sU7a;f^HuCPY$987Oqk|^|&Vz$X0e)I`6fn zv%9X^0k)D#^Puku%wpw$!Utadvf;TGV(}Uhg}dPy);EWP9ssVWxhs^YC&<57;{-^t z4x`TsWOyLujRjZ?IFNdSXJS3t0GrCuzw-V`BzQ-wvP`}d3yD#bidL?5s@27bTLjPe zfZmJ?1(Q7wv%VE$(irmg3^7Fn4{3*Kg%yRBHU_=ONK;dSX@Nb@6>KgpYu>+0>;gVs zb*~(+R|uYmlcCyZ8i3Hn;rfO7FS><2QU@_+6ugxM*8Gpf@pdj6hC<=<>9J9cJI*Oe9xT;AMtI!bcBj_e%%fRrzqLO*oIz0cX9y{dcCBsEC(3g z{3y!29hN-h**c8JpYH330ZfOBfhDt^GHu`|er*wL7a6;#yiKEf*`sr*`R%9*Q`Ikj67z32f%Ub@Bit z*xZy#)CzFg4Z4+A|WCxA<*xc#7$$MVB5Q-_7t)#oH!{t8E zy=eiY+0bk6toaO#(kRzVCZH9?@2fXo;>L+TKV!RYyz=cC?W(YEBtT9lG;1p^;um;E zI{3IlLm|h00CUMwkW}(932h)qC)RWBJ?X#r`gqs_a8{8J&p>!o66CsYXIvD@sTT4E zi)`e1O|+4;xr&&uo1V9_3nyXT#JrqAk@>b$H4>5a-1}kI)i5T)hCyFUhpAOr&-oae z15U2-rOdzq^*o5^y{OJj#j>Y?)|Dsgfd9zVTPw{$GCeL2$9Jm=GIL5dA+>1Xa@Qn~ z?LVm2W|jd8h71@t5lPsn1VsZDX2iGk^OPq6fW44G%mYv?`&C=O zcV|pi7y{mk5YDw`-EEtspC_X)ypCo2k_i|QRDPUvn)l0`pyEUL!CUws1{7?#Vo#Pa z));O=P*B%K>Xj&-%8Ziu24wI0vyhL+Agb~-sKqMMgTji>q5h#H2YZiCynQi+7Y}PN zrKS85xeTbrBR?RN%?$En$WMD$30?j+tH`ZMnjm>=-sa;UW1f`bpn~802%2C%uf-mPD8O;a#sIJTfL$vfU!B!#qOA$jQ`& zyS~xQFveoM-VOS{IY-rT255c$q5(UcKN^nRMRgS_pgT61txj{GG(%$l;K+q%fS}(s!~iz{saf^P_aW9=S^jc;>hl32 zj~~51b2wqOAQl$BXh1``UrK5Ml$RK{Kb)@`QxJ=^_$EA|2uZZf6%L?sgF53Tek!FZ z5a%JRM}Np zP&V)o)E*W$X{LYN$Ui*n{mE$@F;SLVOckEr#|CgN6@r4q8B?-jgvgEJCg>zC-<08z1ZfJ zC$wSY4Gd&WfRQVyL4CDZ;E}r7E84fte=SP9SOQ5aXRd|SRjGord)7W^;S9je1dbg? zT*D=$GsajJ>fL($CfcM4Rs>M#Jt7lnDiLf|j*gY)6wreC4^H;QpIeb@O{W&qUH|fK z?18JquigtN=jflb)fJbNX8D?Xfh!cH<^XWl3GQN5y^f^ z4E&~v29AK|y>gb{C$fqc^Vmc94aD}RYr76QslKt2cP65>`TSdXXA3IbGx8pS;7V_T z0T6DvA_k}P#2^kDixzpDTqc!_}eaLz9dWlnWuki>UR?0(I(>j znzRJDz6fj^@5$zvNPN{bV-TG}>ryRZ2;+jgU>|)$E042kdV0^DoNG71O;o>OMxR-p zY*f*)z%xb zxsHgZA;^wk>hmLziB`y~RQGaS4VIuXp3&Z2uS1hEh&d|C6QT>t8Q!mM^Ws6y&C8`B zr7h=f(xWXqIAa&Vc4b4u2p+hHp0gpX!q6s9;R;qG6{*L4iq8L(V1^dHm%xG~L&-Z| z-rd267f0TK;!8nAV+|qvmhlVXeBNZx(7N0>YqL+sm&VW)Ej{#k=YN_v;7l=3&L2l-l01q;z=x_!YRb#{a?hY=4 zXdS+T;c=Q&S&G2L>6=@J?#_EcOGch+^0q}aI;61u1a5-UO3BzJLGdI5niz|AGv7n( z0fAQo$ouxqvwEJ8+iZ?DDQ?2wx5}REKL%X+`;Vvolh_jnQ>}$b$-ZZ=zqE0cGLpA^ zBnsY3fy(LOxdn8>_;q=ouDCWqbS;**9Glgyw7KTJZ%@$RxQoGQWR-PbMxB}{`)-eA(une$KQUzko)ud5o*0Yl)EVjn$H=+4H>t}|N#WHwVY?NJv1v(Qm)-|o*!Q~l z7)NpCy@E@{0lkj}LZxBEW!J_d$0)W;u(BnT`T}yKk(OI$aA)IeD^${9?)L0+ULjSa zOsiw1u2LD#JF&|m*~{$?4WRNx{FLeK%-aSV&p@)gOFKmFGnGnY%^+OWU|&OsW4uQ` zfNx|Xzk5iS-l*vdTI_q>7?vS|DdZl6(fHQwq*PO(>`1+Xq}`Q&u31})Mb7&9UDa3Y ziC-D7FMxbcX%u^IPqB4t)%5*6!VK5B&~orK&VaQwt^VSR&?;R=hrlA}_>`yx{N4{OJ#Rt1;Ho}rGtRwr&{t8onG zPO76-mIgRhtNopWj(fHXRS84hT8yd8KMGYNQr1Z|{MKtwq3Y&=?p@Th06_w!rR_PA zUwuJosTDMIbuXTVl-Ap-0^G%=;8W=11ZC4KtBBNnqKZ+xq1tdzBkN&;`AARle9eYn z;A}^zLPA~6b~Wv>MoUn-y8wWtxY8NrViMN!@7Mg3?B>OVU77EmeU{I!bv5vFf#9>G zt~)-(jBE%9ZsKVknj$%vRBM2P>Jdk}k5VrH$pAQL^Q|L0scC;;Cb>IHQ6wqZuL-22 zS^vht>vadVU^a_##)P^~Dkv-2zk}oYHprIa2_)31_u5AkwIKd&HN}^HD$@Yp#jfwX zo&01E?HTHh&6_OFAD`#^7)FXY8B?>A`({9y;eA=^1%ZV0^{bhhu^gz)sJi`(&s}+Z zn*TyNf@YlIGYNI$)FbvGwukW+z(nO+o$EIyV=}M?HL`IE?XEl-M5nRU)0h}7mI#>a(22~5v@c@8L^p7|-=rl8+K%C6w60|(W}`4B;TIqDlQ zPH)w?Kg5;t2TJph9M>K&uH2gOAkt=QoRod^Cu3^bY~}kL1Y+w&O4634AwiFZkffbb zk23eERX{Az-Ti>j%Hbz_=7v2=c=(g{Iin25?M@np?N{9zhtPd{MaO!H+^df&%JBVh z65tFvJ!la6H-uI{Qjk6S1Tb1x^Xe-qWJejmLW-%gU;Z3N2F8h`szr6OZHMP!a23+ee95iJ%0yU7MvQt_|h^KMT3Q)^p{*njUl1?pmFuQ z$FR-Y0*G|UTZL7#6{xB>Yq4r9A|6zO zp#YXKbt*_uN$E>bego)Gm@9qE1!{S*g$h$nD8Tv(S^~EcR?9k-#VBuWfF7RlNa1sN%Yy z9eQ2b2VSb>SUV`Qund@DQD<9;FTxhh4u;c5LPW+Ir~s#n_iwlPQN;_@n7i-}-x0?D zzze-WlS)eagw;iVO`j!zS}-|4!AV19R9T@`ho*yj(1p1IARp#FN00$=)J1E?p>D{YJJFyQ9Yd(3}E*WZ( z(LjkLqk1c6E*(Dk6u`}7#Sq{6oGI5Cw7AfHunGx!`t`w!JP(i28x9)A%@VSqA8Nio zBHZW*w3h{tCWSlxu(Lqt>jU|k?dSYnx>Y>ni=+?a_W7Q5qfZBJZ@*Sm(YI|btM4Do zBp3eSAINX-PELxdw@-K7XCO-{oT6i|)#^1dR^KLolhXtGue}-o> z`_5e=ESCKY3F2Sl6~1>1URx06aIf-I)>a-EgNObm*A zgHZqPHV63beSo?IP=%Qn((dk|a>X1w7_{*ER!a~lZ;RAaoV!W@bWEUYrg(|Xu zVCMj2|DTEMY_P0ZpK@;z>&LzVm>ggSt3Z1}yoOlwjNS`~I&fS%DPk9q%Hj4DE>X}w%yYS6fXk&LhhcZhAD!08E(?&lLaBd4 z9QNrf$W}+O5y?{yW&J0R?cA<$bNj14!xAu&Fsh5m^gg}2h-t^x7rJ(lS#z{;Pd>Qf z$t1m8AX6!A5L>VvCpCuPNAPZ|Vqdj;BNH|@10+Q=;M2cTc8q;V48+F+k5K4~SQB8fGKCm`Q z1hzt9QUXxk*VS8r_$#>HY8Lf)*^&Lx-70@JoQdY)D6;Pev!YbqT9NU;ny4Dkdi zptpGr^T!bN&Va;mtbG2nScn|3>H7!}U%LcQPc}eIiK&aF7bybp&|vVq@gcdP16dUxt^*vbpvuEOe&E zL`lE5@P7Gp<9RyyVXwMg%y1k+jBXg~D-8AIS&Q}aB#OT=f0rTHRijmqjrlY->qjg?8mN>9)>9D3=1ZY$=9 zrP|Z|#f~u+$8VpQ;QGqIMKs`X?~1Wp$Rn1;2OTNhOC6E7c`Z)*li(WY1d8QEH6cZL z<(JLR-gaA&EB;tZWj1^|n6Sr+t)&JupL95$n+rB~WFpl91VRTEGj-_1J-`Zj-uKVC z9N`dK28;`fG26&TyMYP5GjQpL?q%_vr(TS}QXM!Mo4zX9Mctv1pg|-_KKX7tx8vH()%|*)Nc4LoUb=W@*axj3#kQI(hC1%Q&CH0 z6nQ?D(@ca7%eB%Ol~;;qV?T^iEZ3CnJl;QhMNS_*=nl#W%0%J&G3K3`v39iIZKb?b zKnK_XX*Oqd(TPZH9NdAvL!dP|W<8e^r8aWC-kBo*u^^tCmb)O+`<0wARX&|LTzXJF zY^lLw$jKYDV`{*uJTJ+?edtPXZg7hFUBlN`XRYLY#SI9`=MtGfPiFiTRjosm8i$9~ z0_$;2>0y&EFz3E8p&g^ts@d=uX5&OycxSldcc?$_zAF9(sP@6Dk<+QMG;0l@)CL&F zA%3#?n{E$t^TRhfhnqIVXb@~e*l$ySS$v&NO<-Wa`JSngL9#BYwJ&|_2$ufvKw&i1 z1}%7S^VY%9Q0&WC`kmy4($k@AxE+z=5(9zrP13M9*agS*)s11UOT9U zQS-yN=b?iq_>C_lZ`8*ph+vsl_IhW@&~VBXe^7}?1rD?kAwZw2NJLT*J`Tz$YYl&7 zvpsjHxb%9e>PmY}1oz9pL)<)POo_t7&+79p2h3V!iC~Z3k8&s@uH6cHlrnyNN^Q9@ zmk|g{qToRPvSg6N=Lcc2pc10+MKg!NmL((X`7o`UV*pt)UkMlFSxhEzF1}l({?g|e zHnz2ijRxIJTUs6}=GyN(_gw(mGwZB`B-;&keg}LvA<~GFCX&ah25|y*UXbf6c^?lJ zHhoD3dGU0UH-7}ZzTbJ16^ScUY7Yo^b{mt0k~PxtuyoMSEb>MpETv@nd`xKr^0-qy zxUl&rQbIJXl`RA>vL}OT$40i05~DI+Ja>k5;P7ozd4}j&9v4`DU5YPxLLN*tdz=Hg zvjMsC<;r+i{R=h(uTV8I$(*MTsW+$mq;TyO0OOV#MR=CYsu=ybdT9m>xm z$AkWUC^d4&XQ-{jncSGFm0(n2G;%);%7WQw>;O15UUS-rg3Tf)lBFj zImHnQN=_kd90B8^b_rdNgAtbuj!%_4>ap(Whhv!s74WHoY?y^7t9UkAZ(5%!|HNFglel_WjZ}1d zA7FEFYHXhtcDvKX%Fr~+H49sfAv!A~*f!`y*(!vtx>Qg`%FV~;M(;eWfrA(00=O;V z2F$9bU=gr#bFNlNKK3dq3M$qnWG%wQ$-6@0-R!$2XDXhCQbRfGL|E5k4LI#6u3!vp zrf$Ty7{{joDAu?t&SJ0^O~=60<@LZ{SO@ZQMwP2T|PkV3k}2a``NdEH0ho4c~wj=COoQu2E+r zIE4xu>glQHe5>qP#+V##=~JguMv{@^VPZ(HGMF2_M%|5{F# z5S8W_(bI-l#nb#zbziGpb6;5o%w#ZKYg=#=R?&bL&?-!h=={)P{tqlOPx(5-A;@An zCe&j`O_t3~Yg%hZlf)e=iKemcHM@lj&1XbwFxs-5-j`) z6;cx_#Pku!UI#%gQ+3ScEV1&WD+~8kaVk4LQ~8e`jZV@|Q0C>y5capU9$|9pI`_O# zP4=MN89{Ap9*al^oDnbWx=O=$M|uVd1O;MeJtHB)H&VR*p~bBbp?UXy&O-e$Ur`M5x@kg174{6V(OG5{tJzLPPER^ow4fJ))S8 za4pvOdm-JttMohq3D~6d#q4*p=68Zu-JoMSrdskmYAc&lbnd;XlOq;79alQf@W^4} z+f4O_Yt6E~0M}RP@;1wkNAIUzS{q609zh%)Mb+huC*zVX%#wEp&cDp}yrdjDm{1dJ z_yi|@0p<+EShp8!HRg4KJB2&r+%caNpJOk4khC9ejx=ITZk8tAUb%tH0?w|5io!?? zacQH=$}5}*{2?(+B^E`Y8GE+jFx4Y&86dc{{qk%hyeFqb)!~t=1fenzom_|=n9n1I zF~pl+8oWyWkU0&@N}j94Hq-iC>~Xv%Gg|A|zRFlw5 zy7+Pn=)MrHs?|TFLF}O5{dTL=fWdcZ(K0v6$)yZtQ>R{Rl(Pp zlHW)^+0e+ZwzCUxcJ2D0juv@JO@bMN5Ij{R6Yy}-?8MC%#^ooo$nD*+cG-{Q*^dUj z1$9lw4fi}d{d^2zRxhh;4(FoDqQh`r(=OHt05l`5A(q_B^Co#w)5hSGC+KthuKzx! zWtXKKTNIW-@6?;8i7?e*O0|7e)WkbN*ROHyRv8C1JTY?IZ-i7ct|Q6Jk&gvSc{QP< zYZhuf6YyCF{C^pGqdMb;&1X`DOfh-6WROK=KT6Nl%jT>UKYbBlRFKTYc#51 zjgd_9x#w$aCR}RBGZGisvLE^8#37esv(X8>@BK=`qG$uioVjufbvD@qhV=^-S$Yh$ zQ(jOZb6`7+E}&hv?Y!iEtn*gCTG=$s!~AL+p0JXsOs+x5%$d z#!eEifD+8>S2|GI)*b-B4S&e-CHY-M>O>`QUT-HJ%tkT+6n2UH`uK+HlRi#51 zPPyc}3d^UdYU@qIONQD04|{JJ6xAF54J)p?OUSaM3dq9Jf*>Ivxv;c!NeT!8iqZlq z2rRIKbg6WAC?Or9gh)w)2oe$!A|XgT*Ae~AJ@?Er^SpTO7x&Enjn3%V-E*#U<)^+h zn9=W&pZ$%#hV?8e&OS>8Uf*05<}WdFuM=1T zR0#(bHnbG!ftrOph5258ia4_tT%MobF29FU=&}7JIl^=dGmO1OrADO+IMrG`my2l0 z?vmaMeMl-L&IrtQ_`0b)zf?U{-mWM8w2#FdML2VSn&TT%UZjqHA;kZX@_x$%t7cws z^Yy_E`%f%g*;lmUEnatSWP`i2DrQup+!KCR2*58c@vov1~%-1U%Y>-k_dKOK3t zhhqpUHeLAAVtt&d{t44%6;=or z=!G1;XsV8Qe1UVHP_nwH!y>P~aFX2}$tA~#+KALpyxKABba+cKD@yGKa|~hzazH7y zeT*_YSrS$L&C)nK`r#h1yE>;l*$z_TqabQmh*FE2zVn#%8@ITU{;qeO5SYdYesGyd z%FydA7dd8|nX1lwJp+7CEQ_~BH;*Y)ltB29oJ*IAMo$0F}dlc(KsTt1w$a?ZC zIRAt^Hy`2sT1I~R1Y8>*Js4YWr^ROUs4c8Rd(U7rUPxCV1qM~jOT5>%9*|4^YII+_ zy`L2pQ=h!|Huw4`N3sGl-7y9iQidWX&+1HZD))?tBmXP2bT)L460gb;DK#+VXxseS z2tx-x_0jY(_bq!rY=%FH+RxVZ$cOW9`n&Oq^J6>C`;`$CPE-qs=z`H9d!M8=15nb} zf|W3NR-|xR_xpToc-E*6i(FRpnfXO-iJ7U}l%aZIgn+Z@YRaK1EjJ9z9W=ua`yYf_ zMx|L8e0B7TC)?rWZpF-058HBsu7B{(@66gs;v61yp(c3MaCN#}ht|79mhr~4`wS<~ z`H3ZM;C~Q&KG3hvF|M72<*m*X{BSexMwYGDq?**7HaPWpIU5?H@`G|{HvhF-F)YSt z(^9u=V3rb!`ZdUXbdKnfyp)H|t*|OOEd8X~{`F;{mDgPizRi#t{N1S`{=3n4PB=!- zyvyM({~&g&en!G~hjK=m>1#DcF6TEahwDIvnfnp>jtrIZ@@pewCDVJeUcTh69+Sv> zbXP3jeZs_ICLFF(SzKODneE#=FR#>^U&AXZ@k~P;PqVF-@D&%x;a8=y!DrEUs{!$0 z#?)b^L0sWG$#?a4QEC!?qQC7FK0VhC_)%NZxt1Wdq-Sf{`^6TQ?0Qutrw+`QVGLJZ z_jWYv?CIJS2hS7EhrZOG!$B+BHzV)|`}_M9QP38WoBef9D)QpGUDHe7D;0D!bSC&q zk=OjM?0z=;$j{5q#y7ItsoJlO<>Xrp&cW+YSS+wHlPB}jg}nLYyoa#AC5OHW_ILdb z6sOw1wM2e=Z2vymAJ%ex^^N6s?tshFr|A6N%_Q;@_{!ltEg?@o-CEyA=ctxVp|MWp zq*_bn;{0B%#7=fhw<&7y?%H}lN>HqDqM0dWyflIR!eqx?|CFo@2PLGc0ZRT7u+Y72 zWYKaI6gb04MCI%s5pY8HcGEudM#Lr9w!^pE1^3Yb!U!W4dJ^^1cuZX|Up~KJh>}6U zg}VAUdrE)0_dW`U08wZB*$ciS;AEK0Mz=yBtbccH6(qWFcLS0*GjmLux#LTd5g%0i zzXjbnQG$e#c)j0WC!MP2*Y!$Zezf-($`Yt}N@()(8F_j_?)vApDrfuAL(TXG^M#GN zGDZp>gYeHCo_QYxn%&#g<**h`qG-cakXxjAf`^!YAW-xu;6zA7msg8G=j#^$jf{%8 zQuoe=)*Q|sCHWAj6j4XrBkPkgxtS#d$It$=)8CuBKDn@8-SXt!ubM`!4`fbnRJbCj z5P+_Aw~OilDo;MJ-@KRxv~M$P(u^0dl<)^!7Y1im<9Fhla^X|;0r4vQ6S?jWU^u)X z{w0-@P<{j1j3f|uNZ`vY-hAU*wR$;-=%TTpSt9K2xYfPwH2d=8o@-4%eeB%%b6U=O z8HQ(U`|ipgW1-eD1znGnZnZ$PrP{CZk$O@%Qp~5V8CZtSlWB&)oLG9*3APu>>(+%o zyL?Kh%I@S;v7h0~n|aQY_uBlvaZ|QCh&CGjB#=zQ%R1@b!q3JQUli>Q3>`UNM$BDUY_^m>*)i z!FWtXb{K_hD-v0nb0ML>wQs1)4+pi{%IT;uF&O9_6BH?}!9^LuJu(SD}nB+@( zTR5K>Bba+ub;q5`g3T&mr457n!)HHl9kfZo@ckj&En8OX|LF)4n23(PkvSXZ=m!Sg ze0@JR>mf0J#jWzlxZ{u6F8aC|py=?>uQ3(Y{YQhlQM_4i8D-?>E^7TTn8woDm2dU* z|Jw&qiY-A{)$8AeHE+=TeLIGM+ww$~tkB!hTbTUkn)L|+3I_qrPkl|@Q%XYP1)cps zRRA&RM-}E|h}*J&(B^xIa7+Eiq;IkUqMA068UxH&f3yu_aS>!nsk=~Pzm#$Y4zA-X zeQJPaVF1_fhUxvk^$VXMjNPaGr=b+PMnJa!*UNffX)8(v54b4FI*`*u28rDhK=9b_ zN=*fS2>bF z6o*Wz*Kf;Y_hF?fAdpbLe6BzdgqXS7;~4^d9Y)O2KmvY}!R3+qzI?)meX;II7~~;Y zhh+bcLCOvJ-I98@rVmrLz^9hjc?3LNEy<5o&r5=MCOi}{G!51Pa)`GH3>J8Zo(F#L zbHJ%G({laGZudGcX*K8#*`qALKQ}l4ip&2Ut(my^l4f{*tae!$6!kaV&Js=vNWGMn zew8aG%TK^fzq7Rz0)EImMCM1uRG3fA_i&ejnv^dnS-RX{Y?t&%og&c+hVRp}b?20q zJWVd*UDxGh+Gytw+a5|E0Pla&hb*CtJ%~#oJB+XYZZ!>ZrS6j&E$TvPgMWCNMAxC4 zKq2q`R--M&5BU?M1>#TB7^Jed3B&n8^vnYT(2Z0|q9M-sWTXujTh_%3Sg=V%OILIR zv1wGHA#aQRgwx6c_AoeRsXpAeBMd(r#E zekJ=p1gA~F-CL(}I(df`rvNnW2JD3w|5()M&I#!50v_mmnB?9e#Qu?hnbA_W^B+0BYoW?jYxZk|6Ih zs>Cb%>@dLo2>r3&ZGLaQNN4~u{7a>u-LJJ?>f@|9?-iLw%#4VZw`$G0!; z7N3^{k%4&q`X$}6RlptpC>=I^^wBk3pj(6m$~_D_Ix_=#ZKgrkBVm%MYZUm==#iZ@ zA3#*)%0h>X$=)lVJ$?5W16`ytN8r3(1;(LsVq1^vz`{2`lukowHl%lJL2g}+vAVlS z{nY6zgu8+JvQWkpk@Fu>xar%3aIl?nn2XhaKOqOD!?AnOPBSKqKOK>+zoeFd*j`7#aR3Jbu~pSsgHeg&n;M zS%lnsBftlf(G=4OO`$WIHg=pc(Qwi@Jy_@dHuAXb>v z`6X{78MX`f3hP96+|Q!%nkle8Xxg4RVp**NeKOql6VT|=jy?g&X#~rhO_W7GAJ=O} zh$MaYyJ>g*EqQp)hh?B}aX)%>AU9z77}G4Di&e$O{2navqCWBhUeo7=RU4}_r{7}0 zz|BDlbdA1R$)?P;^WMDp;B(J|#@}Rn&i)B99Ue(AL&enZ^6p=QUY}0rKD&}^wewl_ zS1UVK)l>QT=Ixt2iOPXGQ77KB`ob7_-Sc#Ka#FlJsjeW;^XYxc1Hnv>?o-(y1(26G z+!d#Ie0{>CBkRnNXyn;n*NI4hKwCTOBjghO0pc3INxg*}BK|DE2jbg=CE=kuN+BXw zqiXr^?b(CJmiyO=6_99i?lVFiAyDc>DHz08`7K2mcB$RhnHmLAREm7 zmD4?Rt!L_ZMe>MG7UqpDmlT5 zN{(dc++$>GJK_^htB$#jmBc3Tjr@Lf@nXr{4t4pS99eP+m+rNI0p6LP1DOpf?}=G3 z8au$U+XZLuF%k-szWF=jd()Da*N4d}I|=`U{MN!NJ~WgIRTNJB+(cbhy!a(xb><=l z*}#$&k~5IDgyv2@=l35)bZ5h^`IB7zEe!fn;3VB^{p&+g#SDBRK=c*xP@A~~?llO#yXu(LHf z2;u;?8DgjnRZgs(gZTj+l=y{;cUVS}hFMw?b3u0$U;s-tZ~ze8%@v;wjv zA4u;rr(Lx;hsM$!;`^yS07ElvJIR3hahGha^+%RmJ&g`HEEtjerv<2JRg!y$U8Sm% zg%>UHN`Zct-u4kvONdO~2f05Puago=ye}d-6#2s5^Ah|>&30-SJB+=ClDieLaXx?^{iI^`*JU&b18_WG~+^gT0z`CAw z-5iIA!8}z!V2RU2@rIk+vxiL%@`Pq*yaTGmu3ZAy_1?-nRy1YYPvm2~FQhi3@kuy?{_BX!~y1j%Gv5@7*^X~b977k62N(^es?5BNaZG+$`j#jiB&Y1cwiD|ZpVNa_}dgU z*6-cM6d|DF&fqhLzd*+rT>ZMe9@Qn;#a@=!Wq*`pZ!Y{fT&Pn`uppiu$B|aY_sgm7cGGwB&5T$ zI&K3}7qF2OLw(8_DB{9Qc_#ujKuOtb){u9O zU6EqQFaGQ#V?Fqt^E*Bg)8?P3TOy&9YIz@$<_v=W%qlyUmw@ z^lJj_x7l29VAqhRsJ}>)vR7vGt!M1iR*ti$eHU4@>H8srncW|_d4O?v zkC1GoUP-kw`?~ZPOvkXLCizb)Sqf(I^rBXUO+*$q5!{9XNS(K3HUh5zo=$uyC?EWbo-V;uf!k zi_`M6Y%=0lIWC%w_VqP5GkqT^3C#aKzt3HpaF!5?Bo07b|5{yTDb?;b8^eu2VL}4< zGvX$YC%JmhA1Uu-uJ#jM7_6OyBu84VOLN7=D85NSYFpi3rm_$Tc_L81^jdmG52Mu-ZjQ6QPKkNt_^=QRV1mYX%el5;kY_V)7dHdtTtWui8cY#U9#}v5BigS0(ejAdW z{+eI~gDa2TuGbx_1M9X}z$)<%7dCNQkqggT`g$A7}(W?h3KEg9suh zf)3lPm3$tXBw__ebF<2`?Q-ul|N6#ZAH}LIl0~R~e=7f96DqcT;M9Pd;%&2fxnL4u zX9LN1SVW!vjN{m?2z)|%pk}OBwq-HJIdWjy6SZJxG<2WWpaPpspRu`M(Dk^8UVF0r z>4NFhpdVU%*W-qR>~xmvW(6q}#SNa3dZBGHim6;anATgrq6JR9r9Bm&k%Wjv7ZN=n z34O9*FqI{Z8UeHR{je$D9QYQ6Dc|<)b<-30-Au};_1jZce%=ZTP0M)iT0ntj*fjNh zfR4?o1}fgj8^5mS%&O{wWp;-+o!pe)y}tK>n!wjg%=@?AKRD8EZL%2L8le>SU+_8M zH{zq|_3Nmo{aG7HM;IbQh7>)E;6GbJEsp11ZoQWMDH9}XcXAc9iV?)f#n+{~7JWx> z9K%qE@f!I9Jf|G3xZ!#OQzl7dXd?@OLh@Zt50GJT6f(s*zR>1!4~)3{yk?eDM%vPJ z9fMXUop~E#ov-z$k1nW-MZ(KSBZC_pIw__dL*vV|0r7rV^k>D${5YFs&L~pE>2W@G z3DPKw{)mP#C7s{9-L_JV3yFPUZ71ZfPa+5` z?oT5W=AlHGL_$m_*g8@9BS@`ah+>%tY3W7D{yn3lUlL*Z?@3^3L_KtMN+M|pAJ`gI zYb? zV|q#<9H7{1vc7;;4Z^=sxm+g4G(jk1NkE?g368ybqt!(q64ICWz>Rw_;1|!El82jdb!j$wY0>tDZQ%n^zHBodz$#CT%ZAPo#Qfk$v5{1P zOWzsw=6KiGGyA2pTsK>-M3U4q$zJ#6vZj;iy)xYOs+ZJ?3zHAX;ueR&2F)60?+!V)b52(h_D4&AmZe zDZjIpI=Myf+v*uO-*9?Ix{Z}saDD65%us$H)}}qg!Rg#{)%6U6bJ78@A%j=) zNbTW}AwrErU)6JE!t({SaZ!ZeQ|ZqEiK1K=`4-(A?}1VGKEP}5Vl9Q*LhDG89x9=p zqM?eC?MGf%f%g_V*#QeTdT`)9Jb19Lw-%`nOgPby@8|HjVzs*`D_`-^{Ynm>$MAuJ z!*pbH&zNK8ATUPh+!2oAo`5U(j=of6LUG*3C%KR%CDLKYc*t{{m+aV60Ya!`za#A$E^>E(rU3*rS zvp^=Qn96(-^(6`u&(b97qe79*EM1_IO72th1yn#Vc0wh*0L&@A_}qVcF)MJB9rfTQ z>BFvCDgC+0BK&IVKf6o<2a#)IBY=?yHshANWRvWE#ueBVJ*VKX^wz1C1>57;NBVio zc}luAH}#2l*fp$JzCR9qhE^Fi*>T|D)K>+W265^IZ~uk*rxG3C30G5_>PS@ujxf_>$4_Na|FV{yE6fzSg2Ak_x# zQ$r>S`6y9=Iv0IpzK1W~H{JPZG%j6xL5pyn=H_^;^eIHwZ5Ht#t)q-r7Y8tP7RA*- z2IKRgiT5vB{t5z^a*)wmPEPAj;9aeU3xh77d)7+XG|<)tx9#3Lh}*3 z@2;FEz45Il$g@?@foH_(81$AdhAj!tQdu~eD23IM`iOlG|M~ zD7ur7*p4D~i{>A6Erg*#LXR7;uj$;0YTTxX?M8)U03b{uDfX6$1muA ze4Vyl?mF%O}E$7f2o7A#|(Jb5*jj#kxLl;XBHy^*NyRo zgr#vFU-#k_b|nWUFAbT+U^eys|4d+HkXbAu=+(=jzh<%Exn(Ad208Q~o(rSF|E{x# z%whpIT}W^IHH*bi+exwV5kbOI7U^Z4f4$lU4o)NisxhDMoj%6u^)8#8MT4;n9%M+i zNAJJuPJ!!$yV5Ofh>x$!F4XwV=|h2p{E8q+vDO}PNgTWCtFYeq813R&t8 z!(dav2tCMF?`!IR*Ns7bMY7imbT6>S*Ku+Wcq!k4{b6{X4jKLDLqr0qo$NVB?I`iF ziK57$;T)D|3wn^kz~rL;t~&#+gSdHMaQx$Iym2#aTbqc52_i>`$|te^x>f+xwc6!I zKmJb_{6EnJOC*ZAmPoCVw@KR~|Gpb82&u<^=tLz@9QVcZJQuITN!P-=Dkz3-JsUn? z{=_>L_8&v01OY-Sc5A>ym)tr%#*PS$1v9_F5A`R`|IPiNGZiJO{#i93cB)AlRxWj> zWgds3BS7Puk^dAAEjTz_hgj80XJLlef8)##y#4d|7sHB>`vkJT`W4ZZL`if1xzOn< zL(IPmPl2004}VFk1TsSYT=@U%H|l;54-|WtP}O4srrom_bb>+v?IQgOaJFc$5M6$o z3E-{gWd;iWI;}Xg^ncA$@+iEhAWC=Kip@hI`bw#>(10-#eSS{)-?ctqq>|!4hG6)R z#~1p}kJ%$_+W5MNPQd0U7vblHy4a3;fRn{l5@P$Ai1|Ybo?>U@Sre z(*Jzn|Fq%%bQ@^m0=D-5DA@lQDgXQAV1q~g)VM?cbNf<=5QcB@c&Eko#A-|m5&FkV z4X1d-{cmz&OO$58Cm`|iwFj;E(lY6}U(ZD>!%=a=V7__rC10fkz%Q89xUjlYKb z3pC+36jOQrOpsT-!({)>q|d>8_gqxgC_?(?@fu*IPxynSgUuUh_7M7Cj=M$_m_n5_ z^rEHzMhw^)hzp~ADxp2fy$}1M=lNvc zDxVVA%&^Mbyg?*%y#LKJ|1pAxjbWi(8PCse|4SV;u+4ieP<|Q_!}>>HqwVHzpiXoi z`sJ=$b`0tNmNQmxUW|cR2_Xjl#z+Lbv!q1XkU;y;%C3}|e;eRi^PodoclXl#Pb2=n zHe$t5+oZ=+70uiBzu?To!4}d~&fTLzk_#7*&fT_TjkWWMe1#`Z%@^M77M%$`N$o60 z#qVQ5)O?wV4SBe0x8k@u@%&NkBhPuahxKzar@D0XQ#=c@vwN=PsL3#$Bx=~Z1m{Pn zGQM~!Z3_QYgPgb8UpNb6I&l&%eS)ZhQksyLgyxZEx_r{?fE=GtDuDMyu0MTRLXvh? zR)rRQd>JwqJN1&gxb#Q3g!SihQWMsDzrT>71M-M`-czg(9!V2yC+KI?kctu~&1hQ& z$Vtywzi0x*(Jb^$Tw@{De|tLc(ipvS7o=}VU;x(FN|26}lmFn7_kJ1At9E8L02_{i zf{?nj&oVEKK9~eT^r49yuK)MKf0FPCI(4tRbE(;p*zvHfr5gLRuSteja$lT{m zF)7}aX+OIxz4zDsKGrQ}SAOt5x?4hPm?Y+E_tCz58E_Y`p zKPjsH;o8uQM^HlHvabQn*4Hih`@7heXY=TYb3~SV+Z9*T#qw;rLi`&KW;)o5KAgEY zaE}SA`Vnr+)CPOJC55zb63<(_085ANIJ7fp4+)o@0@V}4fkx-(6`)o-fb-nzB~TfK z#6P3sZ^3!jffnQyn*}is@K3itFAu0BMsQRBEyWm!z_PzvSQY@)imaUSC87BZ>I_JY zA=ndd=~Gpnz1+CJ0kjt-qadSEfB0~ypu|IQbCe>uH zu{dd49o0Nm6VIJWQ4*uLn$0EZacO+Q$ikc6Q^zgMsCvH!?o$eT4CtzjG)7npN+TvP z-OT!hEgJ}K-YL}1QTxby0Q5XbA{iXW!MqC97lIvQRSzDlj8%ku)~Rm|0%ovo(Jk*Q zv!;M1XTJxErWM)DfSbPq0!&jRKqzbFpq|mYRfPnSyNk=ML6k+#-@483M|X(9`JdAZ zhpIi5_RvwKl*wjl6#;*A$??GXHG?$2{Ot*nAD#Ayee|Glah0DbLeK}4j2!9~{YGC4 zT+}8ysufNHnhMp%oFM<8{zGi~hBI2f8NB`b>NMD|Tgh_t_IJhVrcT5JQwDR50%luP z)CS`+0sKL1{PJJB0fanNiTlX+mh{Gbo=DkUyEEjB_deISI`?tjNpzHV!{2DHG zSn74Kck}4*z<#9ET=@6**W(}$!TQPGW*MlkTA=$F%G-Fd-h5X0c000aF3Yelt_b|o zKsn6{V29t?jg7fZ`_tC6GY|F+W$Egh3<3p@>PrwW@KP|R=Boz?QyT>#8V^7;K`l>d z6Hz5Fj9m{v73j18AoR)h^IFr1I1{&CQ3l&fF$E5+~#H(}>G+K5%80gSM zjjUpIC-e%Y-v-ti^Mb;eDV)2RhlP5e5CdgAxiwHUIj3t5Fq`ABK29GvIu(~=Q@WhSQfJVyx<2y!)3s#{*ch$8+zT&sCxZUc4#{j=3RCaZc<&!ALxv3ip^} zV`?EI+>Js=CXz2B7bW^G*h>?Er^D5A>QP%iDs}E?SL)V%KWdBY;&7V$s9wx|9axiicfvL( z7R!r4JV@U&6Ahwi4T}iov5NiI|Fi(1BQL02(HM6{hL>d%_^!>Q(zEnJ6fY8l)9_^EUh41`o)dkIRr+5dP)`*7S5G$EVK-5_SY znulwqbvijC9IxclgEn$i0VWK(toYoS4=bju@x@|28XCw z-`4|q4L6v0@V&oZ6^S2pfoXY>S!{Mwztb<{;%6XXxn47LCCL7F4 z*H*3OVm0vr%!cL9vdcjUBH^$=JX;V2Dh<=C7!$RwVTi%zCEwEx;%en+ng9Ioi+#T} zm2j|le_ihr6-tV`p;Y{tEAo!uB_AoKM)PIct7Wkwn=z?i-f#(J&Y&92NR*J-T`DN~ z4%*)p5hD}^rd!F1fsZUcPe|BnS1y%V3Q)_L+uwX)^?~Q5Nf45ff^D##d8**Z2RSn+ znDZKG^Bfx4KcSJ`JA}mLE7B3P%ai0=-nK`w++e@VsU>gZ7{iinOsEFyls%ZiY@IIR z!lBB_IJA5u1t6pfZI`uGIv#&`hhWXp-3(<`Eg#IQ;}BD*mM>4j?P_yTCy}x?TgRKY zIeyi&)okqs$?l(Kg|@W6$}xe5maSGPf0k3HXdKm!`C%3P>M@y}(f3vjY?#O*CiM+g zbyssnbA%&23{Qt(MX7d%i~$po0zq?g0JQiWNRsvXvBc7H^Vv)HP=zs<6eIajnSy6A zO}3^spY=^&^!p+yziEFE@?hqZl_8whSkM>&M5XTq}DjMe$$r7y5`?ePKsTc?e)k5>AD6}~v?W&O(6I^4-+R0ND6U9zwwh`3e z*sE=zpA{|3){3NKMdQZJ%5P*>q|;vxK1Xr=SyH7zk$(HT)P2@D+!K8>5L91kr8piF z!*r85G?+PPARBfbLFwpEH%I7;OHY+EXE9f+zNzdy5VMU7@)&fZN6U{_mOm-T>Mw8@ z`v7(*tNC?+1m@+E_l-}l(kZuBsXRR%%Z1=)ArZ9+&U*YY{C72Xb@Ax8a(`E`r7?rT zFIq1V#V6Am)(jWTn#73X1H9wo_zJe^r}ii|cGFD1Jal}s@H(x0@epek0@ zI?fjvjHC=l>+i~(K(l4d&|fybLDP5Po)x80YYffKO#Na-AD1+)L7Y$DPoP=|s<^Jl-+c;e3vcvZ&K-)E1aHjwK9-=7{16ZS16-hZ7a2Gn7q)vY_(7 zIC3KgseYt;482&;?^dIb2-b^|&d|<|sk`YL#%u+e&yOUX=`<0Npms|hM@1ufSDl)7 za9e{I#?%{g0;{Tg2L}E)d*-#15@?Y4x5_yeRHd<@QOR661hp;A+g+*xLgWtdd}(6J zMBMBK9HYJRBX!5hlSFO3DPyTJzC`w#;t-*_8Z}-1vTa{%Ce}VTA6InTK2` zp7oi!1|~U|>;RmEQ0AET3p#l>KBzs2baw^i%SYn;6RA7NTtNAX@rAyO&z#CxmZ=1` zAEQ8pp2*>c{4|C08=rg8ROoO2{3TT-BbOx|R<$_rMfW?*QzRv&as3rpLf$p=vA`xX z7}6qv44Iqs6i-KuQ|CAeYNfH~j?zFmT$nSICPPXS)MuA$D$|7b#*C=bV5w&`TRYWLH zYc*b(iaIZyrPRuAqe5{45ez#MbZRV_rB4})i(p|xI^ND$%_~yo3ZB(4rDG^76c^$G zyM|m75GeLB3iSnO-d1mO@RO;%3Vu;oCC)6r6Vf8D6kAfW#C0w1U~h|?7`^n6>Go-? zYQ$50BZ5o5mPVNPhGH!^FHCeO`XDpf>F3=0`sT(OsObevJgGb*x(p~pQPwf-H`#BV z#(hoRXm1aTR+p>>7=ipcl0y6Um^6tOMM6bs(u3}nJC)k#SCNFrjqj5ucDDs;{FDap+6gUK6SMdw=jNW5#BHv88%qju;UqIL$}U-38lp*t}YtXIr^roO7z zx>vrh0a>ZDtWsTHHpaW+OlQP3_+YxmbL>z``!Lh=@XqP$vZGqUhl6yq-&#_(UUn7e z-3z*U)-@&AzKZXh<~`e%(#(&iNg5yLD@sTHy$FwTOXzIv2yoh2J!wAA2`xPlU z6~>awYx18uL+Y@`9VOdck!XdJmZPw^t8e}lLn`rqvw?RnA`8fbyCj5c(vj8{rJmz9(P-3fRx^CNB;|N-8z=` zd4~2ABD8!T24#$4%x%Ea1|j#VD)~8wl^n29%-74q7F~aQ((LkF0aX>8TEe3S86QqK zvdPG9bD(fXl0aXd?{!L%4$9doj6zcSKZ`mWl5}r)`?CFY?O8R4^77VK(gaNgdq7RF zrm5s`DYae@w27cJ#^}V(|L&vLHl+_TKn>|A{FK+!M|rv!Mg@n7>d%HGaCyoe1dtI1-2R}&)DZ;b~cuM0#Duk$} zKi$b{kYP756kYYjYrKNR2gi)ZpNX~8WOnMB>*fB6-O(d5PkNJKLzV=m%35$?vX71; z0|k7dYfbHy=rz4riQCnZ2vk&#niv9e2nN1*A?U)ZdSlqqm&V5H`MU=@Umjv3D`z=g zC}0UrWuXk$hk^tc#9VT35+a{~?SLmv$&oc*(I%>t6|Fd4vA4Yf>Ix4O-_wCbq3Bfv zwJ{MeYJ@B*t&{Q!cTa@7qKlS=b&%fJ5-UYkc{>Fad5{@u2lJjoS!pMVjy47q*!uKQ zb~KNWzM-9$9xCdJju0Yp3@ceRRHQGStxM83tH1d$h|n=c+B7K-?KP(cGUdCkuAcUZ zp#%Vd>Tc<+G+2xI>aH=#d&S8z@>fUSc^3y(?{+ZJ~i$7^L z=1qVkyM`Knn{}>84{3pI$$Sxij5^dMuDVF{6|C2@i#n9-r8g!vVzY4&*8|YCtzbyU|lil z|2B#I74kIQJb-2cbD%j=sjvH#GZ8xvOTbFzm!3wmUFKZc{d?YP8&yj|YxqOELP{bc ztIb!*z>YvZC^}K%3Aj8BAVPS-X z+;e|`HgMlz@EG~GE{mVX-LBA69NDFL1MuTUW;~of=vHQA;_;cGV-cTige1s9qu?BO zvCqHXyaansvmtncL#~kn@gUx`{xVVxX|ciIu*v-SxS{(cu9Tf4B4Y)IjS-FZ3DUpM z=%WJwKBcYo*%py^hBu-^k_RRce{jCBZ|4B$cMW z2wjA}(~j*aQdC9f12XjDMf|9h$Vphz%K)6>;zF7;@6TlQ!751SqCqD2=&r=@7s&$f7qrucoaM< zP69rl_UFB1Z&%BbAlu2H_cB4s#PF|iQ?0=-3$bLLgyWC*+?1Zd8Wcpk?4T_Zjv})H z|8^HRo)s)saa3DO8rP4((*LayF*`7~FHasqRw3?fX8?Irf|5ofZlhMT*MZfq(6TM8 z`dj2T5Pj0GG*tD#>^C?(PrT7$IsrgbfS}UfU4{MmTDo~j7?TDjq80mVMwWb3pVs)+ z>y@&=k7a8O#Vep>G4?zWQt_!YQ!8{r7H*?=rZP&rY8CwCU~70AaNJ{88uu-r`f(EA zOoW(-WE%^HhFs*g1|**>!JI}KgkeXmODPxK*!yX81qJ8dVpgd|wlnz{(zG~+i(8l_ zc{kjk6Kogbt;yvPc4ERY9AIc3?q7%CN8?5hTx_UR?H5?s2dIS(w z`<04ewar7pAra7=&n!PCF=?nV*(&hbs4rgyTTC0}RGOm<)Q3!|#;pri@ClxgA028T zV+xc<>ntI%*(+-g+)xFN9?Xh=*CeDup2>oM&%>YL_is6ZJ3Dn|U;U}aQXX^jE^p(+ zyvWoEJl#AM48_*_0+}(+0E%C@0aw{5C@^DvmeKuI3yseG`x~V^n2-sP>#i#-qO->|d}gxr%KXArOs zT>)7yxaIhp*5@HikaGDWz(DV)OYUYuTl7kRsnU#t{0vgZ8)Uef@HVL*_$RKD9>NWL z$yr%5z9eH;SrlsGU%f&O!JdVnd!>oY@d*I#8+B}BxC81jRWblcD{i^`Fd3km+btwl zM%r8MxHPxi(Ixt29>_2xw*Z07-@$*B*RIxlC>QP#TQ018f8p*3sO(@3-}FpRu7>Qa_tf5D631! zPMw^>Z%GBHmJh!i9i)5)K%6ju*zcq)JzVH*26h5|_N&nAxiR(xxIHHh0!YtWP_n6( zf{JtP1Mg3s=6_>Mr&SA#ZWUyV;v*H+pi<<`6v-zLFnCTVI9O2Y033+BH=k64|2Rqq=z#Q!RB0p{5TaMO$ zpQ3$t1efIkuO;Ep`#e7+WuReL2>{ZKCS>j6c}-NwKXL(cYq;y$q(r1CcfWk_4mg$C z1Li@u?1sd|k|d~)5(1?K22F&>r&GdTBf~C<^x~RAy}y?QUrX4DQYjp7K3ls3UXeWe zJ8GoOMd%foJp4R(zwyBBq6R^4`EzZRfDXcJ*yw@8MG4Px&c-g_k(}A+u(=UOw_z~- zQ+%cTQ_W*FfEkrRhri0%C>61j@~$B7S7>>t=p{seK(H>YKOJl2!LOO{B==NTFj&p5 zG~{e=nWS$3tDtC~tm{?|>|zl5LBnn~rHiT8uGLErTx((y!~r&Xfs{HJEhz3UoA45Z z|BgPnqC^-0AUODM>Q~--i#b&QD13pUk!H=?c{TR23zAt46@Yx$>4=svL}` zAp{mxiE&x{@>Lt07KS9tKNijvBik8$GE>Zu7KX{Eeq9><9g4Aaq&s5iJcv5nm#=;p zQv+}x8xM_#JrX-EjXFy*Z@iBVg#k#pQ}7iyFcTHm3K0B3f@&;6ls2~L#Pu!#wWsHI zz8vY*_qd#HyFJtAZ^Ab7&(3`H(mtDSw zRwA*CIqbxd_dwOZFG&?35jb!KfZe<==0HDiW#>5^$qQMCjmuRuFoMQf$eXMI?E$ID zllpQWAi_sqSILi@7ha}s?C75az&Tzbd7M$^=8IP13Ti6cDu=H^pYT|4M*3O`I1dgX zC{Tu&-U7uD&F+^;Zetw?Aub4*{Oo;npjN1X4-fXbIr!z#=E5}o5;g9F;w)4&EOFtI z+*Ix*)JqIq9vMPxFgV?L_VR+)*SxE?{TL$vQYS@V_^tY|UWFV_pzO-;Aji4_#9p;@ zbIZ}4xocfouet-rCt&t8DxB+1f)b_Zh|QlQSk(`dq(^Vp$eF;-xh=)N)bSMMJ@S5r zt%!oa8xo~l^!qi-#VV~4mEiDbDc!g|#NsW(d`qieG0Wcp+f1=nGsU!TfSfnv{z;{# z^5S)=D-(y3x0g|^)S4{Q8q83vL2RM6GTsyvOnO%&V>nK2lFlPBcelC{ZCkML<#792 z{KU?4->G~X3fy1}V|0;c3bmXb?%hIpHaKUv1mS(RSH@}kK%M9w-X*!atAJ5hY$e9k zF4W46Kl62!q1^`nZE^9CHEtQeouQTTvG-#K9|?REj4lFctoK6-f?@3T75xuGD#cFY zq&OBfIdF@)3urUusC2`5AeLwQBscC0P~gk##+)_TTD#!e>;Y}#!W_308waYm4FJ4Z zd0TF=0LFy-p~%Pe(T`=E+A-tz8LVp2llI?t{0?Q9l!%n18kt&kE-~zfWA5A+9>)@t z7T=U1h40_mEXZZli9IFlt?yp$HL3&PZH;YZT;o$NoqaG^T^r#`AU1V{_<{Z#PYtjN z2wc2&-#D7hcec(`WXR7u>vsKK)=pYWWP9f+zB&g~_+dRT+P#UE*^DqS?2!TaE48S}#dIy9gPuw@2?>f+)j_XRon5}qpUcgAs4iizh8xXm%XKr4V8=ANPmn$6}Z;JXzefd zZ(khz43J+F)EcNPSQZpv!sEndW27{>R=Xxy6{{F27EGnt`i%KOXGrCFrC-DKvHEOC z3+1X=*svnZ5O6EO*wAzrD)WpLt>B56kHIhc8dX9XLI#pibn&!LsyGZ4>`#C3m~-{D zN!(abo7-{;FMTq&la}r#sJ6Gtb7jx#Q#kr$py6+gDkY`2$aeJctdXyd+7GAqddlpE zK(jHI%In@i-=ng1o}S#pT^$L=_yBacsvNMxecPZ+A^W`;S_#D^ed(1g{YZF*nN)1K zW}}1hx`s$q=kDno)5b8a;iq0F2l@*3SoL-a*jiN+Mf%hvwsdH>i_%LSD+~a`{;^^0~cOtsTwA8n>0DmQ|IKyY!2jlS(AhPN#n|a)`)FQ30&R zDjDm3ka#+fYXFrR3LnBK1}Z$MAzeGQxPfnFPz(l+Z) zjNk{UlDyW!3m-B~AMO;cd%#VP$|7X#UbOrc;O>ciQ>D`w+tbnM|4j{_uvBp6P$9(Z zhG|_8GP>VfZ7k9fT`1lQXt)Nz(s`|hU>lnj(~NNBuR6I?54K~y%19>l;T0ROg?Q;F zH#zSalYdh#b(b-(RYsoIw!f<-gqCkKXUpA!m&j%ndz|97im@#Z8;LSmrr0ixbZ)*SWW}{4vR&VB?gBkCB7o z{eE2uz9;nenxgm4uG^8%^N2sK+SZ`$;M{25Ra!qO&h^`FD??0lkgpqn`&yP-S zUQeu1fGOv`1oC{R)GHZ$(9m_^jDQ>t^?wqmQ~cE70$k3V{#5p zmqe3kuQ7*H8U|%1@6%dk9I=*ijLB)T&*3~wsdV!e&Ij#k`X{7H;3hek6^Wu&i?ky* zP0(jhIfA@z1IS3m57@S1PPqG#3EQ}#bUiFBs47dwyfTHfr1YRViXXqD#-V)&M=O5i z?NrOdOJJw1NbVC$a+my2VeUuMkz$Xyy^0FbVl2vwWJjK0+ttKjY)oD}*QU#zF4qCm z#k9gYkXsMtNP16YR-RG1+;=553zx&Z7_W@WUeMQ$<-mq|eT-EuhF?sY&0JB-vKq+M zT%}c(Fy^ko&=R^hEp-j)E)eo}z(1g1c35A-=bG`9pZP zo=ZsUBLw|ka@2_|9>cv!j__BJ4jC&-!P3t`#RV?46DBzmSI6?VfRX=NUIt~(W(|zX z{wTO#pOyI>>U8`(fr8wgQcqA7NdbnB*{c=d`b!pl_^|QXm+0KweQi;@M*^)q4GnHE3pMv%>(s#|K zRKZcTU!AEC`LhRm`(^80T;M{k4fWiOzP#(5Raxy}sfr>I5k-3_X{yiZt__brL{@Th z_RDIDh`p-b9LVhFQP`903z8b+%5>FR%iD)EBhbN1t&rn0Tb9s%s6e-auQGC!P7lE7 z!S7=dGR<^r0VVlezf?&1%UQ7@LxdZ(1ZT6Hlo%|B<%tF|UEk1_mA!kR%|8xRvs|kY zOdA;B^0+FB9YFw0B2{2Fr8= zn;6P$iBqCx#pUdWpEx`#fM$9MCX8wT7aaK@qBfRJ>a^f?OZ>;2GE48VE|Z0k#_9sx zC+zxHvCbbupe04mIuT<^byQMwOYM`0UV-D-n?UbaX+obc8$+z2>1^V{^zcJ;_7n43 zAAEuvzwFksltA?N8+@dvO!`qy5r?eya zO18^Qly~%DVNM}=4e4%Fk?D#kXb?H&azx?4TH6rQ#QguX_ufHKM#;OdjH3>sG9(ES zh8z?mC<=%SIS5D+l?);hRicO@4mnBAf+9(RfJz2I1QbwIGDs8^6%bHz=IfVX-2LtD z{i<%&z5m?W-CE1V;hl5NdrqJ3r=Nb>5KMsMG?LU>$)rw}%+O7urQ+ws58qsQB)fi; zE?eOJsgfMs$l@-w=AU#TTx3eab}Jig;se>9UE&uVweK)L)BligV{iYd*P0gLX%1@9 z2Ls0Hf1^y#7c1s`+x%j4F4lyyR4lgV+SvT_MWfYMo7{_qWAjnBwv4@>-9T3U^NlL6 zs`&de!LuGAp@&3xE-z*Wd6tNT)^B_)jWRQGctU;Iv|P2PF3$aOu#o>gi({K)~v1Sjz_5s6F=_p})l2M9aGIHO@_}#cWd2b!B+x z)#m#9rSW63S+}rLn?HQi-&1yWu_hV1r-rTUcrYh#toWEu^#^bBp5G@a`?`{ocb~dj z6)=*msadk(_=Zb$LGYwZ3Wc(Iz^9}PBVp>Nv4&?Jv$?ikDbkv|!P51_cP#jNTigTS zo4h9<6r(*|FWaV_)>oQSqDS6MXPli)rPz%0vMw;dHK=6wwDlMS%xmR${G=tzVK!Hb z5N7UVCvgEx3}Ob1wMB!~Iv02p!+%!E2N8TQbY0;b5UjKQNsz0AM zu$#NT8i`sD@{`NFHO-n9CSNoUMst%dQ-{sn@MN<+oRAh6Y^U_-5%^EibZzP4u_4Na zsnF^n``Wnj@|ZS6$LcaUJIRL0KYMk0?S?-dI_gg$M<&vO{mFE#HCv^oQoDTmor-;| zz3-+40t{Sl0Q9ujnv>=r-*?)ji9H}8O3T2EUq0Za zR$NIvHm29Zh6GQl9)45)!gHkO=jh%8zBHHA)Y=~oGh{iE!|Bak&dOOYCVl9nYs!pX00VlJRP?Yg6%Ry@z_ zJ&pzh-Byc;qjTwk*!$`-s(op+@|B z)&MvYckw=$Ei`7fr*_0^$A8UTs`UEVA!5lSN?U*wWXO;R>V~*(Lx`T%| zX}ua5btacD;NH}s;zC_Xm${rMo!yWKSYzfZ{L~H$e%;`0j~^!SkKZM;yx5to1^;vF zO)LqU#p9TXk;TTBFyNBV0A{opI`ZU`RN#%ly+E2uII)20A}fg z`c}-fpD}g`e*3LCT4VXL3+>qNk@~^0Ly{$Os&1|sHaFXX=z^URPdcXcf62&>x0MSm zIM>?kLwWkAW)6dhg)fZloO-$ z+VV1c=-JT2Brde$FGcMEb>J5-U)dOl3tObWcFG0@$=|cXMd+d&56U^5Td9nY zw;H%hrYIn*r>=jnF8KiOpf@R{u$wpti+!kgcX?dcW*c?#7B&k|gGXehF~$<=Zz&!{ zEeqrnMy>AF7MYZ~;YO?Tfaa7Br(ZK^**ineWiYZnJm<;nmrU-dO7n5rLmI zwF{v|Rd7LmT8+ksbFRe?Rp<8;_HZ;r#|KwL-aqtIU6JM46(~$b z%BLjLAQqBYMB<^aOCb+Rb%`x=H%u@;$63%Q6svpmc`*fHA42PG`K)EWy(l|St{f4? zoB>$f$Aq*`M#LF5zn;^mp@9xq`3UKC0R*}F0aUR8zHSIWpMxHAKg|!>KP5PTg2chw zIWa@)K!$vdAR%GW3m2ec@cRKnz`$P`UpV=}9omOK=L|n3dh?QvhzPP4L1Y>1q=b#= z*&XazHS&BfzYN`)E_vm%M@mNiPUDfHmM?3eKpg1tSe$YIIJuyZs`vpDF{P7}=shL^ zHiPw9h)`t{(A>(>v{&SkB+uQ~+&F*mq9v6SAhZqua9p!+H}FdUVZQz>^+XG3Rbx~7PL3jMG>0w+M{u(y>iV;1Sk;idE@?ymrl z7QYWC8|k3!2KaVgafhbiu^Q;^ZQm<=3pjelQm^*pw^bVh1~!T04?umZPjD&b?N&CE zlC*d5IPhC_A6EPZwWD5GvPp$_U?jianBLs@7$mq7>C&E|icoi}fUhv zc3_aDLW%%qgYV9Xf8Xrto=VGr`xPPl#W*7;)v7PShm+P44h?8;_^s_*J_G=K{HzAw z@;13_`X)=x4bRnul14VK0l_dp@?ArEc2kUjdh+Kq3vV5M4xT6~5rIwEZQai1zO*IIudT^QD4*WPKK706bho#2i+TB%Y;JaCeVZ&PPz2%rV@zGCy$zf;Fp<6Kf#o z^9weC8v}(^n2pASuu7Z zHOM8D_9R~^-pDCPx5ag{;>Ux2kA+`0kV>%=dDWxJn_}s+d%tZr{ikEVpy;Nz-EFw| zZzmC6F56SM+*0?mNOpo^o|F`%s`7>`fAu~q7-|vw_^VVnHvYWH&DX5Aeu?~$x(&Sa ztYlHOnLIvEV_gG;OFjW4g4K}=&3BKMe@5M42ui!^vZEQEG%=$x1bHCwkEdpjRmD^9 zWpnE_*DQ|Q6b5153dxxi5b8XryVpPb^h%SY>$oLSJ2BBOkoTnhNeV!qpO%k&l-YcN zWEb3Ev-Ss4aSntJ1E1F2^X`?5b6Z*7Q1w=i`#H=)&wmbPXmnu(95TWjjP;B{(Nn$ zVv9M~8P<1LkbvbJ0sf%?W}WZIa8~EgO2pY4d0Q1RV-Mo@7iqQ$_82+e6D)3(6B5xM zpjHgzAKdFY*QQ)$X>4FN>@guoADjO57i}gdfe)a=^rI>ck0c@6Gmw@y0~@oinfKwZ zKBO}$bHVBo(>LfNuLz8P zao%7)Z&R74YDN+On-7Lp&3=@5IS5%jMFKC@f_5^kUK!C{<*5tcn5E-Rmsdf0Ir5an zJ>?)%k_#WwWpUu`gX)C=Y1fugCtEeGwu#{O$leULSnf`~N*NeEr&OHbRS8{}h+mH` z{1J|Cr}3~GiJJRScF@qE@*sPbiKSTg)l{uQ=y%2=!hIEiR8;j$P&G;FlD5kWUulH7NU_AJsOzb>g@Ep*+OUadVmpCaCGr;{iw~tCn zj6t@~NhVc5Afs3%ip8aw~D<3kY(9Qq}}&~T=Orezi}~)qYWx_f+JV8I^l9LNM@8U?^memv`%q#;G=z~OMwS70> zM*b4^NuM?}*r~s1$X4QbtdQ)Yj&IE!^{JuiswyF@#a#LyFoh;wwTzWMTmFYXkBzj( ze&0wX2aWc)G{8gK{g&Vwx=mM=_4;D&0?46K(zB#fW0Y3POpYGa${!z7T3}1b&X`o5A=6XioR7VJJ}sC-BZl(1&N5_ijAx88d9{*IfUjs5 zho=2G9GmLk5LpR*Q;q3H^E*p3$Z2?v1${W*unrin9avM%uG`U2!ByPq&!Tc)~Yj-8LcFhLD-cVm-*&E?CqY%oNrVHDtMx z&lXl6)1IA(4~!g6qlprr3&K+y>v6s1ODxp1(mC+1owJy3G_51C?z<@eJp_Xv{nAM} z9P<*h#Vh&Ee;rf+bSNSY#z8yHe%b@QI&B-8EL4x30HCK!H-G{fYERT3<$nLVgHSk^ z@uh1Ps2VM4A!4UK1spb*>}lEzfu%+qNESe_?@7^;$2or6o&%gy~=165_FC#Z1(v zucvg5DM-HYh*UiI3>bwqueo$|9=on39mEML$igW`=Pp1ddX&RffR06K9gIp)^<1Lbz;75WJ^CITvI4aW>{hjR$%M{kJ@Dh+K>AEhwPIO}^I3MvlBcb> zwl;$fZ*R*!#rOLdMH{M3DtD2yXRRd9AT@-lcT$?|L)h*tJwoyXLKQI!GPbK9!5Qj* zBGc!UlW~q(Rc*E`+XBAfXX_&&)xxlcx`8Ik7EcC*;X===dg=Q>GeuHD3ho}MYTz|Z zoQduJyHTjOUd5RWznS9OkS{NVhQ$dS8Uo9VmCg}GnLy3a#6+?QJAP5PfemmfMfyCJ zf>{?A(fM+3jhg&)X2nH#-L|HxE+r0XL3ik?3+v@vtW|8tXKV}LjR~1wTNckloG76F z^>dxQSD+jy8_3TKVcnW!^w>d=_|!y-8jaavRL(D7jJse#jxYl#>JI@6^PS!XRONjF zH+DSDLXE!dsa$AZ562>KKFS?5-Uiq7T7*=*R#!GW6BPG3y=C;R8EXtU(e1xR6Irt* z8N;!1PUCBj(pJ;J(qqP^9 z+3un%XQhBwG}x@7HjR@})jpm}W1q7Z>G}o#O|)Wa{0vfIg&+4u`{;AOF#;QZRd!$S zK{3H3*^A)L49H0$&d!)4E&F$b{c5`e%IBZ^TK~8hsK*v6DKdVHt#|=7m#=R%&{<@p zh657gkeLLXCnq5%?jXV?x~HB2y6}oTd+JCZ8M z<4TvDau$J(opBL=z$%lEq%;1#I}xY4#wXjFCX-dm$w=`PUwe&RPk~Tj2*=d?&fK*y zTg5$her_V(A@^JtWqqGOF{t()lhTn4#&WVNQk?`-c)wri++?}kr%bl6SQA+pzHnxV z_VwC4YvxHFOxP2l5;g>sN`~0ivxm_j0G|b$$I`Z3_#i2ImBhjYyi+g97f(lw^lozj ztc5Te<+8S&JqV34@N2^KxYm=z&)mCzX@DG+vqhglM-$dO4ooDULNiJjC-*hkvVDHyKFrd^Yc7gSPqhgykg5Tp2xj)Py> zBaR@rfF*xB6KN-01gc^5Xj}cl6Jk+vbD#Qa6HI3$!d+yEY(GZ&93uj^JR_?gP$x1C zo9BvOyJNV{AkqHC;Nsn+FOLHPq2O{iM&mL6*(F zR`^5*@pGcm4kE0mW+bXtkK@QEp$8F{A*8*?DsBIfiAW!O@?P(kAD#svE_PG#Yshb- z3=tymImSc6E$@#JKc{}yFf;)F99f*`Ocgs))MbefA>*K+vPg-zEOugax7f9mk$~P+ zL9OHO=R)CgZ+7o<{_pbrclrLi`~LS1Z)SXLjJM5XyB%xX);Y!tz+um@U=XgOAzHf! z>enmD3Bt(Xtbh6l5&%TSggan4|6EEQyDUj`CNnN=nD0XC$Raj|?zad+WJe4rK@UEs z`dZk`mzQWeP9=VJp+T7=1?m3g@+>6Vxds^1*T$0_?_7vzplah<{a#FlH)7fZK3_tU zzBUKRp$41RV$Kr3)?M_~7!SG*VP)^D_m?D@ge53&dlT-M6+cGAJEOyv1L&|SyAX@2 zSKEjoeXR~s2uD|cm+HYb%xdY~p@H#bM_^X}{jMah@wX4atZZM^k9NosEfLEsvep>W^{QaAXxv85r#%8FW@K{NEh)#&ivc_*{mok_A1w z4^hQ1Ka~1C?(clIisZKH#&C5!xVx zDJDZcCyswF$R0tCy7J&=);g5^3ikEo8=jE*e0OJGh71xwL4mrn8zk>~0noJthocP9 z0&tsY<}C}7Mk-hU3c6VeL4)D+P<4O9?yGyrfbb4Ct(!ma@j-b334H55V8>-^L6bqq zmvx_@u`m7zirNB!V9yAa=ygq00V)dMvFwutyJ`%3mcF+UB^gE!{HppFcky3|JL%Zf zFh^cY#shp51&Ddvu|~+tND1-+M5I|Y(+t4lKgNq=x2hb=Dgt0eAl4mgp(AmGVHcqV zN)VdYuR4VP8T4hLnfP(v<^8?qHevcrvq@Ms`wH@}_tTy%-%M^DV@7&j3YY8up zou`l4%ueT+NvA*FfPBj%kOqvzW>VBmHuXJ*Ys4#t=^-E)CT8IKE5^C8N64Z|j`(sa zg@TL+M8!J4mO;G0w(#YKq@4QhA1EGqJR0i6``*j}4LXVAOU=fL-9%?jG^9c;vPv#z zC0f~{j;jp<*!~`oBPpv<`IP|7JO_wyiV^y>MOeaV&z0Urb!>*-5DDYFI@)U@p)Uia+PboayV-# zFsDC(%Iw7WIU0*^x0^Q*+AY!*^dw#D@#92T&zTY_T2@$b@75 zF=5E~NJvtf&0Vn>>nq7)0W5Kfo5Mo%B%?4Ripq~6hyiecA{u3=mtR|g-Z(}s0{~vy z1LeDHRhL_B(DcsoYXEd4S4mXLNg%g%lk=+4p0a95;A!@N_u^@I{nf6)35ugHo@#(j zhf)}`4U}1ynpAsyf<_9To0lA2Ci%7tGna#DU`8tCT&b{h}_>-sN8uXgstO7ZY zCjdAX3?5*SEN`f_HU07yUc9k(;7zE%bb!dQ6uKuNiU6(Z1LkR9a>qEgQX$bbB5%^> zun0xp(i4)=9+7f^IrJC%{P4TU6)s{%pQzl8bk@nSfAQzd6#Zr2gngQ5b^qFjXj&>x zM>!7p%=QZBEByeb4H^RJBUpN&_fjeJeYyDYfpkb0ox=?D<0xXE(4Axu$PNkU+CqU(+#$+bCK6GdT0|lWo_WKIu{~>Dg{t($@`Ysv4QHnFGJ8N zAZS0Ox#~7_^9t`5EiiF&G%9_O@`0+G375?KsgN|^Gtqw{!87&XagWh;M|}I3euI9> zeWzD?hgZ4~9Q>pD^Cw%GKKy&MfmDrwveFr}b_F0cDXrJRbe!n-NDqvIB9Znmsi~8^ z1`0X1x-VY2*cir=!lxr(sUoZ`MXmSNF98s}K8K?Mg4AIT-M^4Wt2}W~L&^#a8)?sV zRNq?UaV@O)&P4y7^VT`q%jwn$PLZn9V@vkr?a)>{TFPADWQ_spBXpDek>;~7;C!~{ z8W08|_7k&xpBQdDu?L?0S~y=EH}EQ*rukf{EYe!jKqXK!HPcV4fB&~8zD0Sv%K+s& zy)?OUncY5L<^?60DY@@^s#%aTsk$vn&8Bbc+GSNv%g8}>V{?7+Mw@{7gg|2p#Glg& zbU}wlM*)0(h8WC5Z2C`HmONvFn4<3hKRiVmXq7@Up<_3%)%lVORg{-mRs?$x~5@{lb;9aQiT! zCC42uVA846PouxkWEW%K@<;ASH^P_)Q#-NV{1#bY3wu_0@iF)Z5zGXL@MlV_Cp7IY zgMNV{O1ZZ(_-+N5@cW~7>o(W7qDrheX9UM&>>nVKLZ&d=;wu*=AfHWu% z39Tqz_Gh%Z4tg_9*>|v19WTAS4xMtp{^xYp3gAf|ru~st4?W#{QrUnobZP=|isqYP4y}XERmGS}8eYv}=a155whAqf5x2fpJ+Cjuu4Hk2nO}o& zA!A+@luy1Ri74*zSd}ytdd1J#1Hji8x9!YM!={5K$Ln8^+Cs7)db#?oL$nXe?i=U0{Vj-`?@sV_cGp^-3#85j%3zWwwa&Bx%uc5`D*3{N=Q}zvoZ#Su^?`e*?DPYK3R*4DVS) zTW)rkIY-SF34TJW+SczCd44YF+Gz1FfUDle9Z>AzZ*#!XQD;tly7F++sex}i^O&+a z&Z)_KZ#1V;-E$7>(gCM4h5#)Y*D!o?ttH!2eo7=$QNjTL7b+1%X$m&>u(v~ermL&E zTWeUFr#G_*oHVyCZ#!3)QtE}=WT@BCjz2#Rks>4S_3@m?kW0V4PvqrknA>=L$#;D! z3tJ_Xomh;b8I=0CL5)d2(vvCobS&7DHEN8nHxO;G$Dc!0kl}AFZn;-EssI^0LF%p! z7{pXkOPaWk>@u{=FBx!bf8{J2QKmQ8Lx4ht6xBjBxgQ^N;(-2w z5rG10t{?@<6xxiRlKDp^6RjZy?9%UnGUrk=c9_tvLNes|HYQ0iH> zUf?nus=+uMIlqVL`lWL2FGoPntH5*gL;C`MNmHNqY!Kb0?mXE-#~LU{hW)43$t>_?^yA32gxqM z)5U0V{#dU^10$HPcYSYO5Xh$~xx>U7XZTz~bv4Q|xULphQ2a##X3xi zeOyJ{>=~6Eo1Ee4Y7g7De0R=zxrBDYt0zX(t#aAFS1yG~yisgc5ZwFc`~x((Xl9s& z4XPvCK?m4OTj3S>q)|W%@n|)AxzW?^ut5j(@A4^{FZTIE zai<@XD+w`Hp&(leFAhb!A<1o?%=8x07lUyZ2=ET`+<&+Us67B-z2|n3{2MytB5Wz@ zV&$*|z5QZuws|FK1N#ov#T?jYH5!FKL-9!SbR=#TQisKTi#P!uxYP4aWT8kA95y== z-~RC^RHPoj#Q#WwfJrSN-cOhqwP3B-nGx2JCAeM}V`Z^)>6c8-HBm*s8xUVQk*BC(r!U)j@w*ViO#cf;sD~AGx*% z$vWE5qZqlg-pOU>t5I7PyYlnFg%FAaJph6wQ;?v*-?3XnqtHUJpgRHVS|OX-IqL}L zZUy@oQbWwPMmq_~)GE-9M%0vCRBdV%(B-~eP&o^gV7D}b+5|}<;Ed8%(I?L}G2aa? zRUG+ddglXpj_N{5P|7#(C=I})T)=QuV8_cRz{f8aJOhrL!Gf8Y2x&!3sJHyGKTb?- zV-e`6IT;tErj@;ls)C71Br?*G3_Y`jB);TS`$!6q1J#J%I*!r$&&qS#GK+Wdu-W`8 zkc!|fTGPMEDv~&0&}srBvS0rFJ)GHA8c6*P2A`?|;cf&!=}9}#fzV(LpZbRw0W!(- zlyjnWwnkR6)7$*-`AFUYY(C`=`=yDLkgtC-9#3HT5b(B1eftbST&~a{ya(6nz76m` zv>Tv8d&jn+uNvb ~v*z6!ASl4JRXCMXPMo?tk+;zP@5kwNU(oM?^4X409AfMx8 zbUsR&MY{%^_rb3|uFFL2fat=T>ep~uG)S zQ5u?AT&oK5xqFr^)ug?oaspCWF5zdRx-|rkiEBjdZ`ZdZzL&_yd+G7Gmk3NUE0s3) zR|6m$+=DctXSy}>Aek%W)Tj!CESFG4$dD(Ev;kHU(La#Gi4uY5CS5-YT!bkyf@KzM zkH5gU9=tpdQDj5?A>tzq55sfRL;BOO`=Fg9P=jCuWkfm`x5#fR%ZHiu48jJL= zau|i}(*K*e*Z=bYhL5K>AD=w+zfsz}(%n;bzt9qlJus|4ad2!YgH?DZHQ+5mA}dLGKI-3iMG#) z?I(_}U3m2=8HyhnUjp@70+i=(eKUS9GHElc@T)__Ne`(zO710eBUZLl)1Qg-PL|~0 zoy13GJ+#?Q#Q1*-*pF2qN4_@ZbK^deb=N_HkX=4^$%nQRF;>AH+L&TZWGlFecHYIW zkQ;%LKq)X@^^dtAf)L>Rwt^gpwAAvq=zPPnt7FsHgOaFM<);zovrXxcEEIQG?;zNS zC%m!eFCsJ^D4xId#B`Qrr}+v366lMF^o=#5KNP*Y zS?)r-d0JaCHn1A2KjsBNMzUGfAuQD7)S8<@)wq4)P`2d`&d#)4erUNR3rJV$)*F-uRy9!IwJ z#Y4Q1W#>i_>hAypy&p7_`=7i8=BzysHJ;O(-fsKW1OR7H#hwb_O7}s=#S-!cP4=dT z$q`ysInrkwAS=EJ0PC$*{YS7Whsk~%wKsTrHRR=yCyEiTHdQ86E}ds0?!pZ71@oO~ z9XWU}!rV(DJHfBD)(F)8N+~@T0SN+qMCSMt1UI@J>(8${3d)6Y*ht=(8u&h_5NI>Y zUb};m{N#wGWKqHS8zpRaR-yaeN$-7fp#jl>LIM9-o9Hwa!`XmHW0F!p2!^hB1X015 zpXm9xvN(MW%7}{qks3sV3MM)pha)^Kjo*mqwi`5b{{$$b4I%`s`l}b<+I$eDDg{b$ zKZJ#r2+*GbIy`QO2)3X$01-~n;@uZ6?WcbanGVxqH$8!f1yaP1E9^jjXAg)Djs61F zXV*Gyn>J6nE~r%h*qb17$w;pWv}8uoZX=cUX?M2L0X@v10*|on^^^D7UL))}_!PQx zza=SA+YEayrg%ciq~H$i>9PT*5Mw~i7C=<>!s^1L1N@d7^O@Ny`9l1#Ny&ho;mP)UK5w zgTU&Cq}-mYuMTgPLRb6OpMHZVjFh=@AqX+%ZmGzOj3OE=`^9@}$rW-rAE^cfK`p|0 zDJX-r2aWotP-l?;C2*Hq3zagnxdoS_szoG&;s~NVg$TNTZpcIGHAcVRgngf~pZZ>d zX68Zm?~t#9MXGxLtOA&X_K1AFVA+7Eq8ODfF2WNCGg?*D(vip*SCG z^tyyB34zs`ix(Di z6<)^}v_-*ub%+0?&D(EtgBD)A_P}tdAqQGJ@YrsGI7e&ypDuzbWKLrc_)HuUk@WeU z!;kM@m893^h|DT}0((ZNPthA#WUAJ!-HD*^-fK(~qZ-Xq(X`LuL@;LqqSd6C9kG-S z^2v&kY<=D74$6ID89x~uOm)7gjX4fVQjH_}$&D`W^kcK-LYH2EXuHM~TU@vT*Wh`M zhzsMx0+J=;h;Y`jRq?tiRG!^C%{6ck#ZDfxS48IQMnxB>3R@i}7sZIMztVkwhIj{= zXx@nVHlEMBrgmx-5&Q?~QwJoAqRsYd0x7ZS_jmqG*dtz_DqfPQRAE>= zs03A?)Z{#)m!Y$E35-rU4(kj|`ToDU$H~X22?tIunbDtfg5z7!#NZ$jWt}k~5}eT1 zm-*t@D0eP4{WOvRcx}}nc!X^fdimHjMaXt0`L)x9*|pNy9+#tX*H;oKwmnL`qS>mJp5l2 z7m=E%WNGsd4t+!=inrAWY{CLm7D&nRp1jPTi{%ti^;XqN`^{f=kvu$hTB%L`?Z@=f zhi`;3zp#~4zy2~#Q={GUt#gCAv+GE5A{wN#ay$uqPyFIcK(G}~r$kdJTo^~-#%}zmB^#E2M<$asoDbS!Wl78n*ssYS>Fi161vF+3= z$6@Lsu7;n(!KwU{^}wi|1QKrZ?Bm#)Wlghr#`9$?SNf@B-z)~g6v(HIY)p4NJ{zfj-8O1`qTG^hG`?ay zH&0!{80wVH(^7E-t2_bW`ve?WVJUV@FEf=HGJaFNms3J%Azy*k4vUA9F9`yN3eS^E z4@+3o41Hia=_3{PtfT+POH3d$NH$IdS#x487 zpB>o8&7v9z@xB}``s!|W9-Fk{J%n+Xd;$x$i3gc2=p5KbYluHXk_uBmQtr8^_(Fw` zLEJupMmh#_o{BeEa}0_P-Zi#E=Z5n)kQy6Laz1Ja{fn3Bc!kl*XAb9rT9BUd@)cS# zP7!4gmUU+!3d^d1G)P|!QuAiIxf1{WScf{oxh|J{z6cJ7W7|Wrvz^ljA^nelsDZMv;q zasFZf1%n*5-CPfq?$;;*Z;FOYpEHl6;aHUT;!Fy_CXc4SYHrTTrj}S%k7tItcaJFx zQ1iK@g$Hw-<#OX=8ikzab=AwROpy&fsdt1Xy9hgWFm3Q(IBOm}`g` zIKV=b!5j{d4k`~wvxl5f_s9fNqv(Phb!(B;njXT5h1VhEb>j}l+bj~$s zalVmE4)gU~SxMrnRqXFTWF3^{)z7nQoj_4LfM3;qA2fI+tZ4tpEr-;`@ax)x zAdKek@zzH>t>HPe*w0Jj|G#0B^*y{DbeQOw1(C}ggkmhLKpLxYb@T1}y;Sd5%_kNw zyzFH;K%x4s$wHZlXht&}#Vu&ieaKkM4~=|>Hdu79xsCSorV#G-pw;{mYOXDmL=P<; z9&tY|9E(m!6_N|>=?MBzMlAaE58n-C`3P&bi5Bd!E$?-xIV-1$jY%#&cJ|DqUQ}nw#|z%4nWtfd!4N&*aS>ui+5DEF9#_k-vOQ=qK6%XXwrj?p3{kW#2lCA{$AtVz zm3HUR$(zq?9-T2<>&icg+6ThqS-Vnl0IOaPPx4EUyr=x^B9wE}WO-uN6v2gwkRV0n za4*%VHiF1v;cuvgx!+=Va+gg-)?=I^x8n05fMTbSXHfbwJhYPV^ur%U!sSE;Qq+o1 zov$Fzhg8uv zzvET*|59AIjtYamhp0uwU9?L4q6o2H2_m{SjtDzu?IVzu&$_dRf0-lzLGV6BA-T=aFyr@b1)Us^gB zy>2;}a#QI~U@Ye$Hjkg|{lEdR2kt`=aQk@oTOA^DQ*o_4@ccfs z)Cmnn0{^aCeaCCFxYj8XL3^*v1oIERo$3+aoiz+*KPaV#A26-!Mb?hmnO@y<#1+3g z2vIlCI!q9jYso9Dv4#It&QA^Y@7~9t^-KRN|NR`6 zSdjPz28sC1nQvcQ`>Zna^=N^T;DxXTy%!!p2*36!O&LioQ*S8ekV78V?w3i|J5cZW z2V3%Ns7Kw0Lmm&LCB~bxq&G{kOuf8=j|hy+0_y&FD@2x}00>{;_^%Iib32&pAfo6F z_4`j0BO0%WKVWE+8EX$rPE8f<(~J_wR&+-p{x7D{Jozd}3}}A^@1$punpt3B+9E05 z`Cp$py7CkQE1>PpBt)b|@Y?HyphDWv`jH<}u;0>h(u@y;T^_dV!&v}OrWAgE6oy%&jl4wLAELD)ffT9_vV&POjuCRo8_OI?5UwpA|xL9iF% z$x8@dGURH`xxlvhZ-J_oYONTw&RJq|cV0e>;GlviX+%{ZBlLsXn(g#9_A>kJ@9(Z8 z@0cC_xM^7Zc$j`j^7MN1b5W$$h0ubv9$OkurTHHr#I_F7l2bD;v(JK6Z zbwhuo9vq2#^YXm%_*92sR98Tgp%j=MU`xcrcFVK3E)XfBeRtHK;i}PTOKj#Ik^d$W zVt%mh$D30>N^$d>PrN2*W1O9Fa_SSQqFU+NjQyf_Q8ejP*>1N>3=jnrC=9j}_n5Qp zhcaB_u=vmO;2F0eXpj_y*Y^jt9BkjUwLX$}fGEZ_@@Vkgi_mStA%Mm0x?yCDvl2?f zCg-wUR3AGBPhYR@A=E`~BCoS6@$TR~+!j?qd7G*L{l4}Jj?3YGpbZQ#rVOjzA$M>7 z?${%*olw;=urNAhT3Kl$b6Q9*ARE$d4IHfoVF?I(m7KRPZVpjE24riR<6?|`S;-6> z9f@a34$1Jw-H=Xb&_rnPGPSu2bu>t1NwGH+E5!gSj*Mz6rEhK`n<@!rEat<3zjTdE zzu%*UCT^$}&xZr_IUj!%xD~Ke*R^3pBC`RMT;@d7r&&#buDnIjzIS5i=gdn)0$|FQ zOR?Svw7(-$`5sLph{jv)^fj^I1nnsX>9cw?7T&8RF1AsjeBptN#~ov6l6*Gzdhu^m z$Mx*|(^q2HekZx7%U|uLl%vUwp3b6huZ6BphJB0eJ@4F)1$&masB)bUMj zSB>5!Q^}Wgq38To1V8oX8oMqf-(EEy$sov$N!s-^J$$Im)1G{94zMksBetUAFCwYhSVpA38qHEaLkEb`>+#4%DwhbDu&Yv(Xn^G^H z`5pJI-YSZ+^F6bF)SkMQlQLd?%w0n#DOa>p%1=^$c4TfT{dMbEI9+nGm0O9Z{`(aZ z9~EqX=kkw{`_eW1tUL2NB3uM?GMxZH_ypX%Z`5;Y5!#X1A^@WLkl6886zu7bEV7>>8YL-2U}+og`$e%`NLB6})&LQ_r+TMl_Te{Wg-!|3Px=fmRYRJP*_O);h_v05YrNW zL#^igt9PUC;_JaC)q!Gt9rAKb7ooZ#0B&)ASXGW>FesE)KBP#|UmdPt(bv~saT)^Q zn2o+a%DFG81 z4%e_q@@db?&692K@1IybIw%do=WGR`h0_HSa`!>Zz%yoM@W!gvW#C1d!)_P>EO}(< z&sWOZ`*K!UlcxG0rQ!!FiT;ltc;tG;BNu&N&+1cL)-8?2>f=2H#uR%FFk?(>)-HRc zjxPv&m8n`d_1oyi=kd+;&EwHt!#`L43|;Y*`0BCJ6FQNcEz>=_&hDso|HSQ$JBF-% z@ivnwb5)y*HtP%n1x*X@nDa6`*@VlYO6~fLK7C$xY<USUB1x>)NDr>vlP7XQR!Y-sT@C81nqeCfF~X zY`D{NsjBov*pU^##i>Dxyu3Wm)FP+>P&{9jF;jJPd_H=SdnB*ajO<6a_nxyIAvD+q zOG(Rvb?SSRigIZaj4;Ei)#cxU;nkAZ8~LbWnAEKh$a;d ze|HB#U{|tCF0+2hTRl8BdaU*WMhw{$I%es9zX#6$sQYyEga6^p7oypq3Fgk3+$Xb= z9gVY!xF14}-TL*>y(hhn^q5XMkRuCsjl!I`aHs6q*FI0P%@JCzY%baBdQK0~&91*2 z4)|?49r%ehAp}GG?IY-9ndc0l%a$IKn~dv^Wx~A^sxBTCi=3mCCqB3n_jygb zo^M>9A0_{R?f#hVuhko3u2)ByWLxw*U-;uQQHB>WM?F1rHk;ZT^VqIE5%oCV(zi=i zJyTbyY-?6{SJX2~r#o1qLE5%Qfha=>uTxJ}dKa%X6r9$I!C7fPf6J|vT6>DZoW8+@ zpibX%>Ni96;qL)5>sYsfUq`eQqPJJJ8*Rb%4K0%Y9=FcIA^dUqQo4u5@Jsm>(QgK_ zEm*-G>TDz28@XOjy|I=bSL&2az2=Ja7Z1gltk&DbPK>c4tAxdA`QU%~B;&IDFFv9S zp$>H1NU%4A8ELN{Y&fE(UxD6B8(4vLGyT50X8M3~u6?Q0)qM~Qr7Gp>F%Jb97_=_3yeuQw*=y zt>;d%gPgFv;0bEcPUG87p~hN8FrNjL*Txh{0qRwj2Ky)038rnL_Ka?V9wtsc_*~+W__np;cp!W zg6suj^y!JaC!*{wj%WH$TV*BMK-vpqF`m@uA#Wyxd|O59 ziv;2VWUJw^x?R`D)xRSPkhI@I^kI0CvRMww&dyGIJiIzGsGZMm>$t;1Svjz`HbsRf zCCN}7y9}h@nFIUbLXt}@@oS|e4h)S6-GvtUjv~yV@>67zC@k8~@*k(RK95^a$}(1! z<|WQihrIV?MwC9V-%yzYFTE3%E)^=E&{GsK&#_Fx+Z(0!LhZ(DBb-(No`10rmo*@f zHHv;t&v%)9b_`vqI+mwcZ;BNuc<86b z_z4^0_irDkD2m>fT)gMm3D(4kTgw;VQ0VThr%3#F;{RK3Tz_%8FZ))%_*5G1KfU

      e!+TM?FC@6cxI=yYghO5Am(yB3{-m;o`l{ltchC1Xb}6Y`}LR zG86@UlP9~;$-8^E_mKq}E%JI_tUq;vK*Z`Y=PK^a!1i$^egN4bog82$E_2P39!=cp z7;KXX*qC*!4UTv$Nk7JEh1|tu#YJ{fZol{K5#e#Sz)CF0XAp>%h4kaQwZep{6J=Kq zEkr4tr?8-w&GY~JPuqXN1&VBM{D1nYAQ*a3>bdP3l5~_YSZqVW&VTua9RvliVhXLf z?0*Nj{TGZy%RfDG+vIV;I617l{_)6d697y2uOq|bBEc9@72Ez}xwfq4DZ;JvG}fT= z$x$Se|1ZC3ZH&iutn6#``qxEDgy%7q1pm+H?I3i6^~wLZV}1Kz|NZCx1CQ4#s_n~m z?zf#vt)U8pcO6uhjs2HV-L17JlWno*JpXTNl7_)pqzMc7{>$`mU>mSv{Y`ZL_9pn? zP4I>8{kJ#K0@p)}xYMqGeI2-9SdhKxa(`z``b!b4NYOo#>-CR;{a={EG2Bz}@vo)3 zS8_uBX+B5Jgcbe44U z!#%46>k_(KUY9hz?Z*)+VVbVtg+p6@@jopNBjVaJ?bG)h%20 z&1~7SOM1^PaD{9~L&laZybSizm+dW`ubNsQw$SrPt^cCu=Ddcqv!~}dN6*cTurx#% zvm2WlnAjRv+Ob<9?7>CwgnS+&ZISYGsUcvI9RA)xm$b zIKgEeN$?BY;OAZc=}h=x>qyUYmWxM_os$VXaUNl0jszn?Z-IZgz$F<|Tf|kQGq||+ z)cW*}2wOW-q}BQwxnb;F?7ZtY?2HU75bKxu)~^^MZH*DO_$R^oxaoPM={e7Wk)eNi zr0{zKe^?n<;$Kw;+hYThLpwD!UVm56L7z|Uteq6xmJ2R#CV$!1P!RRwXoN8>ozL4E zSYJ~>8Y3*g5XR2yLvZo);FoEPTE8N|k6)#UEnyz~w9o}LQy2V#xYicV&1vFbYK*YM zkG8%(dnD4r-qia0i$+K*D})iALHH33Y;7T~tg#h;=_=9!zdQT|Yq0U}o`5c>{Z7*j zk7<}1+h4=)f)Bqu=;;dxQq>34DBf<}Q<@7e}Y`u3m! zUNTI+4Glf|R~QMN!OOufi_4}w0`o#sZ{U#v(jKx(+?>j`rk19VEJIdM25IYLU~3G1 zNg=K5ZIKohz#gr=`Zr|XzYzcMws-^o=(+hVfH9FYHgyC)O`xA=jn-MZeglZmhI^Yl zu7AocJ-WF>n6X-ELH;>fXKmSwOOtAcTb><#X?yn36{dEN%m>|CloPr`Hhi zpFQ~#aNblzU_U8~8c+^Ev-3y;2z8&?92lt~Y#b0)MhFo3{oolPVUss71kuxX8fAco zt42UMAT9U_$9{8)wg@{@7X!mJa15!6HN^cj~AB{a9UX2N&{m(b{Ky%so1ULL|UGDID%)`geF37Xt zF5bx!*7LXZ1cE>58{P#N7#Sg~?LmHmn-dA*BTid{8Awn;fB$VvKi-!7JD7epF1&)^ z<&}+RolgY${5!e=LJsx20PjcP`!!$izXIu{q##hgDPqCHgMTsW{UcQ8C2*1;jsJY> z{iDO+vo!(!Z~9#{;zudZmi6 zvqoCkLFU~E6r}%7MjdY?{vC|^Ply}8cLLn_TOw|JRJ%bKf0n*qL)`yeM*e>^B`+xW zZ;jvi2+2}{Z2$93JTD(!eeizerz!uw2L9(Vr78ifgQSX`11MnsjbJ<8Li{^e_^PqP z{|v5HI$Q}75_JKGi$9j|KKzPp$+HvQz;u8zt-*& z&cUqTz`p>U3|en`JNlb(-IgsUx5%D5tM05f+N=9Uw=G8CLwW~AgfqpF{qiNx6Zs$V z%O>**kkUS&G`(mfcaiCG8qDT>|yExQOb3drK_WH)1Ck)(dAC;d|vQg5XkaI{2 zCt~aL>rZLCU~9ReIkBYVf}R==%oT4GGoM&KcG!DyJVz`Rqs3@GF(W*pWApVL%hYL! z>sz*N+p*{1$-ngD3Syha1*~pF>D|45@s0K2)AnA#@*VuEv*6#kETKAacl#rkzq-6P zWChN{;(A`*U`HW`f?98~s>k@;jYtnJM;s$ZeSOXD4MGl~qYLUO;d zz@U`tiD-3NwXO^$4qY3>0G$1B&dbV+F~x@UG_A0|%E*&{mwhJa{u0msw}tX@`pcxS zlyci#1!dtsmW5!7pw=jhYrOY<$v7|r^+_T%U8eg>wgfL%7cNPtBC{VibN*%N0Hb>) z@40}DkxQHj`IQBp)CB5N<1O>*mkiO<(;EfrJ)#0zZ?i>k z@Fm~+>#MzR7HGmgmAAWoiGi|2Kojie9b*6bL?h z4C5aN^G~<_!>r#S%ioh(trYXq@2E4W{r!&90vu^aED& zasS#oX}=o1t#2mS#s5zh^CMGPD1%yyKW=&Um;GNAgY{QcpNzxWNz*=Cyyzh@=6?S1 zm;B5gb%2`ENhh6t#Sw1Zb`e^t@s-M7ljLWlL9N>K{S&_?WDg-Bt9g0%mz>&3W%`rJ z`EqYCe@u<%=K#D3bsr$D)8PG%Tl=LzD9rgWG4z+#N(;y${P6?!=yzlN$mbu1e8~wk z?*Of$mh2zd!|#M22r#E1P$Sv{85zG6;s0k_8#wbHZv8HB|BXTz9spwXB9{UCqSU1C zM4wX#h;RZ?@_|E_Ijq0FTP@kPZv%I}d-P{V8wA1X#8(M6fAZY-Z>j-UEqwdT2<=~= zNaDH#1gk?11Xlf$s>y>GXo5UGE$|N(NCxtJ$>kdIX-!2Jf9D0H>fTU*()qRJAEXS! zgRYa8?%k=a@w0hjU<7a4p6W386^riG3WYY5hsI8QPp>~%JGd1d4S4Wc(xZ|>gRcE_ z1L56!N*_K}ez}>exB1&a+1Hn+9wa1KuHSxndBb*J^4UUWO5Q7EBNq*RfHU*8^E-~W~9ZB}wsM>I+|%MV}C z0i3O-P%6bQ{T=yp&)7>kfD{xYvZcP2Qg-;!ZT1x~9Wl|Fx%;CT2ITUxff5fIA~R67 z7VPPQ+RGJ`md*Xvs7oRsb3#c%AWRk0ho{ETHf=1Mai$9RD<_?=t<>u`PbzH14VhL- zt0J|&zEQyPnUWF(58@rkP0}~6pUvI*o*gt}-As*EAvT%Um#Wfew$0yczY`Kn^lZH5MW!*sl@kq`&F zUlvH+JS(J2z9%2~dRx38UPeFcOv~JLLXu_!PW`sW zEAiW6Clq!eesFel#kbq9fv|M>ai|J!oo|wxcOzZo88wmC--e^Y9y6?u6=m29mvZaXN zMF0zkFdVpr5r`vg2t(HOYX{Z`;dBN}_{~RoH$fcm^k2Ih{_OftF&XjFyQ1acC&8II zTEqL+vt&{SpO?vr%LTiT`Q4Wd*`Tl`*Js*3NIly$ijY@-Io0dCOD`WXS&#I$Vo;wu zTq|=m_0t8m9BR9W^_Rd-k%l}~vUI?kSv4?Aq~wE{`qm-Q7+)h=H6#`@oXyga;91Vdw_KI6N-+RIM>DVS$IVIQ_q54HBd z85EGM%y<*TaQccn-+hS@hV`|7FXahjKN~KCoD|JK18J6?Hge zwl+CcABMZ*sc?zuihHiyazPROOqJk_W2kJ)w`k7G7os%X+oH`7@ypLU0Ht*=INZTg zItx(x?)HN!rHSZ0iDDdFriI>aL}~U!Ap)f@14>tJz4J^@6}dw-E-aka z-7M8_eX-#;z+(RqD7dErG=xhA9*37V_`b{f>8j!xRCq#Vg7H1ZSC0!io$Zc~?pONZ9Qg7XldwC@fr*rt?@0hC??dh7O+g%VKO zX3Oc6uvTiX)**TZg}81kez8wa0_FHe2+aucNcU9Q81YmH1yo3F4NTQmMMkS3H6nOR zRXS2Xe|%Dx`D~6-10S540%3Y`Xm|Q%w)?t-E}+%O-9kdlt;`OL?#dqEy#M0?0Ki-K z03}v|S=%4f#l`W1*6GD;T~PE>WpM=mof}e}rhGGx@8PQJ|rW9j-a z2jaD>2)M*W+LsV?dy^>3dNNXKeQo>ofRukZ)w-F%-NC>Nr2O3W%pSayzXQ7dP^L%o zw_q3HgwdxbL!MHfe?suCSAoP;ZQFDlZzeDf=clJ_>*Giifk%g{25kdgRbI@TjuMQa zjO1@pC`nNMkynUx{`aVtbpI-?0S|2M$JakFkJM4a-#1Z*e)z60aP z!T56?%3>8*Wf&9;w>A@Ei7$YqH%T5JAWXS&JWdrb4C7JfUVJ6-AwYV$yxooa9=7%z zLBMuK@b(HY6Hq88P$X{3jjw-00smk*VRpyZ^<17{>W5#vO^i@Xn|ZLsYhX{bn7fec z%EC~N6B@;c>km=N4q;TXdUmZNL)U!Oa&El0i>iFSa%7f6O>9gg7j-I4vBp|xxxHWgvflV@p;jH72m zJN8(1JynQ`q!fHJH&A$7#FZ*M#M>hgqVT(1Xij2ex7U&;{KfL0^F zdG*OMrr4^W&wCV`n%S6V(G}cl-=feJE9#m}BkcHsDLZFQQBd3vK4l4?apb>7&Z`N$ z+q4w$pWg_f-mBx#cF!F*iy#r5R?c%6Y0tPjnj1|bzQl<`&y|J62-uuXK{Ih^C0v)W zZFZmQ4HI3N|I~Gxh)QT!MWAv{qkIvbfZ~2=+?h2^yZ=s69Cgh8)3@muf&0<9z>CK= z-;Cz^4;273WVm$8&RoST6b{8|V>2)7Ikdr_;2fnCu*5$5X@u<0;AZp7X&fE}8kf5m zIUUj9piPEl#zeu8jmMooc#X!oj%&)m;_ISqJMl zvL{QeYD#S$kGR05xTX_^hh&Cs%6iEHJ4b(Lm;VoY!5c|S$o<~092NGt`6z%!_)_MF zH>pyExVZ_AQkOfjrAi`S&ry0D;y=bs-m{Vsyq|Vh_aW_D4b_P>Y|wjL1rbNuXg`{1 z=)64_rrz!Ztr{s5m~?*&OkB(q>l@%53VX$gzAlbrnndwiVv9a2))B!x#Bp6s*>*#X zy6hUN$fVadSuG;=mQJ1Q+wnmN^X!-ux5ekxx47m(JEI^n$pjVve3*T82zv3|RzT)K z1d~qnFx-8}x}afUYG{Pw7-}ZQ2^~Qr?ol$0?M&=^!yM+)HQbVv<2q3a6Glz;54afi zV5EclRE1$)6*xs~%>DLWqj6^PU>77t;z)?LVXPD1woo2ANa_;kH%Q&<_d09|Om$0? zSETn8IvuWBDcqZseu28`+Yo7BootjG+8K?K^!C5`N2ez5AxH#_`CCcM^$^G23k^ngUjQ8sW4LuaSOJE^O zGT_pS2;?A2gH~BkYK>1?8~N1S0I$#Yo{T(f6^?eBY8Xw=N7u%p1|vr6BY19$YE}_z zYgkxP>OCe_(|h4aag)4`sd!;uO$oF!^B4)5!Mev%KG}?MZru6Bed;4~7*FxL@eMb` zQ*OkvAGH}i!>Af3N__-*vfeOiC!y-7vhuM#|_qA(ARABUR+7OF_u zqIn0F?(n<5ww$f%0ioafP^m}0K*h*%JutM%`T7&J-SUxg@hW<69aJYyzk5X@9!(?W zCeUFuHQ3PAm17cOZ&|!0ax$K;=DK6+v-pK~vnKMj$9Z2r?7jLM=1^0=pDC`83-$8; zw#)kdyw8g^YrA{-c}*rib|#{&gFmmyq@ImK8;4~hS}ZgXt!P8he&Nay+0rTEg)gs2 zaxy)aM{fJ1RgQDPu+cCFhAV;PJaRjUFMvGH@|AC1a5!18P7zDod*xME+{n&15;=} z09;{xzzOlP#~O9>s8IIL-3&vr*s;_5OhZ*3*yDcNeZp8f-)bx|t3%J#67p5Vh{{%j z-!QU!v?$)q+9kjT(9vmtng6iO>jA(d+Q{qV^fOjn*@#zSHes%>QM=_ur{78ymNO96 z{wOdJ{kACnW^x6_a5g+@?yYd~!ROVO+wt7q05*hryoM5oYnhtq*66Ze7o|9{n6dYT zc2b%ANOW|JsB2ylx=N#kUrLro8J6EyiRePHJ z+vX&Q9-abdWIr6SS-dE5WdV@CorhfxyWG{}@o)@N?x|}Kw@`1A4SChnM<1{~$Z}C4 zSKb_r&T`kq;iQ}|7%F`Lk56e_xFw+v*udmxccr}~Ty*eGMuD;Kw%PfxJE@r817m+Rf+AdX?{rT)`Uou9a5y@s46UlLra2i3| z#23ejRvIhb7Cg#}qxNT+txAN({70$yN6L_ix|v|XF_w~=QM)EUFNb1Xt;Ra^dP>BA z{~e7q&(PF3*QwEyV**&f{~X<;^{6Qk9e*Ro?fmSJ9)L#0IvVr4?AoM= ziB{SIpMo8vPIytWN&!f7B&Bw%%x&l3>6BGO;KxdJIx%_3J^1(9Pc-?XL>1N`Ar;|LQmQ+ipb^)j{C4|#7dF8y{h@NAijJd4O zKyKbQVc{!HmBeA~zO9XhB2m+{$TGIrEyu;QD@>~mN}BTNr@3A**5_&?OLMtVE*@LR zdrwyHFH^5lkk{62QGB_W5)qG11Koj@31F>kl03UhOmrL?BDPRt<>U;4H5=K9OI(JjP15zp31Cigpka zV)6hM`)a6KO-VG@AkK+@{O)WFl@VWD$d~cri45vjkCAb!OG7zG_Yv*fS-(2Nm^r_; z)bJq`W2BFxlTEN)xDS9*7*4i|FcxgT!>z;Ot4mWCSKVr&${&+Rqj;v`EcNFrsM;st z{FdG1IIa&x+aSo{;|hQ{ycD1%}nLnKv^7gAzYeK_3AxmiC9>g&F59f)}$bdhpg zNHEi^`6%VCzUj7wsF>^^pV#d{hYJe?GKA$TZj8P3+TJzcF;`41ZleZY-A*DB)N9uy z>X2Gr8!RT}dK}e%fAnkhi9jo*J6%#FqUz>{E*CcoBF|_AdGA~q$t*9Mtke!M?o6Rh z|1!rptLNNzyW;hD{QN`uy-gjibG=R`=L3(IF2zMogBab8e~?N^ll>^!A z_Nrv=cOb@+<6zLjr{%tn*}M(|;A!+=#YRC>6o>9TsK zl!*Ojc6to zQ@*S{{+p5XOrw~7g_oX!zQUyXRlrPKcgLmR%y%y`naY|LnJb^AAwxE>vc*Jo0_JOOy=|2NIbsW)FOJJSzIB>79H6`S5r`%JUSt5RN#9t%CWyRUzU3`Ejpe$ zC;Zkx$-H;s*LXEgs-EMdMMIxD6HiFPVhrxxMsBZuAI+A>^8SO5#{>7448XID>RXfV zpvnU60j;yYXV%wKI}l#*DuOhUEL9FmT>fDm1iKk5FB&p)y-S;3`H*C?ARUE_H5g}R z3(JdAjLYNC>;~HS#izL@2Q_d@wAZ@AtkdtFJH;68HeCrMmedD!`?2LWh`CzOOm)me zv_`?GB(-Z54cTl1WIq!lI2wC1LR_R8FI@BNbw^h&k8xT_k`8|4D6D#IZ*!v9BI8zn zd!+_51z7vjluWWH9T~Uwwa|?Cjf~7uVPpYkW%jYlJYLHT&x>lEPgt>{-$pF#%DO11@8V(Z}(AYtP(@nVf8?w2yTg^`X^*B1K6{ zw7|adC2H44%9_+sqdBlKyEt%P@C3qj7&Wn%v5TFdmTJcHp@cZjHB7d2b&_K>+fiAo zrGqt-ZZ-^2hxL_pp{W4qA`q4IB!9tB8a;Hb-oz#9W+9~!9OgtHz2erQ0BcjEgrLVxCD;Y!${TwIz?C=D8)A zixiG>gxE%Bsml1y0<7$-f9|;3bn|(0#t+`+lY>`6Jo+2*m4`kaCW6sp7Tfc)d#sAb zCWkJBkCZPBa1bdqWyp=j1gZd3C-l{E%o?OBy~$YE=r@Z@UzV)#ObYPq3>!x>t7DT* z8Q&?c5fBLLcf1S=a{m1Gaqen6f3i~>F7+{q!fgH3la{k-DWon_v-U=_`9@@}Q&lRR zpXzY*@2xwPJ3nRQG?j(l(?UL|*6#&DbJwYJh(ZcfqaUusfJ1Eb>n@Cv*aDsF*Gj4m zMXN^Pg7nlxw6ddKtfZcz^k>&*7CK(>*-j(s1M&OZ7qJ@Uk(K}-kEKt!cAyXxG^#L9 z%czC+A(1BGm#hqX^WO+?Amf>31sEQ~!kdQf-8#HHtmMfo$|o|5xt}c(%ULD1y3nM5 zoI2;L3fw8?eayU4kd3}6V7}W%=8FZp_>tO6QTb6epfIibJ75b>FQOH6HG2^-7nJz@ zAgYw`MD+7VdtqS!^f&lBb~P2Mvw2_L`7nl+nvz}|Opz1h7CE;MqvP6t|9pG>lt=q% z)-QUffzaApZ7Il5@7q(ruPHkhS>C}Yc}#{>gy=`z^W|@0DR3LNi%XqRubNASUv8V3BkDXSZ!eQHf~sSq;D0 z4~CwVFNR~`nm4Z1`-U5=PJjr9_5FGOt`2_yNs>8$zj|=XhXGl+ ziuX}pR^mBWANXf!#!21tTx^LO49Mj#7eM#tAofpWfppH@4QYZ#?huz(;VQIN0CZrF;bskS1!@ zT~bTL z{nXcECtWi&WqHQWyk068KzUL3(bT6V04>G-20u^W$VN5v3IKJ=^xa1w?sy)_nJDZG zu5|COT&{R3TbewYNjdgg<*3H(IsUF3=8FZXQ*{p?M+ZfRIb~bjaS(9Gu|O7>VJ2=< z={*y%XFg0$|Ap@ea^`Bqs&46MBHE}r03p8E9JtSOIUjrOBli%4Y;4^HtiSBGK*1mu z$ECr6&|8-&=>?jqq(c_?U6CQBU-@SSE0bl*r1ePctvyzk0qZX|8(i;mU!BokrO1st zv5(`f8hl(1o$1;!?5fFrw$06a@(B0f9OM&pHwHm}_VhV3nVOe6g@ zy{M3B(s!(S3FkMc9kXLm6D5tg<}Z5-i7QkwsV{I80Lt>pH}v7=F|HmI8-6;)kPLee zo{!OB^yQqm^`>&UcAXu&k{DdC=G@@}+~|(Vlxt-ms) zcX*Pj+9kc^>xY1h0|;a35I3yFFXU#ZzEeKmcHx{e5LZx}$e zdDDYTd5zYz)K$*C{pj$Wo*jEjrAf#uJdsC3!aZ2E90f6wUDD#2s%=R?__K^&JG=rp zyrY*&UOfCApl!&Z@j!W9|Jxt|RkGbbg;aD%J2*cur@*HLz@I0}ZErDv+&qBhmr$}U zT#O@>{=xBN>Z!G(wwTOop2do!s8Y=@fvJ9mZ(o#j&Q&tVQVPOyhq;sU&F-;kkvH^O z>&olZx}i|GVfey9g+cAEa-J*{IY@#}*@A>5b+Gn`07XM;cIkBd%~32vTVr*~c=9V$ zTrwQDikf22L<_BYS2hlC>Hh>5;B+(Xng{#YA}jKf8)HSO>076tKCjvK%xvqS6}`C! zeVP#{%u(ix2dyR>5)Z$PPkfv0G2oup>f7g59Qpow^>k{gdBwKbH8q2MrfRGg6ma(1vsefsu|l%@a0J1M@^SdZ@<+ zq$ey^SC*-t8mYuv#X7`n-#Ju$LEy_6sPEL}Au+MK0Di8OSFU`ZV7#&_(r6m00m^hw zJQRDO0vkvzx--mpORHUQ-oN^$y6o=Cset7w#TMG>9@dh(l<5j&no+DbrapE*UC}Iw zT#A-Jn_O(!snwi6ni4E#RIMG>aXYVUX|irT#|@Bznf+ZPO;Yww&z87+->;t+WeRHi z>$uB^!{(;s;4oTCahPF=E{_N>-+h(xew+0yoID7bZ`c7t5CkNnk}9gA4@Tx|M1-B} zUYFqbuT;g1T24(VpEX#c7~VAoMi+Nl>7H0EMjsb{%BYE}RIiGFpH zvMOhLlq$0A>_ybraEiFv1uR?b!kw52lwHy2lxqaz)uCl!-PVUq9XhcJ|x>FPL#PcX?>=>y7$SAdm(Z3jx3W*eeMI=ejDqx#f%=dx# z0D}?~;HpVSB_TCp?&#R>b7}T1;+isdRM3mJQhDdm97ZLnd5Yu%HD+GMaU?yzT`2Ln zqP8xM1j==szqv6$c2GrLe(&>X;1$;tlo)}~H(L+LNu{Fudt2db`z3Fql0vFj&sDgN zpg*%ZK2MeYl=i-8z#-PLo)1A61AGNa%qwr=e6cRN>7-)IA)n zxJ?w==FROmfsV08Q4VOv3FD?ObIA-dlrg8ZoaA#$%M@46%IhlBrV1<8bvGxj zluSMa^8etbS{@aecX!gr&0VQgMw;Vt%|j~i2#_yruqqsQ$m(`KaqO`-+(DslVz#Lz zFnfcH^4v;9OQ_8Cc%fDg`*>b^H5|j0nMd>nqE=oz6S4~ygCgq6MmFXZ_SO5rI|eH6 z`IKca;c9$RLQJCQX1qPxBB-Z-kIK4RYhLA_J)4n6zAY; zbVlFEvbTZ*^Zj9rK+Kst%Rh6{mK-&2EBQZwGO&^W-US!QALma;o{mVp{>-%Z$N=} zVba#H7#H1v7D!+ilk=J7R?60!NmHYKAj7(uYgo(BYrv9W6NzuK&-I#TmOAz}rG?RN z>FDK1cXbzySORgcOjk`4o*o^gccB7H;usc8f?Z8LadE7}4o8*L1J9|LA5Eah8tW%u=Pqx^0a!LFlP@$|7=r%zp(R~w)X z2fuEZ247o+^FA2$M9EZR_meocNm;0@KMHCMmuq2}cRljrM@>#k7S{&5n2_*+!a-@D ziEoALtL?!-UwVwQy71I9Bgf&^y96_>HmxG_LbcUc-CjTUw}Jv1tEne{z+&_e%4iN$dAfschRk(EhTSBqWr?hwa(EKn zDr~O*S>wW}`(T7gyRAfINrlM*$S0%Ebi~WL8#xC8NUgH5*}*%wm0Dm@k+Zkh2}xO2 z30u`#8V>!EpQ5HnRR~%6vhtCrn?eI@xTic5CWmWD6?<6EO+7u^F#uP{J>A5g)N=`F z)C2=;_Hk?_l4;1jm{TVV7M9X|WM$0=b(nxuiN7q+v%|=a{Ys$trroy3^m&FB2I*yUXU+@-(E2Fr)+mR$=Jhlx4!c&IF7BzUoewQm&>YMPS zj;e>4*`f^H$OjrgvStcpmr(->!=T)_TJk=!r0GNF$fSJKQqNmQHyFxOz>SS=zHAYj z+7-7lo#epyN+VRmK|;F?mo)2y8yY^Zv!Q-^1Sn`TQ-UAkQ}&fZR$k`;~j8HA3hbvK{Sp_26-SWe%5MDkUkg3*|#>ck4W?o_(%bdF*q% z_5h90i^td!q^OTyBptI8O(4U-fPYPV+^Da=RPXNn2-wi^FO?~QQ$i!DHdXM<&5|I8 z%b_Hfp^g&?*Ms9YqBOrG*-K+Be6sHpOg(e2O>j7_rjF}5>5Wd3;;{aAR*Q>1zdR*d zs=!<9s?@u5GbJ)=jY_$X*Qf-V$2oR0PH1>c*;*Tl2TmTCpq3=Hn4cRS2-9y|SsD^I z;V7FoL76jmSmis;Pe@ssV1-opQMH?E3*>EA7RU9fzk3012G}iE|((J)L44dQG z3y0-rNwH7l#HWoi$VMV8hl@(WJ%&)1+_wuneIIWg$!alDKu-V0XXhd)xyD%b7V#A= zIAHymUI3ghl`s}B$gv9^M-SmwH=VzPUn7API68SCAwvAlAgCdBtt{g@_?}`Vk{G~e z6UH(r{mVP)ii$uS#<*8w%&#&apr~9~%Spc^g$CFJI0mHkxvW(u#CMDYv~c4xK8oZ5 zTh{bpp>(!HpsgnKSybl<;p)XQcDjY*qAt8d{8a2ZoyzVl`ZD9iCzx76cqK_*+XFt@ z^Q~`cKOpkNbo~PL-4ZfIKSdTcTC3vgqh`$l=0?4flU5~I*0j48lU9+hauItUC@rI&G}2xN69}F;XcAaN6{LpI+;9o;)X-DX@t9m zO{}5n1eub^eHsDlD>M^sR+4Cg%MMjGD$!9(cfWi*yhp!keh8!h*SpU^b$51kZnP`p z_AJK;#R27FkXM1x%~mb-yh!6GPS*hdiWX!ozNaALVdVgt^_TuJb6a?X<{K)MzTotDc~X&nz%ATgb0U4{qzC zJ7i6^T-fB!K4)?|1sjR<>~%>kiGtwMqz7eU%6LlDXbQC-6!(wW^*)Dk&J-N!n+ByX z3Xgif~oLnmN*B}xk;Ie&Bx8V zyi^?KDpO@lfn{yeptza$G;2mfwl$QONe zkKR{Rl%L?!3&CL{2dlb4oi}v3X>~~nRADm_P?Y4fgZQYz6z-n) z)`OMLfJaZ#(yMTGMt)v}{EVz2^731#hiNU0<4t82EcLzEEI>jchXx5xi;?#9P!SNZ zvjCNrjx$m~-t`NwJVDq`f(>t9drp0mj2(BoGvX6JCcL|%FFY7??Xlx485F9%8A^stxYKefy_SQ+ zmoer*DvdY7xKj)>yCO?ySENWk)`T#cV_MrZ)zxDj3bCZ7N*hH@-Yru&TANm+8424v z;0AIHO`@XwgH?qM#3p(cMeLc4>MW5QIovnQ=LLPj$*hJ(i1)tg+cgg2H0nq)QZ*yW zYz5ugGWw{w7IHsg3qVuXkjdJQs*G9r*SJnl-;9sC-w8@hM$LZ`GEJ>flf)9ljI(^N z#Ej=DDi@Y>!b?-%V%PJl-eUd0(`-+VWVq<~weE?*#8=QBKux;UB!OvyykX(~!wNCi z())3qz`bBWfFIBz@-?GM0R;DTu|v|ITy0i-L?^#QuI>-$g$4Sn6tKIsmw%}sYToTY zF*fXzeOJ+zW6>frR5yvcpp%g!560DRz-*~hihGLQ)iq%jxrvLx`e8EitvkH zn2e+|eYi7yWD>hSD0@feg6)klsFY{X6f0`Jx6DtrtZx_nlFr+29hcL@h${B(o`U`u z4;pO1f@};($9KV)GMT%CTFHW+PL!{%yhkqFmR_1Gn=5tD-xrS5w%8AP7F&<_WzYnG zBSY4PPo8|s0c`vc4&iCE^RH}svcDV0k!tN7poWf4yI^%p?vRw*um3~Lt98g&~lB$`BXg?~B zO9#T>^;7XOq3*K{XtF4d5RLPlA?3qQqxRX+R(N>4+0HB^!B(=$D85kB9mYSY2VXcV zo#f-wl=nsYR=my)Oe@TDA~vmPY=KBBm$g6^ z#U)#sQ-}-AbQ_qwybATrbGA1{3#xU3Bo2e67_8`+aIM^Vu-2H%*Y<9fhuMMM1N!{V zv($An%sh-KJFG=Yss+Wd&t!6CvBVTqcd#w#J-9XJbj03byIc3Ap&I!{e6FNon`Eegnmg7Yw&$c=bpO!5Rb}<6qjNxmV zs

      l9mpB+Q>^fhp_2CTZzvacYxiji12X0^CSE-{49X%04_NnPBQ6dPsn1&wcidWy zDy_(5UY+w?buv{vJ9^3>OVOyj5zv3n#qa4)EP}war^%hW*XO^$f9(w81odrQ%&`}2 znb<0xDx;N1u@D8So_4z79IMro3=*QUO!qPKP~Rr_z=PiX8tyH*=3&{=7G3#Qiv!Mw zOim7-cji=f*k=oOGd#gwAJ#Hxmyja5A|?;AZ3a~eshcKSp+Y9tThMbh3fBd#p0`7* zq9=u1?RtQdYh(twg=MaC9qJ6C^4i6B7dg`H%z?P?OOYE*hjC}8HO6Z9xPPt80};Lj zhJHp4)WNX210qe-bqLw2zUKuwCQVg}UKJyfh7(ZR+PnU4q0rZ{SB}^2-(Aq_GLjzC zMpK&>BCM9AZ&cO}sPp+d=~TqB6-Rvjc%m^ojw*sg3C*NPLTH#(KId{!TLivfKsCO!vfQba|%-K<(O>Zx~uwoSe}oThY}${;@^ zgGl8UK(KNtma~oLwPW;6$4)21TDvOsu7oVNDLd6C2lo|~kTLfFgJ3Ilq>uaq=y`9W z-eafXBbuKS>te=sR%o`ZvTWW>S2v8R2b_9empIWTs%ksU1Bx*mm(&|Vf^={lUzFfo9D;Zz7Ep%?sjkCs6IwA$?T6`KUJIiKey(YZ;4y6f2EZF zn*1G|Y);zyj5@zzsV+W)W4oH5Ubl40m_F(hr(TDS?tIgzk|JBCMfo#A%SEX!Chk_M zdR}~4|ii!`kA?rMbF|dL5T6<^S?>{C)h%9ffxv^uq zbO2;NXj=|#&j@z8`I327!(=k6#>B7YCb;9xf6F~@%^lFy3hh3Bn@qGEq^V3m$GPX2 zC@y2R(!?83QkaEqT@r~unYK;2*~sgIgBpcXrHxc9hC{OR^`2jT+imWNI=K{e5Z%F> zA3toO{aNG9c_Hf$5(!QDm&3BwN>jJK0|JaQyW&gYM3bkcXt?V8WX3=PdYAA-Nl1(c z%J!9Zg?RT+Q=I-BrnpS-b5V)rX>hcqtmxsE(#}ll1P4GbM6uIEV})rF0Ec%T*Ooq& z4Zf<0&<*P-FcL)WHyUVwVd~L99Y%9I^t6jlBkSwk@}baV>Og+4qxKkecO|yicCUK@ zF#fhwSQMsgBn7SM8To*UNBr)f&7Der7&;s}dSEVY)LI#~RZ>6F&B|VoGBgzUFStR=;L<~f`>opc&(wN>{BkEdJ$*a0f-P}-HU|nCT|^uuL7=bHwb0cW z09~#8xE{Fbgqv^$hez3DEsMG9px@XY+yH2|t-Ig~glW6?n(IAB9653F`~+-Fk-l(l&u8KzDH0-i&KA={WPL&Ljk6eVZp$?Iz5Pagq zbV~V**I6K3H0Qz@dM=El)_ChxZ|0>B7l2{6lRO&4_exSq`E?{`-OklFED)OFcU`IHws9`Fz+z0#t5k2QI{P{QD6jrK3 zCpq=N6rcRZ4!c}+=kq>;B~bUf)*m(KeEMCL4io$o5nzhC*0HA+vZcKOj+gGrwj6nK zLx^-9I+G|0n&G;NC(0mdS*5o&M8Qn-m$4c-#p6XRJs=f*o{!0Ui`OaeQ8yaf=_-ul zNb1+>%OsofB?<85)4fzZ!iNl?Q`#}^77f6aKXEB)OdQ^;#kVfz;9J<>Lk47KG@HrI z6=UH30$3jv;f+U{4oFrHoO)&fzVag%@4>-ox;S%*dY!bK9zdx6nG2$M4$fkAdkkFf z$sGR9%Dfw$Z}flr^G1v00`80Uvp(WWr=TNK;qKtbR2N8;!PLvaK|%}A4c4Uq>wPfRlg|M) za>Oa9gD=XG0oWoZ{#lU_2LHta{$5$)m}SCw@=_TX-N9IpQ|J(a%RIX1Rnl}jOwWZ0 zGTmWqyzC?3TxWg2anVRo+-Oc0=$JPPvwKAhGZqJp%xg8>S=Ul8i8P52ls(3M4iN}W zSrsuaMUk?^wmTT<>pywYo5r^hRLQS98t@gRMYG?(?e(4a*|Cd*b9SgW*k!l)IfpAd zwJTS|J(ipq+bq!~g3t-R5ZO!PiE6&&li>VkW^O+Kfxa)EtzPAg zI1j$M8`zR1PCc4%1-g@68Xm@J==+OV>{_O1o zFK#hRT~M8nxEa$jnw6PZb&v@(K1nzK!q+_3X}~D-+@UxWn*I{SrIH2U)$fVL%z0B= zy~zOe&N})s5K*Z3z66Ka>cF}4yn3s9MWZEZ59nv~vQ7UV;XT9u?Xb0MZhyZa%{55bU>mcEKa=V~Lq4|T@ zO>Hk31z1dA!eK-)JkkI zp5Pcwg_{C`jY2qGCxXHl=*BUx_4)O}QFx5epU zsIpTi?R^Vsq|VLAV9jy@-^=I%XHT^{xSnjIo3Xm*7=ofpb`r_CIy#cdbxscCkX3kp z!4uqDUdTv9`yR09wW5DZcO(mbn+Vx>@gQ;7Xm2shb@)k`P-+S*N}!btJ9QUC62;BQ zH6ox30fzRrZUbADx^osz4P<8T%#u^cQxoepJg`fEKCkC~$6>So-vF=s`_^Z@e?X^K zD+Ln#jHBwjCgM{OO~xSSs{+*sGg7oz7&&~om*z6a?g(4j-?$A?`2j>_&;FKyWl`Ty8^&!{HXb!}7;6hTo$M5S4#A|Rk3U5Y4J5JW=gRRk0W zErcEr1(EJl5T&EiLNB2=Q9vm{q!S1Vgh(g>Lg?i@FQRji%y6@|{g=LZ#0L8C$3W!x?V@eHikS~Jpy;7n#z(0DsvJ7N%kRc2=z>nzs z@u@8v{<}W)#zu_7>h${wKzA9`=ooE@DF8sA%WY-5BS0&~3hMNre3a>U2fnA}EM&&LR21T}?*1_bxIKJ541o|*4ZzNhr zwhE@MMrOV!`Pq*rdxJ%)+)DQze>Wp&vUJ0xNvQa)!um{jK`VL+2}P8yPM<9vWL9Si zU%cB1S%1Qmlo&hx;LFdS8&VG(6EUuED~(Iy4VRnOod<~fUC`CnU7<+!J6ztR^x_BC zU5Z>OgzxhHcRSCe5P-S~YHfEQgkqb|x7d3l-@92q3pw1G7!+LF;{gJ)q+#b>+s^x~ zdFBoI32PHpy+Hk>6T5`MBZ|d?#xrr}0%~<#7^S&}TePVUfUL6Ws1SV^ z8Z(h;F>;-}lUYlGIO1JKY<+C?@9aT;cW;7FK~cYB12?uF*%sIc=l*14;&uzJP-|5O z_$YAz8=G}vPs%hsT(1`Aet1-8F%vzB?Urb!_HqqYp*=U}LD#vWDL&8L3qt_6!M=&w zs!%<*K2Iyv7O&S_S^@VlU8?wg0AP!IsJi7`FQC^_-YWN>10A#I|Fp1To!4`LLsr#& zFu>;{He5roIyjL@AWS5r#`n-=O*YuE)$5F5K3IcYoIx5E@7`(NmCiGg!Z0ea@4t8S z_}iXcW}lRgnHvtx76e}j%w<;KdZfzqAp+_9Ckuyz|4HZ16j9Q`npgOOn`>2T^F=XP zG1>AJ{joFW2Vap|$K5SmEJ>BETR+d{Z0=YBCHr!kB%Qx2IHLId_U(m1iue7r@qWFp zo69up{i;uVlwf|Qjs0e_8tij>b#ichvNqwQ^D_A87sNfkQPPju*?vCtp%egta+BWF z7D-NY?eIL_-h`34XzU6-Gc+wWk%)*e;_z0@I%;5d>p6-(Vjs`N5-VCS##{O6`P$B6 z04mz)R;V7%3)Sl^vWi1#&q}!g7x;pyYQC)~R`kS0&ahi@G_B$D7fg)lZOmDCK(dk= z?T;YW<`z7FxE8dD`H^^?dM26*uW;G-*Y#9$ob*Y$g7Ay8ALDbqxjmM8?ujWHg}sr# zTxmowuw08ne|n?l6Cj_1z29`OXkZRV03H^>?@S_CFnAIMFSU!M4gG)}e6u(l&{!I5 z+ixSNjR16f>e3yY@0!N5%d?R$oh68)I=wBg9>bFey5}$Oeda{ABVk8a4^@B>tEhR3C=2{sajc?!2gkdn??^JcV03-# zJtoW4`A~;3072>*0+zGq`YOl=ikXB-&2>wNI~UdEXdQCp${(iz7K#YwM6UqMz*F+> zU>&-v=Vbvz9M0H=goAIq4B4moVF?EIQQ#I#5Fgz_z!!dlq^oQTU=-Hze?1)QIvgrl z#6*2zR67FZudK076pT_OIu>t9dMJ@`ZJ)a_=h}m*q*}G=DzfiAqB0{b+l%oK=hwtn zJ--w~bLZ)@bGp3$iN>oCd(RxeaE_8&j94XI_3N$kSRVw#wPTF=pX(B5R|Yq{wZ9_{ zol$FvD>F4JH8Ok36pkwbCclus%!Y@AJnF!}VTp$FKw}(wrBwj8S2wlRo|Q4Q6NNN} ze;Z?*tG|)gRB@u>B~uCuH#tj2JEvl{@dP=3R!}k|u00@DanegVU4sIV&AC74*uVx} zhO?68mPVet>KwB7P~HaV@?5v;YB+!1!~qvnQ!uH+N}iA4%F}i$#pV#F8xGwPbSq1+YprB{8eOi;^QzcucVXyvOK&cFponTEW za)U%H+<-!t&E;Y>!FF5;-pi*h@QpCuS_s(^d7DNS1VL7VKh@amZ>_j;n>5V zgw+u~S5gfaq4zoA%#9p|TC(v48Zfu>jVmAcLWe$Ju1aWUr*Tf@5Ajr;j?KRGGo!tGUJ!9k}p9PKP;uf=iG-pM}t>UrJ-^nCB#bLcA0bmZdd;IQr!WWDc>UC%1ROR04t z-g!>S{rwK;!6d>`{o^`lek}IABTo=g**$W$jB1F>;~_#K8<7plVNEZS2xTIISA5JF zDA^RDybZyeihPn>(#51@`5c;8Ntkheiit@mi;SYbQss_BVc6S8mPh1Pe!|rAOeIyK zf`7+eH59 zu1{H4-@fJdannKh!39Tf_PSWgszhmqU&>j`Lo7UroCYz(^(h~L6!*EOHdWUfZ- z&eP61#A(*R$opbPIC0&ti6p;J+GuKptI(g<#faXIZf)wqqc*f&dTDFh9g`~x*O&yv zfaiwW%dFv}OA_7w9_AamEk*ZN-&A0vBg&WOHIfMZiuadRHL*usxe`Pwrj=e?=i*>} z94aCfVbYeZODw{eR{N0p%`})8sV83$BKLoN=_m*e-Ip(TAlkV z7e<=!8_Aj~mgwyo>|64)w%7;b8Cg8PU#nyq${?{u9pLx($WVG*m228DwClpb20&ZfH1c1Jf?)XuzET%8q zvWHBj)4k#TgHAglsHd);nS+E3;v1c6>xglhFA5N4M~U$~88`cIpZb?y3}g!=CKPBQ zOQ#sajh)++KbhLM2jzkQCGo9O&r@A?vT&raP>m`*&nwVjfVD;qEW)`-Mqzm(X#B;XvF;IfAV!z&b@ZQa= zMNSK-)8T$4rNT)&F;k`@<7|x5QxGPFGv>4zf{}D>L~s;4%*!oC@8ibu0FP2Mb)u>` z-AUh481BCw)0oLbb2*ZOIY$Cvq`M@45?qJavZmn}CO%STrh)jap^MM;mx|My^OP## zqz4vsGwCz7%U>=fkg!$Zz3_M!;|ps3;Ys>0iok{KLwBz{wNy@QK=` z3a9VFebB^7atWAR;=rVhU$uRypH*U)aLyfM<-sSfhE1${uF<-KSEkByq(CE>4K+)F zzfdzPli!hDCr=Wg}0jd;AiI9PY5PlqU)K{HfsMjHsdip4*)EgHVY_MC*f;l2^~K(QrH?KW?kK+L zAkrDHl~!n1*Q>SPeN=-bRotHqhNk5AA;OT>G1)KDrwyXEnZwgOk37O?+*Qvl$S|MK zVP~{udLja|>PEv5i0BMy6uh^1Z*2;L}X}Qb z`WBCOUHV;5T0#r@vXe*4COk``mh@IqiVB5*8nn%KAzC{Hl~mgi6je|LOUf;CiM;H> zyZkvI2*eSIKZR%ujPml-X0f_`K8x>%mPiRAP+=rT6!$*{TbnrWVIn`;Qk?|*R+l1A zj4&uxgQvNE_b4xvB_e@}1v{wF$eR7N@`xt&xcB9LW>%r!4_paF2QboHmcCpT_`dOH zxYt`CLm~NsC#J~4HSebXvvIl&MC%4(KTc*ma|qB(naev`vZ`=4h(0MILUL`{x^cb~ z!A5S0JbGVtSIf1}m@TRJB9$6iXV;$J?_SL{gB<^qmQrPUqBgIfXT7s6z5z2C&Mn(@ z-zBv%W86Ucuw*r&F2V=KBS%g4gx4~F!rWSg;btGJE?3@m zv_`c7KsUYQ>qF-G!iiNelN_$aMXHFTp;xpg_F=5Ew^qaq>H%09IEec2SFhi_18t3%JU935(XIvhM+Gi+J!$;g%E7nQUellou;(Jk?fG`;kx_4&bsgsj zo)n{^MZ!Gqa_kou8nLQ27v5m9x)7UZ;-bFL84i95+}wo5@K_jaU9Opr7`=8e@h|_J9P>W4YZYn%+ZkB5-+%-*chc5ez zSka1i=kH}Dt1*Z|HNwETud9OWx`MkLbIQn=6Ma$}9w7DxgRC%N@m9Kn1EvZyQwkif z>yAnz6W*ndSA#h1N|F`fJVyS(`N4DF8x=p!!1ItV6e>`lRHX zbh35bki5>LEGlHPvoGS>jmCu*l3Pl1CoAsB&KoWN(Sdi-N-1B1f~t;uwS`jUlJ*o5)n_(y zFfZb7P3~tk2h>f1ub@VUa#qQwGLk2FY^k3W`;~hlKbm^ApTJ5M(fmZ zZCILZ5)nD^N4y7$o7&Ivb^_LLeIRe}pg@j|YSc07h~kOZDSi7=kqky~oA(ovZz)xl zUTvH!#)Fc4EL;)E?C%j1sxnY}Nlc))@kcV@E3_ZfSPYLcgMV9Nz1^&_oVSU%YVKjL z3R#9_bk+OhFwKJx9lES3IDy+040|^iV^@|g<^26KojFDUf}4VM_qxpkCs_~#2JA#8 zbc|ah#U;|&{Yk~a(|7%3M9L@fhrp2eSz%!7eaEL{s$c9?#2t-fIBC(TJ5Xr7_5N9`;Qhrf|9%Iz?aN>9 zFZ1@HejeQfH2-CAh3JA;5+NEh zN33G=tWNbTdis5Z^!4rl)_zv~o2<3W>8e`$ba!@?mj524Y?Sq&Xh!vD*Gj0p*P9aJ z3xj#vcqSjxi&q6k*6MZM@CVuyz z?1cN+dsd*vV0aCR#=CW4mH(c%$BR4nE}YZJn%1QiOd`lROwsU2Ijyu}ep@J;=GZ5{ z_*JPJQ=6LJdBZ9LoANLL%nIr_0;I7sAI_i>rPrBnO&m6zVo;VdzuYX%{;qzhQ680D|a~D z5|*$mBcvVLE{ew37z{As;Ar)hck&M#;KwJ+s$6%6b-6nW+4o8hU zhl|nx8(;X`nMK#X`GRl~6(9qdPt5PX((&uw_@uDJSNDl8!7vt3RLeIOAYYITTseE!%>sG1E#cb=gzrh*1sDEWu;QJde9hguGf~iZNN_{zj zz&z|l9Un*vDWh*Kr@uPx@Rv2isiX{(HETyma-lVN_Ay)#y}(^!$4Sm&;uKjSXm$>k zQRl&jr+&TZ+yGhk8P5#M-L#^iqu%DbTBhr*w}uXiR6*+H5?W07S&9F!`X3cWuJmT= z6#+S%N(*hRn^}jC78GPRgMgW?XhiP;MQRR^WlYxkQo#r#JBOjeCE`105U1H8^@qUf zt7%jK>-E8KpyRE@CF7hnlX#N>_hNSyTw3LFG+i$G@gRmS#b^{xPv0s{ie*?hVhc++ zx+}46Cx1c@`p|^kZLP@^`1a2|>B5?tOvZyI&JND*BD=AHQSEUX_ik-~aT<9I<- zy^-g$vEJ35I#u#A>q@*pp=v_kV~;lk%!02)SZ{<`2fTP_1{?~l=B8HwbSP3j+EhP} zf|vF9kC(*avC&&DZxV9(+{2kszjgWXn=UU|!+wD2EhHe1s1X;ZVzf0g4a_by9ue)} zBu2eAZHtHGw;=G)?KLNBuB^x0y~*v7OqZ_K%s`3pin#wHD^48-WhjkZuE}OzQZ|F? zs`vJ7FT`+CZvZT?@6d9ag#~Z`?&=BpC%YyzIEu0i{L9ohG5xPYQjQ^PVeD@wzEs_7 zQsyu!w6eP@hx#_O=n0&D9IX3C#8;yw3w-ApUIqqRXgpa;F1dGfTo_G00AR{gSLt1T zB!ECvI8?1NR0)>ZA7yP#cu+UPL53j}Si<9tw|C$$`L|nR@$6s@? z8UfeHnj($B0?KYZ+Sc2Y46*Z1>7c10Q3h0o}dZ`v$S{Lp^P{zjpA(A#qcW7M<^@h7>5irRHL^ZrquAMzA)>@hq2=Ln6ElW%jN2yc^^% zBK35%{jNeBpA%u9Is|bH09$OelPaxfoV8s6>zi!5T@M%8xTi-3n;dDoT zI9+C1eRCjO2}+O}r{T6#gKC;V9kh8M)@$}t`EzIjy$-a?OgK-s82LJZBQ1o`5bTHVKX_J=^ol3Ut;p-Gc9!K4d>uIlVwndEW|!PKuElLEQoZUlQ?p~=A8Sn+`>*P$ zB@w|9t5F5|mS)0zyj+dz#(}`92%svJ-rX;SdTe7e(4Z%31s`EtSfAnDaC8KyiB7i4 zQ3=+5NWR#_b59-DM6PD@ed@+}apZU=LSVU#!i}6R;ex&bjPAxcpM*n+M3!DP!%RUh$1) zn}}-&S6p4q;J+w~myk?*6@60e9YKOBP}H(_uD%GWMJLDfjnxw`0EcB)-i5!5KRAKt zt6p7@puSa2c(I$NVqnfyHSI6b@%R~juC&FoNrQxyn2h^U1Qp?@#a@6b&^pjPCK$Czu2VoM%JK4~?(*}5)wfRHAMdHIt0)7WC|~Dmoc&#T zVF+p;Dj!_4a|Gj6LWMp65xsYX-cwE}_Nwznkwk)@)c^40{k z0Y7MT2nHCX{sbKV9szr{Z6c|SNrc|Hz-<$tbJZ*0AYq^;uH*-JzV_m54U9AuMk?63 zp;k1W*TB=nQcr`cmma@8B~;v>ZzbM$`Xl3ksFst8uHXDQrg~{0{A6;)oCp0hQS?{e zUHK&VoRIdD&_pKz-I7KPifF@)ftN13+qxn-d;z&FO2^JFTBj{c1U;r&2bvVo5(Cr) za5QB%Uhs>AW#|%1@1sUK4E0k8T!r`Watr+hvJDC#j>a0f6bG`G=75C&LtO^;18i69 z1iLlu_MjMPI7@ZE%jW(aQ2WXakgFE_&Y!%8sy||N5R`5AS+_Sc znz*=!f)ddMfbn{tB2U0FoV#cz;p%?T5DheWg?Z%)qZr*wNK-MWdSj)UV(Sf|AHBtP zwC?lo?eqF(01g0Dc0stPb@ThyYn5Q+MTRBx#oeNQn+Dg{>Ji7KMbLVyrrvn#c($%F z%SfqE`nfRO+w(czi|=_4T@B;vWpfHm{63bNU~C8)X?4|0k{c+!>Kc-kl=?zU@vHbn^{hE^1y|o<-5s)_bZ7Q=SO<2Xdrz{R`toTrNUV!=5 z>0Lt}dQuG_1pOSl7KpNrU@$bnvUB=)CJ|;@Y;2tWE5Uow%T;xk@#cm|AlUE@{HVPu zc!PIJm6f;WVNV~W@cw-fS9VS_!|%Wn#>~_Qt*+h3{=zK={mX3NgT}&I0z=;C#dXic zl*$P?f3|J?wMp|_82GzmZ0GL>gsT|5s_@0XR)iwJ$bk6T5z}NsVCbKZEbr|2wIj3- zfXezS|76KnkyZ_<+(72nlF&V;f#sj;BQPBzPlo0vJmk8t_V?{j;L;2K{5F3t5fs6t z_o^z7|FvbT#u*&9nyan)U9Panij=|T$@@uZ~bs7zK-A!L;u;Du{oiy)PXAH z$e)d!a_FF1w+YhJZ9}*&uyOtxHS975bxYqr*?g6oOea4$@a3QgGb7)+WSzCy0iXb?oGIQjKVFz21_?o5NEoSZue~Y6b zC&Ayjtgyd5sYH8lZ|DD7fr^I?%4er;Isj2e{wpBr^wQJ|mS3!aM*ycg8d6mJ(BH%J z%|z<4U1|zpH-7G5ZHCO~_iOL|Zbp!uoihT5)Xp8lb|k=DHfKx{>8bxcu{S=i3%11_ z;R1jED~0%Fjz9hfnt2hh^KKKj1_SZJ;2@U8YHn1rah}}O@?qz%VKpo?;WGbgC2P%5 z<`33%d|8ew;&DIyD6q6nCSZBkb?dDlEpZEc?YRam2ygyB_Ne|k9;iCEO$R=u*!e4J zOBC$zO>jh}g_Z1QJMf$q3JlWsmjAxw_v><_;eYsKKb&ig2XxeO4L^C%zGI*jA3fC* z`%#Ju@2*z;3g51@t7Sgq*P6g#MsVL6^n`xvo4*?XuY&%y|FFjex>E_;waIZkho%1& z1by?VrmB!nN&agCqA3{h+4*KN%QT5VIJ3h4@lt#E-xo%A>x}+>17a5p{G4&=UmJ{X z>Lk)=oq2Ipu@?r`ZSOSsdGJYKvi3y>VokP&DYw(X*nmI9vbOR3)|HR!Ui6Y|{iMD1 z_P&PT1xqzE@ak!RSMn*E``i;#v+vAOf`FLhA9?E^DGpn>l^MNPm260c=2oPgWQQ_?JdXcuj1PDy=Z4WM z_1}7MHp?yj@rPvY6k><}_uu!&f}tdif5>)z z9(!&)_&G+cj_uZ4!LbZ@s1#WVK2eqi7vpyO(fL9L7)!L4LXp+Mt@pFdu8}d8v1_Dt zj^YI5w)Uw016JM8r-HbGe-Jz?llBfQ{_3oYen(~%CD)e_X-!Vng z-P>DRqiPBSe_+Dr0OywUh|S)DK?%fmm;c><(7aj|zdM+2orvB>Ek{WRmHSokx%iBj<7FmZ|`gwSu#U^#96hp zZNCi<`*oGTe|u_r;^(qpu*%mxCzdILbw9AeIR}{NubY}%M`w4V$ZZ<+x4h@a5pPyN zZ2PBIz33h#?%ula+2Ghu*Xq(KRhnP7>Kab@gRRkW>rY?7gLd+1|5l!tp0R_`&D+jn z>&0QL;Hd&9^Oh!|-*dQ}|F1#Xo;%wmPZ?ZXEK~n^$$wO0Td%zvJVxI4(r5au3$If{ zMY5Tl-JV3qdn-2X2z$2MLTu|#4&XtL*fM_i81RDD^cNK*<+h%h4m~yU&z@B<<_1#y zfr!5*eQfg{#5@z?@iO`yQ1hUM9y}(Y=GeWhz@IDlb*VHE+N)SQ3^m$ zwfIA#nj5k<^S@i0!P&1VcY}ACbpO_D&us^f;XB6|z4g`;OyCxr2sw4EL-vKUrJUUj z(Ii`yA75yXFnEx|9roYbhGHnVcqzNKj*=ZbHC6OL%pgk=C^z$Bp8Xn<^%Xkg0L!m? zlr#S0DE~2N?tl3JJcjKsz1r4WyD)%Tz*>J`Kbc!qrhrHC)GG~%EuXlP1DJ_a9@9Vi z#-GniQ~?*S{n3wqeHjFv3Of?mVjrLZ0zr@3r(cyu%^~Iz{@$T?-KgIh>P{Ogyc+9h#XJWQ$nMdG3M`Cpue*0d>G{DZ^(y^`eP&bvqQ`18} zj22&pN|lL}yT8hD(_r8?Y-hfX%lz%`{q@Mx$AGJ+-+75`%P_ze_*ON)JbFKmhG)3U z2DR&_BU-lp^bR~|k9sEEZ{KTw8nE#Gxvf)90d9XuOXUs~e;gze=Ux8oe*W!#{#Exg zcWOFZmSIib#GgN)MjN<~s>t_M&(xV|*?yH}n*TFB(UdBO!p~WNe|se$?(#p|E8W!j z+N0jC9&Jbcp~>mNF}+&hs>z_u2xTMICI8Nj=>FTXqsfE>Ui^L9b+&s;ci1%7AO;d& zxBA`_Kk^d{ln%)LOb6oUK|a6`UhyjC*`Gg`S?$~pvVv`x6Ti)N6ptBzz-ueOxi!VI zgBhfi=W>T`ZGK46|KEN{Qw06GV`_4Bkwg}vTcfoV@7}xBLO84rUih1Baq@_{EVms0 zn*ycEBiGFBhEnd{M4+}37Zj)qnzu5^|Co&HCWFi=qeDk>E3p#+SG&QAB)D9^-Hm+GdINGJC_ByZJ# zH=yz`?Egl2xR_kCMB=DZSW8u&;q%cv$YJEXs^Ib80TBJkz=JM4lU=>;mJEifW*jJ# zRorz?eP|Qgp9V!jQ%= zI;)j&8#4*6>uc3~>u)qDOgmK~f0&5kx24kSzrq_7Sl zu9G%atAm3@jBgLiXbX1WS#frozui;`!hG(Xlc?Z_FdxwJ`d2X)-9Hs+)|J)PpHt=G z2YqJw>iYaV{XKLpywdtH`{Z#Dq_Fq=4A3tez{|m5P|&v z=C+B$nQ7`s!@{6#zT&J>MeVrfU2n6ZOWVM~*w0O?V~|Rf&yR-1EhIjluVM!5REqjI z%?XxoJe-W(Ji=oD(Ed;Xpldb;Z?M1h5VV~&cyks9@S=ku%7ruaB=6ESN1y~kS#=(+ zs{{K~j12*GEaqeGtUM5tHW374T~+=rnX`liuzEpx2Cy*>Lc_i@K*aVCP%?3u0sjZ# zLW-pKuw)R>^+3DY#a0&>e&$_k3sS!*Oj_8Ib7 z4d2K!u!66pyGz;Jjb(jS6^qO!lao5zlXA4K8O50qXqq!A@Ie zcNFz}@$e?Y4{SX1TtH7ei~HkpMYxf}JBHHog?ytWv3ID1K}ViI>ZjFlFxoRkTQ&`m z@i=1Wf0pqB_C2788Lt8fn6uC>&du2!(qiw7+t0Zq$2xYMgJ6;?_1XhPW?v~B4vb{8 zbrS&z>!r=~A#aIOx%_mc88qC&!t;cSRZf(S+Dh<28Z$dKbIcw~;FF5o=Ncx*?g8R~me1C_oF-i0h);^am;B9s$&sbNnKdwv;`fRO>K@N_I&OM(nK6pX{4$Aq z{$f=V@9H}c0xY6X!mp#a!DNb=7UO26p_>j)Ly$O#Y4it9vmf$sKWBRW0<>+PDAG%c z;N9;$UoKtAHp*mXbP+;wE`S#;&QVl%@4rK->c#E97%` ztSd*RU$CQmZoj~fOAgdYsnp1Q@47BPvFx%CG%3EN3ocaz0ol~?fyz2+T!Z{g8Bs_ zhxLoqvz~skGy`@8XlGAzz9YQk#jooF-Idz3ndjdNblUTx*RIS?Y|7w;(B4=vt(~f;X#)SIOc~uxk$Y(BMQQ^5Ur1{nypTX98XAdpc2{;ZNd3uBPZBVSkLIGrJ zTdrpKk&1Qrzyh3nut`UTNXY&qsPtDZvi_p;*UH-aA zrH;F-3svh=Dtf@eml+59u@%CjBqkb*N`~pC|2P*7EauH^d$ckzmKf0g`<=yPmMZ$K zK%7f|<0}qSFb*mNQ3tgvSHS97eM6UC3s0rnFy?PqatFNxkL;WlR@0i^sS0R-Sp~Q^ zIl~1PXnAGh^pDe#Y}%~k%B9hmU?3nceI*82`!s!~94M?GY79)c>I2x`G6o;QfJULL zBTL{c3$J{I2B8DTr&OuB*Oe5v!a`HIJR~;(F~r(al61x=LvpvvhOMm^ZNK}RqO`Pj z>S(|CO{wp6J7LtehmKyKX_dU>?gOHX2O8A;+d+#}vdFB4oBgxG51R7;$=Z3~jHazB;Dv496 z-iKthsr@ODEGzK`%pb=$3YOrOzlcAD62X%0CWlq;trEI0d7zNbJx(uA%xI}0S529A5H^E4=bakpkc|9?cf7i39eyWi4@ zH~G!J4oKftUzAf{*8DO2h{uhrT#k(7Dj@C<_b8f*4*xt20(!yz#lXmSn&&MemEv)|J#sut6LOio6SB zG{E@~Os(B4U}|na@3nhHTU!8lNi%3d<)@z0Uu|eGjIX)9A1JL&j=@)>o{O$T>#ue1 z7`a*T!P4A69-}=rxsvJu8LnJLjxZbjq_AwLTmv929EP~Cd@?+~WJpful2*%mr~Rvq zaeSqY6~*XCl8N7^L6C2~UhNInus7&!>Gw|4u)h~cGK?9%D~1gi@6@H(zo#jFqSB>r zv*RUA%tl?MpKOt(TcRVbh$bz1$r>EcweqbS?==I7ylW6(?RcIX!8fR;74K8F`0>>` zp>B!(1_EOQ0>PVq5(uK1_vC3(&UUaWlzIXEQwq}n_*KwgyZ(JNNp_HbeK}{t!wO>}QdDE(nH zepb?So6mo zO~~|?MeUaN9gQhQ+AG2V>QjI~F;s-N8wa0$!SFho2QJw|6cLYTs8ChRqR6-O4HmvO z87Li>^r1?6%8o{}!~;!~8H*Q-nyTa`VYs$qRSC%2gTQW!kq@5N$o)KMTQ+@r4~h&} zo(9D|;n;*B^x_-dwRz&mY^uDmAIUx5}0HMnZ6%;fy5-*oJIapnNUpGiAt>FH; zB)dL~|7gc;W18nH(|J9sIPA21+)ADQV(&^x{FC$UU|65S&|Lll?RJQ2%tCMk+(@oq zJhvqKiHPY)h*`Vag|$jbq{o}8-n>Jk#@=x#Gl#(rt;_qMIfl>sOo}6|#k$7@a>`!B z8da;vo#!bS_nVE)_Pli_VWq6Xr%;-rMH3^e@Pa)DBjRnM-KH?Neb&)}1xT`JgB^_9 z(fhlNeEs1mpu+gAtWzYdPzK%evPPe2qSEAuH>H`TJiN`S9sJZmI`fr)7#Z3? zYq0C?>oACDriTt*_W~R12zvuSx{YRTxyI1!v}|0gCS7t6KVNx+lDVGYUFzI=D#}pP z5Tr3#4|@@N-c&J;_k+E1S(k}Sb&bD{PA?e6ecK!@THDjRViB+ePIwh#(x>3F5TroJdt{ zKN_Xvj)od=E7vB()P~1XtEZo zUU8!YEkx)TyIV+R9!6JA|11?cen1`6}tyFZPou>LX`oUY?o!eiX=pmQGp_gCx4

    2. u zP7(0+BjZc6<|r&SYRO&`fHtt5Kl%jkIOI4MCwWH_zP{OR4 zYh(8PdJhSz{)R~XsncW|?~$Fs(R47X!ggaxh1zU>TY2p?*WRxPBS3BU^8$HL{tiRp zk|eK`4V%Xv%K6b7y3NLr?xoVSY#0eFoAmyc%fB&!c5jaHmPd!kw;VOJGw578AC?R_ zweGIP7GzJA~fBX^~sd-5!b5y?ifR8#ioKlX!soqwR zK5Xb3`lknP90e>PQyDnlK4+06#S1A8ezNgjIv)b!68~fUz-n^SowlM@P#u(4KY6-h zk!FG8RHF=2Nx9%+eEL%m|8o{#n=`qa<@K85O~C0+=$A98FFiK8`t5xHN13+#i`2v9 ztd&{(YK2Xir5%%N&XC+0l=>^)#Mp)Ml!ci*lKE24b?&IkaXVf}+fAxIQ1qb#SZ?@5 zCtH$ya{ODHGu6OkF{6QA7hkzfb~+|p6d2IXDixZrL!>&I?l3CDRz;z@f*QeJ z%S_EFOK7*lh|t8o-gfbefQlCD)>heud9@6=d2XOnGZMYr+1*2mfYFeXaD_jOBo&+< z_M|W0vFit-f6U+V_3*=ogA#1Qs-tw~5zAvUz!?)A^kF?E7llztgq|Wp@0cZ+{5t88 zD?%x}EezfonPPei6RNfn(wmAYdp%H)a65e1&Kp}-mcZ7!^jaAweauQ;er>M()38|a zs+N@8d=`^DT(9o@2H2}}w(u10x?@<$WD)*Qbi1W@ccp9H$|nd(bG)TH3&1#a@B624 zj|xo9RyV-vs|}uVw_9N%^AWB0Q6`HY_x9uVN8<$3^O~|wvfr^m8sF%IiF05^)jP$N z=Q7BZRbx$j=?)el*LCZenu$7d!>T6BU*eD5Z+GWgD7lX4KIjmJyxy;1;xU$7$1Ypl z6lc94N^6iFi$&sk#auIRX18@hzWFTf+c@qn)OWB@y=Ay8(mSL6ZWk#X=Qv>ED#Xf92aSh7uGQ>J41ulQdmo1BQ+MTH-P%>JZ^`||m~jlaF`an@6R5AE4R6uA z_a8P%Brh!i&|c6W%hmXstIq-m0BYZi0h^5!c675KQXB;Ce?bUSAppiP16%g~-u+8l zImXu`JJ`t>cjcp`_HwYIN_*>A*ZE|noZIXByr&=4CtkHCW&r*-{G0&a$V(=P3u|v( zmyUbrj?f2_wUx(#`)9g+mhk2I4?wa{?EH=UsI=#;!rsUR9Do>g?ex@XU%3uHCUP!@&LzFZV4$^#wA0RNN3XN-b+uRt zRD{kg1lwJq>RsJ5S?moPzxBrBQ(8Wn6dH(!nN`aw;YP}ZMW&2*YL$A>w_y8>% zBB*0+CcI(`Ij7bhDO}^+O$$?S?f4;|ung?G0x+iFVCGQW*6#OceC{Q>nQ1w?GsFZc zZtTv*ZQ%(V>RA|kp^x-j-@!(qs3@jqo&JWJ3(rcETGC`Y37F6N0$k5HYXZwKO6KN% z9{BZ}?(I^pYn}oJ2Tot;KJCVeI12yaYETLv4)7Kc@_HpHuk^+H>kYi@m>TFXTBotf$ z+|MTro__YtgOsPXrOza&p05_No%Ubo`%^YMT~WW&QzNDZQJ6GV@$6`X1nMo}5%N){ zMFHmNR6d1@Ah>FxTcul7xYMWa+f7R?l$^EK!S*3x?lV=MG~5?--ZRQ38`)UCE<2)DvALbTk{hmyTLa zEa|%DI!g~0$t>F5d{Fb2o(vKu3y@Oh#ucv)I8em9&x!&UYps8O&t^#e{s$P`=97>` z?cYzHd>}C*tWFO3aLId>px};ju23=$l(cQSIG8n$&q=5h?0hlUim6(KS6SYpp2|zhm~5;enx`O4 zrBTA^GTo6nU&7INZ^tA|IGps<0tdgX6GOcmGwss(0TIn--r7*MBXeqX=Hp36`#e`l zhfi=;*L^%<{QbdttAXYKQ3LFI&_ChS31{Br5=$AT`K;f%y}GbLSQc`R;BJJR;q4yy zkB<3HFnR5zVeH?!X;(7;Xje5kb~mP^lBTVE=B@bFH;(go?3vj?TVp0_q z0xyMnIJVEVw!IP9W{{nss(67`KtS)ZgB=eNMro~G^kT8IwkWTv-Jfo%BjCpN4g;hf z*dZ47+5*@IK*4PkC8bJSs)TOD>WGv2V)jL2wQng-rf0C|Y+?`6LLwEpqm0_1I3=I) z9Y!{MT7KZ(+Ee0(X>nfs#9$#p-61QSYB{wUHZM#iM9wzul__%fK@=e7 z_(>I-JQ+o(h#WB|0=0?Mj6v$z9WK6KRX2#lF*jwOjcyM+UK}{D0O>_SOMizN6xJOx zM8cFy79a^9qrDYVod@%qCrxnuH(Tl;*`>TtqC~`_cQCzlNmL~sMWpp32VPPx5zETx zXNS?tkhZoX1Z?aiLd!_~JChq?!_|=GQ~mB=?o8#RpYZ{M{WV|dq70q9hy;K>SMsGn z%MYiQe@^Pp@g3{HCnP^3Ge9sOkO%yGm(}!q$4bUI%Ax1q!9X?Jp){tWlH$^IZmjhX zPEl~VN=?DsfF;vK&(XGPYF6$}r?nSx(y7*fDv=&Aln%tU%)(<$uebMzuT_RS=y$Za zrWN;R$DY%Mo4_(o^U8S?2Bx$RBHs(%UOWusTXS_`SCOONe#&1Np1}z3*Ec>Tf<0lI zO~j1e;K28zwcAqVmDGvn4N?IlRJJ}VvLPxM(cQ2(f}?aSVfim8_#7MMss@U$636=_ z@G5AdzRsesj(OC(4;|#U@Cs{%Cm$dojLwWwzpa%bEV@_ z{fHO@K2|3h?2dj|NTg~GV3vprQy2#Xe8rr{*}ZaY9`Bj`Mss^x2UfYX>fU=uWM~Ky z5`*w`;TFA5^3>ylFIC|=m`(>6Rb+G-=#BN4DL`U6@g`|!y74;Sv0h&4r#cM06`q)X znsEXWy+f*JHYMTceIyz&H$^_ktyp>`Zg)WFgn% z+L`6UVY2gn$L^GCEuO(XgeRPZCq0okj?waTx?EIx{9}rIs0?Arj*f3En`~sb0i`0B4drd(>yeKH_=n*E9#L`Bw$%P5!+6zF z1p^cI3pj-5l#5z}!D?lT;n)Gi#sMpKbR)tbZWxFZ=Efrmc5vKe}N>I*5v*cu>l?aBv7NhoexgF{g7LB$$0ig#^MJ) zLX3+Tc1!b0>iDq^8_|D)umSSQCNE^}%sD_!@A{zC^9S~e5!u%xeBi7EfFn*5R|bJ{ zD}c^i9jCv(V^|m7-d7e$8)e=Ym8{mgxV|{dOiQj+ZSw1BM5e1gI5{6!RBx>a7raes z?nQtCS?POv=jkS7w!oEm*O-FJhkjbjs_+1m=bNs~!RG73cCe|?xf0|v?p6!cC z(Rz;$qhJ!j`Ln%uMITo}!J1}4e312rQtRv-FOjkTR$}BS6-J0M?BQ z+7vvruSoqM&_~UvP*FJf!3Rha3OSc%Tn{s_EkJ-)Kvi0#dD$2MYDnf`r5g5O&k#UW zd)NQP-g`#FxwdV|`~Ai7ATD+xn%B1rVkXcLK&L`x!iPth4&Fry|! z9iq3v7Bh@87!1ak@4Cr;-u*uB`+RGC|GppZpS_;F)_%BM<-E@GIFI8v1FDHT%HILW zN4!5hdw4IWEjIzJ&$-OHr=Xwu=>Z;gt~U|?M0hV~n0W=5j(yl3(y;VAXqwIq`T&K2 zbzQ&&$3ST2;o(fiH5}_-;9qsvN;)tlc=E4}n92YYERg$?Uy+bwo*l?9#mg5A*oAvy z8aqag5)KuvXpUw2|Md1}sH;k?z$EXl9GO1&G_lJp*35eMm2?;(oDA}IwHjKs9}aU) zv~Lp~T#xqF9yp)fSKp?gPJ9V^$2U{0a)+SNHu<$)Kc_?GHzljbMYZw2dbui^4nJ6T zt~r4|`guS_}J^8-Z z#v(gp(^z*f{P}ElW=d68ve@($^>i0D$#TT+uCC0&@D>qxnfg!hj9-8#0YT*%x@LI> zoDzL48%$(COF=`;+R!%fTGYm1vr;*w2WO9aBzyGAw@Y0aim;bMR!Xsm_ew81*$JuW z)@FYpBbgEDiUqKe_xndHk65}hxlcn0=5%>}=YuR6>lohgjE>_KL*=7%>DZ4K_y@AZ zIX;XZ(9W&z9LeyHH+x0KC!OHL_dVK2y9K;!Qp96)7RGyPlf11*0*MthYx!feO)#v5 z7#v0^jia5p-TRKawztyf2Pdix-N=d{XU8hiwn?74f6A4tXSR*B7lGVu+DwD1*{F8uF2njbaDN}G zb45X;<)F#4g2D5^5=r>X$yo1cgP4lBpUwJI`>o;g&p-VAf=#JsRm|G0=GNjniG!ay z%BPPpuJLhQG$psE`aBfw$D~#~{4|U+dZ#SBHFUXv*8~9W!*3nwEh10Ky8JbYy5BKP z^8V0gohI!b{_yajNcP?&8G`M0+d!!Mz*O7Gwvuvu%DpWw<)`wQTUnBL08*hc{b6bL z6nq6gbhH6;VDD((o0v?-ZGZ2q9niRPFU!;5?B~5%t!Z~aDsbn=I0cCI7VZ^ix&(Ur zywKSzmrfOy0_Ek;KxRO?x)HD$?QIc+-PF^5e!e2UGIy!qF=yeZ#C4dd>-F;N1wun8 z41~RUzXE@mTp1}V_6@*#(DOFUmyzim84&X7Zg$bH%-#Op>I2P^v42&e;9-v&1ZkL( z>Sg=Jd(%#NF*|Vm^ey)pR?eCIo;N;T|r~hbvOO| zL-E){dlLc1L4mk_tC6SHBc!|YJ>?Pb$d%SA(j;wVyj3_X(q zMOe0TC1`%X0m=HB%W+)Zn%&(gh#!ErC@ZU%WH>~F2|BfiLelT5f6HdIx94FJSv1^+w0 zL>0ZO-8DPJUc3%7Vt8Pk;Tn@=%!M9?zeB>bg)N?C`7_|8W0+^tVf( zBK1vj*N?8Y-zY%YOtn|f_qg5v#fP-OL=SB*9+_|dodb+5i}ofW%-@0n^qcfZjNz$X zAER?+a`^du_s4{4U}qDAkh4j;FkKYw=Iv=fbrJ8pIu$mC01YBy1J2nVY6x%wh}UQt z1PrbLQv@}|o?vB4*!qH;tLZ(t;Cg;yR6HQMd3l$C2W1VkwC(8_b6#m+nzx=(h|4SN zrBFrA4P`W}#F`BUdVflhW@WDh7Li9G$5K^N4o<~pZMxv}((zhGbmt2sZ9bJ+0-00$ z#5MV{3RQbnV%5ip?WQsjviylSqcN^C4qwfQSlG4kUW8-G!m{gkueGvgBXVWA;Zwzb z+7l8Q%CE0^GW*%~1S4p~+H$-~=-itn_*&mbuV3#nN}6nTYFwX@+9Zg}TiUXK>CzV# zZm@^m=>>!{uf?zpk4Ac~m6+B5npjQW1w-bwh=#o1GwM%W2jz~BZ;1Tj*Qr>3l|@mr zEY|o~Q8MIb_H4c==uc3<(l!kg-Cj2#dm7^`o9)K7R#PB&YSrLoSxuFxMcy$z`g?M)7^z(W}0wI zbh?s6P7c!c_Qkbh+@!?>+k%S_^J59$d)Fp==}v60Pdoz;2l zlj;l3i8h!ch(_AlC00dG+N(*)kwLLq z#MY3T`}c?pKS7yvk3;Ab;4jN?*yMFUdR<-CyHzyvT+jtartmHr`=qyAzx zP^Z4qngO184|h|*L|ukUxvHPluhnigXa~Hi()wN;5F-tmXXW;EV%gDQpNQ9kyg$wN zUZ-sk*?)OK4O-+!1!Z0K_SX{jvY$_m=rCM-Sf3zGI;;B-1$tt~2zkuL(fFGqu#q!= zxB}>MVRk&{I@*t37MS5$+;20_d^Abip%9hXXF8db%VbTOlY~p)#!4YL`jp|on5IST z#Bvy#9~ecTwRZ?afWkt#Q=ARx0Il14BXSMxFW;&;$re5r<<((Yp~G-kdpff-+#ZYn z)ZQz!oXzSxQ-K?eiTk8H6V0`EH9>fP}LV?Ha!?o%G z#Zv#q)$@4H`ryGDl&Yh`6@Tz@2{oo=FWs0YfhNV3{$ysmn}&0A2ioXAeVhlIIH<(g z-=c3X&G|JY{JQqcMQaqH{7(2CJN~I7=?jd<05w55H-XXZ#v>sq87qcf_-8uFw$8|$ zKknJ&x$OT26K1=`Ker{*bQgW;&&(8WLW379|B10wmNCdRmW-0LO_B_c2?<^uzm}61yyInzD zxi;b&u)xIjC|{+IM2bY9F6^v3>W!3VQC(Bz`Eb<1X2Qss-s-KQpL=rn!aUGPZDSr* z)&uuZ&*t+&p!cm8x}d&;+T>jq3ab*|TgclRZePSUHTBySUL4SCJ3bg&C(W#r-!513 zs_u3Y9(snLir@6qR$}dD;$Og0wmRUwOPpu9c_;JZX--9JO4G|VsBrRm!OR}K%TT#c zjUw3g5OSbhHwMn@u=?4j)_Dd7ht+Rw0+(Nk>PC@*ILIMx`oZe4`i39J0O-}ynInfM zDuhu6Rc{M!EkVzn^7bUFryl-Zeml?f4Yu>D@(_1-Aw8D)#<#m5CCbxs%RMEH3;r_~7ta{!Fa-^rXHjmpft3{7h1p>Q&`=sb(jwD+jRD_hC zmEY~kZ%JWhhA^jm`=`&^mCEc533Z%=j@tK6C2L3QM%=b>c^4FgKdHYe?Hq)=!%6wMqU4riFgJ3h+cvT8D}A7#j^T&TX|#t0FJy%fbeX-A(Ts2;49#qjNZE&8o0e zmts43JaX6Hc%VbQ*_xo3PSBIK8n{jxXe(OScGm}I=6>#r;qK0vTkS0?xpQ39-R{|R zv%)Uku_{^~IoH;U)X-r_2Bkd=j|Sr+M8kYEB;;vh?J=NcQ$Mw~xrm@5o8N$c=#Bie zMJn>)&=W6Ez+#W=YkXW z3edJ+9}EO6y)OMU8_VKOh8>q?Fh|kOV2$Hj$=2EDP5^}@?qEPC5`od=#5i)Do~nXP z#4z1dQv~OuNYmKKyT%a^-@PsW@bDLD0+yk})F5%+)4A&Q_`8AEph*Z#Fp>-I7Ja4$ z7>zL|fC9)=^tJd5&O^Bkybm1c70v{@0r^5|TnL!jXLH%>=m?*Z?*@I#Q4krlG)5*2 zVznIq&L}74UD1=X5hf<@=0ft}xhHul0q~w&OlG)toH0&ndB4 z8-3cgEoGTwT4EaykxjozT7nUqEW*litVLv4irb4JBH7on)Z7fHIWFxbCH+F6X!o^XA&)UA% z`uJlz+xqvIGH)QJjI)k(i8{oT(fbdr(%Yx_Hn2{OhoS?9q>aP1TD0rE{^kPIUuRYP zV1&-iNwU0ts!};0bzeeg7z@xIirT9zdlirJ_x5>K@-%K?U?<*Bz2TN9duc@a1xwLm zGaJi_s+EttsUw@oolC@(H>YmoagVN+jH}m&R#km+gm_JFpw!%x;jba#re$EN++y5p zkS)VG1KD+0H9cK$badK_*S4TNBJ$C9l#LW&FyrKr`6CA0xthkq zx+#OI=uPV^K!bt`$@{>gdm+!@wReAr%cBCod;DN*Qs$y-nn-#)RC#f5KJyjaw?^ zi`2AHyqCBL;@SnluS1pv9je{S_qa&4Pu_9>ds`U>pSdQ zOVu@!-ZSEi0!k*|_l?Ex!jFI&zwkeBBLe8ykA4N*7x^Hcvlm>zATzxkdbh)R3SJSZ z!u}xnb(J1Bj?P=O&TI=30ia896-bZ9H<+-H4#Z^|wOQV@pA2m1zixyeHbTz$3;FIy zS!H?ZI+jvFjUrk@qY|wnJA4z*z9kWN#%gVOaiWo?eVTH5>M=u@RDLit)>i5JP5b?e z)3R~QT`_vL$x>E%T8_P*z{yuM%s7$rVs)@L4Y9s>V6Zr+hJzX$|M@*PD{uNCrNp=_VV!7)1N{!5=?jBZBA_*7=GCJ zIfLHOwP9Ry@5u4<(5V={gPu4HvW}BPAkUfMDssnu`iY7&-CjLqwaeV&)^DdvRat)#*}M)x&}-g@@s(_ z>24gE6B&oR1Ljibw;CqV4@UtO6Ak&w1d)Iutfmz;T{*mho{jbvWCXuqZ zxOw2V&l~LYSn~l3GFk9Ar-?EE^sjWXZ5A>J?Hj8#EB*NK2k zHOlXOf_5#Y3ecC7eVu_ypmR;p!gnW-9Jnx2VGW9N>vb^DqJY^X0ugyoaKmx1Fufhj zP+RblpL88AFs|06`gzqVE`Q@FfiTN=#P61Jd^Vndi_1E9vPPg58B9Bd6>pryr`ICk z9kw4|q+Rl3bQS46>zk3huEaacOWWpj9e*|uri2eFiWoQ-Mg+W^7S$}@)ggD_V7=7H zXKn;QcybP0dMoKj3T;_sK>^TbFh!HDX2-`NYN(Keq5)5!b1+8fk~y~94`0SejwkzQ zb(hHRC`50X7q!5D;(QO<^Sbvw$gPsVy#7T};4%SRE+4wwaTXf!TBE7Wmu19uq+SDx zHo@Q9lceRS7_qq5kUna5 z0=s^0JbV3u_ufN=F-U6~puybB{$$}?*tNbh5}W&t-IH#c+-n{U{3GBdgDx>Ogg*lg z`?P?bJS1$61q36kRiO9Wnw!jSzFWw+kAe@?B3dUxXBebU|H~PMs#vqv^a6-!lxaQc z#`m7xabGh@0EEEbP3V0tfG})W9IL*UoRZXQ<_0>3PXk_3@c4r!BuY0@*k^Kr>)@eA zRA!37dbINZn9d+uxtB(L76JEXn&6h}2>otAdHv77y8#)k1aOVRt5>%Z=E2nX$FFau z*TX4X?)OUc^-Dy z5MCQ~n-{~UR3E`nr%el}{kaZclt~`4de^osK$?C&wIV$){1ljDH>kiyP|rJ6b$wUA zkN>jyUC8J_69> zfJNCaGJSVvxdOHrbk{Kmza>1*z|p^RVq*NBct^1wI;Vd`1MssQv(-?P5EC$I!+XiLy@w<`z2Hgk+7&`HjNY+Aqg z!Hn2$P|cnjY*mRaW-4m!7?zqx_jt#azN*@tvUpGQRBv_f^u1zIROTuq zryIg`Bu35WY5<*P82ErdZEsDaFKGbnaK4>F(9^3?6BR#7$PemP-~Ih{stog~;vZ`D z!l8TWkdFPv{84`Ik87qoc3x4eCVlT5o#*@tq$kAy-`!LpBC8jx=0Apt8T{;?k>1-6 zC1^i#^$Ci6soMTeh1YCm`N6^1At5@8*;?~g)@*CbkKh#1-h5y0mS~%TcDHcmp5I(R z5aXb-DWi`#4;YY|H~;@~Dntt1=lbp1VniF+Pl9q`2;`-|1|-Fu755w^V<7LrN3Ypw<=>!NsYeI8wN+jAFPeN^}HbMto@x4o$Ii|+I` zyXvXQIYlB|v)q29{5=1=#l2OV25c(h2szQ~;*dsX{)@QZvvN-&*4z`C5IDb0!k7jZ z%$)@v#k4)iZ>7&T)8tS6geX0NJ9KU0Xl|)ABz=(SQF9$4)Kf)+Sh1VCAq& z3omKx4Jd@ygfjD*Seit_p0fh|WeQ&4njt_{?eE+wKikX0G=2GZba4g?-}GAQx1r^~ zFAj#q*WKwjQQta$J5sXqM==z1O(|t%nYWqO5-#uk{dH$R^cPn}r-J6XfG$wE{fFEA z?`xiB88A>I-3Bvr=wr?_t?G-<3=yl`*+c@XtCd)3K$5clsaB z{iD`>w64|y1fN5Fde%eD%6xA&l>bERAour`UYK3}CcT$D{@ddobF*$|^XG@VxAq$4 zc!n51ny*e;fo~0AC6EK89aYBgrz=g)0L%l1?|X^*bCq{>#bS5)5WeTzeLAG3K2>`y zDJwZoC^N1lQ2zIwGX-zwmekMdyNN~@SAgZ1a%!HYo|36M9LoeUg|PyKE8sa+7x`Vc zbJEAyKPdKejPYCjB#h8SD9UZ5Hs^0?s-igs0%M`otZSf$dcE_2yMTd)CC&plsKsM( zv@$~+YK3|LE|8UAvfD!s(4Msfpq1exgto)R@9K8O^;)ai&x$X{yof&IiGDzYx*jI# z&YA0}L{wY{eWH#|Fgltbv(|c!L4Zc3{hel?qvU8qe_!D?NB}`;dUJ0vtIibKQSd#Z z)hnAh!XzQbli)9bRS2_&gA$M9-tU5wA;1!B{j@3HL6Q>L2&+OHuSaYr!w{!?4b4@( zb`$ARq1`GJFiK$Sz*RzSgva0I%P&2~&6;UZ#}+ZrwSAAAU!PV*j};IvhdY2js&UZ) zi-N~jDV88r(UPy_`~tLygcYT&nNLFuTt;ulfS5fww;BQ(Y*fI9-!=f-@N>Fbc5fSm z11yJ>Q(+&#W+zB>TJC`HUEgvBqC;+i^5gZF-$mIA6+-Cy+O6D|=2(8}1;ld%k!U%T zN*y|FyYn!sq9Jf;mq77U{Z!yzK+IER2ZlkqR-9-+0}6?Df=G>=b`Zjh0R|8a3tiG%scL6c$x9jyrdb` z!9em0wR=a0Ztv&-6OEI>RKm90d|_iTnEifQ9?;F^Pzw*SfRuHytv_BP#M%jHoDMXd z?H!5#$^C-_l4kv52OI8ePG!!sta;zqt7v_}X~2_6zXw&MDFx_|F>Mir;4@nzeBukZ zz%4QWw+O-@9{q+wgcv`UUx07TMxSzIT-`y^q zwi(5#Fv*ORPRjdO)H!*e(=3t1C`cMsIE*b}W`wuBiAV%>ZYY9Rz8K@bUZPEe1{SaH zd;@|FOaHquwM4(GLqG4J+mto&Cjzt_W7eim%rsJl6fiFapju7^O=rAGHm2a$I$1pT z?BPS%ZrjsPIoH7Lgz?fYqcp&A5OSYRFS>BY?(ys%M4NT$ZR^Kh@z#ff;k9J+MnK>n zOXp)5*P22r-$M!SvGZC-XB5Ho^F+lr9{d^5aj_3th3+X{6hGqVb%cdrN7l_kjqh+??>q9R4y}Cn-=a-xHOnSiTPSYFhA{lMxoVJ&n zt-)zD=$mG%LxWk4#gKvCPc2og4RAP&T*rYKjW}e^A~aUQB7TIhpvoERdC-rse(ikM zS5%1>Ch^!zn`BoAxg-Psh5}XKDkv4b9lwDcxNnDX{2NfWMx0EzYrP7&>EB@#@us1~ z0>O35X*>I!!U&FUG&sJ;&i^y+9V@%AxkF|RhBsbB!)laP-icJN{*2c1m?ptE4m`UintC%!B=OD4)VAW_*D%%SI7H4uEQ4 z$2q5qpzMBok)dSIQ^L{TYb=Kk@`134I^W-CmejEyx!10`$XJR-V0+`B5PUK9=%R3M zqAF+8R#$XL6DaWh5zGuj-}CP*nZ=P?1clw){yJYv1r;Ke%(op0K3u9cOdfh$RBY(r z^{FMDa>CVsBxk!om<-{s5xNRFH&|;bEZ@kt7ij}Lq}VSH$L6j1Rh|5pu6VcxbHjM) z{NR6XE&1y<`#SA9wq@N)6Q{KljU5od~$XkYMrws8Im;oQv!%Ci++Ky-eMVkJk1^%r_s# zBEc;nu)Ahq;N6?QL0=g$IO#q+bjH@t6D+VaZIvm!46A zk3u$g0D^UqGCWY@aq6gY!W=%yRYNCy1verxPo*@zaa|t(bI(8cEr*)6ug?!fEsR!{ zbmN_S`+t@2;~seZ*_=vI`;)uTcl(#1vaD|tpZ~@rOu1dcyC$bSx;-}bLdYQ!&4S|=w}{9hk}oP8C96yz&FiCGzUPsnb1>Vb>(*slBokTvOnr-R#Y@V* z;wUK09N_aZ>qt6GS^@?g$rL}|-T~*3WxVxp(lJ6Z%o4FXe9E2KZF<~uA$34jcr;%^gm9ycIbOBv6*QlScT|Wqn&QSAYQrBDl&qC zuQ5RP6ZxTf_a1#@P`&NYlcAnl)&1=vIz51mnRzk~kci~v!IM)wfWk?AX^aH4ys@0; zM(<1+xs8E;VdI4U5R#3t8pu-hf(9QivJa!yhi$EceYn^OhbFrwE}i%*S*n2T;h{y# z7dfB2Av$Q7^uc{Kwgr_LI$velvol5*_dz%R;LDIprl-9;fPTpunrr%Ds8q}G_z0lf z1mrcc{LKaUDsVexAVgov=1i}lhf)VgA()&E2A!U>Sq#Plh7x5|;_22TE5eIY&rVA= zqZ2;xAvw|#-&(3g1OX<*)ooahmpBUtjntR?NT0DeX8a6LIVMv4uQKnCg=?~swp;5} zg>eToaKKBE+OFB3J&(HRjm!fERqH0F_Jq>NyFfzh~ukP7sI zeWSLdMeT~l(FnhVnJVB{Q6!NxY?UQL|HTAcmYX5Aq$X}U9f%vF6DNl9*ZooWL$ch& zzLdS;^W^FPpzTB_)9GK$U)4_C>TQ4S3CJl)TPI%-Er$=8S2=OJV43>dgS{Jly?YX| zZWA{KizSK#Uq&n%PQy2P zlsa+j5Yd@`qwWCne)NJ#iy=>&#UIZQW-3#<>;$7c%HqYo(t!&z`d)Su&R654(iTrN( zJj1fMhh)AjR7nnfAL(Z|{RG?0@90p+zik$SCi>YD$HC3%XsMKho;(rN3BU)MOz06$ z1*6TgIBt&2I5KV>4dS`(wDRg~#BmSHm4VSnvUt+c@dksEnibW~PXl58oZB-9t}?C{ z);{a=@q|GjSD}~C1QPu0`fBG|iGpN#PmS{l$GQ@I>+?=M`l`9%jf=O=Shv-^kQ*-D zaHmwwyruit8_akmz0PFi(1PbcWY4cSipt{|#-R8X<>k zMR90cHOD1I#tTOgdFstB)5|8ro{e(q;E>urH}&L^Tk*mJ#irCb6hB+`oT6VpYpM>@ zTKQUgB<=|Z(Zc*7Vk;9NX9p$p2BZ`|tYLF)ClHv9_RP=4^-NOQAPd%xZ3T90DsZIy zoUQzgjRcy}_e*LJ?OP`&h9W~VeyjKUL%f)xwq)T<^aw6e7pRQV^_8~FRM*{z}AvH`=z1GEu5}O7TUT}F^NrT zcEKNyc=t2yYhZhvq>x`aqt_o&H%R$Y*;o>;YCVI=<1izsnyJ|b`2??nG%E7fPSw&! zvj>LhSX9?wo@pds17^U;Ro$V^v;TE!k4E63^gL*Sa>wlV)9suMpCCSb!bQpaeCc6E zcSWGo9$0-ge6=B{UX=Ljr+$6;M>EqngkiZ|3t&{BGQ@i{J+VLRY|Lk`=onm zET$U`Int_QjmHJ?_QxrZt%lUKU)??rk2n5mDd@rWSO=wnY2_onxR-uBL<_j9B<@6< zhqqG}28>Eylv4hzbtTh+Zo8Quv7NyGka6u0kteEFDs4v5@=9iqcbn2!0kky%mw)G6 zmN|>ct(tA-|!ys-OdbJX=#!%~TL`DFgFzDlTuSKAoPJp{SKCYKS%PZ8uwqP!$7hLwY zFMY>#xq78l*tM}N$`zS6QmQqR*Y)_R=Wt7930(;cuqaNC4B{^l-TJ}9jPHZ@f6eF^ zc@X}XF5D73qFT4~bt=M;^ggcga=wS6w$*k%a98K+o}uJm}XZ50@1WOOlDW zOk|&2v%HSBS0be&>`{?0Ap1>DNaPyr%B!To^U&2T3J^Gt_sSt2OMn?642d_6I}_pa;<5DI-? zKWW@3K_u0}OQRngJj}tJ@{^*i96fFXUXHRC+3e7dd#ZLyeD%uQl@VPz>8Iz!Mf3#T za&PGi(8qY*wHPwfGMTYAcvT1h3hcAc5{+SAq@&4&uNR!+@Vp!|yk+rR!DDD2a?T&* zkHZ(_xdb#zMVSl1T%x9aA>wL}zMz91)0##wn{|+j;J9$Bf(6`NO#9`teZ5uSO>mVK z=#nqK$nzq}qiXJ#>(6f#x0Gk`czL2CdY<*&2e_s%Fx&C0VIW?{_=4k@t_f|1tK2&J zLTNnNUq=TI$LeJ$vRYz=6TEasqoBN}O0+8)F1(QWwRcT3Q(Qzogm6HyZIc;X#%Fdc$$(eIe1Ew=1rqHz6p+BR~;uDTbHq;B3=+Dn{qRAk}eJ^Tx6!>T8GrsI!>$}MV-&b@w^Ib%wyNl9&7Mms$nYK&i zx|2$m0;-qS1@;%iG(Pi=ITkOpy!A777b7Wj7I#o6a&)ghQErH0rknc0M2$|IN5ZV6wjM5XCT zbNKS8b=dbOs=Py1k@u_+LW%KzGyk3ix>B>?}TGO zp>HrqW!?5!oZx?zLWAG9aFNmNyxW=H#0I;c2X>z%iBuKr$6r9|M+M=rkrm@flry1D zDc67#tVwfQ9)n(-!;)lB;r|hEg`ThlTXYZco;$1<%_JX_e}7|b5-16LJOH=H$`oYL zx9^heiRY+tw*(`S^%j> z5*4^tPR0U7sY{=2ywBX{UF5gx^?ygK`$FH3pB$b1S)Xc}=agw>0^|plF+lG)@8b!w zxcPTgkjiJ1?o&@)!?>>Oi9Es_LE(W=pHFnz=9;N#_5}%PxWR`1#{@bXz;=vUwE>eys|u30;`|DC+D`$H6(14gMl~w zq~50xm97osp~w@I?pyqd+pv|WfFU5@fN6d_m?<5i?Mq%9^LY;VR#wvYYj0+G=7(z$ z-`u%h2c-D4AxI_6PT*BEB%vLB_IxB~%2gOw{mri4NXI(p4bMP9IL!xi1;%op<(xeN zfd0!6X! zQZ3LM1I*&>pr%8x>!5jvC76gYpD?LzqIYG7?S=w?-yr_3qR(cVX^Q<|;b~!xv{n|7 zzrJ}o<8##+5(0+H#mmGcIW;g1ZLQ6fNOoR5OZj5D^#wu%_2*}kESpT+P0GMEI+;~1 z7B!XX-ufg@??h_cAG29wPOT*8X5NY%9+)Oa#EE zKradGKk@JVXCp{)L96$?t{BWp5wo3+L5_o^>$?x0#DDR?U)M$ODl3A9*~*Ve#S=y5 zd%ijA3{4=F6r1J%H>D;))HV{jDS!z5Uqn*p z0Qtp@+4|Sd#asFOAH`KneUVmxe$H(bGlgEBswmHglOx#m^7*LL?I#Q9aHh53n}W#1 zOywwYE6ZW^;80cm)|8tD0xErO6B5K<7`FZzfK~>tMNr=yf=`Fzn|K^W`gCWs8QuOQ zJJ~p0Ws=<<0@+((wS8&PD-Jb5yn3J0%yKh-EkOtO@ww5^TZcqJuYP@ei}sH>g=`rj z903GX!c>VHSoF$^_M&TjgZS!p_uW;oqm<&G5xL-*`zxsJ1G2T5XuSvfYi!RmI&xrGbqqOdQ=D5Nxyps-Iw64o$B!D7-Q zis*UzISrT~70mV*1ISKAz}8?*(NAFm@s0h~leqyTrXl-RROX9jgEDG+#j=ug!c|bN z!ZR85l6xk7Ze?MzZcaYgXz5v>yIOWtK*ImWX;_NWZkuTzoge!~mswh^)JdSJF|~0> z+AX~}0qwRx=Q7n9YG0lGC&BL%9cZT1z8!OE!+5y41@Gk@Kaa*8TnjeA1tC-m?V2Na zzaSQ!H@a$hoP=L1d6ub# zQ}nUi-wnsydoWXOmnB2I(o-y`A0qpntF(hM8GxE=4Sdz66bZv-lN#b-FLL0Rp;GM_ zi0X?)0}DTNvmgsN zuvG9h4=(~hoaYPAE?0LSoh1GG{ALSyH@GZmv&z(yza4?n7y?khdf(&n)1y0vj8`0n ziqC^4fa`Qh&_pLh5CHuW*AB%DhTxS3rPC7RuIsF7AvZ`b)Zh!#K`&ZU9wu?+9DHf4 zlO-eGp2X!VEM$ZAy}<0%!L!|-+xTP#87{rDbxHJzY=<}oVQ@haiFO)qS=uZuU(w)B z=KPkpHb)Q~NjUaCe8J+YsmTu)1IF_ET~e6y;=LxT3c7x-Z7lp;$#0YJki)eV)P-Hs z>uD$eZ39^IQTa^kj-nRI{ai#mc@<@CX~05Iweo%dqtyKkI79{2rWshJI%ogK$~0EinBs z=3C%L6PP^3t!sy*x&a#tm-8ZHVtV1BEIx1IQs{u{0x9O7KvSsJ*5b|_!b>Z-6a|- z$p?RaPl}LTxI%=UV|_+NE+Ym>7RvWkNerU5LO-BskX+vF4kSfvJ7PF}7Ltf~ zm*LSEQ4SqZ`565HjL$>IuLu)$yq{+3F%fZ#zIDm*Cd#9yXEA2|uLt1Bcux&3s@4q? z9}kFGt3RA>gf&D!*{&zsStzmNuqNk5U@u z$q3pEU-+;VfET*_0=i#6G5-wH5X{}G%E=UvqE=-PO@FzQI(qPijN`_@UEEe9;w1V^ zAP1BmnZI57F7EFPu}${Nun(b+EP4q3VYm5bcV6@D|gLn-VgP=N1#$?F8 z&Xz7Fod(E1lwk9W7UZ*lx}1Q5t|l-cD8+|vIcwpvphN$Ot9jh*%#*{y1z*pMfc|># zork@cXA8kv10hPQ=`hmyD{Qzn@cI=)rrhd2mJQyM-`&fdfhxojN8jTVT zl8<$Se2hv3XzKN;9-Mbv3FH|g@dTPi2BWr9q{vbG;}7ZudpLZZ431ByqIwb=(Jz~K z(b+Xof;FQnWS^yt*N@`?gr=Vf%RvKv+f)3e9Ook7d~?1{H+fTaYnS-AQogj*xk@l8 z&#=7+i7HFvv=ZUa$){+mfiB@QDc%l}(_foa?sK~CiYS4kW2xlE(`v5hJXj*e_xQv| ztZ-uqw<)*x25MO2JE7pmK#Z93_{_XK- zW#yeIW$A54Sc5$bk!+caw3U0SYi&B`){mU6%_-KfCf~*Dy=YRJD@h6G^A|Q8J{{84 zo`_w|7&V(my=2~(%GNauB3f^LM)H!Zw=?4guk$zdM%w05BP)`rCA=VUE%&cbjeCC6 z!lv;6P})&J@Ow=J%-0{_H{$R;j(ewDX8X-*H`Mox zo{N>q(69gTEc0AQxhho?bjZz1z_hl(-le6y9zU+Jn=^>{(L_#(L=U>fClju{Scsb= zC7~>QK|Y6E+J)Wt)sago?XkRt#E_+DwNWNszz$x{B~$34ZpHBS)h^2nodsVrp3!Yg10&=ZNK z9pQ1i2*76{ATO}7tQr8L+rHV@Jb3>P#mNK=S>+_Lb?;9EHvV%%MGdDauds3Au}TAWGe}RscK+C?lqfn}~dh--LL9FuE`vz^pHnTtuy6cZzR|0$V$#L%9OL+s$Nk-g@ zmxRCR^lCh{fLLp3^Ipd#lU~JfnRT)x^-(L$bpI%Ms_GDgW8aHqV9Q>l@1C@Vy|P7NdxC~L1#WG$ z;Ni&pBRb&=jd^nf=CxoCD+V9ywevWiJFr{;Nk2~AlpYt(q&hWcvG!;brjmUgd;M9v z6eOM}o9%62pSvURUKGOa(^<0em5p`7HBJ zIXG5+1xG$4Y_H7&-StL}ilv>I5Iq^Y+38upY{=QC@W|L_p-l2+_!Rl+r*Me9m6${jC9E4^T#;0#Bg&6~Tv>|9b0`6Uc?0|K0;R)6GbQ4f7h1XLg$RTcpp7g9;^lfj&iwkhyz@aS zn_DMbs4FZKK)4au#0J*$B@d$i<^m}ALc-<4cCqnuq(@SqTmMjIQ|VaKk^Y{Zl%6<_ zNQhgguE?w4IDFrq^`a!LfpT}l{8dX-D{1l4mdO=a8H?Im(X+9(yZy3DeV>Zi*;Gb|PzIZSUfY~f?kt{)6kmiGtY1DA z2=4AGfCgSUjMpeqfc0d&;%|hzT;Re{I`>JvOe8?FeSnMLBcZetk|_`PfgUqr-tgtr zis!oOZ~}VlqxZ^I?iY{ng_NK=ONOn%jh9cn3(F zQz3qi?eO7%VhKI$Qn1ViW>ZaR>`k6eaAyeh1g2~gIhD!@KIS5mIz#$`1rcNf$SmAC zF6hw8kbVm)W2%Q5tbak$=|+x>T>l{WMt7vYTZdNz_3=yR$#Y}8@*W5A{ZHcDSN)w9 zEAhC_{9-C!YV(x+G`y4=79RQKsZysm_RW19Q%+1-3aVyNi#W5RMx32Y077>S6><52 zxk4L4e5!6}2DbU8@=*@#OA;Oak~#TfO%Pt(cbru@@GaS|XnvHZNc8VtnVpf` zxd%`f?MpY|_#_H`arx)7BSjZp2fCd2ee=K8<*D7ddO?id2U#Q6mf};eym;S!B0Z#d zK9D1$0%9kGa`a!``;Y%dma^GJA=A%gsjmHd;X^F|bOH*r9J#DBFG2ag$~e8%LaKP^ zEpQq|Lp`JYnb&k5*e*%!k|Ma1&N=))?7at6R9Uk&JR&M0Mnn)4FruOaB}hgQ11MlX za!^E&AUP)y0TZBtf|5;ughp~|KoF4FC{aQql4A=^(?HYoU#Giqbewtb`~K^$@4I(> zt~F~$9XV&8y=&L5UG>!SP%Dm%+8b``g}4t$ttdsy&7D<_CnL#=nZbyPOs{r?ryt zjR}xq-{&ykG6&pwLHbKkV@P@bQ*p1gGTrmZe^#t?DsmI*AeHiDwSQj0Qaa~1Wb*7JLLm0eIM_QV^e(8<; z6!i2~jYr2RA?T=tx#o{>rb%uzFE~LhNOSV}>QL`W-pf{A&wVH_07jo zlJX?`%I6}I)2yWf)CHv;(ffztWK)3K7LS8imE$rjFm#w8sDL-X7ucTc-AoJo*_Y)_ z;_|04`G=(f?jR$Z+pXq6krs`EFH)+_tXqKUOoCP^I&ZRGGo(>ya|fLnOVbdmSQ)IE z!su2Sjq@s+eJA}*{z;_s*EUC_O5t+k0Cgge=j}i^y0y8kNihV;&Y3!XI>l!U`9Z1r zFTm9N2!VKy*~|0OCQjajJ{l=0#nseaN7tP~xCNJe7XbG4_^t^n8LB8p9Rl4P5jgKt zqYch`skV0VSWJpyWrHdTMl*!&BI(=tkZQYX(!40R7Hkm|4W9+unJn4{1#UuR{TRZ8|HC;FAim5*M$%}+2druxYv-g(m)_A>~c z=_%ueQ>BC$5MVM~SFV_ejYqqMP;j^#S*{d&``ZICYRO7vUIiFUs*(p#z^}N@uONwLMV{T|psBpG+ zKfr5!hzMqP?p6oY01>+cirg){P!4nUL#{yx#97k%MQB0quFs%c8L0;sAeF($pq51H zQTT_qFl{&6HPEOz_7}-FkOnM)nij9FqkqrzL_FldmswJc=0^;8ee?5PQkQ{5CZMb* zE19=OI#-5wMHo{iXu@||8O;URLk(K+7>V<_agW0t(eWKB~HK=Dg{bhf?b$0QsR^vm$ z)c+f{(bSDnkN`+ay!v_By&W3y;=cRt6JmcsJu4ni@|-DsY-q(a<4MeClazI?T*iLo zbDSJ{vJHm(W_Pzb-FN-`R!x1nqwI_Haitw6#~JRm$)WPW7Twjem6eFlWs|_^Q)vHJ zgnjCuVkMle;3^|=Aw0z`MN!6rUM^0u29MdlQM&_vm{8g`?$5qK#`mQ}V`(9cz)C9M zyc!wbkAQQ?v;WX&a}L^4a1^wynbiys>`g444e0uihH-}`5dE6RfBQ`*l_6uIO{nLh z`E(QS3()_NjPwiCjy#wgL6XucV7G9k*!_e~Ex^o>a6oAqCkJ*rKasPf)5+k8Wvlgv zXZMKy;j?sZVVdjzK7HOVfhd4aj~lorkgr2;K)Mq4dBR(M>Pq;zcK%@Ud9M*qbsB<| zhK7o--j;14#^TsLjXJUO`t%cf(XrBx8eizKGH_mLPd5{1ecnDY{-7cfavwC(&oW0o zNAs7@sZQN9J5!;dg6m9=GrbYVvM`BNXFr_qy&>k8waEawjsj!rS~!FZU(3%}hMBKz zd^&rOecj-V;)A2n6+%!_Rj<(uB_Q**@0Tu|;)4g2QqYdOI!JO96Rf-y=X}MxhiD^c zOJ8h=THIUT%{|5#8mABVnA3UI!}g_~CJiVWkHUuusH($T-n9R<*QfZPfRg8c)5Q{W zkgTM{7Y&w$(z>OTvw!ya{HxDGUVMJp6B~-Ol@Q{^`Vv58PSYWOvK~S&vA1+8gA404 z`xPr4T9R+M6_Lk27R$-aKt(nN7%CRqpnhH-um|l;sb1KFIsNnnOJJxj@RF5{2eTfY zynt{xAU$djwg1pvV}I%F&3pUc=OLGK1Bn0L_{YZm5-vA5K$d{=hw`dhO$)dI7w z{_>1|aJ^=>zeJH{NrBTZPg)(Zg6qFnL8o>|fhF&^3LiO&<(?lpx&G@<=xmcSkb(8M zcE%lPNsu=FW#Onp^zMgteQ}eKI@*)uCBS0(3Uu}K;84xe+kt{7-D)~RKO~re z+JLRTfOZo7@`Yxs(5v-lLfQ_fSE5<#t6xAM`68h$xBmIdttM2gA6Q8`kgr_j%B4j@ zKRgL=U1Xn2+@FGCIf0z{6r?It-)xbjlgAu@{nOHC-#>B%{V*)5|5*v7A*wMCe0~Js0450xY|L`t{ujAxv{$)SXHs(fnj=0S4!Tfc88JT|1%>OEz zF+FNX`SRLd#KwrYQ$D5ve2|nL_T_TE#_$Ug%Xv80Xp!DtqAYx~xtv=_>mL?u;hlOy z-4#;^{mKAq@i&@h`DwF4cda3Kp;ZDm`ssdWDLnd&-y+*e#q*v2F53z-Z1r$%x@+49 zPdT4(j7ZuBhf=@+r48S!!9UX;(RSwdA$c>xL-^Df_2>@N4;jp@--Chs%kP<4q{{kj zGrxD!Z$I-lLG^DB{7+0^zh~z6%uw0m{>R2M#izXomTPR0#J?G0*9@ug9-w7Izo!=# ze<6e#lJ|9{9(LWP{$e-NX znCew{(!-LTyQAU@{C`JU|Mwy->=Lj5qr(|XdxRM2$^SnuwcfIDtH#+80%+8_FLwb+ zN3yGZt~g{D)m#2|vg(;$_>%jsb8Y13n`HdcV*>P$UwZ?jpEhJ%J%}VUy?-hULvH0e zZR?*?L%TdYxB>fu@ovm2dX`2FX#eiiFS1c;h8+7h*(l|`Z;)xO0CS z@NWbDZNR^iZvR2jjU==_ii>5k-ghmCM|bbi?1XsjPh|2>bo1X6zVu)4E`cQU%8f^8 zO=^F5$3hUs8vFN{E>J7!dC&O|6*dNV&g(_RySoq){yj|k_h5d{%wkOI{eQ@2v_zrY z8oKq|*eiW%vlf{Z3ZUPy;eRdA?M2G537m5@6vZ4;j_o2?*-Zg2h1rP=J8UE`}{4B>(!L^GI2S^M6`dX7C}9HNNF;dojT|{0TnQAn(xuOMfW)^GE)lxMl4> z1`NVY3Y$Kq9si*ywg+?)3L-)mVOopT`a~$Ivxct+;>ho<#y{(s{3R7D&j3{`);%`` z=u4phK56&S{~wI{%aH09mDv#39ogV12^XG|08@A-sr>g~e$UL`-aP*!o0+FXqe2GlFy?l5tziWJXl(p^Uh73csZ>_xiGD)c$>fUPayRfja%GOcqq}nlgy_hHaiZ*F} z!wg;G_g2Wx-_Lw(mhTC-?!p1B4#xL=R+ZOI<)6}cp0(tmW{ah0Q7&u$h&wcyxFG-F zB3<)IRL8M+B>>9o8;Tgy4C(z2@>YW+=c%E8 z3eyvJ#f*4QZcQKy-qQdx$T9tkSz}&<~bqE?oWlt!*GxQZaCqyObukj5% z1v?1bx*b#W(B&M^Ek`Nsdi|?1Mm(a(7VvNKvj4A{nqADJrqXUvil^?BaMK|2f0^bb z3_bw!Su18sZM<2>s}=x_JEC>k*ItS`isG{y4DyTX53~es z=WUd_tG|+{9TIY5_#y3+iq!xCrtmiRJIeUyJbpQ}e7c{0z)izzG2I8iqx+SkYd`FT z9y8WAZ>skzy?NA3qmSklI$8Yu%7X`}zs2d^kberZQ{70gpiNfHZ3vsUYo}}lVI-%G z=ndnUd-g7A+Chhh!~*uq@3I~1-^~*v(|ssM%!cvG_|cYu12BHGA8v6!K-9$fE~tlU zg(jgsf-Qt5jC`g?F6&|96f<D5pC2cy_ zelafuQ%8;#F1Diluy)8OjR9vTc)lf_J{j9#;_jK|I&K6g;MpmqoR;S=87~CUg@61u zr0&^#xAx568Yr*OZulUhn^Sa^CBrN5+a0W~@+$DC2sL%Rt7p$W&Typd5bq;k2|l;n zX}SNu26&8BP|4AMonk^?T}24^*gx8i?E#{c7lV(jQHrNl#&e&#Q7rErEtb-1{6!s7 z?J?Kkkq(JD6Z9GUd62vZU^Lg76s)N4myd*{Xvv*x3e=0w*2Z}!YlX1vv<2BouXonh)H~}wSid(f?Xrx{K4SeYQ#Az7dG(JnRdauXQ5^cU zdD{&1{LX#X^ZScoGHzH0r-}S}dvDraG6h2wU;hS3ev*|WO{6yMlK8Hd6oPn8$$!+o z3Hr7E5w`Gaqw(*lp_YbzPYrdm#{9OL-y7<;uK}fp|5i7=Lko^<*DU2Ubb~N*+U_|5 zP6rP2r$~_3`X1up@6;Z@PX`Elpwr;@!AXs#|C?iq`syLeMJxa{4*DHm{28SF_wM1zn_M&v?vt8u+LV+%O-n(f zztnzTjD7)z{V(60N*iZBo>%n^#TChodW`3K=)CpPzr0?W)|I|)43$7{ zn#fo5bx;|${&eVzNemxG&-oUwtx=x%a1*_(_OE5N!EWK*SUtyUy>4EczFF$!fF{_H zAeHeEtsc$n>w322#%;9ei2;DYLdrW0ye6w$yBDfCbU&PLZsc-(WM;!^~A9;U5RXN$Bt%|Q}D0KqXoql zKnltL0(a1>re_rLkb2=pb!fG`xGORp*vul-1n51wO6;k7_C{(h{dK0`PvX(VPtq}K zyu4~fJ+|swxQi}#>xrgh8&$l2YTWk+$ODPn^weLX<%~=qgX56mnQ6p6oZReYXnqvE z^o}mw6bdn9R~HxIr*2| zkH0BPwMXxd@F_w41LO0MDw<8+mkSDt8@`K!N1H61Jggg!TZs&!UY1#-wlTr zm!7Iu=zbNd&&(x$J)-IBk`-IlJ=w3d0ZSft@&~1wZTmq8u9w@z{Yf#O?8F`GCUuQk z_n}CfyNPCzr-x-Kx5w1Serb~QzOkiieEsaib+G)MlolioU0Tp zX;tQWpWsk^*MvU|w`G15Ofiag3UT2q>(P}#7|!3QCmt6p4v{$$?^MNXc6ghozOMa8 z#qOD&AYvCEo|YfGf6B16!L>cyt7$~Pg#}otXYg;()12oq$Gz?YNs?a_%^3T&A%Cr_ z5hFV$l_36B`=9sOeJx%;1ypYTvs4g!dKk4ul~4dOh9x(btvc=+7>-}rc%V@##f8(s zC)_q?o=s$s_15A2$=9W5~eGDwy9 z6By<9lJ(CiR-+BA8Q0D`cagB{V%IwkzvlBxHU0S98fdAQl>^UY5PgO>41*b*C2DA>-=19iND8dYoOM6^2&QXrelBMHsnV|F~i$VH2AjReN;ZNmV!rTt%NY zb0fiq)<4_1Fw^^(Uf|+;>>_E!B2`F4<5r*GcDdpV#A(9(FL zMO-(Kz>Pd33coLO!S}ae)MNE|L>hRZytG z4ja(m=A@UC8X}g)y{}PcbEY5F{mNeh@1y*J@MR5Twco!6I*0ExZE8kvbaJwH)l*9$ z#kUy{jXi|xp}4-?K%$v&1ziCo54brls)bzO|K>Ch!CFYLYJ3`)3lj| zZpxdi6OlCwk+(|ZpV-)VPp~j2(F7wy)YZ(g_{=2ZXfEh|Z4KdxsOk%26zh!+;S$9;0X*g*6f{&7<_~YDF(Ky-_z>Qp+6M;*r8k2sAcx`LG4(k?L%gh){h) zChJUoko!(|+;AfQW@3S!lck><@%sE{%V>{s>}xe#>nW0CAt~WSiI?n7JVY zlCwzU{d1ArZ{r6^vWTAxc;79kB%!9~iuX!D&s8q4!tJh8pOIsx}6Ye|}M zwJiaCXpm6nRCp-Kpvbcy>nu460wJX!&$$`+!k<1(9e|^7^AkY>?m!?aJvv4hZhR3W z%b8NNF!v4N2Q=f;=ONj{S?Z6718AHn2Z@8mXy-J9`=4C}_yTq7dUE0qS#U+qcGzM1 zQXH_d5f05--5}``?l22{x5yzfDf`@|^O>l5$!N_MGZh5Sp1SGS#hpB}LUhXr zTNe+I2^!+bAF=uc;>&}3NIMECvNP}2_CGt3ES3o5Zdq?3RK1FyAUlBoq(3NmyY-{l zyVkmNIjPt6=tr}CTu8R^Fb4raS)q|*Lv_S!MXa$>s#1cku2Y8@k|&N4XSAG2W7$r% zZ=2_g2=j>tA%nSt`R7m{~>(x-o|)&a18jeBOOeX_=3v~dm*}M zWBa;Qq>*D3-T%yd`Ep^Buj@U=5=1!9dbTfgtpzH*E4#y1`7r8jcgN;8bf_GK;B1NP&2-P*bY$vgGu?k1b zED($2wt#L__uz{lfeS5zJOkM2v39%F;>{v;6NjUoqn;DYWaKc?W_nT@vDm{|937*5 z9804Fi{@>2Yn=@}+i$}Xs}C`V-jQ!ffn{Fq)}^b(MY@WDHw*{##r9ovyfWY!;MEOW}N&Vr%rbG>K)x!OAcYE?c zs?~M*HUHIwO{`YonNeqMIc zC_uTtHv=1(GDiLwBvy(>E%X@(=!(T+ORij}U3@ALz-7wL^X=Qf43$99_@7RVTg4!k z#dD%92Q;=NnX>{R_U1av!QGIJx}Ra&-Z zJ>Ilkpsk3*bCmt4Wpp}58h;v-YKF4DY~nT7#2=-fcct>tQ=Pd?cJq8V?+XL%)(;05 znWCJkQDig`9E!uT>BNW%AjoE>Mi&Q+yn0SyCfGb$;67$9{ZVG&h3|BXt6418rgliW zo8%eoKXIslFiiZ+rMf(jZ+CXl*MS-El2YgW>%2JDby>kZATrmuh&-)4%)`8qyoGL- zC(rPD^5n*UOvsgm)6f`ahw0orZb|ZVc@VCK`;PG#f^bN+=y<~?1(@P}d;i50%U=xJ z$G>0v{R{uXT_g5o9FzIIkCa`Pr+nQTFwv4~vdrDh*T86nlma?3GB6eu(czHSw2;jzKy)S6+ZijH=KIbWwRT?lfnq6pKal!F8QF9n$-cu}qd@66%C-@pei0Ln1ggsS%zN zQ=~0y!&~Qe)CEuz28O2I&BTXAt2rd@N#rqdL59@PyvHH-_ zUP2P!HTmK$24g|b_5HrEw&ks<(hIM;Q*Fm-nU5hR&5)PpSIN+#kzn2jZ5WX>mG=D` zHqd$Hs<$swEA=}kGhejT={ZY$0Xenb30ZF;RDP{g9TpJt#Kr6*kI><&UV2K83D0y%*oha%w7?h(JoP*r1mXvtCZ`x z8uj?>52WYAE*-P7qYh?{o6Ih*?r}(f`R=#>NVI>5nW&ou!hUgoP4Gc=l2fG70~?0P z69yEAFhZ0mT27K8?l}3lC_J~2jBXq#Oc^0{#0jEm{MKMXbRAWEHDphaYJ&ImSJ!)7 z3&$jT*3DZLGp=NXMn)Cgcp zvd2#c4f7+#OvY1|OD#0He@MsuiT5l1!~1@1MxKS=8uU<$5o^lc&VH?(7gF)f+m14k z=RQqmZWpzjK5CG+nz?z871O2ep*Zn46|mny=}h4$&smUb*)(@@jODaEm#u2TAfXlGlib}NmyUb2?zV%*40BmMC?!5FqjQEnq1$b3@;|S2zIQv9N(c33z3Bm^It!9u)2>k6gZ!gSo5MII zbuX3-ZA#|-#Jk}}9y?G*MZI@&3=GaF@eL`i` z3f!0Y4)IE||FKLjfFz-Qk2Q zfh*s7xLR#c0R?A-ymr$YqlXX14y$;Nu?!NJhp%R;?=0T5UVBM-Yx$>F%Hdv@Q2ue7 zZPzV-ZrAu(*{2ZmBS|gnB@t9OTwfoix;5bsSEEc*^9Ju!M@C;$>@t8AaVgF5*{z3l zdEziUK_+(bTujmwj=yu%K=3j|61SVnXf9>nGHm^fg#Doo(ra*ys z?i%+}9pJaN!ZS9k<`SzJRw_C#caIV68X#zOJL^z^*l0qEPXvBC?$DkbxL5i0Rfn#1 zb?U=TaZbWaJYk!XFaP4plXzg{d>|KN3x8bt? z&2LYmR3|}9lA2+Wg>1>t-%8X4Ko!FLJI-+#qjoH|E>+Y0So5{J%eeL0UI~W~zTOk` ztKfFq|Gv0&al2$)?`+Giy>Jw5>?hW~WYW)7s`O5eKu1nVw^p1#2ok5j4WMdomKNWW zO~UuzbeSDiOK;;zhdPO5B&H8ZXWse2(E?2tDGHqj=e`_F>0M{D@QRDg34dMN?cuoK1noq%W$$Qx2hdviNCl- zNwf&&Y*|`n5@B<^h2&mu*8_4o_&P4gGZFTHuc z>pi5Rf+P$>kYyK=fnNI zv>5zn&{YplaBmKjof|CV+aE>0@AG%~I^Q&xj?5rW>BnL#*AmJfSVky}p$?V~M9PgQ zA86!K6$@BWIo6)d?i#dTJ7Z5xv|JJYPQk|Z@V5=er zf>u!!0-arPXT&=WlRIE1xL$aC`%h?0EIo8dQ!ZXBqJcix5?Td2y z(LAjssMhGxwQ|xLG3Jm~W2p`mT#FoVhlk@|l%U9MC{dphxD&M|1uKJ7S3uum7p&Xr z$*tRMi@Lq78E%&tv))^*Dony5`sLUHn)wOJvJXtO1v>Jua^Xv(-^BVf} zs+N~5g`EgYeZF38kLz~pxH1`H2kYexOsG5Lq`jmIQbfFna7Zr0sEvO4!d3Jn=XGpKEeYISxm!#-t1ooBx=hs@D#g&-Z($CF&?dOFYWM zos_?k3soh#%%S5*O5GPd3nJLVH9wYi1GLIu0N*!mkk#oPv+{ClwJIXd`7xhgO>mS9 zT^|+rB=XWb{n-BPDt2VgD(2{l`jP(HaJQ%$38iSbd@tq!6+|QBxV8AqE6Ts>-W|Dt zBndZT1C|i=`JSlg#ES>Dt1TO{X~=0CVKIqYH+*1&`_{N?Q6@5TgD<+_-m=Q)Xd!x` zUHys$Xoc_lO4pE-VL(|X35Q?8o>!^d5~7BiYHT}+?E08O*bIbZkER_^%+q$4cl-H7 z_}SmJA-AwY(^8#T@`q}b({J9^@@_`bm~iNNHTM`<LIHAAWJA$OgR5lXCHVkte8z{4 z1KRCTcH%~(3R3-Hg2wq96FzDVjHd>=$Qs<0&9875I9S9i(Vyg&f$0 z`=9r2vSQ`t)jr*IOo_r#v8=pm$?|1fmWrjDjjvm?k15C2)^mrW4wa2DE#3Hes=6a} zyaB5zp5q@WXh~MybxZBNadW1GS$O{O026XmH2HH9(fy*PwQd}tfA#jOzN`HuW;4>! zo=f_+A3^E!JaSRU(CY3Fw<^q4GnAN)wR4Z$mQ_H`ou8~O1ua%-bInrc>^Tvyh52=q zE6V~ZCV0Y@qcOyzQE~>t`r+ zpq!9fkFBT^yUTbAxhyXEoOHf|)Wkc|JG4C(`nywFdP9% z>%NUYy9DlG%gCsSAyu!uXXkw#7cv~Jagat!-KBL@sFJV%3dv8^z*pT0hyVaJQ9Z%vE&%~{~Y&Txp1l_RQnYz$VIR#SSJ- zr`?QERNY(0e74;4jBUJ=K)+2h>9Ey-%R-d+7lF?l@+`I}6scKV?3^sDNGtjB7Oj7z zGwGZ8M~O&Ljr5xsExrrv60alzUmTJyfHXsYtE7PzuIW-qm7<)6F0BAOynh`LBWU_Z zgmeWH%B5Q8*(I#Oj5y_LJT$kgS?rK{5CT`lmsP?|k$}5ND)`x9|JaDLgL#TMysV-; zrU^>$Vf^u}f?GcGTeG!)V7}S6I;`A!Xt*h{6v`p_8|TP#Gd2-e&7H@>+4fg+Mbt5G zxVr4i-6=lv`Sn6UZX%FAE-eM!Rgb^HpsY|_%%j-JzInvH0?0hEPGbM*k-_O*|&J~N5i&nVZB2s8z=I4SrZ1hr}i4gdH z;3_qGdT?*%XUyeV6pjcAmshAHZiTpp#|M zeE9hosDd>(+_XS790J6Pkpf!9YK;BCm@)U#)F8QqnPQ=l`17LAA|TWLwEM%%s3{&w z7)37IhdoJS;^rykhQ{-Dh}+8_&r2LQ^wsY9JNBZPvcjGrwu6D2giWK^{DR1oUOu^} zv-*{iA4R5LX-G}Xaj58~8Xnng9?=u3YkR7H<@;o=xkydPm9f~|unP3iPsr62FN0l> z4b04k8*2EaS%_3kniINKW}?k_%v6<|!J43qm53L{zdwBte1= zcPGx+gj{;pbVEfnVVF%i5HIQK;K^NXGR6FLt>oDpJAo5LhyYjfKxusR8F~eY(Q~)8 z=Z;3Vsx3DP`fIJQoBJ)@*B%UnBGciGGBhY{O){)hE&+9Z1i6$z`18Z1U~HwfK&eqsme*&dZuWka?(94nfv{Y~IkYiA5rQsx{;&+U5_f zxcsc;n<|i0d_N^zv~Y$v8EzVtzgCs+IwK&!?G%RI8whREYA6tU#;ejcec_PLYVP z|8y!{pb{@3ae7RLPtIw%$%wcnX!bPt zh>7-$W2hLImTdB9#V`_SGGUU;^9@dgtWk5X449>$+;Yyph{V;E1C|!M_HkRFnpHvp zH!Y*I4}p!XOh3+v0OHOp{b$F!VcFM8w0TR)YVe58_?8?KGV>G%%YD8Z+@NZ{ZFw?W zh=tAteck&IRK`32)Wnz9cCR}p8$D(z(>^TyF|B3geY>s0mP^X4ad189+A@LwoH{NG z2`&uJ?g%`*-RX;c2vmK#O(}hXUJ?lAPH+07ErK6tH43t9b_rQGdXn{JMXm5Hj)7sy zoB<_qC>OyQq#8%a*{~q@;F&Kgv%cxszjnaPuHi znRh1UcSUNw;JBgRY4hkaB%VXHs!y>H>YAhjaXszV^A9BHWM98pSLRwYqK9MVfkOUO zUtPEnmcK2Vbr{QR@q_mXxq~2L*vj^-{)_HbN!PPFRMb;tRA(@&;CA%)w$RMg9=2|rPWZKvrwAbB=j;BjUAnB>AeXY<_|qv`-Z$n(u^gpTZdCde zu|iJ3S_7x-q*IWyxj!HdU)KjNRe+F5Lr9hbU4*-IVAMfPNV%q-eWd}I+^S@1Cm7tj zgMi$3=tpv2?+p0rhLj*Ior|JuSs~f2h`rG6vvHZ#XpT{~!F*XH_@QVaE9?gh7hwtX zhco9zQ`6TqXylMY9no_|@KUe-8TGTcNRa3|_SF6n^@rDe*!vA5SgQNlPv zmu31Hh(-gO?mh~uyuIpWF#XtF<2^w6vbLmIS+LfouTEK?FxP^)<>KU0Yi`>muEEYs zsC!)CNJHPvAV6o#r{Fo{$|@>Zf<@BxW^O%q#l=gCCaz%h z^hs^rEpfKqYF7Im*VDL&gbLuhy2m=SP6HiFn8uLCD#8<$h|XeFE-!TTmds==T7Vo6 z^ZDHOBW*5dpU6}IL>K1!sQzOKLj!Lrp&@z=#%uVzhyP@0xrUW{A4YDxRoJF<({N_Sk{_H~Z8Tr6X9-rvhxu}qh@tck^HV>bKHkw`$O?4Hs)(gH%Cmqq^>VfNRy`+e(L z=O|>a?pbAlA+u|tErnv#e5wYQK^JxcA|Ynx7c1$z9%S5dPn~@X7N!14qJ2G3hx8q! z|1W#MQhvH4N}r^kzs9?bd4B4IT$_s$?w(*B$LQp<7Ln3|2~46sWe$LPSq-JdH0X~l z0{!8yY;=S=^V?6_|4B0i`Gp)a#%nUT_G157p&OF&hCCmbcEq*M3oez4-<)aVt_#MKZ~Jv2l%l8-^F6Ri{?;&_>y{6!-^oU0(=OTXWnq2vLHYn zmty6t&~gBXS$5DLPouc{&*^zKETeXtv`)u)aZX={J<@Ix9d&@vE=Rf6lcJ|I+H;sE zQZx|Cbph!sG4%3-5|Fs)A55*l03va>*yjIY%PiW|Pwe0^Sq#BbL40O9JC~v^0Os^n zN9J`1f8I|1D0B6%`!W6^b0q@DN;uPE??vP(AljH~Iqd0ivhHR+RbP~8Cy+oqvbM1g z_;WD3K_fp0X3>E9m@%aWLsR9|7KeVZ#~d! z(~8--CO=VJoAp);$C{Yr}E$1OG_9$knWbB#Y5gt z{VGoOpRC$$O`sXU;maGnsDv(I-Vm5Bz4HbQu1VV}nSK_dftaLb4b9H~x;Mgl^d2%E_k*MVG1B2U1M#z|=QvH+n6aEssFE}=#@sMTZkpK_jtz#REwM7A z;96Sw+v}Zq?=u|eOl5<7LU-;xVza zLbr-{9#GPsuhJ-Sk|TZoR!SH#Ii5$+bMl?Vxkant)@3@a`r9u(hfr%AWt*Zi9NlIJ z&hWybE+gM5f&qZw`!`YttT^Gn-(_&OG42LoQgZusb3d1CuO6=S<2fxw^P%0fYh_#K z^RLY=nBCrx=lj>QhI*2+9uPVp*Olod`>{c7fEHh!H{39d!H1Y>7Zz0=YCeSq$=w8{oyy*i@<(fArrb0*opayoTi>;<+~qzU6>W}35S*U z+e~`du>-k9zW(dV%PZY`6k0f)`K=S!vD_P`$dzL43Az*IbUkAesgBdS$GYKOWl57LM3}6W<*2Sf3F?o*25-~ePPhqRy4W*>jp9lXp;gl8*gYgqhp<>_jS(^#}>TTO!j_2=pjJSbV1 zJv@ByK$k&4>GmcQq)zbkno9$;Ie(YuW!WYadhZcWhn?!oxQQH>=eMo}o!BTGu}{#y zg)(i0$umJ#pRxNgZ77CG4C=RBb+#hCEfK9!&BHDnOBlu=-soRS+cHAe=t~nUhMx+h zTDJYFnm!oEh%hpahMk!v2tMuMuj639_lV=GrJoCwJ)WbY&F9;Omo}qtd6vikhPz$q z18`>mXnT;?d`~x^b@n%YfKIh_Ad7D0r(=Z{?Qm$(Lz-{&h=PDlk*3V!eWON@q4%-@ zQzCyK6&;08+0s|+!qpH@>J`Deds+Wwiu(+9y3h`JU+M10(Dm^8+#QWMVc65aJn+Mw zexn;w;NIm?D}+<_nqXI$vL84=>U6hrCg0(6?39DAT)n#IIDNQRya6uQF12B4VWI|V z4I~4{hPy;tbXfsiDQa6JgP0J~y4%nAFQ)H8F0kuSz$dD|{-`Ub6YrG5U;l9d9O{0h z4c|48{no`_K07(NbnPe$eqlCx?Z?vS&dD|dQl|Bn7eQBLjo_;|SAM9aTgyoXV`Ld6 z`@@Wmx_gpFZY*8HgpnnUp7d}$1S3g%TbZs6(a!#^OrThNfiap#v=}J zi%Jwdg~Y9^nAXAHGH3(YC+pRPtN z&~n+=y$=#GiBnOq|KErt<{bdEMcIlB@n46e8De3OE#OYHi(ZAe$!)G79@XYu3)9wL zvJ0E=F36T`EtbAbbIN=6!02x~$?UYjpTH#g1NpcDMGw`C{mSJEKMcEzIGxyR`2{f0G{)OJ(zH-%l zyR&KJZh!ElR{55rI~E>uU1wV5MRanLbwUuiN$vGAyw*S zuyU&mb3>k#L_)7uH{h4Km8BZKJ;>Qc4)vN1P4_D?<=kh^;=syL@x0f6q{ScSIi22J zhH`(ku}}s(o%QVrU(_IJ6tRzu@@r{mYew6ZAzO!KCf>6m1zQusE7N!)6m?Byd!RJ1 z7OILXk!EohEYijIXqR#c;DESPpb0J&U=g}Kb$O;>8MTh%0F}Ec1*zsSvw_| z!m=Y(x}3mCU-IZ7eQ4(QB&$-UR7>;9tvpPv1ofR3JKvJPeGdv}UcYaI6bDNI!?G=W+#HYq;*~T9v>n?4D_NKK?bRc6rwEU-byr& zK~8)`%`(er{E5!>mD!>THl2Wj%2&A+=!bNwBMrftnP%$a!i2n34IMBV6U{>RSvYtXptdsA`wPSoJ9}>|J%=h$8Jfai*H6u~+j+(~4MZ+7*BI zajK*6i}>TZvi6t2a@1Xl#g4Ei1nnH_OScW8n_IF$mfadEzGC7pCkyr~P43C{gDd-s z{YsuQA9hHU7HsVfu?d>fSQy2Wlr*T~NUg}O?Qn!7D%Hk%+4o2_x_$9pQOEqXEK26n zjORX8HBrA6sGP5Nt!qVFYM5iEx%60G={tTl&Q-{s&=P*{RJAwG-uEaelXd9}I9Cb9 zHdD~z^|s85m$OKA@Nsr>(!hH)q`(~PW+5Dt=Smp1?)GKxXC_WVBid#I3p^lH*Rbo^ zf8@RU6lDM{$F-8#{=uZq4o(fXFNdv+pvC3dLPv~@y^QH~Xsb)neVTpeA?hCX?e)kd zbNXw!%U_ssy&b!R4N8`+5W+!~BeYsZyUV`eOfBXf^f{X~r#g+cKCBk^T=U*Vvr!1= zwo8Lgm&Odh)Tlz+Q3a0Yvo|fx^14nb*u>h&yE0?t{WPzr4ZX0zA3qw(Aps!v`p5Or zH2<@n?`C`O#=}tf3Xf}>a`hNKAI(e|HXtYNB*|LDeJx5U0A7LcaM=kqRmCd&hT+;5 zy_^g~t60+a%vM-=rf=@|01T5d&lm21;6m)=RKwEtr?7XIuW4LHbLY?{ZS3co9<{af z7PS0L7Einv8iuy{W;P~nXQQ5*PFw(;F7$%;N1pOCYE%ssO=rdTt6SnncE4Cx|PB*CfZn$O}mVqt>X^9U!0DSP}Z)Do26*AwGU6={AzE^_kVw0}| z)>R44w|hyYq7hsFBCkh{$QhYJb|a_3NC;N?UG0%0?Htd;p<3S1iQ*s%%327>Qj=u75{x_a7W_dZcyxVjr!td*TWOmx00W@ zsxT`kIbCp!^?<$;9Dc;r{EmLEJs5VFsFaijb)%EcP}N&%E@tXZzF9Sff8LezH6aB+ zK&oBD3lUu8n=NBKpVN$$F%4JnHN>;n4lP{Q^gw1fbeC>RPv98Ug9Zf5_4mPdd-fKi z^(PjZ6E(OdMtoocm`tsj>W@4z=CO6-@YaeMXn{VSknTpkZv5dr#1{4>8rLQljg`=D zdH7kbOUniBT^=hqob;C6h4Pby2*f(CETql4U;K>b>uQyje-?`A7?P9ci`Y?k6 z^ZQ`W!nr0?U7lNaiElasYT}-ak!6<$ackOR`|J0@li78xk7)SsSNfFjFlt@=QC`gR zULGDVX?N86{?6vZP5D(V=A7Fe_XT)aKO7K+xAkpKG^ZAT{_wVCtYRXR%l9G;qYv1= zfr}kL+NE9B?8ds)A6a4ScT_O9_t83qN0D)N%h!G5lbfwf;T?^M(YyFf)bE^;wMb&n z$6+eY@=~_J9$U4+gIP|{x9b#;(6aZf&FLWVLe(*oR{j}I64D##$6;paRhHG9qQ~{M zGA)wt?HV(b!3QxcS80s!%g>*?I9}fO_?+i3l2rJjrP=5EPn|1>U1ps#9V7d zwLpGSVjWtAZCun#$MQ<#maVGjfTD?O&~&1wz`3z4kQfDk0X<@wwnz6WgTZGf$Zcja zFAd_wJssbBeZbD%#XSZfx}cpt!7Tm5-g-szvBf~zbr}-Y8GVN3J;?Q$5$Jlmv_wb) ztcP73o)$APxJ+YCIJ+BXtH5dU*t_@ohChT}z!r!uVaL?1JdH|>&hovftZyrB7qVyseLnDO@G z!m6bzYE}*w5Z*jvH4UJLH)oKrxyMf5eWJ{|-7?!3`o*R2Q|N~SQm8ram__dw(}Qvj`a3$coxoly=PLsPN6hh+=~0KV47JyMu=aN zvjPuLuw<(+Nyq&oAwvb^{c{gPM8zi=mG4d2K!2UyyO9E1Mbg6Rv=3%ht;AE+>97JL zA`{ZM$1|fz6MbZsz1rq2^txUHJvx*{+hwHeNcSpCp9I)DZCl-P9nqd0t~k)BgLdiK zL|3ghWr8l5t=;JX=l8T5oY?Ac;s0arEd!#?yEb5DK@r3v1p^fXL|W+*Lg}wK=_u2Qu`}uvoEL$@3s}t9`u5*wk z0+GpSdF3lm=#MSmu?yzDO|dNBsZ-VircCtC?wTVX_WbT_ z%z0}*Y-Cs9;;cyQ^~EjyowDgz^`_IKv${pe1R?1ycdnr%JD*v9Y<79vwatP@^)e`z zp2D4|nCr9T?eDra6S`b2##fu@29D1cGJMsY>DeI3p2w~Rmj5vPyvekPYaZKfwy^5~#fUi;&atiWuJa z-9KKL9f{e?xJ{Tm$vHnUehnyCL2s1|Y-A3Y@6gw-P`V9W&&&>JA3rky?EPwzW>L?Z z#67gk7|W%J_Nq7o%JJUds_amA=^-@Lm^%{PIad?*Gg-YYA|oFcgYO)%S;FI?-GVt8 z$}X;6=uO$j-nf)J;neQgvIF^? z18|+e8?ttV(~ojDrEF}$4DX* z@B_Qs#>XM=(!X#`%mGRq5|==syScO=N%Y^;=;$}iFJR~oId zc(LTXT6N^;Vd&wKfWHT4<#lNKZ|ua#%f&!)rd?Tq0$Q!;XSHF5;uoGhT0APwZrXEt ziedR(o9OoQF2i*iA)&$!d6NS?v9%kJd^Jv1eIiPoPl!3#qr=i`tX>_*{#DTek2dLd z1=)(c``ODjz1g}$WJAUv88EAMj_JuJWHfPmw$mk+6S7K>bSm=8()LO(SB6G@+K+px zlBIW^7vr+k?U)EmV~zQ!S0Ul9IE7yWCSERwy&n0szsseWzOhj~n%~&RzHqZ^-&_!1 zh8*0Hck*4>Hz;B?t(=C{0_7eCdX!_%tI8}$p#O1O z#^%rjn*iR)U~zT^Z24TOf_oZaJ+pbXnWAYv09=a}h?Vb1>fv|SB?f0g6pmFhH;1io zZY^}6eQ*+6gHpIihlMPckNH2U!VEyK2pp&2sg zYT9ISU}8TYVL4u$+puz=RB@IRbE|OwTx!U#?kpu&Cf?;VTLIS8!bt0vXsEfGNFP}q zjTYp*#LWyKh4TIHN9eqPTObqpKW}>`n4uE_t3A3b0#eqX?_a6cHPT*;DqoMfVEq9# z31p!A?8yVfw`jw=1QXo4s#5h!@Q#_C_PMuP<0Xp{76^FJFqiB?7{Z3Tbyl_=_;V`@^X3Oi`b* zDt{CjZ|f%C`6);K*x75}Gfq4-`Ch5D5`V&|+yPAb5MR!d?&+qN zES*&p&xc-$WSw5n1`aa*fL$lSZ2%qV*Ad_Om3XwEO+9}{@9AkGJ21O^x|a#1~wv= zw{^Be^gqj{zVj%6b_sD}=Su@|5~S^*do9#ij;(6}=FNMLTfKYaGINe*_U;~MvRM_h zHudjdJEzAWP^`}k;2P`CC5@21=x>s07a*9_-a8f(iLtm%!jJUMQ-zy z!jTgSUGB540}R5Ie)I2YH)qSso6T_Q2_27IR>`i!0Y6b6M14h(zC*r4Vhi6dRRUrk z#LnGw`sG=E(tB;P2cDPXPk~z0&>mbieVfX9d2NEXVvGp$K2CD#tb^m zT8b{;YV^C6dfS!Kc~q*AbGg*=jJ*}s$%L+??V;ARQ4Co$b)p0zBew$JT!AafO`Dp@ zJ7mjmZcTmJ&v%K4AmV(An;%ikASO#BzXZEf9$%-J;y7$Ja*+5kOlfjVti9e6gYe?q z{@SLw!vS6neR@_{4rp=J=QI?MyED@ppv<8F#-20%w`azts&x_|MtUmibmk__hv?M$dU;=SP!A0RerpDj=?WtFAoS-gWFq zwR3EL@hAeLJ&%$fqQ^jMqVglIb(;87S@>jT8b58uZ=48 zT#w}A$9o-)u6RrtoF_2QOdr)d#xPY+Ief+>MWDxV=PH+%B4!G$C5<${(N5+$9?3P| z-f!0^#DerDj0iJ6ecZ+PRrYbs%|`x(dasMywZ#rv7kYK#PJ++M9kqhm4}s6(LGB7L zysJ|u)b|e}jmQtW7$N2-s-JQal`prUaubLs;vAb}P^xO6LZcEvmCmGU#k+YGY9Rf4 zESGjwMsI%XkbuWqi!I!f;^bJD$qYS{QXcjLqE}3(&_}5UAl}WDDt#Kuu(|Lm(Cr<& zTW>K}ha%<-Mr&!S348>3fWRRO1&QsY1gVZ~DO}|m^!3|XPN={=HBQY&a{y*D(Cf^L z8A40B?(-jrNgtE@i-3YvP;5N@X|V^1`_UEgowXr-NSyzur z$t2(}@}+HpqPk_PZ-2hjJ@3zn5QThLYrPu)a>57$k;uBq?T7>&_(}LFM`Q#H zpf?GV5$a&3Uo?<|^8}@9KK1j2A8QQ`V+817*;Gl;SuM^gpS5@2y6*K=Lls*%x-qBs>MPRS3m&#yhxyO`O#Aaq3BsI+;|S z-)=c??^U?CWELp4LW)>?#S25CO^y_v7l{_3i=P7&V4^nnspMdAaU@k|Cj&T)wtF_$ zR(T{(cb$2v0|46*C}+gltFzMyjN>0+#SXc3L1ui;ZSG5-XA9)4R~L!9Whs_#Jw58{s+uxrBB|^7b;PGPX_F{2<3_c~$W^a}b z6nE4?3u}1yt${R9ahn2FRa3eEB&Gip44h98u-CX)BV(5y+DSn*^U1ip6-kafKEShE zp?rbeR#^X6`SZ=`ft~5B1LozfzCVq(uY_D&E!1Urngu;YX^lx-mC2W1+Lg-uk&l$2 zJeJ-L0)%juP4A3FQ2w6`1uthVar=L^4p{X#y5xOU#Ji|}Po@u*0*xb~&>HDaoP2Ks zrGLi76hX^Z1_S3H@F=@5;B;jkF#}#V4P4cSHg{ziqta6-Po_Fmm z5+jI%$}98x2UANknWjL{hd)scs`fLG9-Ks0o0z1G)!{#fqB7uDY8SztN)TMt9N19R ze}(BOKC`=N6p^nBYRiaxh)ER?M6EJd6XYv%_Y56{gp+}#xZPD(LybI z`eWsd<<76g9DLj|IHSFb{DtO3<iZSYaihsJU_B)#3&ux5~%BiDaVhcPg^5%?$hv;HN;=`egivyQ# zzYL{c2@t@4O4;SmEby04=P35&XBxZ~F_)jWSRPqmT9(k1xYiJ0v4v7&eR2$aN3^N@ z$tEaEqchZVNBbmb11|ZCx%qa;=%o_J^0@Xm2_~#gNUVLiPjRDs&w?KCOg(9uo+5C- zpVqW7fr@$@RmYa9FP?CKhssqP(tGlUv8rkjs%JEl1$n1rDg{RCwG*DNjRB(cWT%ac zx+z*HH>LSgy%frVox>YNb(>$iT|~V6LqSEX*w=?UuT_^sJrbwq4Hvh8dEB^Kx{F=I270VE#T zJCI~rVtLkYhhuh!yDN0PsX;6=Gh?%9d!X)=&X_-Yx5>A6E9G4;R6Mtz)MY36&M5OZK9E@(m~HTI!t4-mzVjiK8zZwJ zr336$^Mc+14_+KX%LYmBroH7nxp3?2cS~BN4Yin>VPy6c5B^@#E+ditU;Q z)BQB5mmLx^juWjDl{n7IA3G=d>1Pt}w{UgLuym^_l#lbf7v-BN42l683JzcpNGdoh zfBaZY+I&%ce>8fy_(4=~DbeT$At!?7KqSZ>IPJP zru-Ua#<50P!99FKi>G0WC~9s_YhEV;i{>tj|IFk2q$q=qUtJIVHpqI?mm%uvJB!wx z)HQykJFAAuY$Ogt-vU&yUqD{qsYCibZuO%7Wu6hDg|WNnc6O}z2-msF*_b~Q@p!Lm zJxACk1Fl}jsOV6wKF zm)N!b$6faCr7X64A>RLHsOXb4Hv4?EfX<=Jn_vtMlV zU4Hki!0e^jAr*y}9Lj%2tBz~rS+{xM-er!Y4K-}$zgA_{T+Zj!`7BzdTBUnQUsQ!W zx-#;pOxB`8e&dxB3Vi9Ux*EFr_3DI2TdOze(5!U39lF~ct-G|Brk~BHWzV+86usIj z(~Q6WbIX~l()_;iWkzh-H5uH(nDUAgPu~qv*2%Ls!{3I#OT@EQ%+=lK4!sFh`gHVX z2nyn!QCe1K2R+b$_Cg7_J6T4gPMUNc$yE<9rXK2KBWs{XuW7XAg;<0orU+26CC6B6 z7R0-h83?`?bh9$Ob1gtuhGoQEATXLOg zJZ#q*ePz#XI$NO@^5ctich?`BN4a@fbY%B73VFCitxJ{JS z%GV!h<;87eMA9vNEpKm!AdNlqi}F4`ld7C`8xwg?KHW+t&?f&gI**k%GkkV?7K^oQ zLkVz%YxYD}P?)VIB|MY*MvEJlsVUzfl*ev9(wW!S&^P>1CUrQWJPbEwL@qx;u^X$x zt&yZyU^?v|7ayg1GfMTt)-T#}!S$Z5GS&92qPW1`chq6V)ZR%kSED)}bqepa1bRGh z$&e99$}GQf&PZp~jHFThTfh1cN;6Phrd7qarfuV{h>=iVm`Zz8fkS#D*Ywg@ak2sJ zx4x$R0+0t8yc@nOvXQ}_3b#$GN%X8=(O%DM-5i+hvTk1B-IraT^*_19l-257>lUu zG8Cl@lxDBhud8=tue;gOGnYNF#fz!<(pk{zi;ZYb5NyW8l&^TBXiUU99HVr}g`fX6 zGSuk~9`2^E;l5LnhqBG2x5=vVSSStZYrN7DTwlPu&Nf^<6w9Eiaq{7sy2cG-4JAWX z#$)Fn)L#*foeffz40lK~eIpHSevK>rGym*xcb>CXSuNFy@p2e#E@ElVq)|P8nf(I; zjXwOugQ8WZ&c@!2Qf57{Q*R=!>}39UoMkJ-XEUlP)Pp?v!GAuD_i) z6(oV>)ma$x>&o0(e~fz*P;mO746Z@Y{Jol_66T{)vSWAX-T5jo_#o`CH zwR5IkXJ@o4=;C!%BJ=jq3eQ_4Jy#|vp57Co5ZH3@I?J<@pG&-bD<&(ElV ztx=_@A(_I#2t>GClWZ*U^|}WXd^vvPnkbm-s>}E!#36K%R2e@k-=@w2uul|_?&@5o ze1vCBrC@X=Ss9O#6b{*uk<@~o-<3AHnPKKQN#o$tSZB0`lKCeIsxfc=O0_ZFgik!( zUJnQ7AGZHIw-SriaW*m!)23NAroL*@zJ$VafVB$k-#_Ws2M}& zx<3eayj)Uur!0#9_`p>6?y|@PLB*4x$SFqgx^BT$j0u@oR5T7`%a&`Ofr!P zwM^174L3&ItZZ;+KCyP)u9h%1-tzXn{HaEfqH9aL6|`kG*Bausr%Y16g$p~=%)Z7>yVF)=nazM-k&`=Bzl`0(*_8QWX$M71$; zt)(FF=N3L_)|zhKYlf*vqcRK(6vz~l!G+xFSkyjJpE+Q|Idi^g$59=9mUd~el*^q> zo!`M$1Aocg8B2YnTz`)Qd4miIIwf<-mVC*M`1w-%J)!P7p8SM{T3NnFfwc;@Q6kDY z*eVhu$hHhE|80zUYUo4cuJu8-d$>a+Wgn6i?W?IEd-mafjMCh&;_fdJ$G=+NH`$8#lbrLU?9V} zV}fgmQhw^#ZbP{*Y%Wg53nw#wBzq#tx;S;5Ut)i}4(ZiX<8=d$)XN%uZLEygow}5o zI4-R(3uA3-zWk$?iK&+P6H)?rVQ1@D?VVs}eY%S;aw{+rP)_~7>S9D3UzWMpZIS6_ ze)8DfklKWh1D&lCvu>Z_MWI@nKtRd%FvOL%Jx;%uoMzM}^9famHkz4X=1%>*wn0&j z+v&Qi8!5Vi-JN}hQdru`LF2AC<7vy)iUZ0@%dd#(3+zMm0pxkw?F@&u(tfN8CdADX z?&h91B|EQLUo53$#2UH@oi5ai!?~&6;@uV-UXzhZOCYWwL;;vW@7<*j>N|}h!%?gU zZ6Yz@tH7QM0Z3<{PITMRn$c*phTdsh!f7}rUU>IM+BS!b5{3@Ly0O(JvE3%;)iT)L zvkEgRiYz!A=KnaqCi(v2RGRmDTJ6RFl`b2nm_BI8QIyOb=(vi6B@ehYN9<4edP{#H zKyS|b&XEb_5<5c@ocRu8zMy?>i+kxYP+wk4wd}nqjfKLV!nXG7>ubdpX}sQt_h}h; zvZayP5?>eBlAEp~JnM^I39lt|$CV0SUd+3Q#rFb|5+0t2zwu1SSN6(ez{R8GXP%*C z4G;1}e<3xb9^|L^01^SF(k~pvtz=43!bJrsvvZ4_0?a53Y4unbO>ZgDM3TTsIEBj| zGZ&geB|DRb2O!A^Y0Isdt_JiwsW`1qo^_Jq8_p;TIRZX3QVv9@YSW~TmD(A6M>vs; z%Bv{h!<@*#y8NJ7ae^KX)hUnlI$e3-&F%_0!-NZ3y=N80z!hL!e+sofIT_!fME&T5 zIP97a_70L?aZa*O9orej>=@g^>>B0-wU6UeKbt*Nm1ebg?AF$+#aBKKe}8ppjO>B5 z()e8y37eJ8^4-n%n`|0q2d{N0z)sd6@cb}hKAxzxM|5dn@2a$mbYWR%D9($DJ4|&a zI+Ik>md$z9)amXl3?JW}JI)?s8$Bvio;`nYLT{~aOuVoqoci0f>9NJGIVcq6#g99C zM5jkbMy(2;p1o9>#8ontGmI3iZdnw{^UOM7^{2u1oj?1{smyhpeTpzzKGUXyG4gX6 z+i2j6)>H;e?{th7GAE<+NQlYaVICwJBi>k8)t150Eax5h9>?V$zO^oOTn5*+;>(Xu zLf#g0YRpBjT{2QPefk8d>)9g%~)zy48 zXtf71YH|F`=hwgA4o2nx9Q=Y%@SM}`?LDvSZ)QLjBH025J6pse|Yp47BN_e5_%txzrHv8hvy3MT-X7Xc7}l--bBlT>x>)>>|7`{$QomfUYRiQQ`K z)iz6mRjrNnCYC0b<#h610=T(~7sdOs5k~I!V2qNl*?8|`#Be|3|L`o^a!2o!KK+*H zS4BMBM5|mI$8}Aqy|=p#C9Ql}kso_*GjC&I=ZeFaY*liK<0%|X>~x)9Rnj}JZwWP> z#K^RV;o+K)%zO#F4W8|z-RhM|)Ge=005hTlIn7v>y|bhH3o*Lpy(rp2{(k&dMtVlY z8}XA#!zOW?TDBW2y&-W;9wTte{QWmtSzHmu8k8|S!hvgB1s!y@NIEoeXaAP2g}%eY_FEfZD$`0(3T_c(EPVIjNG`a}o(&PpK*aDwYC zcdHmM_g5nx~hAPj=&69c^t^ zEQYGH_uoLY(@}L@R51Dhy)cS>lEcOL*Ox|%_&SvAIRA8jg3_Sfk9F02OBc$P$F4?W z)8a%Z(tE{h>py7Ag0>6`KCN25XnRa}x%wnMTi)YsywfMH+3ZPr=lyl z=(hhTfT{mR9(e*_e~Yib8#9L-ZUW+ca&4+*Rafnz5(%OZIG z`}NZ%6N&$SJ|PbV$^oZ3qzF%pA**|L`no;uqn@a=(t@bpkEVEj^^B)55z0!g(PQFn z%|x&D-Ntjm4@~I1nzS~GnwXn5W_QIF%Mj!J%w}IzBB>__K(D;n&!bU$m;;z}$-}=R zsx9ZkeloNHfbi7C1#-PhTI@#^c73ntBJ~U=LX9-tb?EA`f{WZiuSiV6J{iDBy6DsV z`<)w-*V)`BnTZqoF%J}O^`%_M5txBkZgtP46WwUrR~TJX^!?%JrfJ5Ny94G zb-#^?;uL}CT852iEK1|+nV#B6J3QNG6y{>2b@oTE)C)w+#F6;WXOynDzu`dc@B&{q zVEY9eMfs}*SBESwWNlo(_L`td{`vXw5!T6=ET_{Pdm0e9l%AX9Y^S&I5+~vzxA6iK(VGLhQAVz^H$ID1CmB`HN z9S~&5OxlEnAN{&{ip;Azdq4U9oTzMD>5ib1P&+9dj{tC+3EX)$bxYo_Um40TATMaR z@-TMTLWJnP>J57x|0w*;YyCQzKV6?oqC5-unN44(BsspuFhe5jnN(|1HZm4W$a!Hn z(RfkbALV*ETE`W7*Cf#pjRmYDS2PI~_4^(d8pX)<*(+gGMRWL3M!!N-?rFChw?#cq z>SgD1Ts>hb7e5U)!$hG=?5r=$v2*-&K^IY~Y*mGoNB77>B8u{V_tzmwz5_FUiNat1 zKbY-_=aPHxEl`i=v{V+D!w^x(uft^9)@PD>7h5kkznAP?U(6b9MONj^AtT}I5+)^< z+*DR-YAJV7Q_VZ~4kN*^yYynOEM4wK9XmG;dQjgd_s=fdm^6d}+iUM!B;o!!#r9?h z-T5M4n|9gzk&*jCZljy@Njt%oPv#fw>2CjCPdb&80A;vhd^)UWckq00TVem3ttq>> zDATWDZY#MpxdN7I?YEE>JsZ;Bw|bIakrf?#neg|D)E@3RCbt)~!87C}!%cBa!4kTq z4wc&d5EMK48GuSdlLAkG^^zImbyx__a~E=`v3FHXpUI+ed76T)v@J3 zsJasOMAKVTwL1QXV0Xt+gjYz?v|6 zU>ap_pRbW4fh*(#9leR9sI*2R&4W2z&aX1P^#wsV>$opZ<4h3?rhwGSNGyzT^!4cE$5Ys z7~z5b$F5>n=SUqxqPwppFp&xHs3RR-q(V~3BV*uj)!n%TK)-?yM@>9GH^zvBRQep} zx?eQ%Ml%>jXcQ*d1C5;}A#gt3^l1=!oW6%Fxe1xahWPlDiE5yD3pq@wP0Hrmxraqq z^hCXybEBJux|y3bJ$8Wwn=}4yuo$p_mW;J}d%98A8s;$nov4xuw`zq$=Nym8bPQ4^ z$)NWhE`50%rRjaWQ~~Bdu{p_wkRQMBaUP?5?~|A7p^iJep3Ab+SdLuHYftt@6#duo z;Sw}c?gw8i3l}CXxVVh9+j1o=oNVS>g8LcF_5SxcFKMQaeHz7O_2x$B76z z&FNhlV%O|L2GEVs9BQJtY&8`E`IH0X$LUg`F?Obf6BqlEdeem+S1H49GQL683>_C2 z6fRm#j@x;hI-#{th>a561hA|Rhs0;*3)cT3hU|;ue&1`!z~7Pk`rio`v_Qe z2TgT4UY4eR4(Fk8?DoMBf6WeE9QuxfY+&18~zGL|LgJUneQ()Ro(U}L&{dsmUBzu z-W8S^TD2oWk$rt5ku6dPem6~I*UU*CJf+g)e>~+FajP$gzhDTbX6jrn=fn$2mSCG4 zs~(lnHp{_~;K8!PCJLDu_owK|FqM5_9Ga?T<3?mJ5SRdbi^+`=$SJ%JDZ~h0_iX^2 zlRZF$YSEiALcqFDZKBA=ZqFQxUO0XtT#~U9);O?b{QH(-d&?#49Kzg2`D${Z&(bZ4 zSuiR`q$ZU94nqG9o=88!us+^ShOTDA)e<|8 zY!N(9`lw7Mj0dHoPVsg~r&(;oT>az@(}(VzgK3;H+s`&Dj(qkxc2=Vqt1N@F3!rHb z_{v@H2t3Cc;GbPr@^tvUUJF|eb3e&fl2cK^yK9|=;C=>Tw|b{$Q|1W~P<&k2I(&|9 z+YZi@`di(8wc#(ny8k?z1@>PhhCTQE;wy=4+S}`khL2CE|G0ev`B+}b^6cnCjKSH;vLGot!XtvCq+<0AAe0ySe zH$p7G1Rl2ev*t^CTP_(!q)_j$lE*31zCWU8FICv!+6!D(v6+#-djc=%>S-*D$^4F@ z6P@K3o2UUk#r?+}>`kXOC%xC3G%WG*9Lj@Nv(I(3QRH^6*lzhw*D%R(@syOpTT^0t zqb>gHRzny_2dSXJ^Cvv}xBiA+&%&6x5|U4fXUjoQB~u8|I{f6gTDj-ct`jHOEA!e- zb&n6@`F1z4EW0DhadIBZfjg!xQ*llg&%7V|S95W|GaQ_|!ONE)fBSw<{Ui4*cHBgf zo$VOwNJcEf%81Nc_z98a?=6b={+x%AGd}0Sx~|aVZoRxn4Lq_(}6-@b`K>>52H6uQ&huZ#zg70Dy$R zEr_*$e;qw3FxW>9is@(oj%}7^ZJoz9QKincf0`fvM9F@9CGwB$-M?}1V(>>-Ec5rY zyQB|*Ymz-WGP41}5TQ4J;T=krJ%fHu^QM9XBb-z%UvhXGEq&F<8kJKkD4? zz@c~*7H2v9|I)X}6e(tjX>#lfYdT=l(w&P+${-QmaL5!jQ*I?ozqMb>{J+cef0yb1 zF4LX`{Qs$C%DXc6)smoKk$*UVQjPv#RPg&pUF`pE$wk>1vDVD{_Uj{nOVy`d>;xhR z3r_*ti>oke{kQu45Zoxb>tB{J}hNJj(*q+<{p;=X_Lf zu%h*)6A7P@a1)vdXx1Ry5oGWZlJq7jWdW#JG*>|$0xglR6>UtWhX5J&mLR1xnDWmd z;5}4{{{6dO1wPLD{YgTUWN;sLcf00NplI+J5r?bJpvn#jVNu}J6Phhu42EITg3hCS zaS>X!HOxrx_8P=NWQccmfyLwNKHL&wgV4h38^B3_(jD_8@>EWiXGUtNA<{m_m`xg^ zQ>W~qcQ`Z5_LPGW?rQ5liVlkdU7N`f1inwkr03^=V`$rZ&o%cE%tF5mIZ(P7&GA!= z&0Mhc9^cw5|J5CHTY-0Iqv08vek%Fha~7}xXOK*XK;B!ctWoCXypR)yy9)EpbqPV~ zwJzs??`sU6DEw_(_D6)p6}!jcA~ht97IWo4Lh`}q_<8HEtd^FD*u3LPN=#28Ubntg z40p1OmHvpuMXLMdzo@fQsH<5o>z^R5BDR#fy5BByuf4(FE=)}hKIeUV*J?9yWTWTd zau^@RgeaPFpg%>zqe$qCA_mTNR$uW_OfW<-M36?QOCI%+^!*HzfI^;0^$5qwT_vK3 ziiBQTRQ&}%$CNeOHO<~U8W6>z1g8aO)J|((hm8TBy5C3ZAKT+;4BUR7v5{be_)%`E_NC( za)uomMdjc5=i%%&jyUWY-ivF9yVWmt(FzGmWOms}B z287x)eYCMyDD{Ovs}3e1mnGAM0F2uuJGu*T9s&aBLQoW5htYrmS{vRI= zZksH&orE_U33m;1Us=-`f$TKT@89}*vSBMjC^ccQo4pp;NNzV<9;%sGQD@!`7eF7p zbZ^`*OhMbQ&?>fz6eZC7qWQq~LPY%5ekYH=uR5}uo@L}f{t~MgEes{PfX3~W^Nhc6 zS4@;bo9^5CvBH=sXCLF~fpQ7;BHNMs^4bG%JyMt%u{wSY($~StbxK++o{S3Sx6en# z7yq_$fUv(8rz3N5obFMAOi$$BWjT}70Bql}g{l3`$ z_-e5TFYVfgBx!IRkm*--YGDY_`xqzxL7R-Z>HMLvHW!wp4!Ep$nShpfbMB8R zKot#d6#h2fd`_MSyttfxqZ2UX;xDP>Z_uJ=`0po_XWUi7XfM~qDgS@lA~TsnOTM0>|4=bRwB_uc!1ss_YHhq*dG-+lfgSo;x_f(&s6@gE9W2~ zT4fDSIu#??a}bSk*PQM%be!pnI3w=n)Y7*)I}itbi+F`8{{ROf8T;o}(Q?acxYAkg z?yeXp-#=ArMJ#;cyYPDfstxPDPao$`A_lYwTIDGBHuSaw-CmUHJ;MVC(Q5;guYlWo z@5yKRuUC2LCajgk^I8BaN$Y|nH1?4#zzpEKohnny2cyiYvlB7tR+a~lj70J&*eZ&L z=2y_aZNt~!wxLmvY7zV^n0qgN{TyKB))7}GwS`^9953l9w+7_u z{KG=-yF*58$(_Dh#^zW_!S9px5q#vrtQ#~x(%uR|5hMq$pdk>@YJ92L8^t_eUad%K z;gzJ#BPY~s!A>zB|Dty&9v*3NqTG8~#fO!40iPPcAMho8;;-Z_V;wK2Ltj5f-{VW(s=p! z?6L-nh<*jxmBS>7V3l;$j+w`zXc}9*>&lc+myY0zHFDiGDFhF)+ohQ~;;svGk84P1 zwSqRRaH!$Hr(ZY<`*KXJod<}b51k~-2L3k}3rs=N3`HL&3_^Pzc}{3}GF<3EDC9kU zk^PV80{qJ}Lbfw4iihU}u!{mUh_sb6_CoggtGe^PXr_dpeISuQ?5r?R<%BN0(~o;$ z7N43Y)OI|Sl*~VO16ThhW~29j_GBV{?(#0udEyk_5M3n2W5wE-snMtT0O%dg($P|$ zk0RJDZ&oBLO4s{UC8iYmr?_q~!Hr2ajr{kEEl~Fb9$cpnf4RS|+)Zs{Z_4!D~~{s!B7oGCKHKPee-|xy%CeiSqW}6vxMPqY>$Jez*khhHPHiAyzJHj( zS6Vv3s3qZ!cEdIQ<)kR5y~1$7}K}+ZeYeGsPNuxE^YGdF~gD{ zGa|j4b(LnsL>bCroOUKEREE?p7mDMJ!PG`P!8fbce;ZZV?vubFAIDH)#!v(<^rG=^ z7itnjWG3_WU}9}@Pw_KN-$Z;)oaj};3GoCv{$oa28HxDco;tG-uaWek-qp8E{+810 z&C+wRQm`<#qmdW>N0hH_GIqaB~CN!@grh=4(?LLZ+&F+pm>r0Q`Uc4$HC}VyN zE%uq+D$^@*L9tJ3w5J@4&4J-pyoJR+k{0lBnJwl{_mI=OyBFLvGLj&Dd)ftFg6%u) z{)@99osfvTNTz16F+G(+W4gHhA^11a~GTr(}9xZHt#TjH9x@yBh z=%2`t6()qAYVz$h#9jJYVcHHqirj4Gc3>=1T%<^>pN!M!(D_}bR3ZPd+KOC0K0fja zdfOo`_ldi=cO5pCCWfI`*_nR6@-jw_WZfiE0gG)d?Dn#s?W~OR46?LqLqTJ4P@s{D z#g;NU?|iCY`wEgPF0Dy38Qf6ph4Nhp+btiMoG?F%%uH4q(ANS>!!}h(LEJ+Fk&LF= zrrqyIhWsxTM$n44uwpW@|lrUZC+E{IXwjOh2?T=CTXY?4(1=*h1 z2~%ChVflf@*i|Z;mB#ZmeS>mgx*pCs4%0n`9cd~7$FET(c=y@$P;ZnY!XO(W>rQI2 zCld276yDLi^Oov^h>!ZE&}@{J^o>cRAkrTFcwA(-5ef$Ulb42T5cEBzoOgYG-Y2Jr z%y}(C@Y&N6P<3{_*LdbkT&>6|DuACCucTk^t`Q)Z8dTq1_)Zg!WB?Bt582<_U!(Kvn95+9w2T0K(=l)g z5m8>vs!B?jAC%Zd`7@0@-2P2K8T8}2iMkC);wc%rqfh=B;s1VLPpN|>&RdS7N)0@D zlRu48n9Y3c3(_>7WE#k8Gp(eP`e-Tm{7U)(`yD}PdBNfJwqr3@7Ew5LutwzSV}Z<> z$1b@2VM(X^nmtoIKIM)xR9kAkJUvWnPZ_%j4F}aG+keg3bQYcq6Ot9k2JZhOJ8Hhw zQ>Jp@*4SjHsemE@^W@jY_?gc>CA^gMmF$eFDOD)oU^Wbc+d=6vq?>t?|0)uhjwne5+m?vAj`R<9iK-odvuewxDs7Dm5TWN2jehly2L!T4{W==y03UDlr?lr8)XJ z73@}y&&`H7bZ0cu=tAz6nb2nGyy3`KX@9BA8xg<8*B8HEnc@&;;z&RCR$kw(V|mp7=Omn^GY|<`am80A8-(8%HhLQ!fZ1(+!J6)NC!JK8Fx~5- zoMVl(3<{lWxR5jEs$=bg8Nx@Cm)^W6b$xge01)O=+vkB>^!=gbUuNIerR#l_SmxSw z%jgOgGJ=l&kS(-t;&c(64R8g=(XU{XL`~y!@HN{n)pkvRh1e(>F!^RLLLdFrhvdI} z8ZfID#3q4DBmP*@f(_EJqysk>ng2ZFP`M`RcZ9++nxo5T0V=K&!53 z>b6yVup4U}o*S$r_jvFgmpA4oUknq-Eoi9ux*9T@C`1X8A4-4yGE1*y)kyXbzXzM9 zU**nboSEXt)^4|vx0goT@yrkiu@|@MBGE&$EGOZ941Ca+&M~Nd`64M|G^WcMSq@68 zvnv`HKCBt%W{@0Efyj*hUxT>t`|u%b6w&&t_Zg{rJwRP3_wt-rBr@13Uw)n=qz#AE zQCUa=bwfr8xeN8q(@7(>z_SXr94N!7`sb3p*$?t_J~ZS-yW>68)wi!d61I*+>6Dn+ zA56en>$I2yhl3EF=*REp+qSSq_)nB0$vCAh2l`_q^V9 zF*g548be&h3gA|_;APskumpc4p3DCl`yagx9!T&bf7=9QisrE91I5S{iX0i1$u})^ z5QCSB+G%8E+|#$kI{{!64#~Ok7Y@+q-i7(%ks<+km1&J4v!%n$3DOZw`6`TOg-drf z2)`k#agpqwLYc=5S}C8_eFaVRzox&3z~>v%GfvV36a;jGP3!D3c_#1!YMJ4tz7U+= zMHqxB0U3!svc5KLhlFKa%`n{$wOJ@hYAT;ne_%Te#x43^O`j3~fVWQ`ddjFM$4Ipf zavxj`Ow0O^VruX4N5YBa{k-jdFN&Q;8z8Dv@~JUP#hWuFwAWvupZDAn7tCztujitg z9@RGc)+jTO5v8(uVpMd3+V@4ZU&!LISvmH}nBn#z+3HzmB6~my2`SD=FCjHUNT~+O ztrxSBj)YR(VGpJVl;3z!65Nk2%k)dcUk#~!nmGsm8=0Clb8|2p%iRx=`*o`SdLfX^ z--kEyKD_THqp+u9{07okJNJ{o?6c0itp`z*Q^hH(?WxK&AVH@^nE_Bx13jkiCr8@X z&h2b(BCwq+|eY}~tI|LU<-QP;?BKh;dqxTsJ4|>!jn3Gag zYm6dQh_&*b$FyrQ4Ub7f$a30tsUhZHxArc$-m)bgZXzOk5~&N5fJ6lc1)eQmkS9#L zDq%jPxJ+92Oq4;hPo*4)nEU3S09N86c6%?!8<&Hy3*E}R`H_w7$Ou0X2brNeFXybX z5y!FQ4-j}LoMM~g(7IyHsHhGWkvC$WqyFD^9)iXj@FEWJT$j;1LM){}3!P+s-?_#Zi!>Ga#n~Fz0_Q2lY;=Q_vs)VdmuZ57)1zUnUhItSIv=9}+ z;QwT@Sw*9fK!Y~^vQ?Q(@|zV>gCvyD2k4qQjJ*FHTL5pO$oOVe^9}O z={2Jw{&mAng0HwubyRvHKvGZ$`i9Tk_1GFZA2|9Lg0z-hW9m?O;rX4{1Jo7K11mKkM~-2dKd~2!|~ySYw)`38>pP~Gi#d@{QmXZ6IUUh ze1xch{M|^HG?$U@O~T8|9AkO z;;{Um1GV@t;}F&Mk_Q8d(fn`T`&x7n?qIjU(ab7bHHdqGQR_butQKsX zCU=t}t$NEa2at%_d+h6XV!H>Md%j(L+2HpVXrZ?+RgQI{!`sMD)IBo#`V9xPpJ(jYc zNm2E}qw!1GP6c4CxV^9FzPSI5*~tSyQUydWsO2>1^>)|2(Jt1``YkWM6FGyS$alB` zfk!H5`tQb5z!~sA$p2Re@F0;9T%S3v^_zOp z++}&AV;19G*zK+m=;kR=wA2cTPzhW?CVz?P`|X~WeP^3EvtX)B=OIo)y6TffWSx)p)``ksw>lAi^K+8nDY2%1 zjc)$@{0>Y@2$@T)WU*xDLA0}TPw^Xd=Q*6~>g9B3BHupsTTGqUHlHrXW6`6QI~slc zW%I4x^`AC#UBJvPG5usmQg8OHONA^ux97N51EgK446QAN3_ee5sB`8(XlqpT>5aSqvYY0zB%;i%H?iZG(}rQ3!_Qya~`hfobB zag4*gbEOnmqhsm^SPLJ$j9`-3>PT2k$LgNcbXi2bt z$>jRqplvcz3h#6@CBxlxqfcxP}@x`>?Ujt-NaLMG57N#jvSm! zOA)|C+vDd<+$(r3tB#!&4lP=_%vOQ2cpSV^-2IheM}|~S7O8=R>W=+uh0+> ziH%8e%8oJpd?wH~7+}}maIgD&AGEPfjeAHwJ?7p~tz`pw1I4zH`ZIwoM6Ff9vQVp~ zKQtG+TFR0iRAf4IP4=YqYgGNKOSj3Ag8^u8)3Dv%SoUfv_WXPem@fCEL;d$f{{J(B zfTP`pWN;Q^*@B&_&!Aljl8-72g9-gMWV8K_12Muiyk14l2INgX6|KAm zWYf?7NUQQQsQg^PhJz`&Ce|V#MDYITALqs}Re2o{$;J=XC#_8x3I7j!Zyr!%yY-Kg z5Smb-lnf~vY1B+YrAa8wNh+z`JnaTOC<>tgrJ0IG&C_lWMQNU=T}kt>X*bud-@5nS zIXsVZ-uL~!-}8IV`M&;m9#QT4zOHLsYxu0SK8wZoW(fjiAwl;`rYp_ai{3td*I1xn zWuK$Q7q|_NHpZVWMd~jFNQ#o)S&@A-0BwhwL1x0%uTQdzcX|J|HyojC*=*vM485ME zT9Z6)<8auyGSRDr!~E^VLC2nn#YST@QrtJ$Q5`vyewW8LDPp_UHPAUPAKX~}TZ_vN zdQ$-DA~GuP9_!fgVR4{+9^)hVwf~7hxFpc~s_K9JV+YTN+upl@OIzl-BoL$#^SKXe zs`5@4jX-rB1c4Pnw*x8{23o%MbVh0P(kCYtT;EylBRv&`wC=oe4?33kDj^yh-R>pe zrBJ9ahxlZpFfyf4F8f4Blt?dtN|pDNoR_mYtSaw~li}zuW#`pVy^ozr8Nf+ZJ^s-3 z=t-p7zMhHtIQRZK5k_HETSm;vDw1t2jFz0}AoA`iWosLA4WbXUTwb*5=t z0B4a$%? zBPUCC{>4Zl7ezo9cC5Dy`ze2W4wSN=@?olyVa&RZmD@YP>eQ*eaK2T*+j<`kY`mS% z_Q|xpqEb#_(Eqb3cUaK0`iit>ES0ci=LL1thY|o!jyZ+PbM`X5=Sex^I?-l*<3cJj z;N$el)LfsxKM#K7K*jD(#&*!n40~lFHo$|;@0^n+QyG)*h76oZjw;RMEfj{`{qA&adc$J6_-9+xfQQ_mJthx_#H~x15@#EqOUqXG3o& zf6S2owMOwfgIDFKRgsRn)2yT)`hZ*9DBN9 zJv%+IUgt{q84OfiZ@8vQ#}UTF}1B+*cGZMxMt2&(u?M`lcCPjb{fz8+bAz?%Yz>{S--O_y^GN^l zZgKl~M`=lh+T{t{vehK8XJk$Fs>ln{%9kS~K4DrCf`S_Mi+@D;G`Pqaja3A3b4#_H zSHWD5L#T5`I%ja*1}aBblU1 zkw{tgf;uT+yg*Vx+829ia0v#4k&4?%cnO`?0j}koyG5M90;mvUeV}~u^M!5>93-e7 z6Vpq24i}Or25L>O!||RqTDMCi3w~P@=B4&*e8rLken4}$UDEshy%aQ{v4w8L|DE!M zc(AH=8enc|MU+PZpQD*a8`qtR#EcR|>3173P{|{(2(aG&eA2BTb zh=Iu{*{6-g-4~{!KleTKDMBhzxRZ1CZCa0UP~9|<7w-h!QZdgLm$(^fu7>sKH1Uov z)A#Xv&R2efp-t!dST3_nE&+}@{~_&~(Ufk4uWRU?V3A;LFwd{{3p`&&>SZm+=1g(( ztv{NP&gb0FXJ5_VL50d(=KwP2Cz0Tt{Ux>Y6hyLjAv1jNGoCb=^-orblIkq9fJ^U< zEGHNJA+3}wF^y_oNa{ZL4$-OEO$06k3_;Vc-Pqmu%ll041=g1GxBw*yK`vejOD z4k&fx9)3({4Gg?x%i{HFhx28}4XU9Fmyme{1PF77o!qKc+wuOElR#wh4J6ac+4lC4 zCY6>#xUxqj@ri3JgpcAB#spHfkyOIF4vCkozbgMaUfzm85%iRDiAqEONQ$hLN zxQQD1rSo$~*06RSPqjotZg8E0`lH;Y+CSx%iS|Ku6qHZW_R*iO>37p%3-7^88u2U3 z&IBq|YhT@p4G_%ml#vS@5Nlj~16;8UyWKQa832AT(U4Q7ge}=hSwc_xR4?$Ga&P~B z8Q8af=FS`;^ucA=tXhetTY5JpOlTOZp}wxTuw6-zB-9OjP%$vRRmkI)(s(u-+-Ljp znjzw4l#Ku}SY)Wm8T|YL`{6UWj*1vhP-{V`R9qtJ@XL=m$qM#dw%W^^&&?m>a zDaW>k0UJQ#9VME`wSKknpdwD;mJMY^f+N+q|B5XUq`D$;7bgmuboy zvd|rvyPjNk{caz;x6*+H8Cvk%-nWuGxBt||gOKeH_MPN9KmlO%$)?W(Shpj{{-eir zMa2`jOq_5Pc|@$cIt`Q1g$FN0LIQ zVhH%x(H6e?Wf;Ux0Wm(+ABI#U`7DMMROg95C-sTni*x|Erupu7!Y0xwei!Rw5c3Cb zB!*1v^nMVS@jMz@5koR1#=l?Y|J9udKG(A&Jxs>^(8fp<#Pmz&KzgqIN75tIekXsm z7Jwu#KZJV_5&t(N$#9<+=hX<0_LIEMDa^nhd}krBAxfYy)u{Tu504TApIdPD@^ ze#67Rv1*b{|7T*=zf%fC5d60W{#Vt&pazScj`t2H%|`!_y&H$jUv}T?3#8OXWFC0A z4uYzU+krKuCMh%Sx}tVW6FDoYrVeobzNa0(%x%g>s)N^k>XsIGsrrxDBB~n3#L;S_@f8YO%Rkm0zU*y{N!n+E4YzUUHsd|Jr%GEm7PMRp==^ z87q%{aUigRl(O+^h8&uLctxD9;g|V1r8)_=KC^G zmSB z2kmtcgha=viHr0vYI2dP^Z0MWMCK`Nw=XNEIPA@XhZ0J^iN-%w)8X2oeqJa(v*Zrn z@kjU1-8s1VRLp0N_#=BSoZpJu_Q&~;{4YK58?_TQB%~Io_0sVh7z=e9o>Mq^zaDV z^a#TBm^#cX24^`nujl5huCKqc&|(VY%RHSE@yKkt^zEvWZ~TPrkG)EE+JD@cy!o<` zeH06Wtg5NwB-${JZCV4%^Xzt-g$BHJb+1@oM`7EqRAFm__Atv~s=~Lcl2Z1TR6NG& zwte?S2TBVhpv3I7Jq!sqUHP_W<2&XKSN zudh3aJDw`*Wx}Osl{Xyg_H-5|kMIYvoTki}|YL($~`T zm;c8;I#a&FU!lqE?4N5Vgrf;$Af`SZLrIo_a7W-zRvxku zIz+jTks}-HY9ak8bXkAaZX$Q^Dog_GuC?@b9X*^EPP)770z8KCq62s1C9YhHcgm7% zo({JZc3K6p77j&vVrvRIgo#IThl~D|r?j6c9DmhidV;Yj&&aJuTNcrx7qLb6zt8J545#pR9ej1H$h3+0 z+)(#Fi@M%CK@To^xB+q5URIlUqCK&<3}LT@jkfnc^LCB7@>$cyzTfAR`nDe)UVBv? zVPOFwgJ$-Sef6Jpu-_gyT|ovLM`3gCx~}q5_q0&ddAs6r`W}oyn@RNq^wf-nqbEKh z(@ZlB_bj%SUtJu}HkfIQlNRpCFmKSUcZPPws|fdxBQPDANH|UCq6c6$Z~&`)?eR8f zlzuLSe^&E}7A9anYhmf^=+Oq&`VVX?bLDj72@?;^+thH-KK76>=(%jVyr+{U8QtTx z@v6UTW6Z$7vvAK2%WMr*bw&vn^BJ8DMcxs-TLCk1V zmyRB;DJNhYA!g`;uC&n^*O6CoSE2I^$D?Bpj6}pc8mR%wB1|!k#GUH(lF2OH6MNu1 zvVGY_#yfS&qQtq8s?2M+gqafC z)w)o_kCb_ni}?$KN{(M|DG{yfX3F-Vi0rl9aCt1Xc(2jOVf-HNNw)%B#lZ37rB!C) zcopRV4fIz;JFQC@9w`_0kE1-%j>T&?e%S%Wrs<1b{%XfGaE{!H!Xkr1lx{{fxY0_C zrH%=wxG49ptq{6154=Wup%bV>sIp(~9cQ@n<$iQSAwraKS1vP#?(Djhn3WRUt|;sZ zp?f8Xu&0aF<;$aaHJc#Sv?XK?n7NiqC%&HLk*dUaMg?kIS*~I@#a!A1ogmRDVHGLb zKc1Q5J}%U|>Uyx(x_BioEhjI#4En#OL7Gcs=_o_SBC=)+kh>vh6!H#y=Cuc{;o3O}|H z0t_S(b^Izsay_{_0lU0aR({`1AJtbdM$c!ow;^n zUMi?8<(rrQ=>YGd2D^h{K{j%24&JUbQz{jK2CFrJ3|s8`XPu^N!mNq!nYu)wJXNzJ z3Q?7QsTLN>au`bmP2D&!48D(jH#zMh-W4hyftu(q(1ZHP$0Y?WS(y_;zwIz|Uk}t= zli2h1tFEXpCDXA+iHW2HbF-OTU_W&nit?cyKR~150fVQx-SCz{$2(L#CId#XwV@mI z{KZG&c?cU#64t#-@Wa~GNVOsJ$KGaB#br;&uC23)u*c00Mig14iqPbTTfg1Z2E*!o ztdu<|PPxXQ+E{LlQcu%LOVV%`eZ9^9NyM@}!>S4)X1I-N=hfksdSO;9l4J+h?SX@W zT(zd2L(}kMqt$^=*F}uu-S;$;+b?#2YOlv&)Kfbrn~=%&kKe zINV5tL_1Mm7|yRBXp=E`aSAj9Z++@;Ciu0yy7+m}?&^V!XA3Gx?v|{V3j@b+mA3iQ z*~RV^4{nLGHyQcSZI#~5i1EL;hIf?(Hl9nsN-OR2xG_J=?5V~k7GH1uh8yEZ4YUJ@ zyx%>RL>`utysj2j%&G3c*_Cbe)X5$rWW6}7>gj4GEBfAbVK~m;UBbGKT{#tMDPGu1D@i@%lEg?H1Qjs-TS*j{t9@D` zj5njOu~*{UND4xOZA~`G<&~vKXW#&K98K^guy>jV26<5~N;C1NrLLKM1T}fBp-y|% zQ&OPtV;lv9=PKMkaSNT)s3UVfG&FZ58GURtKe<7$A8lsg+?9y%Vw_ zSOy67sP%N1I)=36Q6bR2j_Ms7XRQq z_^$G%Zu&%3D9A>cP4Y6=P&6=bAi61x4j(HTl1Z5F>LzrJ^+T<9o=N^B;kBje=&D7i zpkzAI7`ov=HVg`6xEQv#s)@zVTS^r)!C0*v9jmKjosO%j+5FAvN^|2@z??!W}#mbx9hZihd`5ZBTc2lZ;aZQHF~r zx14Q|@y{7WVk$F3i(@YY|ojV_431G5WFh`xtQ4!{DgO$ra4P?0mScDk;GW za~0wnWKf5_T_iPE+}M1pq#^oDFU*X<61~k#4crEznx$8XR8*goS;5Oda0R`Sp1eZK zKpSB)>_5-DU=RCr!i#qm`PsP@y!*53{7$nvG@iYU`O=Ox@|f}oJq%+2ZvY;8VE5hyTLfNaqEBcRq$t9n0^haRrJDLi*sw_ zQ9^ty2g0Wc(hO3>8+E=s9Jzg7^b=mNdJ%?gS!FqlHb=dT-SsrwG%;M>u#UpJJMY-e zr`1hnR&lJsp)-YfM*{U^YL1uZ*(m4FWXv+YZwanC`o3Vu(@DE1lmh9zNJqK#vCI!p zPdf^hI}+#hb}`1+%NTffjYgE$JdVN|9vk_KFO?R3fS{gX{!~;rVZR%(3(eoGOXat!sf8k!6U$}I z=F;GK?#{EcHxzx3f8_6WWhi8dspE?FtRS;fnCP^M;5{@1|5p%gqI;RY-9p?VyUS50 z3&<(1H`;VYI@IZebwl*2;;vuTA2~G09`>@t=xY&H>92lsb4@{)R>jU|uhUA-PI^o~$nO;eO@zv$h1)y$2>hR}5o~CpR+l^ku z`sjz;Nl1Fyq0JfADT3WBTH`P##T4L0?kjM8|^HJ60bXq^99%*)<|HnwWl=ChS47jQAN{r(%iml{guKxg#{Rn#e4+ z)uh3dlYsvg)AaHkg9Z#c)o}7V^a5X&U`uK;P!4=sBDqi|Et>8+sO@h=9G^<9rg>!} zgNs`VXEMj2ThGaErnPV?eZ-n4xH4745*0MXt{#x$fD&v;Ia=MIL4N`W9vyt-kz z3KUS?+kBSU)zUS7_U4`?!B`D zrx$3HpnHD|^g3?$5h>C)>En670y4_MZ>VPV86L1cXh&CFlD|l%%K=h5)4IlCjP!T@_VYh~n7{CP2IBHg5s(0I9 z|GD=>lQ1O*O6uw6I@@s`5JS^CiylB=Xd+z?kV0Sqb#}s$Ec2&MKryjB#o>F>0N@lR zsm4X{;Q2a$D1hE0pw!>8aF>|nHG6)bg}pN4t631;Y{bn>n=IHUG3VX(dP`h(ZESWO zt;ea2W`3U)QGG;qImgsYGs0^*jC^U9iCjkCOvnrZ?+%m}6LEtNr=^c7ol1y!jnd-F z;~QU@YEb2O6SNH&%)6$q_nmvS_Fgf<2ss9R@wMfzm3;Y$&*UW$R2{b4>?EAo{zNuy zc0}&p{3v&)xV9t5Q`eyxx9fy5`s})VB$~q)(Si+G;(Y^AIa~WO zav`omG%B}pJtP~GOq&56m;O}|)3-P!_oC|q!ZRlBXT*#mtg{l}Ra>xDM6c}-m&5q% z@o=6&nkJh=VoICMwWh&FvALdNUQm8R;}QE&uj%;clw&7!UQ;KDRy~{=!k)4_=MXQt z{@hgT=Tce;9tn`iW*3%`BnL{pRgX#Q@LD;HQV?GWkpaPLFZ_-6qz)Wp$K&Lj2T@pG zH9oQ%GO*7Y=53nHc6+YqhWGFNep|bkNDJ0)h#WJI3%j_b(CllbSx@>|jXG1 z02#GK`LJo5$ow`!y@I6wX(ns%IcVzdOo^`6$+P-ZWlR&tT9JBR|hIc_?op zF}?bAMoQCtf7;<#PkoU_iBUDjx{lkYc_CJfbxy&|w2!^r!oR!1q%QSM6!va;*Lo!` zf$>P~j#-X&aXCkaln4j*L^BM@+nO6G6RydOlM=<>J9dKFa@;f=@l)|)8cK619V*_5 zp4g8W?F=M)s)&fnv#giY?P{phj6;flaGWI1BRNfhL}6L(i;krjsfygBRXU9ks*^h* z>WV&#jz8KO>V1_zr{|BT?Ce-H9fHmTYN#A~!NojwR_dJ=4x5jQ?t!(I0)zD$zd)?`C(-xtJBO3F4zWNR&ZH-;yM51I%E|_ z3(9HEr0CC;(0N$vxoh-~m&=FCuY2d<SVTxg+_p5(-cm+)_k>s$8CkR4 z)Vy$cqFvmSFuk7qQb z-J}&ayWT2~x}&@!PPAQmHn&D^wizpQYXPCrUYu|$$_Gq}W~gx762;ANSeyU-{2x0C z*ppOZUkW&FeUej|nE%aB1C zS54l5f!vW_b@7J<-^YKuId6(}u#>@VW<3w(XouhYk)+9Jc3FTgNpH|!Dr~Ulf=TUu7(@9 z5mRV}HrCJ*`I_h2kR!U3yzI(+RgZP^@;ppQv}$$un%AHzgPFRYKin>)^6r8^L^muSGLkii{z0j z?6snhIV&{j^dLbwx^Ss%>>4sZK$fO5KKg*x33AfNl_ym@P?9jLTH}M>xN(1Us^pjv zU8Vj^+7pvuTtYkU!QPBKTj0e?i8C9q6yYkg6IRiINSjZZ;$jVg9iNzUDqn8?|$ggU^+Y8aNG z!Yqv$iuUv7OArJ&;mT;<#a%52RGO zL!K7pzy6fp9fC8Ln)r{ z-A~x4=4esVUr{iNDR6KyC-bD?uN}V^S zngP~i{n>%e=+Y<6EJZyU&VwdJq{t*2yc72$rHVURV33|yloTYi=(gby2L~Nj6+R*+us~srk$FB2nTE% zqo(d7!dD*|>L@(?Uve>_Xd%JPFnXu~_GfSEdU9VW{alc2U=+6L)(fwyDJci=#4a%h zgD1PO#WoYzzpfV%W-7ZYLYL(-5zR6niOhzaHyi;Igt0m!gb5N&n(ZhebhHUVtXQ!w zrSA{L#ay7-om>l;@k?BhKf1H8IZ4nz3d^9RJvv#*U-Njpr`Dd?5n;DXH};ouyjD5& zDIuj$e3qq3a}wPc!xltnMiDMXbq|H!((tH}#DA(d#w)>{fL;vio)1$**@T;b-}2o1 zU4y~Rh`<)Oxb6dX8oS=zCVL%TJwy}@a&B}XUx~XYyB_Wl<3rt}JK#?{qvzdn3>^6M zsRP8=LDo>jOF>?NIpmDzJ<2-A9DtO=>UJ1~obkA?%@ZLrkPyAVbcpfCo>etfq%2U`nt2 zqk2fnh)*rslPxF-V1Vd_>iv9j7`)o^K0)Gxp7lk2z1CfSc*hEDg$d4hIdK$5Br*K2di#*!ol0r5y@j7E!}HP8cjpBPaq|l$l5O5 znGZL;%xNaoM~VkoD)@`ZNlmcS`+b-Gw6A2fTS8vykNGV8NQCN}DP0r-E#yX1qMt@# z%{H}Jq&RE^EzYSG7*MJncvi%g)Wv>>PXHJFWgrw)?Sn?;k7u3A_UN=JH{o|K+0xvs z7ARCP-uuhdnw>@DHo+6yy7ikO@x*FFiVGG8lh#Y8sUZSik#gUGW;!cM*Z4jZDsU-Y zJJ9u#_(|;XvKsOqfnNSG-7FRcJKP_0o3g|pVn-G1v+C1*S6avy?5QLflKi@NJ2O$D zwuRJgemw~B(RWWU4ZyY*HC*R;sZ|60v&4==iADCPr7-D@3=3p+2>4jLT6j-o z3Es(hBsefgb^J?}MTTDBi(V{uO2N@Z@J0pXGe%LD0K0 zxcvzdj%-ZXJ`o`rbO%XhRB*nvqnSSS;jJt+F&jkrLrn+IYpyn^D_I`EUh+ZjnSAK; z1vLstWocd)!k52!YxdvZgYTCDzK{)t?6l=I9Wq}egs$gT+_0Ar>2%3I=^7q|J=3Oj z7dg70D>#_+0z1J$nzzO&i*^agPZbsPw;KCb>4QN`&hJ*kHNLP~jfQ@DFi^HH3?`}T zkazkid+N~ge8D!vnByn!%u>t8VYsa$3XZ$Sc-vUcoN1BGmDh~m{DmaAY$pt z5MT|Nhq`_~GV-l}I>o6P9nNfalBN|n#jd#G)=cRDl9EXK2qy{%lEh!CCg_v6kV!An zooFbLYHqI*Et;fwtS4#!L$?j zOWk4jOkVwE7o(Xt5YB9P6cmh|Z*Kx}(sW2rigsjLw6srqyK>j%{#qorFxJW#a235L z>g+XMYrWzL_&fz9^Ov`%A3KT!su%wvkSF;SJ)jH@basn@C*fTe487{ED4YyRNklNC zeb2W1w4(1aX${Wm?Ks&rq&+Q8p^TobNjUf#uJ-E*r(G#fv%+KXmrYFNkw?g@pV7_g zLtJR=^vv72p~Dqdw6eSewP+fsu);DsmtP@iYmHvX4vg$chRGQq$tXSUrUMX!S}(gC%NDmLt$ zt0~_Slz)*YN{YZ7?<2 z_BJAPi{Jb`C2!x+`K1)dMk>R}h-4-aQ!bQLft&1KdSc<$>PaUdvYq`G+0MHdD7jGQ z50(o6o$9d;V6tM^_v=ks<0S%X=xEGhBCSE~U~T5|e2+dsA^S~rVH8$t{sR<+Y}-ew zkf=3YE3e=mfExYNR+GF9D)vZEHug;?$a`eFmSDFriWfXWq~PGR`njzYCZyk!?W6F0 zTy~fDmx^O81qYnlgVml!dD#_7#e;c!e310g#h+pn1`a8e!lYm71oj&@mR)Wfpdu6E ze1J8w-pT@`G>b#ehE-lcp6dxYVS9fImm)J~)-U}f*lVhx2#M8lY6dt4u4h9YyJ6S+ zwSI~S)B>l(=Cf84d_N1x8d%QS$LzNly`;E3$K{C?Gp>9Ph~d}Oex3nW;EtZjA$bKx zjux`Iwxr@xY*)+LuqwzuzuUd-0E{4$m02N@tUGX=+ASj&VnSu)h&++u!-gK5Dz^?m91^*BZf zIGT-T{vi4MYrJ&f)Q+1e0kW=B&)A|Kc>b0xsS1d_HV2N%=JJ-G{D$x1CwmtTr;i-f zp4ncZ{FX;Ecv-UEyU}bF+xi$sU zlPjFrK%culchgw~Mt>4z*)?#N*C^1FdBYxV0b!x~EiC^MI{2R>EKCPeO-=eSOj&ui zH_=mZfn5+d#7grK?83Xl|FK>8=e!dl?d<aVAxDoq2FNoQw*8EC|9kn7|Jb4MGG9NF*qPIkA)4?`ZahI0xC4)-W_rxO%ryjC>Mnugyb_*L~8i|a$gdE;kgv|iZQ?GZIb(=6?tQM zp5hxiD+A-QWEi6BUW&f%O2NOG3zbXt68>GyBd+LZq`FBQ3 z{tdn2I{psKwjONVO@=+hx90*ZK^TZ0bUsNYs?lQeM0~+oC(SQ&B=;?CBs5I zvVVP4mEJnuX|@78Yh|(0+pHdVOX=iB;m`S&m7kC4>v-|P}8OZ9)T zK;X9{@=tO^{$H#n`5zS)GiAfs3Pp5wR>*BcNf_n==JbTyAevM*sR!j$=N*MWFX$hC#V(d!*kC{t&nZ>CEB%8TejAbT2;@%x{x3rMIp=vl1=p#NPF zMRM`JgHFURepf{OGB*7!EWZ{OuL95Ihe2CBzK#0LjJ2iPUzN9811z|0_2Y8I#Ep!s z0eH*3+9Mwga6t0xyC&*sl>@e9qK4YXP>;!BR{66CuIdoksAB!{MC$3~Zx#G{X_GCQ z7niknO$axRrjmc&4{B=-Zn?^|2m#`TgYwnyE#rT#gO#Hg=GEf9Z@=e97d(UK;cU%H zQILE@>SPOn+cSxJR(cLaca^SV(TMl-(GFW|qeN%~i56Ct67U16OGBrrk>cn!sIU6o zqWvF~rhXydO;adsM^bJcn-it0u6AD7)wZif%-Gx;4ZRd%XUXN{g3t+6Lp3y00j=QN z8ku%cQCP?4N#t6evrKA#>)iTFfv^x~YO{=iyAH1ST%}Mav=rtFe*Q?>d|r6#tQSef zKrXTCM{)@%_`rWu(QQG%Kgyn__0FO$g%*T$yAP7;m%VmDp}8rgJ=z4S-h*DX=R!A~ zMD;~-d%{5|O+3hwyGoh(r%*Cv`_7Sw9R*2F*8Lxl4-J*rA5P+lXx|3?5=!mju(M(C zx&P^Ee1S$8eit2_Vf?z%AiMjdcBr}LwN9V3@SBNqLHQUQBI`z#6+YvR= zrvINT$n5M9r=VBJ07H8AbA#E zAEA!>h7F5vFJ$YQc;R^Vx z*FeaA=zIQ$wP3R9D@%f+o(IvTFHuj$^W>>#nMcCJ^~mj3MqtKEUqs`*kkw!Qubfk| z=kg~{*Mak}4V~vg|IZ~#AfXr`tWHSIyVhL(Wp>+TW zTk^3%n2`%9N58c7W&n@wB6RlfKT#NbN6rec3na;20@5|umU{^wd!gB^A$-j&32+qy zt!ZOhH+=?ad`LxVvQ~*f-u%>U5Gm|+(8pC%)aKKX@+&LLxRr2L>*BRZyZxGiOBzy!Z$aP{1<@y3~+cG&XT{c0c%5KS>!P0g2=W{_A2e6NT=$AcF(qm zrH>I;5EjdJV<48=$Gn0CwhcHi+Zo_c@US%YcI_L~x!7!*M&oc5rp99?y~VP}E@DyF z5jbo_i;i&Hp9AH@*`S?w2sJWpP(4n1`pNCUiihe0CCS%7Jv$O{TH?}Yk_niGyE7V^ zYb*|GydhWEQ8Os|#hdqobB6LCzjIIVoRL*eV|T737j0s;nO%z)-5cB6h46aGg~x?C zYR}wNb&J+46OoXC&%vkb26OHj(F;C%H-MNYu-A;dwo;G;=1H+-*F=*HZemxaAR?oG zN%f~_2U2c9>xub3{$397lqZtw+4V1*$$mg_B84*TG!u;>o86})Z9$s)$1GYWaIZkN zmN~F$s1;i)(!g-`5a^S4>42MR|N3ZWf+ySfmAj-{+z5>?DX4)5!=Nry2Af;;F8Dnz zqj=hIlaa&jkEvB|__gvMDZcTN$>*m|MFLwJLN(OpwUJHiig|pt=;?$<_nAj5ZwXJy z(M)@*`1g=xil1@>$Zfx6VM`7K(!f^Fe$HtpQeW9alS@J0CfW=sIgHoiM<-rsz*610 zcFQY#8M{N84Ss&RTHtv*TSoFp8!{o90)?4w9y_G!QlaMDKt1gN^cU636S!r*e1xfY zG^I$I*dHp`fDfO0$9WYY?n@6)m3CqBUBWWp2W3{~$0AndBYc|0zdV#nLx^jQX8@%sbLwpc-Mg=qOCbe zrzKbs?e=zi_(Ke+>6+y^{}nMb(11#2nzo4}#M!vQl>&j%$rW%hiWxUr6wizYoukU+Qcm97n;Rxtq{ftuvJ zk=G6~e#54Nplz0GpM`(vm^l_M)TlFMcf_0yJu~*q{_b~<;lxdi!x8+GAmN9&nL)&y z;z_n)5>mYUp0rO)Hp1mHd94D?Qd3dZ3>=Tr_lpoEN=;c-{an?@3nWvs#_JMg$nFv4 zb+>`P*}~_o(z@pelM46k=ibv;!h}-_%c8eJ(=-M@MKk$B#)(8_v$ywnC+I76TWbkEFMbXM)QN&zUV-vbw zN28&`90y&g3Pwo;SLQzors|c_`GF9;x4SWPX4cem##9c~pOjaZQ8N|%i0bb3<_xm&_)WF`mnVp5b&w!S407u5}$gqZ7vMf?>8n*fPl~PMSnd zd}uchq3uYc#Qj7xa=i=>0d8>;Gkfk7-_WrwjpGrg!JA~4W1he)raPIoLAWu@??K@9 zb{%xnk|e2rAs$F73Z#~&Km!(y<4)rGSEfs#nbsldkYe;zC0)`+X&EMQxeTXx5->P- zT)hqB`+|FmTH?-Y$$8k@6gZawwD+`0!*Q(j zh~tesvmpsg*9>%{U#ct}D!#_N!2`(Yb7qz}rG^!@8z)Vs_+(6gX-suAca8Zv)H6F$ zcyYX57~#mDoy)4WZ|nJLm|W@Mco3tUKW-@I+UC8`K&w+J7GAw8*F(Cy3GePle3)>JT<{cXWyTY@xnHI<7a=zgrHnm6 z{6RxLFl>WwhxRgp!o4Va4ZjWgZ+{>e*vULX=;ygjN0z@EKmmeQ=@6W{1!hiW`J2C~ zd5%L%vYwp9ef0Lx9(myLT}&eq6!SG;Ov7ESI!@J{rXy&(N?d22eC~*eCdBoYtGbV9 zj5aH7@$cxkruN9&HK1zi>D_Ov=!I#*3m3a^)!p~dz!^{N61%sjXnC}#x?Xm)$8@^t zUCeSq%Yi3#qOGw;6~FGffh`K=EuVP5k(+}3em^peiCX|!a<-H=l%k$0o8LTBez(w$_AgD*^n4Qa*<@L%-5FTSqE>$Uk&pu(r@ z6Pns09C$AF)lr3A!u5e_8*Z-eaxuOXQtN+p^4^oW3XWb;#6g8~v~uWqBX#r8aZ~X7&;qSEI}oP>4>EiRhNT zl9FC{iFL&V2!_x`t-yJkWPLxXR>7#sxintGuFoAf0a|<`zgTZP66stgzawb~eNN2g zJiTz`rlJ6qBIQGkKtI&t4g5^TH?E!E>Cot7sC#C%r{v~-8Nnk6aXIMOiAQmz4_vdnM+FWEg`S9?eN)c1#iAv-YU;=<{4+M% z4t={S;a+4&jZpR6CFhA;XSa@uJyF=RFTRh85mJ=R$yV<_s)d-fq0}2{C?7uqeB*6b ziwzOYVQM&`y+z~>#F1_EBS}iyGUSbTLODV^UB*6)uu#6*`(ft?gi~&V;*sHuS{q>& zc*ovSpHhgJHdyUqtiXILV=0AEJ%Tc{F%+S%Zn>Tgs}JS8*M9l~a}MjWicP(Ferd5y z;%uj#su*xpmI6`N4q&)$xdooZy~NT2IgHC6bq+EOrA8f+5fM`8nOjbnQ9UEV!gMeA zA|nJle3htwqL&(Kz*9cwA-T$=R?N$D^0VhQJ_Ebl05pr{v2{pQi&rug)wJWwdVEBj z8g9u#K!5_yYcqM+abzjQ2@ESA3_Fh3=m~sZ?V)ArvjB9Z#cu0IHcyu|T=c|?dJ4W< z`7{|Id@uB6QZFw1)OyQo%MK=F7>?IKxXZw^)T>n?JbF{fyBMieI2uER?@3su#XM(X zV!GHVGSb*bSe#9v(oh{mwc`d^N5al`_r7T%ob})QY;cpNYC3L3KVCE;aP)iZz&Q6T zV(!`3H=f_#45$=;Ao>1E>uHzDCaMaPQU#a!1-i?m9bT7@VVXFH^$|`$#+Z2Z*HU;nBZ3} zK2nnzv*EFDt@ucuS*q*wNGG01w9~`DvXk+;l*f{@7*Kd~X6-4r{`P){Pj=yS(lb?S zHY^A)b+ul@t);E@eNa)VQa$sUre;l zyq35a^zEtHDu-|FX0IohITIs%NR<)ZJhaqL6O+SecXSicxvV|4HVP|pQMl^Zrs;zh zcl=U5Njnm>=@V2tOQ$*?HIrQH=yF43SvtHr4>;p>?RL_(4dfjweP4RKKe439Tp87o zm9*o^#L5fnbEpiMc+)5DTk@#|GvR<4)|Irj&Ih}X z)l2ZA=LC;gVUL&*DvOpXdo59DomQYQKgb5Ur=aCSB<@=)sfc42TldX?>AL846vzwbDz!cX3au%OMg2Tg*AWdp-P6f z&2ALi`57;rqnhoqjtFpJQR9;%5e>Pojnc0o=Uh)XdI! z(YZxVdQ?srHa-m%^H0;uAZL_6o$hhcUzAwKO1E+9Gr!Ne)P_^84a%aoS*&u5-kSg& zr*aNqrX#KkyXfAv_Jc@7qeKl<74(Bg!ZI__#Uj1bOE*XxT-JbIL87C?OX*j?*a=$H ziZqnYEy<_PT$mM8)?=w}&mOcbO6LToXt4)3U_@pdWv?~z z+SiT4E)R|OzVnoM6yA4%RFwm z3VtWdh}SKSeqno=brrEcu`3Gu!5KJ_A5haxU@_>C;e>C?g4JUCpNoBa8|x&QI}N5a z=z`gtM5^T4Fa0-}X=_!)-)AKYe6h^#Vgdw8+%Owd4E?%vhn1;yg+NVjkOMTKf?+)@ z<-5uyMogO{EyL$)kb|6hk^BAzZke!H3Q>;W*JCVBs*;(ry*_)`b|oi|9-HvDoJ$uU zzr@F#8Zmh3`#o1Tlf?0$9Zl;^>axn-x)U4BNNq7)TnTW z=1bfsLgT_+uQ|g^v$F7l_LR3@#a`1+2RC&CXo-%ipYc3LHC@eoDrqvn=F5jiUwdxS zd7JO;wkfF+9~7}LFp)AgY3ZB$*4K*+P-%RK%Q3wapFQSlMtUy&89jE~^1Ou%q5W$n z&YkzJ`FjD}qQ{JTuX~Dz!Q7i2gjU}pZ8ECSXE%_1wxe5GWopj$zug5!!IY9`ai+lU zaoQq(f)qFz2Qo?AmIIuI>PKbJQsl6tYbzIbBg^|!x7qt5RK;B~`K5M0xbIn*nyPkb zulJ%~Z{J|JpXUzC!UzaDId@AqULTH?jKcEpRh|x*ro`@SmjtD_@!(N&-TAA!6HVWq z0f8P?&~PU@2j)(kkkoUWBc5g*@igtjb9swIr1^`!u@t@e{9@c$8;3BcMz{5Pnx3ED zJuBgO4pmo?M_xRa5_`?E%i*{wK018im%t}eTw@VWrcauYJgHBr#Xw>>mfxJNhPupH zlg_1ZeP~_j8!m-h@iGz#N!li@z$-stAxD82b$5$C+7hs1iHp?cvlCr=y?2)rI_(>j zfm+dO=iGF%UjAEvbZu2}_XMk{5;RjL2zFSP!P_kb1H#~X4bQfna;h5?oIP&%MB;Sv%9epj1tRsL$y(z zQFDnad{3t-KTFowBtB6?g~v5#lKn463YVFhL3c%5ya1~E-Lea#st<8)!wp#s1&mgi zp0Guoz}&qcQxkpQO%xq#(BFVS1i}3@illWLpE|?SEP6%e#6;*E^(OY#I>b-Yf zl(zZ&u6Vld1SUr1F00e{i?#Pg@Xt)ccg6R`KOFcf+;H%jFqgPRtz)}b@QMc*8MoNJ zS7lFNz)|s3?D}CJ-cwRFF)Ed8$rplZY<9=|Y0Z~rYX)5uaWDSynnz*HMkzZV$SaI6 z9z_N83$NA!NE0oSfL?L*mApsXt4>z>=0Mhw`+d6@1@3uDAJ)xxTZ$<|W?OnAk$1>I zj_fyJ9~H4qyI%B0y`&}a_=o+cAKX&n%e~Sg)Y&@m0z9Ozqd9MARGk}NrF;vqIo_rI z|F!q!;Z&~gza^DWG?&SlU ziuUV@ZW)bsRJp{iRn|H*1nsgMZ8=FCEdGKUPF9Ry%b^wL^_np-0%N+?zGA{{HDM;h z90I-Hw7P7!NLO<9aybW%$a$U$T}$n()U@Gs7EaDr!!g;_VW##uj_|Cj?gC;PhChJI z|9Gl?lPO{vYCRV^wt;i}R;!NxBg1X&lx~OBD+P`{`IfyCiNmr)5Tu@{^%rBpHWh4P zdFVCq$C~kC)pi)1vB`%^dOvob(3Z`@n^~B>e=CNOT6w-e6`h=G>@4+Wzxy$6n0S%2k@E_@S&mfb z!D+%op5)7xwjmWp4w$;i&B&`9!ak|R*zF9n?!wrOx$J1HWVED0HM7C)eZ2q7#Yu3! z2Hm_=LS+tIT6ag@zg>BQ&u(P6l{W3oGgTuK&Vv($piS>igVZ2Q04Zf`ez_mC<>rTD zBU7)G+hmc6b=WXs1@D6t86ny&D+1n~&j@SijGlUh3A_4mXlUZ@yTNwoBmFvYSRgEX zpL}i-IV-eBZQB^hl-F7A(8}6&+2Q*>FS=Vz9razZ2fFO*RIQx|80f0zGiz5O09~Qy zT#9A*0lGgvU=sTL3ENK-oFBV7W{;Ky?Lovvigp3X;oAA&#xig;;*JC=9yL+edSHv^ z?cJJh*eT)CKi~{i<}(d*XK3@eohG?jnThL4Tlb}#>_h$JEe9`~3A}$)&^HpidyH*G zBqC=G z#lb0WNa%uKb>?>VCT=rvjQvo{%hi`Y^^^@iF-vtOPCuSGT%JHKHMczo7XP8p+aab; zPsyD+>*jdI=!$IhozMg+pN_BxN5_+uso;I4rN;4bmU>cvOrtjl5s9e?}z)K4vg zCPYvpx!DSwV7%Mz&~Rx%+5<;-uR4N+LI38xWtr(in!G1^i4?|~zznyQ%lsG8lM)vO4|6)!i z-Jiagff~i#{sk$-QGS&k!5w8Eg#(GB%Cc#@=caB6vLxaN?+bTJ34$kbYoDds?S_jb z>q;Iz+7qx(nIcdP3m(3#Mng!<(T3r@U@G|=UVO1~@9x_jpX=Exu7QPcXYbC<3O8Wr zX8X&6A*tGiW-V<4iSd+1()Ho51Yg{2J2a7AyH~mY?S@|O{+GrUjBi6_94?vsedgXM z=xI6#?hhJh@2ue*^u&K`D2C3E2U06ZE+$gr#6cXn#;<>f_IZWn)OClx{XLp34OSey zNr8x1kL|nfvwR5Ywx|)-(IN3y*c)VEa%SPssq?a>wjqF4Av<|Xua_pt9cRy*#?ADi zz4pv*6+9x2#wzy+ij{q|OT!WTc`KwS^llGi5bBdf>+0BdyQ0BY)%wtU8@>Rze@*45 z)T!?UxBSd@?%Bbd8FKa0o(xf^k4$mO{ECdLaJ?E~^h`2CSj0tLB_AVd@7Q_Y)E&t# zZ(F4RaZ71itus6$)nTN|QWska)cN+gZ$P5naybxI+)9_Z4tF;YnnthYxRI9L?0hYQ zOqwauhCZB+9bV0gyM2~8*Gguy7w?FfH{$LOSo5kG{jMS8i@*Z0G0Uk2RJYFuL5{lB;Z);B)gUi0yA zG#qH<2x6Zj<4#zViCtfy^Z7btqMhTmvF#WwOo^g=uFcjYXJkOHJ&cVx=^8xhr0jVw z15JpV-9?V}xk}Ho?PVVm+*Pf!LyspTnMJ%6eFJ9jTvM0m`3QnTv`V)|v}Dqs?C7YB zL>I-Q9-h{{6bon>-kq*&L$BrQO=~InLc~?UMy)LF54-Dd%sK$X*s!akG?6`cE?J!N zJBYF4^dDTz>A7<8&YJCK}~) zS8`LQ2fEUJ3FFoD3S?4*SEXTqwV8`3Nm4G>M82Mj!%EcFg;mVp*1K+M2c2E?QpO*`9^p9ijrt!#YoBZ-?M~+wG2I9jQ zjAjV+m(rztDa&V;c2LH>`GvsppO3w7T#keqbbopIz2lX_`WL$EMQ{4LsQDkZD|C6Q3{U!>g=gtebQI`H-(Mg$E>h~O$_K&NMPePVf`Q@co z49;?>^eF8q`xus{YW-q$f#n=Y@oWRWUc(aEp|HMJ>1hF&&nz#|K>{9NG#%7;(x7%@ z6aO8eRomS5otWF|90F?P%2kA^sF3%;Cil`YmJx(MnOr{3=@YCx7$Y0`50!ds2d#m3 zTM(|(@xS~nT*qwo7x<(K^k?s(Bn~t}PcM)=sv`ARvI7p`|0d<>ICgQ{9JAh7m_syY z7-Mx>_KD&`ZP<{A3sn`>mD_}zs{p+6w?H<;1il5b7Xbx#@>G4qa36e}e)Kd!E<)9s zhUv~cnC#0OEB9l1GgYJ0x0>dnk%dL(=-g3$+kNcD?*6a|m7eQXNnyh7LrfDS z1^YL9gk$2X>2+CqpDok6GxxXQ=iuffZrEi=!#m#+{)Kl=v}iYpp0M;>af)%&U09Gb z>bp%qKwziHb0-Dn-tw-FpVG2=`$gxBhWb4c<57DlN>B;BiXgw{B}*_}umLo=#8EcE z@kI8{elp$I$vyFw6xuNc7PPHA^pmKQz%hQ_y7_TeXk;5bq!Y}ExB+V0QuXz4ZO3*s zV%EVCSX@xM{jaahm@I?e&W@VERU2W=Z^2mbroRuyDjxk7jHTL2=w;#80F}#9Tg>vq zKQv-~pDEb}ci|0o(svQ+g(Q#4T*_*AT11+v(kh_8bwt*ryRrt{f?W@ixIJ%s&3D1% zXG`RZ3DH?iOLzG<~@CTTYrCh;T zPXb?kr6}6+{4_pZ;MjoEmx`hB-Ej=E-BK`mSHg@Z4@57`1qUg?u?& zj9f-?o$8HsNA}~@#!`m;$}8s4VNcdHV61gtc~J;BMLYb;Ojqf#j_lNwP(1*9^{y9K zpdeGusg2mi$=es1Y^yXpRn}LTFZb#43ni}j=P^{{B5NC@%srqJ zmseb_NDkRmb8U8V_~I)TZC6NgRyeR`QEgV{*W2NAJa3~>4*Wq{-DF&zg$>!M`*3u+ z4=>*}Zu#5~&nz)W1MAYa=1Odt{J3I==}eoJ@H!QPDb2|! z%#@0lSq9o$3IcC$XtX>WBb8)cOa$s#tc=g&Iyg{mdwadvG|7Scx!}~xKel?&ui9Rtx4c(CDXl{RvNNmKd9AA{YwIwi z7*62_@lS+~4LG!gCboC`TqNI|;ce5mBV1|iWU!83r&@{{Cd+Bw(ABJmF>>QWtwqXT zo@I$f5_*uupJ$xnlZP*M7T>E!+{!S=kQMk!kAQY1P8Un*u+~` z0bA`=){_$l=Rj7+oswOlrxUkS8{t(U9ThIiCif6EOtbl)(l_Ugd~E$1cJO*{s?fYG zVU|}A&D?#ZUXX-wXbKr5zu6l)K3$vOEb-||y+Lc}wE+&go8tk>7~=o9E2O#DGX=r=l0aUrlV?)vv4lL z$JHrVMi+qo#tep;J}`old0vrzvmWsoQz>tu^fVg1!_EADy$^SWzUC~-8FnSeV{oj6 zg`sZp=~*|aHh1`a8ZCE6UvA9S3b~mtEFv&(?1WD8IVG_d8@N+dt=m@alR>s^mWG{e zyr7jFW&E`tJSjrFW6;_;(P#D?8#~kGp!9LXIlzvflm$SKB#YDzg&m;8Zk$C&V7g!} zJZ}?K1_#|72Ct70Xp&D|EnVvwK^R;!R^i@lgOau)qvw2?o-C~vQ$xm+?zo-Zxuj8Co5??bNL)v zUarW!obwS!^N9%7X;VmSbarALsiI@wn(Pfxa&_)bh`!YICLL_`uOV%UtF zZ2khg1o89Q4?de`hs;aZ4DC-#L4f(S!?_;onw~dzs^TF9auMK0Y*(-Bn7dctZL9>C z^l>(|{FGn#85t91x~2}xO#8ql13LaTkw!N8_{UAA@=bZ>6Fm|6HFQ6J>I7a*C8MK~ z4QJQo>pb{~aLGIsovi>_VF;=Y9_R`YV=naG>cPal4uI45j%_T;;hwJYC`3}20Cb5m zXDILVv3wQk+H})#UZ1y~3Ug~iOsCISfTvP-Y0;9iWe9tJS zW0U9Y1gEaOxgvuGxa-;ycSso4VB&yp5V+{>I&oC#pt%yL*2iK7!6Q{dZeP;}Nu=53 zv~%sHd7)vgpTjdg{La@|{H4a9QN)+dLYbd$mqoO;j+?aDmj()+$zI?4;N)^D9F2~d zj~{%y=#UxIb$q_Emw*wzHcK3D9C6kPP@(UqAA6$ecJ_?fg12_TF2`rF?()dH#y2PX zVoESt#{L}E4#vY-DtQ-ydk#rbXR6TZZdW}UZCA4=cX($Lpw3Rz1hb|f$xfYI$14fm zhhf0<1s*%ymi?i$PB8G>I|sAsMty=&zIeq^;)#O}Qm<485%j}W-0U#n6Ef4Bg?Ez? z;1*YmITUdcm|-@1&23(SIF*|F!G$M;>IPBzE16|s4Q9Huq*LJzETSCJglnW#i0iMX z{~$4HVZQN7LEh~a^_&7zH$mf=W8K^Kv zDA(?DPx>%zL$Gz8!^67NdPB|u00!XCoA^nFW=U`9s?8(-S-xi`bM(ZGBr(#SO&ht>7&x}i7u(|_cOkqb=hZmbRm>FRhqToRS^ z1vx7Zxhco7YcO^Wd=Q(mekg@v(pG1MZFY`J3J7OC6=Dbj(RDOBVTc|w=*Yq9a*NSNAaMRh&M zx9am&W4*Pla~TEuBF>Yv9_@o}j$PCCeP~RCr^*7{!Dm7VZz!c~ht~L~;^YR8rgso6 z2tHcl!Zmu2t?+3dM|#fNwmVWdQ{9tpGjggh4q@DZQTt>sNC$i~wVyBuxVjBRlATHUtbwGcPdEb3x-T{H>4WV!0%v_& zlQcl?cpXAL4O1joMj_O!FpX|yX=`@;p7n$5U#cMW;;X-?CWjE0o z#Fk_XT`1msaAyIzKUTfPAi+s{GW9N5H^9J*(!rUT@3-)7lEWHhc-8 z!mj42T2H0uQUi|S%Ep@Amv!%rzy5ni?#2S}1X+|J=P%Nw6ujT98HQ3aA+YSTq83|* zKYyx?)9$k1HJrV{J%pa;@JLx)gY>l*% zl!MitkbssLTvD2YGLygtM}ZCZO0R8huBl#joW3kzU;OS>ox4MHGylNs7P&iPh5Qp_+}8V4Yf2brqYu>lUJ^}#@?js8K<0)8ZK>W1}rVUC@Q z<6*pEY-Y!;u*~gFZDV2G5`@5sIEzOq$B;lo5sgFP@nM1tF4z1?%loPxwa2b+)amH7 zi1jtfYs$Riv|=TCywe|P(3FOpiSM#;Q0m-tZ>CW%FYW7k;SIh0&0AFJuS0Dn`#P?J z;zJ2u_Kp3JU$lKtmkn6fi&GtUwa0~#7alBPoA6X!;~H@e_Ey+;83W4KQ&1A z&K7*;+Y&7iY$K=k(XczGfDb^0yMEZrNQme)5D86Als- zu_Wj0NlwOvBAAYiacV!9`d+YA(uA*v9(R_+ENMr+QFv{ywL@)80zIc;(ze}2j;)E6 z1mXwoD~*`T=Z7)4VK$uTN249m9j=)TU$Dz8KaG{jTby-cKfG%832o0wFT1IXHvMDk zDo+|&%2LBs#S93*igz6R+sxLNH#e?$P<+QSpEQ=>0kyEof`{K3_t&_G5?0DT%ntWXA_4C9qAvaa+MA~kpcok->z zJYKF0D^Q)MtDh)o3<}Qt$v%Y8AChfXVC*oFM2&)|EH&ZpLBbL6Y3FhpAYZQi7O+f+VAXkjRPqfm)dh93lm1^ z$JVil`}Dt9%^ku%;vKaCGyHPn>GGhABlfKjzp>$FS~1_X^T?5wSZ#flc;{EOYrJ2p zqB>p;@^7J@KY=aG_8F1tG4!K(5hL-Jsm>h)bS@)^D4TFjNh?N=bzHilokbo@9w7d` z9vqk9nt-6r*2(LEA{Tq4I5vAl(U&AW0L(^9uR-=zH>llUoc$0DH6)&`+d`nK1-bg; zIHy)OHg^b3`D`&KFb_xbj29Lb-b&MMO5(raMX`_O{6_!1fJ%;!s-v8t7QDLF8w)!q zrIAcBm52Y$qXNPU#K`UU6KC!><>F?k6bF8IEH)s5z+NE>C6?N>hV{?%*tP*gN_ z8guo4G@$j10Eqe^IFmce077|)NiPLsCJPapunzpGnv*%5!zJ8Ib0`e}ZWck+FbAUJ z%C39USNhOzt8}CpM)2Fp()}rTn>AzSgzhj<-6`75LPO_;$*Du}+IexU$s$g3#9M{r zoyO~>0yw}mQNP(WmmQnWuBx{5mL#lep2g*VcyT{?-#ljr&pG>1YEk)s(7QS^04U=k zz>KYqp6LI`20nzpCvNhOkM^Tr^KGmHVOUcEX4FPN?xlUrH(kTU#AGr#^Y&@P9LPwj zUH~KNl!Mr}$K4#0UuU|{9X4~chOw58Ol|%|b0xVx_A%M~OV~v7V@GYFZ0Gl36Vs<= zIr8$#FqN`*UnNZxi<=A_x8(?Ges5n=e*M#!0?v8DbdaQWe+KuiunkA*O(6BY*D0?3 zBgBT#R~lQ3O!pP>ka~=?b1>gJ==4gu&naXK9Rj+EnYmZcr87_-F4(OhHv4FF`awNG zG|c&7K2=4^gR0L5=W-dTMExc;172e$-yR-U{Q1SCv>3*^OaQP~NBoaEI5`6wH&CS9mG znjKjzW}!SxK*pIOQGu5Fv+juy>w$f^xcP^9>v#8&QJqH8O0ixp{BdickPM^;jJvH-ucof91|NH zDW55db!sWV#}Hq-3*~-&&)k(U+Xa?w-DjUGH5k15uPl4*TvQ?I>MCwRlX;Ex%{ z);+9{zIaeVBz<-?`RQ)&S&Y!Cxk~v|*mlALeGkgz7O+DVhVOhn9DvIUsxVl0ak6E5 zwi0lL4(VuJkSz;4r|Ra7hd8bkergjqC3AX>(8p>xh`M0&{$Mio*jD$@ty2 zvwgNDwTVZbIa-#tyQaIYuuX87Iv+^7zK_4g0qP0e5Vx=s*X4C^t>peJaBdSJw)A&@ zNn$?|nw}TKS=}<9R2WB#MXv*rRR3Uvq>p*#VTh&K z-@Yhw#lFFzbG7`6d3t{gz$oDWjWg&OF#@}YwPZ@%1-yt*e6MgCUkpKqiSi*95)huZ zG1HygZV#CH84={qbBVTCWd=stYStB)VN*>V%RL$5LL!oFnkg)&qdKDQzj8k07F6tY znh+J@E&bqWmzH>l)=6WblAD(|o>x~ew)!+GF_u|6Reyms{%CRjldHXZOb-<6O}(*O z6Cxs6-Sx)_rGrFat2?|^CU|~@T+whxC|?zF)0puReKZZ|O)tjs;`2~Qv;hg}u)H9U zh{L}(fw)SZ$d{Y?d}nXtppj(1W{Xr_a>c>D8knT=){U;o6{flvn~>qI)tJc_x9&JZ zYB36w;GUPA*OX;rWi6I_VRHdN;=kn0dFp59i8=Iy8Y#Qy3E{@f#6C*#D>M5xC__q` zFGE@gXef9DBc^?uJ}^u;j}7MOPDzbi9jX>4^$c+flYCpjMBkXZtS1=PQI4^Am|v1V z88)0CvGv*p6Q2V83s(o0=i5Y-3jEe^w%#kaRKT`OPr9C(pNZWNy|0F|WQ$5#E|gkn zGh#wlapEKgOm!3Of(~E60l@FfjUwWVX+Q5Oufe>T0f?u#-&Ej#ufq6spgAAoM4oA8 zx@+jzqds#sw1$(jDZ{3{q2SUiF-2D?&g~n-L~{p(z&2|?Lo+E;kog}C&WyYVR3V!F zcHlW*jMvE`lq!_*0-m>^WP=Y3BNveQhp&qhx`Da^Kb z8zlC0iBzpDQ{mP5E&ZUrvT=ks5bdx9K--#oz0u4^Ej@x&zDnDXg7_ep#NS^)z;{_G z9SV@$`#zW+s`!S`eyzyITPBU!y0Nz)Drx-W#KL z)Nm?9c7@?cw~VbATjXYkiZm3GL@#r$NJlD`q#VDRNkJ98i!I{=q!6f8(Awd6Lym)O z>*kj>#m)mz$c;puMNw`hl>V(*zHiQ9JubS>o$ASOO z?j} z+Lsb{tz4m0UM{a1vKnCJUrR(Qk2f*%J?ERMX%C~9=5FL5_1Tfm3jB&S zqnHt8YQ}+zZ;%jhgTrOh$q~CenRJeq8jfLEZ83?{CE5w>H#TN;o@C{svI)g7MJ*kk zWMJGfO(E2$=4ZVJ;QqFV4vRd92WIYWO7ujab2>kGF#bt=Q)SIgPuK=zhtgNmdl`@G zwH<|$xCCcAMFsiXFRzCZ_c>`RYDbvT5Sl2twPF0cvpIn^6i6 z#u~uE_T8>S8yAQug_jXW&97@s&A?r1nTrpmLA1*NA3>T6U@3ihv5%6!SH*_kQhd`D zI;r0fEJgVhjQSb)5d=G%2o3x${K1LJxIe66a{-4&t@NVp2rTTq z`9DNbI)O+FHH_$_eFo@eLL0S>UusxQ347*~zxc*OoH9(?a}fhl4wX+2F7Ly`MwCZy z(U+Ye=XC4vHr0dRr@UZ8V8}T?JnhJ7wGq>1QgY&G z#Di9q(AhgQV(d1hVM3%2rml{qFKXzQq?K5p6~p-&OZ*p_Jzv61x%(&gLXK3+T`|@Y zdD#6QA7-w0skwS$tT1;%#zqByUm&{!CqSz7j2aV~B^F-j&p_jSi};-uAcHu=14-17 zw-?Qx{xH)mBd<%5ptt95y%UIU9`WPjY}7`&cu6u}q_TE64cx3`x%X}~T_ChBd&nHv z+~p^1E{m|aO&tSe<01w;uZW{Pk%kV6aFDmka`#LidyDz;VGe4ST3+JkL`yPm^uw&! zObK(IZLMA5Uff8))ZmrXOP(ZM&2F#+_FHhF8d8H+oq(y-$N?_zxNln>&jR2blR0Vq zeSovdRq>6{Y`>8!Vkd@?`c%4tTGK|;+;F(o{K_l7o>axSkTk;$fkwt0`zYO~nAwG^ zT#2IsW9R>wzm;_TojRnA)=2vfFp{Sd$hJ@J=b6=d79wC9(gzh{@`?KFzZOW6dF9ZH z+*^L;R+Q!5(I_=y!ZeFuZ>duUkey}yxU-jvZ(a;;{o;0QLN3p)*DFDK5VE#zk}A0s zD;MsDDlSF1VOOIz^?NDjo2VXsbEYe@w*mNUKPD2%-=_b-)Im9X2WFd!PM0W17lyW9 zE3TOJ*NXb8+$T$nQWg$xXZ;qj`u>^Gy1>)5g^g6mA-%W**=cGEf(uBsQp!PsSg}9i z0ytTB9VQJN$uOQ-xlMpH5gpd-G-mDI{BiQy%FCb7_MwYe`UefS|4Ud&Cgi60&o>3x zKL7!&b^eFs=t;q275cRHMQs?ic-P5smgaS)vtOaO_@@s6&m=)z`y*wG*sb`J{b5W> zPNz?AV{$vcmlc|ZuuEBwvhH$tMFn$c?y7pL_y%KCbE}o$EgYRYSUbp&Zk3bDf2f}d z37WrqO85sw+oC4Ezfjd%;%HZZtK)H;{y7WPXuI8cBi3nrdzv*-DT)=v?-xFnN6Jm` zKu8-mS&sSA>eP43+D)7IHSX4LnUo$@i_eReA2P6pYvK-VWSeYln^ZpP^9UJBAqO_;0yBZiWcjjFtd4*JtF?x^>zgYnJ35zfdr8zFL_4 zK6hNcG(#!#QyvtNa!|ln?R{(8Phff*0Q((^UC)S`Hr)smh-bc% zU*OojpH}iOJlXn@H6eU#ZWg`f|@ywY5_CuptqCloLEqB_a%7SOgP|2vWmqT9|a zFIR*H(_m2V`AY|($e`Ox?lX*T2%Lo zfj|yhU)6sfRua>wwT)0bDqG=*f2t7BndX?jnVPz9vLSlk zJ+M->w?4Igbp8%0Kh(lX2^A+%I44#PXk{u#-#{M z%R96e2$y*gfxQB&#wFLH@p?Z5;4CMs%?9Nhf>zpZ9zZ!qq6Hd@;^X-bX`!zFe{0hE z4>|o;OR5i@AU=($;?sgfM@J_*HGkhh#7W^`ZJZY|uXi&yJ8GZJuAyS}5!s;0R~0yD zcep%Ke!mh*t`dk4T9b9A3DIm9zte0k1t4>7uKr0c{9Zr+8{SQUbP@7I{B{r(p3#}6 zK`xLKjR?Y7tEr1+44@zCgA~ln&_~t5Vqqf&3Oj6hB?Z6jg6)8n_VNz=u^Nn!fTr(^ z5FQbbF>Uzy4KDZrp9KQFe%CW}IzsqgAoaFe4BX$%16a`L&SpLT8pe2Oiqzw|3$j#5 zh;7MGol5~DyntzeE$S^npEly?+ndrKpaq}FS?kh=J4H{TP+r=D0xiVYpH+=+7HpYm zI&`G(%%LqOU)xP#{HY!_@hd?bzd)d@+N4zJ=2ov}^Rjo5%amPdcYZx=EtdqT%~sm4J7Fb&0Ch=KdYx zpA|HGB2Q9CXgSSw_%L)OdwuloaCIqSVbTXT-^;}Nl z%{Js*JGmifUR%!npee*$i94m`AdKek9N_YTwadn+_w#0MIeAyWtNhKRG+)7l4IhRN zHXF$=Ns{4_GhD(6oL5PkhoFyd<9mDQ)=Lm7r8Dah;z2$A4Zl98y~d(SfD9AIS`xNjYUC#HufS$fCUh#uu< z<*0=jeHf_zo3&4s3+PLH02UF{)4T@%ycdRLjD8kmG~u`#>4AhuCi?$KrvFba4^$tv z9??u>TB#TShfGy{tDB_VEDVx+c$fGhZA5Vz5AuV4^I;{Vp!)VLEhL=|>FE~9=RQ^o ztoCD4I^d&Atrz$Tk8ogJNJFS3uQ~x5V1KgJAyjES+S@|pZ)y}cyM>h%_n!Nl-Jx!U z>Ib^PXxc{A7X+VU$k>u`O8j$>|9WZBYdMEEIRMEtRUaMC8n~3;Qooc1xFz!_S$3jd`yg|${xx^sKl6B8%zkVLY@Upw#LFEW(;5tH<}Vk+9$^|Arn z|FnwBo&Q)PbBFy?Q#<3OsS#cG?2% zlGGiFm`LXhO`;`UAul1w-Z`Vtf?Us8dC#`;u&& znNoB*eJw}h*NFS`?$a{-dPL*0F8M+~(YVt)kYM4VNU+@3zN2&n0tWYH1JBZIcFRw^ zHcQA{5yt6*xhcZf52B@`n_`Cw*+hgv1 z`c$cfh<$qSyELNz6h&nh@_^8jZf>v~6#SZuiBP}-NFPYnUHwnvPN9-#!A`4$APRT2 zw)z6fJ>pOZ6r}}yrc-*6b}h0fdW6|53S2iLHaE%*pZJXS4O=ZBYBd`xAK zU$CoKStYw*orN1*;v?uv|F15I@>Q67;r42Mg2kukwf73_0Zgs(6U@j@o{K*K#VZw= z%f2-ZS!C5NeTo3HrFQZ7mxlsastCdXHtfXG3&Pk9a&sQnj{3Dl*k#_A$zsP(_igxE z@t2E{aG|G%(b@frzE+@$H|@W|)Km@?ZZB8*JGMVswKSaIXJ;9`hHtDc$7#tp+!D8f zDn6m`8ctpb>d=wJH@@^4W0kNm>75K*YxF6!3h zrS-pd5^Zo2HtH*W$wHv3q4jq>Zvl;En_P;p+>X*ZJhu7$h zj-bvNN=J-r_Vv#7LtM{LZ)EAU3LIc-T}{7Jx+*OuK_`Kh{7fgOWw=o4qrN*+Jccj4 zW@fdo)!D_gSfGzLeRj3dpz_?$j=4Yw2r?-umHk&P56cE$61sc)ThG=d-fHoJ#!p?; z2OFw&z5d1D&TlT<6R70w@i+4Y?~4y+slx>I5o7noT##B#@UKK)l_Icn>EqA8#4qf7 z!)v6+Q&^XTU;k{M-P^-!K6a>I`X#~U#iH8FbxqfEDPQ2HXL5PHYH$CgJqLb?U5e@X z#(ZR-z5165fb#GxI=->1nf@U^BeNyX;tUA*lF&MnU;2^(Fmty4F-p_w?{|*XcNJK+ zjIR3V@4sm-roDN3f&^X?@Yxxa^P-D+Wyx1WUkxt=UosHd#rqEn|M1cOMApip&)GX! zE0ObQi91b$n@ewyK{4$AlDzytA(fvB`ZeRz_&5jv&+;9=a>dJO4uDV#d3!KX>uYg(xKIe^sB8t@HY)ahTNkzP3dD`LX`z*$Rt^gAew$Po91*Z&XunfoXj z?BKfcoPWBZACHF_)UEfW&A((pV8g+U(32ef365lm{UG#%)db`Dt@$t6U(4|Sqb^G7 z_ZEW#@e0rX`gufP(i@CR>#sQ|rsF4Py+E44-!L<)_O9jG{PSfgM8nGyPJRq=U;W%)z Date: Mon, 30 Jun 2025 15:30:50 +0200 Subject: [PATCH 054/128] changed version to match the other controllers --- motion_primitives_forward_controller/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 506d4ef4d5..d4406cc736 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -2,7 +2,7 @@ motion_primitives_forward_controller - 4.23.0 + 5.2.0 Package to control robots using motion primitives like PTP, LIN and CIRC Bence Magyar From fddc82480be5382d1ff01b65eb8f46f05226cb98 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 30 Jun 2025 16:13:40 +0200 Subject: [PATCH 055/128] removed name parameter for the moprim controller --- .../src/motion_primitives_forward_controller.cpp | 11 ++--------- .../src/motion_primitives_forward_controller.yaml | 6 ------ .../motion_primitives_forward_controller_params.yaml | 1 - ...imitives_forward_controller_preceeding_params.yaml | 1 - .../test_motion_primitives_forward_controller.cpp | 2 -- ...otion_primitives_forward_controller_preceeding.cpp | 2 -- 6 files changed, 2 insertions(+), 21 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 525a8026e4..bf98755aad 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -53,13 +53,6 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi params_ = param_listener_->get_params(); - // Check if the name is not empty - if (params_.name.empty()) - { - RCLCPP_ERROR(get_node()->get_logger(), "Error: A name must be provided!"); - return controller_interface::CallbackReturn::ERROR; - } - // Check if there are exactly 25 command interfaces if (params_.command_interfaces.size() != 25) { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time @@ -102,7 +95,7 @@ MotionPrimitivesForwardController::command_interface_configuration() const // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - command_interfaces_config.names.push_back(params_.name + "/" + interface_name); + command_interfaces_config.names.push_back("motion_primitive/" + interface_name); } return command_interfaces_config; } @@ -118,7 +111,7 @@ MotionPrimitivesForwardController::state_interface_configuration() const // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - state_interfaces_config.names.push_back(params_.name + "/" + interface_name); + state_interfaces_config.names.push_back("motion_primitive/" + interface_name); } return state_interfaces_config; } diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml index cd100b7be4..b0c0aaa38d 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.yaml @@ -1,10 +1,4 @@ motion_primitives_forward_controller: - name: { - type: string, - default_value: "", - description: "Name for /", - read_only: true, - } command_interfaces: { type: string_array, default_value: [], diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index 916a6abbb8..6a46535909 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -1,6 +1,5 @@ test_motion_primitives_forward_controller: ros__parameters: - name: motion_primitive command_interfaces: - motion_type - q1 diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index 916a6abbb8..6a46535909 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -1,6 +1,5 @@ test_motion_primitives_forward_controller: ros__parameters: - name: motion_primitive command_interfaces: - motion_type - q1 diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index 55a17fe03a..c1c980c021 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -34,7 +34,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_TRUE(controller_->params_.command_interfaces.empty()); ASSERT_TRUE(controller_->params_.state_interfaces.empty()); - ASSERT_TRUE(controller_->params_.name.empty()); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); @@ -42,7 +41,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); ASSERT_THAT( controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); - ASSERT_EQ(controller_->params_.name, interface_namespace_); } TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index 1a43a6982a..c738b31c5c 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -33,7 +33,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_TRUE(controller_->params_.command_interfaces.empty()); ASSERT_TRUE(controller_->params_.state_interfaces.empty()); - ASSERT_TRUE(controller_->params_.name.empty()); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); @@ -41,7 +40,6 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); ASSERT_THAT( controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); - ASSERT_EQ(controller_->params_.name, interface_namespace_); } TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) From 332f00d9b1be76b12005b794924b17d7dc1e1a75 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 2 Jul 2025 13:18:32 +0200 Subject: [PATCH 056/128] copied controller hpp, cpp and plugin xml file and modified them to run --- .../CMakeLists.txt | 26 + ..._primitives_from_trajectory_controller.hpp | 121 +++++ ..._primitives_from_trajectory_controller.xml | 8 + ..._primitives_from_trajectory_controller.cpp | 495 ++++++++++++++++++ 4 files changed, 650 insertions(+) create mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp create mode 100644 motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.xml create mode 100644 motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 0f5ab87f9d..b71c411295 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -31,10 +31,19 @@ add_library( SHARED src/motion_primitives_forward_controller.cpp ) +add_library( + motion_primitives_from_trajectory_controller + SHARED + src/motion_primitives_from_trajectory_controller.cpp +) target_include_directories(motion_primitives_forward_controller PUBLIC $ $ ) +target_include_directories(motion_primitives_from_trajectory_controller PUBLIC + $ + $ +) target_link_libraries(motion_primitives_forward_controller PUBLIC motion_primitives_forward_controller_parameters controller_interface::controller_interface @@ -47,15 +56,31 @@ target_link_libraries(motion_primitives_forward_controller PUBLIC ${std_srvs_TARGETS} ${industrial_robot_motion_interfaces_TARGETS} ) +target_link_libraries(motion_primitives_from_trajectory_controller PUBLIC + motion_primitives_forward_controller_parameters + controller_interface::controller_interface + hardware_interface::hardware_interface + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + ${control_msgs_TARGETS} + ${std_srvs_TARGETS} + ${industrial_robot_motion_interfaces_TARGETS} +) target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") pluginlib_export_plugin_description_file( controller_interface motion_primitives_forward_controller.xml) +pluginlib_export_plugin_description_file( + controller_interface motion_primitives_from_trajectory_controller.xml) + install( TARGETS motion_primitives_forward_controller + motion_primitives_from_trajectory_controller RUNTIME DESTINATION bin ARCHIVE DESTINATION lib LIBRARY DESTINATION lib @@ -115,6 +140,7 @@ ament_export_dependencies( ) ament_export_libraries( motion_primitives_forward_controller + motion_primitives_from_trajectory_controller ) ament_package() diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp new file mode 100644 index 0000000000..67652f8a82 --- /dev/null +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -0,0 +1,121 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ + +#include +#include +#include +#include + +#include +#include "controller_interface/controller_interface.hpp" +#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" +#include "rclcpp_lifecycle/state.hpp" +#include "realtime_tools/realtime_buffer.hpp" +#include "realtime_tools/realtime_publisher.hpp" + +#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" +#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "rclcpp_action/rclcpp_action.hpp" + +namespace motion_primitives_from_trajectory_controller +{ +enum class ExecutionState : uint8_t +{ + IDLE = 0, + EXECUTING = 1, + SUCCESS = 2, + ERROR = 3, + STOPPED = 4 +}; + +enum class MotionType : uint8_t +{ + LINEAR_JOINT = 10, + LINEAR_CARTESIAN = 50, + CIRCULAR_CARTESIAN = 51, + + STOP_MOTION = 66, + RESET_STOP = 67, + + MOTION_SEQUENCE_START = 100, + MOTION_SEQUENCE_END = 101 +}; + +enum class ReadyForNewPrimitive : uint8_t +{ + NOT_READY = 0, + READY = 1 +}; + +class MotionPrimitivesFromTrajectoryController : public controller_interface::ControllerInterface +{ +public: + MotionPrimitivesFromTrajectoryController(); + + controller_interface::CallbackReturn on_init() override; + + controller_interface::InterfaceConfiguration command_interface_configuration() const override; + + controller_interface::InterfaceConfiguration state_interface_configuration() const override; + + controller_interface::CallbackReturn on_configure( + const rclcpp_lifecycle::State & previous_state) override; + + controller_interface::CallbackReturn on_activate( + const rclcpp_lifecycle::State & previous_state) override; + + controller_interface::CallbackReturn on_deactivate( + const rclcpp_lifecycle::State & previous_state) override; + + controller_interface::return_type update( + const rclcpp::Time & time, const rclcpp::Duration & period) override; + +protected: + std::shared_ptr param_listener_; + motion_primitives_forward_controller::Params params_; + + using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; + std::queue> moprim_queue_; + + using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; + rclcpp_action::Server::SharedPtr action_server_; + rclcpp_action::GoalResponse goal_received_callback( + const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); + rclcpp_action::CancelResponse goal_cancelled_callback( + const std::shared_ptr> goal_handle); + void goal_accepted_callback( + const std::shared_ptr> goal_handle); + std::shared_ptr> pending_action_goal_; + + void reset_command_interfaces(); + bool set_command_interfaces(); + + bool print_error_once_ = true; + // cancel requested by the action server + std::atomic cancel_requested_ = false; + // robot stop command sent to the hardware interface + std::atomic robot_stop_requested_ = false; + bool was_executing_ = false; + ExecutionState execution_status_; + ReadyForNewPrimitive ready_for_new_primitive_; +}; + +} // namespace motion_primitives_from_trajectory_controller + +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ diff --git a/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.xml b/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.xml new file mode 100644 index 0000000000..d4485d3a9e --- /dev/null +++ b/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.xml @@ -0,0 +1,8 @@ + + + + MotionPrimitivesFromTrajectoryController ros2_control controller. + + + diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp new file mode 100644 index 0000000000..8c25655f87 --- /dev/null +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -0,0 +1,495 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#include "motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp" +#include +#include +#include +#include +#include "controller_interface/helpers.hpp" + +namespace motion_primitives_from_trajectory_controller +{ +MotionPrimitivesFromTrajectoryController::MotionPrimitivesFromTrajectoryController() +: controller_interface::ControllerInterface() +{ +} + +controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::on_init() +{ + RCLCPP_DEBUG( + get_node()->get_logger(), "Initializing Motion Primitives From Trajectory Controller"); + + try + { + param_listener_ = + std::make_shared(get_node()); + } + catch (const std::exception & e) + { + fprintf(stderr, "Exception thrown during controller's init with message: %s \n", e.what()); + return controller_interface::CallbackReturn::ERROR; + } + + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::on_configure( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + RCLCPP_DEBUG( + get_node()->get_logger(), "Configuring Motion Primitives From Trajectory Controller"); + + params_ = param_listener_->get_params(); + + // Check if there are exactly 25 command interfaces + if (params_.command_interfaces.size() != 25) + { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Exactly 25 command interfaces must be provided!"); + return controller_interface::CallbackReturn::ERROR; + } + + // Check if there are exactly 2 state interfaces + if (params_.state_interfaces.size() != 2) + { // execution_status + ready_for_new_primitive + RCLCPP_ERROR(get_node()->get_logger(), "Error: Exactly two state interfaces must be provided!"); + return controller_interface::CallbackReturn::ERROR; + } + + action_server_ = rclcpp_action::create_server( + get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), + get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), + std::string(get_node()->get_name()) + "/motion_sequence", + std::bind( + &MotionPrimitivesFromTrajectoryController::goal_received_callback, this, + std::placeholders::_1, std::placeholders::_2), + std::bind( + &MotionPrimitivesFromTrajectoryController::goal_cancelled_callback, this, + std::placeholders::_1), + std::bind( + &MotionPrimitivesFromTrajectoryController::goal_accepted_callback, this, + std::placeholders::_1)); + + RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::InterfaceConfiguration +MotionPrimitivesFromTrajectoryController::command_interface_configuration() const +{ + controller_interface::InterfaceConfiguration command_interfaces_config; + command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + command_interfaces_config.names.reserve(params_.command_interfaces.size()); + + // Iterate over all command interfaces from the config yaml file + for (const auto & interface_name : params_.command_interfaces) + { + command_interfaces_config.names.push_back("motion_primitive/" + interface_name); + } + return command_interfaces_config; +} + +controller_interface::InterfaceConfiguration +MotionPrimitivesFromTrajectoryController::state_interface_configuration() const +{ + controller_interface::InterfaceConfiguration state_interfaces_config; + state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL; + + state_interfaces_config.names.reserve(params_.state_interfaces.size()); + + // Iterate over all state interfaces from the config yaml file + for (const auto & interface_name : params_.state_interfaces) + { + state_interfaces_config.names.push_back("motion_primitive/" + interface_name); + } + return state_interfaces_config; +} + +controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::on_activate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + reset_command_interfaces(); + RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::on_deactivate( + const rclcpp_lifecycle::State & /*previous_state*/) +{ + reset_command_interfaces(); + RCLCPP_DEBUG(get_node()->get_logger(), "Controller deactivated"); + return controller_interface::CallbackReturn::SUCCESS; +} + +controller_interface::return_type MotionPrimitivesFromTrajectoryController::update( + const rclcpp::Time & time, const rclcpp::Duration & /*period*/) +{ + if (cancel_requested_) + { + RCLCPP_INFO(get_node()->get_logger(), "Cancel requested, stopping execution."); + cancel_requested_ = false; + reset_command_interfaces(); + // send stop command immediately to the hw-interface + (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); + while (!moprim_queue_.empty()) + { // clear the queue + moprim_queue_.pop(); + } + robot_stop_requested_ = true; + } + + // read the status from the state interface + auto opt_value_execution = state_interfaces_[0].get_optional(); + if (!opt_value_execution.has_value()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "State interface 0 (execution_state) returned no value."); + return controller_interface::return_type::ERROR; + } + execution_status_ = + static_cast(static_cast(std::round(opt_value_execution.value()))); + switch (execution_status_) + { + case ExecutionState::IDLE: + print_error_once_ = true; + was_executing_ = false; + break; + case ExecutionState::EXECUTING: + if (!was_executing_) + { + was_executing_ = true; + } + print_error_once_ = true; + break; + + case ExecutionState::SUCCESS: + print_error_once_ = true; + + if (pending_action_goal_ && was_executing_) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + } + + break; + + case ExecutionState::STOPPED: + print_error_once_ = true; + was_executing_ = false; + + if (pending_action_goal_) + { + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::CANCELED; + result->error_string = "Motion primitives execution canceled"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + } + + if (robot_stop_requested_) + { + // If the robot was stopped by a stop command, reset the command interfaces + // to allow new motion primitives to be sent. + reset_command_interfaces(); + (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); + robot_stop_requested_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); + } + break; + + case ExecutionState::ERROR: + was_executing_ = false; + + if (pending_action_goal_) + { + auto result = std::make_shared(); + result->error_code = ExecuteMotion::Result::FAILED; + result->error_string = "Motion primitives execution failed"; + pending_action_goal_->succeed(result); + pending_action_goal_.reset(); + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution failed"); + } + + if (print_error_once_) + { + RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); + print_error_once_ = false; + } + break; + + default: + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Unknown execution status: %d", + static_cast(execution_status_)); + return controller_interface::return_type::ERROR; + } + + auto opt_value_ready = state_interfaces_[1].get_optional(); + if (!opt_value_ready.has_value()) + { + RCLCPP_ERROR( + get_node()->get_logger(), "State interface 1 (ready_for_new_primitive) returned no value."); + return controller_interface::return_type::ERROR; + } + ready_for_new_primitive_ = + static_cast(static_cast(std::round(opt_value_ready.value()))); + + if (!moprim_queue_.empty()) // check if new command is available + { + switch (ready_for_new_primitive_) + { + case ReadyForNewPrimitive::NOT_READY: + { + return controller_interface::return_type::OK; + } + case ReadyForNewPrimitive::READY: + { + if (!set_command_interfaces()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; + } + return controller_interface::return_type::OK; + } + default: + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Unknown state for ready_for_new_primitive: %d", + static_cast(ready_for_new_primitive_)); + return controller_interface::return_type::ERROR; + } + } + return controller_interface::return_type::OK; +} + +// Reset Command-Interfaces to nan +void MotionPrimitivesFromTrajectoryController::reset_command_interfaces() +{ + for (size_t i = 0; i < command_interfaces_.size(); ++i) + { + if (!command_interfaces_[i].set_value(std::numeric_limits::quiet_NaN())) + { + RCLCPP_ERROR(get_node()->get_logger(), "Failed to reset command interface %ld", i); + } + } +} + +// Set command interfaces from the message, gets called in the update function +bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() +{ + // Get the oldest message from the queue + std::shared_ptr current_moprim = moprim_queue_.front(); + moprim_queue_.pop(); + + // Check if the message is valid + if (!current_moprim) + { + RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); + return false; + } + + // Set the motion_type + (void)command_interfaces_[0].set_value(static_cast(current_moprim->type)); + + // Process joint positions if available + if (!current_moprim->joint_positions.empty()) + { + for (size_t i = 0; i < current_moprim->joint_positions.size(); ++i) + { + (void)command_interfaces_[i + 1].set_value(current_moprim->joint_positions[i]); // q1 to q6 + } + } + + // Process Cartesian poses if available + if (!current_moprim->poses.empty()) + { + const auto & goal_pose = current_moprim->poses[0].pose; // goal pose + (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x + (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y + (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z + (void)command_interfaces_[10].set_value(goal_pose.orientation.x); // pos_qx + (void)command_interfaces_[11].set_value(goal_pose.orientation.y); // pos_qy + (void)command_interfaces_[12].set_value(goal_pose.orientation.z); // pos_qz + (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw + + // Process via poses if available (only for circular motion) + if ( + current_moprim->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && + current_moprim->poses.size() == 2) + { + const auto & via_pose = current_moprim->poses[1].pose; // via pose + (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x + (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y + (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z + (void)command_interfaces_[17].set_value(via_pose.orientation.x); // pos_via_qx + (void)command_interfaces_[18].set_value(via_pose.orientation.y); // pos_via_qy + (void)command_interfaces_[19].set_value(via_pose.orientation.z); // pos_via_qz + (void)command_interfaces_[20].set_value(via_pose.orientation.w); // pos_via_qw + } + } + + (void)command_interfaces_[21].set_value(current_moprim->blend_radius); // blend_radius + + // Read additional arguments + for (const auto & arg : current_moprim->additional_arguments) + { + if (arg.argument_name == "velocity") + { + (void)command_interfaces_[22].set_value(arg.argument_value); + } + else if (arg.argument_name == "acceleration") + { + (void)command_interfaces_[23].set_value(arg.argument_value); + } + else if (arg.argument_name == "move_time") + { + (void)command_interfaces_[24].set_value(arg.argument_value); + } + else + { + RCLCPP_WARN( + get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); + } + } + return true; +} + +rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_received_callback( + const rclcpp_action::GoalUUID &, std::shared_ptr goal) +{ + RCLCPP_INFO(get_node()->get_logger(), "Received goal request"); + + const auto & primitives = goal->trajectory.motions; + + if (robot_stop_requested_) + { + RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + + if (primitives.empty()) + { + RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); + return rclcpp_action::GoalResponse::REJECT; + } + + for (size_t i = 0; i < primitives.size(); ++i) + { + const auto & primitive = primitives[i]; + + switch (static_cast(primitive.type)) + { + case MotionType::LINEAR_JOINT: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); + if (primitive.joint_positions.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: LINEAR_JOINT requires joint_positions.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + case MotionType::LINEAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_CARTESIAN (LIN)", i); + if (primitive.poses.empty()) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: LINEAR_CARTESIAN requires at least one pose.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + case MotionType::CIRCULAR_CARTESIAN: + RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: CIRCULAR_CARTESIAN (CIRC)", i); + if (primitive.poses.size() != 2) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Primitive %zu invalid: CIRCULAR_CARTESIAN requires exactly two poses.", i); + return rclcpp_action::GoalResponse::REJECT; + } + break; + + default: + RCLCPP_ERROR( + get_node()->get_logger(), "Primitive %zu invalid: unknown motion type %u.", i, + primitive.type); + return rclcpp_action::GoalResponse::REJECT; + } + } + + return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; +} + +rclcpp_action::CancelResponse MotionPrimitivesFromTrajectoryController::goal_cancelled_callback( + const std::shared_ptr>) +{ + cancel_requested_ = true; + return rclcpp_action::CancelResponse::ACCEPT; +} + +void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( + const std::shared_ptr> goal_handle) +{ + pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback + + const auto & primitives = goal_handle->get_goal()->trajectory.motions; + + auto add_motions = [this](const std::vector & motion_primitives) + { + for (const auto & primitive : motion_primitives) + { + moprim_queue_.push(std::make_shared(primitive)); + } + }; + + if (primitives.size() > 1) + { + std::shared_ptr start_marker = std::make_shared(); + start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); + moprim_queue_.push(start_marker); + + add_motions(primitives); + + std::shared_ptr end_marker = std::make_shared(); + end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); + moprim_queue_.push(end_marker); + } + else + { + add_motions(primitives); + } + + RCLCPP_INFO( + get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); +} + +} // namespace motion_primitives_from_trajectory_controller + +#include "pluginlib/class_list_macros.hpp" + +PLUGINLIB_EXPORT_CLASS( + motion_primitives_from_trajectory_controller::MotionPrimitivesFromTrajectoryController, + controller_interface::ControllerInterface) From b1f1537cbf4a7e0f1fa4b2decc49520cc1fe5467 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 2 Jul 2025 15:19:29 +0200 Subject: [PATCH 057/128] changed action to FollowJTrajAction, goal_received_callback() and goal_accepted_callback() getting called succesfully on click execute in RViz. Bunctionallity to aprox primitives not implemented yet. --- ..._primitives_from_trajectory_controller.hpp | 15 +- ..._primitives_from_trajectory_controller.cpp | 208 +++++++++--------- 2 files changed, 114 insertions(+), 109 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 67652f8a82..7cdec636c8 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -23,7 +23,9 @@ #include #include +#include "control_msgs/action/follow_joint_trajectory.hpp" #include "controller_interface/controller_interface.hpp" +#include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" @@ -31,7 +33,6 @@ #include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" -#include "rclcpp_action/rclcpp_action.hpp" namespace motion_primitives_from_trajectory_controller { @@ -93,15 +94,15 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; std::queue> moprim_queue_; - using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; - rclcpp_action::Server::SharedPtr action_server_; + using FollowJTrajAction = control_msgs::action::FollowJointTrajectory; + rclcpp_action::Server::SharedPtr action_server_; rclcpp_action::GoalResponse goal_received_callback( - const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); + const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); rclcpp_action::CancelResponse goal_cancelled_callback( - const std::shared_ptr> goal_handle); + const std::shared_ptr> goal_handle); void goal_accepted_callback( - const std::shared_ptr> goal_handle); - std::shared_ptr> pending_action_goal_; + const std::shared_ptr> goal_handle); + std::shared_ptr> pending_action_goal_; void reset_command_interfaces(); bool set_command_interfaces(); diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 8c25655f87..253c574462 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -70,10 +70,10 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o return controller_interface::CallbackReturn::ERROR; } - action_server_ = rclcpp_action::create_server( + action_server_ = rclcpp_action::create_server( get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), - std::string(get_node()->get_name()) + "/motion_sequence", + std::string(get_node()->get_name()) + "/follow_joint_trajectory", std::bind( &MotionPrimitivesFromTrajectoryController::goal_received_callback, this, std::placeholders::_1, std::placeholders::_2), @@ -183,8 +183,8 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda if (pending_action_goal_ && was_executing_) { was_executing_ = false; - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::SUCCESSFUL; + auto result = std::make_shared(); + result->error_code = FollowJTrajAction::Result::SUCCESSFUL; result->error_string = "Motion primitives executed successfully"; pending_action_goal_->succeed(result); pending_action_goal_.reset(); @@ -199,8 +199,9 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda if (pending_action_goal_) { - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::CANCELED; + auto result = std::make_shared(); + // result->error_code = FollowJTrajAction::Result::CANCELED; + result->error_code = 69; result->error_string = "Motion primitives execution canceled"; pending_action_goal_->succeed(result); pending_action_goal_.reset(); @@ -223,8 +224,9 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda if (pending_action_goal_) { - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::FAILED; + auto result = std::make_shared(); + // result->error_code = FollowJTrajAction::Result::FAILED; + result->error_code = 404; result->error_string = "Motion primitives execution failed"; pending_action_goal_->succeed(result); pending_action_goal_.reset(); @@ -375,115 +377,117 @@ bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() } rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_received_callback( - const rclcpp_action::GoalUUID &, std::shared_ptr goal) + const rclcpp_action::GoalUUID &, std::shared_ptr goal) { RCLCPP_INFO(get_node()->get_logger(), "Received goal request"); - const auto & primitives = goal->trajectory.motions; - - if (robot_stop_requested_) - { - RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); - return rclcpp_action::GoalResponse::REJECT; - } - - if (primitives.empty()) - { - RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); - return rclcpp_action::GoalResponse::REJECT; - } - - for (size_t i = 0; i < primitives.size(); ++i) - { - const auto & primitive = primitives[i]; - - switch (static_cast(primitive.type)) - { - case MotionType::LINEAR_JOINT: - RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); - if (primitive.joint_positions.empty()) - { - RCLCPP_ERROR( - get_node()->get_logger(), - "Primitive %zu invalid: LINEAR_JOINT requires joint_positions.", i); - return rclcpp_action::GoalResponse::REJECT; - } - break; - - case MotionType::LINEAR_CARTESIAN: - RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_CARTESIAN (LIN)", i); - if (primitive.poses.empty()) - { - RCLCPP_ERROR( - get_node()->get_logger(), - "Primitive %zu invalid: LINEAR_CARTESIAN requires at least one pose.", i); - return rclcpp_action::GoalResponse::REJECT; - } - break; - - case MotionType::CIRCULAR_CARTESIAN: - RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: CIRCULAR_CARTESIAN (CIRC)", i); - if (primitive.poses.size() != 2) - { - RCLCPP_ERROR( - get_node()->get_logger(), - "Primitive %zu invalid: CIRCULAR_CARTESIAN requires exactly two poses.", i); - return rclcpp_action::GoalResponse::REJECT; - } - break; - - default: - RCLCPP_ERROR( - get_node()->get_logger(), "Primitive %zu invalid: unknown motion type %u.", i, - primitive.type); - return rclcpp_action::GoalResponse::REJECT; - } - } + // const auto & primitives = goal->trajectory.motions; + + // if (robot_stop_requested_) + // { + // RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new + // command."); return rclcpp_action::GoalResponse::REJECT; + // } + + // if (primitives.empty()) + // { + // RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); + // return rclcpp_action::GoalResponse::REJECT; + // } + + // for (size_t i = 0; i < primitives.size(); ++i) + // { + // const auto & primitive = primitives[i]; + + // switch (static_cast(primitive.type)) + // { + // case MotionType::LINEAR_JOINT: + // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); + // if (primitive.joint_positions.empty()) + // { + // RCLCPP_ERROR( + // get_node()->get_logger(), + // "Primitive %zu invalid: LINEAR_JOINT requires joint_positions.", i); + // return rclcpp_action::GoalResponse::REJECT; + // } + // break; + + // case MotionType::LINEAR_CARTESIAN: + // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_CARTESIAN (LIN)", i); + // if (primitive.poses.empty()) + // { + // RCLCPP_ERROR( + // get_node()->get_logger(), + // "Primitive %zu invalid: LINEAR_CARTESIAN requires at least one pose.", i); + // return rclcpp_action::GoalResponse::REJECT; + // } + // break; + + // case MotionType::CIRCULAR_CARTESIAN: + // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: CIRCULAR_CARTESIAN (CIRC)", i); + // if (primitive.poses.size() != 2) + // { + // RCLCPP_ERROR( + // get_node()->get_logger(), + // "Primitive %zu invalid: CIRCULAR_CARTESIAN requires exactly two poses.", i); + // return rclcpp_action::GoalResponse::REJECT; + // } + // break; + + // default: + // RCLCPP_ERROR( + // get_node()->get_logger(), "Primitive %zu invalid: unknown motion type %u.", i, + // primitive.type); + // return rclcpp_action::GoalResponse::REJECT; + // } + // } return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } rclcpp_action::CancelResponse MotionPrimitivesFromTrajectoryController::goal_cancelled_callback( - const std::shared_ptr>) + const std::shared_ptr>) { cancel_requested_ = true; return rclcpp_action::CancelResponse::ACCEPT; } void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( - const std::shared_ptr> goal_handle) + const std::shared_ptr> goal_handle) { - pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - - const auto & primitives = goal_handle->get_goal()->trajectory.motions; - - auto add_motions = [this](const std::vector & motion_primitives) - { - for (const auto & primitive : motion_primitives) - { - moprim_queue_.push(std::make_shared(primitive)); - } - }; - - if (primitives.size() > 1) - { - std::shared_ptr start_marker = std::make_shared(); - start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); - moprim_queue_.push(start_marker); - - add_motions(primitives); - - std::shared_ptr end_marker = std::make_shared(); - end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); - moprim_queue_.push(end_marker); - } - else - { - add_motions(primitives); - } - - RCLCPP_INFO( - get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); + RCLCPP_INFO(get_node()->get_logger(), "Accepted goal"); + + // pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback + + // const auto & primitives = goal_handle->get_goal()->trajectory.motions; + + // auto add_motions = [this](const std::vector & motion_primitives) + // { + // for (const auto & primitive : motion_primitives) + // { + // moprim_queue_.push(std::make_shared(primitive)); + // } + // }; + + // if (primitives.size() > 1) + // { + // std::shared_ptr start_marker = std::make_shared(); + // start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); + // moprim_queue_.push(start_marker); + + // add_motions(primitives); + + // std::shared_ptr end_marker = std::make_shared(); + // end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); + // moprim_queue_.push(end_marker); + // } + // else + // { + // add_motions(primitives); + // } + + // RCLCPP_INFO( + // get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); } } // namespace motion_primitives_from_trajectory_controller From cf104d4e01d2019081fa87cc1251c77b55b2ffb3 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 09:35:52 +0200 Subject: [PATCH 058/128] added std::atomic moprim_queue_write_enabled_ --- .../motion_primitives_forward_controller.hpp | 2 ++ .../motion_primitives_forward_controller.cpp | 31 ++++++++++++++++--- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 3a6299c0a0..d6363cacc0 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -114,6 +114,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; + + std::atomic moprim_queue_write_enabled_ = false; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index bf98755aad..a3ea102f39 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -120,6 +120,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activ const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); + moprim_queue_write_enabled_ = true; RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -210,8 +211,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); robot_stop_requested_ = false; + moprim_queue_write_enabled_ = true; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } + break; case ExecutionState::ERROR: @@ -251,7 +254,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( ready_for_new_primitive_ = static_cast(static_cast(std::round(opt_value_ready.value()))); - if (!moprim_queue_.empty()) // check if new command is available + if (!moprim_queue_write_enabled_ && !cancel_requested_) { switch (ready_for_new_primitive_) { @@ -261,12 +264,21 @@ controller_interface::return_type MotionPrimitivesForwardController::update( } case ReadyForNewPrimitive::READY: { - if (!set_command_interfaces()) + if (moprim_queue_.empty()) // check if new command is available { - RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); - return controller_interface::return_type::ERROR; + // all primitives read, queue ready to get filled with new primitives + moprim_queue_write_enabled_ = true; + return controller_interface::return_type::OK; + } + else + { + if (!set_command_interfaces()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; + } + return controller_interface::return_type::OK; } - return controller_interface::return_type::OK; } default: RCLCPP_ERROR( @@ -383,6 +395,13 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal return rclcpp_action::GoalResponse::REJECT; } + if (!moprim_queue_write_enabled_) + { + RCLCPP_WARN( + get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + if (primitives.empty()) { RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); @@ -443,6 +462,7 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ const std::shared_ptr>) { cancel_requested_ = true; + moprim_queue_write_enabled_ = false; return rclcpp_action::CancelResponse::ACCEPT; } @@ -477,6 +497,7 @@ void MotionPrimitivesForwardController::goal_accepted_callback( { add_motions(primitives); } + moprim_queue_write_enabled_ = false; RCLCPP_INFO( get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); From 632ca1a8bed64656e0a4171e61b50490c8ee79fd Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 10:15:04 +0200 Subject: [PATCH 059/128] added std::atomic moprim_queue_write_enabled_ --- .../motion_primitives_forward_controller.hpp | 2 ++ .../motion_primitives_forward_controller.cpp | 31 ++++++++++++++++--- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 3a6299c0a0..d6363cacc0 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -114,6 +114,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; + + std::atomic moprim_queue_write_enabled_ = false; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index bf98755aad..a3ea102f39 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -120,6 +120,7 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activ const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); + moprim_queue_write_enabled_ = true; RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -210,8 +211,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); robot_stop_requested_ = false; + moprim_queue_write_enabled_ = true; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } + break; case ExecutionState::ERROR: @@ -251,7 +254,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( ready_for_new_primitive_ = static_cast(static_cast(std::round(opt_value_ready.value()))); - if (!moprim_queue_.empty()) // check if new command is available + if (!moprim_queue_write_enabled_ && !cancel_requested_) { switch (ready_for_new_primitive_) { @@ -261,12 +264,21 @@ controller_interface::return_type MotionPrimitivesForwardController::update( } case ReadyForNewPrimitive::READY: { - if (!set_command_interfaces()) + if (moprim_queue_.empty()) // check if new command is available { - RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); - return controller_interface::return_type::ERROR; + // all primitives read, queue ready to get filled with new primitives + moprim_queue_write_enabled_ = true; + return controller_interface::return_type::OK; + } + else + { + if (!set_command_interfaces()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; + } + return controller_interface::return_type::OK; } - return controller_interface::return_type::OK; } default: RCLCPP_ERROR( @@ -383,6 +395,13 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal return rclcpp_action::GoalResponse::REJECT; } + if (!moprim_queue_write_enabled_) + { + RCLCPP_WARN( + get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + if (primitives.empty()) { RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); @@ -443,6 +462,7 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ const std::shared_ptr>) { cancel_requested_ = true; + moprim_queue_write_enabled_ = false; return rclcpp_action::CancelResponse::ACCEPT; } @@ -477,6 +497,7 @@ void MotionPrimitivesForwardController::goal_accepted_callback( { add_motions(primitives); } + moprim_queue_write_enabled_ = false; RCLCPP_INFO( get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); From cb328212b7c06e5f523ddca9b14b35bbd2c6e4cc Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 11:07:11 +0200 Subject: [PATCH 060/128] added std::atomic moprim_queue_write_enabled_ to moprim_from_traj_controller --- ..._primitives_from_trajectory_controller.hpp | 2 ++ ..._primitives_from_trajectory_controller.cpp | 35 +++++++++++++++---- 2 files changed, 30 insertions(+), 7 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 7cdec636c8..13c70becb2 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -115,6 +115,8 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; + + std::atomic moprim_queue_write_enabled_ = false; }; } // namespace motion_primitives_from_trajectory_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 253c574462..d75ccace00 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -124,6 +124,7 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); + moprim_queue_write_enabled_ = true; RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -215,6 +216,7 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda reset_command_interfaces(); (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); robot_stop_requested_ = false; + moprim_queue_write_enabled_ = true; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } break; @@ -257,7 +259,7 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda ready_for_new_primitive_ = static_cast(static_cast(std::round(opt_value_ready.value()))); - if (!moprim_queue_.empty()) // check if new command is available + if (!moprim_queue_write_enabled_ && !cancel_requested_) { switch (ready_for_new_primitive_) { @@ -267,12 +269,21 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda } case ReadyForNewPrimitive::READY: { - if (!set_command_interfaces()) + if (moprim_queue_.empty()) // check if new command is available { - RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); - return controller_interface::return_type::ERROR; + // all primitives read, queue ready to get filled with new primitives + moprim_queue_write_enabled_ = true; + return controller_interface::return_type::OK; + } + else + { + if (!set_command_interfaces()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Error: set_command_interfaces() failed"); + return controller_interface::return_type::ERROR; + } + return controller_interface::return_type::OK; } - return controller_interface::return_type::OK; } default: RCLCPP_ERROR( @@ -385,8 +396,16 @@ rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_recei // if (robot_stop_requested_) // { - // RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new - // command."); return rclcpp_action::GoalResponse::REJECT; + // RCLCPP_WARN(get_node()->get_logger(), + // "Robot requested to stop. Discarding the new command."); + // return rclcpp_action::GoalResponse::REJECT; + // } + + // if (!moprim_queue_write_enabled_) + // { + // RCLCPP_WARN( + // get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); + // return rclcpp_action::GoalResponse::REJECT; // } // if (primitives.empty()) @@ -449,6 +468,7 @@ rclcpp_action::CancelResponse MotionPrimitivesFromTrajectoryController::goal_can const std::shared_ptr>) { cancel_requested_ = true; + moprim_queue_write_enabled_ = false; return rclcpp_action::CancelResponse::ACCEPT; } @@ -485,6 +505,7 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( // { // add_motions(primitives); // } + // moprim_queue_write_enabled_ = false; // RCLCPP_INFO( // get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); From 02ac151d7278bf33c52535caf2d434c1226ef1a0 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 11:48:12 +0200 Subject: [PATCH 061/128] added files from https://github.com/mathias31415/motion_primitives_from_planned_trajectory (+ pre-commit stuff) --- .../approx_primitives_with_rdp.hpp | 56 ++++ .../fk_client.hpp | 42 +++ .../rdp.hpp | 55 ++++ .../src/approx_primitives_with_rdp.cpp | 253 ++++++++++++++++++ .../src/fk_client.cpp | 67 +++++ .../src/rdp.cpp | 124 +++++++++ 6 files changed, 597 insertions(+) create mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp create mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp create mode 100644 motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp create mode 100644 motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp create mode 100644 motion_primitives_forward_controller/src/fk_client.cpp create mode 100644 motion_primitives_forward_controller/src/rdp.cpp diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp new file mode 100644 index 0000000000..d738cdb1f0 --- /dev/null +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -0,0 +1,56 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ + +#include +#include +#include "geometry_msgs/msg/pose.hpp" +#include "industrial_robot_motion_interfaces/msg/motion_argument.hpp" +#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "industrial_robot_motion_interfaces/msg/motion_sequence.hpp" +#include "motion_primitives_forward_controller/rdp.hpp" + +using MotionSequence = industrial_robot_motion_interfaces::msg::MotionSequence; + +namespace approx_primitives_with_rdp +{ + +struct PlannedTrajectoryPoint +{ + double time_from_start; + std::vector joint_positions; + geometry_msgs::msg::Pose pose; +}; + +// Approximate with LIN Primitives in Cartesian Space +MotionSequence approxLinPrimitivesWithRDP( + const std::vector & trajectory, double epsilon, + bool use_time_not_vel_and_acc = false); + +// Approximate with PTP Primitives in Joint Space +MotionSequence approxPtpPrimitivesWithRDP( + const std::vector & trajectory, double epsilon, + bool use_time_not_vel_and_acc = false); + +double calculateBlendRadius( + const rdp::Point & previous_point, const rdp::Point & current_point, + const rdp::Point & next_point); + +} // namespace approx_primitives_with_rdp + +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp new file mode 100644 index 0000000000..e7b2d5c673 --- /dev/null +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp @@ -0,0 +1,42 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ + +#include +#include +#include + +#include +#include +#include + +class FKClient +{ +public: + explicit FKClient(const rclcpp::Node::SharedPtr & node); + + std::optional computeFK( + const std::vector & joint_names, const std::vector & joint_positions, + const std::string & from_frame = "base", const std::string & to_link = "tool0"); + +private: + rclcpp::Node::SharedPtr node_; + rclcpp::Client::SharedPtr client_; +}; + +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp new file mode 100644 index 0000000000..f5190e246d --- /dev/null +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp @@ -0,0 +1,55 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__RDP_HPP_ +#define MOTION_PRIMITIVES_FORWARD_CONTROLLER__RDP_HPP_ + +#include +#include + +namespace rdp +{ + +using Point = std::vector; +using PointList = std::vector; + +/** + * Computes the shortest distance from a point to a line in N-dimensional space. + * + * @param point The point to measure from. + * @param start The start of the line segment. + * @param end The end of the line segment. + * @return Distance from the point to the line segment. + */ +double pointLineDistanceND(const Point & point, const Point & start, const Point & end); + +/** + * Recursive implementation of the Ramer-Douglas-Peucker algorithm + * for simplifying a series of N-dimensional points. + * + * @param points The list of input points. + * @param epsilon Tolerance value: points closer than this distance to the line will be removed. + * @param offset Offset for original indices (used in recursion). + * @return A pair consisting of: + * - The simplified list of points. + * - The list of indices (from the original input) corresponding to the retained points. + */ +std::pair> rdpRecursive( + const PointList & points, double epsilon, std::size_t offset = 0); + +} // namespace rdp + +#endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__RDP_HPP_ diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp new file mode 100644 index 0000000000..72c87ae9b9 --- /dev/null +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -0,0 +1,253 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#include "motion_primitives_forward_controller/approx_primitives_with_rdp.hpp" +#include +#include +#include + +using geometry_msgs::msg::Pose; +using geometry_msgs::msg::PoseStamped; +using industrial_robot_motion_interfaces::msg::MotionArgument; +using industrial_robot_motion_interfaces::msg::MotionPrimitive; +using industrial_robot_motion_interfaces::msg::MotionSequence; + +namespace approx_primitives_with_rdp +{ + +MotionSequence approxLinPrimitivesWithRDP( + const std::vector & trajectory, + double epsilon, bool use_time_not_vel_and_acc) +{ + MotionSequence motion_sequence; + std::vector motion_primitives; + + if (trajectory.empty()) + { + std::cerr << "[approxLinPrimitivesWithRDP] Warning: trajectory is empty." << std::endl; + return motion_sequence; + } + + rdp::PointList points; + for (const auto & point : trajectory) + { + points.push_back({point.pose.position.x, point.pose.position.y, point.pose.position.z}); + } + + auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon); + + for (size_t i = 1; i < reduced_points.size(); ++i) + { + MotionPrimitive primitive; + primitive.type = MotionPrimitive::LINEAR_CARTESIAN; + + if (i == reduced_points.size() - 1) + { + primitive.blend_radius = 0.0; + } + else + { + primitive.blend_radius = + calculateBlendRadius(reduced_points[i - 1], reduced_points[i], reduced_points[i + 1]); + } + double velocity = -1.0; + double acceleration = -1.0; + double move_time = -1.0; + if (use_time_not_vel_and_acc) + { + double prev_time = trajectory[reduced_indices[i - 1]].time_from_start; + double curr_time = trajectory[reduced_indices[i]].time_from_start; + move_time = curr_time - prev_time; + MotionArgument arg_time; + arg_time.argument_name = "move_time"; + arg_time.argument_value = move_time; + primitive.additional_arguments.push_back(arg_time); + } + else + { + // TODO(mathias31415): Calculate vel and acc based on time_from_start + velocity = 1.0; + acceleration = 1.0; + + MotionArgument arg_vel; + arg_vel.argument_name = "velocity"; + arg_vel.argument_value = velocity; + primitive.additional_arguments.push_back(arg_vel); + + MotionArgument arg_acc; + arg_acc.argument_name = "acceleration"; + arg_acc.argument_value = acceleration; + primitive.additional_arguments.push_back(arg_acc); + } + + PoseStamped pose_stamped; + pose_stamped.pose.position.x = reduced_points[i][0]; + pose_stamped.pose.position.y = reduced_points[i][1]; + pose_stamped.pose.position.z = reduced_points[i][2]; + // TODO(mathias31415): Also use RDP for orientation + pose_stamped.pose.orientation = trajectory[reduced_indices[i]].pose.orientation; + + primitive.poses.push_back(pose_stamped); + motion_primitives.push_back(primitive); + + std::cout << "Added LIN Primitive [" << i << "]: (x,y,z,qx,qy,qz,qw) = (" + << pose_stamped.pose.position.x << ", " << pose_stamped.pose.position.y << ", " + << pose_stamped.pose.position.z << ", " << pose_stamped.pose.orientation.x << ", " + << pose_stamped.pose.orientation.y << ", " << pose_stamped.pose.orientation.z << ", " + << pose_stamped.pose.orientation.w << "), " + << "blend_radius = " << primitive.blend_radius << ", " + << "move_time = " << move_time << ", " + << "velocity = " << velocity << ", " + << "acceleration = " << acceleration << std::endl; + } + + motion_sequence.motions = motion_primitives; + std::cout << "Reduced " << points.size() << " points to " << (reduced_points.size() - 1) + << " LIN primitives with epsilon=" << epsilon << std::endl; + + return motion_sequence; +} + +MotionSequence approxPtpPrimitivesWithRDP( + const std::vector & trajectory, + double epsilon, bool use_time_not_vel_and_acc) +{ + MotionSequence motion_sequence; + std::vector motion_primitives; + + if (trajectory.empty()) + { + std::cerr << "[approxPtpPrimitivesWithRDP] Warning: trajectory is empty." << std::endl; + return motion_sequence; + } + + rdp::PointList points; + for (const auto & pt : trajectory) + { + points.push_back(pt.joint_positions); + } + + auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon); + + for (size_t i = 1; i < reduced_points.size(); ++i) + { + MotionPrimitive primitive; + primitive.type = MotionPrimitive::LINEAR_JOINT; + + if (i == reduced_points.size() - 1) + { + primitive.blend_radius = 0.0; + } + else + { + size_t prev_index = reduced_indices[i - 1]; + size_t curr_index = reduced_indices[i]; + size_t next_index = reduced_indices[i + 1]; + + rdp::Point prev_xyz = { + trajectory[prev_index].pose.position.x, trajectory[prev_index].pose.position.y, + trajectory[prev_index].pose.position.z}; + rdp::Point curr_xyz = { + trajectory[curr_index].pose.position.x, trajectory[curr_index].pose.position.y, + trajectory[curr_index].pose.position.z}; + rdp::Point next_xyz = { + trajectory[next_index].pose.position.x, trajectory[next_index].pose.position.y, + trajectory[next_index].pose.position.z}; + primitive.blend_radius = calculateBlendRadius(prev_xyz, curr_xyz, next_xyz); + } + + double velocity = -1.0; + double acceleration = -1.0; + double move_time = -1.0; + if (use_time_not_vel_and_acc) + { + double prev_time = trajectory[reduced_indices[i - 1]].time_from_start; + double curr_time = trajectory[reduced_indices[i]].time_from_start; + move_time = curr_time - prev_time; + MotionArgument arg_time; + arg_time.argument_name = "move_time"; + arg_time.argument_value = move_time; + primitive.additional_arguments.push_back(arg_time); + } + else + { + // TODO(mathias31415): Calculate vel and acc based on time_from_start + velocity = 1.0; + acceleration = 1.0; + + MotionArgument arg_vel; + arg_vel.argument_name = "velocity"; + arg_vel.argument_value = velocity; + primitive.additional_arguments.push_back(arg_vel); + + MotionArgument arg_acc; + arg_acc.argument_name = "acceleration"; + arg_acc.argument_value = acceleration; + primitive.additional_arguments.push_back(arg_acc); + } + + primitive.joint_positions = reduced_points[i]; + motion_primitives.push_back(primitive); + + std::cout << "Added PTP Primitive [" << i << "]: joints = ("; + for (size_t j = 0; j < reduced_points[i].size(); ++j) + { + std::cout << reduced_points[i][j]; + if (j + 1 < reduced_points[i].size()) std::cout << ", "; + } + std::cout << "), blend_radius = " << primitive.blend_radius << ", " + << "move_time = " << move_time << ", " + << "velocity = " << velocity << ", " + << "acceleration = " << acceleration << std::endl; + } + + motion_sequence.motions = motion_primitives; + std::cout << "Reduced " << points.size() << " joint points to " << (reduced_points.size() - 1) + << " PTP primitives with epsilon=" << epsilon << std::endl; + + return motion_sequence; +} + +double calculateBlendRadius( + const rdp::Point & previous_point, const rdp::Point & current_point, + const rdp::Point & next_point) +{ + double dist_prev = std::sqrt( + std::pow(current_point[0] - previous_point[0], 2) + + std::pow(current_point[1] - previous_point[1], 2) + + std::pow(current_point[2] - previous_point[2], 2)); + + double dist_next = std::sqrt( + std::pow(next_point[0] - current_point[0], 2) + std::pow(next_point[1] - current_point[1], 2) + + std::pow(next_point[2] - current_point[2], 2)); + + double min_dist = std::min(dist_prev, dist_next); + double blend = 0.1 * min_dist; + + // Clamp blend radius to [0, 0.1] with minimum threshold 0.001 + if (blend < 0.001) + { + blend = 0.0; + } + else if (blend > 0.1) + { + blend = 0.1; + } + + return blend; +} + +} // namespace approx_primitives_with_rdp diff --git a/motion_primitives_forward_controller/src/fk_client.cpp b/motion_primitives_forward_controller/src/fk_client.cpp new file mode 100644 index 0000000000..7694fb53a3 --- /dev/null +++ b/motion_primitives_forward_controller/src/fk_client.cpp @@ -0,0 +1,67 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#include "motion_primitives_forward_controller/fk_client.hpp" +#include + +using namespace std::chrono_literals; + +FKClient::FKClient(const rclcpp::Node::SharedPtr & node) : node_(node) +{ + client_ = node_->create_client("/compute_fk"); + + while (!client_->wait_for_service(1s)) + { + RCLCPP_INFO(node_->get_logger(), "Waiting for /compute_fk service..."); + if (!rclcpp::ok()) + { + RCLCPP_ERROR(node_->get_logger(), "Interrupted while waiting for the service."); + return; + } + } +} + +std::optional FKClient::computeFK( + const std::vector & joint_names, const std::vector & joint_positions, + const std::string & from_frame, const std::string & to_link) +{ + auto request = std::make_shared(); + request->header.frame_id = from_frame; + request->fk_link_names.push_back(to_link); + request->robot_state.joint_state.name = joint_names; + request->robot_state.joint_state.position = joint_positions; + + auto future = client_->async_send_request(request); + + if (rclcpp::spin_until_future_complete(node_, future, 3s) == rclcpp::FutureReturnCode::SUCCESS) + { + auto result = future.get(); + if (result->error_code.val == result->error_code.SUCCESS) + { + return result->pose_stamped[0].pose; + } + else + { + RCLCPP_WARN(node_->get_logger(), "FK error: code=%d", result->error_code.val); + } + } + else + { + RCLCPP_ERROR(node_->get_logger(), "FK call timed out"); + } + + return std::nullopt; +} diff --git a/motion_primitives_forward_controller/src/rdp.cpp b/motion_primitives_forward_controller/src/rdp.cpp new file mode 100644 index 0000000000..4ef0dc85a6 --- /dev/null +++ b/motion_primitives_forward_controller/src/rdp.cpp @@ -0,0 +1,124 @@ +// Copyright (c) 2025, b»robotized +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// Authors: Mathias Fuhrer + +#include "motion_primitives_forward_controller/rdp.hpp" +#include +#include + +namespace rdp +{ + +// Computes the dot product of two vectors +double dot(const Point & a, const Point & b) +{ + double result = 0.0; + for (std::size_t i = 0; i < a.size(); ++i) result += a[i] * b[i]; + return result; +} + +// Computes the Euclidean norm (length) of a vector +double norm(const Point & v) { return std::sqrt(dot(v, v)); } + +// Subtracts two vectors +Point operator-(const Point & a, const Point & b) +{ + Point result(a.size()); + for (std::size_t i = 0; i < a.size(); ++i) result[i] = a[i] - b[i]; + return result; +} + +// Adds two vectors +Point operator+(const Point & a, const Point & b) +{ + Point result(a.size()); + for (std::size_t i = 0; i < a.size(); ++i) result[i] = a[i] + b[i]; + return result; +} + +// Multiplies a vector by a scalar +Point operator*(double scalar, const Point & v) +{ + Point result(v.size()); + for (std::size_t i = 0; i < v.size(); ++i) result[i] = scalar * v[i]; + return result; +} + +// Computes the perpendicular distance from a point to a line in N-dimensional space +double pointLineDistanceND(const Point & point, const Point & start, const Point & end) +{ + Point lineVec = end - start; + Point pointVec = point - start; + double len = norm(lineVec); + + if (len == 0.0) return norm(point - start); + + double projection = dot(pointVec, lineVec) / len; + Point closest = start + (projection / len) * lineVec; + return norm(point - closest); +} + +// Recursive implementation of the Ramer-Douglas-Peucker algorithm +std::pair> rdpRecursive( + const PointList & points, double epsilon, std::size_t offset) +{ + if (points.size() < 2) + { + std::vector indices; + for (std::size_t i = 0; i < points.size(); ++i) + { + indices.push_back(offset + i); + } + return {points, indices}; + } + + double dmax = 0.0; + std::size_t index = 0; + + // Find the point with the maximum distance from the line segment + for (std::size_t i = 1; i < points.size() - 1; ++i) + { + double d = pointLineDistanceND(points[i], points.front(), points.back()); + if (d > dmax) + { + index = i; + dmax = d; + } + } + + // If the max distance is greater than epsilon, recursively simplify + if (dmax > epsilon) + { + auto rec1 = + rdpRecursive(PointList(points.begin(), points.begin() + index + 1), epsilon, offset); + auto rec2 = + rdpRecursive(PointList(points.begin() + index, points.end()), epsilon, offset + index); + + // Remove duplicate in res1 + rec1.first.pop_back(); + rec1.second.pop_back(); + + // Merge + rec1.first.insert(rec1.first.end(), rec2.first.begin(), rec2.first.end()); + rec1.second.insert(rec1.second.end(), rec2.second.begin(), rec2.second.end()); + return rec1; + } + else + { + return {{points.front(), points.back()}, {offset, offset + points.size() - 1}}; + } +} + +} // namespace rdp From 9b8e261eba80a7940cb96e89b8a414fdf3b6f375 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 13:01:12 +0200 Subject: [PATCH 062/128] working with hardcoded primitives in goal_accepted_callback() --- ..._primitives_from_trajectory_controller.cpp | 190 ++++++++---------- 1 file changed, 86 insertions(+), 104 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index d75ccace00..289575a8bc 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -390,77 +390,30 @@ bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_received_callback( const rclcpp_action::GoalUUID &, std::shared_ptr goal) { - RCLCPP_INFO(get_node()->get_logger(), "Received goal request"); - - // const auto & primitives = goal->trajectory.motions; - - // if (robot_stop_requested_) - // { - // RCLCPP_WARN(get_node()->get_logger(), - // "Robot requested to stop. Discarding the new command."); - // return rclcpp_action::GoalResponse::REJECT; - // } - - // if (!moprim_queue_write_enabled_) - // { - // RCLCPP_WARN( - // get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); - // return rclcpp_action::GoalResponse::REJECT; - // } - - // if (primitives.empty()) - // { - // RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); - // return rclcpp_action::GoalResponse::REJECT; - // } - - // for (size_t i = 0; i < primitives.size(); ++i) - // { - // const auto & primitive = primitives[i]; - - // switch (static_cast(primitive.type)) - // { - // case MotionType::LINEAR_JOINT: - // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); - // if (primitive.joint_positions.empty()) - // { - // RCLCPP_ERROR( - // get_node()->get_logger(), - // "Primitive %zu invalid: LINEAR_JOINT requires joint_positions.", i); - // return rclcpp_action::GoalResponse::REJECT; - // } - // break; - - // case MotionType::LINEAR_CARTESIAN: - // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_CARTESIAN (LIN)", i); - // if (primitive.poses.empty()) - // { - // RCLCPP_ERROR( - // get_node()->get_logger(), - // "Primitive %zu invalid: LINEAR_CARTESIAN requires at least one pose.", i); - // return rclcpp_action::GoalResponse::REJECT; - // } - // break; - - // case MotionType::CIRCULAR_CARTESIAN: - // RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: CIRCULAR_CARTESIAN (CIRC)", i); - // if (primitive.poses.size() != 2) - // { - // RCLCPP_ERROR( - // get_node()->get_logger(), - // "Primitive %zu invalid: CIRCULAR_CARTESIAN requires exactly two poses.", i); - // return rclcpp_action::GoalResponse::REJECT; - // } - // break; - - // default: - // RCLCPP_ERROR( - // get_node()->get_logger(), "Primitive %zu invalid: unknown motion type %u.", i, - // primitive.type); - // return rclcpp_action::GoalResponse::REJECT; - // } - // } + RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); + if (robot_stop_requested_) + { + RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + + if (!moprim_queue_write_enabled_) + { + RCLCPP_WARN( + get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); + return rclcpp_action::GoalResponse::REJECT; + } + + if (goal->trajectory.points.empty()) + { + RCLCPP_ERROR(get_node()->get_logger(), "Empty trajectory received."); + return rclcpp_action::GoalResponse::REJECT; + } + + // TODO(mathias31415): Check if first trajectory point matches the current robot state + + RCLCPP_INFO(get_node()->get_logger(), "Accepted new action goal"); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } @@ -475,40 +428,69 @@ rclcpp_action::CancelResponse MotionPrimitivesFromTrajectoryController::goal_can void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( const std::shared_ptr> goal_handle) { - RCLCPP_INFO(get_node()->get_logger(), "Accepted goal"); - - // pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - - // const auto & primitives = goal_handle->get_goal()->trajectory.motions; - - // auto add_motions = [this](const std::vector & motion_primitives) - // { - // for (const auto & primitive : motion_primitives) - // { - // moprim_queue_.push(std::make_shared(primitive)); - // } - // }; - - // if (primitives.size() > 1) - // { - // std::shared_ptr start_marker = std::make_shared(); - // start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); - // moprim_queue_.push(start_marker); - - // add_motions(primitives); - - // std::shared_ptr end_marker = std::make_shared(); - // end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); - // moprim_queue_.push(end_marker); - // } - // else - // { - // add_motions(primitives); - // } - // moprim_queue_write_enabled_ = false; - - // RCLCPP_INFO( - // get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); + RCLCPP_INFO(get_node()->get_logger(), "Processing accepted goal ..."); + + pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback + + const auto & planned_trajectory = goal_handle->get_goal()->trajectory.points; + RCLCPP_INFO( + get_node()->get_logger(), "Received trajectory with %zu points.", planned_trajectory.size()); + + // TODO(mathias31415): Process the trajectory points and convert them to motion primitives + + // dummy primitives + MotionPrimitive moprim1; + moprim1.type = MotionPrimitive::LINEAR_JOINT; + moprim1.blend_radius = 0.0; + moprim1.joint_positions = {1.57, -1.57, 1.57, -1.57, -1.57, -1.57}; + industrial_robot_motion_interfaces::msg::MotionArgument arg_time1; + arg_time1.argument_name = "move_time"; + arg_time1.argument_value = 2.0; + moprim1.additional_arguments.push_back(arg_time1); + + MotionPrimitive moprim2; + moprim2.type = MotionPrimitive::LINEAR_JOINT; + moprim2.blend_radius = 0.0; + moprim2.joint_positions = {0.9, -1.57, 1.57, -1.57, -1.57, -1.57}; + industrial_robot_motion_interfaces::msg::MotionArgument arg_time2; + arg_time2.argument_name = "move_time"; + arg_time2.argument_value = 2.0; + moprim2.additional_arguments.push_back(arg_time2); + + std::vector primitives; + primitives.push_back(moprim1); + primitives.push_back(moprim2); + + auto add_motions = [this](const std::vector & motion_primitives) + { + for (const auto & primitive : motion_primitives) + { + moprim_queue_.push(std::make_shared(primitive)); + } + }; + + if (primitives.size() > 1) + { + std::shared_ptr start_marker = std::make_shared(); + start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); + moprim_queue_.push(start_marker); + + add_motions(primitives); + + std::shared_ptr end_marker = std::make_shared(); + end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); + moprim_queue_.push(end_marker); + } + else + { + add_motions(primitives); + } + moprim_queue_write_enabled_ = false; + + RCLCPP_INFO( + get_node()->get_logger(), + "Reduced planned joint trajectory from %zu points to %zu motion primitives.", + planned_trajectory.size(), primitives.size()); } } // namespace motion_primitives_from_trajectory_controller From 992898352a5ebb77ae30887dedd74332ce955d7a Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 15:27:33 +0200 Subject: [PATCH 063/128] integrated fk, not working yet --- .../CMakeLists.txt | 5 +++++ .../fk_client.hpp | 15 ++++++------- ..._primitives_from_trajectory_controller.hpp | 4 ++++ .../package.xml | 2 ++ .../src/fk_client.cpp | 19 ++++++++++++++--- ..._primitives_from_trajectory_controller.cpp | 21 +++++++++++++++++++ 6 files changed, 56 insertions(+), 10 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index b71c411295..674538f17b 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -14,6 +14,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp_lifecycle realtime_tools std_srvs + moveit_msgs + geometry_msgs industrial_robot_motion_interfaces ) @@ -35,6 +37,7 @@ add_library( motion_primitives_from_trajectory_controller SHARED src/motion_primitives_from_trajectory_controller.cpp + src/fk_client.cpp ) target_include_directories(motion_primitives_forward_controller PUBLIC $ @@ -65,6 +68,8 @@ target_link_libraries(motion_primitives_from_trajectory_controller PUBLIC rclcpp_lifecycle::rclcpp_lifecycle realtime_tools::realtime_tools ${control_msgs_TARGETS} + ${geometry_msgs_TARGETS} + ${moveit_msgs_TARGETS} ${std_srvs_TARGETS} ${industrial_robot_motion_interfaces_TARGETS} ) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp index e7b2d5c673..eda8822d5e 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp @@ -17,25 +17,26 @@ #ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ +#include +#include #include -#include #include -#include -#include -#include +#include "geometry_msgs/msg/pose.hpp" +#include "moveit_msgs/srv/get_position_fk.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" class FKClient { public: - explicit FKClient(const rclcpp::Node::SharedPtr & node); + explicit FKClient(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node); std::optional computeFK( const std::vector & joint_names, const std::vector & joint_positions, - const std::string & from_frame = "base", const std::string & to_link = "tool0"); + const std::string & from_frame, const std::string & to_link); private: - rclcpp::Node::SharedPtr node_; + rclcpp_lifecycle::LifecycleNode::SharedPtr node_; rclcpp::Client::SharedPtr client_; }; diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 13c70becb2..5d4cf3d3cf 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -34,6 +34,8 @@ #include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "motion_primitives_forward_controller/fk_client.hpp" + namespace motion_primitives_from_trajectory_controller { enum class ExecutionState : uint8_t @@ -117,6 +119,8 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co ReadyForNewPrimitive ready_for_new_primitive_; std::atomic moprim_queue_write_enabled_ = false; + + std::unique_ptr fk_client_; }; } // namespace motion_primitives_from_trajectory_controller diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index d4406cc736..cb3ead0355 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -31,6 +31,8 @@ rclcpp_lifecycle realtime_tools std_srvs + geometry_msgs + moveit_msgs ament_cmake_gmock controller_manager diff --git a/motion_primitives_forward_controller/src/fk_client.cpp b/motion_primitives_forward_controller/src/fk_client.cpp index 7694fb53a3..27fe2a1d4e 100644 --- a/motion_primitives_forward_controller/src/fk_client.cpp +++ b/motion_primitives_forward_controller/src/fk_client.cpp @@ -16,10 +16,11 @@ #include "motion_primitives_forward_controller/fk_client.hpp" #include +#include "rclcpp/executors.hpp" using namespace std::chrono_literals; -FKClient::FKClient(const rclcpp::Node::SharedPtr & node) : node_(node) +FKClient::FKClient(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node) : node_(node) { client_ = node_->create_client("/compute_fk"); @@ -46,7 +47,19 @@ std::optional FKClient::computeFK( auto future = client_->async_send_request(request); - if (rclcpp::spin_until_future_complete(node_, future, 3s) == rclcpp::FutureReturnCode::SUCCESS) + auto start_time = node_->now(); + + while (rclcpp::ok() && future.wait_for(std::chrono::milliseconds(1)) != std::future_status::ready) + { + if ((node_->now() - start_time).seconds() > 3.0) + { + RCLCPP_ERROR(node_->get_logger(), "FK call timed out"); + return std::nullopt; + } + std::this_thread::sleep_for(std::chrono::milliseconds(1)); + } + + if (future.valid()) { auto result = future.get(); if (result->error_code.val == result->error_code.SUCCESS) @@ -60,7 +73,7 @@ std::optional FKClient::computeFK( } else { - RCLCPP_ERROR(node_->get_logger(), "FK call timed out"); + RCLCPP_ERROR(node_->get_logger(), "FK future invalid"); } return std::nullopt; diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 289575a8bc..9a2ca278a6 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -70,6 +70,8 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o return controller_interface::CallbackReturn::ERROR; } + fk_client_ = std::make_unique(get_node()); + action_server_ = rclcpp_action::create_server( get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), @@ -436,6 +438,25 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( RCLCPP_INFO( get_node()->get_logger(), "Received trajectory with %zu points.", planned_trajectory.size()); + const auto & joint_names = goal_handle->get_goal()->trajectory.joint_names; + + // Get endefector pose for each trajectory point + for (const auto & point : planned_trajectory) + { + auto tool0_pose_opt = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); + if (tool0_pose_opt) + { + const auto & pose = tool0_pose_opt.value(); + RCLCPP_INFO( + get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f)", pose.position.x, + pose.position.y, pose.position.z); + } + else + { + RCLCPP_WARN(get_node()->get_logger(), "Failed to compute FK for a trajectory point."); + } + } + // TODO(mathias31415): Process the trajectory points and convert them to motion primitives // dummy primitives From 9b1986384a0b5d4c51348a2df781f7bc4b1745e2 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 3 Jul 2025 17:39:10 +0200 Subject: [PATCH 064/128] PTP working, but code needs cleanup (FK for LIN still not working) --- .../CMakeLists.txt | 2 + ..._primitives_from_trajectory_controller.hpp | 42 ++++ .../src/fk_client.cpp | 2 +- ..._primitives_from_trajectory_controller.cpp | 185 ++++++++++++++---- 4 files changed, 188 insertions(+), 43 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 674538f17b..e7c6e25b15 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -38,6 +38,8 @@ add_library( SHARED src/motion_primitives_from_trajectory_controller.cpp src/fk_client.cpp + src/rdp.cpp + src/approx_primitives_with_rdp.cpp ) target_include_directories(motion_primitives_forward_controller PUBLIC $ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 5d4cf3d3cf..eede5ad4c3 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -34,6 +34,7 @@ #include "industrial_robot_motion_interfaces/action/execute_motion.hpp" #include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "motion_primitives_forward_controller/approx_primitives_with_rdp.hpp" #include "motion_primitives_forward_controller/fk_client.hpp" namespace motion_primitives_from_trajectory_controller @@ -121,8 +122,49 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co std::atomic moprim_queue_write_enabled_ = false; std::unique_ptr fk_client_; + + MotionType approx_type_ = MotionType::LINEAR_JOINT; + + // ############ Function copied from JointTrajectoryController ############ + // TODO(mathias31415): Is there a cleaner solution? + void sort_to_local_joint_order( + std::shared_ptr trajectory_msg) const; }; +// ############ Function copied from JointTrajectoryController ############ +// TODO(mathias31415): Is there a cleaner solution? +/** + * \return The map between \p t1 indices (implicitly encoded in return vector indices) to \p t2 + * indices. If \p t1 is "{C, B}" and \p t2 is "{A, B, C, D}", the associated + * mapping vector is "{2, 1}". return empty vector if \p t1 is not a subset of \p t2. + */ +template +std::vector mapping(const T & t1, const T & t2) +{ + // t1 must be a subset of t2 + if (t1.size() > t2.size()) + { + return std::vector(); + } + + std::vector mapping_vector(t1.size()); // Return value + for (auto t1_it = t1.begin(); t1_it != t1.end(); ++t1_it) + { + auto t2_it = std::find(t2.begin(), t2.end(), *t1_it); + if (t2.end() == t2_it) + { + return std::vector(); + } + else + { + const size_t t1_dist = static_cast(std::distance(t1.begin(), t1_it)); + const size_t t2_dist = static_cast(std::distance(t2.begin(), t2_it)); + mapping_vector[t1_dist] = t2_dist; + } + } + return mapping_vector; +} + } // namespace motion_primitives_from_trajectory_controller #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ diff --git a/motion_primitives_forward_controller/src/fk_client.cpp b/motion_primitives_forward_controller/src/fk_client.cpp index 27fe2a1d4e..faebd725b2 100644 --- a/motion_primitives_forward_controller/src/fk_client.cpp +++ b/motion_primitives_forward_controller/src/fk_client.cpp @@ -16,7 +16,7 @@ #include "motion_primitives_forward_controller/fk_client.hpp" #include -#include "rclcpp/executors.hpp" +// #include "rclcpp/executors.hpp" using namespace std::chrono_literals; diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 9a2ca278a6..b4503715ce 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -434,69 +434,120 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - const auto & planned_trajectory = goal_handle->get_goal()->trajectory.points; + auto trajectory_msg = + std::make_shared(goal_handle->get_goal()->trajectory); + + sort_to_local_joint_order(trajectory_msg); + RCLCPP_INFO( - get_node()->get_logger(), "Received trajectory with %zu points.", planned_trajectory.size()); + get_node()->get_logger(), "Received trajectory with %zu points.", + trajectory_msg->points.size()); + + const auto & joint_names = trajectory_msg->joint_names; + + std::ostringstream oss; + for (const auto & name : joint_names) + { + oss << name << " "; + } + RCLCPP_INFO(get_node()->get_logger(), "Received joint names: %s", oss.str().c_str()); - const auto & joint_names = goal_handle->get_goal()->trajectory.joint_names; + // TODO(mathias31415): Make FK working // Get endefector pose for each trajectory point - for (const auto & point : planned_trajectory) + // for (const auto & point : planned_trajectory) + // { + // auto tool0_pose_opt = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); + // if (tool0_pose_opt) + // { + // const auto & pose = tool0_pose_opt.value(); + // RCLCPP_INFO( + // get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f)", pose.position.x, + // pose.position.y, pose.position.z); + // } + // else + // { + // RCLCPP_WARN(get_node()->get_logger(), "Failed to compute FK for a trajectory point."); + // } + // } + + std::vector planned_trajectory_data; + planned_trajectory_data.reserve(trajectory_msg->points.size()); + for (const auto & point : trajectory_msg->points) + { + approx_primitives_with_rdp::PlannedTrajectoryPoint pt; + pt.time_from_start = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9; + pt.joint_positions = point.positions; + // pt.pose = fk_client_->computeFK(trajectory_msg->joint_names, point.positions, "base", + // "tool0").value_or(Pose()); + planned_trajectory_data.push_back(pt); + } + industrial_robot_motion_interfaces::msg::MotionSequence motion_sequence; + double rdp_epsilon = 0.001; + bool use_time_not_vel_and_acc = true; + switch (approx_type_) { - auto tool0_pose_opt = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); - if (tool0_pose_opt) + case MotionType::LINEAR_JOINT: { - const auto & pose = tool0_pose_opt.value(); RCLCPP_INFO( - get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f)", pose.position.x, - pose.position.y, pose.position.z); + get_node()->get_logger(), "Approximating motion primitives with PTP motion primitives."); + motion_sequence = + approxPtpPrimitivesWithRDP(planned_trajectory_data, rdp_epsilon, use_time_not_vel_and_acc); + + break; } - else + case MotionType::LINEAR_CARTESIAN: { - RCLCPP_WARN(get_node()->get_logger(), "Failed to compute FK for a trajectory point."); + RCLCPP_INFO( + get_node()->get_logger(), "Approximating motion primitives with LIN motion primitives."); + + RCLCPP_WARN(get_node()->get_logger(), "Not implemented yet."); + break; } + default: + RCLCPP_WARN(get_node()->get_logger(), "Unknown motion type."); + break; } - // TODO(mathias31415): Process the trajectory points and convert them to motion primitives - - // dummy primitives - MotionPrimitive moprim1; - moprim1.type = MotionPrimitive::LINEAR_JOINT; - moprim1.blend_radius = 0.0; - moprim1.joint_positions = {1.57, -1.57, 1.57, -1.57, -1.57, -1.57}; - industrial_robot_motion_interfaces::msg::MotionArgument arg_time1; - arg_time1.argument_name = "move_time"; - arg_time1.argument_value = 2.0; - moprim1.additional_arguments.push_back(arg_time1); - - MotionPrimitive moprim2; - moprim2.type = MotionPrimitive::LINEAR_JOINT; - moprim2.blend_radius = 0.0; - moprim2.joint_positions = {0.9, -1.57, 1.57, -1.57, -1.57, -1.57}; - industrial_robot_motion_interfaces::msg::MotionArgument arg_time2; - arg_time2.argument_name = "move_time"; - arg_time2.argument_value = 2.0; - moprim2.additional_arguments.push_back(arg_time2); - - std::vector primitives; - primitives.push_back(moprim1); - primitives.push_back(moprim2); - - auto add_motions = [this](const std::vector & motion_primitives) + // // dummy primitives + // MotionPrimitive moprim1; + // moprim1.type = MotionPrimitive::LINEAR_JOINT; + // moprim1.blend_radius = 0.0; + // moprim1.joint_positions = {1.57, -1.57, 1.57, -1.57, -1.57, -1.57}; + // industrial_robot_motion_interfaces::msg::MotionArgument arg_time1; + // arg_time1.argument_name = "move_time"; + // arg_time1.argument_value = 2.0; + // moprim1.additional_arguments.push_back(arg_time1); + + // MotionPrimitive moprim2; + // moprim2.type = MotionPrimitive::LINEAR_JOINT; + // moprim2.blend_radius = 0.0; + // moprim2.joint_positions = {0.9, -1.57, 1.57, -1.57, -1.57, -1.57}; + // industrial_robot_motion_interfaces::msg::MotionArgument arg_time2; + // arg_time2.argument_name = "move_time"; + // arg_time2.argument_value = 2.0; + // moprim2.additional_arguments.push_back(arg_time2); + + // industrial_robot_motion_interfaces::msg::MotionSequence motion_sequence; + // motion_sequence.motions.push_back(moprim1); + // motion_sequence.motions.push_back(moprim2); + + auto add_motions = + [this](const industrial_robot_motion_interfaces::msg::MotionSequence & moprim_sequence) { - for (const auto & primitive : motion_primitives) + for (const auto & primitive : moprim_sequence.motions) { moprim_queue_.push(std::make_shared(primitive)); } }; - if (primitives.size() > 1) + if (motion_sequence.motions.size() > 1) { std::shared_ptr start_marker = std::make_shared(); start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); moprim_queue_.push(start_marker); - add_motions(primitives); + add_motions(motion_sequence); std::shared_ptr end_marker = std::make_shared(); end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); @@ -504,14 +555,64 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } else { - add_motions(primitives); + add_motions(motion_sequence); } moprim_queue_write_enabled_ = false; RCLCPP_INFO( get_node()->get_logger(), "Reduced planned joint trajectory from %zu points to %zu motion primitives.", - planned_trajectory.size(), primitives.size()); + trajectory_msg->points.size(), motion_sequence.motions.size()); +} + +// TODO(mathias31415): read local_joint_order from param instead +void MotionPrimitivesFromTrajectoryController::sort_to_local_joint_order( + std::shared_ptr trajectory_msg) const +{ + const std::vector local_joint_order = {"shoulder_pan_joint", "shoulder_lift_joint", + "elbow_joint", "wrist_1_joint", + "wrist_2_joint", "wrist_3_joint"}; + + std::vector mapping_vector = mapping(trajectory_msg->joint_names, local_joint_order); + + auto remap = [this]( + const std::vector & to_remap, + const std::vector & map_indices) -> std::vector + { + if (to_remap.empty()) return to_remap; + + if (to_remap.size() != map_indices.size()) + { + RCLCPP_WARN( + get_node()->get_logger(), "Invalid input size (%zu) for sorting", to_remap.size()); + return to_remap; + } + + std::vector output(map_indices.size(), 0.0); + + for (size_t index = 0; index < map_indices.size(); ++index) + { + size_t map_index = map_indices[index]; + if (map_index < to_remap.size()) + { + output[index] = to_remap[map_index]; + } + } + + return output; + }; + + for (auto & point : trajectory_msg->points) + { + point.positions = remap(point.positions, mapping_vector); + + if (!point.velocities.empty()) point.velocities = remap(point.velocities, mapping_vector); + + if (!point.accelerations.empty()) + point.accelerations = remap(point.accelerations, mapping_vector); + + if (!point.effort.empty()) point.effort = remap(point.effort, mapping_vector); + } } } // namespace motion_primitives_from_trajectory_controller From 9143c7176604077745e5340c7780dfaac9e1e045 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 7 Jul 2025 11:14:59 +0200 Subject: [PATCH 065/128] fk call working --- .../fk_client.hpp | 18 +++--- ..._primitives_from_trajectory_controller.hpp | 2 +- .../src/fk_client.cpp | 56 +++++++------------ ..._primitives_from_trajectory_controller.cpp | 38 +++++++------ 4 files changed, 48 insertions(+), 66 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp index eda8822d5e..ec38a50851 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/fk_client.hpp @@ -17,27 +17,25 @@ #ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ -#include -#include #include #include -#include "geometry_msgs/msg/pose.hpp" -#include "moveit_msgs/srv/get_position_fk.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" +#include +#include +#include +#include -class FKClient +class FKClient : public rclcpp::Node { public: - explicit FKClient(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node); + explicit FKClient(const std::string & node_name = "fk_client"); - std::optional computeFK( + geometry_msgs::msg::Pose computeFK( const std::vector & joint_names, const std::vector & joint_positions, const std::string & from_frame, const std::string & to_link); private: - rclcpp_lifecycle::LifecycleNode::SharedPtr node_; - rclcpp::Client::SharedPtr client_; + rclcpp::Client::SharedPtr fk_client_; }; #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__FK_CLIENT_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index eede5ad4c3..cfc9da8f2a 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -121,7 +121,7 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co std::atomic moprim_queue_write_enabled_ = false; - std::unique_ptr fk_client_; + std::shared_ptr fk_client_; MotionType approx_type_ = MotionType::LINEAR_JOINT; diff --git a/motion_primitives_forward_controller/src/fk_client.cpp b/motion_primitives_forward_controller/src/fk_client.cpp index faebd725b2..29b3850183 100644 --- a/motion_primitives_forward_controller/src/fk_client.cpp +++ b/motion_primitives_forward_controller/src/fk_client.cpp @@ -15,66 +15,48 @@ // Authors: Mathias Fuhrer #include "motion_primitives_forward_controller/fk_client.hpp" -#include -// #include "rclcpp/executors.hpp" -using namespace std::chrono_literals; - -FKClient::FKClient(const rclcpp_lifecycle::LifecycleNode::SharedPtr & node) : node_(node) +FKClient::FKClient(const std::string & node_name) : Node(node_name) { - client_ = node_->create_client("/compute_fk"); + fk_client_ = this->create_client("/compute_fk"); - while (!client_->wait_for_service(1s)) + while (!fk_client_->wait_for_service(std::chrono::seconds(1))) { - RCLCPP_INFO(node_->get_logger(), "Waiting for /compute_fk service..."); - if (!rclcpp::ok()) - { - RCLCPP_ERROR(node_->get_logger(), "Interrupted while waiting for the service."); - return; - } + RCLCPP_INFO(this->get_logger(), "Waiting for /compute_fk service..."); } } -std::optional FKClient::computeFK( +geometry_msgs::msg::Pose FKClient::computeFK( const std::vector & joint_names, const std::vector & joint_positions, const std::string & from_frame, const std::string & to_link) { auto request = std::make_shared(); - request->header.frame_id = from_frame; request->fk_link_names.push_back(to_link); - request->robot_state.joint_state.name = joint_names; - request->robot_state.joint_state.position = joint_positions; - auto future = client_->async_send_request(request); + sensor_msgs::msg::JointState joint_state; + joint_state.name = joint_names; + joint_state.position = joint_positions; + request->robot_state.joint_state = joint_state; + request->header.frame_id = from_frame; - auto start_time = node_->now(); + auto future = fk_client_->async_send_request(request); - while (rclcpp::ok() && future.wait_for(std::chrono::milliseconds(1)) != std::future_status::ready) + if ( + rclcpp::spin_until_future_complete(this->get_node_base_interface(), future) == + rclcpp::FutureReturnCode::SUCCESS) { - if ((node_->now() - start_time).seconds() > 3.0) + auto response = future.get(); + if (!response->pose_stamped.empty()) { - RCLCPP_ERROR(node_->get_logger(), "FK call timed out"); - return std::nullopt; - } - std::this_thread::sleep_for(std::chrono::milliseconds(1)); - } - - if (future.valid()) - { - auto result = future.get(); - if (result->error_code.val == result->error_code.SUCCESS) - { - return result->pose_stamped[0].pose; + return response->pose_stamped.front().pose; } else { - RCLCPP_WARN(node_->get_logger(), "FK error: code=%d", result->error_code.val); + throw std::runtime_error("Empty response received from FK service."); } } else { - RCLCPP_ERROR(node_->get_logger(), "FK future invalid"); + throw std::runtime_error("Error calling FK service."); } - - return std::nullopt; } diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index b4503715ce..0a6ecfe773 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -70,7 +70,7 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o return controller_interface::CallbackReturn::ERROR; } - fk_client_ = std::make_unique(get_node()); + fk_client_ = std::make_shared(); action_server_ = rclcpp_action::create_server( get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), @@ -135,6 +135,8 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); + action_server_.reset(); + fk_client_.reset(); RCLCPP_DEBUG(get_node()->get_logger(), "Controller deactivated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -452,24 +454,24 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } RCLCPP_INFO(get_node()->get_logger(), "Received joint names: %s", oss.str().c_str()); - // TODO(mathias31415): Make FK working - // Get endefector pose for each trajectory point - // for (const auto & point : planned_trajectory) - // { - // auto tool0_pose_opt = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); - // if (tool0_pose_opt) - // { - // const auto & pose = tool0_pose_opt.value(); - // RCLCPP_INFO( - // get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f)", pose.position.x, - // pose.position.y, pose.position.z); - // } - // else - // { - // RCLCPP_WARN(get_node()->get_logger(), "Failed to compute FK for a trajectory point."); - // } - // } + for (const auto & point : trajectory_msg->points) + { + try + { + auto tool0_pose = fk_client_->computeFK(joint_names, point.positions, "base_link", "tool0"); + RCLCPP_INFO( + get_node()->get_logger(), + "Tool0 pose: position (%.3f, %.3f, %.3f), orientation [%.3f, %.3f, %.3f, %.3f]", + tool0_pose.position.x, tool0_pose.position.y, tool0_pose.position.z, + tool0_pose.orientation.x, tool0_pose.orientation.y, tool0_pose.orientation.z, + tool0_pose.orientation.w); + } + catch (const std::exception & e) + { + RCLCPP_ERROR(get_node()->get_logger(), "FK-Error: %s", e.what()); + } + } std::vector planned_trajectory_data; planned_trajectory_data.reserve(trajectory_msg->points.size()); From d3bd21c8c6f5e60b7d6d2d58aefd1f6d5b38d66f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 7 Jul 2025 12:04:15 +0200 Subject: [PATCH 066/128] LIN working --- ..._primitives_from_trajectory_controller.hpp | 2 +- ..._primitives_from_trajectory_controller.cpp | 63 ++++--------------- 2 files changed, 14 insertions(+), 51 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index cfc9da8f2a..d8ad394db6 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -123,7 +123,7 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co std::shared_ptr fk_client_; - MotionType approx_type_ = MotionType::LINEAR_JOINT; + MotionType approx_type_ = MotionType::LINEAR_CARTESIAN; // ############ Function copied from JointTrajectoryController ############ // TODO(mathias31415): Is there a cleaner solution? diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 0a6ecfe773..061a137bed 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -447,41 +447,26 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( const auto & joint_names = trajectory_msg->joint_names; - std::ostringstream oss; - for (const auto & name : joint_names) - { - oss << name << " "; - } - RCLCPP_INFO(get_node()->get_logger(), "Received joint names: %s", oss.str().c_str()); - - // Get endefector pose for each trajectory point + std::vector planned_trajectory_data; + planned_trajectory_data.reserve(trajectory_msg->points.size()); for (const auto & point : trajectory_msg->points) { + approx_primitives_with_rdp::PlannedTrajectoryPoint pt; + pt.time_from_start = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9; + pt.joint_positions = point.positions; try { - auto tool0_pose = fk_client_->computeFK(joint_names, point.positions, "base_link", "tool0"); - RCLCPP_INFO( + pt.pose = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); + RCLCPP_DEBUG( get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f), orientation [%.3f, %.3f, %.3f, %.3f]", - tool0_pose.position.x, tool0_pose.position.y, tool0_pose.position.z, - tool0_pose.orientation.x, tool0_pose.orientation.y, tool0_pose.orientation.z, - tool0_pose.orientation.w); + pt.pose.position.x, pt.pose.position.y, pt.pose.position.z, pt.pose.orientation.x, + pt.pose.orientation.y, pt.pose.orientation.z, pt.pose.orientation.w); } catch (const std::exception & e) { RCLCPP_ERROR(get_node()->get_logger(), "FK-Error: %s", e.what()); } - } - - std::vector planned_trajectory_data; - planned_trajectory_data.reserve(trajectory_msg->points.size()); - for (const auto & point : trajectory_msg->points) - { - approx_primitives_with_rdp::PlannedTrajectoryPoint pt; - pt.time_from_start = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9; - pt.joint_positions = point.positions; - // pt.pose = fk_client_->computeFK(trajectory_msg->joint_names, point.positions, "base", - // "tool0").value_or(Pose()); planned_trajectory_data.push_back(pt); } industrial_robot_motion_interfaces::msg::MotionSequence motion_sequence; @@ -495,15 +480,14 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( get_node()->get_logger(), "Approximating motion primitives with PTP motion primitives."); motion_sequence = approxPtpPrimitivesWithRDP(planned_trajectory_data, rdp_epsilon, use_time_not_vel_and_acc); - break; } case MotionType::LINEAR_CARTESIAN: { RCLCPP_INFO( get_node()->get_logger(), "Approximating motion primitives with LIN motion primitives."); - - RCLCPP_WARN(get_node()->get_logger(), "Not implemented yet."); + motion_sequence = + approxLinPrimitivesWithRDP(planned_trajectory_data, rdp_epsilon, use_time_not_vel_and_acc); break; } default: @@ -511,29 +495,6 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( break; } - // // dummy primitives - // MotionPrimitive moprim1; - // moprim1.type = MotionPrimitive::LINEAR_JOINT; - // moprim1.blend_radius = 0.0; - // moprim1.joint_positions = {1.57, -1.57, 1.57, -1.57, -1.57, -1.57}; - // industrial_robot_motion_interfaces::msg::MotionArgument arg_time1; - // arg_time1.argument_name = "move_time"; - // arg_time1.argument_value = 2.0; - // moprim1.additional_arguments.push_back(arg_time1); - - // MotionPrimitive moprim2; - // moprim2.type = MotionPrimitive::LINEAR_JOINT; - // moprim2.blend_radius = 0.0; - // moprim2.joint_positions = {0.9, -1.57, 1.57, -1.57, -1.57, -1.57}; - // industrial_robot_motion_interfaces::msg::MotionArgument arg_time2; - // arg_time2.argument_name = "move_time"; - // arg_time2.argument_value = 2.0; - // moprim2.additional_arguments.push_back(arg_time2); - - // industrial_robot_motion_interfaces::msg::MotionSequence motion_sequence; - // motion_sequence.motions.push_back(moprim1); - // motion_sequence.motions.push_back(moprim2); - auto add_motions = [this](const industrial_robot_motion_interfaces::msg::MotionSequence & moprim_sequence) { @@ -615,6 +576,8 @@ void MotionPrimitivesFromTrajectoryController::sort_to_local_joint_order( if (!point.effort.empty()) point.effort = remap(point.effort, mapping_vector); } + + trajectory_msg->joint_names = local_joint_order; } } // namespace motion_primitives_from_trajectory_controller From 4a96de5b06b5fc79de7bc0074f0c3c7e580dda88 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 7 Jul 2025 14:30:35 +0200 Subject: [PATCH 067/128] changed fprintf to RCLCPP_ERROR --- .../src/motion_primitives_forward_controller.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index a3ea102f39..0989159735 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -39,7 +39,9 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_init( } catch (const std::exception & e) { - fprintf(stderr, "Exception thrown during controller's init with message: %s \n", e.what()); + RCLCPP_ERROR( + get_node()->get_logger(), "Exception thrown during controller's init with message: %s \n", + e.what()); return controller_interface::CallbackReturn::ERROR; } From 40d78fc9882fd12a552e541470b3cb20f610200d Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 7 Jul 2025 15:28:14 +0200 Subject: [PATCH 068/128] changed moprim_queue_ from std::queue to realtime_tools::LockFreeSPSCQueue --- .../motion_primitives_forward_controller.hpp | 6 +-- .../motion_primitives_forward_controller.cpp | 47 +++++++++---------- ...t_motion_primitives_forward_controller.cpp | 2 +- 3 files changed, 24 insertions(+), 31 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index d6363cacc0..64f0ef3a94 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -18,11 +18,11 @@ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #include -#include #include #include #include +#include #include "controller_interface/controller_interface.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" @@ -91,7 +91,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle motion_primitives_forward_controller::Params params_; using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; - std::queue> moprim_queue_; + realtime_tools::LockFreeSPSCQueue, 128> moprim_queue_; using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; rclcpp_action::Server::SharedPtr action_server_; @@ -114,8 +114,6 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; - - std::atomic moprim_queue_write_enabled_ = false; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 0989159735..ab8cdff00e 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -122,7 +122,6 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_activ const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); - moprim_queue_write_enabled_ = true; RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -145,9 +144,10 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); // send stop command immediately to the hw-interface (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); - while (!moprim_queue_.empty()) - { // clear the queue - moprim_queue_.pop(); + std::shared_ptr primitive; + while (moprim_queue_.pop(primitive)) + { + // clear the queue } robot_stop_requested_ = true; } @@ -213,7 +213,6 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); robot_stop_requested_ = false; - moprim_queue_write_enabled_ = true; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } @@ -256,7 +255,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( ready_for_new_primitive_ = static_cast(static_cast(std::round(opt_value_ready.value()))); - if (!moprim_queue_write_enabled_ && !cancel_requested_) + if (!cancel_requested_) { switch (ready_for_new_primitive_) { @@ -268,8 +267,6 @@ controller_interface::return_type MotionPrimitivesForwardController::update( { if (moprim_queue_.empty()) // check if new command is available { - // all primitives read, queue ready to get filled with new primitives - moprim_queue_write_enabled_ = true; return controller_interface::return_type::OK; } else @@ -308,13 +305,10 @@ void MotionPrimitivesForwardController::reset_command_interfaces() bool MotionPrimitivesForwardController::set_command_interfaces() { // Get the oldest message from the queue - std::shared_ptr current_moprim = moprim_queue_.front(); - moprim_queue_.pop(); - - // Check if the message is valid - if (!current_moprim) + std::shared_ptr current_moprim; + if (!moprim_queue_.pop(current_moprim)) { - RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); + RCLCPP_WARN(get_node()->get_logger(), "Failed to pop motion primitive from queue."); return false; } @@ -397,13 +391,6 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal return rclcpp_action::GoalResponse::REJECT; } - if (!moprim_queue_write_enabled_) - { - RCLCPP_WARN( - get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); - return rclcpp_action::GoalResponse::REJECT; - } - if (primitives.empty()) { RCLCPP_WARN(get_node()->get_logger(), "Goal rejected: no motion primitives provided."); @@ -464,7 +451,6 @@ rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_ const std::shared_ptr>) { cancel_requested_ = true; - moprim_queue_write_enabled_ = false; return rclcpp_action::CancelResponse::ACCEPT; } @@ -479,7 +465,10 @@ void MotionPrimitivesForwardController::goal_accepted_callback( { for (const auto & primitive : motion_primitives) { - moprim_queue_.push(std::make_shared(primitive)); + if (!moprim_queue_.push(std::make_shared(primitive))) + { + RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion primitive to queue."); + } } }; @@ -487,19 +476,25 @@ void MotionPrimitivesForwardController::goal_accepted_callback( { std::shared_ptr start_marker = std::make_shared(); start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); - moprim_queue_.push(start_marker); + if (!moprim_queue_.push(start_marker)) + { + RCLCPP_WARN( + get_node()->get_logger(), "Failed to push motion sequence start marker to queue."); + } add_motions(primitives); std::shared_ptr end_marker = std::make_shared(); end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); - moprim_queue_.push(end_marker); + if (!moprim_queue_.push(end_marker)) + { + RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion sequence end marker to queue."); + } } else { add_motions(primitives); } - moprim_queue_write_enabled_ = false; RCLCPP_INFO( get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index c1c980c021..ed1e3317d7 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -72,7 +72,7 @@ TEST_F(MotionPrimitivesForwardControllerTest, activate_success) ASSERT_EQ(controller_->on_activate(rclcpp_lifecycle::State()), NODE_SUCCESS); // check that the message queue is reset - auto moprim_queue_ = controller_->moprim_queue_; + auto & moprim_queue_ = controller_->moprim_queue_; ASSERT_TRUE(moprim_queue_.empty()); } From 29d5a5ec4cfd43939ee28cf7e055ef273266e0d3 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 11:23:07 +0200 Subject: [PATCH 069/128] using realtime_tools::RealtimeServerGoalHandle --- .../motion_primitives_forward_controller.hpp | 17 +++-- .../motion_primitives_forward_controller.cpp | 68 ++++++++----------- 2 files changed, 41 insertions(+), 44 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 64f0ef3a94..51d2ddf348 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -17,12 +17,14 @@ #ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FORWARD_CONTROLLER_HPP_ +#include #include #include #include #include #include +#include #include "controller_interface/controller_interface.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" @@ -93,15 +95,18 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; realtime_tools::LockFreeSPSCQueue, 128> moprim_queue_; - using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; - rclcpp_action::Server::SharedPtr action_server_; + using ExecuteMotionAction = industrial_robot_motion_interfaces::action::ExecuteMotion; + rclcpp_action::Server::SharedPtr action_server_; rclcpp_action::GoalResponse goal_received_callback( - const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); + const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); rclcpp_action::CancelResponse goal_cancelled_callback( - const std::shared_ptr> goal_handle); + const std::shared_ptr> goal_handle); void goal_accepted_callback( - const std::shared_ptr> goal_handle); - std::shared_ptr> pending_action_goal_; + std::shared_ptr> goal_handle); + using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle; + std::shared_ptr realtime_goal_handle_; + rclcpp::TimerBase::SharedPtr goal_handle_timer_; + rclcpp::Duration action_monitor_period_ = rclcpp::Duration(std::chrono::milliseconds(20)); void reset_command_interfaces(); bool set_command_interfaces(); diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index ab8cdff00e..aa3eae43e6 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -70,17 +70,14 @@ controller_interface::CallbackReturn MotionPrimitivesForwardController::on_confi return controller_interface::CallbackReturn::ERROR; } - action_server_ = rclcpp_action::create_server( + using namespace std::placeholders; + action_server_ = rclcpp_action::create_server( get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), std::string(get_node()->get_name()) + "/motion_sequence", - std::bind( - &MotionPrimitivesForwardController::goal_received_callback, this, std::placeholders::_1, - std::placeholders::_2), - std::bind( - &MotionPrimitivesForwardController::goal_cancelled_callback, this, std::placeholders::_1), - std::bind( - &MotionPrimitivesForwardController::goal_accepted_callback, this, std::placeholders::_1)); + std::bind(&MotionPrimitivesForwardController::goal_received_callback, this, _1, _2), + std::bind(&MotionPrimitivesForwardController::goal_cancelled_callback, this, _1), + std::bind(&MotionPrimitivesForwardController::goal_accepted_callback, this, _1)); RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); return controller_interface::CallbackReturn::SUCCESS; @@ -179,30 +176,27 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::SUCCESS: print_error_once_ = true; - if (pending_action_goal_ && was_executing_) + if (realtime_goal_handle_ && was_executing_) { was_executing_ = false; - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::SUCCESSFUL; + auto result = std::make_shared(); + result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; result->error_string = "Motion primitives executed successfully"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); + realtime_goal_handle_->setSucceeded(result); + realtime_goal_handle_.reset(); RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); } - break; case ExecutionState::STOPPED: print_error_once_ = true; was_executing_ = false; - if (pending_action_goal_) + if (realtime_goal_handle_) { - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::CANCELED; - result->error_string = "Motion primitives execution canceled"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); + auto result = std::make_shared(); + realtime_goal_handle_->setCanceled(result); + realtime_goal_handle_.reset(); RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); } @@ -220,17 +214,6 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::ERROR: was_executing_ = false; - - if (pending_action_goal_) - { - auto result = std::make_shared(); - result->error_code = ExecuteMotion::Result::FAILED; - result->error_string = "Motion primitives execution failed"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution failed"); - } - if (print_error_once_) { RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); @@ -379,9 +362,9 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_callback( - const rclcpp_action::GoalUUID &, std::shared_ptr goal) + const rclcpp_action::GoalUUID &, std::shared_ptr goal) { - RCLCPP_INFO(get_node()->get_logger(), "Received goal request"); + RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); const auto & primitives = goal->trajectory.motions; @@ -443,22 +426,21 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal return rclcpp_action::GoalResponse::REJECT; } } - + RCLCPP_INFO(get_node()->get_logger(), "Accepted new action goal"); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } rclcpp_action::CancelResponse MotionPrimitivesForwardController::goal_cancelled_callback( - const std::shared_ptr>) + const std::shared_ptr>) { + RCLCPP_INFO(get_node()->get_logger(), "Got request to cancel goal"); cancel_requested_ = true; return rclcpp_action::CancelResponse::ACCEPT; } void MotionPrimitivesForwardController::goal_accepted_callback( - const std::shared_ptr> goal_handle) + std::shared_ptr> goal_handle) { - pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - const auto & primitives = goal_handle->get_goal()->trajectory.motions; auto add_motions = [this](const std::vector & motion_primitives) @@ -496,6 +478,16 @@ void MotionPrimitivesForwardController::goal_accepted_callback( add_motions(primitives); } + auto rt_goal = std::make_shared(goal_handle); + realtime_goal_handle_ = rt_goal; + + rt_goal->execute(); + + goal_handle_timer_.reset(); + goal_handle_timer_ = get_node()->create_wall_timer( + action_monitor_period_.to_chrono(), + std::bind(&RealtimeGoalHandle::runNonRealtime, rt_goal)); + RCLCPP_INFO( get_node()->get_logger(), "Accepted goal with %zu motion primitives.", primitives.size()); } From c4bc08947eb22534998e1ca5e12daec7c2cea527 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 11:41:33 +0200 Subject: [PATCH 070/128] Preallocate std::shared_ptr current_moprim_ --- .../motion_primitives_forward_controller.hpp | 1 + .../motion_primitives_forward_controller.cpp | 28 +++++++++---------- 2 files changed, 14 insertions(+), 15 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 51d2ddf348..c809e46145 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -119,6 +119,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; + std::shared_ptr current_moprim_; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index aa3eae43e6..9f64a555f4 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -141,8 +141,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); // send stop command immediately to the hw-interface (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); - std::shared_ptr primitive; - while (moprim_queue_.pop(primitive)) + while (moprim_queue_.pop(current_moprim_)) { // clear the queue } @@ -288,29 +287,28 @@ void MotionPrimitivesForwardController::reset_command_interfaces() bool MotionPrimitivesForwardController::set_command_interfaces() { // Get the oldest message from the queue - std::shared_ptr current_moprim; - if (!moprim_queue_.pop(current_moprim)) + if (!moprim_queue_.pop(current_moprim_)) { RCLCPP_WARN(get_node()->get_logger(), "Failed to pop motion primitive from queue."); return false; } // Set the motion_type - (void)command_interfaces_[0].set_value(static_cast(current_moprim->type)); + (void)command_interfaces_[0].set_value(static_cast(current_moprim_->type)); // Process joint positions if available - if (!current_moprim->joint_positions.empty()) + if (!current_moprim_->joint_positions.empty()) { - for (size_t i = 0; i < current_moprim->joint_positions.size(); ++i) + for (size_t i = 0; i < current_moprim_->joint_positions.size(); ++i) { - (void)command_interfaces_[i + 1].set_value(current_moprim->joint_positions[i]); // q1 to q6 + (void)command_interfaces_[i + 1].set_value(current_moprim_->joint_positions[i]); // q1 to q6 } } // Process Cartesian poses if available - if (!current_moprim->poses.empty()) + if (!current_moprim_->poses.empty()) { - const auto & goal_pose = current_moprim->poses[0].pose; // goal pose + const auto & goal_pose = current_moprim_->poses[0].pose; // goal pose (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z @@ -321,10 +319,10 @@ bool MotionPrimitivesForwardController::set_command_interfaces() // Process via poses if available (only for circular motion) if ( - current_moprim->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && - current_moprim->poses.size() == 2) + current_moprim_->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && + current_moprim_->poses.size() == 2) { - const auto & via_pose = current_moprim->poses[1].pose; // via pose + const auto & via_pose = current_moprim_->poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z @@ -335,10 +333,10 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } } - (void)command_interfaces_[21].set_value(current_moprim->blend_radius); // blend_radius + (void)command_interfaces_[21].set_value(current_moprim_->blend_radius); // blend_radius // Read additional arguments - for (const auto & arg : current_moprim->additional_arguments) + for (const auto & arg : current_moprim_->additional_arguments) { if (arg.argument_name == "velocity") { From 01a24e82ed9a931e0ed8d986ae70e1be92264e49 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 11:53:56 +0200 Subject: [PATCH 071/128] using get_latest instead of while(pop) --- .../src/motion_primitives_forward_controller.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 9f64a555f4..f62b173ef0 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -141,10 +141,8 @@ controller_interface::return_type MotionPrimitivesForwardController::update( reset_command_interfaces(); // send stop command immediately to the hw-interface (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); - while (moprim_queue_.pop(current_moprim_)) - { - // clear the queue - } + // clear the queue (ignore return value) + static_cast(moprim_queue_.get_latest(current_moprim_)); robot_stop_requested_ = true; } From 42542e70e871bb9f98b33fd3c53a6e2356ca54bc Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 12:17:33 +0200 Subject: [PATCH 072/128] pushing primitives directly into the q instead of using shared pointers --- .../motion_primitives_forward_controller.hpp | 4 +-- .../motion_primitives_forward_controller.cpp | 32 +++++++++---------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index c809e46145..6ed760ad2b 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -93,7 +93,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle motion_primitives_forward_controller::Params params_; using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; - realtime_tools::LockFreeSPSCQueue, 128> moprim_queue_; + realtime_tools::LockFreeSPSCQueue moprim_queue_; using ExecuteMotionAction = industrial_robot_motion_interfaces::action::ExecuteMotion; rclcpp_action::Server::SharedPtr action_server_; @@ -119,7 +119,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle bool was_executing_ = false; ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; - std::shared_ptr current_moprim_; + MotionPrimitive current_moprim_; }; } // namespace motion_primitives_forward_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index f62b173ef0..24661ba7f4 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -292,21 +292,21 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } // Set the motion_type - (void)command_interfaces_[0].set_value(static_cast(current_moprim_->type)); + (void)command_interfaces_[0].set_value(static_cast(current_moprim_.type)); // Process joint positions if available - if (!current_moprim_->joint_positions.empty()) + if (!current_moprim_.joint_positions.empty()) { - for (size_t i = 0; i < current_moprim_->joint_positions.size(); ++i) + for (size_t i = 0; i < current_moprim_.joint_positions.size(); ++i) { - (void)command_interfaces_[i + 1].set_value(current_moprim_->joint_positions[i]); // q1 to q6 + (void)command_interfaces_[i + 1].set_value(current_moprim_.joint_positions[i]); // q1 to q6 } } // Process Cartesian poses if available - if (!current_moprim_->poses.empty()) + if (!current_moprim_.poses.empty()) { - const auto & goal_pose = current_moprim_->poses[0].pose; // goal pose + const auto & goal_pose = current_moprim_.poses[0].pose; // goal pose (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z @@ -317,10 +317,10 @@ bool MotionPrimitivesForwardController::set_command_interfaces() // Process via poses if available (only for circular motion) if ( - current_moprim_->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && - current_moprim_->poses.size() == 2) + current_moprim_.type == static_cast(MotionType::CIRCULAR_CARTESIAN) && + current_moprim_.poses.size() == 2) { - const auto & via_pose = current_moprim_->poses[1].pose; // via pose + const auto & via_pose = current_moprim_.poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z @@ -331,10 +331,10 @@ bool MotionPrimitivesForwardController::set_command_interfaces() } } - (void)command_interfaces_[21].set_value(current_moprim_->blend_radius); // blend_radius + (void)command_interfaces_[21].set_value(current_moprim_.blend_radius); // blend_radius // Read additional arguments - for (const auto & arg : current_moprim_->additional_arguments) + for (const auto & arg : current_moprim_.additional_arguments) { if (arg.argument_name == "velocity") { @@ -443,7 +443,7 @@ void MotionPrimitivesForwardController::goal_accepted_callback( { for (const auto & primitive : motion_primitives) { - if (!moprim_queue_.push(std::make_shared(primitive))) + if (!moprim_queue_.push(primitive)) { RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion primitive to queue."); } @@ -452,8 +452,8 @@ void MotionPrimitivesForwardController::goal_accepted_callback( if (primitives.size() > 1) { - std::shared_ptr start_marker = std::make_shared(); - start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); + MotionPrimitive start_marker; + start_marker.type = static_cast(MotionType::MOTION_SEQUENCE_START); if (!moprim_queue_.push(start_marker)) { RCLCPP_WARN( @@ -462,8 +462,8 @@ void MotionPrimitivesForwardController::goal_accepted_callback( add_motions(primitives); - std::shared_ptr end_marker = std::make_shared(); - end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); + MotionPrimitive end_marker; + end_marker.type = static_cast(MotionType::MOTION_SEQUENCE_END); if (!moprim_queue_.push(end_marker)) { RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion sequence end marker to queue."); From a80e592b4ab36dc45aa30a51f049f7076e9e99ce Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 12:34:50 +0200 Subject: [PATCH 073/128] added check for remaining q-size before accepting the goal --- .../motion_primitives_forward_controller.cpp | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 24661ba7f4..e4c432e39e 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -376,6 +376,26 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal return rclcpp_action::GoalResponse::REJECT; } + if ( + (primitives.size() == 1) && + primitives.size() > (moprim_queue_.capacity() - moprim_queue_.size())) + { + RCLCPP_WARN( + get_node()->get_logger(), + "Remaining queue capacity (%zu) is not enough for the requested %zu motion primitive.", + moprim_queue_.capacity() - moprim_queue_.size(), primitives.size()); + return rclcpp_action::GoalResponse::REJECT; + } + else if ((primitives.size() + 2) > (moprim_queue_.capacity() - moprim_queue_.size())) + { + RCLCPP_WARN( + get_node()->get_logger(), + "Remaining queue capacity (%zu) is not enough for the requested %zu motion primitives (+ " + "start and stop marker).", + moprim_queue_.capacity() - moprim_queue_.size(), primitives.size()); + return rclcpp_action::GoalResponse::REJECT; + } + for (size_t i = 0; i < primitives.size(); ++i) { const auto & primitive = primitives[i]; From b942ec55ec5021161e9b3eec71ce94dee0c4bbed Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 13:17:38 +0200 Subject: [PATCH 074/128] Using MotionType from msg definition and MotionHelperType from enum in the controller --- .../motion_primitives_forward_controller.hpp | 7 ++----- .../src/motion_primitives_forward_controller.cpp | 14 ++++++-------- 2 files changed, 8 insertions(+), 13 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 6ed760ad2b..86df5dbd9d 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -46,12 +46,9 @@ enum class ExecutionState : uint8_t STOPPED = 4 }; -enum class MotionType : uint8_t +using MotionType = industrial_robot_motion_interfaces::msg::MotionPrimitive; +enum class MotionHelperType : uint8_t { - LINEAR_JOINT = 10, - LINEAR_CARTESIAN = 50, - CIRCULAR_CARTESIAN = 51, - STOP_MOTION = 66, RESET_STOP = 67, diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index e4c432e39e..238c2e3b87 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -140,7 +140,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( cancel_requested_ = false; reset_command_interfaces(); // send stop command immediately to the hw-interface - (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); + (void)command_interfaces_[0].set_value(static_cast(MotionHelperType::STOP_MOTION)); // clear the queue (ignore return value) static_cast(moprim_queue_.get_latest(current_moprim_)); robot_stop_requested_ = true; @@ -202,7 +202,7 @@ controller_interface::return_type MotionPrimitivesForwardController::update( // If the robot was stopped by a stop command, reset the command interfaces // to allow new motion primitives to be sent. reset_command_interfaces(); - (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); + (void)command_interfaces_[0].set_value(static_cast(MotionHelperType::RESET_STOP)); robot_stop_requested_ = false; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } @@ -316,9 +316,7 @@ bool MotionPrimitivesForwardController::set_command_interfaces() (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw // Process via poses if available (only for circular motion) - if ( - current_moprim_.type == static_cast(MotionType::CIRCULAR_CARTESIAN) && - current_moprim_.poses.size() == 2) + if (current_moprim_.type == MotionType::CIRCULAR_CARTESIAN && current_moprim_.poses.size() == 2) { const auto & via_pose = current_moprim_.poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x @@ -400,7 +398,7 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal { const auto & primitive = primitives[i]; - switch (static_cast(primitive.type)) + switch (static_cast(primitive.type)) { case MotionType::LINEAR_JOINT: RCLCPP_INFO(get_node()->get_logger(), "Primitive %zu: LINEAR_JOINT (PTP)", i); @@ -473,7 +471,7 @@ void MotionPrimitivesForwardController::goal_accepted_callback( if (primitives.size() > 1) { MotionPrimitive start_marker; - start_marker.type = static_cast(MotionType::MOTION_SEQUENCE_START); + start_marker.type = static_cast(MotionHelperType::MOTION_SEQUENCE_START); if (!moprim_queue_.push(start_marker)) { RCLCPP_WARN( @@ -483,7 +481,7 @@ void MotionPrimitivesForwardController::goal_accepted_callback( add_motions(primitives); MotionPrimitive end_marker; - end_marker.type = static_cast(MotionType::MOTION_SEQUENCE_END); + end_marker.type = static_cast(MotionHelperType::MOTION_SEQUENCE_END); if (!moprim_queue_.push(end_marker)) { RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion sequence end marker to queue."); From 1669026b6dad022292be7852b2b633bddbca31f3 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 13:23:12 +0200 Subject: [PATCH 075/128] increased moprim_queue_ capacity to 1024 --- .../motion_primitives_forward_controller.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 86df5dbd9d..55dfe3e871 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -90,7 +90,7 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle motion_primitives_forward_controller::Params params_; using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; - realtime_tools::LockFreeSPSCQueue moprim_queue_; + realtime_tools::LockFreeSPSCQueue moprim_queue_; using ExecuteMotionAction = industrial_robot_motion_interfaces::action::ExecuteMotion; rclcpp_action::Server::SharedPtr action_server_; From a4c13673435f9e20a7b30dded9c06dce6547e885 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Jul 2025 18:55:41 +0200 Subject: [PATCH 076/128] using ros-controls/control_msgs#228 instead of industrial_robot_motion_interfaces --- motion_primitives_forward_controller/CMakeLists.txt | 2 -- motion_primitives_forward_controller/README.md | 2 +- .../motion_primitives_forward_controller.hpp | 10 +++++----- motion_primitives_forward_controller/package.xml | 1 - .../test/test_motion_primitives_forward_controller.hpp | 8 ++++---- ros2_controllers.rolling.repos | 4 ++-- 6 files changed, 12 insertions(+), 15 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 0f5ab87f9d..97ecb81250 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -14,7 +14,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS rclcpp_lifecycle realtime_tools std_srvs - industrial_robot_motion_interfaces ) find_package(ament_cmake REQUIRED) @@ -45,7 +44,6 @@ target_link_libraries(motion_primitives_forward_controller PUBLIC realtime_tools::realtime_tools ${control_msgs_TARGETS} ${std_srvs_TARGETS} - ${industrial_robot_motion_interfaces_TARGETS} ) target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 54a62d5b14..94edf30d6e 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -6,7 +6,7 @@ Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ) [![Licence](https://img.shields.io/badge/License-Apache-2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) -This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotion.action` action from the [industrial_robot_motion_interfaces](https://github.com/UniversalRobots/industrial_robot_motion_interfaces) package. The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. +This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotionPrimitiveSequence.action` action from [control_msgs](https://github.com/ros-controls/control_msgs/blob/motion_primitives/control_msgs/action/ExecuteMotionPrimitiveSequence.action). The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. - Supported motion primitives: - `LINEAR_JOINT` diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 55dfe3e871..88b68f853d 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -31,8 +31,8 @@ #include "realtime_tools/realtime_buffer.hpp" #include "realtime_tools/realtime_publisher.hpp" -#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "control_msgs/action/execute_motion_primitive_sequence.hpp" +#include "control_msgs/msg/motion_primitive.hpp" #include "rclcpp_action/rclcpp_action.hpp" namespace motion_primitives_forward_controller @@ -46,7 +46,7 @@ enum class ExecutionState : uint8_t STOPPED = 4 }; -using MotionType = industrial_robot_motion_interfaces::msg::MotionPrimitive; +using MotionType = control_msgs::msg::MotionPrimitive; enum class MotionHelperType : uint8_t { STOP_MOTION = 66, @@ -89,10 +89,10 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle std::shared_ptr param_listener_; motion_primitives_forward_controller::Params params_; - using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; + using MotionPrimitive = control_msgs::msg::MotionPrimitive; realtime_tools::LockFreeSPSCQueue moprim_queue_; - using ExecuteMotionAction = industrial_robot_motion_interfaces::action::ExecuteMotion; + using ExecuteMotionAction = control_msgs::action::ExecuteMotionPrimitiveSequence; rclcpp_action::Server::SharedPtr action_server_; rclcpp_action::GoalResponse goal_received_callback( const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index d4406cc736..e4f63d8265 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -26,7 +26,6 @@ controller_interface hardware_interface pluginlib - industrial_robot_motion_interfaces rclcpp rclcpp_lifecycle realtime_tools diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index d0e06ace19..5915f37041 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -41,11 +41,11 @@ #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" -#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "control_msgs/action/execute_motion_primitive_sequence.hpp" +#include "control_msgs/msg/motion_primitive.hpp" -using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; -using ExecuteMotion = industrial_robot_motion_interfaces::action::ExecuteMotion; +using MotionPrimitive = control_msgs::msg::MotionPrimitive; +using ExecuteMotion = control_msgs::action::ExecuteMotionPrimitiveSequence; namespace { diff --git a/ros2_controllers.rolling.repos b/ros2_controllers.rolling.repos index f6462c4b4f..d53c3fe358 100644 --- a/ros2_controllers.rolling.repos +++ b/ros2_controllers.rolling.repos @@ -9,8 +9,8 @@ repositories: version: master control_msgs: type: git - url: https://github.com/ros-controls/control_msgs.git - version: master + url: https://github.com/urfeex/control_msgs.git + version: motion_primitives control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git From 371fb5085600651781c49309ea49d741c95ce5e7 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Jul 2025 11:07:55 +0200 Subject: [PATCH 077/128] Add export and install for parameter library --- .../CMakeLists.txt | 46 ++++++++++--------- 1 file changed, 25 insertions(+), 21 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 97ecb81250..0e82e7deaf 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -35,15 +35,15 @@ target_include_directories(motion_primitives_forward_controller PUBLIC $ ) target_link_libraries(motion_primitives_forward_controller PUBLIC - motion_primitives_forward_controller_parameters - controller_interface::controller_interface - hardware_interface::hardware_interface - pluginlib::pluginlib - rclcpp::rclcpp - rclcpp_lifecycle::rclcpp_lifecycle - realtime_tools::realtime_tools - ${control_msgs_TARGETS} - ${std_srvs_TARGETS} + motion_primitives_forward_controller_parameters + controller_interface::controller_interface + hardware_interface::hardware_interface + pluginlib::pluginlib + rclcpp::rclcpp + rclcpp_lifecycle::rclcpp_lifecycle + realtime_tools::realtime_tools + ${control_msgs_TARGETS} + ${std_srvs_TARGETS} ) target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") @@ -54,15 +54,31 @@ pluginlib_export_plugin_description_file( install( TARGETS motion_primitives_forward_controller + motion_primitives_forward_controller_parameters + EXPORT motion_primitives_forward_controller_targets RUNTIME DESTINATION bin ARCHIVE DESTINATION lib LIBRARY DESTINATION lib ) + install( DIRECTORY include/ DESTINATION include/${PROJECT_NAME} ) +ament_export_targets(motion_primitives_forward_controller_targets HAS_LIBRARY_TARGET) + +ament_export_include_directories( + include +) +ament_export_dependencies( + ${THIS_PACKAGE_INCLUDE_DEPENDS} +) +ament_export_libraries( + motion_primitives_forward_controller +) + +ament_package() if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) @@ -104,15 +120,3 @@ if(BUILD_TESTING) ros2_control_test_assets::ros2_control_test_assets ) endif() - -ament_export_include_directories( - include -) -ament_export_dependencies( - ${THIS_PACKAGE_INCLUDE_DEPENDS} -) -ament_export_libraries( - motion_primitives_forward_controller -) - -ament_package() From a8bcee31945c921b1d20d0777cc44bdbecf00b4f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Jul 2025 11:26:29 +0200 Subject: [PATCH 078/128] control_msgs in ros2_controllers.rolling.repos needs to get changed back after control_msg PR is merged --- ros2_controllers.rolling.repos | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ros2_controllers.rolling.repos b/ros2_controllers.rolling.repos index d53c3fe358..f4ee54e9c3 100644 --- a/ros2_controllers.rolling.repos +++ b/ros2_controllers.rolling.repos @@ -11,6 +11,8 @@ repositories: type: git url: https://github.com/urfeex/control_msgs.git version: motion_primitives + # url: https://github.com/ros-controls/control_msgs.git + # version: master control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git From 5e955d3dfcce52970f3c2bb35373bf8e6efb1af7 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Jul 2025 15:59:12 +0200 Subject: [PATCH 079/128] pre-commit fixes --- motion_primitives_forward_controller/CMakeLists.txt | 2 +- .../src/motion_primitives_forward_controller.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 2cdb8619b9..ca606ea599 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -136,4 +136,4 @@ if(BUILD_TESTING) hardware_interface::hardware_interface ros2_control_test_assets::ros2_control_test_assets ) -endif() \ No newline at end of file +endif() diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index b6925d7e3b..238c2e3b87 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -512,4 +512,4 @@ void MotionPrimitivesForwardController::goal_accepted_callback( PLUGINLIB_EXPORT_CLASS( motion_primitives_forward_controller::MotionPrimitivesForwardController, - controller_interface::ControllerInterface) \ No newline at end of file + controller_interface::ControllerInterface) From aa3112ed74b991770515c464a7422da5fc01e42e Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 9 Jul 2025 18:02:54 +0200 Subject: [PATCH 080/128] modified moprim_from_traj_controller according to moprim_forward_controller --- .../CMakeLists.txt | 13 ++ .../approx_primitives_with_rdp.hpp | 8 +- ..._primitives_from_trajectory_controller.hpp | 32 +++-- .../src/approx_primitives_with_rdp.cpp | 6 +- ..._primitives_from_trajectory_controller.cpp | 132 ++++++++---------- 5 files changed, 96 insertions(+), 95 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index ca606ea599..e9bc2ed52c 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -97,6 +97,19 @@ install( DESTINATION include/${PROJECT_NAME} ) +ament_export_include_directories( + include +) +ament_export_dependencies( + ${THIS_PACKAGE_INCLUDE_DEPENDS} +) +ament_export_libraries( + motion_primitives_forward_controller + motion_primitives_from_trajectory_controller +) + +ament_package() + if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(controller_manager REQUIRED) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index d738cdb1f0..2468e61e9c 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -19,13 +19,13 @@ #include #include +#include "control_msgs/msg/motion_argument.hpp" +#include "control_msgs/msg/motion_primitive.hpp" +#include "control_msgs/msg/motion_primitive_sequence.hpp" #include "geometry_msgs/msg/pose.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_argument.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_sequence.hpp" #include "motion_primitives_forward_controller/rdp.hpp" -using MotionSequence = industrial_robot_motion_interfaces::msg::MotionSequence; +using MotionSequence = control_msgs::msg::MotionPrimitiveSequence; namespace approx_primitives_with_rdp { diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index d8ad394db6..8d28e7d98e 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -17,22 +17,24 @@ #ifndef MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ #define MOTION_PRIMITIVES_FORWARD_CONTROLLER__MOTION_PRIMITIVES_FROM_TRAJECTORY_CONTROLLER_HPP_ +#include #include -#include #include #include #include +#include +#include #include "control_msgs/action/follow_joint_trajectory.hpp" #include "controller_interface/controller_interface.hpp" -#include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" #include "realtime_tools/realtime_publisher.hpp" -#include "industrial_robot_motion_interfaces/action/execute_motion.hpp" -#include "industrial_robot_motion_interfaces/msg/motion_primitive.hpp" +#include "control_msgs/action/execute_motion_primitive_sequence.hpp" +#include "control_msgs/msg/motion_primitive.hpp" +#include "rclcpp_action/rclcpp_action.hpp" #include "motion_primitives_forward_controller/approx_primitives_with_rdp.hpp" #include "motion_primitives_forward_controller/fk_client.hpp" @@ -48,12 +50,9 @@ enum class ExecutionState : uint8_t STOPPED = 4 }; -enum class MotionType : uint8_t +using MotionType = control_msgs::msg::MotionPrimitive; +enum class MotionHelperType : uint8_t { - LINEAR_JOINT = 10, - LINEAR_CARTESIAN = 50, - CIRCULAR_CARTESIAN = 51, - STOP_MOTION = 66, RESET_STOP = 67, @@ -94,8 +93,8 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co std::shared_ptr param_listener_; motion_primitives_forward_controller::Params params_; - using MotionPrimitive = industrial_robot_motion_interfaces::msg::MotionPrimitive; - std::queue> moprim_queue_; + using MotionPrimitive = control_msgs::msg::MotionPrimitive; + realtime_tools::LockFreeSPSCQueue moprim_queue_; using FollowJTrajAction = control_msgs::action::FollowJointTrajectory; rclcpp_action::Server::SharedPtr action_server_; @@ -104,8 +103,11 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co rclcpp_action::CancelResponse goal_cancelled_callback( const std::shared_ptr> goal_handle); void goal_accepted_callback( - const std::shared_ptr> goal_handle); - std::shared_ptr> pending_action_goal_; + std::shared_ptr> goal_handle); + using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle; + std::shared_ptr realtime_goal_handle_; + rclcpp::TimerBase::SharedPtr goal_handle_timer_; + rclcpp::Duration action_monitor_period_ = rclcpp::Duration(std::chrono::milliseconds(20)); void reset_command_interfaces(); bool set_command_interfaces(); @@ -119,11 +121,11 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co ExecutionState execution_status_; ReadyForNewPrimitive ready_for_new_primitive_; - std::atomic moprim_queue_write_enabled_ = false; + MotionPrimitive current_moprim_; std::shared_ptr fk_client_; - MotionType approx_type_ = MotionType::LINEAR_CARTESIAN; + uint8_t approx_type_ = MotionType::LINEAR_CARTESIAN; // ############ Function copied from JointTrajectoryController ############ // TODO(mathias31415): Is there a cleaner solution? diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 72c87ae9b9..e9533da615 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -19,11 +19,11 @@ #include #include +using control_msgs::msg::MotionArgument; +using control_msgs::msg::MotionPrimitive; +using control_msgs::msg::MotionPrimitiveSequence; using geometry_msgs::msg::Pose; using geometry_msgs::msg::PoseStamped; -using industrial_robot_motion_interfaces::msg::MotionArgument; -using industrial_robot_motion_interfaces::msg::MotionPrimitive; -using industrial_robot_motion_interfaces::msg::MotionSequence; namespace approx_primitives_with_rdp { diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 061a137bed..da90451909 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -40,7 +40,9 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o } catch (const std::exception & e) { - fprintf(stderr, "Exception thrown during controller's init with message: %s \n", e.what()); + RCLCPP_ERROR( + get_node()->get_logger(), "Exception thrown during controller's init with message: %s \n", + e.what()); return controller_interface::CallbackReturn::ERROR; } @@ -126,7 +128,6 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o const rclcpp_lifecycle::State & /*previous_state*/) { reset_command_interfaces(); - moprim_queue_write_enabled_ = true; RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; } @@ -150,11 +151,9 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda cancel_requested_ = false; reset_command_interfaces(); // send stop command immediately to the hw-interface - (void)command_interfaces_[0].set_value(static_cast(MotionType::STOP_MOTION)); - while (!moprim_queue_.empty()) - { // clear the queue - moprim_queue_.pop(); - } + (void)command_interfaces_[0].set_value(static_cast(MotionHelperType::STOP_MOTION)); + // clear the queue (ignore return value) + static_cast(moprim_queue_.get_latest(current_moprim_)); robot_stop_requested_ = true; } @@ -185,31 +184,27 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda case ExecutionState::SUCCESS: print_error_once_ = true; - if (pending_action_goal_ && was_executing_) + if (realtime_goal_handle_ && was_executing_) { was_executing_ = false; auto result = std::make_shared(); result->error_code = FollowJTrajAction::Result::SUCCESSFUL; result->error_string = "Motion primitives executed successfully"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); + realtime_goal_handle_->setSucceeded(result); + realtime_goal_handle_.reset(); RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); } - break; case ExecutionState::STOPPED: print_error_once_ = true; was_executing_ = false; - if (pending_action_goal_) + if (realtime_goal_handle_) { auto result = std::make_shared(); - // result->error_code = FollowJTrajAction::Result::CANCELED; - result->error_code = 69; - result->error_string = "Motion primitives execution canceled"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); + realtime_goal_handle_->setCanceled(result); + realtime_goal_handle_.reset(); RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); } @@ -218,27 +213,15 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda // If the robot was stopped by a stop command, reset the command interfaces // to allow new motion primitives to be sent. reset_command_interfaces(); - (void)command_interfaces_[0].set_value(static_cast(MotionType::RESET_STOP)); + (void)command_interfaces_[0].set_value(static_cast(MotionHelperType::RESET_STOP)); robot_stop_requested_ = false; - moprim_queue_write_enabled_ = true; RCLCPP_INFO(get_node()->get_logger(), "Robot stopped, ready for new motion primitives."); } + break; case ExecutionState::ERROR: was_executing_ = false; - - if (pending_action_goal_) - { - auto result = std::make_shared(); - // result->error_code = FollowJTrajAction::Result::FAILED; - result->error_code = 404; - result->error_string = "Motion primitives execution failed"; - pending_action_goal_->succeed(result); - pending_action_goal_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution failed"); - } - if (print_error_once_) { RCLCPP_ERROR(get_node()->get_logger(), "Execution state: ERROR"); @@ -263,7 +246,7 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda ready_for_new_primitive_ = static_cast(static_cast(std::round(opt_value_ready.value()))); - if (!moprim_queue_write_enabled_ && !cancel_requested_) + if (!cancel_requested_) { switch (ready_for_new_primitive_) { @@ -275,8 +258,6 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda { if (moprim_queue_.empty()) // check if new command is available { - // all primitives read, queue ready to get filled with new primitives - moprim_queue_write_enabled_ = true; return controller_interface::return_type::OK; } else @@ -315,32 +296,28 @@ void MotionPrimitivesFromTrajectoryController::reset_command_interfaces() bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() { // Get the oldest message from the queue - std::shared_ptr current_moprim = moprim_queue_.front(); - moprim_queue_.pop(); - - // Check if the message is valid - if (!current_moprim) + if (!moprim_queue_.pop(current_moprim_)) { - RCLCPP_WARN(get_node()->get_logger(), "No valid reference message received"); + RCLCPP_WARN(get_node()->get_logger(), "Failed to pop motion primitive from queue."); return false; } // Set the motion_type - (void)command_interfaces_[0].set_value(static_cast(current_moprim->type)); + (void)command_interfaces_[0].set_value(static_cast(current_moprim_.type)); // Process joint positions if available - if (!current_moprim->joint_positions.empty()) + if (!current_moprim_.joint_positions.empty()) { - for (size_t i = 0; i < current_moprim->joint_positions.size(); ++i) + for (size_t i = 0; i < current_moprim_.joint_positions.size(); ++i) { - (void)command_interfaces_[i + 1].set_value(current_moprim->joint_positions[i]); // q1 to q6 + (void)command_interfaces_[i + 1].set_value(current_moprim_.joint_positions[i]); // q1 to q6 } } // Process Cartesian poses if available - if (!current_moprim->poses.empty()) + if (!current_moprim_.poses.empty()) { - const auto & goal_pose = current_moprim->poses[0].pose; // goal pose + const auto & goal_pose = current_moprim_.poses[0].pose; // goal pose (void)command_interfaces_[7].set_value(goal_pose.position.x); // pos_x (void)command_interfaces_[8].set_value(goal_pose.position.y); // pos_y (void)command_interfaces_[9].set_value(goal_pose.position.z); // pos_z @@ -350,11 +327,9 @@ bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() (void)command_interfaces_[13].set_value(goal_pose.orientation.w); // pos_qw // Process via poses if available (only for circular motion) - if ( - current_moprim->type == static_cast(MotionType::CIRCULAR_CARTESIAN) && - current_moprim->poses.size() == 2) + if (current_moprim_.type == MotionType::CIRCULAR_CARTESIAN && current_moprim_.poses.size() == 2) { - const auto & via_pose = current_moprim->poses[1].pose; // via pose + const auto & via_pose = current_moprim_.poses[1].pose; // via pose (void)command_interfaces_[14].set_value(via_pose.position.x); // pos_via_x (void)command_interfaces_[15].set_value(via_pose.position.y); // pos_via_y (void)command_interfaces_[16].set_value(via_pose.position.z); // pos_via_z @@ -365,10 +340,10 @@ bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() } } - (void)command_interfaces_[21].set_value(current_moprim->blend_radius); // blend_radius + (void)command_interfaces_[21].set_value(current_moprim_.blend_radius); // blend_radius // Read additional arguments - for (const auto & arg : current_moprim->additional_arguments) + for (const auto & arg : current_moprim_.additional_arguments) { if (arg.argument_name == "velocity") { @@ -402,12 +377,7 @@ rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_recei return rclcpp_action::GoalResponse::REJECT; } - if (!moprim_queue_write_enabled_) - { - RCLCPP_WARN( - get_node()->get_logger(), "Queue is not ready to write. Discarding the new command."); - return rclcpp_action::GoalResponse::REJECT; - } + // TODO(mathias31415): Check if queue has enough space? Number of primitives not known here? if (goal->trajectory.points.empty()) { @@ -424,18 +394,16 @@ rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_recei rclcpp_action::CancelResponse MotionPrimitivesFromTrajectoryController::goal_cancelled_callback( const std::shared_ptr>) { + RCLCPP_INFO(get_node()->get_logger(), "Got request to cancel goal"); cancel_requested_ = true; - moprim_queue_write_enabled_ = false; return rclcpp_action::CancelResponse::ACCEPT; } void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( - const std::shared_ptr> goal_handle) + std::shared_ptr> goal_handle) { RCLCPP_INFO(get_node()->get_logger(), "Processing accepted goal ..."); - pending_action_goal_ = goal_handle; // Store the goal handle for later result feedback - auto trajectory_msg = std::make_shared(goal_handle->get_goal()->trajectory); @@ -469,7 +437,7 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } planned_trajectory_data.push_back(pt); } - industrial_robot_motion_interfaces::msg::MotionSequence motion_sequence; + control_msgs::msg::MotionPrimitiveSequence motion_sequence; double rdp_epsilon = 0.001; bool use_time_not_vel_and_acc = true; switch (approx_type_) @@ -495,32 +463,50 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( break; } - auto add_motions = - [this](const industrial_robot_motion_interfaces::msg::MotionSequence & moprim_sequence) + auto add_motions = [this](const control_msgs::msg::MotionPrimitiveSequence & moprim_sequence) { for (const auto & primitive : moprim_sequence.motions) { - moprim_queue_.push(std::make_shared(primitive)); + if (!moprim_queue_.push(primitive)) + { + RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion primitive to queue."); + } } }; if (motion_sequence.motions.size() > 1) { - std::shared_ptr start_marker = std::make_shared(); - start_marker->type = static_cast(MotionType::MOTION_SEQUENCE_START); - moprim_queue_.push(start_marker); + MotionPrimitive start_marker; + start_marker.type = static_cast(MotionHelperType::MOTION_SEQUENCE_START); + if (!moprim_queue_.push(start_marker)) + { + RCLCPP_WARN( + get_node()->get_logger(), "Failed to push motion sequence start marker to queue."); + } add_motions(motion_sequence); - std::shared_ptr end_marker = std::make_shared(); - end_marker->type = static_cast(MotionType::MOTION_SEQUENCE_END); - moprim_queue_.push(end_marker); + MotionPrimitive end_marker; + end_marker.type = static_cast(MotionHelperType::MOTION_SEQUENCE_END); + if (!moprim_queue_.push(end_marker)) + { + RCLCPP_WARN(get_node()->get_logger(), "Failed to push motion sequence end marker to queue."); + } } else { add_motions(motion_sequence); } - moprim_queue_write_enabled_ = false; + + auto rt_goal = std::make_shared(goal_handle); + realtime_goal_handle_ = rt_goal; + + rt_goal->execute(); + + goal_handle_timer_.reset(); + goal_handle_timer_ = get_node()->create_wall_timer( + action_monitor_period_.to_chrono(), + std::bind(&RealtimeGoalHandle::runNonRealtime, rt_goal)); RCLCPP_INFO( get_node()->get_logger(), From d2df2befb1356102858bab565ade5655c9bde9a1 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 14 Jul 2025 11:30:37 +0200 Subject: [PATCH 081/128] added param file for moprim_from_traj_controller --- .../CMakeLists.txt | 17 +++++++++++++-- ..._primitives_from_trajectory_controller.hpp | 2 +- ...primitives_from_trajectory_controller.yaml | 21 +++++++++++++++++++ 3 files changed, 37 insertions(+), 3 deletions(-) create mode 100644 motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index e9bc2ed52c..bfe823621c 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -27,6 +27,9 @@ endforeach() generate_parameter_library(motion_primitives_forward_controller_parameters src/motion_primitives_forward_controller.yaml ) +generate_parameter_library(motion_primitives_from_trajectory_controller_parameters + src/motion_primitives_from_trajectory_controller.yaml +) add_library( motion_primitives_forward_controller SHARED @@ -60,7 +63,7 @@ target_link_libraries(motion_primitives_forward_controller PUBLIC ${std_srvs_TARGETS} ) target_link_libraries(motion_primitives_from_trajectory_controller PUBLIC - motion_primitives_forward_controller_parameters + motion_primitives_from_trajectory_controller_parameters controller_interface::controller_interface hardware_interface::hardware_interface pluginlib::pluginlib @@ -84,13 +87,23 @@ pluginlib_export_plugin_description_file( install( TARGETS motion_primitives_forward_controller - motion_primitives_from_trajectory_controller motion_primitives_forward_controller_parameters EXPORT motion_primitives_forward_controller_targets RUNTIME DESTINATION bin ARCHIVE DESTINATION lib LIBRARY DESTINATION lib ) +install( + TARGETS + motion_primitives_from_trajectory_controller + motion_primitives_from_trajectory_controller_parameters + EXPORT motion_primitives_from_trajectory_controller_targets + RUNTIME DESTINATION bin + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib +) +ament_export_targets(motion_primitives_forward_controller_targets) +ament_export_targets(motion_primitives_from_trajectory_controller_targets) install( DIRECTORY include/ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 8d28e7d98e..288a913988 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -22,7 +22,7 @@ #include #include -#include +#include #include #include #include "control_msgs/action/follow_joint_trajectory.hpp" diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml new file mode 100644 index 0000000000..b0c0aaa38d --- /dev/null +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml @@ -0,0 +1,21 @@ +motion_primitives_forward_controller: + command_interfaces: { + type: string_array, + default_value: [], + description: "Names of the command interfaces used by the controller.", + read_only: true, + validation: { + unique<>: null, + not_empty<>: null, + } + } + state_interfaces: { + type: string_array, + default_value: [], + description: "Names of the state interfaces used by the controller.", + read_only: true, + validation: { + unique<>: null, + not_empty<>: null, + } + } From 61c638ef1c63a4f2274b6ef36e052a550cfa2f47 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 14 Jul 2025 13:59:43 +0200 Subject: [PATCH 082/128] motion_primitive_from_trajectory_controller: Added params for local_joint_order, approximate_mode, use_time_not_vel_and_acc, epsilon_joint_angle, epsilon_cart_position, epsilon_cart_angle --- .../approx_primitives_with_rdp.hpp | 4 +- ..._primitives_from_trajectory_controller.hpp | 12 ++++- .../src/approx_primitives_with_rdp.cpp | 8 +-- ..._primitives_from_trajectory_controller.cpp | 54 +++++++++++++------ ...primitives_from_trajectory_controller.yaml | 43 +++++++++++++++ 5 files changed, 98 insertions(+), 23 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index 2468e61e9c..7757e6f895 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -39,8 +39,8 @@ struct PlannedTrajectoryPoint // Approximate with LIN Primitives in Cartesian Space MotionSequence approxLinPrimitivesWithRDP( - const std::vector & trajectory, double epsilon, - bool use_time_not_vel_and_acc = false); + const std::vector & trajectory, double epsilon_position, + double epsilon_angle, bool use_time_not_vel_and_acc = false); // Approximate with PTP Primitives in Joint Space MotionSequence approxPtpPrimitivesWithRDP( diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 288a913988..3c1a446d63 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -66,6 +66,12 @@ enum class ReadyForNewPrimitive : uint8_t READY = 1 }; +enum class ApproxMode +{ + RDP_PTP, + RDP_LIN +}; + class MotionPrimitivesFromTrajectoryController : public controller_interface::ControllerInterface { public: @@ -125,7 +131,11 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co std::shared_ptr fk_client_; - uint8_t approx_type_ = MotionType::LINEAR_CARTESIAN; + ApproxMode approx_mode_; + bool use_time_not_vel_and_acc_; + double epsilon_joint_angle_; + double epsilon_cart_position_; + double epsilon_cart_angle_; // ############ Function copied from JointTrajectoryController ############ // TODO(mathias31415): Is there a cleaner solution? diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index e9533da615..43c8ca97fe 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -30,7 +30,7 @@ namespace approx_primitives_with_rdp MotionSequence approxLinPrimitivesWithRDP( const std::vector & trajectory, - double epsilon, bool use_time_not_vel_and_acc) + double epsilon_position, double epsilon_angle, bool use_time_not_vel_and_acc) { MotionSequence motion_sequence; std::vector motion_primitives; @@ -47,7 +47,7 @@ MotionSequence approxLinPrimitivesWithRDP( points.push_back({point.pose.position.x, point.pose.position.y, point.pose.position.z}); } - auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon); + auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon_position); for (size_t i = 1; i < reduced_points.size(); ++i) { @@ -97,7 +97,7 @@ MotionSequence approxLinPrimitivesWithRDP( pose_stamped.pose.position.x = reduced_points[i][0]; pose_stamped.pose.position.y = reduced_points[i][1]; pose_stamped.pose.position.z = reduced_points[i][2]; - // TODO(mathias31415): Also use RDP for orientation + // TODO(mathias31415): Also use RDP for orientation? With epsilon_angle pose_stamped.pose.orientation = trajectory[reduced_indices[i]].pose.orientation; primitive.poses.push_back(pose_stamped); @@ -116,7 +116,7 @@ MotionSequence approxLinPrimitivesWithRDP( motion_sequence.motions = motion_primitives; std::cout << "Reduced " << points.size() << " points to " << (reduced_points.size() - 1) - << " LIN primitives with epsilon=" << epsilon << std::endl; + << " LIN primitives with epsilon=" << epsilon_position << std::endl; return motion_sequence; } diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index da90451909..79c554d880 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -57,6 +57,33 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o params_ = param_listener_->get_params(); + if (params_.local_joint_order.size() != 6) + { + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Exactly 6 joints must be provided in local_joint_order!"); + return controller_interface::CallbackReturn::ERROR; + } + + if (params_.approximate_mode == "RDP_PTP") + { + approx_mode_ = ApproxMode::RDP_PTP; + } + else if (params_.approximate_mode == "RDP_LIN") + { + approx_mode_ = ApproxMode::RDP_LIN; + } + else + { + RCLCPP_ERROR( + get_node()->get_logger(), "Error: Unknown approximate mode '%s'", + params_.approximate_mode.c_str()); + return controller_interface::CallbackReturn::ERROR; + } + use_time_not_vel_and_acc_ = params_.use_time_not_vel_and_acc; + epsilon_joint_angle_ = params_.epsilon_joint_angle; + epsilon_cart_position_ = params_.epsilon_cart_position; + epsilon_cart_angle_ = params_.epsilon_cart_angle; + // Check if there are exactly 25 command interfaces if (params_.command_interfaces.size() != 25) { // motion_type + 6 joints + 2*7 positions + blend_radius + velocity + acceleration + move_time @@ -438,24 +465,23 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( planned_trajectory_data.push_back(pt); } control_msgs::msg::MotionPrimitiveSequence motion_sequence; - double rdp_epsilon = 0.001; - bool use_time_not_vel_and_acc = true; - switch (approx_type_) + switch (approx_mode_) { - case MotionType::LINEAR_JOINT: + case ApproxMode::RDP_PTP: { RCLCPP_INFO( get_node()->get_logger(), "Approximating motion primitives with PTP motion primitives."); - motion_sequence = - approxPtpPrimitivesWithRDP(planned_trajectory_data, rdp_epsilon, use_time_not_vel_and_acc); + motion_sequence = approxPtpPrimitivesWithRDP( + planned_trajectory_data, epsilon_joint_angle_, use_time_not_vel_and_acc_); break; } - case MotionType::LINEAR_CARTESIAN: + case ApproxMode::RDP_LIN: { RCLCPP_INFO( get_node()->get_logger(), "Approximating motion primitives with LIN motion primitives."); - motion_sequence = - approxLinPrimitivesWithRDP(planned_trajectory_data, rdp_epsilon, use_time_not_vel_and_acc); + motion_sequence = approxLinPrimitivesWithRDP( + planned_trajectory_data, epsilon_cart_position_, epsilon_cart_angle_, + use_time_not_vel_and_acc_); break; } default: @@ -514,15 +540,11 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( trajectory_msg->points.size(), motion_sequence.motions.size()); } -// TODO(mathias31415): read local_joint_order from param instead void MotionPrimitivesFromTrajectoryController::sort_to_local_joint_order( std::shared_ptr trajectory_msg) const { - const std::vector local_joint_order = {"shoulder_pan_joint", "shoulder_lift_joint", - "elbow_joint", "wrist_1_joint", - "wrist_2_joint", "wrist_3_joint"}; - - std::vector mapping_vector = mapping(trajectory_msg->joint_names, local_joint_order); + std::vector mapping_vector = + mapping(trajectory_msg->joint_names, params_.local_joint_order); auto remap = [this]( const std::vector & to_remap, @@ -563,7 +585,7 @@ void MotionPrimitivesFromTrajectoryController::sort_to_local_joint_order( if (!point.effort.empty()) point.effort = remap(point.effort, mapping_vector); } - trajectory_msg->joint_names = local_joint_order; + trajectory_msg->joint_names = params_.local_joint_order; } } // namespace motion_primitives_from_trajectory_controller diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml index b0c0aaa38d..4861cf84a8 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml @@ -19,3 +19,46 @@ motion_primitives_forward_controller: not_empty<>: null, } } + local_joint_order: { + type: string_array, + default_value: [], + description: "Local joint order used internally by the controller.", + read_only: false, + validation: { + unique<>: null, + not_empty<>: null, + } + } + approximate_mode: { + type: string, + default_value: "RDP_PTP", + description: "Approximation mode for motion primitives: 'RDP_PTP' or 'RDP_LIN'.", + read_only: false, + validation: { + not_empty<>: [] + } + } + use_time_not_vel_and_acc: { + type: bool, + default_value: false, + description: "If true, uses time for motion primitives (e.g., UR); if false, uses velocity and acceleration (e.g., UR, KUKA).", + read_only: false + } + epsilon_joint_angle: { + type: double, + default_value: 0.0, + description: "Epsilon for RDP simplification in joint space (angle difference threshold).", + read_only: false + } + epsilon_cart_position: { + type: double, + default_value: 0.0, + description: "Epsilon for RDP simplification in Cartesian space (position threshold).", + read_only: false + } + epsilon_cart_angle: { + type: double, + default_value: 0.0, + description: "Epsilon for RDP simplification in Cartesian space (orientation angle threshold).", + read_only: false + } From b05520586cd0ca3a0083b9eb660dd7bd4cfd6965 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 14 Jul 2025 16:30:55 +0200 Subject: [PATCH 083/128] calculate cart vel and acc from time_from_start --- .../approx_primitives_with_rdp.hpp | 4 + .../src/approx_primitives_with_rdp.cpp | 106 ++++++++++++++++-- 2 files changed, 101 insertions(+), 9 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index 7757e6f895..4d0ddf152c 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -51,6 +51,10 @@ double calculateBlendRadius( const rdp::Point & previous_point, const rdp::Point & current_point, const rdp::Point & next_point); +void calculateCartVelAndAcc( + const std::vector & trajectory, + std::vector & velocities, std::vector & accelerations); + } // namespace approx_primitives_with_rdp #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 43c8ca97fe..8b8c77a457 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -41,19 +41,25 @@ MotionSequence approxLinPrimitivesWithRDP( return motion_sequence; } - rdp::PointList points; + rdp::PointList cartesian_points; for (const auto & point : trajectory) { - points.push_back({point.pose.position.x, point.pose.position.y, point.pose.position.z}); + cartesian_points.push_back( + {point.pose.position.x, point.pose.position.y, point.pose.position.z}); } - auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon_position); + auto [reduced_points, reduced_indices] = rdp::rdpRecursive(cartesian_points, epsilon_position); + + // Compute cartesian velocity and acceleration between trajectory points + std::vector velocities, accelerations; + calculateCartVelAndAcc(trajectory, velocities, accelerations); for (size_t i = 1; i < reduced_points.size(); ++i) { MotionPrimitive primitive; primitive.type = MotionPrimitive::LINEAR_CARTESIAN; + // Blend radius (zero at last point) if (i == reduced_points.size() - 1) { primitive.blend_radius = 0.0; @@ -63,13 +69,18 @@ MotionSequence approxLinPrimitivesWithRDP( primitive.blend_radius = calculateBlendRadius(reduced_points[i - 1], reduced_points[i], reduced_points[i + 1]); } + double velocity = -1.0; double acceleration = -1.0; double move_time = -1.0; + + const size_t start_index = reduced_indices[i - 1]; + const size_t end_index = reduced_indices[i]; + if (use_time_not_vel_and_acc) { - double prev_time = trajectory[reduced_indices[i - 1]].time_from_start; - double curr_time = trajectory[reduced_indices[i]].time_from_start; + const double prev_time = trajectory[start_index].time_from_start; + const double curr_time = trajectory[end_index].time_from_start; move_time = curr_time - prev_time; MotionArgument arg_time; arg_time.argument_name = "move_time"; @@ -78,9 +89,22 @@ MotionSequence approxLinPrimitivesWithRDP( } else { - // TODO(mathias31415): Calculate vel and acc based on time_from_start - velocity = 1.0; - acceleration = 1.0; + // Use max velocity and acceleration in the reduced segment + double max_vel = 0.0; + double max_acc = 0.0; + + for (size_t j = start_index + 1; j <= end_index && j - 1 < velocities.size(); ++j) + { + max_vel = std::max(max_vel, velocities[j - 1]); + } + + for (size_t j = start_index + 2; j <= end_index && j - 2 < accelerations.size(); ++j) + { + max_acc = std::max(max_acc, accelerations[j - 2]); + } + + velocity = max_vel; + acceleration = max_acc; MotionArgument arg_vel; arg_vel.argument_name = "velocity"; @@ -115,7 +139,8 @@ MotionSequence approxLinPrimitivesWithRDP( } motion_sequence.motions = motion_primitives; - std::cout << "Reduced " << points.size() << " points to " << (reduced_points.size() - 1) + + std::cout << "Reduced " << cartesian_points.size() << " points to " << (reduced_points.size() - 1) << " LIN primitives with epsilon=" << epsilon_position << std::endl; return motion_sequence; @@ -250,4 +275,67 @@ double calculateBlendRadius( return blend; } +void calculateCartVelAndAcc( + const std::vector & trajectory, + std::vector & velocities, std::vector & accelerations) +{ + velocities.clear(); + accelerations.clear(); + + size_t num_points = trajectory.size(); + if (num_points < 2) + { + std::cerr << "[calculateCartVelAndAcc] Warning: trajectory too short to calculate " + "velocity/acceleration." + << std::endl; + return; + } + + for (size_t i = 1; i < num_points; ++i) + { + const auto & previous_position = trajectory[i - 1].pose.position; + const auto & current_position = trajectory[i].pose.position; + + double previous_time = trajectory[i - 1].time_from_start; + double current_time = trajectory[i].time_from_start; + double delta_time = current_time - previous_time; + + if (delta_time <= 0.0) + { + std::cerr << "[calculateCartVelAndAcc] Warning: non-positive time difference at index " << i + << std::endl; + velocities.push_back(0.0); + continue; + } + + double dx = current_position.x - previous_position.x; + double dy = current_position.y - previous_position.y; + double dz = current_position.z - previous_position.z; + double distance = std::sqrt(dx * dx + dy * dy + dz * dz); + + double velocity = distance / delta_time; + velocities.push_back(velocity); + } + + // Accelerations (starts at index 1 because it compares velocities[i] and velocities[i - 1]) + for (size_t i = 1; i < velocities.size(); ++i) + { + double time_interval = trajectory[i + 1].time_from_start - trajectory[i].time_from_start; + + if (time_interval <= 0.0) + { + std::cerr << "[calculateCartVelAndAcc] Warning: non-positive time difference for " + "acceleration at index " + << i << std::endl; + accelerations.push_back(0.0); + continue; + } + + double delta_velocity = velocities[i] - velocities[i - 1]; + double acceleration = delta_velocity / time_interval; + + accelerations.push_back(std::abs(acceleration)); + } +} + } // namespace approx_primitives_with_rdp From 2f3e0ea73576d72194d8ab196d933bdb720b595a Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 14 Jul 2025 16:58:48 +0200 Subject: [PATCH 084/128] calculate joint vel and acc from time_from_start --- .../approx_primitives_with_rdp.hpp | 4 + .../src/approx_primitives_with_rdp.cpp | 92 ++++++++++++++++++- 2 files changed, 91 insertions(+), 5 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index 4d0ddf152c..1084e4d396 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -55,6 +55,10 @@ void calculateCartVelAndAcc( const std::vector & trajectory, std::vector & velocities, std::vector & accelerations); +void calculateJointVelAndAcc( + const std::vector & trajectory, + std::vector & velocities, std::vector & accelerations); + } // namespace approx_primitives_with_rdp #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 8b8c77a457..d517b7569a 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -167,6 +167,10 @@ MotionSequence approxPtpPrimitivesWithRDP( auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon); + // Compute joint velocities and accelerations between trajectory points + std::vector joint_velocities, joint_accelerations; + calculateJointVelAndAcc(trajectory, joint_velocities, joint_accelerations); + for (size_t i = 1; i < reduced_points.size(); ++i) { MotionPrimitive primitive; @@ -197,11 +201,16 @@ MotionSequence approxPtpPrimitivesWithRDP( double velocity = -1.0; double acceleration = -1.0; double move_time = -1.0; + + size_t start_index = reduced_indices[i - 1]; + size_t end_index = reduced_indices[i]; + if (use_time_not_vel_and_acc) { - double prev_time = trajectory[reduced_indices[i - 1]].time_from_start; - double curr_time = trajectory[reduced_indices[i]].time_from_start; + double prev_time = trajectory[start_index].time_from_start; + double curr_time = trajectory[end_index].time_from_start; move_time = curr_time - prev_time; + MotionArgument arg_time; arg_time.argument_name = "move_time"; arg_time.argument_value = move_time; @@ -209,9 +218,22 @@ MotionSequence approxPtpPrimitivesWithRDP( } else { - // TODO(mathias31415): Calculate vel and acc based on time_from_start - velocity = 1.0; - acceleration = 1.0; + // Get max velocity and acceleration in the reduced segment + double max_vel = 0.0; + double max_acc = 0.0; + + for (size_t j = start_index + 1; j <= end_index && j - 1 < joint_velocities.size(); ++j) + { + max_vel = std::max(max_vel, joint_velocities[j - 1]); + } + + for (size_t j = start_index + 2; j <= end_index && j - 2 < joint_accelerations.size(); ++j) + { + max_acc = std::max(max_acc, joint_accelerations[j - 2]); + } + + velocity = max_vel; + acceleration = max_acc; MotionArgument arg_vel; arg_vel.argument_name = "velocity"; @@ -240,6 +262,7 @@ MotionSequence approxPtpPrimitivesWithRDP( } motion_sequence.motions = motion_primitives; + std::cout << "Reduced " << points.size() << " joint points to " << (reduced_points.size() - 1) << " PTP primitives with epsilon=" << epsilon << std::endl; @@ -338,4 +361,63 @@ void calculateCartVelAndAcc( } } +void calculateJointVelAndAcc( + const std::vector & trajectory, + std::vector & velocities, std::vector & accelerations) +{ + velocities.clear(); + accelerations.clear(); + + size_t num_points = trajectory.size(); + if (num_points < 2) + { + std::cerr << "[calculateJointVelAndAcc] Warning: trajectory too short to calculate " + "joint velocity/acceleration." + << std::endl; + return; + } + + size_t num_joints = trajectory[0].joint_positions.size(); + + // Compute joint velocities (max per timestep across joints) + for (size_t i = 1; i < num_points; ++i) + { + double dt = trajectory[i].time_from_start - trajectory[i - 1].time_from_start; + if (dt <= 0.0) + { + std::cerr << "[calculateJointVelAndAcc] Warning: non-positive time diff at index " << i + << std::endl; + velocities.push_back(0.0); + continue; + } + + double max_joint_vel = 0.0; + for (size_t j = 0; j < num_joints; ++j) + { + double dq = trajectory[i].joint_positions[j] - trajectory[i - 1].joint_positions[j]; + double vel = std::abs(dq / dt); + if (vel > max_joint_vel) max_joint_vel = vel; + } + + velocities.push_back(max_joint_vel); + } + + // Compute joint accelerations (max per timestep across joints) + for (size_t i = 1; i < velocities.size(); ++i) + { + double dt = trajectory[i + 1].time_from_start - trajectory[i].time_from_start; + if (dt <= 0.0) + { + std::cerr + << "[calculateJointVelAndAcc] Warning: non-positive time diff for acceleration at index " + << i << std::endl; + accelerations.push_back(0.0); + continue; + } + + double dvel = velocities[i] - velocities[i - 1]; + accelerations.push_back(std::abs(dvel / dt)); + } +} + } // namespace approx_primitives_with_rdp From b9261a38a2e2eecd6e062fbc2d29291abac49e12 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 15 Jul 2025 10:11:33 +0200 Subject: [PATCH 085/128] Added publisher for planned_trajectory, planned_poses and motion_primitives --- ..._primitives_from_trajectory_controller.hpp | 6 +++++ ..._primitives_from_trajectory_controller.cpp | 22 +++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 3c1a446d63..cfb5271b44 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -34,6 +34,7 @@ #include "control_msgs/action/execute_motion_primitive_sequence.hpp" #include "control_msgs/msg/motion_primitive.hpp" +#include "geometry_msgs/msg/pose_array.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "motion_primitives_forward_controller/approx_primitives_with_rdp.hpp" @@ -137,6 +138,11 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co double epsilon_cart_position_; double epsilon_cart_angle_; + rclcpp::Publisher::SharedPtr planned_trajectory_publisher_; + rclcpp::Publisher::SharedPtr planned_poses_publisher_; + rclcpp::Publisher::SharedPtr + motion_primitive_publisher_; + // ############ Function copied from JointTrajectoryController ############ // TODO(mathias31415): Is there a cleaner solution? void sort_to_local_joint_order( diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 79c554d880..4a58d88597 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -115,6 +115,15 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o &MotionPrimitivesFromTrajectoryController::goal_accepted_callback, this, std::placeholders::_1)); + planned_trajectory_publisher_ = + get_node()->create_publisher( + "~/planned_trajectory", rclcpp::QoS(1)); + planned_poses_publisher_ = + get_node()->create_publisher("~/planned_poses", rclcpp::QoS(1)); + motion_primitive_publisher_ = + get_node()->create_publisher( + "~/approximated_motion_primitives", rclcpp::QoS(1)); + RCLCPP_DEBUG(get_node()->get_logger(), "configure successful"); return controller_interface::CallbackReturn::SUCCESS; } @@ -436,12 +445,19 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( sort_to_local_joint_order(trajectory_msg); + // Publish planned trajectory + planned_trajectory_publisher_->publish(*trajectory_msg); + RCLCPP_INFO( get_node()->get_logger(), "Received trajectory with %zu points.", trajectory_msg->points.size()); const auto & joint_names = trajectory_msg->joint_names; + geometry_msgs::msg::PoseArray planned_poses_msg; + planned_poses_msg.header.stamp = get_node()->now(); + planned_poses_msg.header.frame_id = "base"; + std::vector planned_trajectory_data; planned_trajectory_data.reserve(trajectory_msg->points.size()); for (const auto & point : trajectory_msg->points) @@ -452,6 +468,7 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( try { pt.pose = fk_client_->computeFK(joint_names, point.positions, "base", "tool0"); + planned_poses_msg.poses.push_back(pt.pose); RCLCPP_DEBUG( get_node()->get_logger(), "Tool0 pose: position (%.3f, %.3f, %.3f), orientation [%.3f, %.3f, %.3f, %.3f]", @@ -464,6 +481,9 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } planned_trajectory_data.push_back(pt); } + // Publish planned poses + planned_poses_publisher_->publish(planned_poses_msg); + control_msgs::msg::MotionPrimitiveSequence motion_sequence; switch (approx_mode_) { @@ -488,6 +508,8 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( RCLCPP_WARN(get_node()->get_logger(), "Unknown motion type."); break; } + // Publish approximated motion primitives + motion_primitive_publisher_->publish(motion_sequence); auto add_motions = [this](const control_msgs::msg::MotionPrimitiveSequence & moprim_sequence) { From 0e20eb395888ee284b8d6b5b1c35dc0ff99d80a4 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 15 Jul 2025 11:56:21 +0200 Subject: [PATCH 086/128] added python script to record planned_trajectory, planned_poses and motion_primitives to csv file --- .../CMakeLists.txt | 5 + .../__init__.py | 0 .../record_moprim_from_traj_data.py | 273 ++++++++++++++++++ .../package.xml | 3 + 4 files changed, 281 insertions(+) create mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py create mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index bfe823621c..2d21dbc188 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -123,6 +123,11 @@ ament_export_libraries( ament_package() +install(PROGRAMS + motion_primitives_forward_controller/record_moprim_from_traj_data.py + DESTINATION lib/${PROJECT_NAME} +) + if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(controller_manager REQUIRED) diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py new file mode 100755 index 0000000000..eefb85fcc3 --- /dev/null +++ b/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py @@ -0,0 +1,273 @@ +#!/usr/bin/env python3 + +# Copyright (c) 2025, b»robotized +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# Authors: Mathias Fuhrer + +import rclpy +from rclpy.node import Node +from trajectory_msgs.msg import JointTrajectory +from geometry_msgs.msg import PoseArray +from control_msgs.msg import MotionPrimitiveSequence +from sensor_msgs.msg import JointState + +import csv +from datetime import datetime +import threading +import os +import sys +import time + +# Constants for motion primitive types --> defined in control_msg and moprim_controller +# Would be better to import these from the actual message definition +PRIMITIVE_TYPE_SEQUENCE_START = 100 +PRIMITIVE_TYPE_SEQUENCE_END = 101 +PRIMITIVE_TYPE_LINEAR_JOINT = 0 +PRIMITIVE_TYPE_LINEAR_CARTESIAN = 50 + +data_dir = "src/ros2_controllers/motion_primitives_forward_controller/data" + + +class MotionPrimitiveCollector(Node): + def __init__(self): + super().__init__("motion_primitive_collector") + + self.trajectory_msg = None + self.poses_msg = None + self.motion_primitives_msg = None + self.executed_joint_states = [] + self.recording_joint_states = False + + self.timestamp = datetime.now().strftime("%Y%m%d_%H%M%S") + + self.trajectory_sub = self.create_subscription( + JointTrajectory, + "/motion_primitive_from_trajectory_controller/planned_trajectory", + self.trajectory_callback, + 1, + ) + self.poses_sub = self.create_subscription( + PoseArray, + "/motion_primitive_from_trajectory_controller/planned_poses", + self.poses_callback, + 1, + ) + self.motion_primitive_sub = self.create_subscription( + MotionPrimitiveSequence, + "/motion_primitive_from_trajectory_controller/approximated_motion_primitives", + self.motion_primitive_callback, + 1, + ) + self.joint_state_sub = self.create_subscription( + JointState, "/joint_states", self.joint_states_callback, 10 + ) + + self.get_logger().info("Waiting for trajectory, poses, and motion primitives...") + + def trajectory_callback(self, msg): + if self.trajectory_msg is None: + self.trajectory_msg = msg + self.get_logger().info("Received planned_trajectory.") + self.recording_joint_states = True + self.get_logger().info("Recording of /joint_states started. Press ENTER to stop.") + threading.Thread(target=self._wait_for_enter_and_stop_recording, daemon=True).start() + + def _wait_for_enter_and_stop_recording(self): + try: + print("Press ENTER to stop recording or wait 60 seconds...") + sys.stdin.readline() + except (EOFError, OSError): + self.get_logger().warn("No stdin available. Using 60s timeout.") + time.sleep(60) + finally: + self.recording_joint_states = False + self.get_logger().info("Stopped recording joint_states.") + self.save_executed_joint_states() + self.check_and_export_all() + + def poses_callback(self, msg): + if self.poses_msg is None: + self.poses_msg = msg + self.get_logger().info("Received planned_poses.") + + def motion_primitive_callback(self, msg): + if self.motion_primitives_msg is None: + self.motion_primitives_msg = msg + self.get_logger().info("Received motion primitives.") + self.check_and_export_motion_primitives() + + def joint_states_callback(self, msg): + if self.recording_joint_states: + t = self.get_clock().now().seconds_nanoseconds() + self.executed_joint_states.append((t, msg)) + + def check_and_export_motion_primitives(self): + sequence = self.motion_primitives_msg.motions + if not sequence: + self.get_logger().error("Motion primitive sequence is empty.") + return + + types = {p.type for p in sequence} + if len(types) > 1: + self.get_logger().error( + f"Mixed motion primitive types found: {types}. Only one type allowed." + ) + rclpy.shutdown() + return + + primitive_type = sequence[0].type + if primitive_type == PRIMITIVE_TYPE_LINEAR_JOINT: + filename = f"{data_dir}/trajectory_{self.timestamp}_reduced_PTP.csv" + self.save_joint_primitives(sequence, filename) + elif primitive_type == PRIMITIVE_TYPE_LINEAR_CARTESIAN: + filename = f"{data_dir}/trajectory_{self.timestamp}_reduced_LIN.csv" + self.save_cartesian_primitives(sequence, filename) + else: + self.get_logger().error(f"Unsupported primitive type: {primitive_type}") + rclpy.shutdown() + return + self.get_logger().info("Motion primitives saved.") + + def check_and_export_all(self): + if self.trajectory_msg and self.poses_msg and self.motion_primitives_msg: + if self.recording_joint_states: + self.get_logger().info( + "Waiting for joint_states recording to finish before exporting." + ) + return + self.save_trajectory_and_poses() + self.save_executed_joint_states() + self.get_logger().info("All data saved. Exiting.") + self.destroy_node() + rclpy.shutdown() + + def save_joint_primitives(self, primitives, filename): + joint_names = ( + self.trajectory_msg.joint_names + if self.trajectory_msg + else [f"joint_{i}" for i in range(len(primitives[0].joint_positions))] + ) + + folder = os.path.dirname(filename) + if folder and not os.path.exists(folder): + os.makedirs(folder) + + with open(filename, mode="w", newline="") as csvfile: + writer = csv.writer(csvfile) + writer.writerow([f"{name}_pos" for name in joint_names]) + for p in primitives: + writer.writerow(p.joint_positions) + + self.get_logger().info(f"Saved joint motion primitives to {filename}") + + def save_cartesian_primitives(self, primitives, filename): + with open(filename, mode="w", newline="") as csvfile: + writer = csv.writer(csvfile) + writer.writerow( + ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] + ) + for p in primitives: + if not p.poses: + self.get_logger().warn("Skipping primitive with no poses.") + continue + pose = p.poses[0].pose # PoseStamped -> Pose + writer.writerow( + [ + pose.position.x, + pose.position.y, + pose.position.z, + pose.orientation.x, + pose.orientation.y, + pose.orientation.z, + pose.orientation.w, + ] + ) + self.get_logger().info(f"Saved cartesian motion primitives to {filename}") + + def save_trajectory_and_poses(self): + traj_points = self.trajectory_msg.points + poses = self.poses_msg.poses + + if len(traj_points) != len(poses): + self.get_logger().error( + f"Mismatch: {len(traj_points)} trajectory points vs {len(poses)} poses" + ) + return + + filename = f"{data_dir}/trajectory_{self.timestamp}_planned.csv" + with open(filename, mode="w", newline="") as csvfile: + writer = csv.writer(csvfile) + joint_names = self.trajectory_msg.joint_names + writer.writerow( + ["time_from_start"] + + [f"{name}_pos" for name in joint_names] + + ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] + ) + for point, pose in zip(traj_points, poses): + t = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9 + row = ( + [t] + + list(point.positions) + + [ + pose.position.x, + pose.position.y, + pose.position.z, + pose.orientation.x, + pose.orientation.y, + pose.orientation.z, + pose.orientation.w, + ] + ) + writer.writerow(row) + self.get_logger().info(f"Saved planned trajectory and poses to {filename}") + + def save_executed_joint_states(self): + filename = f"{data_dir}/trajectory_{self.timestamp}_executed.csv" + with open(filename, mode="w", newline="") as csvfile: + writer = csv.writer(csvfile) + if not self.executed_joint_states: + self.get_logger().warn("No joint_states recorded.") + return + first_msg = self.executed_joint_states[0][1] + joint_names = list(first_msg.name) + header = ( + ["timestamp"] + + [f"{name}_pos" for name in joint_names] + + [f"{name}_vel" for name in joint_names] + ) + writer.writerow(header) + + for (sec, nsec), msg in self.executed_joint_states: + t = sec + nsec * 1e-9 + row = [t] + list(msg.position) + list(msg.velocity) + writer.writerow(row) + self.get_logger().info(f"Saved executed joint_states to {filename}") + + +def main(args=None): + rclpy.init(args=args) + node = MotionPrimitiveCollector() + try: + rclpy.spin(node) + except KeyboardInterrupt: + node.get_logger().info("Node interrupted by user.") + finally: + if rclpy.ok(): + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 9e9d0954a2..3e6882388e 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -33,6 +33,9 @@ geometry_msgs moveit_msgs + python3 + rclpy + ament_cmake_gmock controller_manager hardware_interface From 5bd7e4886bd79704cdba484cf0ffdf5da96cdadb Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 15 Jul 2025 12:46:19 +0200 Subject: [PATCH 087/128] added python implementation to compare planned, reduced and executed traj --- .../CMakeLists.txt | 4 + .../README.md | 13 + ...ed_and_executed_trajectory.cpython-312.pyc | Bin 0 -> 9691 bytes ...planned_and_reduced_points.cpython-312.pyc | Bin 0 -> 9590 bytes .../__pycache__/fk_client.cpython-312.pyc | Bin 0 -> 3260 bytes .../compare.py | 141 +++++++++++ ...compare_planned_and_executed_trajectory.py | 230 ++++++++++++++++++ .../compare_planned_and_reduced_points.py | 224 +++++++++++++++++ .../fk_client.py | 72 ++++++ .../record_moprim_from_traj_data.py | 2 +- 10 files changed, 685 insertions(+), 1 deletion(-) create mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc create mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_reduced_points.cpython-312.pyc create mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/fk_client.cpython-312.pyc create mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py create mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_executed_trajectory.py create mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_reduced_points.py create mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/fk_client.py diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index 2d21dbc188..f8e6406718 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -127,6 +127,10 @@ install(PROGRAMS motion_primitives_forward_controller/record_moprim_from_traj_data.py DESTINATION lib/${PROJECT_NAME} ) +install(PROGRAMS + motion_primitives_forward_controller/compare.py + DESTINATION lib/${PROJECT_NAME} +) if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 94edf30d6e..163c2a735b 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -28,6 +28,19 @@ For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver ![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_integrated.drawio.png) +## Notes +Save data: +``` +ros2 run motion_primitives_forward_controller record_moprim_from_traj_data.py +``` +Compare data: +~~ros2 run motion_primitives_forward_controller compare.py~~ ? +``` +python3 src/ros2_controllers/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py +``` + + + # TODOs/ improvements - Use references for command and state interfaces to improve code readability and less error-prone. - Extend the tests diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc b/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc new file mode 100644 index 0000000000000000000000000000000000000000..f0f2b8162bba65d83c0a314f3f5b346001e1621a GIT binary patch literal 9691 zcmcgyYfKwimaekPFKn=l4YnZx6A}`40wf`w2kC}9NJ7HoK}dJf^usEA3$Wt{R22c- zHz`CR zI!^V{YHa8=sxgx=^_pp1W{6u7)?TYh({Wp`4f2ffl7zk24tdN+RIdY>AS^{@2+KGp zvRvLqQM}baab4-3SW*phzXN2FA z&n#F+k;a+$ixKU$q#8=p-F$h5c>yO~;5135SaFMac^%YsbHp$}MGWtQ4jD6|CG!xKgwGInyaJxv@ppgl~hr&(x-EA3YqU&h%Ons#7G9Ujk0GsGY-*BazziJVqQY& zF)|>d=p$*#LFC`XqXwVkKnActK9wmoP*UlOB}zt8gUHL2N%kMn*ZGS2I*EMJp5%N= zUl-`>dL@0`MYa5zEsDdU(yHQojh4zJcN)ePS<_ZLyTF3^`A+oBlov_(E9DcJB+hum zjYKD8lRT*83+7h_Qc6=|Eh&u!38lwHv!PH28Ic`1)+IO<8OQlX^|>isV%N|jNW@ktd@r8>vA5KcXo%J542*dSH*tLp%j zAt!PnH!8p9xog(=XzE8LxYv>31ql`FO4zEmO(;~UTeZ+qh?MHF2Db5J2I)(Yu0%Pg*NECk~g-CAGv=P-n`EEU*P{?|(_AZP*{y;Bp>~)PU4#Ac|R7YkY+Jx%S=6hT8(J7jVdyDI7 z^ZYh1Lx;{wC@D~60e$TrC*^uf&LLRi`VR1#6!?NFUjO58D$?-Fm`AD5_A`p{ z3K!?`{AaKNQrDbc>Z+Hv0$n{I231-Ne%_s zBnon4Tx3LqgvhfoE+VG*@z&rE#-_dftN4%`fFFF!p^!nb^hXDTXqr>Z!XV3YV+x&G z#S=+k`r;$ppH)WckL`-(oF+eHQp^dKzs&JUi59E1O_5YQ#VaN@J~YTGra0Tj#T6sZ zA;o$uuT0u?I5`mKg3)AHmQa$0`b>&XuyIfk z1uqo36Fiwj+*sNkPmOYXkdF=wiXj7U0d-a5g&4&cPeqinzP{90SWJc4WMmNZ%cps0 zydT6WOcM0|^M~Hwp7_u7N9}2cZqnAEVvcb5LbZy|bj2J6V@D%*jEVs|XzfoWMXlq4 zI3DLhjN0tLLe0nj)xGfd?W!gN{p$DM?ReaH7=|Al;ru8yMT9HqU^tRW41v)}Zup82 zCPUXWlpILc9ghx-@LX^-Dh>uU=BSWL1_kyC9^6!GFtk}Q41tk(jzwV*s#u^yBZ;J- z7}6c-h%Fw!>^Plh7!~6j)KIgd zVC?}uiZr${jm;eA2Dl_r>@ZQ2g4SDw5xFr@afo~9iJ=vDA&1yoabh82cqk== zu@phECLsY?f>MI|3pMRP7wQ&`fh4O}X z7YPVQ;@H0K{H(x@N5yCgMz2h}%NLq0u)r9yiJ>?wta748Q8j128YwDb(kn82Lg17V z5pN%1l{R8)8QC#Gp`(gPHH2crc2-TH*zoX%u>l2qzY0G0`{5s(2U7{IIRUIuR%q^P zlfF zy&TipMFksTVZ_4vhS)STuGAA=%%gTvn*;@}D6EhubQyPB_&ZoD6V!KZ&&}$oYI$R0 z&fPR|>S4L}=Ju)Wa!qrteCI^hBQq7;zFfOITf6%|oJXgP^W1{)Rs5Gm*?DxL6M_|Q z?W{HH4b63Dy-mxWmaL~`!7Y1Qa-M^7`N4^Sx=t{+4Bb zYu4WiSr02V-s-!3dFJw5-CXzYjq;vjxt+&zH7Degy)xUkR1ujt^NqjZH~c?*`0Een zcg?d4{@m6hIsZ{jTGjTs_H5wba^Ofda71P*A6C}f;%|RA^WogCIrjG+`SlaIU7fkw zlXBPlGUAph`zOwR6WDgI{CCxNs^_~G=!N~cP)9Cs461%_rW|G0_g&lf+3uVBruNAj z8s(iwvKx*p4ri-7?+-6|x^wpP6CDr1%DySzt@7Kx8K1nVMc&()-PC!%J6m@q7dV@9 zp99M?Hra7-;nboaAMBD#ezwG%2H`Hxb?KUP>*%aAw_)de-9q1D{l6RUpUri?mp$^H z{O0>|e{9Kl`D*9H(MivDmXgW#oTYkt_<<$3;w+!!CXL^DH%_N=-loTt*;IASI!RBy zzGAgc9=>M2Zog)iy<5Iy=iIX>>)k$obn)>0x8-*~ko!}U_9g4kQ+y3y4$sxiidpZD z`JTn@`<%)*g!zW^e9P8A)*6tjb}U&N3t9fG)jxe~df)7}xjpmroqh8ybB*)Ea^S#{ zwUx+sUUN<}(~%|XCXxf1-RSt*8hBI+NWO8hGRsuTzCBCK>o6ru)=y4d zJ$1u2-6}g9Ry@I#n$0UUb+=P9sTFU@mzciq7|Sx_%`)BxRXe_B8o}-`UY04#vMZQ%1?9S3IoIxGS8LYQ zy3i(fC33Fh#L0)Qa?EnmG3B^*{`SS0i?_owVY%_m+{U&=Th4U~I2g+(U01tq*p`?o zOoI|1X~Wz&7oB@oE;;Zu)A~P;6Ex-Opanau$$zq)H8KBUWFUMB>cF=ge6l^kpvO-H zbr`^5p{oGS0O#MVUhUU`J~9@7HJ)E;74elt{lo&4u^teiLIVXDLMlKH1y|ehl&ft6 zSKIbtiR(ZEC9kNFm0XJp8d;yx$POCWUr8f}R3bUB1D`1^s=p4f&RV2w#!m z%aj$>acOzQVNq#$alS@NWrbc5Fw7}d5I$rEfWxxJoiD&Qv2}n1aMNr=V#X!8V%0>J z9-|Uuzvn3E@0Q%Lg8QIzNhO-Qj0~E?T}T_(q)mB;yp*`)_sZ`A41zy!6xWySSRM1wg9jhn#dW?L!jH2<|taA{msI-CP z>2bkk#D=6_`Sd^m2qEni$peUT?N?O#H)(Ca0Kk;KE4+ID){a{~{S)=?rCWpkdHyE- z%g;lAM^z9C<zv05&PWP_Y8kq)Un&)M-NLfX;gG6NbNtbuzveNM8q_dO?kKASqoR$yaFE zuY<9%BSdpO1}G|j)_?`{)1*V^Ae3&)qBCie(ZE z@jVF;6MR7O_~OK4_ln1TQ6g=ACm;8!F^}I(_)RK@h8^+vh~V+= z$m7Mv2M2hbD@I`?!Q&at@52F}(fk2iVAfhy>?}gzJi5Zafs65s;xUe@VJ7K3 zs+It-!wz0?1fZ8BhF^>T@n|s1SUj5G@zm9lX`I9}hsP6*KZFB}RPrZq(20YSI5>ra zE*$&}2d5zj1^6?VJ_~_ThRvr#BYZb5Igf)LTx=_VCVVf>d>;qz;@~|Te1L;61d0ho z`}+mOEewwU?1jQ83Lr@`0$_^;;}GE%#P?x71MbgQ7_^T9{9+w1P-#Nhzz7aHv^Cu^+o{$|IKWAs% z(NKJn{8;551oGi0^YtT_gu^#x`btzW_#vKo|1uGVaq3{ zub#fKZHcK~0j<`fzXNa8JZ1ijzxng2pUYcu8@m=f*{yHN?cEQ~_sAFClFz@DZGT&C zxR~=@%DLWo2(ZTSYsUfBXq#%2>-T)sJwH6(ldV4>A3Xi9tbDHfek6PFyu7I==edw` zy!FUPyDriboqu^df2m@)rFZ{7TI$6uy$3CQZ>8Mc8=ceLQ(d$Exw>Ch&kfEG-?^M~ zwPF;&^PCbqwyO6(ePD^%g2&}~DLjHYMA0zooAb<;%KoPL{fm9_xl0(Kcn8-%dG+K+ zU6_DrH`(zKhKGI(rWnn+#{N2(;@Dzz5nzh$ubJ~tV8fsyI3S-H2z(4bS%3ikB0^{2 zF*-vdW5ys7o^}6<5yS5>Yd(pR=)#S{_)7H+h58IU?lE7|851&P%)0+C83EY<^nyGl z!yitlkoioy5d*j{h1VihWYZf9o9TG?4aniz$Qi7@g48@)Owemw9x^MH0OOCu5yt}r zoeURXdc{}Bk4O8(q5>xu?@NsqWw=LqIBCMWp3U0*Y*ve&wTi&(a8uFGO!cIU;#`Yj z#odE5jMp9*@T&ponfAb-=8(?l$0>gf>Z@m{fYG1)F{K?!OoELj`Cmfz=kOEo(K$h_ zINK&VSA1|-cvt-U@wV&>+#H=6y(vvevz>BNTh7-GWq1d-%vf$aW*oDZX%7b~r2_0cK4jH?V_j6kh3`G_y7$bz=bU@*x#vF4NBvtxg@u6h$KLUwe{Up+|G*zw(iMm&KLTQo zU)S#1r}W3apLbM`+=GxMBUpaf{5$mRNN3Z z#!YcLZWc()h*L-#yZWi*B5|wG9=B}3NftS+qD9o#gFKW}p)}w!ZjV>QZKAc%YAv){ zMYXju?us8OYoC2#AB{kTL|$XsgEC|1u>w+*)nvx!%URUxa^Rw_lCSRsOK zSrbdMX4Z1sdW%+DN#Z*s9HLXKR3vO{#clg7uq93ke}zhy=b|lSFaK6))}dIWVx2bo zcek-lwvu(-uDVsQ&2QOv^*Vj4ZEN?fw6QhNcWrs!tUF#UT0@o3&QkN!9^#!vf_NL& zB3=`(6>CMKGJ;ysR4C~}X~t!Mio1m>OIz z!`hOZMg<75{st-5g>ZMPQh;FVZWO)v2KiH?Sk2b64eX|m^*9h`@2#`> z8J#U9omc;XB4Aa%+xOHpSdT+po%J}>bz6@^ThWFMR4QxDzOKA| zBl&<{vqZc}Y+6qjyDesgGqV}y)Lxp4Mrm_``K;G!U#}JRMGJUEr>3)1iY%36J3+lzE;cb(#;XF<^4}0~G@M~Am zqN*ZMpI0v%!(1dF45?boktiBw!Z2LWi~B>(nv6^aw7O!0Ob*CKmf?pu)=MD|X2m0w z&Ea5#77XfPu19#v_Ok48K^GY$(SM7uoREwXNem1)E=tPeVu z^&??HHiGYfO4-V=tdAcX7zsxOnNo5S?`H%79D)jlqkfqV0*#^*yiA^x&4Va9>>C|p zK*Q)*a2&V{%*aT1O1AKv;G0z4Mxm$5=$J~IF^>=w!W>@702g6pU1S6_AjC|``e9}g zvS37}hB+o8)2hbcuu4sZH7bTFn-B~P3BE8h6&({~U6hB>WA~;97@mtT!<=kF9N5aw z$y5l;Bb(SDQtPp8VEQt}4@D?U@**K9onLl)f5a3+bha*KCFfZt4_k- z6#T_x-6+tbK#yX2LbkAjMJ<@t*^JGi3|uzjRrcYD z@@?Rno(gpbkCa7Rq1o{?#$-Q!1d=A_AQ{BFG`Mm zN$P>!F?~68IlU!kZ%OL&_R5*IRA7cr@132<=ri5dO;W}7r0yYInbb|2Q)Y?opVCJV{c4k_$t}U5!S=aW3 z9iMjI>|AWk?l`!3F1zE%-5p*g&o1`|v;9FSbUE7}mWHF* z{t>Bi6kNtxIcJ@5Hk0Goy23vtu7jq(`rf&5wOFG5aSA8!Tt{i*$b_R`GRx%0Eb|Sq^Qx3xJp{UQyNue$B2* z0F+j+y4(6&1xS}CueOMm5Pm+cN}^5EPXZiy^#}k!Yx1$hbpoz8DMF~x6s-l833!4^ z5{q+WDb~Om*J_EuqkmAxnr_p#3hSo8es+L#*VLnc+IrCuAc3P~sbWuHsm}|Ra>gq~ z0AI11wO|Zb3jopI*NM(S9p=GsE^B2~khTbvmi1xLtOfq(nzs4%iU&d{p^VrC5Vb8q zUNr+mY!+Rb) zSX|m@A?Vil)__^W$~E}b09)89wpt4(%QS9PSGqiBO(l(2zW|?durQLJfE*}&+!l9D5MIw2CDaZ4`G5ay=70b7&LIf- zDMpBf)z}xWLLvI3j`VqT2p`h2kspFka}wcm6yYOOHWi{)gnunT7@$UYZoaD#M-WCdW3{EI*z*RCM?I$^EH??UHV%LTi_P!< z*V)CtI;;#dFsP*eIgE#oAe4?-!_f&2c@PfjVBEz>9%1y+OUZg1irNPTqLV%$>SH4Q zA;2XH-w@{T5LOJ!R0Qw}gf~UZyIzF-M&BDg91{vSx<+_wcs&RMnrH`PvI(?|4M%v{ z2!;*v5MDu-k+I>CDTL7~**MM%jQ_H1=Ae>8jKIk>6At^s5F5%y2!|oCMLRJkU5KoC z7(W+5cx%Y|Sa1YkM@8885XPHiDu9A4!ax~1hBNG8vK4}t2(O0zs0Ua70B6T>b^>Q7 zadrx4r*YPcvsWSW)}hxheFiews!UW3S+H>}f#0hwEyXzCL=W7}t6GnqKX@1bMeZie;+4Gn% zn7ygjlgDNn9)Re(sdv){GNC)dFB}K+&X#58wybkohF@~-{K{FgVglY33sKRyY-`Kf z+A`1Iw{2gk0Da%M2xrx_m=Zrema*m*>oL>XQzG0p zGI1fJ<7J=s}qCE62&Z(cHoF%XOj8w%uvH^QP4Q4unhT z&FP8E=t65on2-!9dKk`>vy&{x*F2Th(#yVSHhbtZXy=6K%bm?2Zgr+ZVqX=BE? zz%P#8GfS74Wbcw~;GsH*Wx75~*Gmn%mgx4vxR&Xku{1n9~O&$JTt6 zC*Qm!-`sjFIv>qf*Q}TcgX0^5GPu97uNxaU~k1vx%)62hp(nZu?CV7m$ zeroQ0f%<&6rMHXz{ADZTeyA)ad^PCd@5u^e@c$5G9RAxOPO|#Aj-}#yp~$$_e;Jw`dX&Sh^x5> zNO_HNEufBLVU|Mx!9~<-2o6YIb{Ffz!9k&{!NG+G02Ne^HOyH#f#6p1?RmCp@3U3= zN>yHyY*g^e$wE0*C}XlosRt0VKul>wv1tPR1(?@sD7%T2`)34d5k6tPv`k~m`2c5C zkyCudXhtim(Jl{aI0{xM-c%@wHN6fQPeZ1i^yGzue; zX`c^|&*$?x6!XZ2^49_^GyLqJyf5TRz)Ol3#o&rLaNmlZeK!eZFp9mtr4NE}$HLqp^mibGe@o%Cm)~D9l*sTxruz8T7&-6`mz`xhwuyBxOq$3Du08N}^?xwv@J!6V*ZL%B|JNNpmPbAehqJp+suQ zWoDOBsnUQ7s0f9s5R9UbfucZ>lLGtDqmRA!qO};19wdN(9*W$A$S48>E&67cOUjmt zx}C$!dvD&n_h#n3Z|1L|kRL(&XKH2Xxq{H&IO8^{LmWK@Vh5>66*QFLqel};o{UG} zv{&<%#Ed8)54wd^aRaFm@jUc8Ycmq@slMe2gy?k-BGSW-$&9>+RQXdOqY$|`&=DRR zhywGU|`--i%pT7jb8LqZ{jK7pO|^ zY61P9UWKi!n@q`IaNYQQwlSCB? z9NoKks~P;!p%)Ddy`y#cmmKLr%jTbV8^u zE(&!CcXjH(6}v^`>Z4Q32Fvbz-Sa=J0+e+cltt8~dt>ojk9Mhgx0vqv%pq4=I$a>J$?vWvbW4`e9fxddjTG z;kx+x$(av1NQ|G9yKxqiC+Ae@)#LgD`lF`@NVWgwZSoXvzT@kY^1`B{qr5|TzI??| zo$>-->z|uX5K47=J&}V4XO>r1BA3;)1cxX!0U(tebnry}Dfzfc43qhmNLJQpb zqf#j2YS}DkIA1lZ6o3tIR3l(cRP{1pK1z(LW-`AWJItztc~`O;3xa9Fos}v?Wg_P& zf3lef$WvyLt)EmVPh2-NC+L1BPB%1z`SVmSVSA5EHg$W0Os4K3IDyeIFl6vDNpu?J zIS+g40{_}T7p!{11Yh}X(O*Z8A=;emIeP;7aQ@PN7ZQ@UT4Y{d| zwA0rca!ZL@O1!0vTgrG-x!j(9_hs4DgUGp^`2Bb*GHyl2cjf)a)rJp1u%%2`%Ea#3 z-Ic#gf3Dm*2t>Bu+I(wkwtX(X^U?i}euo=#Py5e37;D8Qt=MEMmbPN)KVN$id!s!x z(i*yC4PDy3W({3w4NX}?Q+wg5gYem%{`>v=;n!N>F)KW_d*Sh5Yv#5!bGtROV9hM- zy?JME{QYM5gF^*{&mKxB6zL-BMJsr5@AdCBgKr-64^R#ZFML6GR@&(K6CieY?svZ+ zAm}u=(gb97(eX6w?CHVNEG#6wET}>TQ@w`EkTOoTDaKOORQ1(zQn1s);0_b^HPY__ zdF-)qHNOL5gNMG3+Dfpc3|q=@Q;G9;2X5|j<-ENw{;J;18iYxvu4`A5GJmjnvcZGx z$GD`cRgKd@j6besHD|_t-{>^hww<$3=S9vDs1Xby4szc-#CMz!`G1M>j^~}hbN!nQ z^vvUvek>e?2c)zAxa5(B?Rac09z!V$<%N?z7B!aiss;yvE7>x(3xExDWm+L`c7y?< z-PKn+OlXxB3=>~_k)3*xop#uyuk-JLAo(A#14IWm=uO~yT{7fchTs0?r0m<_SIhcK z`U-*nOUYO?QU+bIvB=&Do#FGI{4%}5P1#3wiHjuoa= Date: Tue, 15 Jul 2025 15:58:45 +0200 Subject: [PATCH 088/128] added rdp for quaternion inbetween reduced positions --- .../CMakeLists.txt | 4 + .../rdp.hpp | 25 +++++ .../package.xml | 2 + .../src/approx_primitives_with_rdp.cpp | 101 +++++++++++++----- .../src/rdp.cpp | 90 ++++++++++++++++ 5 files changed, 193 insertions(+), 29 deletions(-) diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index f8e6406718..bd7a59e065 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -16,6 +16,8 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS std_srvs moveit_msgs geometry_msgs + tf2 + tf2_geometry_msgs ) find_package(ament_cmake REQUIRED) @@ -74,6 +76,8 @@ target_link_libraries(motion_primitives_from_trajectory_controller PUBLIC ${geometry_msgs_TARGETS} ${moveit_msgs_TARGETS} ${std_srvs_TARGETS} + tf2::tf2 + tf2_geometry_msgs::tf2_geometry_msgs ) target_compile_definitions(motion_primitives_forward_controller PRIVATE "MOTION_PRIMITIVES_FORWARD_CONTROLLER_BUILDING_DLL") diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp index f5190e246d..85b341eccb 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/rdp.hpp @@ -20,6 +20,9 @@ #include #include +#include +#include + namespace rdp { @@ -50,6 +53,28 @@ double pointLineDistanceND(const Point & point, const Point & start, const Point std::pair> rdpRecursive( const PointList & points, double epsilon, std::size_t offset = 0); +/** + * Computes the angular distance (in radians) between two quaternions. + * + * @param q1 First quaternion. + * @param q2 Second quaternion. + * @return Angular difference in radians. + */ +double quaternionAngularDistance( + const geometry_msgs::msg::Quaternion & q1, const geometry_msgs::msg::Quaternion & q2); + +/** + * Recursive RDP for quaternions based on angular deviation. + * + * @param quaternions List of quaternions. + * @param epsilon_angle Angular threshold (in radians). + * @param offset Index offset for tracking original indices. + * @return Pair of simplified quaternions and their original indices. + */ +std::pair, std::vector> rdpRecursiveQuaternion( + const std::vector & quaternions, double epsilon_angle_rad, + size_t offset); + } // namespace rdp #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__RDP_HPP_ diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 3e6882388e..4e391bc89c 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -32,6 +32,8 @@ std_srvs geometry_msgs moveit_msgs + tf2 + tf2_geometry_msgs python3 rclpy diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index d517b7569a..ea3e6dd89d 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -41,6 +41,7 @@ MotionSequence approxLinPrimitivesWithRDP( return motion_sequence; } + // Reduce positions using RDP rdp::PointList cartesian_points; for (const auto & point : trajectory) { @@ -50,38 +51,82 @@ MotionSequence approxLinPrimitivesWithRDP( auto [reduced_points, reduced_indices] = rdp::rdpRecursive(cartesian_points, epsilon_position); + std::cout << "[approxLinPrimitivesWithRDP] Added " << reduced_indices.size() + << " points due to position change (epsilon_position = " << epsilon_position << ")." + << std::endl; + + std::set final_indices(reduced_indices.begin(), reduced_indices.end()); + std::set position_indices(reduced_indices.begin(), reduced_indices.end()); + std::set orientation_indices; + + // Enrich reduced_indices by checking quaternion changes in each segment + for (size_t i = 1; i < reduced_indices.size(); ++i) + { + size_t start_index = reduced_indices[i - 1]; + size_t end_index = reduced_indices[i]; + + if (end_index - start_index <= 1) continue; // nothing in between + + // Extract quaternion segment + std::vector quats; + for (size_t j = start_index; j <= end_index; ++j) + { + quats.push_back(trajectory[j].pose.orientation); + } + + auto [reduced_quats, reduced_quat_indices] = + rdp::rdpRecursiveQuaternion(quats, epsilon_angle, start_index); + + for (size_t idx : reduced_quat_indices) + { + if (final_indices.insert(idx).second) // true if inserted (i.e., newly added) + { + orientation_indices.insert(idx); + } + } + } + + std::vector sorted_final_indices(final_indices.begin(), final_indices.end()); + std::sort(sorted_final_indices.begin(), sorted_final_indices.end()); + + std::cout << "[approxLinPrimitivesWithRDP] Added " + << sorted_final_indices.size() - reduced_indices.size() + << " additional intermediate points due to orientation angle change (epsilon_angle = " + << epsilon_angle << ")." << std::endl; + // Compute cartesian velocity and acceleration between trajectory points std::vector velocities, accelerations; calculateCartVelAndAcc(trajectory, velocities, accelerations); - for (size_t i = 1; i < reduced_points.size(); ++i) + for (size_t i = 1; i < sorted_final_indices.size(); ++i) { + size_t start_index = sorted_final_indices[i - 1]; + size_t end_index = sorted_final_indices[i]; + MotionPrimitive primitive; primitive.type = MotionPrimitive::LINEAR_CARTESIAN; // Blend radius (zero at last point) - if (i == reduced_points.size() - 1) + if (i == sorted_final_indices.size() - 1) { primitive.blend_radius = 0.0; } else { + const auto & p0 = trajectory[start_index].pose.position; + const auto & p1 = trajectory[end_index].pose.position; + const auto & p2 = trajectory[sorted_final_indices[i + 1]].pose.position; primitive.blend_radius = - calculateBlendRadius(reduced_points[i - 1], reduced_points[i], reduced_points[i + 1]); + calculateBlendRadius({p0.x, p0.y, p0.z}, {p1.x, p1.y, p1.z}, {p2.x, p2.y, p2.z}); } double velocity = -1.0; double acceleration = -1.0; double move_time = -1.0; - const size_t start_index = reduced_indices[i - 1]; - const size_t end_index = reduced_indices[i]; - if (use_time_not_vel_and_acc) { - const double prev_time = trajectory[start_index].time_from_start; - const double curr_time = trajectory[end_index].time_from_start; - move_time = curr_time - prev_time; + move_time = trajectory[end_index].time_from_start - trajectory[start_index].time_from_start; MotionArgument arg_time; arg_time.argument_name = "move_time"; arg_time.argument_value = move_time; @@ -89,20 +134,13 @@ MotionSequence approxLinPrimitivesWithRDP( } else { - // Use max velocity and acceleration in the reduced segment - double max_vel = 0.0; - double max_acc = 0.0; - + // Use max velocity and acceleration in the reduced segment (min 0.01) + double max_vel = 0.01; + double max_acc = 0.01; for (size_t j = start_index + 1; j <= end_index && j - 1 < velocities.size(); ++j) - { max_vel = std::max(max_vel, velocities[j - 1]); - } - for (size_t j = start_index + 2; j <= end_index && j - 2 < accelerations.size(); ++j) - { max_acc = std::max(max_acc, accelerations[j - 2]); - } - velocity = max_vel; acceleration = max_acc; @@ -118,16 +156,24 @@ MotionSequence approxLinPrimitivesWithRDP( } PoseStamped pose_stamped; - pose_stamped.pose.position.x = reduced_points[i][0]; - pose_stamped.pose.position.y = reduced_points[i][1]; - pose_stamped.pose.position.z = reduced_points[i][2]; - // TODO(mathias31415): Also use RDP for orientation? With epsilon_angle - pose_stamped.pose.orientation = trajectory[reduced_indices[i]].pose.orientation; - + pose_stamped.pose = trajectory[end_index].pose; primitive.poses.push_back(pose_stamped); motion_primitives.push_back(primitive); - std::cout << "Added LIN Primitive [" << i << "]: (x,y,z,qx,qy,qz,qw) = (" + // Determine reason for addition + std::string reason; + bool pos = position_indices.count(end_index); + bool ori = orientation_indices.count(end_index); + if (pos && ori) + reason = "position+orientation"; + else if (pos) + reason = "position"; + else if (ori) + reason = "orientation"; + else + reason = "unknown"; + + std::cout << "Added LIN Primitive [" << i << "] (" << reason << "): (x,y,z,qx,qy,qz,qw) = (" << pose_stamped.pose.position.x << ", " << pose_stamped.pose.position.y << ", " << pose_stamped.pose.position.z << ", " << pose_stamped.pose.orientation.x << ", " << pose_stamped.pose.orientation.y << ", " << pose_stamped.pose.orientation.z << ", " @@ -140,9 +186,6 @@ MotionSequence approxLinPrimitivesWithRDP( motion_sequence.motions = motion_primitives; - std::cout << "Reduced " << cartesian_points.size() << " points to " << (reduced_points.size() - 1) - << " LIN primitives with epsilon=" << epsilon_position << std::endl; - return motion_sequence; } diff --git a/motion_primitives_forward_controller/src/rdp.cpp b/motion_primitives_forward_controller/src/rdp.cpp index 4ef0dc85a6..a8a7714e66 100644 --- a/motion_primitives_forward_controller/src/rdp.cpp +++ b/motion_primitives_forward_controller/src/rdp.cpp @@ -121,4 +121,94 @@ std::pair> rdpRecursive( } } +// Compute angular difference (in radians) between two quaternions +double quaternionAngularDistance( + const geometry_msgs::msg::Quaternion & q1, const geometry_msgs::msg::Quaternion & q2) +{ + tf2::Quaternion tf_q1, tf_q2; + tf2::fromMsg(q1, tf_q1); + tf2::fromMsg(q2, tf_q2); + + tf_q1.normalize(); + tf_q2.normalize(); + + double dot = tf_q1.dot(tf_q2); + dot = std::clamp(dot, -1.0, 1.0); // numerical safety + + return 2.0 * std::acos(std::abs(dot)); // shortest angle between unit quaternions +} + +// Recursively apply the Ramer-Douglas-Peucker algorithm to a list of quaternions. +// Returns a simplified list of quaternions and their corresponding original indices. +std::pair, std::vector> rdpRecursiveQuaternion( + const std::vector & quaternions, double epsilon_angle_rad, + size_t offset) +{ + if (quaternions.size() < 2) + { + std::vector indices; + for (size_t i = 0; i < quaternions.size(); ++i) indices.push_back(offset + i); + return {quaternions, indices}; + } + + double max_angle = 0.0; + size_t max_index = 0; + + const geometry_msgs::msg::Quaternion & q_start = quaternions.front(); + const geometry_msgs::msg::Quaternion & q_end = quaternions.back(); + + // Check intermediate quaternions for deviation from SLERP curve + for (size_t i = 1; i < quaternions.size() - 1; ++i) + { + double t = static_cast(i) / static_cast(quaternions.size() - 1); + + // Interpolate on the SLERP curve between q_start and q_end + tf2::Quaternion tf_q_start, tf_q_end; + tf2::fromMsg(q_start, tf_q_start); + tf2::fromMsg(q_end, tf_q_end); + + tf_q_start.normalize(); + tf_q_end.normalize(); + + tf2::Quaternion tf_q_interp = tf_q_start.slerp(tf_q_end, t); + tf_q_interp.normalize(); + geometry_msgs::msg::Quaternion q_interp = tf2::toMsg(tf_q_interp); + + // Calculate angular distance to actual intermediate quaternion + double angle_diff = quaternionAngularDistance(q_interp, quaternions[i]); + + if (angle_diff > max_angle) + { + max_angle = angle_diff; + max_index = i; + } + } + + if (max_angle > epsilon_angle_rad) + { + auto left = rdpRecursiveQuaternion( + std::vector( + quaternions.begin(), quaternions.begin() + max_index + 1), + epsilon_angle_rad, offset); + + auto right = rdpRecursiveQuaternion( + std::vector( + quaternions.begin() + max_index, quaternions.end()), + epsilon_angle_rad, offset + max_index); + + // Avoid duplicate point + left.first.pop_back(); + left.second.pop_back(); + + // Merge results + left.first.insert(left.first.end(), right.first.begin(), right.first.end()); + left.second.insert(left.second.end(), right.second.begin(), right.second.end()); + return left; + } + else + { + return {{quaternions.front(), quaternions.back()}, {offset, offset + quaternions.size() - 1}}; + } +} + } // namespace rdp From 309e04755fa015d68f7a9272236a21b72a059ede Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 15 Jul 2025 16:14:39 +0200 Subject: [PATCH 089/128] chagend prints from cout to RCLCPP --- .../src/approx_primitives_with_rdp.cpp | 102 ++++++++++-------- 1 file changed, 59 insertions(+), 43 deletions(-) diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index ea3e6dd89d..59b3bc1e17 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -18,6 +18,7 @@ #include #include #include +#include "rclcpp/rclcpp.hpp" using control_msgs::msg::MotionArgument; using control_msgs::msg::MotionPrimitive; @@ -37,7 +38,9 @@ MotionSequence approxLinPrimitivesWithRDP( if (trajectory.empty()) { - std::cerr << "[approxLinPrimitivesWithRDP] Warning: trajectory is empty." << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[approxLinPrimitivesWithRDP] Warning: trajectory is empty."); return motion_sequence; } @@ -51,9 +54,11 @@ MotionSequence approxLinPrimitivesWithRDP( auto [reduced_points, reduced_indices] = rdp::rdpRecursive(cartesian_points, epsilon_position); - std::cout << "[approxLinPrimitivesWithRDP] Added " << reduced_indices.size() - << " points due to position change (epsilon_position = " << epsilon_position << ")." - << std::endl; + RCLCPP_INFO( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[approxLinPrimitivesWithRDP] Added %zu points due to position change (epsilon_position = " + "%.4f).", + reduced_indices.size(), epsilon_position); std::set final_indices(reduced_indices.begin(), reduced_indices.end()); std::set position_indices(reduced_indices.begin(), reduced_indices.end()); @@ -89,10 +94,11 @@ MotionSequence approxLinPrimitivesWithRDP( std::vector sorted_final_indices(final_indices.begin(), final_indices.end()); std::sort(sorted_final_indices.begin(), sorted_final_indices.end()); - std::cout << "[approxLinPrimitivesWithRDP] Added " - << sorted_final_indices.size() - reduced_indices.size() - << " additional intermediate points due to orientation angle change (epsilon_angle = " - << epsilon_angle << ")." << std::endl; + RCLCPP_INFO( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[approxLinPrimitivesWithRDP] Added %zu additional intermediate points due to orientation " + "angle change (epsilon_angle = %.4f).", + sorted_final_indices.size() - reduced_indices.size(), epsilon_angle); // Compute cartesian velocity and acceleration between trajectory points std::vector velocities, accelerations; @@ -173,15 +179,14 @@ MotionSequence approxLinPrimitivesWithRDP( else reason = "unknown"; - std::cout << "Added LIN Primitive [" << i << "] (" << reason << "): (x,y,z,qx,qy,qz,qw) = (" - << pose_stamped.pose.position.x << ", " << pose_stamped.pose.position.y << ", " - << pose_stamped.pose.position.z << ", " << pose_stamped.pose.orientation.x << ", " - << pose_stamped.pose.orientation.y << ", " << pose_stamped.pose.orientation.z << ", " - << pose_stamped.pose.orientation.w << "), " - << "blend_radius = " << primitive.blend_radius << ", " - << "move_time = " << move_time << ", " - << "velocity = " << velocity << ", " - << "acceleration = " << acceleration << std::endl; + RCLCPP_INFO( + rclcpp::get_logger("approx_primitives_with_rdp"), + "Added LIN Primitive [%zu] (%s): (x,y,z,qx,qy,qz,qw) = (%.4f, %.4f, %.4f, %.4f, %.4f, %.4f, " + "%.4f), blend_radius = %.4f, move_time = %.4f, velocity = %.4f, acceleration = %.4f", + i, reason.c_str(), pose_stamped.pose.position.x, pose_stamped.pose.position.y, + pose_stamped.pose.position.z, pose_stamped.pose.orientation.x, + pose_stamped.pose.orientation.y, pose_stamped.pose.orientation.z, + pose_stamped.pose.orientation.w, primitive.blend_radius, move_time, velocity, acceleration); } motion_sequence.motions = motion_primitives; @@ -198,7 +203,9 @@ MotionSequence approxPtpPrimitivesWithRDP( if (trajectory.empty()) { - std::cerr << "[approxPtpPrimitivesWithRDP] Warning: trajectory is empty." << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[approxPtpPrimitivesWithRDP] Warning: trajectory is empty."); return motion_sequence; } @@ -292,22 +299,25 @@ MotionSequence approxPtpPrimitivesWithRDP( primitive.joint_positions = reduced_points[i]; motion_primitives.push_back(primitive); - std::cout << "Added PTP Primitive [" << i << "]: joints = ("; + std::ostringstream joint_stream; + joint_stream << "Added PTP Primitive [" << i << "]: joints = ("; for (size_t j = 0; j < reduced_points[i].size(); ++j) { - std::cout << reduced_points[i][j]; - if (j + 1 < reduced_points[i].size()) std::cout << ", "; + joint_stream << reduced_points[i][j]; + if (j + 1 < reduced_points[i].size()) joint_stream << ", "; } - std::cout << "), blend_radius = " << primitive.blend_radius << ", " - << "move_time = " << move_time << ", " - << "velocity = " << velocity << ", " - << "acceleration = " << acceleration << std::endl; + joint_stream << "), blend_radius = " << primitive.blend_radius << ", move_time = " << move_time + << ", velocity = " << velocity << ", acceleration = " << acceleration; + + RCLCPP_INFO(rclcpp::get_logger("approx_primitives_with_rdp"), "%s", joint_stream.str().c_str()); } motion_sequence.motions = motion_primitives; - std::cout << "Reduced " << points.size() << " joint points to " << (reduced_points.size() - 1) - << " PTP primitives with epsilon=" << epsilon << std::endl; + RCLCPP_INFO( + rclcpp::get_logger("approx_primitives_with_rdp"), + "Reduced %zu joint points to %zu PTP primitives with epsilon=%.4f", points.size(), + reduced_points.size() - 1, epsilon); return motion_sequence; } @@ -351,9 +361,9 @@ void calculateCartVelAndAcc( size_t num_points = trajectory.size(); if (num_points < 2) { - std::cerr << "[calculateCartVelAndAcc] Warning: trajectory too short to calculate " - "velocity/acceleration." - << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateCartVelAndAcc] Warning: trajectory too short to calculate velocity/acceleration."); return; } @@ -368,8 +378,9 @@ void calculateCartVelAndAcc( if (delta_time <= 0.0) { - std::cerr << "[calculateCartVelAndAcc] Warning: non-positive time difference at index " << i - << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateCartVelAndAcc] Warning: non-positive time difference at index %zu", i); velocities.push_back(0.0); continue; } @@ -390,9 +401,11 @@ void calculateCartVelAndAcc( if (time_interval <= 0.0) { - std::cerr << "[calculateCartVelAndAcc] Warning: non-positive time difference for " - "acceleration at index " - << i << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateCartVelAndAcc] Warning: non-positive time difference for acceleration at index " + "%zu", + i); accelerations.push_back(0.0); continue; } @@ -414,9 +427,10 @@ void calculateJointVelAndAcc( size_t num_points = trajectory.size(); if (num_points < 2) { - std::cerr << "[calculateJointVelAndAcc] Warning: trajectory too short to calculate " - "joint velocity/acceleration." - << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateJointVelAndAcc] Warning: trajectory too short to calculate joint " + "velocity/acceleration."); return; } @@ -428,8 +442,9 @@ void calculateJointVelAndAcc( double dt = trajectory[i].time_from_start - trajectory[i - 1].time_from_start; if (dt <= 0.0) { - std::cerr << "[calculateJointVelAndAcc] Warning: non-positive time diff at index " << i - << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateJointVelAndAcc] Warning: non-positive time diff at index %zu", i); velocities.push_back(0.0); continue; } @@ -451,9 +466,10 @@ void calculateJointVelAndAcc( double dt = trajectory[i + 1].time_from_start - trajectory[i].time_from_start; if (dt <= 0.0) { - std::cerr - << "[calculateJointVelAndAcc] Warning: non-positive time diff for acceleration at index " - << i << std::endl; + RCLCPP_WARN( + rclcpp::get_logger("approx_primitives_with_rdp"), + "[calculateJointVelAndAcc] Warning: non-positive time diff for acceleration at index %zu", + i); accelerations.push_back(0.0); continue; } From c6a7e66ea23ef76ba24e2aedd9e2d006d9271001 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 16 Jul 2025 09:53:09 +0200 Subject: [PATCH 090/128] changed "added primitive ..." print in approx_primitives_with_rdp to DEBUG --- .../src/approx_primitives_with_rdp.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 59b3bc1e17..79f148db53 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -179,7 +179,7 @@ MotionSequence approxLinPrimitivesWithRDP( else reason = "unknown"; - RCLCPP_INFO( + RCLCPP_DEBUG( rclcpp::get_logger("approx_primitives_with_rdp"), "Added LIN Primitive [%zu] (%s): (x,y,z,qx,qy,qz,qw) = (%.4f, %.4f, %.4f, %.4f, %.4f, %.4f, " "%.4f), blend_radius = %.4f, move_time = %.4f, velocity = %.4f, acceleration = %.4f", @@ -309,7 +309,7 @@ MotionSequence approxPtpPrimitivesWithRDP( joint_stream << "), blend_radius = " << primitive.blend_radius << ", move_time = " << move_time << ", velocity = " << velocity << ", acceleration = " << acceleration; - RCLCPP_INFO(rclcpp::get_logger("approx_primitives_with_rdp"), "%s", joint_stream.str().c_str()); + RCLCPP_DEBUG(rclcpp::get_logger("approx_primitives_with_rdp"), "%s", joint_stream.str().c_str()); } motion_sequence.motions = motion_primitives; From e88c216ccc765755998aa1a5c14a9bf9bec6ba40 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 16 Jul 2025 09:53:39 +0200 Subject: [PATCH 091/128] moved fk_client_ initialisation from on_configure to on_activate --- .../src/motion_primitives_from_trajectory_controller.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 4a58d88597..6cac6bd2f0 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -99,8 +99,6 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o return controller_interface::CallbackReturn::ERROR; } - fk_client_ = std::make_shared(); - action_server_ = rclcpp_action::create_server( get_node()->get_node_base_interface(), get_node()->get_node_clock_interface(), get_node()->get_node_logging_interface(), get_node()->get_node_waitables_interface(), @@ -163,6 +161,8 @@ MotionPrimitivesFromTrajectoryController::state_interface_configuration() const controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::on_activate( const rclcpp_lifecycle::State & /*previous_state*/) { + fk_client_ = std::make_shared(); + reset_command_interfaces(); RCLCPP_DEBUG(get_node()->get_logger(), "Controller activated"); return controller_interface::CallbackReturn::SUCCESS; From f290219e4f8d2873110d554cb3d107c68ea8794c Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Wed, 16 Jul 2025 15:05:39 +0200 Subject: [PATCH 092/128] removed was_executing_ = false; in execution_status_==ExecutionState::IDLE --- .../src/motion_primitives_from_trajectory_controller.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 6cac6bd2f0..862a2e5ad3 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -207,7 +207,6 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda { case ExecutionState::IDLE: print_error_once_ = true; - was_executing_ = false; break; case ExecutionState::EXECUTING: if (!was_executing_) From 2f33e9035f3ceda0e35479a8fc9d860f35870335 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 17 Jul 2025 15:08:39 +0200 Subject: [PATCH 093/128] added filenames to compare.py --- ...ed_and_executed_trajectory.cpython-312.pyc | Bin 9691 -> 9677 bytes ...planned_and_reduced_points.cpython-312.pyc | Bin 9590 -> 9661 bytes .../__pycache__/fk_client.cpython-312.pyc | Bin 3260 -> 3260 bytes .../compare.py | 43 ++++++++++++++++-- 4 files changed, 39 insertions(+), 4 deletions(-) diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc b/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc index f0f2b8162bba65d83c0a314f3f5b346001e1621a..6697808af1372c02a8d13e4c8ecf3e079bc78463 100644 GIT binary patch delta 1678 zcmchXO-vg{6o6;F_Ihov|2Nq97lQ*hp$LPaG@wvKAV5k85LHb|yLDp+P_Th9t_rQN zBPFU)s{)!sE!0B}J&^X0q~wrGPrabDm27<3n&i}|61mhN?xj+t&U4hHs)W>BI`Vw` z=KahY@4h#CXMQ?k_(8ANB05@vA55D)8wNY`-bO=5FMADL)JBw)x`>KWi0UKUl}3ax zuRu}Z8wjC;K}*aM6HxEN;%tB^@-y+pD4q{S?%e&2XE^eeW|gv8`#Iy@{!ZJ)iqq85 zL1*F?i%=Ssd1MiZ&f_7ChF=>V@Y*%qs&2h^ec{WxoTsJW2p0I(TxeittjsEGTzd2g zha3SCG=4PvfY)V43%n~E-m2ZYbhq!Gu@D-}HxK3lL%H!csk@20I+*UuSZNCC+EY+F zvkSZG8rf*cL^JFo(Vd+uh|LE`Bu|XiNm+1jhHsd&k-ShRTdQQ7UAEBQ5!vD_>5)b( zBeh0bG9itS>0RaEl(OL2T)5%OF6IUQ-x0P-gzH}s$vv0u=)atf!BC9%Kd^h~4Q8S?FS_tulV;!6Mj|U{_)r zePBDF8c+p*PlTQ1iqq9-1<^;b%#Dvs^q;7~wVL&f{a`mNPba928A}Ab@^j zgj)e^fDlEIO(bKu9hMz{R{@=1;4aThC2_Q<3r8YSBKiLO?A#*m0`u#DZt|fk=sgLZ zd?LCiEzi!xa35HD0X=|z^1Z8mEKrR{V0D(FXt)%{i_-jDLW+lD(F8sRmNCFMm^Cjf z7eF})xCnR~@DAWz(&KJm!eq+b%|$_RncQ^OGE?M7_bcKxs#u^i(MVtCi-KNziDEuN zc0I|I%vW#vvSV3)o>s=8vLG8o*T+TCAFpd}a3FzDZ?p;!`CN4c#)*hB5^}l2}JW1Qj{}+KY`R+XH*Hi!O*X_qX zv%=I5MKb^x0!$N~zrFo=iQ-XELR}`Hk!zj}JVoWAG8UeR;|(h2z%G%b|5U#kZbEt& znXKu-N6H47x91$kx1@X1zq1Mzhp$5*FG&z8NdZHVn-9k$;RJ@}EUMzk*!&W1C4c(8 zOeb+4b)_oDgNqqMF;}udJoJks-9(iQE64eR?~ctylC#m1c$0cEbS9u7ODw}MPwNpQ z?jg%VQ delta 1713 zcmb7@ZA?>F7{~8vZ!Z`6POAu%VlA{Z>N4bIB3M8X5W;JD8zN2h7U*ngIW10c5lDO~ zF43`TA`&tizl>#Hs_p~XhlP*CZOOTmMJ$@k%xv+~8ug3&wDZ*LEt$(a$^G5uJkN8^ z|J-w*=lj;JR?W9+brwTMqvQ10CDXiS2lCI`EBhHi?#~J+2bG8s*bB^{N>EU$1&&hV z)e0G>N*D(7GRCX<5|-0}n6v0Ca`4Y!((XV>-Zvic;!vqTZLa=|H(b_m=d)jVlp$Wt zoTJ>4brqTKeV$b<&-T$JdGrZiku%H;^HgsTO=h!b)ckB+!ne-dJhxoB?D@(-Dw-0d z&56RJr1dxvyc^p`W;!0`mWUSZImgoBm^NX0H*Q%uv1m$d8 z$w)A&+~7n1$g|y^ShmC>l5tPmwc54jP3MImZ-VBDy}E%TYO0XZF$z8^n{9f)ZkO2Y zB&U3Xtw?dydAVh_<&(^X14L`vH0<0o7j2p?w}Ll=o5pRaOh%!7$*_u?ltz4^Yg4Z{ zNoydX8=pD)NS7_XvQ&v5>(#OVy0@sW$y8?0Tf;m+B|gd9XH-+uA;TK_dIoL>!dlUu zUs!ISlhLyD_^B3egE$Lu7Vn@hoC|uz%$Ij|F3!BYe% z2G}Ti@NV&&{J_v2aO?%_1JJ+8;4(ltpn@VP4^IYgB~0G~><3gqfE)3RPGWCT=@A5X zc=ANZAB^A{2-gD+ikD5Ld9{$qhrJQ^l;0P?4G=j5s1qNUY<;+m+Kyb@4z3Q0q~@dt zN8F)c*gftEc*D30BHaKNgfst&41)7G;22;CFbr^u?FDvpLOfkiqZ|RpC`C9|OsPyV zJSJ`x?9IMNJpw4fhZ?sC&?6H%ELCt{X`h@>haw*6o0 zSL#=clFdo#y4UFjef`AMFVzje9*USNp7pmq*cO!H#3zMC(@%BTH@JE3I=*p!{yee6 zE~P65$$pU3cCB~2NKY^6?v-l$h^;@7Gmy}||45~|);QOAecuh|ypveV?{>u};x5Tr zMXKBGdq`*3+DWOpo9uEW3_S@|Z%U4I{b;874LZ~RA@sH<1F2(gmikwvy4Tf%CFCGIUYO~dJu#z4sLjs%1LQ@%*}9Xbg{$^=YH znjRMbWu86tfK3X>Ek3{5LV%wsP=bL|xSzk1e+J`44yhSN z7dhl^a0rnq@PU(6h^@iv3lD>!(Bv6H7WE$(*jd?ba0-542GS2Wh5F??z-jP(MnQk@(fj2)&oIJi3; zJK6fVJGpQ02v2gHP&mP*(|3XL2E`qgC)_SX#eQIB;1v17z{JS~3{C^f9rBm;J-;(E zNpjs()m{*|g84-7$@q@o3FFg8PuL~$#6i~RJXn0w`=(>Q_MFA_Yf1Q#2J9&bL3-8ZQ)r<_X z);~Yn0iCg#OYt=mU?joA@QdoW2e`ZIp8 JnH;Yw4giCA*x>*G delta 608 zcmdn%{mqN-G%qg~0}#|{mSxFn}}^(z?Hv#w-a&Ax$gJL^W) z&Fm}rcL?qm-6^_T{D9zb(SxFg#dpeI5c9mu>oxhW@OIuEb{D*>E(=sQc-|2Zn*3kE zWiyv(1SeYpDAcZQ&XBWUWaOE=P+r)7g8MAT8HF=kCi<>W-l2HF@aeM#j%-42)d28H8>#2;XIpzsq3wiN%GHF^ut(ACo1Bs$i66^k@8F#lXVTQFVz~ T@+J#MtJ?==1{SHJLZBG{af;;; diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/fk_client.cpython-312.pyc b/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/fk_client.cpython-312.pyc index 4aeb7643743ae206b8b95e27c31bc5fab6d965dc..287a000aca71fce5b7a3ecd1d12519e5fec7e1b3 100644 GIT binary patch delta 64 zcmdlZxkr-gG%qg~0}wj%6JSqr&F19D5lVO(%DAO<@$@tibKT$jhR@ SDA`f+g#k!?aG6}n;|>58{Se&% diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py index 2ab17d65b3..d0cc1e8c3f 100755 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py +++ b/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py @@ -42,16 +42,51 @@ def main(): data_dir = "src/ros2_controllers/motion_primitives_forward_controller/data" - filename_planned = "trajectory_20250715_114409_planned.csv" - filename_executed = "trajectory_20250715_114409_executed.csv" - filename_reduced = "trajectory_20250715_114409_reduced_PTP.csv" - mode = "joint" + # filename_planned = "trajectory_20250715_114409_planned.csv" + # filename_executed = "trajectory_20250715_114409_executed.csv" + # filename_reduced = "trajectory_20250715_114409_reduced_PTP.csv" + # mode = "joint" # filename_planned = "trajectory_20250715_114057_planned.csv" # filename_executed = "trajectory_20250715_114057_executed.csv" # filename_reduced = "trajectory_20250715_114057_reduced_LIN.csv" # mode = "cartesian" + # filename_planned = "trajectory_20250716_090701_planned.csv" + # filename_executed = "trajectory_20250716_090701_executed.csv" + # filename_reduced = "trajectory_20250716_090701_reduced_LIN.csv" + # mode = "cartesian" + + # filename_planned = "trajectory_20250716_091324_planned.csv" + # filename_executed = "trajectory_20250716_091324_executed.csv" + # filename_reduced = "trajectory_20250716_091324_reduced_LIN.csv" + # mode = "cartesian" + + # filename_planned = "trajectory_20250716_092410_planned.csv" + # filename_executed = "trajectory_20250716_092410_executed.csv" + # filename_reduced = "trajectory_20250716_092410_reduced_PTP.csv" + # mode = "joint" + + # filename_planned = "trajectory_20250716_093119_planned.csv" + # filename_executed = "trajectory_20250716_093119_executed.csv" + # filename_reduced = "trajectory_20250716_093119_reduced_PTP.csv" + # mode = "joint" + + # filename_planned = "trajectory_20250716_093707_planned.csv" + # filename_executed = "trajectory_20250716_093707_executed.csv" + # filename_reduced = "trajectory_20250716_093707_reduced_PTP.csv" + # mode = "joint" + + # filename_planned = "trajectory_20250716_101518_planned.csv" + # filename_executed = "trajectory_20250716_101518_executed.csv" + # filename_reduced = "trajectory_20250716_101518_reduced_LIN.csv" + # mode = "cartesian" + + filename_planned = "trajectory_20250716_101907_planned.csv" + filename_executed = "trajectory_20250716_101907_executed.csv" + filename_reduced = "trajectory_20250716_101907_reduced_LIN.csv" + mode = "cartesian" + filepath_planned = os.path.join(data_dir, filename_planned) filepath_executed = os.path.join(data_dir, filename_executed) filepath_reduced = os.path.join(data_dir, filename_reduced) From c1e08f8e3991b1ca00c063100947102a08dce384 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 17 Jul 2025 15:37:12 +0200 Subject: [PATCH 094/128] pass full interface names to the controller (such as $(var tf_prefix)motion_primitive/q1) --- .../src/motion_primitives_forward_controller.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 238c2e3b87..95186ccedc 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -94,7 +94,7 @@ MotionPrimitivesForwardController::command_interface_configuration() const // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - command_interfaces_config.names.push_back("motion_primitive/" + interface_name); + command_interfaces_config.names.push_back(interface_name); } return command_interfaces_config; } @@ -110,7 +110,7 @@ MotionPrimitivesForwardController::state_interface_configuration() const // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - state_interfaces_config.names.push_back("motion_primitive/" + interface_name); + state_interfaces_config.names.push_back(interface_name); } return state_interfaces_config; } From a97c200ca0c73e8ae9edc3f173186b89dcb2738b Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 17 Jul 2025 15:41:46 +0200 Subject: [PATCH 095/128] pass full interface names to the controller (such as $(var tf_prefix)motion_primitive/q1) --- .../src/motion_primitives_forward_controller.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 238c2e3b87..95186ccedc 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -94,7 +94,7 @@ MotionPrimitivesForwardController::command_interface_configuration() const // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - command_interfaces_config.names.push_back("motion_primitive/" + interface_name); + command_interfaces_config.names.push_back(interface_name); } return command_interfaces_config; } @@ -110,7 +110,7 @@ MotionPrimitivesForwardController::state_interface_configuration() const // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - state_interfaces_config.names.push_back("motion_primitive/" + interface_name); + state_interfaces_config.names.push_back(interface_name); } return state_interfaces_config; } From 5102a827e83283fcf08409218e3f55286457c24f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Thu, 17 Jul 2025 17:38:54 +0200 Subject: [PATCH 096/128] Wrapped rt_goal_handle_ in RealtimeThreadSafeBox and introduced std::atomic has_active_goal_ to ensure only one action goal is accepted at a time. --- .../motion_primitives_forward_controller.hpp | 4 +- .../motion_primitives_forward_controller.cpp | 48 ++++++++++++------- 2 files changed, 34 insertions(+), 18 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp index 88b68f853d..f5e53e1b66 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_forward_controller.hpp @@ -30,6 +30,7 @@ #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" #include "realtime_tools/realtime_publisher.hpp" +#include "realtime_tools/realtime_thread_safe_box.hpp" #include "control_msgs/action/execute_motion_primitive_sequence.hpp" #include "control_msgs/msg/motion_primitive.hpp" @@ -101,7 +102,8 @@ class MotionPrimitivesForwardController : public controller_interface::Controlle void goal_accepted_callback( std::shared_ptr> goal_handle); using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle; - std::shared_ptr realtime_goal_handle_; + realtime_tools::RealtimeThreadSafeBox> rt_goal_handle_; + std::atomic has_active_goal_ = false; rclcpp::TimerBase::SharedPtr goal_handle_timer_; rclcpp::Duration action_monitor_period_ = rclcpp::Duration(std::chrono::milliseconds(20)); diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 95186ccedc..6fe3e6efbe 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -172,31 +172,35 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::SUCCESS: print_error_once_ = true; - - if (realtime_goal_handle_ && was_executing_) + if(has_active_goal_ && was_executing_) { - was_executing_ = false; - auto result = std::make_shared(); - result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; - result->error_string = "Motion primitives executed successfully"; - realtime_goal_handle_->setSucceeded(result); - realtime_goal_handle_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + goal_handle->setSucceeded(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + }); } + break; case ExecutionState::STOPPED: print_error_once_ = true; was_executing_ = false; - - if (realtime_goal_handle_) + if(has_active_goal_) { - auto result = std::make_shared(); - realtime_goal_handle_->setCanceled(result); - realtime_goal_handle_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) + { + auto result = std::make_shared(); + goal_handle->setCanceled(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + }); } - if (robot_stop_requested_) { // If the robot was stopped by a stop command, reset the command interfaces @@ -360,6 +364,13 @@ rclcpp_action::GoalResponse MotionPrimitivesForwardController::goal_received_cal { RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); + if (has_active_goal_) + { + RCLCPP_WARN( + get_node()->get_logger(), "Already has an active goal, rejecting new goal request."); + return rclcpp_action::GoalResponse::REJECT; + } + const auto & primitives = goal->trajectory.motions; if (robot_stop_requested_) @@ -493,7 +504,10 @@ void MotionPrimitivesForwardController::goal_accepted_callback( } auto rt_goal = std::make_shared(goal_handle); - realtime_goal_handle_ = rt_goal; + rt_goal_handle_.set([&](auto& handle) { + handle = rt_goal; + has_active_goal_ = true; + }); rt_goal->execute(); From b47e7eab36b43fbb8f9a7089ccfa7189192c8b20 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Fri, 18 Jul 2025 08:57:52 +0200 Subject: [PATCH 097/128] Moprim_from_traj_controller: pass full interface names to the controller (such as $(var tf_prefix)motion_primitive/q1) --- .../src/motion_primitives_from_trajectory_controller.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 862a2e5ad3..2b4772fa71 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -137,7 +137,7 @@ MotionPrimitivesFromTrajectoryController::command_interface_configuration() cons // Iterate over all command interfaces from the config yaml file for (const auto & interface_name : params_.command_interfaces) { - command_interfaces_config.names.push_back("motion_primitive/" + interface_name); + command_interfaces_config.names.push_back(interface_name); } return command_interfaces_config; } @@ -153,7 +153,7 @@ MotionPrimitivesFromTrajectoryController::state_interface_configuration() const // Iterate over all state interfaces from the config yaml file for (const auto & interface_name : params_.state_interfaces) { - state_interfaces_config.names.push_back("motion_primitive/" + interface_name); + state_interfaces_config.names.push_back(interface_name); } return state_interfaces_config; } From e4e37e7cdcee8ff74b4bc86ddcdfc5ead4df67b5 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Fri, 18 Jul 2025 09:02:48 +0200 Subject: [PATCH 098/128] Moprim_from_traj_controller: Wrapped rt_goal_handle_ in RealtimeThreadSafeBox and introduced std::atomic has_active_goal_ to ensure only one action goal is accepted at a time." auch in diesen controller integrieren --- ..._primitives_from_trajectory_controller.hpp | 4 +- .../src/approx_primitives_with_rdp.cpp | 3 +- .../motion_primitives_forward_controller.cpp | 50 ++++++++++--------- ..._primitives_from_trajectory_controller.cpp | 49 ++++++++++++------ 4 files changed, 66 insertions(+), 40 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index cfb5271b44..a3cd9d4ff4 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -31,6 +31,7 @@ #include "rclcpp_lifecycle/state.hpp" #include "realtime_tools/realtime_buffer.hpp" #include "realtime_tools/realtime_publisher.hpp" +#include "realtime_tools/realtime_thread_safe_box.hpp" #include "control_msgs/action/execute_motion_primitive_sequence.hpp" #include "control_msgs/msg/motion_primitive.hpp" @@ -112,7 +113,8 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co void goal_accepted_callback( std::shared_ptr> goal_handle); using RealtimeGoalHandle = realtime_tools::RealtimeServerGoalHandle; - std::shared_ptr realtime_goal_handle_; + realtime_tools::RealtimeThreadSafeBox> rt_goal_handle_; + std::atomic has_active_goal_ = false; rclcpp::TimerBase::SharedPtr goal_handle_timer_; rclcpp::Duration action_monitor_period_ = rclcpp::Duration(std::chrono::milliseconds(20)); diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 79f148db53..d1851158e3 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -309,7 +309,8 @@ MotionSequence approxPtpPrimitivesWithRDP( joint_stream << "), blend_radius = " << primitive.blend_radius << ", move_time = " << move_time << ", velocity = " << velocity << ", acceleration = " << acceleration; - RCLCPP_DEBUG(rclcpp::get_logger("approx_primitives_with_rdp"), "%s", joint_stream.str().c_str()); + RCLCPP_DEBUG( + rclcpp::get_logger("approx_primitives_with_rdp"), "%s", joint_stream.str().c_str()); } motion_sequence.motions = motion_primitives; diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 6fe3e6efbe..578e7dd224 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -172,18 +172,19 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::SUCCESS: print_error_once_ = true; - if(has_active_goal_ && was_executing_) + if (has_active_goal_ && was_executing_) { - rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) - { - was_executing_ = false; - auto result = std::make_shared(); - result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; - result->error_string = "Motion primitives executed successfully"; - goal_handle->setSucceeded(result); - has_active_goal_ = false; - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); - }); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + goal_handle->setSucceeded(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + }); } break; @@ -191,15 +192,16 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::STOPPED: print_error_once_ = true; was_executing_ = false; - if(has_active_goal_) + if (has_active_goal_) { - rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) - { - auto result = std::make_shared(); - goal_handle->setCanceled(result); - has_active_goal_ = false; - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); - }); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + auto result = std::make_shared(); + goal_handle->setCanceled(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + }); } if (robot_stop_requested_) { @@ -504,10 +506,12 @@ void MotionPrimitivesForwardController::goal_accepted_callback( } auto rt_goal = std::make_shared(goal_handle); - rt_goal_handle_.set([&](auto& handle) { - handle = rt_goal; - has_active_goal_ = true; - }); + rt_goal_handle_.set( + [&](auto & handle) + { + handle = rt_goal; + has_active_goal_ = true; + }); rt_goal->execute(); diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 2b4772fa71..4faf7b7f07 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -218,16 +218,19 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda case ExecutionState::SUCCESS: print_error_once_ = true; - - if (realtime_goal_handle_ && was_executing_) + if (has_active_goal_ && was_executing_) { - was_executing_ = false; - auto result = std::make_shared(); - result->error_code = FollowJTrajAction::Result::SUCCESSFUL; - result->error_string = "Motion primitives executed successfully"; - realtime_goal_handle_->setSucceeded(result); - realtime_goal_handle_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = FollowJTrajAction::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + goal_handle->setSucceeded(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + }); } break; @@ -235,12 +238,16 @@ controller_interface::return_type MotionPrimitivesFromTrajectoryController::upda print_error_once_ = true; was_executing_ = false; - if (realtime_goal_handle_) + if (has_active_goal_) { - auto result = std::make_shared(); - realtime_goal_handle_->setCanceled(result); - realtime_goal_handle_.reset(); - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + auto result = std::make_shared(); + goal_handle->setCanceled(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + }); } if (robot_stop_requested_) @@ -406,6 +413,13 @@ rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_recei { RCLCPP_INFO(get_node()->get_logger(), "Received new action goal"); + if (has_active_goal_) + { + RCLCPP_WARN( + get_node()->get_logger(), "Already has an active goal, rejecting new goal request."); + return rclcpp_action::GoalResponse::REJECT; + } + if (robot_stop_requested_) { RCLCPP_WARN(get_node()->get_logger(), "Robot requested to stop. Discarding the new command."); @@ -546,7 +560,12 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } auto rt_goal = std::make_shared(goal_handle); - realtime_goal_handle_ = rt_goal; + rt_goal_handle_.set( + [&](auto & handle) + { + handle = rt_goal; + has_active_goal_ = true; + }); rt_goal->execute(); From 71d3b6b8e7632c16abcac9131e0180d6f5d986f7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Sun, 20 Jul 2025 20:29:23 +0200 Subject: [PATCH 099/128] Update ros2_controllers.rolling.repos --- ros2_controllers.rolling.repos | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ros2_controllers.rolling.repos b/ros2_controllers.rolling.repos index f4ee54e9c3..f6462c4b4f 100644 --- a/ros2_controllers.rolling.repos +++ b/ros2_controllers.rolling.repos @@ -9,10 +9,8 @@ repositories: version: master control_msgs: type: git - url: https://github.com/urfeex/control_msgs.git - version: motion_primitives - # url: https://github.com/ros-controls/control_msgs.git - # version: master + url: https://github.com/ros-controls/control_msgs.git + version: master control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git From e5457e4bbae207db7329d4a10e4cee1a7b7dd17f Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 09:37:04 +0200 Subject: [PATCH 100/128] pre-commit fix --- .../motion_primitives_forward_controller.cpp | 50 ++++++++++--------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 6fe3e6efbe..578e7dd224 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -172,18 +172,19 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::SUCCESS: print_error_once_ = true; - if(has_active_goal_ && was_executing_) + if (has_active_goal_ && was_executing_) { - rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) - { - was_executing_ = false; - auto result = std::make_shared(); - result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; - result->error_string = "Motion primitives executed successfully"; - goal_handle->setSucceeded(result); - has_active_goal_ = false; - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); - }); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + was_executing_ = false; + auto result = std::make_shared(); + result->error_code = ExecuteMotionAction::Result::SUCCESSFUL; + result->error_string = "Motion primitives executed successfully"; + goal_handle->setSucceeded(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives executed successfully."); + }); } break; @@ -191,15 +192,16 @@ controller_interface::return_type MotionPrimitivesForwardController::update( case ExecutionState::STOPPED: print_error_once_ = true; was_executing_ = false; - if(has_active_goal_) + if (has_active_goal_) { - rt_goal_handle_.try_get([&](const std::shared_ptr& goal_handle) - { - auto result = std::make_shared(); - goal_handle->setCanceled(result); - has_active_goal_ = false; - RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); - }); + rt_goal_handle_.try_get( + [&](const std::shared_ptr & goal_handle) + { + auto result = std::make_shared(); + goal_handle->setCanceled(result); + has_active_goal_ = false; + RCLCPP_INFO(get_node()->get_logger(), "Motion primitives execution canceled."); + }); } if (robot_stop_requested_) { @@ -504,10 +506,12 @@ void MotionPrimitivesForwardController::goal_accepted_callback( } auto rt_goal = std::make_shared(goal_handle); - rt_goal_handle_.set([&](auto& handle) { - handle = rt_goal; - has_active_goal_ = true; - }); + rt_goal_handle_.set( + [&](auto & handle) + { + handle = rt_goal; + has_active_goal_ = true; + }); rt_goal->execute(); From 2f205c12fc73b2ecd01ec8c621cd2e54e5e42cfb Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 09:37:26 +0200 Subject: [PATCH 101/128] modified tests for full cmd and state interface names --- ..._primitives_forward_controller_params.yaml | 54 +++++++++---------- ..._forward_controller_preceeding_params.yaml | 54 +++++++++---------- ...t_motion_primitives_forward_controller.cpp | 37 +++++++++---- ...imitives_forward_controller_preceeding.cpp | 37 +++++++++---- 4 files changed, 106 insertions(+), 76 deletions(-) diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml index 6a46535909..8d3bfe495b 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_params.yaml @@ -1,31 +1,31 @@ test_motion_primitives_forward_controller: ros__parameters: command_interfaces: - - motion_type - - q1 - - q2 - - q3 - - q4 - - q5 - - q6 - - pos_x - - pos_y - - pos_z - - pos_qx - - pos_qy - - pos_qz - - pos_qw - - pos_via_x - - pos_via_y - - pos_via_z - - pos_via_qx - - pos_via_qy - - pos_via_qz - - pos_via_qw - - blend_radius - - velocity - - acceleration - - move_time + - motion_primitive/motion_type + - motion_primitive/q1 + - motion_primitive/q2 + - motion_primitive/q3 + - motion_primitive/q4 + - motion_primitive/q5 + - motion_primitive/q6 + - motion_primitive/pos_x + - motion_primitive/pos_y + - motion_primitive/pos_z + - motion_primitive/pos_qx + - motion_primitive/pos_qy + - motion_primitive/pos_qz + - motion_primitive/pos_qw + - motion_primitive/pos_via_x + - motion_primitive/pos_via_y + - motion_primitive/pos_via_z + - motion_primitive/pos_via_qx + - motion_primitive/pos_via_qy + - motion_primitive/pos_via_qz + - motion_primitive/pos_via_qw + - motion_primitive/blend_radius + - motion_primitive/velocity + - motion_primitive/acceleration + - motion_primitive/move_time state_interfaces: - - execution_status - - ready_for_new_primitive + - motion_primitive/execution_status + - motion_primitive/ready_for_new_primitive diff --git a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml index 6a46535909..8d3bfe495b 100644 --- a/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml +++ b/motion_primitives_forward_controller/test/motion_primitives_forward_controller_preceeding_params.yaml @@ -1,31 +1,31 @@ test_motion_primitives_forward_controller: ros__parameters: command_interfaces: - - motion_type - - q1 - - q2 - - q3 - - q4 - - q5 - - q6 - - pos_x - - pos_y - - pos_z - - pos_qx - - pos_qy - - pos_qz - - pos_qw - - pos_via_x - - pos_via_y - - pos_via_z - - pos_via_qx - - pos_via_qy - - pos_via_qz - - pos_via_qw - - blend_radius - - velocity - - acceleration - - move_time + - motion_primitive/motion_type + - motion_primitive/q1 + - motion_primitive/q2 + - motion_primitive/q3 + - motion_primitive/q4 + - motion_primitive/q5 + - motion_primitive/q6 + - motion_primitive/pos_x + - motion_primitive/pos_y + - motion_primitive/pos_z + - motion_primitive/pos_qx + - motion_primitive/pos_qy + - motion_primitive/pos_qz + - motion_primitive/pos_qw + - motion_primitive/pos_via_x + - motion_primitive/pos_via_y + - motion_primitive/pos_via_z + - motion_primitive/pos_via_qx + - motion_primitive/pos_via_qy + - motion_primitive/pos_via_qz + - motion_primitive/pos_via_qw + - motion_primitive/blend_radius + - motion_primitive/velocity + - motion_primitive/acceleration + - motion_primitive/move_time state_interfaces: - - execution_status - - ready_for_new_primitive + - motion_primitive/execution_status + - motion_primitive/ready_for_new_primitive diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp index ed1e3317d7..dd4d7b6f0c 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.cpp @@ -37,30 +37,45 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + std::vector full_command_interface_names; + std::vector full_state_interface_names; + + std::transform( + command_interface_names_.begin(), command_interface_names_.end(), + std::back_inserter(full_command_interface_names), + [&](const std::string & name) { return interface_namespace_ + "/" + name; }); + + std::transform( + state_interface_names_.begin(), state_interface_names_.end(), + std::back_inserter(full_state_interface_names), + [&](const std::string & name) { return interface_namespace_ + "/" + name; }); + ASSERT_THAT( - controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + controller_->params_.command_interfaces, + testing::ElementsAreArray(full_command_interface_names)); ASSERT_THAT( - controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + controller_->params_.state_interfaces, testing::ElementsAreArray(full_state_interface_names)); } -TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +TEST_F(MotionPrimitivesForwardControllerTest, check_exported_interfaces) { SetUpController(); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - auto command_intefaces = controller_->command_interface_configuration(); - ASSERT_EQ(command_intefaces.names.size(), command_values_.size()); - for (size_t i = 0; i < command_intefaces.names.size(); ++i) + auto command_interfaces = controller_->command_interface_configuration(); + ASSERT_EQ(command_interfaces.names.size(), command_values_.size()); + for (size_t i = 0; i < command_interfaces.names.size(); ++i) { - EXPECT_EQ(command_intefaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); + EXPECT_EQ( + command_interfaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); } - auto state_intefaces = controller_->state_interface_configuration(); - ASSERT_EQ(state_intefaces.names.size(), state_values_.size()); - for (size_t i = 0; i < state_intefaces.names.size(); ++i) + auto state_interfaces = controller_->state_interface_configuration(); + ASSERT_EQ(state_interfaces.names.size(), state_values_.size()); + for (size_t i = 0; i < state_interfaces.names.size(); ++i) { - EXPECT_EQ(state_intefaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); + EXPECT_EQ(state_interfaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); } } diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp index c738b31c5c..7d08329323 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller_preceeding.cpp @@ -36,30 +36,45 @@ TEST_F(MotionPrimitivesForwardControllerTest, all_parameters_set_configure_succe ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); + std::vector full_command_interface_names; + std::vector full_state_interface_names; + + std::transform( + command_interface_names_.begin(), command_interface_names_.end(), + std::back_inserter(full_command_interface_names), + [&](const std::string & name) { return interface_namespace_ + "/" + name; }); + + std::transform( + state_interface_names_.begin(), state_interface_names_.end(), + std::back_inserter(full_state_interface_names), + [&](const std::string & name) { return interface_namespace_ + "/" + name; }); + ASSERT_THAT( - controller_->params_.command_interfaces, testing::ElementsAreArray(command_interface_names_)); + controller_->params_.command_interfaces, + testing::ElementsAreArray(full_command_interface_names)); ASSERT_THAT( - controller_->params_.state_interfaces, testing::ElementsAreArray(state_interface_names_)); + controller_->params_.state_interfaces, testing::ElementsAreArray(full_state_interface_names)); } -TEST_F(MotionPrimitivesForwardControllerTest, check_exported_intefaces) +TEST_F(MotionPrimitivesForwardControllerTest, check_exported_interfaces) { SetUpController(); ASSERT_EQ(controller_->on_configure(rclcpp_lifecycle::State()), NODE_SUCCESS); - auto command_intefaces = controller_->command_interface_configuration(); - ASSERT_EQ(command_intefaces.names.size(), command_values_.size()); - for (size_t i = 0; i < command_intefaces.names.size(); ++i) + auto command_interfaces = controller_->command_interface_configuration(); + ASSERT_EQ(command_interfaces.names.size(), command_values_.size()); + for (size_t i = 0; i < command_interfaces.names.size(); ++i) { - EXPECT_EQ(command_intefaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); + EXPECT_EQ( + command_interfaces.names[i], interface_namespace_ + "/" + command_interface_names_[i]); } - auto state_intefaces = controller_->state_interface_configuration(); - ASSERT_EQ(state_intefaces.names.size(), state_values_.size()); - for (size_t i = 0; i < state_intefaces.names.size(); ++i) + auto state_interfaces = controller_->state_interface_configuration(); + ASSERT_EQ(state_interfaces.names.size(), state_values_.size()); + for (size_t i = 0; i < state_interfaces.names.size(); ++i) { - EXPECT_EQ(state_intefaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); + EXPECT_EQ(state_interfaces.names[i], interface_namespace_ + "/" + state_interface_names_[i]); } } From b2550d125fe28ea06cfcdcaa06ca4e9f84500ede Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 10:12:33 +0200 Subject: [PATCH 102/128] argument_name --> name, argument_value --> value --- .../src/motion_primitives_forward_controller.cpp | 15 +++++++-------- .../test_motion_primitives_forward_controller.hpp | 12 ++++++------ 2 files changed, 13 insertions(+), 14 deletions(-) diff --git a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp index 578e7dd224..a81b89d71c 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_forward_controller.cpp @@ -340,22 +340,21 @@ bool MotionPrimitivesForwardController::set_command_interfaces() // Read additional arguments for (const auto & arg : current_moprim_.additional_arguments) { - if (arg.argument_name == "velocity") + if (arg.name == "velocity") { - (void)command_interfaces_[22].set_value(arg.argument_value); + (void)command_interfaces_[22].set_value(arg.value); } - else if (arg.argument_name == "acceleration") + else if (arg.name == "acceleration") { - (void)command_interfaces_[23].set_value(arg.argument_value); + (void)command_interfaces_[23].set_value(arg.value); } - else if (arg.argument_name == "move_time") + else if (arg.name == "move_time") { - (void)command_interfaces_[24].set_value(arg.argument_value); + (void)command_interfaces_[24].set_value(arg.value); } else { - RCLCPP_WARN( - get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); + RCLCPP_WARN(get_node()->get_logger(), "Unknown additional argument: %s", arg.name.c_str()); } } return true; diff --git a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp index 5915f37041..bbefe63dbc 100644 --- a/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp +++ b/motion_primitives_forward_controller/test/test_motion_primitives_forward_controller.hpp @@ -164,12 +164,12 @@ class MotionPrimitivesForwardControllerFixture : public ::testing::Test primitive.blend_radius = blend_radius; primitive.additional_arguments.resize(3); - primitive.additional_arguments[0].argument_name = "velocity"; - primitive.additional_arguments[0].argument_value = velocity; - primitive.additional_arguments[1].argument_name = "acceleration"; - primitive.additional_arguments[1].argument_value = acceleration; - primitive.additional_arguments[2].argument_name = "move_time"; - primitive.additional_arguments[2].argument_value = move_time; + primitive.additional_arguments[0].name = "velocity"; + primitive.additional_arguments[0].value = velocity; + primitive.additional_arguments[1].name = "acceleration"; + primitive.additional_arguments[1].value = acceleration; + primitive.additional_arguments[2].name = "move_time"; + primitive.additional_arguments[2].value = move_time; goal_msg.trajectory.motions.push_back(primitive); From bf53eda062d0baf8fbd670d46608acda83e7f927 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 10:22:19 +0200 Subject: [PATCH 103/128] argument_name --> name, argument_value --> value --- .../src/approx_primitives_with_rdp.cpp | 24 +++++++++---------- ..._primitives_from_trajectory_controller.cpp | 15 ++++++------ 2 files changed, 19 insertions(+), 20 deletions(-) diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index d1851158e3..b75bb63b47 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -134,8 +134,8 @@ MotionSequence approxLinPrimitivesWithRDP( { move_time = trajectory[end_index].time_from_start - trajectory[start_index].time_from_start; MotionArgument arg_time; - arg_time.argument_name = "move_time"; - arg_time.argument_value = move_time; + arg_time.name = "move_time"; + arg_time.value = move_time; primitive.additional_arguments.push_back(arg_time); } else @@ -151,13 +151,13 @@ MotionSequence approxLinPrimitivesWithRDP( acceleration = max_acc; MotionArgument arg_vel; - arg_vel.argument_name = "velocity"; - arg_vel.argument_value = velocity; + arg_vel.name = "velocity"; + arg_vel.value = velocity; primitive.additional_arguments.push_back(arg_vel); MotionArgument arg_acc; - arg_acc.argument_name = "acceleration"; - arg_acc.argument_value = acceleration; + arg_acc.name = "acceleration"; + arg_acc.value = acceleration; primitive.additional_arguments.push_back(arg_acc); } @@ -262,8 +262,8 @@ MotionSequence approxPtpPrimitivesWithRDP( move_time = curr_time - prev_time; MotionArgument arg_time; - arg_time.argument_name = "move_time"; - arg_time.argument_value = move_time; + arg_time.name = "move_time"; + arg_time.value = move_time; primitive.additional_arguments.push_back(arg_time); } else @@ -286,13 +286,13 @@ MotionSequence approxPtpPrimitivesWithRDP( acceleration = max_acc; MotionArgument arg_vel; - arg_vel.argument_name = "velocity"; - arg_vel.argument_value = velocity; + arg_vel.name = "velocity"; + arg_vel.value = velocity; primitive.additional_arguments.push_back(arg_vel); MotionArgument arg_acc; - arg_acc.argument_name = "acceleration"; - arg_acc.argument_value = acceleration; + arg_acc.name = "acceleration"; + arg_acc.value = acceleration; primitive.additional_arguments.push_back(arg_acc); } diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 4faf7b7f07..1c6a2732db 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -387,22 +387,21 @@ bool MotionPrimitivesFromTrajectoryController::set_command_interfaces() // Read additional arguments for (const auto & arg : current_moprim_.additional_arguments) { - if (arg.argument_name == "velocity") + if (arg.name == "velocity") { - (void)command_interfaces_[22].set_value(arg.argument_value); + (void)command_interfaces_[22].set_value(arg.value); } - else if (arg.argument_name == "acceleration") + else if (arg.name == "acceleration") { - (void)command_interfaces_[23].set_value(arg.argument_value); + (void)command_interfaces_[23].set_value(arg.value); } - else if (arg.argument_name == "move_time") + else if (arg.name == "move_time") { - (void)command_interfaces_[24].set_value(arg.argument_value); + (void)command_interfaces_[24].set_value(arg.value); } else { - RCLCPP_WARN( - get_node()->get_logger(), "Unknown additional argument: %s", arg.argument_name.c_str()); + RCLCPP_WARN(get_node()->get_logger(), "Unknown additional argument: %s", arg.name.c_str()); } } return true; From fc46588f3ffc40165eca923d451ffe9192c610bc Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 13:19:20 +0200 Subject: [PATCH 104/128] PTP: For velocity and acceleration, the maximum values from the joint trajectory are used. LIN: For velocity and acceleration, values are calculated based on time intervals and Cartesian distances, and the maximum value is taken. Alternatively, fixed values can be provided using vel_override and acc_override. --- .../approx_primitives_with_rdp.hpp | 15 +- ..._primitives_from_trajectory_controller.hpp | 15 ++ .../src/approx_primitives_with_rdp.cpp | 197 +++--------------- ..._primitives_from_trajectory_controller.cpp | 136 +++++++++++- ...primitives_from_trajectory_controller.yaml | 30 +++ 5 files changed, 203 insertions(+), 190 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index 1084e4d396..faf11f3780 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -40,25 +40,16 @@ struct PlannedTrajectoryPoint // Approximate with LIN Primitives in Cartesian Space MotionSequence approxLinPrimitivesWithRDP( const std::vector & trajectory, double epsilon_position, - double epsilon_angle, bool use_time_not_vel_and_acc = false); + double epsilon_angle, double cart_vel, double cart_acc, bool use_time_not_vel_and_acc = false); // Approximate with PTP Primitives in Joint Space MotionSequence approxPtpPrimitivesWithRDP( - const std::vector & trajectory, double epsilon, - bool use_time_not_vel_and_acc = false); + const std::vector & trajectory, double epsilon, double joint_vel, + double joint_acc, bool use_time_not_vel_and_acc = false); double calculateBlendRadius( const rdp::Point & previous_point, const rdp::Point & current_point, const rdp::Point & next_point); - -void calculateCartVelAndAcc( - const std::vector & trajectory, - std::vector & velocities, std::vector & accelerations); - -void calculateJointVelAndAcc( - const std::vector & trajectory, - std::vector & velocities, std::vector & accelerations); - } // namespace approx_primitives_with_rdp #endif // MOTION_PRIMITIVES_FORWARD_CONTROLLER__APPROX_PRIMITIVES_WITH_RDP_HPP_ diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index a3cd9d4ff4..28619f9658 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -140,6 +140,21 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co double epsilon_cart_position_; double epsilon_cart_angle_; + double joint_vel_overwrite_; + double joint_acc_overwrite_; + double max_traj_joint_vel_; + double max_traj_joint_acc_; + void get_max_traj_joint_vel_and_acc( + const std::shared_ptr & trajectory_msg, + double & max_traj_joint_vel, double & max_traj_joint_acc); + double cart_vel_overwrite_; + double cart_acc_overwrite_; + double max_traj_cart_vel_; + double max_traj_cart_acc_; + void get_max_traj_cart_vel_and_acc( + const geometry_msgs::msg::PoseArray & planned_poses_msg, + const std::vector & time_from_start, double & max_vel, double & max_acc); + rclcpp::Publisher::SharedPtr planned_trajectory_publisher_; rclcpp::Publisher::SharedPtr planned_poses_publisher_; rclcpp::Publisher::SharedPtr diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index b75bb63b47..18155e50ab 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -31,7 +31,8 @@ namespace approx_primitives_with_rdp MotionSequence approxLinPrimitivesWithRDP( const std::vector & trajectory, - double epsilon_position, double epsilon_angle, bool use_time_not_vel_and_acc) + double epsilon_position, double epsilon_angle, double cart_vel, double cart_acc, + bool use_time_not_vel_and_acc) { MotionSequence motion_sequence; std::vector motion_primitives; @@ -72,7 +73,7 @@ MotionSequence approxLinPrimitivesWithRDP( if (end_index - start_index <= 1) continue; // nothing in between - // Extract quaternion segment + // Extract quaternion segment for RDP std::vector quats; for (size_t j = start_index; j <= end_index; ++j) { @@ -82,6 +83,7 @@ MotionSequence approxLinPrimitivesWithRDP( auto [reduced_quats, reduced_quat_indices] = rdp::rdpRecursiveQuaternion(quats, epsilon_angle, start_index); + // Add new orientation indices to final set for (size_t idx : reduced_quat_indices) { if (final_indices.insert(idx).second) // true if inserted (i.e., newly added) @@ -91,6 +93,7 @@ MotionSequence approxLinPrimitivesWithRDP( } } + // Sort final indices for ordered primitive generation std::vector sorted_final_indices(final_indices.begin(), final_indices.end()); std::sort(sorted_final_indices.begin(), sorted_final_indices.end()); @@ -100,10 +103,7 @@ MotionSequence approxLinPrimitivesWithRDP( "angle change (epsilon_angle = %.4f).", sorted_final_indices.size() - reduced_indices.size(), epsilon_angle); - // Compute cartesian velocity and acceleration between trajectory points - std::vector velocities, accelerations; - calculateCartVelAndAcc(trajectory, velocities, accelerations); - + // Generate motion primitives between reduced points for (size_t i = 1; i < sorted_final_indices.size(); ++i) { size_t start_index = sorted_final_indices[i - 1]; @@ -112,10 +112,10 @@ MotionSequence approxLinPrimitivesWithRDP( MotionPrimitive primitive; primitive.type = MotionPrimitive::LINEAR_CARTESIAN; - // Blend radius (zero at last point) + // Calculate blend radius based on the distance to the next and previous point if (i == sorted_final_indices.size() - 1) { - primitive.blend_radius = 0.0; + primitive.blend_radius = 0.0; // Last point has no blend radius } else { @@ -130,6 +130,7 @@ MotionSequence approxLinPrimitivesWithRDP( double acceleration = -1.0; double move_time = -1.0; + // Use time or velocity+acceleration based on use_time_not_vel_and_acc if (use_time_not_vel_and_acc) { move_time = trajectory[end_index].time_from_start - trajectory[start_index].time_from_start; @@ -140,16 +141,8 @@ MotionSequence approxLinPrimitivesWithRDP( } else { - // Use max velocity and acceleration in the reduced segment (min 0.01) - double max_vel = 0.01; - double max_acc = 0.01; - for (size_t j = start_index + 1; j <= end_index && j - 1 < velocities.size(); ++j) - max_vel = std::max(max_vel, velocities[j - 1]); - for (size_t j = start_index + 2; j <= end_index && j - 2 < accelerations.size(); ++j) - max_acc = std::max(max_acc, accelerations[j - 2]); - velocity = max_vel; - acceleration = max_acc; - + velocity = cart_vel; + acceleration = cart_acc; MotionArgument arg_vel; arg_vel.name = "velocity"; arg_vel.value = velocity; @@ -161,6 +154,7 @@ MotionSequence approxLinPrimitivesWithRDP( primitive.additional_arguments.push_back(arg_acc); } + // Add pose to primitive PoseStamped pose_stamped; pose_stamped.pose = trajectory[end_index].pose; primitive.poses.push_back(pose_stamped); @@ -196,7 +190,7 @@ MotionSequence approxLinPrimitivesWithRDP( MotionSequence approxPtpPrimitivesWithRDP( const std::vector & trajectory, - double epsilon, bool use_time_not_vel_and_acc) + double epsilon, double joint_vel, double joint_acc, bool use_time_not_vel_and_acc) { MotionSequence motion_sequence; std::vector motion_primitives; @@ -209,6 +203,7 @@ MotionSequence approxPtpPrimitivesWithRDP( return motion_sequence; } + // Collect joint positions for RDP rdp::PointList points; for (const auto & pt : trajectory) { @@ -217,18 +212,16 @@ MotionSequence approxPtpPrimitivesWithRDP( auto [reduced_points, reduced_indices] = rdp::rdpRecursive(points, epsilon); - // Compute joint velocities and accelerations between trajectory points - std::vector joint_velocities, joint_accelerations; - calculateJointVelAndAcc(trajectory, joint_velocities, joint_accelerations); - + // Generate motion primitives between reduced joint points for (size_t i = 1; i < reduced_points.size(); ++i) { MotionPrimitive primitive; primitive.type = MotionPrimitive::LINEAR_JOINT; + // Calculate blend radius based on the distance to the next and previous point if (i == reduced_points.size() - 1) { - primitive.blend_radius = 0.0; + primitive.blend_radius = 0.0; // Last point has no blend radius } else { @@ -252,11 +245,11 @@ MotionSequence approxPtpPrimitivesWithRDP( double acceleration = -1.0; double move_time = -1.0; - size_t start_index = reduced_indices[i - 1]; - size_t end_index = reduced_indices[i]; - + // Use time or velocity+acceleration based on use_time_not_vel_and_acc if (use_time_not_vel_and_acc) { + size_t start_index = reduced_indices[i - 1]; + size_t end_index = reduced_indices[i]; double prev_time = trajectory[start_index].time_from_start; double curr_time = trajectory[end_index].time_from_start; move_time = curr_time - prev_time; @@ -268,22 +261,8 @@ MotionSequence approxPtpPrimitivesWithRDP( } else { - // Get max velocity and acceleration in the reduced segment - double max_vel = 0.0; - double max_acc = 0.0; - - for (size_t j = start_index + 1; j <= end_index && j - 1 < joint_velocities.size(); ++j) - { - max_vel = std::max(max_vel, joint_velocities[j - 1]); - } - - for (size_t j = start_index + 2; j <= end_index && j - 2 < joint_accelerations.size(); ++j) - { - max_acc = std::max(max_acc, joint_accelerations[j - 2]); - } - - velocity = max_vel; - acceleration = max_acc; + velocity = joint_vel; + acceleration = joint_acc; MotionArgument arg_vel; arg_vel.name = "velocity"; @@ -339,10 +318,10 @@ double calculateBlendRadius( double min_dist = std::min(dist_prev, dist_next); double blend = 0.1 * min_dist; - // Clamp blend radius to [0, 0.1] with minimum threshold 0.001 + // Clamp blend radius to [0.001, 0.1] if (blend < 0.001) { - blend = 0.0; + blend = 0.001; } else if (blend > 0.1) { @@ -352,132 +331,4 @@ double calculateBlendRadius( return blend; } -void calculateCartVelAndAcc( - const std::vector & trajectory, - std::vector & velocities, std::vector & accelerations) -{ - velocities.clear(); - accelerations.clear(); - - size_t num_points = trajectory.size(); - if (num_points < 2) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateCartVelAndAcc] Warning: trajectory too short to calculate velocity/acceleration."); - return; - } - - for (size_t i = 1; i < num_points; ++i) - { - const auto & previous_position = trajectory[i - 1].pose.position; - const auto & current_position = trajectory[i].pose.position; - - double previous_time = trajectory[i - 1].time_from_start; - double current_time = trajectory[i].time_from_start; - double delta_time = current_time - previous_time; - - if (delta_time <= 0.0) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateCartVelAndAcc] Warning: non-positive time difference at index %zu", i); - velocities.push_back(0.0); - continue; - } - - double dx = current_position.x - previous_position.x; - double dy = current_position.y - previous_position.y; - double dz = current_position.z - previous_position.z; - double distance = std::sqrt(dx * dx + dy * dy + dz * dz); - - double velocity = distance / delta_time; - velocities.push_back(velocity); - } - - // Accelerations (starts at index 1 because it compares velocities[i] and velocities[i - 1]) - for (size_t i = 1; i < velocities.size(); ++i) - { - double time_interval = trajectory[i + 1].time_from_start - trajectory[i].time_from_start; - - if (time_interval <= 0.0) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateCartVelAndAcc] Warning: non-positive time difference for acceleration at index " - "%zu", - i); - accelerations.push_back(0.0); - continue; - } - - double delta_velocity = velocities[i] - velocities[i - 1]; - double acceleration = delta_velocity / time_interval; - - accelerations.push_back(std::abs(acceleration)); - } -} - -void calculateJointVelAndAcc( - const std::vector & trajectory, - std::vector & velocities, std::vector & accelerations) -{ - velocities.clear(); - accelerations.clear(); - - size_t num_points = trajectory.size(); - if (num_points < 2) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateJointVelAndAcc] Warning: trajectory too short to calculate joint " - "velocity/acceleration."); - return; - } - - size_t num_joints = trajectory[0].joint_positions.size(); - - // Compute joint velocities (max per timestep across joints) - for (size_t i = 1; i < num_points; ++i) - { - double dt = trajectory[i].time_from_start - trajectory[i - 1].time_from_start; - if (dt <= 0.0) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateJointVelAndAcc] Warning: non-positive time diff at index %zu", i); - velocities.push_back(0.0); - continue; - } - - double max_joint_vel = 0.0; - for (size_t j = 0; j < num_joints; ++j) - { - double dq = trajectory[i].joint_positions[j] - trajectory[i - 1].joint_positions[j]; - double vel = std::abs(dq / dt); - if (vel > max_joint_vel) max_joint_vel = vel; - } - - velocities.push_back(max_joint_vel); - } - - // Compute joint accelerations (max per timestep across joints) - for (size_t i = 1; i < velocities.size(); ++i) - { - double dt = trajectory[i + 1].time_from_start - trajectory[i].time_from_start; - if (dt <= 0.0) - { - RCLCPP_WARN( - rclcpp::get_logger("approx_primitives_with_rdp"), - "[calculateJointVelAndAcc] Warning: non-positive time diff for acceleration at index %zu", - i); - accelerations.push_back(0.0); - continue; - } - - double dvel = velocities[i] - velocities[i - 1]; - accelerations.push_back(std::abs(dvel / dt)); - } -} - } // namespace approx_primitives_with_rdp diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index 1c6a2732db..e458503fc6 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -83,6 +83,10 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o epsilon_joint_angle_ = params_.epsilon_joint_angle; epsilon_cart_position_ = params_.epsilon_cart_position; epsilon_cart_angle_ = params_.epsilon_cart_angle; + joint_vel_overwrite_ = params_.joint_vel_overwrite; + joint_acc_overwrite_ = params_.joint_acc_overwrite; + cart_vel_overwrite_ = params_.cart_vel_overwrite; + cart_acc_overwrite_ = params_.cart_acc_overwrite; // Check if there are exactly 25 command interfaces if (params_.command_interfaces.size() != 25) @@ -433,8 +437,6 @@ rclcpp_action::GoalResponse MotionPrimitivesFromTrajectoryController::goal_recei return rclcpp_action::GoalResponse::REJECT; } - // TODO(mathias31415): Check if first trajectory point matches the current robot state - RCLCPP_INFO(get_node()->get_logger(), "Accepted new action goal"); return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE; } @@ -472,10 +474,13 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( std::vector planned_trajectory_data; planned_trajectory_data.reserve(trajectory_msg->points.size()); + std::vector time_from_start; + time_from_start.reserve(planned_trajectory_data.size()); for (const auto & point : trajectory_msg->points) { approx_primitives_with_rdp::PlannedTrajectoryPoint pt; pt.time_from_start = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9; + time_from_start.push_back(pt.time_from_start); pt.joint_positions = point.positions; try { @@ -503,17 +508,53 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( { RCLCPP_INFO( get_node()->get_logger(), "Approximating motion primitives with PTP motion primitives."); + get_max_traj_joint_vel_and_acc(trajectory_msg, max_traj_joint_vel_, max_traj_joint_acc_); + RCLCPP_DEBUG( + get_node()->get_logger(), + "Max trajectory joint velocity: %.3f, Max trajectory joint acceleration: %.3f", + max_traj_joint_vel_, max_traj_joint_acc_); + RCLCPP_DEBUG( + get_node()->get_logger(), + "Joint velocity override: %.3f, Joint acceleration override: %.3f", joint_vel_overwrite_, + joint_acc_overwrite_); + if (joint_vel_overwrite_ > 0.0) + { + max_traj_joint_vel_ = joint_vel_overwrite_; + } + if (joint_acc_overwrite_ > 0.0) + { + max_traj_joint_acc_ = joint_acc_overwrite_; + } motion_sequence = approxPtpPrimitivesWithRDP( - planned_trajectory_data, epsilon_joint_angle_, use_time_not_vel_and_acc_); + planned_trajectory_data, epsilon_joint_angle_, max_traj_joint_vel_, max_traj_joint_acc_, + use_time_not_vel_and_acc_); break; } case ApproxMode::RDP_LIN: { RCLCPP_INFO( get_node()->get_logger(), "Approximating motion primitives with LIN motion primitives."); + get_max_traj_cart_vel_and_acc( + planned_poses_msg, time_from_start, max_traj_cart_vel_, max_traj_cart_acc_); + RCLCPP_DEBUG( + get_node()->get_logger(), + "Max trajectory cartesian velocity: %.3f, Max trajectory cartesian acceleration: %.3f", + max_traj_cart_vel_, max_traj_cart_acc_); + RCLCPP_DEBUG( + get_node()->get_logger(), + "Cartesian velocity override: %.3f, Cartesian acceleration override: %.3f", + cart_vel_overwrite_, cart_acc_overwrite_); + if (cart_vel_overwrite_ > 0.0) + { + max_traj_cart_vel_ = cart_vel_overwrite_; + } + if (cart_acc_overwrite_ > 0.0) + { + max_traj_cart_acc_ = cart_acc_overwrite_; + } motion_sequence = approxLinPrimitivesWithRDP( - planned_trajectory_data, epsilon_cart_position_, epsilon_cart_angle_, - use_time_not_vel_and_acc_); + planned_trajectory_data, epsilon_cart_position_, epsilon_cart_angle_, max_traj_cart_vel_, + max_traj_cart_acc_, use_time_not_vel_and_acc_); break; } default: @@ -579,6 +620,91 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( trajectory_msg->points.size(), motion_sequence.motions.size()); } +void MotionPrimitivesFromTrajectoryController::get_max_traj_joint_vel_and_acc( + const std::shared_ptr & trajectory_msg, double & max_vel, + double & max_acc) +{ + max_vel = 0.0; + max_acc = 0.0; + + if (!trajectory_msg) + { + RCLCPP_WARN( + rclcpp::get_logger("MotionPrimitivesFromTrajectoryController"), + "Received null trajectory pointer in get_max_traj_joint_vel_and_acc()"); + return; + } + + for (const auto & point : trajectory_msg->points) + { + for (const auto & vel : point.velocities) + { + max_vel = std::max(max_vel, std::abs(vel)); + } + + for (const auto & acc : point.accelerations) + { + max_acc = std::max(max_acc, std::abs(acc)); + } + } +} + +void MotionPrimitivesFromTrajectoryController::get_max_traj_cart_vel_and_acc( + const geometry_msgs::msg::PoseArray & planned_poses_msg, + const std::vector & time_from_start, double & max_vel, double & max_acc) +{ + max_vel = 0.0; + max_acc = 0.0; + + const auto & poses = planned_poses_msg.poses; + size_t n = poses.size(); + + if (n < 2 || time_from_start.size() != n) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Invalid input: expected at least 2 poses and time_from_start of same size, got %zu poses " + "and %zu time values.", + n, time_from_start.size()); + return; + } + + std::vector translational_velocities; + + for (size_t i = 1; i < n; ++i) + { + const auto & p1 = poses[i - 1].position; + const auto & p2 = poses[i].position; + + double dt = time_from_start[i] - time_from_start[i - 1]; + if (dt <= 0.0) + { + RCLCPP_WARN(get_node()->get_logger(), "Invalid time difference between poses: %f", dt); + continue; + } + + double dx = p2.x - p1.x; + double dy = p2.y - p1.y; + double dz = p2.z - p1.z; + double dist = std::sqrt(dx * dx + dy * dy + dz * dz); + + double vel = dist / dt; + translational_velocities.push_back(vel); + + max_vel = std::max(max_vel, vel); + } + + for (size_t i = 1; i < translational_velocities.size(); ++i) + { + double dv = translational_velocities[i] - translational_velocities[i - 1]; + double dt = time_from_start[i + 1] - time_from_start[i]; + if (dt <= 0.0) continue; + + double acc = std::abs(dv / dt); + max_acc = std::max(max_acc, acc); + } +} + void MotionPrimitivesFromTrajectoryController::sort_to_local_joint_order( std::shared_ptr trajectory_msg) const { diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml index 4861cf84a8..d04cb73772 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.yaml @@ -62,3 +62,33 @@ motion_primitives_forward_controller: description: "Epsilon for RDP simplification in Cartesian space (orientation angle threshold).", read_only: false } + blend_radius_overwrite: { + type: double, + default_value: -1.0, + description: "Blend radius overwrite for motion primitives.", + read_only: false + } + joint_vel_overwrite: { + type: double, + default_value: -1.0, + description: "Joint velocity overwrite for motion primitives.", + read_only: false + } + joint_acc_overwrite: { + type: double, + default_value: -1.0, + description: "Joint acceleration overwrite for motion primitives.", + read_only: false + } + cart_vel_overwrite: { + type: double, + default_value: -1.0, + description: "Cartesian velocity overwrite for motion primitives.", + read_only: false + } + cart_acc_overwrite: { + type: double, + default_value: -1.0, + description: "Cartesian acceleration overwrite for motion primitives.", + read_only: false + } From e6601b0547aa983b75c925c81c352c1267d29426 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 13:31:59 +0200 Subject: [PATCH 105/128] added blend_radius_overwrite --- .../approx_primitives_with_rdp.hpp | 5 +- ..._primitives_from_trajectory_controller.hpp | 2 + .../src/approx_primitives_with_rdp.cpp | 57 ++++++++++++------- ..._primitives_from_trajectory_controller.cpp | 5 +- 4 files changed, 44 insertions(+), 25 deletions(-) diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp index faf11f3780..aa07749a19 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/approx_primitives_with_rdp.hpp @@ -40,12 +40,13 @@ struct PlannedTrajectoryPoint // Approximate with LIN Primitives in Cartesian Space MotionSequence approxLinPrimitivesWithRDP( const std::vector & trajectory, double epsilon_position, - double epsilon_angle, double cart_vel, double cart_acc, bool use_time_not_vel_and_acc = false); + double epsilon_angle, double cart_vel, double cart_acc, bool use_time_not_vel_and_acc = false, + double blend_overwrite = -1.0); // Approximate with PTP Primitives in Joint Space MotionSequence approxPtpPrimitivesWithRDP( const std::vector & trajectory, double epsilon, double joint_vel, - double joint_acc, bool use_time_not_vel_and_acc = false); + double joint_acc, bool use_time_not_vel_and_acc = false, double blend_overwrite = -1.0); double calculateBlendRadius( const rdp::Point & previous_point, const rdp::Point & current_point, diff --git a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp index 28619f9658..5cbb5b44c3 100644 --- a/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp +++ b/motion_primitives_forward_controller/include/motion_primitives_forward_controller/motion_primitives_from_trajectory_controller.hpp @@ -140,6 +140,8 @@ class MotionPrimitivesFromTrajectoryController : public controller_interface::Co double epsilon_cart_position_; double epsilon_cart_angle_; + double blend_radius_overwrite_; + double joint_vel_overwrite_; double joint_acc_overwrite_; double max_traj_joint_vel_; diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 18155e50ab..6e78fccfaf 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -32,7 +32,7 @@ namespace approx_primitives_with_rdp MotionSequence approxLinPrimitivesWithRDP( const std::vector & trajectory, double epsilon_position, double epsilon_angle, double cart_vel, double cart_acc, - bool use_time_not_vel_and_acc) + bool use_time_not_vel_and_acc, double blend_overwrite) { MotionSequence motion_sequence; std::vector motion_primitives; @@ -119,11 +119,18 @@ MotionSequence approxLinPrimitivesWithRDP( } else { - const auto & p0 = trajectory[start_index].pose.position; - const auto & p1 = trajectory[end_index].pose.position; - const auto & p2 = trajectory[sorted_final_indices[i + 1]].pose.position; - primitive.blend_radius = - calculateBlendRadius({p0.x, p0.y, p0.z}, {p1.x, p1.y, p1.z}, {p2.x, p2.y, p2.z}); + if (blend_overwrite > 0.0) + { + primitive.blend_radius = blend_overwrite; + } + else + { + const auto & p0 = trajectory[start_index].pose.position; + const auto & p1 = trajectory[end_index].pose.position; + const auto & p2 = trajectory[sorted_final_indices[i + 1]].pose.position; + primitive.blend_radius = + calculateBlendRadius({p0.x, p0.y, p0.z}, {p1.x, p1.y, p1.z}, {p2.x, p2.y, p2.z}); + } } double velocity = -1.0; @@ -190,7 +197,8 @@ MotionSequence approxLinPrimitivesWithRDP( MotionSequence approxPtpPrimitivesWithRDP( const std::vector & trajectory, - double epsilon, double joint_vel, double joint_acc, bool use_time_not_vel_and_acc) + double epsilon, double joint_vel, double joint_acc, bool use_time_not_vel_and_acc, + double blend_overwrite) { MotionSequence motion_sequence; std::vector motion_primitives; @@ -225,20 +233,27 @@ MotionSequence approxPtpPrimitivesWithRDP( } else { - size_t prev_index = reduced_indices[i - 1]; - size_t curr_index = reduced_indices[i]; - size_t next_index = reduced_indices[i + 1]; - - rdp::Point prev_xyz = { - trajectory[prev_index].pose.position.x, trajectory[prev_index].pose.position.y, - trajectory[prev_index].pose.position.z}; - rdp::Point curr_xyz = { - trajectory[curr_index].pose.position.x, trajectory[curr_index].pose.position.y, - trajectory[curr_index].pose.position.z}; - rdp::Point next_xyz = { - trajectory[next_index].pose.position.x, trajectory[next_index].pose.position.y, - trajectory[next_index].pose.position.z}; - primitive.blend_radius = calculateBlendRadius(prev_xyz, curr_xyz, next_xyz); + if (blend_overwrite > 0.0) + { + primitive.blend_radius = blend_overwrite; + } + else + { + size_t prev_index = reduced_indices[i - 1]; + size_t curr_index = reduced_indices[i]; + size_t next_index = reduced_indices[i + 1]; + + rdp::Point prev_xyz = { + trajectory[prev_index].pose.position.x, trajectory[prev_index].pose.position.y, + trajectory[prev_index].pose.position.z}; + rdp::Point curr_xyz = { + trajectory[curr_index].pose.position.x, trajectory[curr_index].pose.position.y, + trajectory[curr_index].pose.position.z}; + rdp::Point next_xyz = { + trajectory[next_index].pose.position.x, trajectory[next_index].pose.position.y, + trajectory[next_index].pose.position.z}; + primitive.blend_radius = calculateBlendRadius(prev_xyz, curr_xyz, next_xyz); + } } double velocity = -1.0; diff --git a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp index e458503fc6..7925bd62c3 100644 --- a/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp +++ b/motion_primitives_forward_controller/src/motion_primitives_from_trajectory_controller.cpp @@ -87,6 +87,7 @@ controller_interface::CallbackReturn MotionPrimitivesFromTrajectoryController::o joint_acc_overwrite_ = params_.joint_acc_overwrite; cart_vel_overwrite_ = params_.cart_vel_overwrite; cart_acc_overwrite_ = params_.cart_acc_overwrite; + blend_radius_overwrite_ = params_.blend_radius_overwrite; // Check if there are exactly 25 command interfaces if (params_.command_interfaces.size() != 25) @@ -527,7 +528,7 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } motion_sequence = approxPtpPrimitivesWithRDP( planned_trajectory_data, epsilon_joint_angle_, max_traj_joint_vel_, max_traj_joint_acc_, - use_time_not_vel_and_acc_); + use_time_not_vel_and_acc_, blend_radius_overwrite_); break; } case ApproxMode::RDP_LIN: @@ -554,7 +555,7 @@ void MotionPrimitivesFromTrajectoryController::goal_accepted_callback( } motion_sequence = approxLinPrimitivesWithRDP( planned_trajectory_data, epsilon_cart_position_, epsilon_cart_angle_, max_traj_cart_vel_, - max_traj_cart_acc_, use_time_not_vel_and_acc_); + max_traj_cart_acc_, use_time_not_vel_and_acc_, blend_radius_overwrite_); break; } default: From 2de2acdf3db7a036a2273dd22937beb23f2b7963 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 21 Jul 2025 15:35:48 +0200 Subject: [PATCH 106/128] moved evaluation stuff to https://github.com/mathias31415/evaluate_motion_primitives_from_trajectory_controller --- .../CMakeLists.txt | 9 - .../README.md | 13 - .../__init__.py | 0 ...ed_and_executed_trajectory.cpython-312.pyc | Bin 9677 -> 0 bytes ...planned_and_reduced_points.cpython-312.pyc | Bin 9661 -> 0 bytes .../__pycache__/fk_client.cpython-312.pyc | Bin 3260 -> 0 bytes .../compare.py | 176 ----------- ...compare_planned_and_executed_trajectory.py | 230 --------------- .../compare_planned_and_reduced_points.py | 224 -------------- .../fk_client.py | 72 ----- .../record_moprim_from_traj_data.py | 273 ------------------ .../package.xml | 3 - 12 files changed, 1000 deletions(-) delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_reduced_points.cpython-312.pyc delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/fk_client.cpython-312.pyc delete mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py delete mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_executed_trajectory.py delete mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_reduced_points.py delete mode 100644 motion_primitives_forward_controller/motion_primitives_forward_controller/fk_client.py delete mode 100755 motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py diff --git a/motion_primitives_forward_controller/CMakeLists.txt b/motion_primitives_forward_controller/CMakeLists.txt index bd7a59e065..6e25797fd8 100644 --- a/motion_primitives_forward_controller/CMakeLists.txt +++ b/motion_primitives_forward_controller/CMakeLists.txt @@ -127,15 +127,6 @@ ament_export_libraries( ament_package() -install(PROGRAMS - motion_primitives_forward_controller/record_moprim_from_traj_data.py - DESTINATION lib/${PROJECT_NAME} -) -install(PROGRAMS - motion_primitives_forward_controller/compare.py - DESTINATION lib/${PROJECT_NAME} -) - if(BUILD_TESTING) find_package(ament_cmake_gmock REQUIRED) find_package(controller_manager REQUIRED) diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 163c2a735b..94edf30d6e 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -28,19 +28,6 @@ For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver ![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_integrated.drawio.png) -## Notes -Save data: -``` -ros2 run motion_primitives_forward_controller record_moprim_from_traj_data.py -``` -Compare data: -~~ros2 run motion_primitives_forward_controller compare.py~~ ? -``` -python3 src/ros2_controllers/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py -``` - - - # TODOs/ improvements - Use references for command and state interfaces to improve code readability and less error-prone. - Extend the tests diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc b/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_executed_trajectory.cpython-312.pyc deleted file mode 100644 index 6697808af1372c02a8d13e4c8ecf3e079bc78463..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 9677 zcmds7Z)_7umT%kbb~|$p0OjsJvh z2NF+v*GP;ekw${7M#9X@9@)`K7X)`3t@cCi8}|*}eQA#~7jG{s?P*6^MJJtdzeu<#`uaKwo?W{yjk((>>Q6XB9&?p>^tZs= zpb&*jN$R{wP0i;mYD%Z9=NS{OGbe2+_B^ZdrlkG69a*kY=j#v+)Pbx(oqRoFE^MPH zfi+XS^G;R0iJCG^nZmXeoIe#dDQrBQ<%RLxC`wmFaAJp_1%8h{wP9!+?UQFDxnnm+&=@(eOb%q2=ReZor2toaiMP33KQ zMzTt_AhbYc>|p|IT>Bu)U7GaONab0HO<WSJB3Pa8#NNE8M#EpIpXelM-kaS>Y(jR)i|Rh7e_!Vj9nE>a)Fd^lbNm$|X{1sEUTGhhrRGs}9iRr(h+N2xJa@f!7){PZ zeWwQZIvRYSp=n(WuNr+54mBH5)q4t)S|gSGpHs*$c{FcO;By)Uf1$ruYOLI0v>_a7 zL9Jx=)JS%cdLu=QVa+GMqQQ4$RioE!$Pf-~Fk~fPVmB!_QshBRF*DkT+Ms@qQBF9- z-fh1FqmLi3%a?df<7+9zGK4mf8HhHc4z%U&E5_*5%*4I5?KD0{p{-w!5TN-0NbVD=TzK&Q2pCGrofBbKPe%SuPnm^VU1ZLYdLfc#=z}c@*N(D8x_l(TOZ%vI3Xj zquGow)ff8K(zSPV1#faO_`yTJ88$1n(RfUZ=Xiw?$2ftXR7{x_JdqT7BsszVSrw%I zcu29G*7S$13X|f53%sDzX{p-U8qFj#f@0;8<71p+O>!fAQn3g;QrKfvV{)#;=~$8v z#nT~yLvb!G=Gf3SY<^!TXX)x4{niw&TIRe*m^X8+r!qo{OM;0gbXIpKG?+&GWX_Sy zT;_$45RZ*z!)5`$Y1H6_X~mMvM3sh-k<4Tyn~8Ag=or{n%?r@^D5zEFG}!&;4}Jf5 z;@@*u59ORjNc%zx6Xo$SY6b7<3KNH5$D_9`iWwYaM>FZH=D3)hO7dY^?KZa9_R)U~ zFaF&j)son#`uyi1JZ=IE!?(^zb(FfI;-y?D63wK>A?Tzua!HJkq3aq?$8wvF$72%$ zAG#dRj)gSgxR^$m_1O2sms z%qpxnF*2UaWJSf!rzcXpz-4)b#wAJ});^^Ty&dz}cs9vH3$-{7(T)jmq=`*xVoZ{c z@oA(uV4|i)&0B@e@{?J`nZ<(|Npe$}iL7GIh|mj{9aGp5PUO>EidSp`58(uZ=|m=; zR%|FPXyrIOFs;FdvCQRgi{cuMCwbhM1X^+HB_!TTBUX})jAz6M)*>ow8ZuBMDs^a7 zZ|MMDZ)1UAD=e&77|EolI8vEQ@pLSb;=~JzL(Fmli8jOvRRiy?Q4onHaeUp?S%Eu` zXX66;rS!1;ssj3k&8qz{amgrU>OL(C0>lc0=>)$FspT`7ZX~$sNjXDk66Tb zA$E;VDIG)>%cxFjlR%e>!wMM#m$BR8uVJkesK+ej@!e>hZIw56mfc;2p$CxNF}p)< z>n?kC6;7@)RA|R?`<_z!o_}jRTC^1G48p;bg_LaoMw_ z#+!}vj)g%vaBw*=R0<5qr_aiPp>p7_WV#8A2zJaJDg}C$1AV1H9~3=k+W5uDtqV6V z%x{_>{;fssJyzazyxev|9y~8|BTG%u!l~Z{w*E@^`wxHl;ll0(ZZS}P^+-8zRMXb7 zWByPncwjkrq!c_N)6EZ>+a9oW*BmpB>xZvj{Gvl{+f{DaU1s;ly~pnlKem|tOyTYS zVyKqzUC*yuZ?`TCFPawjm&5(#;4x_an4z2v*Y?fq`*hEZeY5-I4W06?Bc%;T?p-Xk z4&1-EqM+hzA@h(2wXod*_& z?uqh&lXBgUm*}@ZxyyS^nvou`j_J3{?1myYzj;3T+oOw(<=%l(*MJ-zl+XM%80liJ z3>1z|dtppL^ibK>TDDMYCc6f%tepj3u zKjY@yMO1QjRJ_dY!oLfi>zuIEM zIxUvjV2KUNEjyRk&T6;IY@oyjipPrk=C;lEE|_lbTj-hZT(~F)UtePTh;5BCjYYZ` zU1B$r5E;sMEc<(x=+|JrSlN$~YStc{N;#>%XEu;{>*f$4XyZz=Aa%Pn-sTldO=eTxJ41^FCT z7+9i5zM*Z)w68?_zG~U|HQfm#0wZagwJp0sC09t^w7cxuv+U|CxxngXInejWVs7%QF-IRd-k$xs4)0|wtal^%E{~YCAtOkV98Z&7IedNZtn6$FpnMtPQMGpRA5|tcO;p_<@d9NIE{D-^XoF+{f*3AGbeW<2v|3 z-Ah`;lC!gJ5&MKi4zS4aQWiO-I?0J|`T6>q_UoWAQa!S&H~_|y@HrZud_zqemsVCw zYid2U!1yAm$MU%d6(o$v=UuLit3Q#u2Z+) zEx8l=9m9~4>a;sGGHbVTJ#Sf)w^ncM_2k}u*K-H368ykza(&&-HM&Wj=q7nXw-+!0 zxY4iCt>2-v{xC&N#DBH-O-2pjp1A9~6CI@7NRi*rQ8Rv93<<*3)NUnZMykh*#E|$^ z&Bt`Kg!EUV4{*%2PfhLj(p$_7=#}wSczOTUj$1YV1NryDy@7w;@5R6BJOm6?MXFFW z{{#8=!o7iizO0U@Ngkx)XMoaZsZUGE`x0!{)~*nWGLRFfUk}M@Cu%1)31^@_>tR$FBO}qt`=6tI9Te+1E!M%U40|NM-gCe}Y!gR_??z`J6Oc@M)$sT^~znx0ov0e@x@@V=2_G=NFij7#u7A>db}fLGjE zVLQ;=b{&R^!iAj|0huD#?xz5m*C7yaS2i#i(xL`wdj?R`A>g$r?8F2kyeje{U@TX_ zOF-xaqFBUCU0OF6@ST9p|=zuA`ZAZ zM**KnV~oZEIFN?LOeW(g;UI3ILNhs>J&Lv9$tmDDEgZuHW17MVOa?F+#AFDQlbHM% zNH{3Gh51uJlm;9=13wW?Wh$p}~<2aJZD(zzVr><|QvSM1=u#tJ;{X%vWv zXVf#X3;{!s%BxQy1jZzJ0wuT#(igGPZ7^|P2qkd07lk>K?Alxy)UNBVmja#3f!a>MSz3H5@$f6;%>yI3#R9bckPfH97S zYujhG7vEi~d!=x+Vs~C^pJ^|8=Y7-dWqViQ$RBCu;}cg-RM_BWn~KB5EhV^+K9hG= z8hn)occsB!@%mQXl-2o|vco;qM_Fx}mX^s<)plf0Oy%G8Jdl;cOhuaTc8N7NDGcebt z`>$f)=sRJG{_h2*ICd|74`7Pnujw<7;Dtd&F(D5F4BmzxEdqi67%}DHi*??FEO~R5 z$gKPS8VRdjtuqoOne-Ed<)zx2_4YJ;0i?e)<*mq?XN>#5WC3IY&Sn z5ctyq@l5*)p_UM5jO|o-8``UTsEE&D)on`Kl;{)}PYbh9EW=NX04Y$F#)E}{iXXNL zUnQ^~zmWaG8<%G<-;iddxdFNBVA+2N>hQbUcGGstdDA)fp4|OrIdB+cADV3#um!l% zR7m!R<}^)REj z0sO~MdNMu&5WD(eh|yB*B;yvN@$soH?L$Q-2}7-&gw*iipb1wo!QSBx)$l}aQ>q23 z``@x}q%vqC$sZIx10j447V&9j)nYQ49&M#ezTZ=xKTz#|ptk;=vOi?bnoI{Crp@o0 jOz)T;{?zO-F{|4t+Bu#3$`bq?&3<%z)k4uNs{a22x+H@W diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_reduced_points.cpython-312.pyc b/motion_primitives_forward_controller/motion_primitives_forward_controller/__pycache__/compare_planned_and_reduced_points.cpython-312.pyc deleted file mode 100644 index 6d09bfd6aa029328c10179859c0124e769347089..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 9661 zcmc&)eQX;?cHbqJ%Uynx`k*B1gHrrO+mgQ$Cw3g$k{#Q!6UTO(I98M6t+*?SG(}3g zt1o7Wqk#lRUfmPb6cCk5Ys&p2GVH_oP_$KBp!K0m&qeUGv zDILaHZm(f${i)59+ zx2%z+SeiB6GT)@sRvh~p4ZGx!oQj5pwcfJb1Ye>@k+-UJbtzdww(574X6=ectZTH{ zzP^ohuuj%>tLA3OH{Y=D+BN!C+g9&eX=Cf4@A~S#S$DivGKZW`&r*xiW7sZu9u_uI{rgas%0D5CU(O|`tRd7_8Z!4e#&OcZ*8;n zDVuE-n^*suz+hFrKK9f#SW7}(owX#?bz4h9ThXRAwSzRq2etWB{MMRZV*bN(2ggd;l9h&cza|FI+D$>{3 zHT7-l=?CaN zwJJWVyn%@JRaN3;cST2|KzECBqHDU^+e+QNnntAt-K|gPYHv^IR^1Ptt>|i$<{5~j zeHt(Hf<{&9(2EsXqbhfu&`TPxQnOxmn>PEnXC3Q@D|#BWjz+g8SE(!Gkv!#|+pFf^ zQ<2pusa=aO@Id7zbxdoo)K#83p>f&mQu`0EKQ7;};FgJbcbxI+9-@onLv%latEO=v z7!ZOn?qL+(W!+vDc&1@K8shxu0xILthp6Y6~k8B9=92b%GFGtwGhqLIpaoDSW zh;F-z71b2ZU-0T>GR#E+;-G4Ujzsw(CJe&`yQn|DRnw92fW|8~$aud@vWzguv0j4r zAW<|@nGOddoFGnyIUb#vG4d@>Fya}Ck(Ww!pIUp5!VEYe$V5CBcn0}6%1<8fXucg2 zx;!QS1i%b>jwl0qh(_?0#W$=jLYH3{i*@?^(V=06=QOTwOz?rTkavBr^q%qgwZ6KB zBZ03D9uEdadCoH)6bC&eJ02#&dP*vu;b<@-3Le#HP>4o60y72+B}NZ;yc=cRFe_6$ z$FM%=T-FbVMVW-y0h6+sVOgIr+CLnQiZY>;M#0aBA_N2x3`hMk6$F}(jteq=UZw~5 z=#Xz@lmQDPqrowdGBCr#;YryfaH4NQ4I71?tfFHoO(PjGD26$-k^wHl%DTufSm1eP zQq~VK6Ho*rGBLz45t&jg28UE?GOSTCL|MdOU{LghnaSv=DC?pEj2?wI)z1iAgc;&w zBhP`a{G3dLz&)~&4e}}<`39yh6T)D0Ts92z;5=`K>=+1!Ib=gylqyci(XhRu0_Q_! z1n}wv{3hWSlXW9Nj{rS_=yBP^4wS7RTGPiTWPDP_L1==Pb(8Rm@vG_hxT(vVBrZ?nTIt$LO#Hstv zn(EhO60?%!d|SHzLXQ#7LsM=-iO$nQqNC&G*c;-fmjx`EhF!Y$uRS zvu$cyYFp;wqG?m&Xpy!|wWZoJHS@K}wgTOi=mDz+<9AP7Ig#v6j-=Z&N9Vh5f9vkP z+@-e@Cl-l!iUg@Ns-qO)oORB6v*$j3 zbMDRg?zv01xdr~NJ8^1}IEQRix%L@#tx)3W5+ly_|^xVAjPjE3LCQ)CiP?kzfM(mm70OikwetULQmwtsHR{N8!~ z#`8J*-Xw9~W}mv8x}4cqu(c)iMVm9-kqV@R%%17-tUlW_XUti*CUp-eXHqvsr|2Bj zm)-+KMt_Z-rLTJn4LkBw-|b6x{JA$S6{x=A?^bY;>RYy>sVp~Obj_4KWzXPwswuN4 zPqh{)*EeM>(*_rrIQ69kbGl~C)8@>nf@4dfx9D)rkke#(WSTCyx_x$kmic&KZeaf0 zTrg+fl{oo;uqJxG+k2&V8C**iY3H&Y>Ibw7#mR?_1^SsU48VY8a5RD!i>{`ktNyVS zu^gDe_Wz+bE3c-vE)pA1P<rftTdB9wBQvAZ zqaTcCogdfD)%~eE@7_A!{-aGdHr?EEyZbL+{_)Fyb|Sy+#f5W!_r_nn@i!OmjQn); zC!>Eqo`2~~uKu-x^=#sJ(NRBRnl^o4$q0Ez2l(1-ncA1y_xmrT&&|9!{pJU6Wk#-z z&5r$GB4^qP`wj+h`pW6FKHWV{W*R{wdvqS3J3fCYzj5Cp@%(Sw{yAY>B5LzQ?IKYR zbA*G#IBi^Vc=8TUu6=jGv1iF~An!O(r0R1GCm!o{PBPJ3mYcCmTRu8}?c(gkYra`u zuJffr%b`1T!Eq|ld!H~W@IeEA7t~qDAaF2N7F`R4I6M!Rv z;}pOV1AuAEo8zjTD?kY)O0BIT|A_TmZ zPpAadRr9qAaNH>ARaj~@FtIE}NrVbottmx|X04BqMWZUUM6tM%;?RNeB|Am_>t2Z@TO$~}RnJ}G(15qC-e*&;Kmfgi9I0KLDjlNcgaY3*yf;W%28k2!sSg8Lej~V)*NZARHuy2&N^;6tDs+PcB{cME^V}ss%vtqfHRVF6}eR)8n%Y5)soOE zi<`7asMM^nV)5!vA*SqXow5d7Dl!_y)>mY!q6+@pvGM_M)_onn)liX_R)t$&1?>SH zf^DIF$4V=(${TJq-$dytJdh%HsT4#A?5~wiXzxl6KuG1i5PI(ERzYd4fIBpn+ z5-5G#5_gSbUe6gNK@R-EfBkv(m;ZSC5C8=PBSyn&#*9{>l(P~?E_ii3I;3S%7=#3M zf=A~lkB(5;Sju&I^fwkB!P-39__Fc5nz{053OoY)V~*}fAk3k}nP*r?nT1knPv6mq zBRs-EWA&9>+H)3Vv7X)t%S}Lrj?(79LhJkgd2ZoP4l4r<3@FckA4bFHApwt>!_je$ z_wXncgmIVie;#3$UP9KR1lHEyAD!@tQ6CfW4+5G|dWYmlfMjGyCL(}x@Mu%Sylds< zXD^)fp-fUlIXREEhS$R*7?j@zg=_>XqeBrvCc&{m0g^K4GBP?eJjo-BOD4wzk?~)a zX%3hi&xo8%G2yU33>l?NLJ|$>Fuxs1Ql)%cfbnw?9&HU-9}5oiC{TG6dpts^WFo)^ zSsuY_{83b(2$Ri_@Ly#A=^uYFBoBie#oS0V5mu)tPipi zkYxi_qB3|N>Q~Q90Q?Y?4NA{49+ItNfc%s*K$)EI0RwzLsnq-s8gc{*p#h4o%W!!G zIIB}~Ms-eA`Qj`n#*u}8gGfwZD^kG~uMfKR|E&2ymi_QTuK7TYXoRxZym_g)E8pC; z)cjn&`ME;#^T2;#YsfWrcTNRU!HgS{xu)#JTtjEU z)|EH`S%AAS@mjI2`4L7Myh-|g+tzt^p>6jg%s_inuO*MBo9=_^yQz0G`?I0j;?L{{ zi;lJ>$L73ab5>Y%Z2!zrw`>I2WfNv?Ub1xLEgjis?^(7kTfyF!F3eFgC8eZ~j%Lk; z<{k6QLdSytACBHN7mi)XAG(m+|3>ax{fl=0m6M61$(qlNrsRtSqdT+vQ)6?{?n-h= z{pYnUnahRRZI3XAp(#Z{p7>mmGAFxJ}q&Fk;J{!hN->*+0-_RP7=#_7&aEuLl6 zoV0#{LG=ZRSsL%Rc(R?jmR+ec$>ZtcMTS#n-j7`aR5E-}f|iUfr@#yr)SYud3$b(V&>L^b58hD_Ze)us&^Wrjq?zesgx9GFJ>*gdLoxgBP>yb&`{ zN!^tbOGJI1sL#1~E)u)S$-t*gJMIykMYy*^+Fhhw>E0ZqmzKt&yQS!En)%N3cZycq zvKcejzl7x^!ToC{4o832iNmiRy^CWlFaGNBA#kIBFx(%}r=KG}*=0I?fcoS`Gn9T{ zmLK$~K-byF%TU07Rp4>>pNTlm>f<_=i0j3&;A;QF5GsA{%R)d%n1q)k!;NvI*AUnS$iuiuTdry6m+6gPnPPKY*hFF zg_ej(jVL#b^M3^H^%|jdiCd5z_yiopf z@kwOqH7EoM3hm@qPkLgA2}bxI0{K7>P{zd}w?=pVzLqM>bU79$=Z_ zj~B{)Lv{iZi#}T6U_XGKh=L_hYV`u)7W~2C$u0pf-XIh1Qf>t3s>7qL%cDQYC}^nS zaK#;{Z^h5P8<;W}#a~}h2f?|cVeSzB7odZ~PdEa_vL46r$D1+S^mEMhbFAhUSlchK s-H*s`AH)btGWMyy@iT&Y|2RySXi|FkUq|+u8vp7&-6`m#cPyDe+%9bn=s%bfuw3bcUQqV?DR0pXew^l2s&7mlPU`lg`5~(GZ znO#byN&_mOA{44ZFp5G3iULJW3hYCUKK9;=)?z?<&;SB@C~^}jqX>K`IdAq0Q{XXyh%Oc>}z)rG~vX$w7f;N%LGenK~mKu*v>F3MFz?P5`_23rBNiFb8At!$b zG>NDSi{Cd&sA?B_0lJ1o+Oxwrd6P>2AnXCVuPt+L?nJNigSXjAw`~he@Vh9W$M0{w z3CaUp?~k^7nT*#1{OFnh%6tZ072&i$mIr;BQ+n{R$h}$fbX}Zl{E^4{steR5zFGkP zr&nR;od#$CO(!>c;bn*=-Qn zV@PbB+K1FQ_2wERp=D%4!(3jbHmJd(sRf8=A)`nJAT^Pp$ zkM&ctUT;$WKr^)lX7|4l=jof_N5E>!GHLhqCit5g-3@Jrb|RG6Rvh*G!&F=Sc6T`0 z8J=>6ryh?zi5?Cww8Wk8QDS&+`oVN3k#Q24C$k5MOgnM28;R}S-M)Jm8S6yGoyhpX zrQ7Yu4~~OiXyhA{JBgbo)Fmiz^kEF6-6GneNBFuWbYE%)n^L)7M$C}cU=N)DXo|~1 zQ-b|DP0E$~Ma1WWSC$P_xV{qqH|abL&Nv+@TY(eNR9vIZQA$3DP2CjUQ?EqJ&pP< zX8H0JLv_pwd}DB7F^w=b@r`tWJ~;ENveJdTVWb&E>1hg5+OUTw%1_b9b!6E@UO{=C z!A}wAD+rc!5~UStl&Y(+N(B}PyBGm2n?e!^m(5a@BAv^KYywehy$205pe7;a59X~# zwSXDolcZHERbjnqmkd~}+jUHVjpC?*s5wzLtBA-LS#`rEAvboa)e#A<i zsUe++jKl27CL%?iDv{jznu=NC^3c4X2fa9XXch?-u~~uc9*JU`?goj1`5}0L;R$NU zVr7!Xf5S?VsIW`^)SX>g}U&eE03`w|C~d=TdtgJ^1MNu(j}P@Z7_RPIB5wPIr=7Cz<{H z`qSi_-I1}*$Yp2b^8R&asl z&fJnSw{-B<-Gj*w+OeM;s~~pvSOU>_A5kwkkxK_}e77BW>u7KYGgx@(3&OI}Mb95m zVvps1{|iC|y~Zm|0Cpc8Uxl6iJo+>XOInabbeh4~Y``i_886#ZYo%`M=6Y2V+_bQm z!?b&i_&bz5_1N&4Ol+~xH$hj8bktEt9c`;A_U_P|`$9eM?u)&u_wp7Zl5LvCHBDg; zHcK}8V22>An0nn{bOgeW>v_Y|xbGXDrM6w?B-(qC3y9VTq#+J7-z>y;y%5=d3A2vH zW3gQSdJ8-c$kGpmlh}}S_FtC+(x@AcJB!6o$^&S&l$0f^#*I#C5US?-KR+D@G9vUS31NMOE=qA2JIlt4Q-erW`Z%)R& z9d@;3uwt$u`hTfd%T~t1Yc3YKJHc~IA1JQktIU*pWS5ypqF)aB4Plq`8Sr+_YVw8p zj(6nW!*?jlj?nrA?T&+jAe>A9A^IgqeF?PZa#|Q|+0OwTju!+VMp_$BgQL#|;=fI9 zzW2|7G9+&<9>+lB%GXiMJ-cSZS=#a}P}=Euh=AST@i F{sVxJ(>4GA diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py deleted file mode 100755 index d0cc1e8c3f..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare.py +++ /dev/null @@ -1,176 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - -import os -import pandas as pd - -# to run with ros2 run ... -# from motion_primitives_forward_controller.compare_planned_and_executed_trajectory import ( -# compare_and_plot_joint_trajectories, -# compare_and_plot_cartesian_trajectories, -# ) -# from motion_primitives_forward_controller.compare_planned_and_reduced_points import ( -# plot_cartesian_trajectory, -# plot_joint_trajectory, -# ) -# from motion_primitives_from_planned_trajectory.fk_client import FKClient - -# to run with python3 -from compare_planned_and_executed_trajectory import ( - compare_and_plot_joint_trajectories, - compare_and_plot_cartesian_trajectories, -) -from compare_planned_and_reduced_points import plot_cartesian_trajectory, plot_joint_trajectory -from fk_client import FKClient - - -def main(): - data_dir = "src/ros2_controllers/motion_primitives_forward_controller/data" - - # filename_planned = "trajectory_20250715_114409_planned.csv" - # filename_executed = "trajectory_20250715_114409_executed.csv" - # filename_reduced = "trajectory_20250715_114409_reduced_PTP.csv" - # mode = "joint" - - # filename_planned = "trajectory_20250715_114057_planned.csv" - # filename_executed = "trajectory_20250715_114057_executed.csv" - # filename_reduced = "trajectory_20250715_114057_reduced_LIN.csv" - # mode = "cartesian" - - # filename_planned = "trajectory_20250716_090701_planned.csv" - # filename_executed = "trajectory_20250716_090701_executed.csv" - # filename_reduced = "trajectory_20250716_090701_reduced_LIN.csv" - # mode = "cartesian" - - # filename_planned = "trajectory_20250716_091324_planned.csv" - # filename_executed = "trajectory_20250716_091324_executed.csv" - # filename_reduced = "trajectory_20250716_091324_reduced_LIN.csv" - # mode = "cartesian" - - # filename_planned = "trajectory_20250716_092410_planned.csv" - # filename_executed = "trajectory_20250716_092410_executed.csv" - # filename_reduced = "trajectory_20250716_092410_reduced_PTP.csv" - # mode = "joint" - - # filename_planned = "trajectory_20250716_093119_planned.csv" - # filename_executed = "trajectory_20250716_093119_executed.csv" - # filename_reduced = "trajectory_20250716_093119_reduced_PTP.csv" - # mode = "joint" - - # filename_planned = "trajectory_20250716_093707_planned.csv" - # filename_executed = "trajectory_20250716_093707_executed.csv" - # filename_reduced = "trajectory_20250716_093707_reduced_PTP.csv" - # mode = "joint" - - # filename_planned = "trajectory_20250716_101518_planned.csv" - # filename_executed = "trajectory_20250716_101518_executed.csv" - # filename_reduced = "trajectory_20250716_101518_reduced_LIN.csv" - # mode = "cartesian" - - filename_planned = "trajectory_20250716_101907_planned.csv" - filename_executed = "trajectory_20250716_101907_executed.csv" - filename_reduced = "trajectory_20250716_101907_reduced_LIN.csv" - mode = "cartesian" - - filepath_planned = os.path.join(data_dir, filename_planned) - filepath_executed = os.path.join(data_dir, filename_executed) - filepath_reduced = os.path.join(data_dir, filename_reduced) - - joint_names = [ - "shoulder_pan_joint", - "shoulder_lift_joint", - "elbow_joint", - "wrist_1_joint", - "wrist_2_joint", - "wrist_3_joint", - ] - - joint_pos_names = [ - "shoulder_pan_joint_pos", - "shoulder_lift_joint_pos", - "elbow_joint_pos", - "wrist_1_joint_pos", - "wrist_2_joint_pos", - "wrist_3_joint_pos", - ] - - pose_names = ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] - - # Load the executed CSV - df_executed = pd.read_csv(filepath_executed) - - # Check if the pose_names columns are present - if not all(col in df_executed.columns for col in pose_names): - print("Pose columns are missing in the executed file, computing them with FK...") - - fk = FKClient() - - # List to store the computed poses - poses = [] - - # Iterate over each row - for idx, row in df_executed.iterrows(): - joint_positions = [row[joint_pos] for joint_pos in joint_pos_names] - pose = fk.compute_fk(joint_names, joint_positions) - if pose is None: - # If FK fails, e.g. None, fill with NaN - poses.append([float("nan")] * 7) - else: - # Extract pose as list [x, y, z, qx, qy, qz, qw] - poses.append( - [ - pose.position.x, - pose.position.y, - pose.position.z, - pose.orientation.x, - pose.orientation.y, - pose.orientation.z, - pose.orientation.w, - ] - ) - - fk.shutdown() - - # Add the computed poses as new columns - for i, col in enumerate(pose_names): - df_executed[col] = [pose[i] for pose in poses] - - # Save the CSV with the new columns - df_executed.to_csv(filepath_executed, index=False) - print(f"Pose columns added to {filepath_executed} and saved.") - - else: - print("Pose columns are already present in the executed file.") - - # compare planned and reduced trajectory - if mode == "cartesian": - plot_cartesian_trajectory(filepath_planned, filepath_reduced, pose_names) - elif mode == "joint": - plot_joint_trajectory(filepath_planned, filepath_reduced, joint_pos_names) - - # compare planned and executed trajectory - compare_and_plot_joint_trajectories( - filepath_planned, filepath_executed, joint_pos_names, n_points=100 - ) - compare_and_plot_cartesian_trajectories( - filepath_planned, filepath_executed, pose_names, n_points=200 - ) - - -if __name__ == "__main__": - main() diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_executed_trajectory.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_executed_trajectory.py deleted file mode 100755 index 3053429894..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_executed_trajectory.py +++ /dev/null @@ -1,230 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - -import pandas as pd -import numpy as np -import matplotlib.pyplot as plt -from scipy.interpolate import interp1d -import os - - -def compare_and_plot_joint_trajectories( - filepath_planned, filepath_executed, joint_pos_names, n_points -): - # Load CSV files - df_planned = pd.read_csv(filepath_planned) - df_executed = pd.read_csv(filepath_executed) - - # Remove leading/trailing rows of executed trajectory where all velocities are zero - vel_cols = [col for col in df_executed.columns if "vel" in col] - moving_mask = ~(df_executed[vel_cols] == 0).all(axis=1) - start_index = moving_mask.idxmax() - end_index = moving_mask[::-1].idxmax() - df_executed_clean = df_executed.loc[start_index:end_index].reset_index(drop=True) - - # Resample planned trajectory - planned_positions = df_planned[joint_pos_names].values - interp_planned = interp1d(np.linspace(0, 1, len(planned_positions)), planned_positions, axis=0) - planned_resampled = interp_planned(np.linspace(0, 1, n_points)) - - # Resample executed trajectory - executed_positions = df_executed_clean[joint_pos_names].values - interp_executed = interp1d( - np.linspace(0, 1, len(executed_positions)), executed_positions, axis=0 - ) - executed_resampled = interp_executed(np.linspace(0, 1, n_points)) - - # Compute RMSE per joint and total - rmse = np.sqrt(np.mean((planned_resampled - executed_resampled) ** 2, axis=0)) - total_rmse = np.sqrt(np.mean((planned_resampled - executed_resampled) ** 2)) - print(f"Total RMSE of planned and executed trajectory: {total_rmse:.6f}") - - # Plot in same style as reduced joint trajectory - fig, axs = plt.subplots( - len(joint_pos_names), 1, figsize=(10, 2.5 * len(joint_pos_names)), sharex=True - ) - - if len(joint_pos_names) == 1: - axs = [axs] - - for i, joint in enumerate(joint_pos_names): - axs[i].plot( - planned_resampled[:, i], - marker="o", - markersize=5, - color="blue", - alpha=0.5, - label="Planned", - ) - axs[i].plot( - executed_resampled[:, i], - marker="o", - markersize=5, - color="red", - alpha=0.5, - label="Executed", - ) - axs[i].set_ylabel("Angle in radians") - axs[i].set_title(f"{joint} (RMSE: {rmse[i]:.4f})") - axs[i].set_ylim(-3.5, 3.5) - axs[i].grid(True) - - axs[-1].set_xlabel("Normalized Trajectory Index") - - # Global legend - fig.legend( - ["Planned", "Executed"], - loc="lower right", - bbox_to_anchor=(1, 0), - bbox_transform=fig.transFigure, - ncol=2, - ) - - # Add total RMSE text below the last plot - fig.text(0.5, 0.01, f"Total RMSE: {total_rmse:.6f}", ha="center", fontsize=14, style="italic") - - plt.tight_layout(rect=[0, 0.03, 1, 0.95]) - - # Save figure - base_name = os.path.basename(filepath_planned).replace( - "_planned.csv", "_compare_planned_vs_executed.png" - ) - plot_path = os.path.join(os.path.dirname(filepath_planned), base_name) - plt.savefig(plot_path) - plt.show() - print(f"Figure with comparison saved to: {plot_path}") - - -def compare_and_plot_cartesian_trajectories( - filepath_planned, filepath_executed, cart_pos_names, n_points -): - # Load CSV files - df_planned = pd.read_csv(filepath_planned) - df_executed = pd.read_csv(filepath_executed) - - # Use only the first three values (x, y, z) - pos_names = cart_pos_names[:3] - - # Extract position values - planned_positions = df_planned[pos_names].values - executed_positions = df_executed[pos_names].values - - # Resample planned trajectory (linear interpolation) - interp_planned = interp1d(np.linspace(0, 1, len(planned_positions)), planned_positions, axis=0) - planned_resampled = interp_planned(np.linspace(0, 1, n_points)) - - # Resample executed trajectory - interp_executed = interp1d( - np.linspace(0, 1, len(executed_positions)), executed_positions, axis=0 - ) - executed_resampled = interp_executed(np.linspace(0, 1, n_points)) - - # Calculate 3D RMSE - diffs = planned_resampled - executed_resampled - squared_distances = np.sum(diffs**2, axis=1) - rmse_3d = np.sqrt(np.mean(squared_distances)) - print(f"3D RMSE of planned and executed trajectory: {rmse_3d:.6f}") - - # 3D Plot - fig = plt.figure(figsize=(10, 8)) - ax = fig.add_subplot(111, projection="3d") - - ax.plot( - planned_resampled[:, 0], - planned_resampled[:, 1], - planned_resampled[:, 2], - "o-", - color="blue", - alpha=0.6, - label="Planned", - markersize=4, - ) - ax.plot( - executed_resampled[:, 0], - executed_resampled[:, 1], - executed_resampled[:, 2], - "o-", - color="red", - alpha=0.6, - label="Executed", - markersize=4, - ) - - ax.set_xlabel("X in m") - ax.set_ylabel("Y in m") - ax.set_zlabel("Z in m") - - x_limits = [ - np.min(np.concatenate([planned_resampled[:, 0], executed_resampled[:, 0]])), - np.max(np.concatenate([planned_resampled[:, 0], executed_resampled[:, 0]])), - ] - y_limits = [ - np.min(np.concatenate([planned_resampled[:, 1], executed_resampled[:, 1]])), - np.max(np.concatenate([planned_resampled[:, 1], executed_resampled[:, 1]])), - ] - z_limits = [ - np.min(np.concatenate([planned_resampled[:, 2], executed_resampled[:, 2]])), - np.max(np.concatenate([planned_resampled[:, 2], executed_resampled[:, 2]])), - ] - - # Determine common limit (min and max over all axes) - min_limit = min(x_limits[0], y_limits[0], z_limits[0]) - max_limit = max(x_limits[1], y_limits[1], z_limits[1]) - - ax.set_xlim(min_limit, max_limit) - ax.set_ylim(min_limit, max_limit) - ax.set_zlim(min_limit, max_limit) - - # ax.set_title('Cartesian Trajectories Comparison') - fig.text(0.5, 0.01, f"RMSE: {rmse_3d:.6f}", ha="center", fontsize=14, style="italic") - ax.legend() - ax.grid(True) - - # Save figure - base_name = os.path.basename(filepath_planned).replace( - "_planned.csv", "_compare_cartesian_planned_vs_executed.png" - ) - plot_path = os.path.join(os.path.dirname(filepath_planned), base_name) - plt.savefig(plot_path) - plt.show() - print(f"3D figure with cartesian trajectory comparison saved to: {plot_path}") - - -def main(): - data_dir = "src/motion_primitives_forward_controller/data" - filename_planned = "trajectory__planned.csv" - filename_executed = "trajectory__executed.csv" - filepath_planned = os.path.join(data_dir, filename_planned) - filepath_executed = os.path.join(data_dir, filename_executed) - joint_pos_names = [ - "shoulder_pan_joint_pos", - "shoulder_lift_joint_pos", - "elbow_joint_pos", - "wrist_1_joint_pos", - "wrist_2_joint_pos", - "wrist_3_joint_pos", - ] - n_points = 100 - - compare_and_plot_joint_trajectories( - filepath_planned, filepath_executed, joint_pos_names, n_points - ) - - -if __name__ == "__main__": - main() diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_reduced_points.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_reduced_points.py deleted file mode 100755 index c69f942ff8..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/compare_planned_and_reduced_points.py +++ /dev/null @@ -1,224 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - -import os -import numpy as np -import pandas as pd -import matplotlib.pyplot as plt -from scipy.spatial.transform import Rotation as R - - -def plot_cartesian_trajectory(filepath_planned, filepath_reduced, pose_names): - # Unpack column names from pose_names list - px, py, pz, qx, qy, qz, qw = pose_names - - # Load data from CSV files - df_planned = pd.read_csv(filepath_planned) - df_reduced = pd.read_csv(filepath_reduced) - - # Extract position coordinates - x, y, z = df_planned[px], df_planned[py], df_planned[pz] - xr, yr, zr = df_reduced[px], df_reduced[py], df_reduced[pz] - - # Prepare 3D plot - fig = plt.figure(figsize=(10, 8)) - ax = fig.add_subplot(111, projection="3d") - - # Plot planned and reduced paths - ax.plot(x, y, z, marker="o", markersize=5, label="Planned Path", color="blue", alpha=0.5) - ax.plot(xr, yr, zr, marker="o", markersize=5, label="Reduced Path", color="orange") - - # Mark start and end of the planned path - ax.scatter(x.iloc[0], y.iloc[0], z.iloc[0], color="red", s=50, label="Start") - ax.scatter(x.iloc[-1], y.iloc[-1], z.iloc[-1], color="green", s=50, label="End") - - arrow_len = 0.05 # Length of coordinate axis arrows - - # Draw coordinate systems for all reduced points - for _, row in df_reduced.iterrows(): - quat = [row[qx], row[qy], row[qz], row[qw]] - rot = R.from_quat(quat) - pt = [row[px], row[py], row[pz]] - - ax.quiver(*pt, *rot.apply([1, 0, 0]), length=arrow_len, color="r", normalize=True) - ax.quiver(*pt, *rot.apply([0, 1, 0]), length=arrow_len, color="g", normalize=True) - ax.quiver(*pt, *rot.apply([0, 0, 1]), length=arrow_len, color="b", normalize=True) - - # Draw coordinate system at the first point of the planned path, - # using the orientation from the first reduced point - first_quat = [ - df_reduced.iloc[0][qx], - df_reduced.iloc[0][qy], - df_reduced.iloc[0][qz], - df_reduced.iloc[0][qw], - ] - first_rot = R.from_quat(first_quat) - first_pt = [x.iloc[0], y.iloc[0], z.iloc[0]] - - ax.quiver( - *first_pt, - *first_rot.apply([1, 0, 0]), - length=arrow_len, - color="r", - linestyle="dashed", - normalize=True, - ) - ax.quiver( - *first_pt, - *first_rot.apply([0, 1, 0]), - length=arrow_len, - color="g", - linestyle="dashed", - normalize=True, - ) - ax.quiver( - *first_pt, - *first_rot.apply([0, 0, 1]), - length=arrow_len, - color="b", - linestyle="dashed", - normalize=True, - ) - - # Axis labels and title - ax.set_xlabel("X in m") - ax.set_ylabel("Y in m") - ax.set_zlabel("Z in m") - ax.set_title("Cartesian Trajectory: Planned vs. Reduced") - ax.legend() - - # Set equal aspect ratio for all axes - ranges = np.array([x.max() - x.min(), y.max() - y.min(), z.max() - z.min()]) - max_range = ranges.max() / 2.0 - mid = [x.mean(), y.mean(), z.mean()] - ax.set_xlim(mid[0] - max_range, mid[0] + max_range) - ax.set_ylim(mid[1] - max_range, mid[1] + max_range) - ax.set_zlim(mid[2] - max_range, mid[2] + max_range) - - plt.tight_layout() - - # Save figure - base_name = os.path.basename(filepath_planned).replace( - "_planned.csv", "_compare_planned_vs_reduced_LIN_cartesian.png" - ) - plot_path = os.path.join(os.path.dirname(filepath_planned), base_name) - plt.savefig(plot_path) - plt.show() - print(f"Figure with planned and reduced points comparison saved to: {plot_path}") - - -def plot_joint_trajectory(filepath_planned, filepath_reduced, joint_names): - df_planned = pd.read_csv(filepath_planned) - df_reduced = pd.read_csv(filepath_reduced) - - joint_columns_planned = [name for name in joint_names] - joint_columns_reduced = df_reduced.columns.tolist() - - planned = df_planned[joint_columns_planned].to_numpy() - reduced = df_reduced[joint_columns_reduced].to_numpy() - - # Insert the first planned point at the beginning of reduced - reduced = np.vstack([planned[0], reduced]) - - # Find indices in planned trajectory where reduced points occur - reduced_indices = [] - for red_point in reduced: - for idx, plan_point in enumerate(planned): - if np.allclose(red_point, plan_point, atol=1e-6): # match with tolerance - reduced_indices.append(idx) - break - else: - reduced_indices.append(None) # no match found - - # Prepare subplots - fig, axs = plt.subplots(len(joint_names), 1, figsize=(10, 2.5 * len(joint_names)), sharex=True) - - if len(joint_names) == 1: - axs = [axs] - - for i, joint in enumerate(joint_names): - axs[i].plot( - planned[:, i], marker="o", markersize=5, label="Planned", color="blue", alpha=0.5 - ) - - # Filter valid matches for plotting - valid_reduced = [ - (idx, reduced[j, i]) for j, idx in enumerate(reduced_indices) if idx is not None - ] - if valid_reduced: - x_vals, y_vals = zip(*valid_reduced) - axs[i].plot(x_vals, y_vals, marker="o", markersize=5, label="Reduced", color="orange") - - axs[i].set_ylabel("Angle in radians") - axs[i].set_title(joint) - axs[i].set_ylim(-3.2, 3.2) - axs[i].grid(True) - - axs[-1].set_xlabel("Trajectory Point Index") - # fig.suptitle("Joint Trajectory: Planned vs. Reduced", fontsize=14) - plt.tight_layout(rect=[0, 0.03, 1, 0.95]) - fig.legend( - ["Planned", "Reduced"], - loc="lower right", - bbox_to_anchor=(1, 0), - bbox_transform=fig.transFigure, - ncol=2, - ) - - # Save figure - base_name = os.path.basename(filepath_planned).replace( - "_planned.csv", "_compare_planned_vs_reduced_PTP_joint.png" - ) - plot_path = os.path.join(os.path.dirname(filepath_planned), base_name) - plt.savefig(plot_path) - plt.show() - print(f"Figure with planned and reduced points comparison saved to: {plot_path}") - - -def main(): - data_dir = "src/motion_primitives_forward_controller/data" - - filename_planned = "trajectory__planned.csv" - filename_reduced = "trajectory__reduced_LIN_cartesian.csv" - mode = "cartesian" - - # filename_planned = "trajectory__planned.csv" - # filename_reduced = "trajectory__reduced_PTP_joint.csv" - # mode = "joint" - - filepath_planned = os.path.join(data_dir, filename_planned) - filepath_reduced = os.path.join(data_dir, filename_reduced) - - joint_names = [ - "shoulder_pan_joint_pos", - "shoulder_lift_joint_pos", - "elbow_joint_pos", - "wrist_1_joint_pos", - "wrist_2_joint_pos", - "wrist_3_joint_pos", - ] - pose_names = ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] - - if mode == "cartesian": - plot_cartesian_trajectory(filepath_planned, filepath_reduced, pose_names) - elif mode == "joint": - plot_joint_trajectory(filepath_planned, filepath_reduced, joint_names) - - -if __name__ == "__main__": - main() diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/fk_client.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/fk_client.py deleted file mode 100644 index 5a9b9a1593..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/fk_client.py +++ /dev/null @@ -1,72 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - -import rclpy -from rclpy.node import Node -from moveit_msgs.srv import GetPositionFK - - -class FKClient(Node): - def __init__(self): - rclpy.init() - super().__init__("fk_client") - self.client = self.create_client(GetPositionFK, "/compute_fk") - - while not self.client.wait_for_service(timeout_sec=1.0): - self.get_logger().info("Waiting for /compute_fk service...") - - def compute_fk(self, joint_names, joint_positions, from_frame="base", to_link="tool0"): - request = GetPositionFK.Request() - request.header.frame_id = from_frame - request.fk_link_names = [to_link] - request.robot_state.joint_state.name = joint_names - request.robot_state.joint_state.position = joint_positions - - future = self.client.call_async(request) - rclpy.spin_until_future_complete(self, future, timeout_sec=3.0) - - if future.done(): - result = future.result() - if result and result.error_code.val == 1: - return result.pose_stamped[0].pose - else: - self.get_logger().warn(f"FK error: code={result.error_code.val}") - else: - self.get_logger().error("FK call timed out") - - return None - - def shutdown(self): - self.destroy_node() - rclpy.shutdown() - - -if __name__ == "__main__": - fk = FKClient() - joint_names = [ - "shoulder_pan_joint", - "shoulder_lift_joint", - "elbow_joint", - "wrist_1_joint", - "wrist_2_joint", - "wrist_3_joint", - ] - pose = fk.compute_fk(joint_names, [0.0, 1.0, 0.5, 0.0, 0.0, 0.0]) - if pose: - print(pose) - fk.shutdown() diff --git a/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py b/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py deleted file mode 100755 index fce0b472fc..0000000000 --- a/motion_primitives_forward_controller/motion_primitives_forward_controller/record_moprim_from_traj_data.py +++ /dev/null @@ -1,273 +0,0 @@ -#!/usr/bin/env python3 - -# Copyright (c) 2025, b»robotized -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -# -# Authors: Mathias Fuhrer - -import rclpy -from rclpy.node import Node -from trajectory_msgs.msg import JointTrajectory -from geometry_msgs.msg import PoseArray -from control_msgs.msg import MotionPrimitiveSequence -from sensor_msgs.msg import JointState - -import csv -from datetime import datetime -import threading -import os -import sys -import time - -# Constants for motion primitive types --> defined in control_msg and moprim_controller -# Would be better to import these from the actual message definition -PRIMITIVE_TYPE_SEQUENCE_START = 100 -PRIMITIVE_TYPE_SEQUENCE_END = 101 -PRIMITIVE_TYPE_LINEAR_JOINT = 0 -PRIMITIVE_TYPE_LINEAR_CARTESIAN = 50 - -data_dir = "src/ros2_controllers/motion_primitives_forward_controller/data" - - -class MotionPrimitiveCollector(Node): - def __init__(self): - super().__init__("motion_primitive_collector") - - self.trajectory_msg = None - self.poses_msg = None - self.motion_primitives_msg = None - self.executed_joint_states = [] - self.recording_joint_states = False - - self.timestamp = datetime.now().strftime("%Y%m%d_%H%M%S") - - self.trajectory_sub = self.create_subscription( - JointTrajectory, - "/motion_primitive_from_trajectory_controller/planned_trajectory", - self.trajectory_callback, - 1, - ) - self.poses_sub = self.create_subscription( - PoseArray, - "/motion_primitive_from_trajectory_controller/planned_poses", - self.poses_callback, - 1, - ) - self.motion_primitive_sub = self.create_subscription( - MotionPrimitiveSequence, - "/motion_primitive_from_trajectory_controller/approximated_motion_primitives", - self.motion_primitive_callback, - 1, - ) - self.joint_state_sub = self.create_subscription( - JointState, "/joint_states", self.joint_states_callback, 10 - ) - - self.get_logger().info("Waiting for trajectory, poses, and motion primitives...") - - def trajectory_callback(self, msg): - if self.trajectory_msg is None: - self.trajectory_msg = msg - self.get_logger().info("Received planned_trajectory.") - self.recording_joint_states = True - self.get_logger().info("Recording of /joint_states started. Press ENTER to stop.") - threading.Thread(target=self._wait_for_enter_and_stop_recording, daemon=True).start() - - def _wait_for_enter_and_stop_recording(self): - try: - print("Press ENTER to stop recording or wait 60 seconds...") - sys.stdin.readline() - except (EOFError, OSError): - self.get_logger().warn("No stdin available. Using 60s timeout.") - time.sleep(60) - finally: - self.recording_joint_states = False - self.get_logger().info("Stopped recording joint_states.") - self.save_executed_joint_states() - self.check_and_export_all() - - def poses_callback(self, msg): - if self.poses_msg is None: - self.poses_msg = msg - self.get_logger().info("Received planned_poses.") - - def motion_primitive_callback(self, msg): - if self.motion_primitives_msg is None: - self.motion_primitives_msg = msg - self.get_logger().info("Received motion primitives.") - self.check_and_export_motion_primitives() - - def joint_states_callback(self, msg): - if self.recording_joint_states: - t = self.get_clock().now().seconds_nanoseconds() - self.executed_joint_states.append((t, msg)) - - def check_and_export_motion_primitives(self): - sequence = self.motion_primitives_msg.motions - if not sequence: - self.get_logger().error("Motion primitive sequence is empty.") - return - - types = {p.type for p in sequence} - if len(types) > 1: - self.get_logger().error( - f"Mixed motion primitive types found: {types}. Only one type allowed." - ) - rclpy.shutdown() - return - - primitive_type = sequence[0].type - if primitive_type == PRIMITIVE_TYPE_LINEAR_JOINT: - filename = f"{data_dir}/trajectory_{self.timestamp}_reduced_PTP.csv" - self.save_joint_primitives(sequence, filename) - elif primitive_type == PRIMITIVE_TYPE_LINEAR_CARTESIAN: - filename = f"{data_dir}/trajectory_{self.timestamp}_reduced_LIN.csv" - self.save_cartesian_primitives(sequence, filename) - else: - self.get_logger().error(f"Unsupported primitive type: {primitive_type}") - rclpy.shutdown() - return - self.get_logger().info("Motion primitives saved.") - - def check_and_export_all(self): - if self.trajectory_msg and self.poses_msg and self.motion_primitives_msg: - if self.recording_joint_states: - self.get_logger().info( - "Waiting for joint_states recording to finish before exporting." - ) - return - self.save_trajectory_and_poses() - self.save_executed_joint_states() - self.get_logger().info("All data saved. Exiting.") - self.destroy_node() - rclpy.shutdown() - - def save_joint_primitives(self, primitives, filename): - joint_names = ( - self.trajectory_msg.joint_names - if self.trajectory_msg - else [f"joint_{i}" for i in range(len(primitives[0].joint_positions))] - ) - - folder = os.path.dirname(filename) - if folder and not os.path.exists(folder): - os.makedirs(folder) - - with open(filename, mode="w", newline="") as csvfile: - writer = csv.writer(csvfile) - writer.writerow([f"{name}_pos" for name in joint_names]) - for p in primitives: - writer.writerow(p.joint_positions) - - self.get_logger().info(f"Saved joint motion primitives to {filename}") - - def save_cartesian_primitives(self, primitives, filename): - with open(filename, mode="w", newline="") as csvfile: - writer = csv.writer(csvfile) - writer.writerow( - ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] - ) - for p in primitives: - if not p.poses: - self.get_logger().warn("Skipping primitive with no poses.") - continue - pose = p.poses[0].pose # PoseStamped -> Pose - writer.writerow( - [ - pose.position.x, - pose.position.y, - pose.position.z, - pose.orientation.x, - pose.orientation.y, - pose.orientation.z, - pose.orientation.w, - ] - ) - self.get_logger().info(f"Saved cartesian motion primitives to {filename}") - - def save_trajectory_and_poses(self): - traj_points = self.trajectory_msg.points - poses = self.poses_msg.poses - - if len(traj_points) != len(poses): - self.get_logger().error( - f"Mismatch: {len(traj_points)} trajectory points vs {len(poses)} poses" - ) - return - - filename = f"{data_dir}/trajectory_{self.timestamp}_planned.csv" - with open(filename, mode="w", newline="") as csvfile: - writer = csv.writer(csvfile) - joint_names = self.trajectory_msg.joint_names - writer.writerow( - ["time_from_start"] - + [f"{name}_pos" for name in joint_names] - + ["pose_x", "pose_y", "pose_z", "pose_qx", "pose_qy", "pose_qz", "pose_qw"] - ) - for point, pose in zip(traj_points, poses): - t = point.time_from_start.sec + point.time_from_start.nanosec * 1e-9 - row = ( - [t] - + list(point.positions) - + [ - pose.position.x, - pose.position.y, - pose.position.z, - pose.orientation.x, - pose.orientation.y, - pose.orientation.z, - pose.orientation.w, - ] - ) - writer.writerow(row) - self.get_logger().info(f"Saved planned trajectory and poses to {filename}") - - def save_executed_joint_states(self): - filename = f"{data_dir}/trajectory_{self.timestamp}_executed.csv" - with open(filename, mode="w", newline="") as csvfile: - writer = csv.writer(csvfile) - if not self.executed_joint_states: - self.get_logger().warn("No joint_states recorded.") - return - first_msg = self.executed_joint_states[0][1] - joint_names = list(first_msg.name) - header = ( - ["timestamp"] - + [f"{name}_pos" for name in joint_names] - + [f"{name}_vel" for name in joint_names] - ) - writer.writerow(header) - - for (sec, nsec), msg in self.executed_joint_states: - t = sec + nsec * 1e-9 - row = [t] + list(msg.position) + list(msg.velocity) - writer.writerow(row) - self.get_logger().info(f"Saved executed joint_states to {filename}") - - -def main(args=None): - rclpy.init(args=args) - node = MotionPrimitiveCollector() - try: - rclpy.spin(node) - except KeyboardInterrupt: - node.get_logger().info("Node interrupted by user.") - finally: - if rclpy.ok(): - node.destroy_node() - rclpy.shutdown() - - -if __name__ == "__main__": - main() diff --git a/motion_primitives_forward_controller/package.xml b/motion_primitives_forward_controller/package.xml index 4e391bc89c..444deed469 100644 --- a/motion_primitives_forward_controller/package.xml +++ b/motion_primitives_forward_controller/package.xml @@ -35,9 +35,6 @@ tf2 tf2_geometry_msgs - python3 - rclpy - ament_cmake_gmock controller_manager hardware_interface From d24793002df53a09b42820a4cfeb919b26badfbd Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 22 Jul 2025 11:01:49 +0200 Subject: [PATCH 107/128] clamped blend radius between 0.01 and 0.1 --- .../src/approx_primitives_with_rdp.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp index 6e78fccfaf..4dac53169e 100644 --- a/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp +++ b/motion_primitives_forward_controller/src/approx_primitives_with_rdp.cpp @@ -333,10 +333,10 @@ double calculateBlendRadius( double min_dist = std::min(dist_prev, dist_next); double blend = 0.1 * min_dist; - // Clamp blend radius to [0.001, 0.1] - if (blend < 0.001) + // Clamp blend radius to [0.01, 0.1] + if (blend < 0.01) { - blend = 0.001; + blend = 0.01; } else if (blend > 0.1) { From f22f4a936c9812ddceb358473a6f4b5932fc3bbe Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Mon, 28 Jul 2025 16:59:52 +0200 Subject: [PATCH 108/128] edited readme --- .../README.md | 62 ++- ...rim_Controller_ExecuteMotion_Action.drawio | 99 +++++ ...forward_controller_kuka_demo_thumbnail.png | Bin 0 -> 798865 bytes ...m_forward_controller_ur_demo_thumbnail.png | Bin 0 -> 917635 bytes ...om_traj_controller_kuka_demo_thumbnail.png | Bin 0 -> 879262 bytes ...from_traj_controller_ur_demo_thumbnail.png | Bin 0 -> 953855 bytes ...ol_motion_primitives_from_traj_kuka.drawio | 258 ++++++++++++ ...otion_primitives_from_traj_kuka.drawio.png | Bin 0 -> 445168 bytes ...trol_motion_primitives_from_traj_ur.drawio | 372 ++++++++++++++++++ ..._motion_primitives_from_traj_ur.drawio.png | Bin 0 -> 632857 bytes ...ros2_control_motion_primitives_kuka.drawio | 237 +++++++++++ ..._control_motion_primitives_kuka.drawio.png | Bin 0 -> 432172 bytes ...rol_motion_primitives_ur_integrated.drawio | 369 +++++++++++++++++ ..._primitives_from_trajectory_controller.hpp | 2 - 14 files changed, 1393 insertions(+), 6 deletions(-) create mode 100644 motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio create mode 100644 motion_primitives_forward_controller/doc/moprim_forward_controller_kuka_demo_thumbnail.png create mode 100644 motion_primitives_forward_controller/doc/moprim_forward_controller_ur_demo_thumbnail.png create mode 100644 motion_primitives_forward_controller/doc/moprim_from_traj_controller_kuka_demo_thumbnail.png create mode 100644 motion_primitives_forward_controller/doc/moprim_from_traj_controller_ur_demo_thumbnail.png create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_from_traj_kuka.drawio create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_from_traj_kuka.drawio.png create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_from_traj_ur.drawio create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_from_traj_ur.drawio.png create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_kuka.drawio create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_kuka.drawio.png create mode 100644 motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_integrated.drawio diff --git a/motion_primitives_forward_controller/README.md b/motion_primitives_forward_controller/README.md index 94edf30d6e..9e84aa5a3a 100644 --- a/motion_primitives_forward_controller/README.md +++ b/motion_primitives_forward_controller/README.md @@ -1,12 +1,18 @@ -motion_primitives_forward_controller +motion_primitive_controllers ========================================== Package to control robots using motion primitives like LINEAR_JOINT (PTP/ MOVEJ), LINEAR_CARTESIAN (LIN/ MOVEL) and CIRCULAR_CARTESIAN (CIRC/ MOVEC) [![Licence](https://img.shields.io/badge/License-Apache-2.0-blue.svg)](https://opensource.org/licenses/Apache-2.0) +**This package contains two controllers:** +1. [motion_primitives_forward_controller](#moprim_forward_controller) +2. [motion_primitives_from_trajectory_controller](#moprim_from_traj_controller) -This project provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotionPrimitiveSequence.action` action from [control_msgs](https://github.com/ros-controls/control_msgs/blob/motion_primitives/control_msgs/action/ExecuteMotionPrimitiveSequence.action). The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. + + +# motion_primitives_forward_controller +This controller provides an interface for sending motion primitives to an industrial robot controller using the `ExecuteMotionPrimitiveSequence.action` action from [control_msgs](https://github.com/ros-controls/control_msgs/blob/motion_primitives/control_msgs/action/ExecuteMotionPrimitiveSequence.action). The controller receives the primitives via the action interface and forwards them through command interfaces to the robot-specific hardware interface. Currently, hardware interfaces for [Universal Robots](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) and [KUKA Robots](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver) are implemented. - Supported motion primitives: - `LINEAR_JOINT` @@ -22,11 +28,59 @@ The action interface also allows stopping the current execution of motion primit This can be done, for example, via a Python script as demonstrated in the [`example python script`](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/blob/main/ur_robot_driver/examples/send_dummy_motion_primitives_hka_ur10e.py) in the `Universal_Robots_ROS2_Driver` package. ## Architecture Overview -The following diagram shows the architecture for a UR robot. -For this setup, the [motion primitives mode of the `Universal_Robots_ROS2_Driver`](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver) is used. +Architecture for a UR robot with [`Universal_Robots_ROS2_Driver` in motion primitives mode](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver). ![UR Robot Architecture](doc/ros2_control_motion_primitives_ur_integrated.drawio.png) +Architecture for a KUKA robot with [`kuka_eki_motion_primitives_hw_interface`](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver/kuka_eki_motion_primitives_hw_interface). + +![KUKA Robot Architecture](doc/ros2_control_motion_primitives_kuka.drawio.png) + +## Demo-Video with UR10e +[![UR demo video](doc/moprim_forward_controller_ur_demo_thumbnail.png)](https://youtu.be/SKz6LFvJmhQ) + +## Demo-Video with KR3 +[![KUKA demo video](doc/moprim_forward_controller_kuka_demo_thumbnail.png)](https://youtu.be/_BWCO36j9bg) + + + +# motion_primitives_from_trajectory_controller + +### motion_primitives_from_trajectory_controller + +The `motion_primitives_from_trajectory_controller` builds on the same architecture as the `motion_primitives_forward_controller` and uses the same command and state interfaces, making it compatible with the same hardware interfaces. However, instead of receiving motion primitives directly, it takes a `FollowJointTrajectory` action as input and approximates the trajectory using either `PTP` (`LINEAR_JOINT`) or `LIN` (`LINEAR_CARTESIAN`) motion primitives. + +The approximation mode can be selected via the `approximate_mode` parameter, with options `"RDP_PTP"` or `"RDP_LIN"`, using the Ramer-Douglas-Peucker algorithm to reduce the trajectory points. Tolerances for the approximation are defined by: +- `epsilon_joint_angle` for PTP (in radians) +- `epsilon_cart_position` (in meters) and `epsilon_cart_angle` (in radians) for LIN + +The `use_time_not_vel_and_acc` parameter determines whether motion duration is calculated based on time stamps or if velocity and acceleration values are used instead. For PTP primitives, joint velocity and acceleration are taken as the maximum values from the original trajectory. For LIN primitives, Cartesian velocity and acceleration are estimated numerically from the end-effector path. + +A blending radius is also calculated automatically, based on the distance to neighboring target points, and clamped between 0.01 m and 0.1 m. + +Alternatively, users can override velocity, acceleration, and blend radius values with the following parameters: +- PTP: `joint_vel_overwrite`, `joint_acc_overwrite` +- LIN: `cart_vel_overwrite`, `cart_acc_overwrite` +- Blend radius: `blend_radius_overwrite` + +This controller enables executing collision-free trajectories planned with MoveIt using approximated motion primitives. + +## Architecture Overview +Architecture for a UR robot with [`Universal_Robots_ROS2_Driver` in motion primitives mode](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver). + +![UR Robot Architecture](doc/ros2_control_motion_primitives_from_traj_ur.drawio.png) + +Architecture for a KUKA robot with [`kuka_eki_motion_primitives_hw_interface`](https://github.com/b-robotized-forks/kuka_experimental/tree/motion_primitive_kuka_driver/kuka_eki_motion_primitives_hw_interface). + +![KUKA Robot Architecture](doc/ros2_control_motion_primitives_from_traj_kuka.drawio.png) + +## Demo-Video with UR10e +[![UR demo video](doc/moprim_from_traj_controller_ur_demo_thumbnail.png)](https://youtu.be/nsG4sW8BfLI) + + +## Demo-Video with KR3 +[![KUKA demo video](doc/moprim_from_traj_controller_kuka_demo_thumbnail.png)](https://youtu.be/zaRkU-whyPM) + # TODOs/ improvements - Use references for command and state interfaces to improve code readability and less error-prone. diff --git a/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio b/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio new file mode 100644 index 0000000000..dbbde2e7b2 --- /dev/null +++ b/motion_primitives_forward_controller/doc/Moprim_Controller_ExecuteMotion_Action.drawio @@ -0,0 +1,99 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motion_primitives_forward_controller/doc/moprim_forward_controller_kuka_demo_thumbnail.png b/motion_primitives_forward_controller/doc/moprim_forward_controller_kuka_demo_thumbnail.png new file mode 100644 index 0000000000000000000000000000000000000000..91f6750d1537d22e68b74287bc59f18206bbd143 GIT binary patch literal 798865 zcmV+3Kq0@0P)Px#1ZP1_K>z@;j|==^1poj532;bRa{vGi!vFvd!vV){sAK>D|D{PpK~#8N?EUAm zEJu|EExcnX( z)QQ>t_*Biz{m@H5vhwJK<3xnJ8&y*?`%H=a$N%u};(z!L{}uwl4?_`%$L)3N!|O^Ji%WlrK)k8c?|MH*M1=A8 zTgJi=^7EqqZp!jDn&$Ved@<#NDP6@EW4fsiNH@R#;Uwa2EyGO|5y%`@P^5q)Cy{~l zx6BI?ffxcp7&NVMzue_>h(HYEGL-j4M8ESAkyH-cPzQU4eQLALfH(vQfDi_9Z;YC!rWdrHG0V{q z0_v(l-*#A@p91{`l^XyF5FztRWVIZC5F%8-tyXyb;u%&Krw~L)45%cca2WLy>(umw5d^yHr4||2nZ@m1b`E^t&s@W&fdd$%7c7+ye5jUxjUDC z`rNc%(`Wl0Bl^Ba2m#)E00QqFs;U~*x#StEPuKP6x*o$oxf()*SJ~wp$8d~L8Ne~+ zoTTv-W56&_9(!M*swy;14evdMVL;b)2w}*4tvnJ!z%T^L2ZuG01<85VYl0%?|W?-^4`z~3?X3GwGeS|j(IreP3`36)ICqI~KJrzC*{nfT)jH>B5d!D#tHu-gnq$VPJQ#+6zVFcY1Hv%m z@dow-TVcA#ag+_$j8gzy7ib;5S2^LF=Bs_LSIHZ^XX_uzAdWka%6n8b$Dat`9M=LN zkdG}rd&l}9k3WuSwu7YStfx`56=h!@$0iSlp-=p2JZkO3JW$A4a*_7}=Y7fp6TZKy zugcFM1oQ)WVYl6)>pD~w+rjCY#A$oyck|yY_jFxaRj8^O!$6q`mCGihLI`NvR_E0L z&_1lJ51p=syw|>PDjx%!^QbDXvXg1E9J#*-~Th(0if@0qL*f9z6@ z2mWnT3JOlQAGiGP%on#jeidJg>GnRj`TY+k*7-v+xxEhsS`m9x*f!~&ExinPvCWq~ zqm5AZ&-C+j5-DlguVRx@xq!Q&9(?4sHoEQpZS-O9i*S*9xn8{Iq}XWM=PRClU%J$$ zlOzR_HkfzK^DfWaMz^IgF6+C=lxf;m)!T^A#?eBoswz~v(dE1BA+i3l^mVgkX(Z4+ z@jZXHEXIqfg0IuZ{9BCND8~@7+iro_!;5YX$t2_zTllA8T*%^b17Ki*mUKj^y;x7A zLkn(@oNwT(2F_Ld>l*|(Ks>rWVB7UrueW&h`VCg=4G)q;&@>I2roqEUkMY@OpW)ZP z`W61}?|*~&-U8>#CBA$93@={3#AdhUqEZ*@&bidC*46}S^9GXRCWEJ<5Si$Px~eMF zb%naBQ8)ZtRRj>d&x>AXb+tsSDYX4cK|i_uUUVgIUh%up<=@AB$J>_1=#~;oovRmh zOU>s6K-YCxFE7xw+w_c6Y|E15vjmSVUGh25wk-s}d_GUP-b6M&Vgh@F;E5*~E%uB! z1UT%v0h?Wiw(S83=8HKF4i0f}c!0XD(X}0_s>WimNFWG7L-LI1xOOgY8d;8M$*v|2 z*(rcFrl?~uNh%%ZYQ)51# zV}JhuhlfWvJUql=F-KihiLV9)3i`gsX0yR+wZwY8!fw~1>pBo{AlPp8j;Vb!P~rrr zJZ06}H?Of?Er~N1JVkz<^o#PJb*9}dpK^`>Qrqqj0aSGjr{Mjxn~jGq|C-6BA86W% z&vecq808?&BS6p%5p6#pL}0Pl!`@X<^c-(wd)8{L&4zL ze2zx*HE=b{fBAp>-!Hf7_exw)mtU{y*mt21egB6i z4w82vW5yqgK6d_BX_`%QDA`1$SQ#r#-~VCB`fyrmqgY(}OT^`kU`g+KKgN5F!yEg6 zbo2WkPCWg2|4gpa)&sP^O^{oAmwdn~@GTqVfcK0Ls)5xInf1SzH1oP5^J(CR&H6n+_2I5{;hf z=S^Nk?ExonqM8zpwYK`Fme7yv);PLn_p^TR`_YsiOIeWk?V9m&6)`#GcP!o5rDXn-F>=Us1jFdiMBf+i@(Kvkc|5jdQd zpzME3)AB0IoHx)&{ZKw*GRMGxsA&?k^wc1-{8c2De3@j%sGXR{__^yT)m`gtW7zI- zLrR%gem1Qkf-l_o&So=sU!~toTgkL$LI{Wnwj3`m@-Wqr&`iM0h3|q(GT4S zh_pP0p@&FLZ*Omb*=&xcsi`&OJOtD->)IAw*CK?N_!)o#h}*OQr?w?G@i9{SFT_A7 zKW2?7C%~+7sGZ>JuYQlWuV11Pj!V-(BJhy`c;Idtht5?PhKS{IiDBq5U(6M3H!ZwO zm-&J`QO+JwH7!}6t27Qh#CeEQjl@DLKp~^Y8i}Ih7i#A zJ?oIh6IG=Ryh02RM=(VIwyA+GX>7zx<2sYJpK3Ff^Cm$c16x@CFbwDvAP!;B_t+mM z1DtcIzeVS=QjU~k!FZMF=d#&*S_4GY;N@81n%s#~kaR2~DDRjj*CL?YPU{5Y5%#+i zfv+m~$$AtzUebC-*D5H$FVVx0%JcBYd-8V)J~@{U3`$vOWc_91$J()MH}d|NC#}75 z+m?GfTl<&{&Oqq+ov7<70pL_io&8gCjnz3K17$hAoNt+j$r{miGJM^s)259Wc5F4lmL4 ze&i;4^!=8xa1R`QeEPwG!?NA^}vY z^DcB%ajgxUny^?2FV#P_%=^<-GOnZ_0yw;mZhg-|nGNp^9HM-F%3f(ZXZIH$22eU zq4LT#`Cmo34N|vGB!;7=pw%4#65ky-2SiooH+M-TDEmtWwspM8ePS2#X71~h-~Ma}sE#pl>_a(T{YGhfx##$&lZ4AjX) zNih0eY^Kfl->H^V`K%~tcPYgpKl^L|K}nP|`8(TB(ne9FFss)}+eS5Q1Z6xgT-O#! zc3%2kw&&%x<#PnM0B&qWWmDIw`R+i_%{J3@O;C<&9~Q^CtkqK1p{@zu4Fk1M1q80@ zra@IzfabH^?GVBMQIlh*U}Hb1>2T2ug8`6285sk4)ikFGx~j&rf-M4FOQ{(+>j><2 zJG5;}cP|PYc<(Wv&(Jh8ZEr!_cZEr|nmY#@f55ZvzQOUESMVRnRJjBW`<}pI-Pl3V zc&)=`7q`<;Z04*qhLjzz$$NIQj z`S58fPpywierFmP#4E=VAc&Fam_}(BhNRVKnrz+^kSPa)rFWH__ht%PlrNiAXZaB# z!Bf*_EZf5RC)Y9ePgJmo6}~h;l~=M%Fs(-Dn#Sh35P2{<7-+4}n}#@vJZS9&&ELxE zodT4lwq;T8vcCX=Y?gL@K7&y9s`Wq1jnt?1T$!fbi?(JPX)tom;i5BZMrvZCF=XpJ zGuJiwCoZj>;Q>j3g^$C@fWGbBDP7kFR`;ub!`W<>`5FoyPTC>yvH&5NX$gM|>R$_yJ`DNU zPT*<25+XGL1h^Y;=ms4V1#oEZ!_202fvKCIT!aAugZd=21u_7k&pMF`&NXnZhVzv! zKt1{)V6*G6*><>Ct%O-85a9{n9XN+`t&It96i8;hYtY&&z?QQ#l;17 zT?gkYf~f^);?&=fGrv`l8+YiYDxIJkKZF5s7`R|hex@=wSXULArh%_Kh;ikOC}5_y z)>^zuc|^Xl`EdNh^b&Ffcq`}!qZ98ig%9|mnxH|A;F4LJ0^!q7)7 zS1a^ghuKF34#^wdSC@c8h)00OrX6sx?a+1s4<9|kIbzW@{U^H{UhQM3&E((t=(fGckO+vXQtd5b~rH%+|#g3 z))(gQ*UDh;=6XQ$56l=MltJUVj?=VuHvSz3T2n*=9~JD2Ne0sV*xH~Z>&rp?uad0Y z_?@yXYX}DQ@n|wI1iD9%)UM=9)1Y<+?kZmny8d#>j5?!)whk)G8j&>&V=;Ei=lDD4 zwA}A{-2;a|23=;hn<+Egk3}Cn|62efV9X{+6GW!l-v54yg6R6bq@XEF8K=PCl-~9J zJ#ctSACPW-|HFxO{;*6esL6FiP^g^z^IwTTRMVKd0*B>i{-wW;lBRvj@4PtS6hPIL zz@h!`F7#n-$ZT$Y|0dpKQLi6;)L6)LRa#g5c2`R88enooQsWYg=~90bzu)xzu5{~r z4$5rb7jUR`j1f`!ukti90EZ~_(Inyk$Is3+ z5TPGKC?M3fE!Nu|mdg#cZHE8{SJkNM2J`s>`}_MiIy%DBPoH9ce;@n%`#3v0!`ruS zvDs|UbuGt`6NozhAJl2MR}GD*T0THT=zBWpPGcvat{9}IZCeaoi>9tsyTdEcP}6sz zI`{ToHN1-c7O<0aX0p`TYNafhjK>ibT4WzW#=G`6$=l-lR7T!Je9h9dUrXNf24N|` z4AeSQ<`EIB*K53f@eIqeWBSa50*B^LGo@A5UV+09uv{8&cvL)dQynar5c$|POz~LHwA948L5MO@zB|iWBbIj*+oSd8>#)!v{A7M6c5JRupwKi`tPy1`U zz%p_zFq*@F(Hs*CK*@NdYzwB6e@mOHYuDHYp7UOwGbs^eB8)~l_jCD=ZXOpG&Ue|T#x{hT`{=hOtfd0d(3J3%Gu1f(b zL?mfD+q?7m9P{}ci^T#lMg>oI*lf0F+YX!U77;)g*hkbj9N=O=?FHv&CwTSpIb`Tj zJ3-g?2{-fz5ly7tYZ{ zx1P-uICKcnAxecd0O#u#yKcb4hmY|1@ng14ARy|@q%-s>BZ3d)KOP8_{KpbqQOwlm zV&ICV7nPsJa@N2sU56HO*&Z{nh&(Yic@G*0h4Ya|jJfT|OB}OxRjIE+1G3ELUw%FW zuG>Ql7<%%SY0ZktpP0&<-ytx?pPX~_U0r}oCMVJ?W@+jACq@E4Q8m|^rb)i+Y#kWW z;Z_Oc5^O7fGh#cktbO06;4#qtDaSASi*riuPkt~ylXO6nWg)=%-henDYbdgRsIl3q zcC)p20?SmsP5C9uJgp0~eInr0PqLNG%4(07yk(k(B~KZZV@5<>ScEYT!qOA^WVX5` z*9L_TNA^Pwppy?!GEmF46Scd!4l_T6Y(H_CFYNFn6S>c{Em@YLoZ3c~XSyf((6#Jq zJKz@J9yt7~ptN}UnDlPxl>>-mi#yWg`FfP$83EYXs8;5tL8%uWw;P5uO?Hv&= zs@_}H%jHT;^PGOa3*GjPNY*%{Ou6~_k}jn!xLgVS*`75v^49=|>1|8e#(-i}1ncsN ze^juLt8r@H48wq-?+_w^Fq)BY_RAh#}zg_zgn8M&pC}>9coOkOYEgJy{MG zI>3TVSj1#%fDm|4GcxDl+zd_{v|WeQdV}q5i+0zd?FWdfP|xO=&F7dc_OO3=gvXB` zAbPAjWW~A>0IVx61mkLOZAp9+!^DbrpkOr0IWA_yngWU=yhGgO>sF-@MCVTbjK7%lGaaA zhY4U{hxK}`CYCg>r5`O(O+VWlv%XGU z7Z}jt9L<7lyx3TX+DEp@H=xnRO<9NhPS$E<+gbhSGt9=Ffri5{Fd}>56S41mnl~#T z6ipjZBbwHAO;-(z1+|`ig`w{uPSAHfAVA;sSgw}XZnx;W9wA25%`BPX#uzd5H0hq# z73Ot?)04M&`TRRb7~mzM?>od8&@`r*q?qXRgJo7AkI_ngBpijbhy}b*mXUQjvnC2lc%VghCU^A9sn%T zG2K>>2Urs0$?;$2AkcY03vEH)_#&GsCXg(HGuHOjoE$Ig=gc!Yml>#4&i~3!cAzCN z%{&5d)=yE_1U5I@GxnQ-JJ#yP7nx@X2pLbO143;ddr!nP#}oupAc!rce z>BG22it8$h#dS5sXrj!1n0%ko^nQ%*3>=Q{e>iYxbXj=bjea=b@VaN%0Jo>{{gN$E zt|Q)O?^|1^Hn&Aq4C*Yn;DamVYxzB=H3pS|TY$q!I=8joZT0(bvixr@$NSQ>e$(&Q z{dS3NcqA>R--ATHKaIoN-jNRl4o8n?{wgWU0ZAt5Bj8XM#Wb;RnDI$R5<74c$ zJ1mzgY`0tHU7XaL%oviN9co%RZ%BuZVU6P3G!2HX!)m$2YPH0C#(V*qz07AbEEG6w z>Y9GXoI}w1-o{gzn5UJG{KC~x`d(1FpYh1?y@IB4aeAK`fSF=)@Xz+Px6`IY<#SG_ z1e(Sqwy5WqVve)6p*fqGSK20SvsvTS^XFKeoe)$+Byb3tR^_yd%&r9vy^e#c%Lta@ zvc{qJ@J_W*BM3CR8d2&59G+jSv1>a5hhP32Kl|Cwu(!8|^Ye3Tw_7}V^bq^|3u@OU z2lwpjQT~yo$lu3noN@bRU@o<9(y-xk_Lpr;(5}omzpuu zcFG(W*{=qg7j=>ZUY3A?5rK+8PC`&1qU4n_A4%F$G*>e|WO)JaJVGR(H4Fh=+oJ8v zZy|Ga&Y@`<)x=``q%iGHJZ-$I<%nvgT-7zIA{uB^ZJTMI<^IVUUN9{_fZ8<*2F9r7 z%%Mk2e&ZA*)c`W355^&cz;Vg|F4QQS&*ums;9|MNcEc$1PC+$aRRlOf zKtBWwk$qtDD@OXo^#aVR3g>4hc=p{lkkG?RMAz*QBcrs6K%Uzly$9k>Gn+Z5v zqHTAmXN)|}$jZgL2@t!U5>MM0D1Zg;E7Y?YH5_A18izeRmYWWnw!^{xA)bEn37q#B z!T^aN--G6)90OxejAK!GUS%3V!^`DO-zR$<0YN)arH89bDy=_QAHHwTWFDSIA+|9B zmfOC7vX=d>@*Ek^Db1!w?WuVh*b@e7>zjGK*d9K~qzrUPQHN3v4hrPiy2Gg!uGa{; z^mAzKn8%}ytIQ-OYZUy{3Y0t{x{k@3zZ~bKrk|0GUz-yoY2oQXMUqP_b5y^_mLD(n z6UVczJv2&i-_w;04`8TGY;pw#eyLnCviu`118Aug3K^7sH#r2T89zaFOk`9^QDwjA zL4>sf>tJ$+E@S{nJ|{ycOt1q3FnLc+&II}@ud`^Hf3dzmS_kVh#q%szmW|VAqqbdC zzl|l&8&g={vd*IXlGk3=#`nPCUjv!Y`KWXc9DW$r*uc836efVL&&7mi{$cWcO4Iu> z{&avt7Vg%5ozgvUNV*F2DT()W>s|$4zvTjI{}~{5~ZS-L<|arA7985X*PDji>2Nzu$#!dq;liz#+;qFq7_=LE^vN+j-#U^JbLs9-Z^w_i>mUds~XM; zYBkMa02qQXP*D>na>VE|&*cT|=zg&=NWaU+0S?m|NuTR_)x-$dADom6d!_VQwMp%} z@vl9T-Wa`W&t%}x8R#H_&1QqwFP`DzbgXfhd?BXIu%@T~FM-3Z>v44SP{E=10}d-+ z5!jdjhv(}ZPL~^;ov*Onws`R12w#5r1wQ}$bL{Qy<6?P%?PiO|j~`;Om=iQKXzU6; zu(BDS(2c-lUSOTAZL{VPl1$A!ow_IS$XITc`DhQO`&JGcH_o{tB6PW7qg>-A);6Fl zTghf7*ThC=0bIsd%=zghyEo1c%4fDwxB5n~E`3i>pxyDX!OSVEioUw&c7XEJC7_0W zEuAAU$Tai%f_0J%7^(TMjSFghW&dYVPKUhFFf{lHnh%03E#zGh8RQZzV(frcRj zw5ow!d*{BIvpf%jFWHL8Fe2j_7(K1Z=lkYP$n{?{C*V~&lvxp01ln6(9GrpN+U2t0i;gA;d<9%fA0WKo<0Q(FoFVyI`12B zL;0hhHIK~j5v~}2Q@S*+6%aB|IYfdUHU{k-Wf}nL8`rT62~1L+Hh?_+7Jc|{Q#); zs?{whIEo@TkMX1Trj4$A*`E@SR$9O{?n^m1W(JJ>R^dnLpRl*7oWO`F27UceFaVL zO~2oTZhJ?H{>!a*H!9z~iLxBX>2py;;0&X3-j*Q8iHI(hrkiDFeu8vS3SHbMAbmUz zVvJn4$B6A_4TK(* ztT!!&A)=Yhv441oqX&=hxPVoBmYn+^(Vz=8-%R>Fs zSiPb3ifYoua@p8gDNldnFp ztdA^mGMo7F9Cj7UMKwzex;bzut#TZgthvkucjDtqln)Gg1rEKLFco>D)I78|-DJG# z__uz~h2(d>T9iQ-`XZu-?ToOvS}xITHwkR;Wq(2&Z`20NH){0S5CUeinQj6uxBZl& zZqQOal4+RLm%h;;9=kqZ*Y?=%sMR)`&v0~jfWyN>G|h}=|3j|t#F=iO zQ{B@$3Lshe^x5=I0*7;2mae0~u|~ttGa~0|wZ?L}#CEp@fCQk_H6t6-9fGx?9iCX( zs0nCt(rZLy0|~tX74(0`jb#QIC{K_Al@I`69-4#oubLUt44IlorVS|~Xqp=H`5et` z1^{SV1}y12f-H4iV=*IPCfX{Xp~X#ey2;#v8=1^bo873$;M$ zW6BcHpfJkuI-bcVOf!`U#h5G7uy@L;K%e){p>Aq4bxm-0Hq$8EIRd!lMZQvBgFtF) z8#*I7qUAMh$7leR&P8T+n%4&;8!MIfqk}r9;J#_b_6qd$eXl;~InL_3Ns+zlswy;1 zZLHfxP*H>+V=8ySPo|kjKFRG3uyT~~wx$|u8QP zNp7Ta7+<9RwlZan>?C7qT3b*fFUt*Z*&Il7@W?oa?NV%0n;9w&RbVsxjt4d``)!3w%aY*uG6)O9wsSp zZDS6|@`J?tBfzleJL5NqK>pYN=l?wB_6c33#qeQtuW|U}6Pf*EQaLEEqnr9^`u=5& z!!hNJbG5%yU4&RsVH4aI)$yoz3V$p|5 z_?rw>4Hr92Dxcx&li#jL%RZO+=&zbb@l#26X};^;1vLHXZ+E9?+HM~}4qqo3lHjFRQRWsSr6e4hG081GKgNc_+7 zQRcyuWz`5sraDO4HEEOC_w2}A63{d&m7AaWH=8(`SzZv2 z0Ea$!w1dONrp58;1(vHd`Ys?s(99OtKRCeA;X{1#=_mN)(@$w`r_TJ(FD_K0NOh(3 zl%6G^Z$eo6r23LFkf{qr?bDH&k+zKiw%hF%=jZ3BDvzV1Bg~swO2e5?ykgTd?cJQ> zHN2t3z7y>~A}6Bna4e4By-MToHX6%2F5s=-V0@zGceatR_hLj<6EwBOHOGV2un?Wb z54p%!&0!ObLp6EdZZ|YlK0T(qj{&ulq;W{zk_60VaFv_p)pCut>u_}R5OrN$8Vl1l zh_`4QDu*LV1-Kd)n+|8I9nQ{|*lb!H9qr@uFMftEzx+8KK6r$)vokE0OFVh<2#dvB zwX$fM#yS>xPxb~Jz98iqB zojaK<$!Cl|a}Qg2D2o!WmK#G$#5Qs)QIa3LEvXz(O`WI!T-W#LyB>YtA%uuwU>n({ z-0EN&JvK(o)Hw{MEema5Zhq^UKq1Z42@p`DsN8U}maL!kpU&?>lW8k6$Cv^+)+aHJ z@+9cP=5U??8TziHcBIycz}A9p9X$6oX13h-J%)Zjw`;LluF!TJs)|}nQF$N&SS;oc zA-HH8egN3*2sF;-3sfn{Q$@~;0SEIr4i1_nhGKG2%*>ZW#3u5 z8xNF3zq#5-5IFG&L9kvgvE6P^Hw|XubmqyV}Wz4*(RhW?Fm*+b^ zSIC+|ev;>M9gTAOmxGFk&EXIXVMrRGWm-^;N`U?f>2FniYHGT5!vhO*(~{;8UB3=P z89Yhx7%Tf7h;2UJ>jf?Apyu9n-6VMkEHinK6%ac zebD!n?mgX^ehlF7Cc5$KK&H4`5dd&3NM~N$E(+`vEA(;3J}^xhUQy&vuQ2p zgqnn2H(gFOsJ!RzF$@gQq2=|C{t7GA2B4OM0;g%?UeT<|@zmToH+G7mZICtu`u!#z z19X$9yy%LPdGgcccdd@^LY7qSn~A27X`7Ycpe@>g6ooTy>I|gfqF#4yqYWpM&;2s0 z%V@L0=lh--hwXNwznR8i=IJzUi}bA?UDsjgsd4DNPwD3C@(8lcb4s_^L;`kDAb|5| z`+&9^(6$}=en4HAJkGv}*471|r46)|!DabHSpjPy`bgDsTAQ=XSt=U%5Y$XBZRo8Bk_Jk? zm;?XMa+xV2H}O#eIIUJItk-L7w>xaN8|-#FMD@32K$)358u&-8L6-o~m`sIp0EVWi zad5DY`C^W`CXY)2oU=WR$5|fR%$EF44L@q~bsYmv(F~avl13weO!hC!Ml--3eb@2u zMg;TO3lI!+e}=Bzq4ESoV+yQrnJ*K++V|p< zh=B371%1zhE3bYTjqmLp5#`Au&C8>>%)t0FkEs+TUGFn6mqXhJblreTH4f{#=3!GB zvz#l9!^z*p_|h_2)>gW7pA46pM}Rc`P&^Z%{8ecDn&v09<1NxV!9U}vVd&BI9S{9d zP#!(lQqYD4({ZQohhY8`GpJ3_(0t0}@o5^jCihu%=3~H42m}ia#72zN-m7a=8m-tO zBO5U73o8MrwsOiV^*Qq^%Tw}N8mAi6g>BR8*vsHsEX=tn8*&?4U=qt?7zT~NPR(GG zW6aNFv&mySP$~OdWvQ+`G8mb)kXZqOoI!m81~sWJ!7{5OlDwwx$7HTutQ%}>lw@hy zeNi5$G&;2)YXU|T+UOxFPw_BOguY=L1@{;8Ihuyrk~V(~L!Yz~4Zw!3t0f`_xGmCe}nYb4jkr1 z@sC9&oqyCqT(?BHBmLNAzr6^z_w&^g!kBLFr`yx`>5!!V!4`DI&3C2`;i(^w zMw9>da@pyxUekX+01v%u9`E`*l9tJJly8pG7INW@ui85|JY?E8moAaCxU>YEYMPX0 zA2E(MGFK7P(a~b7*dibMY|mJbl(fjSgp?x8R5@U~T_FxVyZ~NIYtP=uZ(7rdnLBE` z@G!bTM1y{a41m&h0351%hNA}$@cHMTl=+PMhksMM6pvX~+UCwKf_1sSbGwfF zudHint`}6BZd;81wrvqLsDYnEUS)pN(lgMDK%146ktzB$Rt*c5wM9!f+%mV}lfa#%CA&)o@@;(7Gmdj*z*38pB&@#g0 zoRHrQp@fQ;StDvH;A^4tlxc=YDYwy_M0Q5k|`i^C$+~9$M zT2W~^n2xr6S_9-Ol}E?!P2<4&3JU&OALg?1?GR{|KA5SxKGW1S=CcLn^F3YvP#c+t zF{ah6eQ%MAnFB-=q*cIBAEh--Y74fxU4zN26wE3EvaAo~uT}zLbu2XtmDpBhJ)r(G z3%)kWy_hKi_rT%bD%}Hz??+h>mD`jbkz#3+Wgp~*tGxdcAY1TUbK%y0&Xe}_bbEbo zPviR~TS(@MbDv#oCtG<<$)=+*FR)5iZy+!Kwf8KqlGlF-y0T(-Cu^VgBzyDP6r|V? z+D313-G!$8`fk_V@+j%u-nlDim>){%kN;dtB68zHS*mJ7>&0xeA(WhR>9iijLh0r@ zl$3LVZ4^hRy!=bxFrRc!laIC;j}h&5jWBcs4afL_wy&hcq!bHX5sly~08k^!9No}k zv)!U?2L%pmEcW&>o6P|`!B!K}X4dFtpXP*ha$1fI7)FAbV&w(k)z>0dodHANsgrck zjRZB4%mmOmuU#TQ1Rb}V=0{c02UtbN=?TozKZ#cg!NR1n%uBy3zuP8(eP7&5@^U;z za-SL}U3Xok=~!XEXxfe%L@9mkMO2!%vQ%#R|Q!_^D^y( zp&zhWEwNLLLkEEV)lK6g%ObWB>tet43PQ|gGx*AU4BkSiFY=W^1}&dBLsl2(QiK83zGH{Kx73(eJ zRg-l^+giI={b|a{Kqte%XuVZM--h!A{TrH}FkdkM!FIF3dc8@3OsLVAK|wJvPzb!o z7%`tSz=>19#mosov4)5oVZNEoP&YLYX`X2S5bMvUhpxkVwZ!XJFVS}`>WV&4Euf3_ zX_8A>oE800j$h?%I1H+(>6|1`N7<4uLC2`^v(|yPZOrf?yPxi9`#A3@w{^CluU%>! z_Wb}~HQ3wR*F(BUfJzTf3|wO*YXUx2f|AEsKjj9Z9Dw=yRi22ZwWz%6tZa^^o}$mf zo;4G99a{_}qH;yd=O4A^oacKila^3{HGweJRLn4y(KWd zVx$#9RTGe_YSr%512~RP9rtRIY`kdc0t|kYK|u8}T=r|(F50*e)X*hh#J(_q4WLY@ zw7;vWq6z$LhPrN4Q%?v04;=gSi%VHxnu}I{D@%+9L@E$iXkWAMwJ)_lUE$*tV6^fO z0>_meN}8;}l!x_mIesW*(x70UYJE$YSI!;Ul4(A6-UAWn2hNeyrZnIg@KuGGw$-ee zsU|mpLJ|5A^p)plL_G!9QRxKUnTBiyuK`k$&)pamG$dn&NYnZZ$d@2^Zda#Tp`xbd z3EWfw7N8q|vX0gt0v$9uF75X$AD})}v%I#l-U=LY@$qigWl9_}?(M%)ipZyw??s|a z{-e@3|Ev4$`y&%7*YeC2Kb6GW*SDf|55?xy*Hzh0NktDZ=Hf&*C1HcS_+|3_!%4+b z`p4g{|2Mt=Jrrq7wi&+WnwD?+udocd=2EG5BiYl}(fA(u@m;QuLDTf|XO;i@>tx1M z3bBaH2Jqdee|0HjcT9d6e_rBKUDHiTP>k0r%5XDH+wAf+l?m^3U6J0qUNSAR{hl0W zmy@dH`Ef~ZZ~%WQMOS%2%xazo7#1NB7{0t14SzjL7Qj~53Zpxtf|`VP(+po6qH zo2Dze__hUG5QX@}Bf_B{2COz)Y_}~!pk~{AvB2Km0!}x%&T(^OW-@lVe6Y9BjS?dh z#z=sRIdDy@+di6M_dOSnA_O02+~ibhlI+bfyKqD0b>m@LO% zvduC1qu@PeH0B@Go8)`^YyK`r6!ray46}D~XN(_6{F#WQ=Fb*DCMN%Z05=C>U?Hfj zV(&zgqp8bnlTvCX@^{OR?{Fhd-%0`fK>wOi{m5-LYi!ml1%L@261IbmKWI=Mq|svK zHNSVwY>uijjlDr&TCHXHQ1dGCh~yWJL>^%}eF2D|MB z+wB_XrzdE4TR7)b9t1#r)6_i=HmwVR#gSB?FE(JHindY*fxk1xz53PuAhJc@Gj;|mKBIW0Eq~Q z2$8b1@9FZRZRwuDYyJina?M3kfm`mx|YD9CI)pZZ-(Y=@$^ z0*BfrcfT%?A+Oin|0|@Cn)YkRtxv~q z)I-C$rmvXitjzY3?=KYkk2kf>8t)#9y$Xj`Z&d^eNBfJv+F%NK5G2#$X%3Z;JY z9Nswc8Iyl)E%sE0WxP&~$}|6-C9AW8!;YnJyac}4`!3CgbM2A2;Q)LMq($xz`T`tLf`rAucr21o4N3|vZdqHXQE)w7?^D4t;l z6^J1)C6h6Jt2^;r_Q`WC`ZYB$dV@Lqm!D8cSSO4`WXETi*?+uU3!BI^*=cbSxYoqQUU7fn$sEeCF#t?AW54~93b8|&N zHUJN*;IbVN6;`@m=8`+HAUJq>GS(i;I&BssPJK3!cnD-tk$b38G0ht)y)J5>iu&jC zyTF*alM9ad&9bl_mV-q)-tbi?(68r$-CSOO zcxjE5YQGc_N+He18W?wKIw>WjHeOQ4BA>{nZU0uZV3ILu(#2&;)_M6Zij|XfD!)Ci zb%B0x4LFD`v3H8VoO2hUrZP4#={73bRKwHhVQt5-tof5u{%S)hP!I%Eu4P*TQb5C4{`i?Li&k zuHdqzmfz3z8xR8DwAFU58T_Sfy_o>M=ThS=!asGB2CxW!CTK&w)I9nF0_zkZ$esAw zIB-TP?#4+zMY)%a*etv2d1j(=-Zb{`&3^2;c*l9PhIn?+Ep)7>vswJSE>fG*cx6S$ zjL0{~i!8T!&e|98*M9md0(rB!-mEO&!+$(qH2lf@zS`mq6;Sy#Z z>2d^sF2WWU))Hs1?5M4>j}f%fM}EYXQ>BNtsM|;-p(*Fh-FzA-v+g9+_~y&EmQE0tW580g9FJzhyuUBcrFHB{|f0E7RSEmIl~G!dh4ki z$r~pk#s^iCu!CWJgj5&3BknZvr&mowe`9Ez>Gu2CEWni(VS!%a%o)O=B!Hg4Dof1m zz89!VSQ3D;)g30PoyI$+2u}TLj?E*Xj?jGKGG_*A(d5Jn1AXv+U|~joJF;>)WW$3K zN87?_7l2hh8U0J%Ud`5AsLn!e)o*G$=bGi0cq{?G_5ySE*+k`)kkwtj@bpdS(O~9$T$!tqeLMhCI>mg7e%a5rn!&tKo-Doo zb9xz(bLjd4Ie`{B1-I!sno+m8x>dH)pbEy8||w~s>B3;L*R9S z!;K?bj$1K@fmL+}zizn1Z*WfN#IFGN2jv!6W4{Y1Cw`8XI*^@0f`TiSF2COIb|9$w zi3MewIqP+)sSr*`z-~py2H=kAZ%5 zwF}FPhXNLvy2N+2Ify)X$|7H7q>U%s{+>%^&2C=Z${XR*shF%lJ6EQW%W7-!3NHFAhS!z{n;aHzu)`CVki{r_=zsOzAg9yvFxPeIA_63-9VO$}wnO;5DK89zj-JPAO zPlTztj7s%MBV>lR9w6ks4K>p(^8Dp)iy8pq4r*I1LF2};Dx^z?#$GC8E-3$Chm|ex zV}pV$y5YZN6xn;~{MK5z(BmhowMypAvDH99g# zEWS?eP5a&uvSW=<&PzNM8eIlA%s+#`Qp9Ab)NPe%mC1Le@MP8;cBNBz7G$^#A^(TX z5;ndU+mUS3t5nf-#Io6!8OQ`1TD$4?5Ow_k7}Wv&8g|&MjP7F=De*+F2_~x%!pW2f z*e`u2BcOdv`-}kh!=@@E_a%~OFxHVU$2M`!Nt4v%t}S%H>ATr$b12;-TIhjeN)GI(x|s{tS(yhcF;v7R(4BDan#P<0C-^A4G?pe}x!KUH=a|M4(eg;{^?UwW8;LJKu{(28(B1V{ zURjIN_CqC>b!Gynl8@D0RrChEre^0a(Kl^O4DNYzEZ@fyN;PV)Gw5ipz#!3(u(2is z|AC+512xA%kgR~~06Rk-(pqW+;_v6Ek|kdMn(^;75G@SmAt@US60Dz9Jw0q3W6-70 zBqoPk9|;zh^du&GG_)%ce>EVMOd6mL{*wrg4lk>1kcAsS;JWRKs=G@~^6eYXBx zWG}v*GP1}#5BIZvpcg{%Q38`9H$7qt_;#E&K3U`z+8^SeVipMS`VV`HGrD1`TU=HF zNO+ZUeohT{LPx|@8t|pq;K*k3(;lDWi6oe4Sfg8IIjtYm#o~%H<4pr_%D7VrN-x;E zs~2xRezVEd+U6y9al?n5C!EPc&I$VjYPnit--M7xk!qb=KHW{n$e-e~Hz>4<`o`FW6p)Wx=Ay zglNQ-gm~4?c7q%s_T;xlplp@dgT-f7YB=n|X@7IyhFaq7!;0U#ARRa7%LmE#Tdk9t zvCn=9p~uM#hD=Sl?&J_JmUUw6)dJJ0B>CVQb$^EboBYoDiGkZ`D6%ihI-q`2MzK=| zmR%=HAi#rYs;QC@CIccO3?z*D>)?lt1S`8S zGibRA8V8KaXKOS0mxu$sjbCikvYE3YgaC=|1*e{$E2-J^sheg$%@m@lLC3<qB`hi(SG^Fq25Wbm?TEmdOdSKzsgYS|7pdI8!K{W<#n~VKS}H4>)1$X3L54b(i#>D+!5w9t#E&@cq7Ndl4ZB!(ZtD z;&XNqyo7Ng5T;G(f*nrk&)}s&pmW&K#FC6Pd4Jd?_gI^~vbxtv-m&+C>|lMojUhRc zZExZ0zL1(>2?8eq*n6q?w-qxnFu$AlMK_F_xKmta!idDchx4R05Z7K??N;-d4Zcf{ zcoNGANER^&3@I3uK;#EF;ZUPfI~|btZJV~Pnp}~&F^Usfb1r_a|Z1+q&rFhfa*v4XZLnz2V@WuGH(?8wV#W-b*oLe z36f5=k?kiIIOXiv*0Qv~3*hQ%ve_u`6>85HjO6CVRBhgO6 z^+(6W)0jWmblQxuk+jNZ9S|+8y39w<39q_^1AAF-56Y?XzAVx0b24kM==-jvQFrWw zLs=w}dF*`GMwuGE`4{wxD6HNa?|Qhv#9D7Gw@qW}O!1h2j>)vNo=V1-cv-%O>&)>60apC z9+bfS)Y6QjUI2f7qElBUx=?QF{ z>FML^1iHHdm4O`v?WGDkq8Oy*tEC8ZTI?5Mu(nO=l$^OQq2#KRW^;GtD)G+XJ$>PJ zei>K^(x6B(ENCO)@DnEwFyh5b&(QT2Wo~<>Wzn#X`RdIII~lqSIte?)I21Y6UqoR; zHnoo@+w@wKZU&5pR*AsFXkmI>W}D3>HGexmvC9nzTJ#G#^h=%puKP8^ zGQzp^i(&v4k3bDedKP{DOgs9&ilcQgpR= z>?yrWFS`=a#F^If##9SM=q8joyVM7~GZ00jt~4j>pXc`7w>70d^?wsfiQ{vN4?W<7X1qnZzl-nHa>}bZ0$~2tNqckAB=Y$vH~X%{+33{@|5}sayPJ$Z zJ(#li*QudX zfF2#R$>Fn0sPuy$9_pKz6_$S3dm^e7<0qB3Z z<~YgODV`%$I?zN#{6kcX{Gxk>0>V^Sm9I>^!{v_Yz5D`#5hm10s+Ez>Mc+_I{fAm? zFuSA-eL={5#Kswp0=42vvEGjR`Rq|s?rQBOcUTf|JM3VqIOF|Y^1uk=u4g=z8RhG- zQx3B1-u|NKRxdw~@S-I3M+SZ$FwWZ+rE(?wo`^Kh8S}iWgV6LGC2AxrP#m*)5Q-4S z5C7`)hD6Tz4Lz^RFOE%ld*^x;i7Yn<^6PVMc8=M{E5LUh1r!m%FX9vGKJ09>R-BwN z&UIA#tzU3Se_j4C<+pvlc=i~9BSr5lJzWkVj1<9+q&VzO9}@ZiP(^urZ}+x$r~lUR zdTgD~sZrqI1Z%)94icy)ATSMREsCoDy*R&H!#{b%#eC!zBHoH#nxpe5j8hZOV5>M$ zcdqbjl>ZlaR)Rv!>WB>fd>Ajjm5Jo-n#u2ePav19*WzhL`Ref%HGbaxC&KX$9p)J) zhTwoejN=qJl=x|$Y?Q^z{3OX}PZxf5vNeJghy74;-Td&N``azYj&l}e&KXaG!2}LQP$lRmW8YY3T9)a%jq|JxD_5P zUd>AK0ZTx%=<)HX`{Y7i47Nomc_Lv8!s7B}`(<|x=5**G`Nm@B_vhlwLP7nNtacN< z@*k>USl=7DJk*>*6Zp6u`#r5%2yy<@qgEgl1>AARpZ!_u&lHZQUZ;rJo}P&fc&9L{ zZ$76sNv3!$8JzsYK$63POSfwMia2#W)KA}6crH+iaBv^8Rb;8myL5l!(E7FPF&RK)k5H;nt;2ONRIqUM#y02{NmEIK40M6Z`yecqy&!; z(>htuOJ;j^%K5*fO1H@5F`!bW2vobwWWb!J!)zN=g{p=v z1B-^n|2?mK12RnBe|;tS@ncPU zorM?joS{w6uw5NZK@3rEM5FZd{{@&JQJ8I}y4uXBQ?s+4Wv`zjzJg?9-3#@Jgxw~W zilw6OWKXbk)X90t^+~ep2S2d{1to6v?h>IX)1@1=;4unXI5E@+#?scZMvTAc^UN-9 zrN>YG4zYY+e}m;BPYod?Af`DG_jaI7?++kQ9nDbk976lV;c& zb~0@F^^Xgw{4S|wU1Cnj$60mOJAbHfXw7rgVLVZ{ax)Ba-?o+h2=r-IRDkj#m{1Z; zph^mGm>VnijO})XE8%`AlHKZ4RoVb0!Eh!;b9I1w9LLcY0hA%XvUYpazIyCjFn_&? z{|J@qeW~?&opQWBctu0+K=UJ*6^!R~Qsm-S1JXP&K}0+wW}?d!YOa$w%*@AD_f^v} z$l+*2CsBhdpS{XmBc?QlJLvviA;Yv4jD{FSKb`UEWM}V`JI7IyioHDn)uJe}rZV^Lr|KWw@r^2VU_Pd+-+9ZeE-k2*x9rfQA6rOUJ+#G_1yL&6= z39wsZ?S6*1L;+fb2`X4459L%gBo73pJ^-m?*gPA-I8J6B65)-hF5WdN`0$LS2VbIY zeD<2HF!#^R#!k*C^|mmou#RNKRVv|Tp{}i3+1{GEQS%hW3y>zga!pd)cAd^JX741C z=1Xc>>z-3$)j%@0 zZE9L8zg^7H4kwt5sCP1W9_0ZsPx@Qg*ZA*@k`!5ejZe;uUv0fhSb4$9>r~&#@XMdl zdJ=g+g0j;*EHMhi_0@}rQ-$O(9W|p4a$C%BRa>w>2E^IK z1!IdrMuKIqzCCKjq1|hWY(RtXk=hEs&#pe*ltH_a=YNYOP8<$xCC`|OqFGD$|JhPKB-ssIj$Pf=^44MPl6S;q0alEQo@<~ z8cIIY6>F5|XV4EjAI%Oy!SQ~N1s%)JcOT}2hU2)?YTl7p21|3qhp@V!tHcQw>2 z$6a!plMpmI9%2LaI*e~Q`vjEur3x+eMrH~l*oJ@taqzAy*DuWk1e-)C%8Ue+R*>P=t|@hpY`wT81eu5WO7 zL5TX*FDNq%35+3$e#S%i-`X|wZlaV{I(*G!PKXwXHVbm)i(%OOY*)BE$vL7EMnA7O zcA)x>l|u6FVB?Ish9J7$!I^ikzTeX`@vB+$5d9|lOF@X7G+VF{#wNswYbQD?*&M<0 zsUdcvvXFf9*JB!j5Y0QCAe*-__(wqbj&HZdO+zgl6&4D@d97A@Z$L=V1yQs|h@b~1 zsuKZ4eZ&x1qzI-EMU$0TgioWi>nmQ~KRw}35=HshV`l1q%M`Hn$cO$k$5|5-_l&MD4Nohh9;H5~UEG65OM3UVNyC{1PJafrSOvs;JXt5j z=6L>Io|>Uw)gL#pilD01Uo9(vSg%y;br7j^JkNSm@1<4&tm1+k=!P^-BS{H6`+ zjFOmYBJ{L(!~T<{X(+y8w=9=sw71O9%~lR83PV4@ANK~UeAo?I z${N9;r;T_@V(~&7lN^iNrzgg3duF6hfpZI5>0{W^p|oChJU$|JUL|D3@55A zG`4C=VBaBH&)aC%MOFwIuTLQha##8-8OvawsjO7gkH#3^L8q#9)9T;C$Uh21Z~#zP zHcBj|_6@MRojkLq)SeMK0U|#Ky91hE5w~3T`C;fl!s){H!qk}jpgYv)ZhsOI5>v-Z zsK!;2X>YJ${FG(%VxnGZSy>ssn9!h&lD)!$pLC2{mZ~-coB0n|mXnKEljW(*ob!OT ziQsV$8;(&c=q`$KI}r*kSmuz8&GA-;P<%myA^s#}=leS*Mktet!SOjXc;V&N#;{838RNmVf5!=G^xSe9Kc8 zF|7|BtStS;)Y!dlA5qZSK*ToJ#2-{v`8f~x`4FF>+{%8hd8(>Xa#7=oXEX`FKZJcJ z&AD&e5fbV-hTKRTKTybC-+OmXhVz`;y84VL(lDr2+L5tf$blo;V@rlzV-FHUNon8BR|d7OU~7MK7OQ z30d9(L3m{SJ{z%rkRXWtWH;ePyA5JotkgjMcxV@eS6XPSI50O9gUf7L2X{PKODp2l zECgB z-`lLcjM$1z0th$v{OwRDT5e7#ePjFiEo-IJvhuS#>E=f2VS(baZ7=n0#-W8U0&oZT zj3=q5HGk@-sl5@ZnVVJ75njvKhlQxvn0O+q!B*cJrXs~)mB?4CJ!{p_Hi>yCY}IJ0 z=xX_7<1Jp62T_vVNuzdgjmwVWrHhSb;7y53&7pvOzX$ja;JSY`Pci;RrnWxfi=nNC zJ?VW{RMuw}3EiC$T^7r9>vZ(+rC-(t_sA;#BJMroIX7V5D*Q`+FqXTfklIT)5K98s z7Eal_gec|#FK?5Qo}a5%Ub;RJ(`<2spbS7AXZY( zDfdR|pZVa0Jza`d4#qZqZ-_ji}hKRiU#db+Y4FLqi26+l|Oyuufn{ zBK9}266O!RB8~K+F++!Zg;r@vc|voYrXGpxp*Qh@Od_71hUJsuiQ={J<2)`&k8TOk zF)*%9=A`};nm`VU^eLjnIvhmA;Lsp(^BCCh+;_On)T5s;@I{$CN-(JL=;%&fPQdPA z)GdLbKhCYIc23UDK}ieh5V&XZ7=?t4tgyxw{06-9k?KuiPm+OEU@*45kh7SlVe-xs z|FM*9DZ(-WP-Or`ogH1%Li_kQDK0n?>ThLX?HHW@Y(Gq8d97e^i%VnzZ9Rt! zFp@&Z5Kh&1sUkd!A39rmXO@)=%#UagbH%~=w=P(z8Q!1jm*hubY4t`?g{G8}M`_8- z2M1q35{VT#4Y@m_w<8-7NzX=`sM>=GPAr2&kzySmyT%RxM0k2#=j%}Ayd=I#AY&RO z&>11dSId;qo`**oSz%F;k=H87`&jIa-0Sr?aENUyAY_K`*bC&T1Ar=L&zD4qCm@s` zVKQb{ITSbp{3c$fg>8;%U4#L;!mnE)!iLXMhvouJQ2`j(8{KbB|*0-hVR+#I(USJT`Y0)v+Jz*T(7Xo1xp_)UuvL5I; z!^{=WDz=~GF4u4WG_YKM_c8hnL-mxA*}E2(c?c0N{%;b%gd6?W_xUu*A>B>)``JO$ zAr>IXj_^rzL$ycWCB?tRg6@`E=@V-r((_3vvH_0ZkIYXS;PkN~XaucA zfX<0oqV5UZL|?0OmEo5bOcwm=qDv@M;3q2ih%X!RanOJ>{5?tLZNsq}g)GyH2hb1e z1uj;{rvTQ*`w-UgA{&&yAw^pC?k_9VtT40hb!cTh_=`cageM>wYFS7nDpPnUqwezDQYg@Ni`!MTQ>FKo{sgE?%al=u9#2=C zYRu~c1tNc%*Z4)(xh3EbbL`5D$DN}<*SZvs#I1q1=p*i32{1;rTga5uupJtg-*=6^9mzPD$g$p4@|sJNxfNx&N!prnj-_61UEzHPxig)K0e4^4$s}rYA&* z5*>{aOk|(sM@DsBJx&Kv39ucltZxtY_d}y&#IxtI;W$kslne`iA%5<4_up~E@FJ#9 zCn(i5)+1fLz460aFjID=7nB6>!G%!~l0$Y&kfH)ei2@{oijRM+!|Ga>NyF9jRz0Ib z@6a{24vi(QxoBnS%0J_xes0yfrb&XhnZlo&{~3olWKUIE><2_nXJEJ0wnsJ!I`Ev* z0>#2mLDSmwRE%}NSPWvagM+q}Yz>;nipE3o)f$NRmop>uA#<)$3O8#Q5}Z0Je6S{DL<4Wm6eW!7!LckJc7MPpj`8#skj zAA#PCn}6JrV7yI1U9A6scKW1-MoQ+;TAth6H&-)Uh*A!_lkj#S$@5j+T(?tB zf)>3I6LUtT-qR;Wh4*+R9yZu>zd50iR|_*B*&wynBMK7WvMBPy&9^3i8OVPvGG7Ne z5--eE(=yvMroKV6$Ys6GL}*oe9c8}H#6@OroKG$)4-LDuNp}6IJ?k!C@rRZZMbg-U z!&;b^FMld*rZ9a)Cz|5Vlx-R|=}=GZ2Vpm#gZ$E&iQG-oNK)5JmlgZLZnZ3Nk%2&604MA+NALuJ{C{PGecW0)@md=Z@HaFQNM>Bs1#s;M5OfECXo5Ds8lo;;l27IKIG9^bhI`0d3t)<3GxAJ(=EI1fe5$53YC3p zl_?t}39lpoK~(*E#1H-F;khC7vU-Sf=c-w=hO48J(q!xEBn$;64L6re*@f*sNI-5o z@)jqJ2yh3W?p}tX+KgQZ_6}-D<(M|I>3f#Dc zXqt-@4(6?7Z+r?|K>ZG@$1seOLPS8a(9=$In%7J|gNAwNCBh`1{$y@oNcZ*!HG1!} zNWlFKT#t_9l{L8&X3$TcpNQY6A&%8IHC|`&FyOchyq2?|3ea36iwxfZk9j5T+4``b z>?!s&?^xRwK`6UX*X~)x6)*twCUI)g9Tf463$c&x4(i)QbXs!$v16J_h)#x%2DIsv ze7pZ|Eo!pWOdQPy-6TM|WLDE8eW{{T%Gma!-n=rSL_#{|DYuYK+dLScA_a zk{`BqEoi14h?V&pu=z-%zE+-h;%}N8asK%DNk$W|9z}Oo_UryAFD3l9E^6ICss7aR9ZK1YRB!Hw zW-FSra?79Gqa^Sqo%Zzx4s`|&PW1-+=YCO*3nu~`0bZpWrj6*a|DRqL@wz75h%jOc#W4Hy`FPB zh2ucG5SWZo&RZt9#{x(cnG(h6N9DO)hs4qT^w5`cmY>!uOkYlUn%%!0E{bg^PE3IR z2u=4%-jObIgK4eSYN7mHT8I?CH|v=->zQ_vzA)o#TK$X*bWS}+z0HsjDA7uH4VGBg zxbUc?1ers|@DOAA@$nBt%6x0f^r<7H$egK6z+|a>TTyw1E?q-Bfl{tL5)@c%wS}99 z&#C_)_xd{-3|$fT32+u6ou<#vY0`r)c82NC8l~()0}fA?{hWurO=r(#Mc9h2#`ic%_#+M=OQE{@_1#asih3*k zOOfVx#)#62y58PCyDbV-(xoaCJ3gi%f;kYF%iGE67Ywq%;ybED5FT8B3#r?5CU3#F z#C97P!_u@YOPDqsPS6bvu#Bi553-9~cih<3QTI8!h(*Q5ceVdhb2KqG51SA` zp2!rLN(rSvD}}ttBhe}4yoC66Nx$ZbCYN2#;1ZIg zvpD9!FBo-qB9jP<(#c7vy4ZEpx;cbGBMb2?CWLBqBGao(@9kZa&T!v*{Bz?j8PXO+ zP6}l2ZgL-S;5dhBymeRNX^>HV4=pqs*7YMUx{C3>Q>*mC#g0^-*V2e-2M)JVDw+&C zj(jTJlJ-G`AEgWDk(@pdPm8_l zIo(5gn)>*6nk$+O@Ps9^$v=JwO%!x6&rHVYI(*i}*`-FzE+C zmB?t-zaB}x9K}#`>ZHHpSv#SXp$whzOSu&oJ)1D%Er@Sn-Zc0JmHhdT`%b@Jmv|P= zXU_??UMFcUPDtXzP8*g8NF%QMCKY1c$ggdu(e&B^#Tq#ALI$U!Q4>n>_j0Vi9X=(m z;06uzKNoqfh;Nu!z#IPSKTqRb&)yfA;uBr6#7YYjtSW@A*Q(<(?8?vU7@uFT?) zh3Lkx{QJB@@r7lcG}q4r@#f6MlKVxEPQMglkxY8e&Hr{;5E)KmBdv1W%+>uA5(L$b z#b-0x9lq7}x<7~OdHMI>k3g>fL-2AVKIA3ZTruB_T;KQClJ|EQHshXw(^bNt*0|DY ze>v6f5ZIx66|w^}Z#IGi&I{GAv^6?MxNSeF=4Z;lXZAnW0Di@oqfmSug8Ej_-pqw< z%hi7bw=c)jdC{rt-|rmqgF;Su9mtv*b~*3Ik4GeU@EH~jX<$_rv{j^{oVo1S%8hmL zLTOEyQPCQdQmSd$FN^4)lXnCQkQN7NTdcQ06yW?KLPht++mN%7L<9n~VUU?PIu@*D zaZ5Bm6R7S~F+LepGuoJcIyop!`v*Nm zWkcFPjx6e>-N2C?F^Q{TMT~s6YhR8pb&<-AOvpt^oOZuzi}M$9Td?B=!>zWktdT1H z@$6)IYiY5cuc2d5Fd`1m*9#E>hj~;?nL_Tj5QyW#0oJ*%xPRMKFUn>#DaBDwVeu4nR=|W~~WU7krBzp4a z#IM4u{9J;F!u_v|`@tp+d4blcoM^%$JwHECao_k@%bb`p@(bZ$L-7rJQF4WU>yOej zjuaYW-^#F3ZJ$)?s8qlpu+El)+=s+4+w3DtY-f)AUB&Mj(g(@59S||Yi|+;cU4H_x zl2V!U0imHqU<9Sz+^j!AKxcw`bTtvb(6)5bE5@wCG443)Gjg@6=nYGfyw|KCURW$N zC(=9Z`kB0ck4PlFwmBauhC+$n89q1Qvw&}{t9K7h# zo_7DgIS*|7zOWbng*OMHlKgTL3i)0hI!E>7F^-bl3)g@ZIOQ&Pu{`0Jne=@9LNX;- zN-bAj!*pxh=|;}b!BJ3B6L;1G)Gm7*rpiSbgONwZlDd&7A;y9|L5pM%uX0o3C1_oE z^haqLjE!IF0+})M&6?>&3(R!QEeKW)dJOsf!Q5}#phDNwG#4!!D|AJ-U*3g~h})3w zH`{Ob508JVYOkmGw)Y+%2__al`HNi{Mm`TS@nv*;COp|73nF$YyEvcvkL62ZahZ*RBo4wjt^hZ{Q;yu&XG zlE?Wz-DkK2k9DV=+I%|cSlC<<<6XF-I3n+Azfh?Fm0?4#CN&p)1G<`~u3UjO}0{Ze0FW;gd*PF{Du9WAvL3-!@IkbnWgY1 zCIwHcXR|GKVodso;E1*@I|ynDc^bW+93uEp$G$I0fVu4N9{GUx&ClAG>gJKWeyo5; z0#!KpWv7G(&n%v`3p@gN4XX0&eVu4jmqDYhj8cRzynD%TvdOY`l#*YqU7|wGL0)6u zEIReXUz~t88|!U3keJjh>b`LFqFVdzPx~om8T>shl7Xl9C&6yhK`&)QMxp}%FlY} z86IzSRLNO*spcsp{Ll08@PsYs-P(^G+I3_08C^*WFoQNVG~|Q1mlYmBjq+mzV^i`9}C@6oNkhR2TJYaZPR$^fN98 z6nWEY4P@0g98%+>+9dn+p-6;I^v2fFmF?I&64$vQ^Yt+1mAJO|I3mzXd~%R_xgvRvZf5k1Y5xmxD?BTP z;AIo3KXVq_A1$79p_B^$?K%AKyV_}MCp@o#&+#AcVrAJqY(x*kBBxaUe8vk8-cB~R z*}{~sZLhtVxy6!e^t0(YcJcmw8zgqz3Uip+txXF^994QKbzA=77%;hZ{AP`6xuIAXknp!7cdH}uQ+5Fz zk-?LG3A4&N+IO>q?turLT~|ifKtOWGCc0s32=?7zlHcp0pl+%%G(#CslQkklJ`59( z1*t4cox{#?P3Pe{Cnte?1Uh~X{!SOey?6>K)S9=H0u>MAJ*%l4#KuoB#TKcNuTXWC z4;RPARI{uo?+fjBp%!=UeNzRkNwz+=+l$vF6Ui5)G zCYc)I@d}HCln4i7oS~&c4#AmJej%~4%dSQEPD2&)uz~v$$3_|CNR!e!c#|nqP-aDH z*}IWujDaA-pH98s5JJ@KJK+tT;_T$fLi{_@)OmWsgwpLOtrG4bTz3o~b0l=&!U*VO z)PH*+yL*8`z#6sgV#*#JN&}Z?Ez!~(x@{eP`_IVAqtMfe0L%q9KC3@zCI&maOh%l- z#2|0N7WN*Tu%cxzB7LoVKUo2>He1G^0&%6FCz zk99s?FRz{(jrSJMF&&E~h=VB6BN?kIE58L!3mR!=sg_Lw@ZuQ$22;c$oXMpibtr#w z3P6bj7QOP5z>wt{nY?eddb!=>$rUV?KZxT(kprNE?PK~DM$_M3U9+2nnmGC}pxr49 z7!id*(WvF0o+CZ#F#;cJ)fb)7mckJS65!SjdX$>Im3lwp3 zD7UE{lIF3T*^c4IuhKniJG02_dlR-5+1dYYgvrO#I3^5hPhT#5IFN{Cd8)q14OLaHp7la}GRT(M<5AhEpNa@J;G;_o!M-c$Q+?oRGjM9(C zSu~`W`8ET$_Px97*`D@Sc~7SC zH=|#1hZWhR#vXxdJ?%MS;LOy7UX|PS_pd2)6MblrCxz%66!_laxAijTN<-^>Vvur4 z-vGXCwz1rtmea?Mp2y|Q4(E+n);CZ6jIa-ERqEQxOL&qajasIPah{XO1hS}($K!Bd z*5zC6};gWWwPDtFrRd)jLYPeqpBG-Kggz)@O1Op^KfCa-mjIW55O^ftl60pvj;1~ zHysFDdBlLk?mt{kDHHrz<7W5RQFU0fAr!BXy!#GqtNfoQ#k9Q&KnYBFU z8;tUXzPAl@xO|{rp}YETRai7ibSyGT#12?d==P1ZU}*S*J)7 z_X=H&|9!6(Gwi3EcF$M&MnDjm+mJHW1y~o?6)9{U(LrXqft18rp)PM8jxd2CI&fm1 zCci;{nqy7WaWz_Mfy0x8u-zdMFa{`ruwt{+s-)s|++T5JQ(+XN%3QsJj>6kV8Opy4$-YsgCMRWJuIp&&c}zGz+*l~jmy$l^cO zdgIS|p)L8Do)s;)AP2oAT12$()K3;|8p6Oa|w`BPEYBYIhHQ{WoQ z8z+0euFGQpPiY|buKQr+c25@5*y{b;Nt*%r>@R~<&mZZ&vl#PjPEbpCgf6K~v;DHfiW;JPpE1>_sIQlL=gUMH>Gp^4n`U(AZA00zqd>0UpnA{k8 zFw&>aNLc(rn3UBc=d%r^H8Tw3{oKut&+}gU#j?&kz*KoBK=q~KNGMB6y6sEo zq+F;0`>S74ZHF6i^FPCn=h-LqvC1m<-@hSCSiM~}{#mST41Fa#^Fn&r_alZoBeOyA zR6{sJA51(tKk%?pp(dvp$K8l&bxj3Dm@7bt8Y$8O z&tWHj+_xZ&jcBju1+Mey+ zr&TiO5;=I(A?J3P2_GSDLg;sLPHGSa#O;Vwo9-z0Ces3Hc?Ci9g~0K^l$;B^%LaIO za12m{BM}%r?UsmL(PNi_<(M}Dwb*DGO`W#O)k!cis%`+!W^s!m4qT~O=4$m={3UJ_ zy*o(~D8tj44@9XV!af)&v@BRS0L7WmYQRy5O{Ojg05Eh}z>t?&#QzU@bTG=Rp{e0o z-zn4KKv~DE-gxdxTGQVrCsNjkT8ZN$3}(-FuiMu=L0qU@6;vl34wNsULiWIrJ-cjLL4l44~+@*ndvXilak2NBB-3>trn)4 zr*dZn1DSNX)wLL*&R~R{Kuh{d8k#CYfpC}?ViNa}cy|rWbnypn%_z<liqaUyS6qt-JRrF+R!>dR+i#K&cegg9SJ^$20Q8H+(yVI42LZ zeUiP1K!f!zFJmqou?S@gwzmvUd#pTz`j;h)K2|QR8!moam=Kzb3&CzcPAllc_@^45htU`Xl`cCWnm@ zw@?%O9T){S!X-nYPC0&a8r(&(nKHx>B2Rum6w)P%iihuJg0OtJKxQG+c^FxX@(L-0 zRW@I7kY8iaI&o`BKJf1%{wN`KoP75paKCf-->A+!g2t_=Cx6XYFf_F#k)vyz4B&nxmG>FNDtAy^qxmD6 zi}VvHNK~Y+(mo=keMk#4rxfi}7wsanJsvFnO?r!Bp4=Me^`hgX)ovSUsscf3DT^3@ zmXOv11&hBqJRvCxJa=7Ry0vyhv?!ltj#b z{hf{5eboCrLGWOb+|?^^@OC7zy_E4I`^-;0#BAW-0n_wT9b%;K8??1${t|y`a=tqJ z{d2vyCSA%APIW8kgRH0A{R{CV>I6F@y={nt$g0JGPT!OrFt=&B#DCz&#RU1K zrA@kvTUsFYn5wKPGNzM-OE!Lb7+5~Gg>Y8g(>JnUjzveITJ6llfaeo~d1)a!-0I&Uz0udec*Jql%_Z_gBq zO|+|P374vNb&ZZxdv(^D5blcLU8UvXP`3PV$#%paSQxtkU8PG+U%42Y-L2bz>2B`jyh3Y(Wk~r#x zONSjDi1cRXR1x!9MOpd{T?B@^CgL;A za>vWuxaI{U!(veg>$U|2L35Sb^iQRi!4Us3?;)AkGD{g!WFX@nL9VhZt(JLYGcf{0 zAdUUu(LW$|3L#3247x)Xc)8lByIsq#?-5hxZ*r|yR+!SFUqII`>nEoSZSsJQIz}vN zO7&(3UEg{mzTwF0&-cRKPj|$f<>ZF_Opt;k3~nGJa?JY2&oc>Bf>mros(%t)P6X&z>ePJ<8hmd|hXL!&*;%T}he3?1j0Puc_?JwX*FfjvJk-IF^tW{aV<+ zOfp44*3zG`dY*15pU)m@&!=7<#UC%FpYY6so@^1@WcmT?%>r#YFVd6}uUFY!5>IN$ zKq@P;_r~@ke>`Ql^4&{3b~fMGv!s#8tFSu!0r43-YSkXLBr#8aXPs80D)M{-WuN_N z;itU~UAg}^P^yEicyoRi=ySmO#_li+U$F&0|9#zbsQ0(gI<)gM(&k@em#73Gh!5<) zO*V3J@}>V#6}vAGytJiNY3TDhgH0pqVZ{s-%^nN)WR=|z;t)92+!<~d*uL!kDNEFn zq)ML}aR$mXa~g4@f2vFTL%w6EfaHWhww$&+aK9*I{c1dRmX)F+sq7i;@*{xbiQ#vq zq-?AO1uRELI)SXIIOLWzf&tvRYT0GR`%Ph$bt7n;Eg@y@HP*m{jXMIfLBWJb@uZKD zBFB4Ui*SswEs_Q-S|E0lyNoS7>WdE^c?vFQ8{3DfDmDih@Q_y~$ZXlzydQQ2&7}O| z_cj7!47l^Q?@kc*vOKUyVEmFtB7s)rK`A-~1q+Jz{Ns-)zIh~lo}}Qy_YAeAsY>}4 z8Aci$jc8uJkz{!I zQF*zddf>Bjfn_X8t;r@9y~F37k$nl2#(q|Dk=J*(2*?r%OIFr8?{5$YOV{()UI)!b z;DhQO2dC-}gY?bz!08y9>r}W#u#ya|!R35Gh6rt{phjH+(65vm5z~{ldQNyjP3XR- zyMwRp-3{7ADL>&&Ov_nDLVyJE*bEu_KWE{N3-tc?>?<3OlJP;8wdeEXJ$lv6V@hC$IhdI3;sc=1iVL3|Sb_eW-&qvJn+`S&?y3MC?{?Bb9C|8VyMnzGU>x=~8OsD2(R! z0~Y)HwPzr)SrT=G%zwAM*3vu=G~PX?OqmIWK}%R%kD`taKvQ-VoQM9(PRn zfuPj(cj=s6d9K2~&ab0g!-8xq)X;(eHO_Ro)rL>1NJ0oLMEhD)ELnE%yquq+FhuA1 z&b5KiZQ@5kjbe(m-6{ve6yk*2kMQX=a1_ zE!+U+Vo8SRe2x`oL*LULJRI+Lb0{Mb>GD?`srA>XuCVDx;CN0if+-1oN}jp>uJslx zJvR~JQ$&ZR?6p$W$qHHa1X^yoA_?@*>T3UUuPl-~hIPBH@Tti!TcPZtipy`FlgJgK zB+>1PYtyXLN@bk(c60WhyXzspjs#a~kO8`geI3ULqgklz^oem!UJh*HXwe(Kg^EZ# z(Bw%!;BlKvAU;!DY==WI`yVkD5H4`Aa# z^3jzU@ymiP;;yk$)asL}U-QG(z(U&;h15wnMA2F{E1kn)KT5iiOe~U*uyEx&+T(j8 ze6QIt#lQV7JNl80itMVI<^NG8)jkA9h4UVHYqLN2iQXf{CtHQc=^aJa$gz* z-KyNMJUyZ2Xc3=t-H!;y3pE3wdCR=kJu73xH#Y`qbPmUa1xP$>8Qkp(zu-*;U7nt; z?e+AH4H8Zk_6uPEuK6q7?Fi6i!(UIr2EzD!`na*CiFiJ0mAs$yiBYI+5O)7mAyE)W zgAV8dbfFKRO1Ki{e*u)oLXOx>K4fZUe*ichpAaitS-Y{!q(lhe8QldQnCB513j|{sOJv_lW@eI3M!z1sY(eEJ3ZW*j` zNO3VJZD`dObzW%`>T#{vG(4wzEd49Jjr<|u+aE$(E?cY#gMhtK#m{Zxh^PHCS(%C2 zpZ~t)rlb0eK0idvz6BMZf9Y=$Fomks`uTd@Yw^CikzPwZLth1@Ee2?Bg|;1yUJ7!%!qLurAFs$RSZ#wmya5tyb+$DE01#8H2ah* zqU3ZPpWW7OuhoV{glf9F{df%G&hHt>f4*aTyvYxW*?7M3x;w---^}juk7*rtLF}v& z$OWs~*ppENhj-h@M(vsha=%b1ViUQysRC5Ruc=n`zEXJ<5~6qAL;01j?7~X1om%9} zwM$mAD`af|46^B2t~W&#dJwZ_}r5qy34w_ zJXxxlXbRQFAJGaJ&dYXwboyhbN#w7y#{{WT6=sQQIWd)ux-5E#NJ|gHmqpXZK4LY< zU2#Ouxb%Sofir`}U<^5}vc}2RW-lleec&d; zp8vARs-GioI={5BF^t&nMeO&_%;5qMKFun9hbsLyjxE$pCwL5onQ5ohD`-UXq*)PE z=^my`L%}DWF>9VNHAmCr+FlIf+gDc<+-4HP!a;EU?&rfd{!iD7cVqc4u?Y4R3{fX} zt_t2eM^3j^%qTQ&|4!8*Py!dY2j3#?m3fc(S@>t()Rd6UZESoB{Q17bMx8mi+Nv;b z=&XDuO~Adjv~q}4=kFag=?{uX25Xq8Ia;jjr7cy7k2*nU6kdPuynWP!P5(w}Ip!6? zas3ze4~|@$9|P=A^U~9vPI&UQhrHEKje+?P*}+f0v(>Lh9VC{rCZaJ;_?13!%Tghi z{1T16u*}g!GM|4IH=bJ4Qqboe`%1v)DnbFtqn$)d!FWf|@eWxT*s7V;KBVpqF#SX` zt(w6uTAu=d=wWpmo3IlEG;M#?!B_TxlvxcNZ;@PP z1ob{{QA~J-EuGZG0XtN-PxnD4df)9|jS-t`ET{-6VNk7X#u{P9?io>6{uSsR5!D<1 zF=2ZUm(RGy^X>nx_W#}PRbH1eXMa=1Uiohc$3Dm;s7sns)1TxuN9E^(;|*LEJ-}JT z#D3~~F*M`D!X#?xvetY@t}N5wO3LywRhOrufqpnunkngvui!G3uf2Ph?=@8r!moKY zZ(zP%S=-%b{(OP^U)1jM5*t-KQB5($Mh4Twts{-=IX%B?EcowkT7K<`(5m-g$uFT% z6NSpCEY3M>`ibAo>Zv$9pYIF<(@yy z=D(DicimLd4@)PZ;`sw31%ws9{5TzQG5FDoTW~LeVBb{CXR7C59!E{Ht*G_(AsA&K zS`Z8dqqie4egRCs%AwhqSKpt$WukMjpdbQ&l0l4Q8I(f3J7@p}c2xgiKTc1rT*b365fGKP%NeCztG6l8Z3Tat8#Pu9GWrJ z-M`rLBKdqy_Y8cw!+)Xac|fdyAr4bgv+g^*${osf&lsLBSR{C^eLcLM7~hePg`>{! z%3jlgwXE3s(H5N1{={;lwk0x&@_#!x`TRQ0r(RPyAz}5sz_RY74(rx0Yfc*52IbRX z0v`fhUachIIN4L!n+Hd}WUAe{KilIoUNkM)oGa-e)~{XARey+9!_|uOSHB=KTK4!3 zMDg;My`RXN4fI-~Ze*SHP;g%@c;qUbwE(124KQ&88Xe5f0cuZ!dV2A&4>jnbbY;hj zym+~#@3i(xM8#C^LL&vJT5c=c(3yi0)a8To+*Lh^wd~obz?{61XyLyC_P@L$B3uKg z#Mm#v%06smbYMSjo$&i#biBmFgPvZ%HxrBBa`VC5S7oBAP(|ol1r|b5H18`{HvnT@ z#BhE7_TPg&5%~4X*PR}Cg2>ZE&*1WQ{$}BFKa5(pVq%TSQbq=_ryvvo*ut=nW)o&l z*~#P;G^kHUNTQ`X4xp0&-QHLB0w6dO1~Rhf-i%0O06_Uj@ZP1T*Rpj838>NgFn6ml zEgq@PkBop1)#eV@V|Wrm0-)1)OCG?=r+_M{2b9V|oDcXo$+ln&0uT>|Rygo^3v?NS z?N5a!aY0Jv5vQnQg%}h1hK7^9f@It-@A0*bEqq>{kD$^0eagaVbk}j8t>K^P!*kvm zKakIQ5c>a%_kRb&tRFfvV*Y(O4Xn9;!?5OEzA$o4zvZX36(eGXh@+>CS?Dm1W=|&% z{UQHOjqZ2%`hAb&+iWfJMgQR}*)K)Avw|y~l-^}QZOfG~Q(SXG0TdL|#Z829dn&&R zn*V%d`}lkt1pQx&56-;-JIS^}6u)1Caro{Ji75En-#;(N`NqlQtgcE|aLf5^{D5L- z{sP^_-_-1*nY_%nbvcub30yTgfyakUjiIX>-O8oe;`a&yFWz%1jT2E2(NXR(v7NPX z`p|FcOir^ok2lLhjEj7w1>M+##Goq_Y*WG6n2kYU0%dn0$l|Mzx5Hh)k%%D4bmlpT1pEqgy3-nZl;S%9|(9PL_}1i zYR6xwqOyl;j*=H>gY>zyt2f%uazC!fw7tblmyKkjw@(VL z&rrh_Z7(ez5-UCKHGAx;S zJB@hd^vYqx*ZcGupgw#h7?A1x?%~hF>kgt%_Tz|#D>-&tC?~>~YNS(?X++O1$jvD@ zegzF#v5YUUXi_c3iAz6X?$eVo#We&+4kPwdH=cnHFLyz(&7g;ut-XzaIPO+e2`aJi zen19_&>j^xAuW)U0*p!si9v=n<}*EOzToY>+;40n76P!$C7(f4Hj##KQ8Wzy4R_8h zlr44D4}1D2ev`a{uyJwNPi{V~vaH9h`yV)8&cRSa1n&ZwEwLL7K zqP*dlA7oF?jD^Hfd!4WS5n2O`he2fK=O$W@gefw|38Y>5b;9N9F;JlBA&}GoY;XGj zlSP^odpuUcT;=VfaQ4Xtk5}Xi5jsOq(LF<<3o9 zTIB_l#jZ8|!(i+bh9`xy&?BGIoI2{o-RoI{4K!85|UI z-{vT2DzxD*?hs+G z*UA=cG2;kVbp(CK(z(y5P)H(03tTVbO`gPR`cb<|lshEw3ZXzl4b zj&_RX=jj&nRc=w&fc+<_)BT6v0=>_@Qt=51TMs047}OK|g0EV&1 zLZ{v=PzX*aFMtIj6~bzPm14~!6jsmfnB2S)?)LrTozdGEa_>GrCFtl){({!uS`E&j z#|_or8!BYt00%73Hu2x-H4_JwWD#?viaZ<7ang(KqjD@zxY;-Asdq|3Sf{FH7j zFwgEGyGxYXkT$c0OS&a(*m?bCnuFO2=3`-e_T@Yq2{3vPJJ22&(3umP6(8@LKP zV(eRDUU>q=Tkzuup(?>7H=djxr!Hg=>xE6^6${rZE@I-u!hMWK_b>p%X zsLbdvM~I3nUHDeLGn%Yr^MZZstubSqSdh~y(=Q4q{$%vDhaJD^A^k{AOQt%TVRD>1 z&);iuP8GT4IZ-3zPETV_ygg8l@u%NWp4QrWXTWc2UWvt&CK%db%^oBDB^aJ1#GU>g zp|#!jL~Pt0 zkpjk;xAk(K9`U``EO?bzWDHXH1QMv;NX|pzhI#%Ws@dPEVr3}lZUuyZc0B2qmbyCG zG+-3FprK$Nrb!13poRdbt(r5mo+q6L4eV?~kskz=t^bN^26A*=$Eo)>((sh!-YAd~ z8S)p1%Epx#;w#fEjB;$hc~C$WSb_6@9j7?Xz%D-R83uRtE%`0IqJ{?`7)x19;u1r! zeTt%rfyrfdPw7tO`-dPU&wIRCo46>{5#brQ&R=uJZ_t3U7GUMqItoqK#-QM>#h%{7 z?4E(0O-v~pCKEPxeH7jGe&RiP0){$t;(wP&?W{u(p^i^3RQ9*s3ecmf*ax<;q!wfq za}r<`J+roh+*fOUYLBT~f5`$#71_ph*od?KbjBiXL3vwuhfhInE^~qyE zK}UDHB5E_IwMUPd6k+gaV({~hji&y9l*ihDX^r#Xt4~Qe#_sXt57YWOX)0@e^R{@( zh538b3+7Ccaft9sCfpGT)|c13ZGEcR+2 zkvSZ_?sv%XIqn0tdpTvdHrm&_HdtR?9ZF!Sl%B4iKxn!P8zCPwJ%cW91D%|4H=n)R zp+5skiLFEGCH;}EX^%=r1po*nW?ThASL?yaCDzy96P_X~Ja3{(yud98SnZoHdR;E4)=QvmhK=`IucQT$4j+7 zQ_3mGjduvcdjy*>5E|M7h*bE>tj?R+pxz*$4z@nWvsi1l(^@1&gUgVWa2{~e8O~0R zx4rRRo5Q#H-v`mTI|hjrdeCv~G%G@C2(F>{C0Rk1(3L zsikO-tZ7Z}SQ_BXBg)L@&HKd2Hm!@P0%wp37*;o5r?N6t_VHVoBUbj|x%Ir3Rb3+a zT=ns>vy46GPz{Sxju8Bv!~6V$`8`wSljuphy+Z&pmRCXkUm3vNvWCIAtFc14=0>6WQV(6jbiPWpQ=5(TiEmO zd{FIm-J>DX0-pueMN>brn^`U2&=v=UVff@(@qjEvDCnn_-Qw!etPPR1;{Flyg8Pj7 zOw3Mcq6=Yl#zh?O1U$kCkZ__J(SRypfSh(-g5qr|$#wNAx*h6-3J&cm1H*9_R}YWy z$}wz{oO}cgl4Q{!!;oX|Rg7Sc)oJJN-#i0ZS{Dr(9Y9(H?MQZPhe{gyT0 zH53&Z4$wqX)a!)^XhA9%*C~%g0XRP^#yanXaZB!aj`ey)s;^KD~W87!i8;>mi zwYCsbJS>FVRfPz9Pm;BWw`3a=08LSruks;ns)7|2;!Ku@zjfBbQ(L>o2fXHc$ zAp9+yCXQHHK|M9-7q*hD0_q}4B0sQ>0bKi2_TpI_C#D$?DQlm0@ZYdlc29{*J28OD zrCHrXEg5+q{##;35tL%uZ(?A7-{_gs7vS&?QQIe@!x{TTU~D+POk-o%eeDaCG|uo( zrD#S&0l`)y(~M6hVXQn%Cn>TGT#2>mOV{eypkyGJU_cFG2P)|;`jZLs6_6ti{ssAq zacFA1Gf;xe&XP`wL^3pCgGT3pH>&>nT4v5S%%H98i37$Dh?Ew*W({9ydoETPBPe&8 zuKw~SFhB5FY+vImt-NO3%dnOb>Ql?k(@dM6ZgGD6J^T+E$kXnF(P?4e%IZOg;p^Ui z#j7!kd+(*Y0`Y`Tk7|rFuA<0P+G`8@CBZsrr7{Z#9UOSCnUY9?#HOVA@bl3?H$87$mnM{{*&I>v#EBa;)EsaQ zD-`rtJ#6ar*=1%$CuD-s}jhFn0EDJ*Z2fBoZ0>dH% z*|+3G(YD@-{Y`0lZdPBpKb#D2-zFcnla*uar{(QJR$v-3ChqMkDq=#+eE(a^n>`?5 zrYcm_9uR1**4-}8ep7}s4ILZ1V;=M^@|^rN!?=MWDx`)*MZKVe5dtrr7n!}8?jAT5 z9)ix3re9JXHXQF0dO8wNT24rpE4QEzViV$rRd~A6GcN;#KH|z{S14IvSs9H@v$g@E zK`QY~?w^{m;3v5opA&rE9_kFA$8F}lQ5l0T1x{V}o>Tt)i7vui(<*fK(HXmD`{$AX z4t+%!`9w;+@ubiUO!8Mns5{=aluisMX1`*iI*-V)VW(aqx5W?Z1=uCiL(mP(Ox%qZ zjB%8YIWzxKm~De98szlSUPU9N&EYP7=g`_2VYm#w;jFPjRWEY9rZvlH)ICDF%%-g2 zqIlIQA>Mzz!?Jrxjd-GU+ra{m6+S?!S@grBF@iC17+V(QzIYOCk9kdIH)t9}w1OFQ z^7pRFPl^NH?-VG_x1S87S*Ng|2zVePokz?_LN}cbccY}!*s7f_!6WoYv~@uW9JHmiwO+(7AfofnyPO#cD4w)X zklCgFTcfl~jnmmbEsA3j_D6UmOqmwMw=s|?j+a@P^njLm6hXBhtU?vpKM&d-(}{KA zsyEN5BfwRx2KHMyiRLi|JPGPg_QTOcQLStGAQD3;IEcpm*`wshEsO^z?~;V7IGGL) z&&M@K`ZNg*t)%NC&u0+Q__g4W?WwCFR}u>9`OjPo+BkHwZFbiStc(MIi$g+1)wIZh zw{z~B=7w1nh^0n+PZpw1s%tf)4`8E;vtgE(*ZG(y z-lH_(57GEIC322ihb0)pDY#l&wt5Q{IdkpNR*j+Id}im~n9p2kd;T)S!P?udKaH8- zH(ny0_rbXpU>!_mu}2gFBq~M@gr;mF!#n5yz0lB2M_5 zEi(e%c`O@I&nUt2uA*BCYGRA|BzDhC9yWuk`}&VkPmdnc9|wk~b+%u4Q?<=EF4lLe zm3RJWCk2Wf?p>0@&O9j}L_0mCpXa`|No*oAdq*$MZ2Yfi}jHlFfKJGkiFFsu@N%&K_Lh$nIR{-4lt(WHB9Ih0G z#HHnLbi)CWPeshUuQk7@OIZG-5xGJF)kLE;TY;^Pw0AUe>uIv7!Zra>OP^+2-|#SG z!WM|CdvPh1Au!BV>uhCp#5jqBoIK+WAtsAVpmXEz==C*);EF`6dU2JCOhSU+WBUO4 zq85b+IH{l3cF>JfU4_Ia6bW1^-}d3r4>27dtGRvo@^!J+e0zUi#j)d~t0m9+k@f^k zJN@I_0Haaxx!aifgi$)O$(~#I!f2!}-Co=kM9{zsoPhE8&0eysMF~ahx{QE4u{chK zXqe)z&*LE4!0M8U3&_za#r01J`JAq5Ql3*v zFt&ITc)I-XdHdUG7$DIo-GT>1Pppj347S!wKUR~CccDf~X6~i8?TEmr`iOXc?R5Xn zHp1E_v(8TAv6WP%CQ_pm{bLcT`gyy!Pd3CkwwxpLmQmTuxHgRrCgx^ahmW9)J@Rj+ z=0zse2nQGm$pGwz7o(s+`DRc%>;~z5oXO6D{%x$nDo^0v!YT#2Kj zqHU&hF9dZ`SiMIc=Gi(cw7bI)MUMRZ#dn+VsrS_4SugKsFAUE3%j4^({$z;Y=u#{j z9WmD-l@tID{(3Np*TA8S;h!V5! zITB;b5}`Njyj}%PH$w)RSnEJIn&>m(he*xq>1vOt4+PA^JZ?+}E zN};e_tXWGS(dh{-y95PP6B=)$RjX|)|99K8>XL9$4bK~&sFb_+2BEfd}`$!`p& zhdRZMZCvRH3lJJUqpks%ke+H^#$KwfZ!*hhs;>4}4bO45;(8|sE@sQb&tFW6(^g93 zfNW+*zSYZee7x=1jFB&nbKFPr9xDk!F`CXZQ|3zZA}C&samNHA4{M;CBYKGlJz?5| zYZ9BAjzH({o`n^2wTc^}Hs}PJctSN-e1F7khUFBTfgi|+sEh9(y|m|yf5r%r$G0AY z+`4=Z^nC(3ubzhNhH-P;WJ zO%jf!B6j;UE&;D+!k(@z+E0Bp9Z`6+N|g`)71PHc+9I}`+$_!H18!dkCpQAX+Xr#J zlpg*~nqqp^-wBW!1_})k>THkbIdAKzO{>qJN8XL12Cf?t!iG&ej0MJjLH_1a5)bcPxC| z>PxNx=^qid2MRppZ)!snIG>HCOE4H5KgkTWDl29li1>3W1gVSm1+KPe8}H6f&kJ1yD>5;}gii z3OG*gmHg*-9AM{-inxG!9J56vUE-luCPA^aY)>$`BaShWQJ#gZSg)&qLUNh%VtUn1 z#`(6XC_5*?syWmKc(5$aw`<3vS29!q96Nwz=oMs zB8OqJfVfO&Pw-IS@MNkbmT)M?ej`7dv@)&QS+eHLGecD&d&pd9aGXrm6=G9(_6Cv% zK=4B5TDB0dPJiCv&-JNRbGRc9`~D$FD4@Uhd*Rjg)NVdj8MCa62L_OsVT}#@@(r?F z@xEoJm+7oE=EJWi#a>&x3aQx=r`z3S<>=>M#*7cJw9x5zKsbpdj$ZG9g`NRK?!U@i zSq9)~p5_Z`J66Y?yoBJmL3+BnapdpkGGQq395v*ssd2;q5S|gUF4;VM?ZxILMPh*J zm__ga0a_S{+pLp-&1k%Gdxjuopy2WJMfztDoMvbq%gVe_QijN=^s{yaf6ZHrttEMD zebAJ34G1HiL*mC$^@562x3aHCbXS(T7>{e&2~@L&4IRV$nZ;(v5`j5eq*omooPmVG zwP=&14#V?*<}?1X)zITcn;Yt*%L9w94Gzy>2($J^Vb^U0L>9du5FiuBB*^AW*BZNl zXe3mrcz52Pk?uQQzRqTtZ|7gwjUhmrd>2t?GJp|xGo-&5+`$9rIN-DE9dVqO+ZXg3 zZtn9!J8*!(cH(d#`O+WEOEv?2|Js34nYvUc@RhoZ;7EPmF=MBH-0nR2Pl|ZAG~D_T zcU`b%f4rf4n(Bzpo>4@6c(TjX1Dqvu7AWYXM_Zgl{#yHt zwbA`Z^|G>;B=!gHBj zI~lOs2%wwB`dLc!{53>=y=Pa1@ND&6m&DEL6D9Qf&~}unSMYC47Pf~yG*C+lWJ><3 z76~L(jVHy4zxsCez7-$Tpmo|1fQ={_-W()-QwBz^^CND^;1cL}L7rmT%N6o_s8A@0 zNRy?@9vAFv%Qx;LDuE=C2tp>%(GkWmWz8@}tTX`}KEZRYYNJG2eT_`G%JzZ$XPXhY z*?9Bff=E#t+-6c}m-WrYA-fut4?qt|`hx4v+g!zD!8z z68q4$TczwaO%C~KNMZS6nh(c@vC@76h+6@Pb(^q3fYga<9xv5X80B<{UBO@D)GJW= zcLSu#MqN2+4+DwJ&EHglU;0=7fR9s1f2*OHdDuW*Amb#B3;~P>$m0K(LO-6`s|gj^ z8wjB6Z3g9p--vun6qQ2>?SL;AI0ts5jaq3fHPo+HYd)=&xZ#gJ-syzMSARfTWu^-u z51#Z{`bvZQDUd$KRsLi}zJp*dV|BW68 z%Prb+S|oDNA9K&-*!*puhJF*bPwj9roR-jnhk{;}KXLqfj)PXTiBat$B2s3^Vc4Cj z7^2j=+VS8GKg31rCp;`6OkAUHCPR_> z=YVS=LAy0^WbjR`r(&V(c`PX8<>7_xhRk587Fz%fiT3ky8*_H^ zxT2%Sy3lAacypw$m(c^y&b0p?i;Q&4Bv}CpXi^MrMAr4haN#g1>rE%68o%!9M^DkN*Fs1zFg zL!L&#mnRc_pK7iB?-cCg`t^P>C~hn_U|dHlZU6fV2n4VPd`v{voJ%LNPnZDidzDsF{~q>6sj=)ec^RP$CgoEwLKZhZ1H- zR(l_*eT>Ryo)Oy|{0YEO01yG#sp#ssURRBwO^)_SJ0!fe^#bYD9Aep}*W0|mBKW23 z6U%$dFlT7kUqGj6&DnYTZEf7m!za8|`WezH-8tCdCB1cch*dd{r9O)hoa79Mm@^u% zDtcNmJ&A*>edua^HR5E3Gs-N@bC$@A8PU(+>E-46#XpvOcvwV40{ZVCZA8Bb>%`WR ze!R8wlH6~v{XRJ|3!DnaczK0^8(0OEnFQ4Myl&JT5PI7VHppB2f%lUBQM0N@sL4$A z+BC~1L%8+)2LrN!FrxRaMV8j7+BuQD#BjXCqIMA?BK8(&wHz1y2{feMaaVqt;eeF< zs@Br#8Jh3(!K*yTN%aq>`=1j#CkCJNJU3lRFcb%7>Hd=L@7yGtVUYUsL{~hlfSL=Z zicE1dK3IaSCM$A0(kTF~K4jkn+gNO>z#PNBGwvZ%OmjwEKY-R>P2D@E8TSWH#0gW0 z9b-0ePK2)>UIW8>64YM}3Z@3;U5w zKaQdUXFUf#d5q|P<*S(q?D2|Z45tRadb40KRF)d8d)-(!xa1on?Ij#F(ySxSi&A za0eV6OV$Eh)_4+LfhVbka=S^JxfJuxws~JTH1EXzA5&);)MguX>)=q_gS)l31}!ed zOL1wi;@09C++B+oDHNCD76|TE+_lBs<>dX2%$dnd_`ysvNH?G2!jP>6d=+BOX2=x45tqWipe1|nE;|meqwiz5|FTjbed(xgj0=4HC(ia zcn%ha3b20Bb?$nks`GH-;oMuWnd4sTzC(?)OAwBq6;d>Y0l-|0u?o}8u?d24+d>aU zvAsfIQc_<=-NT^Yh|vAo*jsK@gyo6^ekOY@n8$91y?Ifi28-8GI;$TL^!i1A<*Ug(vOc^uVr92f{IFYH+L#%$6(VDmOlqO+aZW4`_ zI@LZra5=Ypi#XgQy5#R(I!ip7rMzkKZ2wCx9f1 zvNNYqrA$ys|6reiYLr^JX}f84>*S1YhDv|3v1R*)S^VwvjAF8{%Jg&Q6AGw(Ec%&p zt(7LgcGU6j%7ex9cZXMlS8d8b$G*Ot3p0kp zsjAbFISc!y{+5+6NJz(9AF#0wtG7w2!nWps@bH&59%nuCgnj$JMq<|lWVMEa1C-eM zA$S^T#5#wFB{b^iFVARCFCMQ!Gy%TRaO*m}*BW4O5b=ul>Ih!)r%%@2Mf>GW6|iN| zdD*4jPf*9+=PJ@YHHELHX0p*2ZQkyAj@Z`LHdsg0Uqd=SCu(0l1ySp;?lfCQ8IRtZ zaBpw_DsL&ZcMU4tN70~708}r1sU0n9?<2gSJ*Bf>vuh~7Zk6U{FBFQNR>=4kpc&*w4BberX0NMqp@OrmaI1`BK`qv~X}>X~y@ z3G^6p!;yl=Ifqk8D6MJ|8W0OBIj0bBa|QmStY?J@V5gQu#!xO>iGD4dO32ABGOh&Y zS1rb|wm-W-YyDwY}aAK~7@q`2B_WVP7kRYtv$H25vf#Fv>m7bEHcV8{_7w^CBgvC>D1aCWZDewc7P|42<+ zQ}|{?!&5T9R2r`&BC>^kkW=S9Iear;j~&Pl_a#DKUL+zQ<>kuk6BDNJ>*MK&2xc3} z^A>rkxe1|0%0M!H-4Pj8y|wE;GaLg49V>#&6R)u52_x6xH*8UB zJD%JO0stGovbggbQYpUsMv%nN(h|cpW`PUxjVwQxs5%B{;rVEHB7ykNoB?UcY=3tt z*!$Z+g|hqz`j3l4HWAnZwBY3w3f@d0|ECRZzguzCK5}y!Ac!az&l)FJQSb>%+WOj0 z*b7lVSWZy#Lg*Fg;PtHO?!3>=_x(yAdluM+kf^_qZbE>}UaYYMoHMMIqyC5Y^Leg7 zY%-&qEg|q9*Az(^h}e`O@PJIu%U~B2aG|^BRLM1`^JVeGBDha@@83_y$ysbWX;PH3 z)_!Z@fvG=iNvAI;3UYx;v>D)Hf4eFV8VzVc#u2UWwVki%;=m)L0t#B4WN!Tsrp#Af z27Es5gTHbix{yF6-ko~o7+s+rSe%fJYn9}v-H$3w3t?+9`PAKvV*P9iK!xCtU*57N z+u!~qk@Ry3>gz_t7Z#gg_Z-V@$ZUJaSthCTAJN-t3`%zvm0MLE#*>`Qb%N^=W~q>g z%0mjbv&*?q9O?LChjY=bNN`KRx1bKWE-MqIru!{WL?&5PPeH*o>Ufr-;jUPoC3KCQOIPP&IBu<~(?)cG%E=Z~45RY4y zrKJ@bk9qCr6Zwtk)HbE>qx}r+lArBiYPX_dW6Z+A=F_DtRiGQPFKtSyjJ{wg719T# zBrw03sDIftDWcsQe6rbC8Dk;1Xr)*mb13^e9uY9lUs^^!vP)3Ei2ZT~Gi-m}mNCJJ-@6pbX^X|1)#BX0#|mGHBnR{+wxS|qS|tmGKF0mYYmh%m2SzZ z$(GVR!r2h#gMSL?_8==RooDap$KeCva`Aw!gvi^-IG1_91-Nq}u;l zAn2BL?%mPJ(Z=0hJUV2!kI(txoMFW_a;T3Cm6V33LKhg$Y=+1zIZO6?RWNv}wwOUW zf_AOW?NU;iOX!acjq#afuSQ6z;;;4mSkpab*f3lV~U%0vp1b!KWF& z$q}K9V`^|NHa8BntDoC@XJ9LI6K5PN%K}|$4_72^xYjSj54YaE$oT$%be`5REOe= z?ZJb!{HDu26;dn|WyAAflJeAl!h+&blj4fXZ7yAmQQi>WUD#(eRMm3Ml@3Schzi81 zeg%a~Ip6i9f}Y?_mx&2@0<9>Jiak(F+IeFhf7l-Ka8260_P+lfjHaB`6Se1-rl+@s zjn5EQu_1Tk5f=nU+DoO;>5oG0V|N1g8Bykg184+80?Q2 z60IzJW7;_=B$P61j7T5HS6jk8RI{yWk6fHpk!X6l=$)Gp$iM2giGoKOUY^xUmV=&c zHd}~9VaA&}UQMBS>A42D&v%-Dr^K+6pR<09U%l=A4%SY5czBa&VtD%RnFPHxT2Oq{ z0ku^R0`<_(?^qfJC|N41^=!wh*LF@lJWal7OmA=4rB{Y-g;=3DQ9w852M&zV+2UP{1OV181I82Y()s z8KR-$!K3NYv`!rafj{=-c0!dR)GI-P3HP~k@{~|rwSHn?`C(qG6t~r$WvIbAs+i3# z7r&9)Om{>@(W^!Ddk`ljAlEnYd>+rDWN9c-QlC9hZPo%GRk&{7IJitNFbFA+-F_za zNiG`=k;diISwf%;gGs9Jrv_NrMkGgX#`n6Vt3bPzSxi;tIAs`ys%P+XFBHA z>_!TnE89xv4`EDO@WuY}@p}zE`lNaG|)HB)=4o^FxqID#Mg=mnKI+B|FJeyU)|Ll4eRi zzn>##c0PMoYt83)r!gl4d34!{JK`F>{~601t&OV1-xbf$I55=yX`Z;Ms;W>hif2oT zPg3v}c!yaBiFaf1GnZ+^lca^$kbYrC`tqdSi!g;uT2;RD+|hq$nm(jCyOQ?5`WS96 zB$Bp!%D!96Vq*86XZ@7Y*50xxBEgoJ$n^>aAk=xP%n*5{(Ww%&^lvcvjH-gV(vH_$ znDy;kIt;eIxW^urziWRyS7;BoWvJrftjS&nHyGvr`jGIg0vi<<8I6GB*9L{8Jp<~5 z;9`c8Y$4n*1!qz%SZMB!aEh<&i3BW1w4G;In`FGOA6Avs?j-Mi7&A%`K;#u z;|VZm?l)~P369WvXEZ$EbO>XgUX$W4YLA!Xqv6|QEvgfShl0{PWf5thgVl(&Fz0Ge zNh837H}VvSo?=Na1_C&4+X+9}9>H+CrMjo$yvlyP`sZs+Q5IT7YNk8^vI=>vjP%bNwpLMD{C$IM zEC}J3=bYmaIlgjM#I!dAoPc)xW3eFaBu8m-7 z`jJVW=Bug!-baLDr!-|x8AW-93}47FFa_PrFmaiImOI88cscb@+iT#^Z-Ba37n75% zfBv_UcrXTl4w&P|&iolSuF}4L50qYR3id_w%+?w^YOT^tV=Alr)94;Ms1ICV3~pfS zPpb)rH$t4wXO96r<(cu7hIn=|?-CROg%I3tG@cK*&IGB5JR-?6RYrR(LnYcN?ne_rvkMl`@DYQU-2OZOx0jLgJkfuAzUP4rwBXCT_)i|ENa zx4g!Vzy3>#ek0|AS{qkxflWCNw+~(41rI(Jie<0n<+_Hf$X{{e{&sC!d9rQ;Y}m!C zp0c^BlQmA3>}>w9qHbMhF%c6x{_dl6@W3OB=*q-KQ|-ND?m_Urs$LDA&^a^7!1aOS zZx3dCFAxDIoz_z?2oO&HIUhns|2IFMj!RzKqnjSjj*>(>7=98ouAfQdAG6pLl+E4u zRWW3K!78eiC&%v=j=%Q}yuADduUZ~=FKwsi+ie~h>+Bkl*n)OiQ{4ZY5ZM-jnB@5vjFf*8?K?jA3tZ<;2qle|4A2zBN3*CFzkrR#+s_aP_{gt zSL+d51oDtU6w??6gh z{q2#YN)3iZ17WmK%m3UL1r^{5xwPFQjAceFB3ry=3n?-B`SFV)MY~T;!JZxv+8>Z{lEksvScJajalc_YeStES%V3spy0wL9 z(vIHbA|jb9!hv9y zMg%C1m%9h^-SPSpTDz}TQ2k82UM0z3JyCjkI^4DmyS^5H1EB!mY`vq=ssuQwNG~1u znE4oFeS1MIV|con5B_{)hFm3p(iyRVJ+SS5h5xkmmC%X3??FdV888q>ZTi?T!LUq} zXCRD6J5YhZZ=s=z3;ygESUyBl&)7F9jtw%3^Kfxow84)Y6Be(_DzX=W>b-O47rL~I z31mXWxs5_e@>n-*HZk849{2$p_>hgs(Sg`XIe}I+X4cX3RZynh0BnzqD$A`JjEsCI zm`jJGoQ>v|n52i974h?TTvym*++0waKyE+89@Jl3o}(qZNa@NBPN*%j`{WkeTBh;q zo9Kj^B^ElytgkZt6HSc*wL%|aAx!}E{F;fGekS4*X0k9BWY@a29@ED&VhM=>_eekh z=MYgrH4s(?mC^@yu{!IKg4_kvCO5R5K^Oui%>)Cgp|I9oQ{$~719MPUKUe@(%EmA| z{51R=C|f-j2Jse=6QC}E+vVmYqrH%SQ4C?ynY;fZg{7rq{FYr0wR-=C(d$)KJwB_}0RrNN-6w~hmHMRHN zk4L|PwW7;K+4J>aS>sq(9u{b4I}jH!ybkZCN{S6?YV;vtID!NEgFIJfBLPd24g3*V z4*>@g-V5R3IZ&$g6JmwQ>;y~AHY4k`Ik)I-J!O;LoUR8zah=w;E-v1<8PnBPY??*H z3mpV0G#h;AclaQS&mVKlZi%tM;oqTV&=0i?wzdc@H63*58&`Ede}H4q;Gie?K`=wD zWGbs%?cuOB=oWjvQYB1iht!1w(eHd_cj;6RwrPWrX{}y9`#VR{EM5?6G)9h6R^`zze6wz`o8SmWn;a>zu>Y!xJDooJ#kK!v z8(RcPXd^x##S#Osu(&8iPn~6aMKo@yQz>7C>mTLTtea3e$~5gPOc-*k($-b@Q0Mn3JdHKzC8L7eR0I-^aJ*z(OL=RZt- z;k8M&C`7os|GPC#qy8Z>0s|9ntoZ=;dkkmRr@ROSmpB;M2$BKC+i({94(9!icwwK( zd^hIwLJ)AD-qjCZ;q~`@L>m4Ynze{U^WGoo%M)&A3xKGy%lDgobqn2jqAawHO)TGx z+=$p!#wexn^Y%bY zY#*SvM;10Nc3`m)O3BZqhQxi|wC5+;IEz$BW$|gQAp^K!^#TGiixuT$X3?GARtF)+ z@S$SV&TXz`2EsIJ`>W8{rR>S&9TSb}W0jGR2!VG#>MprZG#b9n%aNRbncCZgm)N zSk1THuay`43D@Z@Rk91C8tKXYw}b4-_gA|V-5b8=Awnh7zrd4%wM)alKQK1cRo~w} zz5*4|G>gLzc66T9-apkdeQ#b6+b?H%!42Q zaK$fYJ0UfkXybXWofKiZVo*m_BKd)l1 zLYUi>nr!W9QP|`s6vrwxsm?Hgz<32YY~oz!FzA36QG0!z9%dLR9W@!^*JdzJR<(E0h=<$+j2u55dN6y}5t6t};66Ot=q>jWRUfM7oqlr=xBezMu^D zh2|$)QJ7`9bw2yiA*1^5SZmMlvmU;IE9BO6p5u}Hu@Y4L;w`|(0$<%q&0H@*_ z9?}aFDu$q2>+E2UQPJ#MayPALnIDj{U$sV+a7>Hm^@D&sOf$<%&9X4=QPx9+mNn=E z3(!|vIr5I&V_WICbEQc}GUZS<;$4B^f(u0gJPE65>c2*$R;=!s#;cKDkL4fyy!eLqYow9BL2O^!vWD85A;Q+a;ju^__yLH)`{CSrE{-O2ZUgn_L(8 zIRb9(6GWczS3B7PaBGGb6t71>tDZYG$?Ub622BIXMq}x}Yi~H5yBI$5TToOto`#$$ z>(4cJc7`=zWMwPfDRS7Ac<}QT_EXHXvTCLf!!IQ;w`3Afc%1cK5-&e(ootd!eK&$l ziTWPY7OaUoHrEpl>84f4ykL&QMUF?NCK+)H)z*Z5!7%Ccj)iR#HUnbh87OIJwweMi zX%dP_Uhm>xsrL6v&Z?x0)6dovxPu}#at63PRn|J?E{;!mOiWA<-YnkHa;pCQL*X&) zS-dRmZG6f-Y0d3|9oF||(K{}(9K6kEP=X8vr&_S~6S7BYNVg+28IdkaToevQZ)o?p z?or@_lNfp}CKrf2ubGmZ{DVCnADahxk4R8@nz{z20v>&yzPLvPRwsIsUVfR%zk&`V z>*jYos)PKl-#uvwrrpbLs4|%Ay_-MNBeP(T_H|cWu6Oq$hlt^IwtGe&1w3|bZ(Ja9 z*`X04+QN3Zdj{yvzGxxgVg~mjF(U(Tq^QOc5P}qviuL|5r6K59GJFz613o`gYf$BE z*z$I>PiT@$=jaj1mP$j2tppv`lOLilAiMH;uA_{#iw7OyxCm;$%d`ar&4y(K$Qb?- zTh_-k#Uhd8DxhMM0Y96wF!^e+*IeSh5{uHTZ#J{>IJ?0!{W7p=K@th7k`7pDf^yiH zgrDrD=`;X{P6y|mk#Q3}UA^DW(Op)Pki%mjiRXhsNMc~A5^8tY~ zLhBoO@@;yLkjw=Jak%V&V3sM1AoD9EBWg}F#ne_J^f6Fm8&*|M$xu>KnZAN) z?r8^X;pWI%Xu|@TmZU;U#PJrJ^rpV){rVEpa}zK|e|!*6Pb>5|x&{4Fau**~1U5$z;E@bX#c?-bVUq zcE`3^6inXK6>4p-khWX@w&|K`oOwc>BH|bhBK@i+$w`l=55ITXeeVf^H#g>dT8~#s z!XYvQV-0wEKI$XuyXl;m&hrkBjkm*SMtRYFh~vU=L=O_6tSpEJb$)(ck24)!QYi*} zn$8KkN;q_HTWuE;trvE^!v2jT!%V3K2Al0?ZL`TZaf5%ibL&uVrJtkyBK_!+W_HC2 z#?$z~AF@an>51uqlWHAGB1bo{p`2nFxk1T_EKD-AK@w#58Q3gsn6Gh+Z~OPgJdyY# zu5Sn5SJwyqbYC#|2tm*b*@dEfCF1^IPie1i#j>#}FO7pW1E4l7JD|f;CV{_>0gy%2 z*4}>bMzzE4-^NJl6?+3>AAWOK5aW*OUQePSza^ zUn%K&IKV85>v_E=f>tC!o9Kma7fL{W7RDN{T+!WPYkN0@{%1|1F5vb3 z*24xmX)v;GFi{C-{s+FIHTrYZh`LNW^{lp4>*UUA`LrLGD5=Z#!E-*1S_^;b_Qn>9 zQUiJzD69Y6+^ls|M2Ddhe%?m0ZGX8Vd3?QojV&~br9-T!h;5EJ8jPg9LBpuPX8p&q zHMOjqXMUvi=)4@?GCQr7Q(hr8;+Ijf`4&x4P`vrQY8Q-P zieyMTnpfKDQeH+e%GdN3^7_b8{03}UoJ+LyRb`65PoWY1!evjGe&p9^cj4A{PaNs~ zKf?cA-p~>+=6%53*~>KqVAfZ*OW7BB6Vm&*U%oiK!*ulKWHLD_7 z7C@YVh1KPOwHFEZpQ3QV`M;&^Hjh&mIE}%~`1i9`LzD=nr=qdT?Yin?PSL12!#RRyhWFpJbZizQ zdSP3Is>RPfQw93tgAM5^ZXDs|v@IQ+pH zMbNNhdN2!UDml|A>5>z!*!?%B^m1TcNtQGg!7X0!N+-l$F6lyWt#AdHw%( z3f;5{ZODP=!{WIrXImjTD;E0H-P>cW?Rh6}WwNXsC=i@{&RdKHIpwwlGS+ske!qmn zOp)i47^PjAeMRn^r6?gY4Q(+YngQ}H|bQL*tq*lAjj&D{eIyV1+L0e#>ITW(n%V8I|0 zmOLvOLkf(iYznw*9b?NcC6Jp>d4Bzsf7551Dka$%3kyMLzNY@&kr0zT7@Mbx0M$>7 z{mVAn+~?;vP7ZN1`~zY%1(flc>h6;&9#b(TdX`8P7j$#?c*^&kqr4SpzLg12RZMyC z*NtX}(JR%$(MeJnkB|oY#u&il5&3pKE{I)Mal>076)77nEtzU^gsUd|XltczF=WhT zia~Z?T4kwUtQyP*z`*C_UCxs1#%Rx3}9 zr>@ewy$+_!#G}KeW>BuF3NqxXZEd$;q4^~h2QX(RAAo+@UcAo^sv3Q4#qWLYjb!;u z?X)nZ#WbFKP$th&mk__)Zlje?ep&!LH9HPWT^JL{?88yFrm~~`4g(F`D7%dpZ0n+%@UJ(}l&d;kVmjZ! zi;)Ax&S~NQr!2K1O_fX{{UuNh5$-}@<}*}dooyI48SaK1E;eK z+$>DGx;1s5eT=GodL0uKe%A3h7XT>EhyW z{?m|r?|0KdA|gGWVoRVfqj}X!rn5&E0c@=b zC|O2wFs{BlH&~+RMXN6BohAZAhTmml{#n}ac3Z;$v1XQC_%#@q*Xn^KK7(uFxtp9C zL~vihm(D0mTGR|f{b-$SK+#B2nmN*Er(G?d_z}9#O&W$e`tYbv!FH?1sKe_wazmL3 zwobLIb9z-etkDFq5EYvwGk!|b04Ex_hz=hD!d*ht@`XGx4W(t7q~C^U2;s`hip_di z8Gsfs+-1P(9k7TwD)q!`c2*< z1+Y5pZGKP2*iT!9S~y;Zl!6MGnmpTYkT=XKLSg(!BTO+^8AhI&N^d z6`skwg?EHoifbwBOTwCYci!x6gYnm`0Dy&8zj?@xm8kPzzQy)}{LcoAI(DZ^651?M z!`$WOrBs%uJXv{LOV%@j?Fi;#@043QaBF?=>*ee2Yt-u*%?m1xgn#etIvlNb$ya1U zFs21$Q?@1y!j;@cGCC{mP}miZ`YE-G6oscjE{!B%y8;aE*W;fn;6WXSKjjNjzNJr* zWd#s{HLB1N-XYF~B~=DQ{XCima~a*=+0afk>Tr{p2SoF z0Ui7gwhn~VZZAfphx?(I%193KHCG439(KKm@_&9JcM~*|tTm#;z)7Q2ajtkz+Rn>i zWIV#m)}4+Ww)@Y=SoN0xH%_afPb5II~Mo|PSysk^iNobbmTm9d0ZW(_^1I*sf zO+c`4l>UI#FfykQ4j5tBWEvah7a}BQ{VMO!?rfO31f%pFqn}k4#WrGjR>d3-r-7J{ z9!YuxaGg0Sc|8hl+H~@_^tIv?U-EO|L zo9?Sdt%?bb%{5;8AL>IenF%r1E_Fu0z&?GH&01C7@@5GVPVg1dUl+#OS2r$a#gGlE zsOvWn(s(~q*$QpoAT-(3P%Q<(9IEt{aS>ffL^jEVHrY%+1ti)Ajep+>Z>ngVy}V)z zSn;JH4H))Gw5kLezGyz|_V3LFrKnU}JM}|Z+pdxj&D$?z*r|9t>)PsrS38XV!vlL> zK48P4Vhn>lU@esWr5wAtkJjtvvTdRBz^9L?91bK`t67+C<6%V%(Q$VbCt(A9;=yFg z&~Aqx%Byw`6zj~yCG1vxT0bBnjN{yyOF!PetB4jDE|4V_;7qmpL{Wk?D}Suvi2IE7 z@n!7juivjM>}lRBP7g&XX@~d5rP|t|1+2A3oSJFvkar^la{BNM3C3EuF$~@}_F3@u z!QGB3vK}y6*6%S^G1`KY2i6 zV7h;$L8{j{R0Umfre^L(Cehh=VZ~b)*ByN?#AE%7eTFTb%hfYvQ?I@X*5R+tPWKkvXveC*~;eG0V zi55a#F9K;JOfUC&uVnRy@8DL_ZirA!gh4F-s;^6K2iLq?a9vr;EB{vF8aXn9nsU*K zFY@eJw*x)0IUbQU9V#!y{*)&dm@ynxQZ;1AJM!rQD|itF=a7J;6X_ClF}t>zOjV=( z0g)yXVh2p=ImdxqVqwG1EeOxeCUOr2;>YEZ|?u9`Q;P1m76X*KVoBAo_;6igoQBhDwr>p}uc`Zx%a{e2g;dy7Tquo zlG3W`z*hM^B=-x1X@EtqzJ0dBlqZp8sG0E(JyO=_pfTPE!CVxVE=^=(85V+{d>7Hej$ zmT6-tV^#fLlP&S~Bs}Zq*%1-@(Pa)}G;g)8liGu04lFTWrNwm6GVp2&kQc!*+~2pB zeo{OkB$hMgiOeOtBA8=2+sF0BSa9AywH>=Pv102 zpb$x|7@OBH&ULWkfhuu^t|29l|sTEPYX9%Xpd!v(CL7~ zMG6!5SiX)lwmT>XM=A~j7YlPHzpm}-`>D@5+pf=4#-DgNZZ~pn0hQRdTV2{FY>nbL z4SW!LBO|4S;~I>sWT%%~HxiynlTap6l@^6K9sUJpuHx~>Q(k!r2e|F3`S?v{{;;iCpi8CjG%$ecD;1I_UxI*3bbq8KgJ zJ9DxfQH6gIn-6aB^v^Y(Jbl@C1BsEL{2ja0oHa}RXI3PfT`=bxT$TbXAXWXW7IeJK z7XRM%Q;JC;{d!OW3J`264vNTpoxHCqA|rCh2y-wdk&FE4B1vmu6E@`>vS}S6mD?w0 zlF5j51VSw#y(Hu0;ygQt`Lz4I;-v5IXBeCO(BsMMr+Pd#ze1W2z9O*qa)QN z(wcW50$1V~FL7<8*v92oqyKgJpBd~y<8T_E&zH@4Jw7(6e_TOdMc#Hop+l(vndts# zidB}?RHz%_8YL8AcJ{MpNX381z0Pcy{-eX(o2W9XkQWhH@pH2fs+81Y5Cx?)b8oX; ze6qJh{;aiFOhF3whx}T=oVzbV3`cOA0muTe(BOS8sH<60n+Nb=XR2BLXu`&NYvC7l zR|jZ@$07kw^qJ13D3$5S@kEFNIPn}W(1}GBrXf3rIMW&9Wp*K>(! z)sLgXe#(C&QX~~x$jR9*HF}RuS>^6tsB7tHwdzY)*}AY-(5Eo18_K1EUV|44qv@3E zGy$_;KvW0oS`CR2jWYAS&IvAsK5vdPHiyUwQ=6Xc5kFbPSZd~1y~Sdsz07vP%zftx z)Efq~Zu4UdZt%Rp;cr77pWtSF7lSm(&y?mCs;|HG)7{z@0!}O@@ydjLAxnaPPpR@u z3Y%ndgIL{#FE;_fVpcVuj>)31st?Iy?Wg}xxCbxd@G!C23qqxGw}1ljG;3xTH=;*v zZ^*nF@7Zi2$P%HJvgPwo*hh!}geg7*kpL-UBM}HeY`f>_Wu~502`QfQWiEkTvL|6v zDzC`sQ~UgO{(+)0{LJnN-ydz9&xo|V zdew6P>8lezAtkC_lg<|X;(v!84py!gXP{{YgAJx^v1K$I^So1ywA!@KoN58XK{=71 zEc>8wzl)D45iF^LcZ_@FwHoJTz}wH-`rVI^DeI7bu2GxL5sXS3nW&cfKlG}3@>VyF zt{B!{??`mhNi!zCl$H@h;x8NapLv)msLGT4Y-ddkEeBhQwDM^5tXGQJN!CSt0?0uy zr?L}2x+^!~i@XZ{t>u^-Zan@mLJAf4D^+;%NA)cHbTlez{(=zbYH&Z5%COqf?M~1l zXMfqi`X&V0Zc$m(Mn}`u+j2%-P^>U`Njay7T>6yygbT>D*JU}djGoA+>hR;Ha+sHaOX?571d4r)XV#K%Bp4Ycs<08P!EGAe;^=;?t!l#*UI0CZSW;M+gRWzvvD!qjsdN zfAHQOxtBFJFSQIkV_*Ucn>{^k{!$Oh2)i8?7(1w;hP!5iXAN!bsmvDDzEE7YfpAos zc6f__tRND_j*w9)>RDsk*#-M@_0$E_*2~{0w`?LIE4}`B?3$Fh%8+VNHr#e{z``x*Ol`ba62F?g^MmW|2=PoDt24?iYzT%M&J@3fANmDk6laK>aRTmMe0*P5 zoAj!6Sm#kP%cO0wDpam2fTw~v-mSYwb)vr>^#A6H`0mheaoV!%<)ML|jINZtJU70F zpWH?&lDg)_Q)i()e22g|^?JN^*HN)pQ{}pEW8^aT2g4a+`bB}N9#VpR_MOmwizsUW zpuX^UE4c97UB!s{SGy7bKKIHw}0grxoT!Z(i|T;&x7V;a9u3PISaiz z_DH-mhG>k;Y_b*T_;9~Cu&)RR;7jo&n8do6d*@(XR}c7nlt5K75Ur-GQ59h!ck}a) zh_`*Yul4zrSJGBW!vfJA^ED=|tyERp7o$ib&DZGIO|y(_5D`pVZ-=16n;*D4>c2h5 zxVSKxi(>%b^-4)r>QkH`pqwOy*!f+VcB7@!BeHG?4+#PkF4jwcoqC_Y+865lT*0O+ zs9*Tk2-_}=o!GTmuCvKRr@Wat3d&XLq5fUz84aHt9=k*mVxY(g9xyf*&LzIsA)Tk? zK6@l!{k+k0Cf>vZpO;(&($5vsqdO#VF?JYzU+DU z2Esk_JNJ$z!E1{uP0wo_Q-WK*Rqmh z(IlUJ6bk-jYsj%%SQ<$^pq|Kh#2)czi9KI46I156QD9}xZM^`RrGp06XjSoawtU&B z;Vjh2zDNO0!uim0&kuIlUee!pA*vv!X}qR8m5p6hYA{qlRcnDUR8`AA{`7Zjdomyf zKY@LJA|Akak^!*}Rfl3x;SJE;3%2O0B*7Ks<*ZSn>)pu8LJrVq3EACW14 zx35W1CS(>#_-ZFnfff}fn36{jeGrT8mblIg=bK;L`30(iV7F;n_fO$6exxKKx*`26 zuE9Gq^juH|09cD@C?sHufZg$Jnv=aS)_SOzz>`pSNpnt+NDMB&^}qKIe_F)_m3_d< zL?r?9>+z$iqMt?fiH+5+i9!dafb}^@?DAUhmB@^EcW1t(ZhKJQm^GRZjO`07(kKfo zxZ%u~z4c`Sn0-Jri8-K}*@tzSE~q;35m8D#sQc{mhLh4+ek*i| zk-HG%z#dZ0F9X>eD=6hzSUpP41uxX5t<9UC8tHz_oBBuWw19Yr0(uISh^6LZ^|1NB zgFqh27wiAqFyWmS6H*gM*o1q;Uh*#u+ugzugtu_1YSKPyG^*JDE1QtkG7e?q^>8qx zD$o_t!s7NZ{QVPxHF?5q>AYRa2yxIQdR#26A-&!fmE`nP2w_y0`AMEm%!K0Y>?Q*# zzDMHR{I@_@xHU!iio*XJ5dQA+SM#=~{u_@DVm!eqaA^*^M6gMNd!2yEX4)wr@wVQ! zTN)RCm%yxhO6^@q`B=@8BO)m;)t!RzHP^sDm3ICfR#R*qh7w!iwu1uWjX?}JUb&lh zcPJ+CSi2FfuHNoV1XN)f(MnM@S|IDU{N^+4Bjhg~{cx8te3^thZ$gvEw<0wnUL(+8 zvGB)O=1wDFIB8NAW`o`rPB2U7top4ySFgxnh=h&d*F`<*#`%`)Si1!zM}}yNKkhBT zSK^t;6H@Jp_V;QHBEbO9@mdmABwY@@K^#3$#r#orG5ey=H}nbw5OsW^Omc8A($Ue8 zEJc8dgYiWV>~gA~_CNx$)P=HF{f7Ivpt83c3^lPZZ(CL6$a@cT z&(G^l&pXzbRBj%SpS_v(1bS+mRX7rLQ+RbD27;knH%bxxU}Ti#{AYY`^{_5~BNOGu zr7#r-zlLj{HcQ#*)#noJdZvKYNtW@OJvRo+Mc*5DF>4BsmmS;o`Plijwj4F(tW%EY zByk%ntQa0vZ{0V@P}x`*UJ#|W4xZs<-}R!&GFFaJZ~WIJUm1N0_%1L z?9YaTJIbCP#>5b3Hlp^55!m4kCk`>1#&1-NjevdMeQQ=1RE_=VxFBJsT}vf4Z~;fO4N}r2-JOS!PAR1oq*J=PySqWU zyPx0x&OCSS3@>4b7n}XvYpu^R3UKcv3af`omY>~>k&Tq_F#y=_pBCSdj@ZB)a!1mV zX{7N^`UIv43uyAz#<;;Fx-?RNKxZ8AOxAsaf;$fLQ=OG795;?8FyI1ZIMsmz73{|0 zC{-9ySxl@kXL2BXY!=zMhMh6W$xi%ZY~>ptu32tSo<9Zg`%X%9SV>T&LHFtiMJ~Ht_3K1xLUIQPhiRNMh}#^^*Q1!tRlIUdyl1w zjyNt`7r1AvY(~5&y`b}Bu>=3Tn>t?{{O8>IJBEwaa?IXaAm~>m8+6yst6vF z6QCtXeDOLV^R|8#!9LBnKt9m;t!!6BF1LYamtRK;(U?kdJIRfrpl%-0+S@xn0>S+y zSb(R4IeGw<5a0GJXuQAVM!>J0Z3yQ-Rc_1HOd6NEn=uv*P^R%u$wDV#!e4ps=z&}} z^}ivP-=|%NR}-dJVgWQAl!LxASZ5{`^ERGm0Iw-wm(bty3GZwzpu@LO>NDRYB^=rj z=wcXj^+V~eL(F_@7qVryP!XYK0UhXEsxpG!U*4n&AYN~8 zC6ZY2zkNIzngzD2yccWR{p0~X2M3J*tpY%mFktI0oj>w~cNZcXmf{hi>v@qI{)79u zZSA(qGFK&%tpD2@Nxq@7o#pyGZEM9z;laKG`$;L(nAQDz%R<#*U3>n#vJZ8@#p!hT zQskag1K~r-c^+==*|95Bm@Ji+T#zjiRB}Uf^xo$E+!m=PH<2;dPa_Wxd_+XV|NNhA zB;s=jsn$QNMVidvmzqrN1S(UdCoL?A=x=f68HRAoRZRe=Is+;iVmBFu7vI5;k5Gcd zdEaonoFH81V}<3I3Ac~VqE=5XUiWGE%W(isSqfMm>df&KaMe!mY*_zBi!We-iX%Ix zidi-VF*LMYB!xfO=w?22L9;!NOS&JX zFmHU?M<2Wn)P;2>{I^kN*7dUOL?bXolaYv*Y~pB71>&MAaNfoqBYHgehREARHQHho zD1wWNH!`APk>tem$2`&lFh&GL;AeQQ#M8JO7x>Z1rN6aRWRrXOJg=Yhqme|qyh8}g z8`UtZEw+Y`$M@$Bl{zuxQqKRPTp;kYRckEsgFZzqXyg8*<~MPyvEQQWA00)vx3}2J zE84g$IUwObM1zMU=p=_&RrLS_U^C8caea!-P8{m~degA2b9NKI zp^l&YGv27PsrJ=cXHE?xn@ya#K-XBRq3JH%oEzK>20zRt4-1Kc5$leaj1UGfmd?FV zJiNr*yGp)Pq`iV4<#<2x@Is-#FSO&oeJBl->kAU%ag z!%A$Si;mGpz9GOziEDU?Z}^dI_>ph;qEU#BNS7@~mkFfTm%G#XZ`7_QV#xs;-ZtqR z7l|?_c`PTnA}4XI)6bm-IdFqqf8nhGMKB!R2O77SqPuf5;QlsEffa5|;HjY)VfCHL z=K%%KQ-e6=q=rSSkU^fMV;@BRj$)Yq2%Ckg=ae~)9!g2fsGLwobL+kOB?`Bp(tdRF z`XZ`$h+!a#D17tsKTkFO{dF1Cb;ayj-~T_X#J(1>w7ZGT$dY^d6Wi_9`s^27Jmp1Y z6eOlx1`4c5q~n}hb^J1**5S^~&gv>dF$1oPXNOfxq8qJ}I_KC$|257?X)m@;)p&B! zJ1nWa3nBoYu13w@^wUoZyWNLK_s}_|Rb`CBW58bc`^h#Gz<)VVzdWD#fVp~>csoBX zA2$m364GIuSJq)%l00Ybg%i_#m)~HnU2wdsl)5o^k%uAdH zJ8$=$!=~7aQh<5V|KG#ue?rK>*M*PU#$Td}0g5)2E)=N%DdWf5ycS9jQvIO_BsQ~Ol`{GVgLQcGfowS&9Muk zkyo7uL^WD_dwWNB_t5lo;*q`5MLC%kpCAsRnE1V)mb)ujoFl|#3TXArQTN#(tTmr| zijK_`-iVna8E@5ezK}{-68q?%T>+2!xJQ?Ob+Zw|aj^z4Q$5e%H!R)aw=yVQKfG&{ zvCiq1hl)xX1?CDhicblp zm81x0nPkLbbYnQOMCWQ3j#yAiHIIMDOI8`=Y8K!b zDK>G->wIBaDzPE8&^8sHgPAjFFXGT2;WW_Ou4L1Vku2Kp@Mq^BS5$3#McL~#GRJMu zURL}1Qg?bDgN^P6M)x|NctnFCFG=3hKex<~bi~NTiZ8=kXm2#yV>oAZl=F?Adw}+O zBEI&1T8Zw1(60TMtW$GT5I3*GFPdiwLez6aa)e${>~ZRkK>xdQXP7ds zpg}I~#?>Qj?HZve43gZozHb8DAlmo{LrvnUf-`0+9Y*h=lba%!t@@=I-HKH*qw#o1 z;E2zyU&HN0;85U+q3_6kddL-nU%f-OEJ9a&6v8Cg)Une2DIHe{I&{CQ6Y-9jMpwyA zqgf4IF`t5uOG}&tc%iV)XI0ZP5Jps*^?<1D2OgR7Q1nZ3mbM4aLQdD zD47Kc6NGlpdLx_(gL5grbN9~PpdT&;Gwc>+an~r7H4BBt3PqcPl}|eyl4D2C_HKmE z@&sWMOL-tdLLHNnl)yphTVf*a@v)L|S;Xye%R(-d{-oTa!);z6P zO}XplEu{X5Lyk)|XY8P~(Xb|m&L|Ie523Oe?r*WYe+rZTP5~bWgo2vNP5h3UAAYh` zxU_ykcO5DZ9ERn`v7DIO1esLw=H z_`Ur{WY4bmMsAPd=-+f$+1CEEU)nM+tE1vi`ts%^!9T(KBz82j5H&CO;3g};ahc=jFme&Vmd;I6;)dwarOc$Ymi%PGjgZv zo-wLs3z)K~n8RWA7V@pWYv);Y{Z*5>!_p?63WG`1Hj@uB-YdK`u9d*i-j1*BC%Cq5 z>9&Og3i<}7Z^G}EqK?CecAW6?y zq<0GzS=17yxJhBM4G>7z9}n$v{K67YTPapXTsltC0z?rJZo(1zr?$|;WApY7z>pc~ z@Hfywfr<{I`0ee5K<&1lFxrck=NuHua>DV+wBLtaXrlNr(2bJ_xpy{UGa#F^}AMAP-66i*k3$MZI56a2r?usyTZ7ZvUjo*yfm z{I5aejN+S1oN3|arT+9VG9*nuEQhO;%>~Xc?tYYb#voPFiGM#&cwrf>;v=E(jI;Is z_HsiKi$oC&4;x|WM&uM?o*~OmVCs7bCWz&r4&uWzAlYX8mZjc|B{WX1-|d1qPQesc zLXx3D^TN%G(M(nR*823+IHTzD<#8N2;JJpM;q_=*eZ8Hv&Amn$`FocP#kplpKzyL< z)A|)~#Vr6sTX}CPJkC7wKIM%*We1v7dO7ba5S>xk-LfiwTCfFTa-3cC6TAk^asO#} z@R=&2->w7u@lpyvtA-u_OsfbeT{ZN*pQ*)2k)iv+{SW=>A%7)4+8Rp7jWA$iPld$I z6!Oj9SVuImY+B!rrD*eJVJiBVBG>3Fou)pW3P+f#A=>Pn9W{<)@bJik>axUt zfj8&8BC>3=j>;0+f%(&Wwhlz{s=3Qsmz*BHrV|AkcMsmQU|2!+#IHRl5?zk)NG%cnT85NPmb3gxRYhlNy$*`5aPh|H9kX@dPb42_pwWF{!CqKyVHs z+TLO7zPj{LK@AP;yt!%vN+Dp@yPxsuHScXryclAj= z%=O9;69<3f1U0_hpq$$7X20epa%J5+`^(F?rby4(9_><2&Hwv6t}7O3zB{C z^51DWvQ4^d>31~?N%dLzHe$C?Sr&b==|oeT7gRtDMTdRcfib@JZz2|_mwq`~<+{c_ zZK3eDFYxzP#(a5~t#myiWxsb|^-KBX>1Cq8zf6>ef~+EbQ%9`y)bQ=@pD>|hmbkLH zDVbx_RoyZ!B&(zDS9Yj{j%ahc{p^DU4YaPu_~0?xQS@fLp4GN5z`J=RbrS6+V z%ehr{Y6r6u&D^D0hZnbbM6YdV?=iT%d@~&!Q6(4i4S`(R$VhK^VtcT>FQlcu8RF%- z50eCZ*#iTZf~}_xVPJ<{7rJg4S3Y9tRXWbsbl(zp8rAu*qHt9-Gp?SU<&S+}l60bAPfB8gT&?gzt4qMgSN9m`L zF)%RC4}o0iBT#tf>pP-ro>Hk>Mv!yfA_lcpsgePyr^fM%s-44;5SRpt=rm+ z4cy_`9)S^1ZtD92&s%Tx<-I=b@8}$&ay|UxmZpL4@S2;kArg_vU&Bw&PuYezv&b)1 zezEY2n~NCo(kEdO`?K2m!e-^_j|lbp%)}H~*1=JI2fZRw+*Tb@t#nfbNDl81d_)X@ z3{l0rJ9f22{_s&Xw`_RE^UR$g5SN`3P zhI3uF)rkt~aNlY4$osU@lI@Er~MB55~0Bs^Tj;VP&wL#9M#l_Yp_Jmp;QG3@7$;LCEBkz{#!A}Iz!B4PP)tuJd z@`4e3gF}5L9@t7oJQ)h;2BqR&o$B$Aj zZm6TxhmiJHV&9D8%_KDq-ejTbK68}~{hc&xGa2#1E^cSl=EYu9D!Awfy-zH6z1*Wf zIfCQmCBo}rg@5qdMZjY=2LoW1P7Mex`54_xm=YL9&+~O_lPONRDwNjfvR4aO|Db$f8Q34fa!Wf8F>T z^)D7*=5HcOM-crW5^M>=@}Ht%ls2n)q9_fpWSP?UZ$q4*R;ad+%h<3)l55!N5#&gP!+_{h^>rwnIiACJ#iVoEQj190`(jeuf<%oGOwrDqMH?-FTc2D@PkZjssLt9oZgAEkN zU_!Ps2eDG#d1*Z8uFwYD{_Y(iMi|83DcZsR1>K;{H)3^_6fI1WyIkgTa%sXA(Wb?i zUb|uh=i_Z_)%e{ulV_vO8n4oxx1QrLs3}*c;e=Fo>DE8}-SofeRc;D%=)easXtvrh zINv^QrLxZ0W`)?}=Il$J`B9s?*PnEmry}UPz2sqsUWUdylMMYWco@YK?W;m-m85T; zVitmifDhKZ_x8dTAikOv&`oDD0^v{Kt=MTMB%ZR{qLNUGl@N`-(s%fNA$$-SjJY7! zL^;P`R+d9#u4ByG{GXaD;xE(-G^AVb@c}ay=+J=tS8Hp+L1IL~i?dj+5z1oT?C&+E z8z$A$(HWUZQaW#Ari0hY6h?soA8vnFfNp)H7l4?|kFpSPC#$dF@Lgp5*Rs7Xxjss< z(+^CeMEEs+?V@#VdCz0q0+V9-1wXig5ujr%^w~mCkMTQA@?BCPlStc$U02k{WYnQg zQ&qeru&nn@ljzcLtPB->UxSVZ&imjHVV|iC>;I@YnpfK`q1oOJD)5c{C6ySaq+F}AA--9|_THknwoyAZp7JZ&Q&pAqaq{gTP$-I_{YZYl zd~3SLP%4aHD=xpsmHrJSu$8I0?-%r3hNl5?TBb8&frCVps-37|o&XA?sdIV{LHkQs zKulu3N-^qud`fD>O%kcKo=-Y0MTRdOxa<6_xO5>5f(L($)7ssHk+7f~s3?Dw|_7K#4^a;(O+;IUGgBo8hJ1x#brR9| zeyq~vo!r~ke>2 zG{YaAM7HSW9AgN)gLPByj(XHaDs@^2n%G*9IqDRIti!}eT9UY@@Kv6*_2+1tz7wjj zH!GEZAtB@rRUskUKJ2wwAs}m(Q;_(v-y^dVz029_6Swi;>9rl0hV+e78z-<&T|r3+ zCf!IUNm~hMxk=?QDI21|Zn;P}1YJMlk6?-Ebh*uGmg@p>eC3M6gZw;Xpv-1%usr$IZFiyPhc{QjSL#MQS2R5#x# zsU&ND0wr1u&X>j%n7%nKqv-7Z60Vvfe<~}dv)^H-Z_7EaIhS8$0gWNBK&nOYasR{j z`{?UvJ)r_-ks!~l<#unrTHJEksbJi(u%frN+q3E z%<&*o?t-iN!`eJ!NaG$Mu*9-FwGrV*?9b$Fzl16Lw({ghrL!|oAyO|C3Cy}1?whL` z!fpa;_h~aHR#%Tt>(VEKk>25_c*F0PyFT??aIYw@3Na()*cI7r^@jWFaB0t2=BVFmQr9%1vF#NfxunP8SBvqCMIhe1{8f>Vv$ ztEXoQ^+)IK!t2VbOoFgfJ7HtH=sICzKoU%Yn7t z#ZBU$le;h(+oho^Kl;j?6G)!Suiz)SLt5gBva3e3eIpEin_@^s{k)>+w~K)ZGipPE zwak!J<#cSQu8v~)q;oVjdrlSLVDW(k4^`uR@HexCBE)Tz?*a5<_!*YrMRfU`ay$F( zOzCJvB%kJ}SIz8)kLucHEXXR?H3(MqOd-whHdMIXYlR~w6MH@Jf!)ao)?`B^hrlgb z+GHzmeb9l5pK%(LPI@9s*glycef)yw+rs0C<_pyysq%3P-Hz@1h3G?CH+6@ zNG4|+Q~w-e`{REzsFuz%M535?_P5G&iy(*eUC3yBzLGJqB$1dk@(`B2-3%*qD(s+y z>p>wQN(y6l^uGtq2lCy@cR)-PnkU(>C^MfNGadD{hyQWfrv3WpQu>`_aTC>yU8zz@ zjU_YK1D)$EJ`~Dwp7Bi#snU`mkQ!AP8H6@ajr+d6rOR2Q8^XzOMMB<@R*bbaSywqn z#fcY+1pP)I6#~r=ik-JnSa0jyxu(7?0TtN}Fgeh0$mxlhvS@l?JRcIbtP6HD!_4Sl zIE>`ybAwzm>=~j~EpcmOk>_xtAzUWJnL^4FjfwBoafP&y<)+|){@16c=KISM_VdFi zcFr|^=ptz@Wj2EJnQyD|DPgvJfRt=U z+A@vDjyXVr{dU{xhfH{#gzl$|igPk+|;@HhL;)`NFGu&|M>0)9c0MDQ7sk z|KGtR1i7maN|wt$f(B5+yT_{ibxA^kl_Rxmv4j1qy(>@e6ATCAIgXpoLte`q8HCR# zV|z&e2bbyVBEMDjR#4-Ynl*?x1B=nhnQE=+z5 zY9_%ydKiq!S%@zZq~(UixKX!@Ka7Q(VjK*Vnjtw3xZ4yWz7x3EDG}?V7p{J{Won>YA>xaw}TCi z^^>dU_RXlR)bE(w!Mi)ga^~3-)AI?Q(m=H+dNciz!chHY$UpAWPwmQfEB34_bga2- zW?o%oX&lDg7bxua1Qavl#fRQoG&?%6la}FwX3-a((SSc*=<8Dg>v$zE%7k_GgJ+NO zq2aN$Q)}HujmzQ84j3OFzX8$?T;0V~-<^we&;eCN|8-!Hi;~4GL={0pb<(KFcR2cf zJC!baeaJR#)H7iv`aT96gnPWk2)Z|6yt1f=xh7T2h{Kv-HV<1X>g|EilfDNV7T!|( z@LF8_`(K_1hTG>rBp}fgY0lBt6=64$)6&t1MP?W0)$3(lV7Nai!L`CRL_hXmx&1M! z%Y195b5&4nVrnqq^8k(>EV;c8!j~im8q$aHA4qY}&qMw`wsZRJv5g8SuPZ6&M7&cE zXdT9)z)ruu=;!gKOH2T<4J=Zu+t_Q2HYun}G)#%IBV=f6r^U+!)5)vMqeuRJ7e-`a z4HurS`SO+0cLqYnPPM^cZkxMaJ}**aOS7p(RaMLAWue@=94I*pG27q>#KfRH$JU*- zFbOp!+le6w(-rE_;#nSW2l&_>^6=o^Us6DtELMi<4L%%4&~d*;wLs-J?O@J^zq$!` zbI-;jK<-@RFJ{qWOV_;`WE;{l+!n(6nBL*B!=EQoY8hg#Gxox}NuAFEVE-s9V}w^# zI8?%zPFlF2;~eNgVft*90d8%uB$wDa!BSa2;|eS>lq(6&Hdf43)7wfG^Lg!MbFpD^ z%56&LnctZQHWh6KA@cLG))=yILVTh+z265)*5NM9Lbw^?3^rWfkX#bPg*?7Gs`hX8 z@i;xxab|Y?4Sfpb0sogUj|^goglXtR3J#WBIKZ%oq6J3wMl}_PILM}OIu^bIC;q$S zDKY$JO!_4J8RGG5y2g<@AD29o4MvfIn`6K)SXJHV?GmjUsGYpkLRHZF7DCKFW`l;k z0heMGc@u@-;Prq*o-e4q0|&wRGBWwa9R}NBfJ0@VWtbNgJ(|o|SuKz7isK4H&|MW! zU-wF_e(dqnO(VOz=R>?MK!*MRs1OrF90)bzF7$04dc1`{_MaI?#LK^-Z`@&H`)(Vx z%386?G(Ro8Z8490N2~QH)VI0(xaYs}e2L%RUA}=eNR#8Vy~5tHnayNJto>TLkH1kV zIX=+q(zHb#?#X*&dB_GOlg{SYJXU}6J2~6?^W^CrZqr>B`j})v?PpKysQvj%V0Saa z0EW=7(X52dv~c>6PQ;nd5kUJgaH|>K4LaF`#xKJEOc=Dj2Gjrf{_RvfeDT<7d?o+( z!Or&+aa2xrXp=Vk(8!0Gynay<2|bneaZ+VQ>`78kBuui zH)%W=S1ht31i&%?Fr2P})ZJ5B_e^VxS%DKdaO8?+Z@ULMthMw_ZvI-(`2f1F%ulN(l6dDb69^a=iBDep6;KmJ$6+ebEI}w z{HH)HBN4%6TRZVjiSeSL)a_Nr`j?zC<>gC^>%ibTjHk2dXKNn;eod{<$s~)W9{?C| zxF#jJOQu5qk5dJXOa+dgN*q69Y33dj!oV+Qc0^QZdPe?(-VNe)mF&R|PN<1nX zh~|&+JplCEzqm*UaL5<)q(&bAqdrL}HCh<(0fz>bG%JGe5bi)BwoYpR^TMQ7&!pAh zic@OOC_M8Dc%&-O;i83=zF(Y+i+h>TCBBlE@|9xkTal?5q^82$l2DGGa1r$ra+EW< zDoV%yQ(R0XR>-S}jx7UtmUS>}(3dA&S@1RBG!qk2;@|2YLIvuWt^lEqxqW6!L2SGJ z1;e*R`=4CZo8_GORTNJ~({n|dtDT0D0L;YGB}QX=re}2^eikgvEB^2Nm9nNYHN&R{ zztDA`_3HYfxAHorJWTb{SKe3<3QkiCcF=in8g4xI;w_ozIMgp4Bf!B+H8G0cCNU0Q z-pq=2sXxNpp(k1#dB;aqIJD4dAAUrwgR{>1EaJ8`J#|STv?E>OFe04{mW0kK6i7Q= zn2qo*n(fnK`CPi8y@?(g>NxT;V&*BJ1F-NcYhpl?7n~r}5iq=-e9t_*?J2y=@;9s}b zH%}~st~v=^_<5vZecz>_MFa3_7u;Hh0r9{QJToP=EJ?=7qK=Xw4;xk>Z@a>+@EyL} zmx4~7ivSBO=u@aHx^)~kt$vp)|K&wbW^0}fL~Q~JTf+35dww>hA=(w;)z$d#vK8UOYAw6s3{ z>F(khYyNU3H{ib~*UDF5>F_epz=Ii3%E)tg=Q^?4p5N)+DAQ=rt;I9oLt`==3R)IO zNRCjDSx%XKUVDE&AhfQynshxxcc$iHe2F_LX|?W=4O7(Ke9*Rc5&m?Ss6gU#bC2b= z?p5+W1e2G|)r5hf(>cHO_4;+vZ;P|T_>GWG0@wo_V*|T8jlz$P2kWt!%$i@OKO(>3a9Ca0os*<>HoZ}&O8tWAF8 zCLX^q`H^eSHt=*{pUaDGm$>|kd9OK&6#?}NI*S2R;Ot)e?-2~sZ`g_P^}3FS$clvZ zI7Ve3p@L5av1D4w3i-POo;oSm40;vw7f4(H;qq9)Oo+@B@U(IhT{^WSkzaYt3?A z`2oqEle8O@chk!!HG>|`(pwCW)mE~eK4YQcQiJ4(_?L7{55!>JE`otPLc7>UYTO$!}uTIit~hKG4KdLcM03m&W1tgcC{d>YKB*OM-Y2vQ^Mon|Dsd4w7 zB`xC&P;9JWyPa@Gn`FL1>E^Z~8}3*;)X>-$F}u!%`EaagSV7rFF@LvM$w|o0Z^vzT zt8Bm^wtH0JcpAtw44WRl9jTccpZ8qVCUACbaO{Fg@$v6qj#N*q>OJCkL|7-aK3kPX zYZ35d`h{IU3B+O2a&cGC=mFYtsX6;i?xsp#Jhsd>C9oUhPa~J|SX$SG*_M5iXBqe_ zV+h*F(W830hr7H%F$MbOuii^-Pv}H_VbutL)`b6kZOHAR`V1o!1@C)+eM?X)1yt<rb#%lT!Eap;k9U=mzI-JDF{BwV)~EU)Bv;et2jgN4@DjXmXyM5M%7 zs@ZUV>Y<&PZ9LC2`Og8#S3@*~$uqB9+}SgFvf>p~BGzC{VnY^5h`lKwW}E0tT)k>a zzjW(1ox?&^!&ZFYQy6y}-F2xlZXrU|rG8Lott zvi}<9iQnuB3icY6x%gLpT-#l;DgVwI$X2HLu771$qf?P-gLB{Y;^o6|hPm3F?F#!? z!`*bY!VsmmFfwg{b|s5I!o{FnJ`X$}KdGT1!s+Sj8#iiGjk_G5k#EcnBCoZGbPlJo zSGBjtu_(fjtDwT{64iR;<6htDhs5@`Vf6MI&4?V&+SFs*Jf%G8cc_TEiO<9g-?Tmm z8tj#j1pQOQ4}UhmS={ao3{%p0V8{ZolgyMGFMu`}868pN?|4_soWhm7p3abd+sz|z zXIhHmN!w&sGDKRYh}WXTa85p5oSxdx^bwqz(Hm zrs}K{4rNh{|H{87`jr*<)e`6qN5o>kx^)0`(m=r3OgmST=P0S66y&`w-z8gLei@X4 zG${pMUOAMV-*YJVwPBDNM8a9m3*ep4w~|-*!xU;5^snB&p0%gh4kmDmpR0EaP@ekh zNSR5QoAZvHa5pp8`d3EoE|q4h<%WM?hV2ybL@5Jv++BduF%p;fiHfOO zaHe9_B^H|?TmsftMM7P?LiYyzn+_%sEXa5e*jV-y_gYt_B;{O*`Y38P0SgXc=uA-i z2#+_Dgt=5;^ zmsQBkb9<1(qS5UtUsLOw`{a;+VBn^$b8|-mGNSmR&*!}^K(2Etz6>W3!?%aU4GnjB z?->5P6h*W3H@n$;#mBcte=mx^8gW3KX`37tNc*c%F}MpN}|%gOWkpGXIG) z#hVMO2ZKN^(eD7oyjsSQho5`gdaBgOSm8MAPfn_Ce24rc2D=Ob#`;So3`Szm?Qu#_ z_bh5i`!oK%s?b0Gs2yQAEwdPov@Zn%LQ4%v@z{%6!RySiO#{BdmT=^Kp8_7`;j zr`d}0x^Dn>Hea4X~Xlfj&qce*$Cz8*3)YXbM87TN5?`s_G1xBa);0XoHp zdD%MOrn9fR)P??MskzFEC+gWx2aB1BcsSw8HS*%=U&~5SfZjUdgvBP`0K&uPE{)wU#yX zq&`nhUzQ!kdc~p7r0!?(vtXC>22{-U)PEQE7{TK>fb@+~&8Kjs$saY-H(U8@9@a!% zR+_ec7~s<1U=L6X_%=W9b3atS$jx<`S9oQM9cbnTl@O}f9cgK3k#(4fb6#&fQX84h zXuX;=b&IoRCQ`N-ZGT2-&h{XrogJf~&>|@#*0x+%H<=mYsia0JUEYBxw=s8Iw{Uj%UmYUA-gNTw%Y1Rw5l+4S+;PD6mX@wT zaqwXWf7+T`^xJyCTX0h#1nbN~<@kmj1Y{S)-+eg`+ z9x&_!+6m+~va6(m!)Pv-jl_afCc>n&zM8`Wpg24nX-*!vnZ3% zPVLF@0~Z_nFlCp}Vs>&jw0rsh{*3kx6;_e_Y;Z|$9{w!fO6~QSi{PuD)62-^#7f#z zFgy=p8MM3fBF~ZlbFFDXVm>r;mTO&aKO` zIw|gM)IW2M@JI~d15G`egDJZD_Qdus#OUhQ$9DY%T44c_=D4j&amMIB!j}uUskqP- z3ayiU_pec9ilOhZyk)V&Y2eWbc3n|Wl}{@At8}3vU65V$zOrnK_YcuDeWkw|Yi+RIF{( zzi58>BgJh0C02QjFC5#lD_R)jf3rzi7w}|w?%dGL7VXGLNn0+NamqEqxLIz+@pfpl z@?Vda@>42=ml(4DL-V4d_Pw~cGg?0tx(pZy;@|i2S}X*7W05xa`|t^zH@oL%_K@g; zwVs0wtJYx=5OZoBSMC;W-1XG{BG|M3iV2abQ8_ViQu)FTp}B`4=`p?gC+K@s@kVq; z9Cu~gCR6m2F%AFUcpt``)pFg6*|7i(2h-!TXhG4X%YM;az_A-8SKGT!qOAP5a@mg0 zLj2G2gO}}0nj-b~zoM=QlU3T^rVoCp&9rB`_=1H?ev1U#ZummyQio`cf71B=bFqAB zyL<;z=0tb9mi_KdJpk z*puD0c3LXK*J^=iHMfP;6ZpoU4JCLy3i_=t#L197K;iEpe_Wa+= zku52=ux5A?lq1SLTIG9N6W5~A!$%eexd^3o)95D4oZDr;PAk;CSgk0-njin6D@;nMLul7}=6Kxx*G~Q)_iV`%o zaPz1Ls45cjw%j^2S4LDMQweq26b@4wUVq-WetGlXKQOyNO9v401M=WA*IJ6nuHwc~ zzLs7M8(4Pl{n>YSf@t7DDdZx)9RP;*eVVlBvXx3Ffw|het(cuwBAX%oXX$ zkX3*u&A0mPz9VKgh&AJpoXe=U?zV6%%K;6r-)%8%T76)db`%1Otrq0+4=H<+ zy0Nm>na(=LGcMnb>9wYp&r7HAC1G160#-XVnJG7|NgS)&Y-r`h6__i`e9*>YoKpvTEAX2SCiKD1RkrYDBi!EaHqKM7b7C{{0>6- zXR3;kc+%*3Bd0%wH|O!ry0DdCe4+ITb{W{Z(hov3pEzb{W1%Ph4c>wG?62?rq1~!P z;EoC67_D6CwOJZ#!&JsUBOaO+a_-6rPisEmE|%O76hD$zGQ(_<9BHXUu^f6@fBX&4 z7tlrenWOgukptfsF{p<0hm2m!OKf@;3vy}gr?J-t1UfYe1_X`T6}4EeyY57!-{0s zQWxRn-Ji%Wyjyxt$=?F*4>8|Dj;zFpVG%J?N#L=`U>z~0t{Ya5DFd$FI##vTH}wO) zi7TYXr+tIL0$pa%{u$sLXQoJFk;@Eru(Zw?Ni#{~41;pW-Zo1my1tJVcvBTo(|3}$ z&3*@phaR1fHJ@NSrB)=op3Am8DZgO@fABs+C{d|WtqjK@*QF=OAu_3ec3eBCd2 zf}2313o?quqgrRMJJYk|>+8KY^u(uTMCjI&hpKN2)&@%7OnO|$pPi`E0_gW1iP1-ZodXCioZ-PvgMyrM!vXT zd;HS~Mo5!g$a})}W;#>W56H0Hdh;ZT^3dCFk23r_re4moA-)msRk&Q4?>+e?b9B8F z9=^>|COuHn(YW}k8G-XFa`!_t7TkO-qj6Rtry1^JmyOW=^2dOpb>0LJ16T9=IKu^q z_PK*!c{%=h3JB|xtgRoU8BU(TAe4T`T|3J#CiQI zg=pDf30r{~h1iwGXN7X+PfZ{DM{?CaB2k)TSs+Z#n0XL53Xy#f`${)tK>B0)`3^-( zOKZWFcc1$_EKrOmPG{{SnODq>0Td02I^mQjv;72g%-)^|`reDhNPxa!=+E20ytl?% zdTJaf!8^_I+T~V+U`ira;_hdU+c?IKhKgX=oL^YC_xjg&Yrb&s#z@)_u@|q3mq~W; zi*J+qnl63(vm&q9QD~)A|K;URMgUs^`@5RLL!Qt1|GJ3r&nksx@8+$jY)HIa_51w` zpzge|di7P8g&ulBMB_LN*FWbEdw()`UaOF?2(#%DdpdL<(#fRWT<^i zYhQ67vCPOK~ag?(R^eSb?I!-7Ur4FTelY+}%t*HJCEZL>lF<_pw)#jH zLb|4dDhDC&2DKf)7^$v)P@yD=up?(+@$b_JHtHN4;w)USUsAug!Oid<#<(MsPEncW zz(PeHP3G7$;DS?}IH3E*h zlll9BJsHZ!TLB4YFBF$Pf`g@D)=G3}1vtZd_ooOu_3xkFGtl_)PEoQbhHZOC5LXaX zbtm8Lp7wHA54azC@+@$vc^Qj@C@yzLw|4HHVEu|b;!3xLm6S#Q)noO&VMKxn9yit)oPqZ0OXmO*jXGYtX zXGY)3#{H1jD(u~3iT~OV%1SM$^Ic9=Mmw^mhP>8s7zII^g2reuyf}6uGcHGItsyYg zs8>P}x%nAc`6f2SX=Yu&I$@AN_ntOobOqBLcI*BT0k^L2gCgS>+0<}X3sg)LWF(J(Q*|@Ppw_UmQnF9VDS4nY``Pi2T}Xh2RWO*1jya_ zQqDQ*H>EjpKPm1UznI~=@dw*G3M{FN4Uw2-9(J>9c)UUu*~KrtkkmLsSfURCc#J;o zx4*zDx)Fw%>6|rDgXh?<4YHy%(W2|lO7b-PF{q-P?r&MB+yKa(wsXwx%3DblOFR6 zNOyhQwH_AP$`k*g7i8yhVEz1;_K2#h9g4koy!`POGrmY3c{LUG;lk#Z?RfT95tN|M zdU;=u!l!kgRrb%^>P3|o%-^x~diEqf3|{91jdCi^JJ3key4lozsn$;&I^9RWkTT7D z5*TZiR(m5qQ^JBex*=ke;a5ec9|^*P5pT(i?{g3re=mvViV+jWR3A%$whvd)_DBQE z5ir@B4j*X&svXRalArggFLZAPo*yI*kzPm$F7c6d$@a593cq%L5x3}v)!b|iU>K`Y zXpPd<@J~o;rMuCF`mNVI6YoL_oeS_HhTA_qWkTd#xp-Ky%7>0fBd9bVqBE?{Z}iJi zX1G&(#Q3iU1Tv3Y0C`v;ndrDR>lK*QZ4Qkme8fBLV;E~1C5K~Aej_LDBhFGw!#^%we=p*V9Jw}O2ZjA<@B9TWc5Cl~Xb;8Fwk!(%5a)><*WFGc^KddR0p zU8MH&+u(7uU`clfkuqSlPGbpwW?nv_yunX4R$)6atH!oUA38EAmy#CCFc@VQMip-Sd*BWZk&~wr}^SP0A*Ah?&DZ^e} z^FpKCA(gqn%CTJ(NSO8Y>j(&bV*8-$Rlz`9q6T7C^t8Y}+dOfg%U9eVztMx<%{iI0 zsW$HH>57EO8eXm*mh&-khUp{aNo9`MN21K&&K>Kvd*68CwfP`y8y1Xd0VcpY;7CBQT&p+>EWGu(}$Y*1-9svvk<0_oBrrqJfH_k!cBj@_tl zNF1&l_Z@6_o?w$bl^SgUqB)_fB>Y*yy=_ zL+U?J6&e;K6CklYBXVP2#Y`>5P*b#>A4LDRESDPt7GsnKV-$Ae25BfthE#8>fCGd) z8||eWNpHfa@<`5*2K*Vg$0BTS^rmrKSU#Su@QWXcyojFJ)-WXqk6L*Yck`ETj0s`G zievK#dW!ckOG)|l`~2PL*!BN|Re}Nrkh$e7%H^Cv4u=8chZ^0(=JcP5NW*$?Q?O z%?q5t3_FfHG|E{3eZ@+RbYe(n=aXP@mN|^$DU2aCz3!9N<3>ip)$Us8t#rLRYkIS7GYj6I2Ik0$T>J zA=!l_4f#!f9Y&vZFSB9z!U_I>u;S~fVYXV_KVMXwn7+wKy-nJT{#gz9eWV*0B!)+L zsI$b2o+$N3k?dp_tu@#1gYr@R6ebA9gmI-VcQMKK_~+K@wQZWs3B#L|@?L;wugZdl zLw9-f(`V>p#rOHu5SSxttX#v`fotE{W%bszoneK=$XuJTb1(Ebil9qlW3%y zTn6lh-M@P4DrRCAZLKrYZ5o~w^vmKl6KM1^H z5lYrDGcXakr*>xCI~;sTv+zgD1{}HvB0Xc;m+Cn_o{hF6_nq%qwgCmuNwNRPNUM+Y zlV7Lp_EGmRVR6Ael*+mFBrl>jVCUSd>!C+{@d?4UHFlPm+yz@W%Yf7 zF99(W#WM$^+!jlWjn}Zc*JAPMsqB-`&|)+gxi`ykuv3sSi_yro(asZ>e{KBj-_bTO zA}8^Ws_nvzK2Tq;PU#$ZR8u>#D<>w~>_20&Ic_p88|jij@ifC^d z#=pJJ&Ckn%p%f|!+Fs`Eu+!_=I>Y|BuE+XV=o_J^uXq0EBelfI+3L8v53CxKYFJaF zcOi{utkkU!iCkm|>ygYX1y}$yZ!)eq=h1S^m?z^&E;?rk32*;BA1K^T?F7E=L8{=^ z+L4qJ#(4PK$S@3I%(nKHFW5av6b&LJ+k*q25MG=DL%poAdj{Ea7e+Y@#;l=RjsK== zcu^|9G~|A(hJ3pxzxbR!XXSNm;rAw}8Nz*NnkQdD>lx{> z(dM7ZV~N}dn3oAYc?EowLSNwsXHHnn&{*iOd`p5I@4iVYr-D2zNTp>q4Qpq|UG#$>ycyCEx5oPft2U&Xzk5!g6Z&kP=e$Kw!uLw zPIfe>0pAhh3$iI$*w;0eMxC))(S@EWlY-zgPgHEy9Fn_V=G*#jbEYIOq(}Dn=&n?pm`V@s0I# zbWzDGfUr<6jsDt!#vpDSB+xKVuvEyGzjkzH-zu`@b-!|3iRP+62-UwPmLHBp$XyqF z+<~pe@TitEyN_j$ZA6&gdsA>Jfpy+B6Oa5R}}lw#{pe7HLoV zG*@7nY#KDwf$vxEmwOiVughm`aQ{9j_M4Kc)w^g7k9tmHdsnDA%&2p!XhTyHxxZJ)UvbU~Q+}AyV9e_Xw>lTB)*- zw8TRL%KE~7(C~OvKo8C*yEu)P&mvgycXVu&vDVYSP-7Z&L;0ZvcNs3fetL|@_tQ`B z4Zf9r;!h^m9cp}Ja{WtD-U6hJ`O3=(&nB^DKbh^h_>C{o4>vF_{6i@ykD^zSocL<-F%WMR+6daWk*w=)Z7+bA z9uL7zmmjZuA2{9MFC~x#nBxN^T5v!uKiNQiV0n!d9Td}FhG^I~l2AGDap(0B1_JE5 zcMZQhI9;7@_@WIGxv3Heec2H&b+BW5f)H!mUt^U2t67_tL@m5QK70PJam^WN9Z_NY zWhrGQ@_0-?fczl1G3OEDYo;qv4H|SIybSz^{D9(%UFJ`?P3kY)VC=vor3Ya0r=D`1 z;4LF)8{*J1AdOG!n6pSkqo!xs>JuAI+ zN*+H+8H|pz@US&~9OMJE>6{Kc%f40Mvaw-AVQ0Wb>>)b^zC!d=5$9b(n6f{)li;QL zOE$>#+gU?!+ZMPwmFxAfQnJhJEb}nxP??x_;4JB@+B4Bp#!vUSp9hHwIa?3XkldT_BOVVmC5-&B<50<>=t>@0%*=qejVwN#bx3nF)^(^UpswH#t)qWTVR> z&>}-C&;OMYXJpmPb;Tl$j>drO#dE;j!KTb6JC=*2iJ+Jq)pXE! z7E|p^fnK;c51Ji%PlZ?^5>2LSu;OJ+ypKLb`erT~dzY9eOPJV)iX?Iwr&6p46AH6l zcQ&B;!lDpOMq5#TdzPqsG3z?zv-Pqy6dtQ;sWo3g4a~n^JyX*1TOK{kP7H|BSu`eRW;V8v%VB_t3 zLRGi`VUBos+*y(md%kGM9oYsr~9CLw17gqm41ZV+7 z&j9eZ0lE@l30B-LAxPW9g-Q6EHh3F^&LlLBlKoLZjM61o5Q6}t&UTW|tEy4y;mtyq zhPiIfgEd|MFm$fhj*05=7z2v5h6G8XofN59%3#^rX zG3`P7`a{cPjb|l?0?>Ad-uy+mQd}%l8Am^3CKA^(!^Ih0M5-;?O_@*8r!5kpD4L^C za-Ry?ksLdhGK0RNi!X>@5rdz`^ar%N6C+Y1L_QPDd|&t$I@1Xl-KBS%)tof$*^4k> zq*$VIHVxM$_qIRBRKTf`m!?h*#^pDI2ll1uA5!V|+-r~L|h1X%HfH?4o7T8 zP;ngZrd6*N$5vA*i31`(0}j{U%{4JU=S$^ZbqGHb$-mmn9Jvo4B_5YtKoDG4OQK(@ zd-9b)OTd=v+i6cdQp~gZ%uYRNi>|<&+ugy|l z)DK(;nGh=}o3mDg>_o6%^mY7?!a10Xhq>31VVpb@lq$IVi%8pEH_I)AzW4syKtNeF z$@23gH0GP;l2Qt+Unu;DAz;H7SF&~Ji+p}~?$Oi>M-YiS{WAME;iUXB3YZ5S6o9<2 zzVbKR?#9YDFgGtaUR5>Wb(7t-i8bvxemc9Xh{ZhDHc(Ea11gI6L{K_poSxbNTLvr0 zjt^hgBJD|7<0%`c?*A&lK%|3Ptpfimmp@7x&v2$GH(y~tdk%y8bg9j;__efWu#SXc zsmFc^jd{zyt*5MCZRrlq7XLygE@t83@0woZnBP^_iK%3uKJ~nwd_%7FnS557d=Nlc z>uuhyMTK6xAW*%z84LMeb9|bI{&;^EBeVvRV3fCpmiB8CJBT@8io2zxm?v`Ehmo>jf;->TE72rLZ_TxZsV2?6Zs>>r#D~KZ>;vB z>_IGx&hnWuaji~{hlKZ!(>(cJcMWZ+a_!c#Q<~ZZ2#_~zC06XwT(7B8vpRbExg-o& z#^}G+CQxcE{GD=9M zZ1S6kYl_iSePy0MQU+LJbL`b_(_u37kWC@7_Ehu$gzKDzBCi~$n_!34xeIL1}I8{2u>?`}B3xuKUtBuLg4& zq4uc+tq&^FDB_*y+C1b57vuG{^X6?dq8Pt?>K6U@HsWZB!faG%4D#o2KV!FV`GpAsI0v8d??cXbi zP+2}nDd!LT3Yp0D^=TReb>>y|F2seEdLs4=#4`pG0jtVYpxnNjldv6tF(Kj*FoHnY zG`lRA)^P}%ecshN%i~3%b}W}6@yT@z1mDyw_=yP@T`4IArhmYKMRH7BHR#HFXiYRA zLG=AU_Z((m|J6CZ$u7)Rbbri*xSHu#>lgC+ULV+Uy$C_jpQlbK%!7^NN-*tMq!RPj z6Yxd4%~kwQ(!f{wb%lJfAJV~oS}>XET2?phg2>r~qnduWiw-{dI1x9<9Ex!0%|`E1 zxMK3o0#HBRrVP+k69w4fOY~;!{L^_^QRn9{p48v*8vmrh;pWirP`{NxJ@{Dj4TGc3;XkDXW zMoa>hxsdXVTZu5jq_7Yvs5dSPA&ym!kZ>5k2AxJzkJbVf%mg*>%M#AwW#w{_^*Ln=U6ZqxpjLDVk3|{EIj^i)S}U~$KlT=l^W8+-8;1Yy$IrIV z>rArrAjm0t+nND9DgCX#ic$?zcSz(BUytQ#b5}jpla@yB=#2;6L0h?(xR{X<|6dsW?p$z5MaUXC-A+ic*c%=}UjgwJ9C&_a3O1oAsZKn=uu4qiiy5Up zUFH!lbk`R&lOr-L1gWdKFlr~HxG8OcjWz5^cr{`YKGgZStueF~cRE=N)qng{7 z6M!bw%^W?`%L-piKL2doS?SMIVVk=;{qmcR<`8aM-j*Sh=#dIs~5S!R&+#1pg!9~5$M)6ThgZ}Y=;jxUE+?p>A={4A5W(qKAwTib)oI&XdX8CW7ea3Y*$PD^3R>Xm^d8$Rh5g z=sV&*A$A$j4Y2>|J_r;k6m|oZ39BD#?ar`XR@v3N^I-q4xGxsnO-Z|{eHU}0&sq;z zFcXH~16v_pkPJpu_H3JX*=x zz4y~0&vsZDm+5;Cd0Dyl%NSUYgL!YJiSA$B=<%!<68M-(?*ZuuPDvrIv5RG;1Kj-$ zOShY4wQ)Ztg*Mw~j={Qx%vC{;qG;qtspPf=ARp^D+=W;=6wj8HG_HXTFb+wsU$*#` z(VAZgy1m_tpHw*rX|?R&oV_N{PEU`%S8@QQR^esBqr^D$pfvSYU31s@V`tTvG}o3B z*Vy_Ozkyx7sZ8kNg_~4iIJLvfve7bsZ99C7!GZwP&VIhQ-nW4I0i}vrE6R{Xtnx#ovAL|y>%E!($4 z9tvl_du7+SsyJ!VaJ)Hd@xLh4xh@dTFioe|z5{lUNeD(qciuJnLlGowAC9kIIYac`6 zxCp`w4{R#}I^4WuV9ZP|Y*jy*Gx~N0CWxQgcs5{EF3?F{$uZYyI~zl3snABKqioo+ z8$N8c2X6LAAK?fdY7#pMr=p;Y1U))i48vlO2G>QfR!E4=d3R^nj8J9>tCF!521-Hi z0Ba|^%tq!%s#hu_FMaeB9${&^p9Te;10#CTTi%xR(;zQ2rJmRL(jF=MXjnk=Kuk8l zF`sbH7qc82nV*fyPbmK+d7BqA^icjt6f6OTZ%>%X{Y@4TDUfqd3deTV5`R)~;8EDb=!d$iy z%$8b~TUdH$BF&oQ6OOd z$vFn7Uz~iqWYRT7?8b0Hcc&DGG>EM&_c?M@SRuh*(Jg%*KrAR83PoiM$h&+WZTEf{ z{J!4npD@^sNvOh5Qb1Y0;HE6kaMTr*5Ov%JX@9&S-X*gHuVC&^{?9sk(YTv6iDpJV9!ZF zAw}s?N`#+hWkv=Ur4$sp>8qmTI7X={Pg3o?MSg$1+!I<4=&+zwKAQCu&c~hLinjDk zYe&(Q>Wrh#G!w6)PtiJC6tQq=s*?xSMBn=8LaqUVhFKqK50e<7sjMkeTt?Vq`SYjw zbD41Wo1do?#6WGwFX(M+EcZeo;oTb;{!3Qux>_;WSv7ul9^H}MXV8Pdp~y9%_053( z7cYv-oqK$UB)j(q;JsBanH3KA*p&vAlG&*1V;Nv?Y=Q)>thA{p)CjgclTxa`nDz8G z{A`iJe6iC)MwPxgL=P3iwVGCSV%z((VP3U~gL6qf84W=lHR?gf$T<(2K-&J_{tj{e zB%?-YZc_mw-|mS6PZo=$mzkkp&%Mm6kyPk~ST+oOmx64y7axWUv6N3Y!Zcv3V@huXJLuHq69sS@hXg$fC&CbW0U!g=BSeqf0&J zapEE=7m>D_ClIJ94#JZ=lHX=whGaO56}+6679WU-m@h?mR{`5^<9k6&2ojC%S#*S<7}=_XtJz#kb=f!$II z4o#y|6KPOVAu+>k2|U%ALhpg2T|m%K#a7g6o&XS#N8W2Ywjtc;0@P9*iDeb{{P1B*(Mm;F^$5VQ-K4m2e|$`bmG3Sv#67zy1;1 z`0c-0`5`OY>|lrL@&|e?YXn!U#j{%9C}TL$i8L#MHR>2ak`K||46Pq9E!c*UaY&TX zrJD&GEFKanzmZPg`mE+9gHj+9M}5ZKLAWHSH7${-#ln$%RcE%D(xx$wG^bx^rL?{@+6E9;l`>LB;j|kak_#o~* zZ-8;06+&Y)E=W7O0G zF7m*|HHyw1P6|I8A1zjjGSq}cTq)tJ6dd^7XL}`Z%mab9%IseIce1qXyssZSfbSLt zJ ZW_5u7QJ?Q+-u>yeigC2qhFy8v9@yu%j_E092-|0u{3srNUXwAIX@?l(OY%h zSf?w!v_M#>dFswVEooc@J!@rPr*jWbjFJ3ewt2yxMZk41U zb<0|Hb~+KsS?9+g`4xHYoJC@Kzl>5`o<~Bk+=g#Xyle?DMCH(fQENc`AF0tq0Y(xrW6B+*IXe?DFoM>pYwtXLvj#4@YD}G;D`sO%oP*lEZdBb zQ7Zw9q*9KnT#g%I(qAKjU&$j;`@6dO%L3E7I%<7&Klesw{e=02b&(O-3vOJ&X<4_g2sXXovpVL!D_UuU4p+@{AdU%IJL1Fw z{F`YjQ#;;ime;%bCf_+sY?=90C|da+a3A!P=d%GuV{G`4=0U~<4*TtAdQyc+Y%;^= zIu8!p1mS##y84AuWBpyn@=)~&iN_~HiM*%75%L~xvyYVY7s7nvC<5!bJG6HYe9OYj z`))K9qgstWX@pKm+(46^8$;a^tHDO1nbzy083Qu$fs60NB9FzUyYzT&tC9H$q9 zcC(@sQ1T{;qsxhGt# zuZt(>M~_PpD>b$M!z79`{2eM1?A^R*k=s8u(sJ+kGtD{tGlonvd=Gi?MoT5@zV=%w zo;US6ZAUnk5!qTvTbxq_bwzitLeAgUOjW_@78#C1#l#o8jFab7Xi=QM226t1-UMk;!&|Nk2-<45@I0le_p=s2AD{-NT18U z4qDlizV0o^T7E^|?>hP#a?Sgho=3b}0WAl!7|nBp>}?jT%Xll@AHHpx01F~?)={WO_? zn-3&R?$8vn<7}WVoJU^xAoGHj9C9Xi_UahqM>{q9d}uH&w`Q-IFeq?-&9G)M=~OMp zU^PP~Q(m|B{USJnJ$H(KlkD;yVxis{_2Q?%$e6wzj7pt>vgS_@U2c*)LhS5Wk;d-5bg}#pvr=IMuf|b?CkV?nt3W zxaen57E5c>I-X(8Mc$QC>z<=}e%4aoVw$Nbt=}Q8|)99}%Z1q5Fv}g|K z+Bo-4cNVz3-6K3K4|r$2(17HS@aCTa)_Cs;{m9^-XwjgGTAFkH?FM^L1v42zC_ z+2~n2ATut58Y0nbkwwO5orTeRQt@e3Luko2B;5^(a0L0tWQaYM&^>h5TZD$Lzn$fI z5`oRAcL>bqba~dkwF|EAMZme-dGiee$}F{_B&woD76^fvmhgpszISb%k3=Gn#zVNM zJf@jnU2aMEeJP_vt$-1!I7^jgnZu&-ltmYRIm_1MqXc-2Q5&u8hKXLYTw8sMnVHU- zLfcfl&-Ywwo;s zq(l1?CEm8(zw%a(s{O13-vOCVx?4A=hQH@{oj*Hi9+OV^Ce+acjr*7ci6iCPtQ{Pt zEtLAVUrnEOUvzA;J4nP+=qX!}rwx~=;7jQ#r$HJP?wysdyP+$hIr(}ERz3W!L_)r6 zMVJ1h@o0A7`miIH$niKYcOwLOw{qiHG$sYd!=2TzjPt`U7I@fg4*r;bUbvCSJFsIC zQwKRSeW;ggfe2|JUZV#RcZYPEY`fE#=`6;qh^$D1B~!wYbwjrd4y8T+%|V7|{@11! z<{=g3{3j+~zZIzb%;RFszP)n4>1idS0zm%NWAoiY4eY7M>cdLx={}p4ohau zr9|WJrzmmHvs8p?n9=r@G&vgH7OdLWkF<6yB={EF2v9&uY`igxK@Q6*Z z**ko4kKvL-8H}Ch0W6*7*waTctdQIZOz!ZGfoaJm=c_joCl+k~fE>N6B!j9!`oZw1 zVk|6SMJ&#{5__th@0(oq-B*6U0qEAG1O#244fJq$ui;3>J%?~()Il(@9Y~QGq!A_~ zSKO3v&y3(_^6oeCmko@y4SXneG}sVWxv@ZR8P#ydy-F& z@U0W#fc?*{@9P_bNg=ZBTu>R0L_i7oI5nQ|*B#M5muR7c9gvJ-r@%nnHVzpC+~_Vn z7-0NRS4@1`z~|7fsqzdD@PU`|s}?J=<$w|643r&D8SyG*%_Elt2QU{=76_+&719RN z(87xsPCBllNeh)Q-{QKvl>f~y%0$lc{3@Mbd3QbB<#)*NMGJM9Zj74DmzPEHGwSf4 z<0KyE4Ab4;y%+fg(@(3z-?=ffFv&e-E@m1d=u_sImE~ztY!m6@-Qb97$fRomS3`bo z=Q$ziBzdvu1j9tEYIQn&!4&gvTmp`7)#AaxQ~!Nc_HU?K|HLIZSrB@l#)I^_6k%(7rnsS&5OEDHW6aiMp(5SHkdS+A8vD9_ zPfqekq1|#(eivuhA;GsCW>1;Q%Ahd|1jm<(gt-aqAdnnbR3=n3S>(`fV3D&=;z~q0 zE61f(W7mMdAZeC3TST9_~ZbsEol4kf^6(8GUTMy=owr=+>F~t z9=JBmCy>Z${*c!$GVn;SfCB9=Byj zUWof-@l?toq;@a;U`+rr%m(_i7BxUKA%8P0OVij~s0WlffR?I1nO5uds$dJ&_w);x z2y`BhZ)>FtHMY)9l?S;GLSZIWFl)vowyd3hcCp^JA8@Q3)`(e@F_}g=?5=M$NNpex z{cF!w4A4oTMaoct$xfrVe&%-J3L8+=iMYuW-{n0GY`Kb~FMBoEl$pb&#_*Tje%^R_ z;NH;g%Lj3r=IM$)H5zgM2aj9=-sgesw}Gb*uWmC0pFviD_nLN5*TG~=NWk&`Udrks z|J_ZqDdA;+n|W&4SP{pLX8!L|1_TD&M&#$NJ$-)4ez!i}j|;^GhCoURk40gvz7!d+h5?9(7HQU?ATO{hPHB_Y*cQsD+7KsyBq$)GpZh#XxY&ycrlKrG=ZP zQgGC>r&h(_9{G19~s72xx&}KY5xFTCUE=DLJN2FAw31{eA7x^O zh(6%+>W#|Z^h+&g>Ub^!)g7|ec{Ha+q!90hYif%kSI!1vN=ZxK6~A1F{5Of(>Ofhn zkn-1_@y|`^H!Wp<>s2=Lo;okt`$d>gMUD1jQmuIjKh5A#cJqIZtS$+%!N-}m`=-D< zA~)lk^B53^^>r>F&u;pXD*2QeQXR`UTidwys0)n7f| zefckQsawMf(V=(%UMFO42LlrGA^R5;wdh+Shx?5IP9tMO9aHOGJ?;9Fr$HD^AHQRn zVzF(%Fbt`l%BRS%QcpDv=}QAZH-B@_G*&hhi_@s^59E%#;7+X$113`1BgXf@e&;D#0ZSr4+VHt8jT z+VkfPddZxu`m$8(wki^FWu?qtM`g*(Ef9`zP)z)@s)gRN7V8AA=!q}LZ!s&4DyCwN zGBl2Ed1UwXlssj4p98E=V^!Y^4en~2B+XK6em?{rW@y=wRQ-i8&)L1QTX#{m2wzZ& zxHA6ukQR@)FJ{bhWHycc824KPOpMbNLFw~KPNh&^7t5?+v;|vws9ya*di%V(KBHJG ziG~(id`>cT#I?a^-M7e8WbdIqH}9jQW<{Y3Yji|{@>LL?5qjJrE0hG>tkja)!*J6Z zz;_13rbQpOL==~JKF+cF9=ZYu-phO-e|h`Vwnla!Q}*opWaB@3`UJ?~K(q2ba)(_k z`T|0c5~1TCPiJr_&5wbQLmnD|ex`R^t?V^p=TE7(A2|?u=;Hs-Lj(UK2^Lr#T$^-V z9{UWmzC!>J?8^TDqPw9T;Qw3J1gB-DyG|GieJ4FHhAeis^^%;S!swIw4Spe=FY`Er zwn6@`_^kO(D*{1gKd`Zp-S*E7VMwTj)jcqC5x)z6Oyf>aU8prdzipoEzOEq1V*C+Q zT^&+mumrK2@aIF)bDTxUlggmvk!x=*jqy%o2y6d_ZehdxX5aPW$6|inkzN1gn{cxe z#6Ef2kuiIhWlle4y9x`>IdEKtwYZ=By_Wq|1rnqL!<|hI8Ak(|BPJeOlK*=e5pd>9 zP6J1aH4Qv5p(4dP>-T|~=hwmqLVY&*e_}#MxiKc*V2lCz94f^yk%GZ+41af#J}t#G zayB{=dW#kAeMT?x{tJzD^LBd>F`yEi>(J&mgwoFaI<&3!h8`~FKn7ysPIT_uvQh%DPW@#|7C(mL zxlZD$ds`0DhV?%T+VLBC!JPm6-=z?wh9@XwLeKv_uhY5sP;(ycHj2YIucM!$`goLm zrukyVu4O~H6%~9dc=yX1bwseQ#_PT9)%#{v$E6Tj_ueqYK$%C}y3GEp0}vZ4dg?}c z$jlNFL0yJk7^A4Ptk)gBjel_@nAmS}B6QnmbD)DMUhUXfG(k{Hstz5gCHhcl zxqEGYzEq8-D`K~eb!rCU#>kg^5~=M~h&-*+7OroJK8_$bh^Sc9Ob?F3`WA{if39l} zm0F8(Hj&n313f#$CT+Vj*ORg;T=Z&eIg~tM3NRN~oc>Eul__JXxgDLK%69*~K9jNO zrV4mQ#IeG687G78sdsGa%I6tj)buMLGb+mQxRba{3Zg&Zdn{(=TIjTCsCkM+}N5V(n)t@A;O z6p>SW%SHw!eQU0Ye`i}5OEOF8`kZ6Ag5o{4HP?Fa23m3^bnNogCc}?N#b{xo62EFR zT=@R;{BGY~wlYciE!ClP9?By5=fd@%pf(>m)7IbAoM5F26YJ|`?tz?)5q@Z{l!HaD zGeKyD#cm4*z4jY;Q!*dXqvmm!F9BR4I-hWhIMwX|vwyDk{#*g`c&b|BIC#@4 zBJ!XclzH-M*D|uPwg@Y#j0+djZQS(M)M!$;zUA%tn!&46!+J``%#PrX6CA*z-j`^= zRzwtE;hO=~)>^=VVg=CZkNQZ^Ab!)Fjwgorq{i&FG4bA-ytstIJ&UMI=GuZP6IkBj%(tKhlQBivNhfA1p7bj7rFA&a38 zDl)4!`QN9yiYb@8Oezy->^M+*URvuUo8&0hfNtYex6u`B47?@97&vj}-UlvUGg_}ce=)UiqKV(l+U+;ds15~fIE zu}B*ICw{-LocnhMS!C{(7;H|mF~5nLp(wtn$06gPSJ#U!HfT|-YTo|RJRLmk&ze<- zv^m9;)$4JJGia)Dsia6fzb~J+EuY;(YP&-CpG~7VcHIT%wC6U+rXpz|es#EzxUO{x zPApz%C72$IS#RcSX4E1nIAnqY9BADTA?SW)R-psYSt@7CZs=c?Z@w95HT~#916v4#t}ccunu7o? z+akfEDYs}msw6dD(H=>r!+#YOz#&HR7<( zQAwzF_0UiS#FE@}%&J`+snke(Am;ad(3TqHLX zKhjU@*leT7sdp`3~iER= zFnU~|Hvn5)V*9bRyL-y_1#8j$jqc>h{Jnl~sA7U_MxdfOd+*VN!1>1yIea1j&xqGZ zqtr^VaypU-H0At=>>4Q?c-2S@&H3+41*W2HV_CDjshn>7cQDrn4%3hq)vUE)yFx;Z z-fC1Ll6kp@o}->ol%vF2d&K1@rrR&l@vF3)u`8DLq!>O^p9Zt_X%4)aLofrY)Nyg%LiF7mtmz zP|nr+z>hnF$W8x&=)iJ+d8uP_co||-S)LqZnns5TmFTl)=JCM?-Gpe3e0E?^?i2AL znin+k7C&T1d`*g+ZIi(e(9y@e{f@Hj_sGbDNIq#R4q5mu`Z6A@VHZce4+ksWl7&S6m&+eox?FX_DjatQ5IBcse#(Q>V) zBM`PnT&*`-U9!pX&uY>XiDpbMIlYZ-l(Q>*=P8&$zKfj%*59DYqtZ3GWjNau7Lj;b#5cUx4YInouVXRgn@N#H5>*q=$kV>}gz zj{AgHpT!2B-TDPmk*^K?(yWaw0KexD^89=#v^q>jGs+pUk1zYjlv?^} z@}C}TSX+tK5ot-u*7GMnf4>r|Fnj=VXF?qfUB$eRjEYyVyJk$s)xec659G@!0sE^D1L zkqj9xnb!ov?UN%^o(+!TZK1ar3wH)HXvm|ljp|>;raS))zpW0!MZlV2KCZ{{ljY%X zB7%0hl$288hd^^!c&-C#trppR2Qm&GR3nRUE_ne0W8MS2=Y3aj=wEgI;V1c~KTlnM zCFSa1$S?Tsvh+*SxKL3QdsP1DM^48n(FY7yj+)r4(vI?oLWk-fHS=()ZTOf}WFD%E zN9m{F2dcnY$`l!hl5z=$F}wiT&ZyX=q7p&#JWGs$;?_=W6O&vhSXF- znkJGzX!asph_6oBQzp zk)6)w$jS8YS=4ZgHxVX7&O*CnAMgK(|Cj;ri~YbpM(s&c-8L0~{5EZHg6GAL^ALbGHiooA3Pgd@dBH?RJcou%ool^=6 zlB24J$QCzli(%dq!&f}n-dca3#V?_M$#mgW->k$!`g z@=`QJjX6AHY}>G?*87)xDOR*>@C=6<1Y&dvKciUzPRCVV%C27o=J{ZtAiXq2gMN~h zBJ>E>=rR-c@Q&)D#`cs5Ikf&d+|EnJ2HL*(p$Wkd!)e2q_OE}@FFBFY#w%HIDNQl1b><2B~T)8jY# zzh01ElJhX2sqm&TNRov zl4EZ|=oG@{Y0TnyFa5WOi(+Noz<%5$!4nBox7p6aF_oN3yc*8EJjNQzK*0;;PqhnXhu#A_0|v{$1;gcUh|+&3?(@V)atkl#{) z*}CEMqN2Fb?;w2mO3ac(c~ygt(14MUB1JT97^K$f(SJ%2Yw-{m6J*Dd8gT10^RGFr z-eYbcQnw69oy!{$Ic8+oBf)gE_b4D4`zV|-Asm|t6Xvi^8H7snz5G75J~x=z!9E{d zv;RArLoRRM0DvcRU=Tjg7H$x=H_v?MD!dvSX!tBf>yH2>g0G?o2uJWFcP<53d<)MV z3L9FbVPp^vu1xSw|K4aye1__-(ZDx0jlxtfZT3)9SUkcti{Ym32vDT>NgOEAE8~t{ z?+&=vE{8`fZ?5sqO;Kxe$}m^v&cz8|dZG2KH8v|7Nj&PkY~VM~ zwI? z2ZBi|ot6g{J*J-A97Zwx5cMu(3kbX5>(j7m9MB|{nm*M7$H1+@k#IWL!u=3)9;j~i_hr&e z1^@Ms%B^8D|Lg?DxMMS4BOuQ~yyvH;Vd7>|3j!aKD#PJ>6I1PX@-Ngg`fk~lZ^T!z z0UwWE9}m);Uk)wH@af`4n!Up-D~s8X;J?Z@XNGZXb@@T$n6=wZyInBs-%w^!T*k8z zi3`MX5P(&*JG*{|6c24-K?56XZZSBFfzkp;f2UN=8Xfqdf_WjS#qui709=d`?7w=x z5V-2oq|w_K<|%BAfQ7XTU1u!3{3~D+O%)~#JdgZ@X0;mjZP0q|1;DLp*gqh8Gv?hd z>*3iOv=G3+9ec<-lgWQIFT&p}=uJLe12XD+H^1q*Q;C6WvTGUGWA?_`v9zPG*O|RJ ze+I6v>!A%;e}(zp!+78SsGVccPVCB)!t4I0*Ts{UE7iN^28vR3u2&k&VrMoFi1L2U zHPeQli74J{K(4ku{^44wOsARQATx{|oR~>#&I0U}zlBaQv@@^>FO9ggol<_(5E}k4 zHEmD*cOV$Ld~XVANdirXg9edy@m$jHMOKql#gI7Gx3>Dw)TDwO#AX@=1~Q%kl)2ew zxq!i-qTz7fK~>m@dk5Xv{jac-3LUds15IcLvgvX_g@S)Z4-l0~Yg_w}(d(a@>zen2 zp8oOFnjMW7cbPLhcqo|8%k7?lfL93ou;=6L5)0Ok{{!L=g!FA-qnY7dC6S@V$CI-9 z)%)RpZSt5sx6`3QRU4?_sNtOZ2WiJzx!8>x`2Ta4Y}eMm8B~(hSrPhn7HNUy#UkkU zQV%I%A14AtewHu32%C1zixJ}%oy*|f->Db;&_Ika6=)jNvA)u7zH6)H^=SF_J z_%ZV%sz_V?qNj~3C9+Ar%>I*vf%@calnKF&i%-6zyFiU1kD0bajUf>W3~yQMTwKIQ=ESbku!iL9zR z-(Jt9zn}!8Fn&2(U~qdQDW~>Rb_tG1lcYZ1g6Nw2wqv0`EQM-F96g6OXU0 zE4=a0jY0p%cOn4hfq2c?1-;4uzHuDlk^I2V;`jj`Q{rFs1kozcO(cLzjmR(N>2dkY z%DijJF{LRn2Xajx^(nROd&Uw9darYxb10I5O88BO7(;Va^UYFoBRdq56Krgyqd*fB zXqjVB3v>#Bp>k5TPlt4obC@4wc~qHlJm27GdgAVuF zZ%Ql^)|}gCG?ktj`T046!lazAV80EZi>_j@Rz(LHtwXAM5Wi}2nM$IOomKcUeVlP7 z<)F8{hhC@eb3V$u1wH+@qToQ0Jey#Zac(%r-a03?0Ye4543fQ_DNfjZ7!_Bv9+1GK&izpV1$7&jWz|6(RZb0 zj<&8Z!blH`JQ~Y_h*W+cA(ky-SvZXeZ6+}f+z`OnrPxtU2lwsC%_+qn zPRnVoKFW+Y8)jL6@9KqLr-bn#uU7xx!lhe`{0u2vpU(g1l)07*_VocjSO^Lwzt4Mf zfhQiG(b|{oG0~vp+98z--msa1C!nTR92Vn3e`!pkN?;pky@t`TsffQxWZ$gE3A;lL z3@&ggw`IjVeeIW8MAON3b{tRZh%O0{`|UE%z(l!BQ6=+DhCmp;=EL`1B`4 z=;uU9fupkRdt{rapiSEXpjqARp7Iv@uc;C(t8LPzy-%mtE#My{_k`4$PUH~v&|Btl zdO@8h29*??*&wMnhI<805B?eEEfy7IS*3uw?FQ}&vC|DdBd-p-WhQ4%@S?s34w1&;QK6%E^E39|%%MP$i9(w$<3&g6JMi3?+@Hpz;p?hzRS!4NCMvgugh0 zoYJSDUxI4HzY{&_5K(59ftfrRG*lhr_{r`%c80q3ER24W)2aJO%nPOW+BX*NHa1CM z&O}RC422lx?exoKChfOD>v+C4C>kUDi@{CDnpcNF6Z#Nlfpo6Rx<{4QlYRw!yK`|l zhZ@N&rV1;`)UPQw*BxpN>Vh5Z9geUL(t08pc=D3S$hV&$R}XC?kkgT1draVynYsIv z&sV>twV>(9?1mRqXEQ$&jMHJc=jm*+VQi~K;6dELb^T=-XCiP1dAm27KgDQRKbanm z_Ecz;t`zUjs+U07cEu`Qm(F;Yp5=pJ>_FwuS0Sh*t5CIP|I672L5~+f!%p9b)EdLx zdo8Cca0R#5J($xG0^#i0wlmTY5l>_2zkyk(oV`Yjm7=aAp~KkVAYwTlT0n2X!Y=#joDiiV?5Z;E??AI%X*1p* z+rd%zxBNl~JZ|C0X;iGCNJxGIT|W0>iHkw-#y!i(pSf}9tW+sW`vq{++0&Ps(c2Ya zGwhpJN{0-$J*{=YE3koS1UtbO!{qdM+J&8R7I`qj5B}puEH#dWX;L}Y9iyJV;S)6~ z8Apk@fHG5S2@wJ&YvF7NF;)Xm$HgJflf^WhU9PJi60L2jvEy6_dfR41pIPU+jC)0Rcp!M+%;Chpk~ z38%OFhTVcytwZA>qO2a_ft3T=k^-=J91*Rwxec^PXg{^vnzxf7RUnk=s=^(8yghfS zJ1lY$fIwa{a{v2UT-m{5ey#Z#_qqN_*Agow#Z@f1$zi@cG)R{icWHgAlTTOf z@T+{~`28wq312v+=ismrA$3aSowAz~J7LhM> z%y@CPefxz=3F(+;?CusW9K-xuBnxmibFtHz%l;ZDtEITdHf*Fud=otB(t>7`T_oWu z+lhFYu3CzJCY|a@W6U7N{QRA6_Xv z3UF4-67@O34c} zjwbzVy{(ad)NDnnll?oW&Nvy>?K!`wk0l?qU)r|Q-zo*|6n7FYaNooq(?n|faiJ4c zztj6@))S!NZGcdue{j~e-xboiuZ}zQPZZ`?JQNtH@U3nRO;sq(3REV2?{b_eo(3zS zAfJUR52!44(1VBx@v~TsJ6XgHxDm3CrHm^g*Kw&b~IRw zFe;&qEgN%pg9)wI(Rb;9@2sTQePNH6&H}{hRC0Y(_j^aD-}X`c8wGU8K9O=Qp`I~m z0>U!!>8;9}wadizsBUBsFeG^%Y_i8U544T2CSkw-fTULPOuueA`9PBP7+#{x{U`4_ zp(gf?YJwO5jXM1LZ=aeSw&2(ajeztTrD^9X7haB*+BrMWS;FbL-%*e(JTVa(ZT#@k z^#TQ&3!)j9QtZF_i&;<{WHj6@YQUbUzkqDfTyev((m(d8zca-~5UB&pwVz-q%(LNLh^QA&Y^dw8c6<1Nb2XReru`kV>@9YH$0(y`K0D=Mz3_Cz^T z&2udq#daPV<-SQt1{rWsY2&J^Js4>-`KR|(hBR0y!i;}?#jN3iBF2?VhzPRv^73Th zH;ts?co84CEr~1oIFd^^`;z0`DF1l*VH8hVQ(!e~CBPCWCDbKv`muQ4)BWzP<9AtFdHs*j)~Em0@@H_!uzcjst0b1zq}nybJ#O_Ybn! zUr36KWYv>63@zmAztjy5RrC{7z#WIoY_96sdX;SLmU6CpvP5BU2%iiAWR>q{XD}88a?6amAHPQPPVd0pv!!G6K>G2kOzdZMSUBq)f<4&8mYLE7 zgu-9x2X4*epTY<@sZ6`WHU2ToyIv<4>5i%5)6?Ux2fI+RUraM^tClR>}LD|Na}vg0{8iZuRI`3K({GrA%3NgwT8sj!<4J=WQNTt z!gy)DIt>vtH0u}Sw%QamDnu4LBn7~>SN~bO=Ui(Z?<8y5Jo6~Eo3I`06+9xq61_`@ zpo(`|6}l5mhtlbME4w4@nVhgnzH7XwFMGDGUC!PMO2~^Rpm4;gb1;ytrK)#G{fxX|H-ZxK^@<(Xjq(4KCH~t@`fp~shbFt| zdJl2ipun9$=g?zj7<9gh&8Sw2A~TeHG0#-GX|Di$IBp{|x3lfPrIt-vi@w)e+`s{P z>In*ph}_Hn+N&=TZ=Z?@uqIow$6Pr)?KS)}>{*C-;1U3f?|9g@*dYGjLyR-(Tvz9{ zE+D_K!>(dU=BYdfBv}w<$69O_-SnE5Y1e0wdlM*QBFTA zww3>hkY{F~lBi(Zr$|RMsdVy}H;cPSg3!{v%#;PzOX{I|qEMz!s%x5y9`DW0rRIjm ztLG6;LPt?yK=+%`XWS-wd{>B9i_H!y-8-A@%qhbY@`Rg6veCye%cDPv*6QqJ1_@wd;1|6Y$l z(bc`OK|TeTK%%+AAIKc4zOP@J@V|RD)%l*go-4nl1^@lJ9@e=PObKEr3 z?>t;ZN+CVtObSH!f3D1F$fThHjLj#uGArgt9rPt54J?FZh>HRE+MLtGU zl&q06n39Q*-#KLSPic2w63CD+|__*bD~O^BU^T;_yg7FxfH zsg)=yq+L8uU@nSf-)l1eQYRX`F`m|5t?Ubyind(eb_#1pUVV5lEVj7pURhe?l@mUi z#p7?9sJ&-oVyAwya-nF4i$E?;k+ekmlB6B+iE@?*55CjnM{<@Cyr# zJ1wXe3bJiN3Bfw~xyj)Jz)1o`zPT_g^AHhE4S)!~-yX1^x6ead;oTdAZ90N_U<07| zTf2P$;maPg4EBCD0G2TErD;_lIN|`(2E&`TCXUrP#^k|b)Y=r~*BVf)jKVK4mu$C| zTexC_r7S37NY)?(zvY56AFmSKKWmzGD1oB4YPOqzY0Lt61rW+pzU7}OZlFS?@2~pz zs;_a0f53S+Z(*2Z&aEAcJ1VjwzflNSUTDaPl`lCvmO>veE5edQ)HH8hN_AaFCRI-3 zUI!ol5U@?Uk%>b6s~_4G)U7KNfFc&NpbBXsaHb2FVI^`#%7vVTP8a1wkTS_7fm;P< z0DCa$`h}*#WZTI?GupeDAtjUr$fcX2G(okONAVlIMb$u3>AmG_^Ti1JB$HO95*0RZ zp)Qw$aQpFGSmPN9M~pFSt#(SJT>sI&!k)dHh&Lg(VA)c0Yz9d_92k)uCwOG8=uq{-4OPSkZ!9!8bG z>#8l4=%z0U!9SJLIh3Ma|8)(2$M~aEwxu!zSY(^rDfsTqpc}X3u{F`J2QpIIQ(w1S zr93bI{nA>^UieL+-J8MSoLFRXd7}V(DbVMlRHb_~q4eb}{yO z3DgDivq`2yGL?o$CwZIQEEH$ylc@eJuM8>CFKDPM@V#B*1(zL4#;aLEQ4F2y3Myb5 zQnGn4twi>Z5HZ|Q>R)lYRMFed_LS0Psf1KLKl}N(oO=5D5JB*Hx2LBnkg@9dffmPW zzuv%SKjo`Pj*c`wse#hYGQ^yx@>DrpUDmz3_wth3{ht;1hp%OaFAnpzXU(c6ElX;h ztsnjLN>*yNHmz&Vo#e0OH=C|x(*guf43f1NP}urK^KZE3JYiZA>k!Fzc|HQ$8{)X} zk*{3Zhs5fr`S4Y8+DFPcT_14?H$`LMdxuKe#b#}z1|K}4>oLK6OeEC!)TH7~`f_)K z-8LlSl%Iqm4HwscCy82{cMBO~#ZzT~n4E9CuwnEnYK0fNJeO5qvJr!_VMLj)>u`AB zu5-TWcI%nZ>Mc#jmb;4S4ct#W6PDI%|CHZ9t8_QHaTeg;WB`paJI{jo*kN{fW&|#M z`F7p%dwTccx2-sJPTCbi($66|h9PJFC9yzKZ(4gB+Tj)gK-E=6y7INtw=D-$a4g`d zBWO?0s8=5zVo2kH<&L=7EB5fb3Bv@8X3%y{GU>f`n`0-o>E=}mly0Oe#&@KjBYYJ|E}fg780l5DVbBpq;PvVoc-R_#YQNH- zEoQS}7TfuCk6t*)jseTbGMXc~XWmxJ+&Qs~kDPQ{5Gi@{8NYS`!!{yBJEP*+4bMNH zxS}@&@`y>jM)Q6V^=Z|Gcza8YXcuI4?>Bwlf_%8Uo4U=ZDbtFP9pn_WBF7-~j%79; zarfK5aqSaeejEC8R$iyr28CWI*}vFggRFDTR3BYoA-b}=w1ht!vb(@Yh z?A%fN*UcKnp@(A`5b5cAn+i95&5GARr@EQ`RAux9(53L11ivv~6uwe;1xuo~Bx!93 zRc>2E+=Bck?~bp~t`}dzqi>|c^vGxuqof(vsi*?uraZya>9`wBDJ@Km-!_y|xOu~m z2dDAG?D=kZI*~%%bVx`Y&&H-`Bc|#ni=Rk>XXHwiy{VmBBfZcz={(No!vS2C0q0W4DoNX;}%|+`OG--;~yXf?r7<~ z#XDc6Hh=e~VgG3nuEU=A`YiveQ)7;Nnu`3{2y}UKow8`o7yy(7JivAe-{PwHq|_|k zrm3z+T7-KXZDjvtB(fhfJXpVQPK!B5Q@B`?zPRc)&UI^&q_>Af|11^7HD9eAa0d31BCHq ztC^`lG6#&RQFih{fe1cJ-k`AOJciY8>MyxH?q2XVw-uMUIX-2 zad_LQ@)}=pdqpMj17?s5lX>#gqppYfgi*-$r@_;PX1vO&v?x$0VzNlcfsf7(ksb}A zJ?nX!jx!D|an*fHy_q<{2Y+sIBR3>x110H9VR60!%M;$JYjoPal89Zf{qVFT_~C1? zT#>|B+$v zb{kN;r$-H@xNTP7VQ#+;KUht9=e!+6bb#z;J0<-tN^Q1Iy!s&;v1{kS6F1cWLp+Vx zZmF8;>Q8iqHT@SJky4yf|CXB$elE9S9Z^Q0Lcu@ANE2g(y?S$f*hlEvDL{l$oB5aA z?Y$>6K)FPv+jY+92HS6{YA)Hdg%acym;ClEMA29)^&0Rf63Vc)nNRx4iOl0IU2>lW z8)UluYA%~3Mdlmz^(zj=k)Ta50Ftf~y5aIIy4EMO5(;&9{2gvz66I4w*jcTZof2OO zkduDuWL3vfK@Z@<3Qpkmo#)PqI|wNs!uM~tBk#G#4|WD0hOTmNq_r)JEZSa})1TCg zF%d2}*79ouFVNeRY(Hi$4_F~Atgt2pKPYg_m=^iZ`=Q4q>PjOPL$kds7I~HX03_CE z-1eynf8^Q-BrrOs+O2;KNlN9R4BTS>6yC9Y*sXIv5R#$;*v452o*Yh_t6a-3c9&~7 zfZKM?1Bo~^x#WKxf?WOxaEH7P#q?g(RcA^re}soL<5Gp{`ac=0FWpRmtlFwh@5C@H za|4laCMz7w`m@JTeJd7p;f`o1a()r8DM&H`A}rh~Q4;W+ok27(^ojSPFyFfK9_;76 z!XH;N(|lFI0gfCO6;rdZl$=8Fib%e{d5AF)ZHdbd^Cb=NUb^U%Cy^Gt*`;><{J5bq zr;=-AqxCy{3r$%SsOZDvaR`k2^cF5Y>logcc-j~(7}4ADd&{EbwH0a2Fw^u#NXrMu z!R^V%j%^kXLxRy~oqXJw4a6biyIc9evbOhmbhFFCEOk0yc0u4Pkun}U;YO`Wfa}nB zTjXJB7a&M$nSDwHc5~nFH_HBM-f^8^Wcl{;+A4yji*Ifl>twagwhrz@>NSNF0(zdn zp(O_Q_fLgNz)9NU!kxGnK^e~V5D1Zk4!43rSjir*P!QG-sKd++}4GZHUm_ zHlQ1UX)XkLO9BG43~pf3B-~0~y^LSwDe?F0&#dxLIA?3U3N?-dodskPH-$0d-rcD@ zv!Pg;yfcAJbi1Vif*$y7lTs8sMXQ(^o>0qxf*g_a~M& zLHpaU@qnVR!)%|N@~P*2(N&c<7TDb{<)j_oCic|K$>CzbUxk@5@h@HJQEQIoq_?a2 zsqxES`U={~c8t4^ry0xPuasPv^!_wXXdYF#ejDjI^N>@$t`3C6AO2N}DI;oc|7sFX zzop@i`ZN{x&O^@}aF(5z3vi_jhk=8K@W3hIW_fe3t-%-n|E=)0PZq~ z7nuz{`lF$Zo@dk@V;}Vm$@R%Mb6rk?T=+cPqtC*VfGWVmGoR_q<@on09Wc=%k!jRDr6K-oLekWPsRjvNJ z?JV;%!+NItk(S2&kR8-Idml~k82{*+&^Cs7&u?sc=RO_`Dn%;IgFlXuW(vx)m#h!mALRvO(}j4T8} z^=30F#wIY&)3#fU8HZQp2(EjHS|$P&)NBE_zv&qHmTkGPpj!AV@A?xyB((yrEIKV6l}#Yb6mbjw*E1t-zj_XV~rYPq<+9Xj+jJ)%=q#E0GjlJAC>X z_IX4?szz?0O|}%zW!>h#88>FJ@Ku`tq|+56QO+}5k$%gLpvSw^W#9rUm%^gHQgCKK zX(!hOX^HROpM4Zaaaft@up#XPbkhDzVMs58LGpVn?__3!tXKlXVL{(bK#-oAP0=i6 z5snr|0tcX^Gwc4RDcDBILdXS=I^^}6@@$~EtqRU7YfjF@Bji!H`;SZ7Iff1DG$g)r zVhpU6D zlPfdJ8=v10?#%$)4*}KhNXYvGNiz;yUe7n5A38`NF{%pCRlsl3dp4Bor}w2qtOelg zpErQpg22R4m(7J4QSNa~*nYZVFM@hT zgG!Z9aJ>EWPl>Y-6zakph3;|rr^tugn{ui5!zZhtU&m5|!Fda2WN)tzEB`!JE;l*>w5m{(v33&owhq z?cP%_wthH8B)6E5&y8};4y()GtiaKJq2b;{+xY9rDdV^>8Lo@MV-&pYTs_5yX}ct> zz)?`fh$X1N@z-?AB);t=Hr{f2zYY!O$Op%kwfwLcI(B1lrYQ+;#4805f4H8QQEX3} zY+<=X(l&*Bs>MBxS&i9z&Y#~UK+3ZU~rN+Q9{^lC3!z1+=Ob_qIQa7_`D zsrr$bvIp5S8d-0OOc&j((9+a;v3QOf9jleiDT9IF1rJ|Rzw`w%#V=nA4@%5vQC|N` zbA{h`9fdm?o&mq#UvffHrCm?V#$I@mvE_IMb{|i{e=Mt|pOlKM1VDW_BqR3Rb!p>s zTFLXsdOZ}zwd;;2ImHeX+1R8ZL0KrJY=Vlmadwn7mS3-0?<3niST>~@64%{D#|LH0 zB@62WrgYIg-76OT(@`RuhV zYv0J03SOri!%-s_$JJPtlfRZw>0ERBPW~^UMI?wRgnr>$#qa=j7%nG@!Z>2P2n2wv zQ*Z?aBfPw6a3MOb<0;x2X&?9A|y(~T~@E8@S&DPVBm zQ-%|048TV=>%)|At>R~;xn3(nN$7>^wDrrY9qMF(iKh3PHBHFZ_Cu8z{jsv1j-pv% z-89aW@!Ju8gQ9kStoU+%=(P>U@5n_#m%g6p@LqHTg(9GFqT|0Z$?hI-s=O2gR#A@R zXy&-LRNg-ECY@=FJ6+VBRzHqptBhcM8v%iq9H)?nf_hDs9|?Ir#iMl+@s7jV(Q*GS z-B$A8;N%Q52A${!U~s7Z1ZCoNvwvvQV?&|QA3%vx%+#2`KvO~A5{mU&cJw)Rh{H5} z$Ikr0h&w(y})uBcng#iqxGq>OdTav5-t9`=)fPZ-d@mh3pBEs|+3nHLBFMl-@KEN2Qvheh_5DXxJ-+8f-G^2 z@3=(H?NCtth1~njn-0}?4_pZSI+5t$W8obaBrY8-uDr)u__O-*`f!ry+=Cw>c66;L zA!Iboz8Ot^{^$Ja>&Be?s+8+l$CBpbS_KS7WJJxFI#Hqq)wT$K;@f@NzyO$!bEvdP zitsP6zH7RVuGGMaTxn#-cs6)H&rkZmzTkF6@fi=Q;0l9k_(xF7uJBqgvJs$xm%DK#jH8xjp zZjRY}qo)TT473Uh`h_r5x2#@IZMU^bpbtBAKIv7t8quVZOgo3X?#{X*@X!T-ZNoTvVT4UrfAx_8%dU zVef5sYzKasW4V)}@m6xDayv6yc?7HpzQySxi&ww4%!s~hfX64{vQ2ss=y=R zO_m5u)|=1uZp7{Ne(D~6KLmX3@d-&a>grpJ#E%=|m^Q5{jVyE*!h3FW-nwZ%t$7^( zk?yrkSrnO6>IDDZ;kJF_eKS+^^3;htENOOdC6s9M)ts4)#TwClD1a}kw8>M*3d@me zQf%BRYs2(!Wv=+-z_UaD zJ^cb8caU&iJ32Z#ySsb=pTN}p-2+UR4@EBhxws&~2!nML_U+yE z>V1YVB9L-{3L%@0vDF1O0EIA{{?SpPCf9<0r8S=S4$!mKglJypJ_tM~KfreNf84sh zX@8}&&8=104)v&>jF(;YX#U3GJUv%;vkvpqMsGdC=99vN7pt%o^2nP0d?`&5E`G?2 zhb6$*NXYY=+z6G4p_#=)jZLz6D8)Uoo-V`6)>0+%Pv8|5q(xL!zI9;aA6Ef#S1C$* zRoM`@je@Cfr`UA_uWSF{nUEE${42A0dr=$Rn!LUv(+Q5?ntAg?ua-#qQ zf9P9nM2dp^nlkf$F~4xur2irmy&Kph@%Me9f|jBck^e@|gm=I1&i;4r)c}lriJLj? z7Bowr+k3WevvKy-*9hi#m{aopV2F?VFyOyBXV>>rq(l|9aNP17L#oT`l1c!1GTJ0E*1m%~0 zR^%;z(+{kkcPS|#Q?d4YAs$UPBRP}gTu^xF!2vE!M-Q(xOWbneE+nZUG$8Td5ZHq1 zubb=8TdT+YaWA?Sto0q*B{zw~v0dG(sqS2oU9vjZ?YR`nb5_LPK3C#VB|o@F ziR2^u$|5Urv&hq6?b9fqcR7Sx_lVfQ(tQKKi1z67O%fd;BstM+CpyN7i5jhE{(8__ z7r4*%r_ZpRG7HSR4hej%U@qR%T0N%8u?=V`9wq64(J>p#m~`eq=7y6Vaa`zhK%bl`ZI;KMHzppw2;8^2?1F3Uq%z~K zFm=wPJT-`7t1k)Ty?dm4Rz(1@aSOgOZxhF@qm3Nl#ZEeDdbgdpTWLD(26(eSiuTvE z#fEQ!Zx`v$T)*rxoV-$k92+)7K7rk$BBnVVA~)|pR~vQpM?#XfZYsE2{ohbB-bm-t zYN`@;X}#|w&d%P!<~|}U6@EQNL7xeggjS|gr}an-J6+*Pc`t7yrf57&vRz0K7U_tO zQLlXaSus$f1uZ}31PYLbz}dqG2dXrSxb5KD&_HHKlw9w@lTv?_X<)LHsruriWn{$} zW2e_OC2Z)r1N1+X*lN2d!e+^sm0*cm7e1Bs8!v&s&Yry|UJF@npbQ5tJ$o)eszyzb zJcWcj#od$C-xwFSFeNbMYt53|_s1F;&K(A}bSaYJU99Rtr5NKK%yg%tJan<<@=X_ct_sN-kUg4Hd%luOyn%LSmHP>!Q5d3kmJ)H<;uRyay2mzIl?^9rl@O$78 zHX4=lr=5mkhux!gefQPI<#mHLUwY^Pk)62Q(oqW1ao}_1eT5Aqf5e=KtQK5BTJ|l@ ziN2?z`&__}I6)~g;uXL{d_+h=-DnWTT>~+xZ&H@qu=FC0o6zuBcW)I(_|qS)<~yqi zdHTg>1?vzsF|nZw!ft*i*?%APx9mlGVd1RPxnwe!(A8RMIk{B=hQqx?j_;@`-M#aqcpUc3rT^B zQL3gu^-|t+{1RLQbcq6pvQS286W*=g?AfGzoOs!{i%zL2e2ENHTx2L*LqiRfAJ|I^ zu5?;!2Ujex0cB^3fPTzV%zXBOD^S@NscdIX(sFGJ%_b2&Y zA+Yo+-0nK((iFgRQG6Sf*^`x+>h25}1@ItuCI$|ookEUifv;~so? z8T)IUQ@xR*&muO`;S0*OKbUJMlbPzSl~y$Gk|lNULRhp7B76j=T`|6yMS^rV1qvi5 zCwm=cuO@Ou;LnE$J|SV-R`}#J=`OuG`5~gjErg{P{Eh zUFrDtAddiAfUEPDPvY*hg-s6ts_fL3g&@;g)8z}b*$>V|EwC3Jrk6s;OeiHYvq*Bf ztT)3;u*RSb4#02WZT+~p03L;!s$N*vpgNv?luocH4A2dQ-#$lS!9Z3?5G+n~1*HFW zK*R=1ZQh+fc5HIlt;!$9VrYChYF3{SJ&Re>JiN;3O$?HvF=BF}T(As^nJ@ZZM4eN3 z9Bi~kgNbc6w$o^$CTU~aw%J${HEC=+X>8lJZ8mP~nak0hZ}0EjYsn!M ztO(x8aT{mThC%2pW8iBA?7`}0G#ORa_PgytWu==9`ZMxinOj>vd{LGL$7=>-gnVL# z__OqtkX8;7k|1YBzh92b_{o1@i)^hm`V@+)-0}hztIRW2-`yO@^FFyb)S|8THqg<> zI3hz|G>z90z_~FSK~xHZiM3)bNBlvfOsMaLr8oc0#vcX25WNL5Ie@HrVCcN)zZD1p z7*{z|C)+%JMA%17>x{z+MtDgINxVs_W~evM1!37)&2p~6dU_Wo5f#yv-?otbwzh!} zc1o?oe%jp%w+Rf6a+PM8uryyMtMFL$cV1q^E1_0~Ia&%`O+i?Yq~-Had}*@D8_NRe z*2G+Py5&N*toX*Jj+M6{D^mz|I-Q#H!RA~Imz6}-b~!GL(LJX6$$GhuboEAdWBKMW zG&C6G@+iS^9#54s4%MAf`!NEDXdxG7HBwAY;Duk z?ubRDLE}>H5@HRu-ecwXQ3XDv&oVSDFJqZ6&Ixm&f0v1kPwq$XSqEoGYP$2AM9brj z$a>i33x{Yh2G8vmi;AvO8a`~DQIa#TP%}JKp_|j8g>eL!tEJ%n0YnKQ7o71o5X!|z0OhlJOKCotX=jHL2e*#{wH6mfNN|U}vkF?#C}*1fwt+vw zSs11MQNLxg%HLMp!za3t%UC`phZ{w$TlAcwldMD>P77l2Ic6Wo!kNXPzGRpObUv&U zkzm)-9Wa=HLitVi#Q4$?JmTW(M;Pap!#ZO7vA{H8m77^!US5%>4f+AT@n^M1P-M45 zGEW$9J58a74xK1xRzBONR}$7%RUY8nvA`9bfI{qf#^(p$TJJ$d#-W8O$478GeRWaVdgyH~v&nzfv1%^5i zI+09CLaa6YNbvm=my^$TtB~8xKd-xQ+?hwJ7=_AAsKzlA2EGklt~U4&oA@n5KgFr$ z4Bz!u`pe%KO6Y_EbZOUQLY9JBEE8~GXt;P;!@+D^6i!_y`D-5Y#5_?ry zti~-m7t5-%OjsKcPoBnr3Wd|}n=e^Y)JJKa6g@&mQPD+KjveiTXhJ^KAFmK4^gmIE z>o%Aavd2#}wd;LQh_zQGHajfSlSQm!2en+QJF z=*enstyihsI}1wp``q=8qoezvr>igcgwj)N=h-BzBG9m}{sY}7(`c7T{-HiGqB zM{?B6n_3M{y!{&{88<=O23!53mfpIcv0 z`zIn>IjJDTS~9XD_jDUZE>YnYo(A;P?=~ztm&lFkq~!$bjXxD>MQck-B(R3ue7I*V zf9rHh*2K*~FftiM2>rPkb^+Qx^iI)3Z#6-w-6F@yNU;rTl5BN8t>?otoQmTuWZYGj zT7wX3yT71$j4Ziox36X!IT=|Ed4@0018-XN=XrnYSUx4V$A6^sI3L_tFVUmfA~Tzm zmZ;|+@(AUY(j)=jOrJGyHQKhx4`0aa+_=LNpUD`A#w&q? zYpo;bhXE6mXtN=Hg{DXmo<-){B_D3*CB1!#n1uKIrn508Hs`SISg+!j=+uG{!ks_m<4HYY>mE@+hp4eR1J%mF$6&gJ-*;?P{~{TO{}xn zEt=Q4*`!&e$8r9wFS3_AlM!{KRoF<6A4XpjP_A>MTvul%tbms}hKViHVGoijP@;El z?_4_8$2z`+Wl&TJD)Lk6%~Zm3xyvZkn#B{pbx6WvH&e>|a(WgBNwbYfD&K~lxiFj( z095z0k-4G9CL=ebq(CHAfhPMCyuTZEdy*+~SOVd^-aydd>trI}8g=1T;KzzIf(PaM z_rgsFtY-*pHT>cgK~;HC^B2pD?|8XEE>Xg6H@qxI1QMKF=<@bG;NATJgg#r|=MVhnZm+~|h2Z!Fk4`#WIjm(E zWR%0tpdE&wUrWi{QxaTP>-NnptzAXxa`O~rN2C!BE)dZF8vTWb&FLH~ASE(y!vgB~ z!Lo%i;nF55fD8oRacSL;8ZRQ)2Xdu(Z)-VRP#^shbN-rqHqvFGX90IgG}c-dyZBGN z(2HbktR;mRjgS(bJj@olq z{4dL$GA*v~NwnO};Ub?M1J8 z*mY6hG!RVz%A!7*W2AU;<#gt}p*IEAeq}&(raOCIA>blXGV0{)DfXjOq5q`;-2_b2 zE`H$5aCRzv)S|%AXhBq1#(APd*0+}XS@_xX%=U1JN+Fb}anXKD0zOaK@&9Cg zAAHbD;c>d?OwM)?fW|9@?Or4pCP?ldGui)h*ndR3ka*;PVGl~JFw$ECn!l;^=voJz zzG=wzs{~9C-whXBXg{DyqRK8e5pPfQd zzdQ+GuQtwMdvaS@Ku$PT>y}cR3?>?cFP&7==Y1#qFb(T_A~(ifn$ATCmwyn~# z%!TZDO594Me+X~EYX>T#Xm*0=jGsYL#Nq_7 z2MQLUoFmlaKt;SmwHQFJ-L&2Lxo2CHt<2FF_)8!9JN^@b<17~(?D{T6Et9RazNMOp z*ZjP0wVjT&2$doJbYwU&U3Geq(Ja<~Fu2Q2@4z5d14AGhIE6%L8gPG=m8&xOeX0C` zi=9L!^$5fJ-s!G=`yCbRia-!vpGovdx3Ko18SSx?mRV)7Nh^pr^)$zpX%{jhZFs5S zx+x%P8GE%E>-du{Z(T(YXa#ZNE9Ufrl=02dGwq1p=5VF))>C-Bv8Aic++UgO`sD?& zeKXrw_mHxeG1(#;`Vtimyv2fm9Ini1?|n!Pfk?Rd1vRxO%{ljs-O8}A$qpr0 zckl58f{iY_gX1ZG+eutf>usQ^!0^M}qhEfAQ4*DvKT@6ez>L|PSY>5J&(NxZ);3^Z zj%^B{1XfY{x1Ur7E;;($f8FJ)`<0UbdyOHfqE?E1I|55@1at`zouevxjg|Hk^@y+EV--N5WI&JZV2I!a_ydXU`pYq)4seUsfH z+$PS)Q>f6+=ga3?H+yz8SaGMEiBTlQBRnCh%*ZD)tdg9jU80T(gO=EhTmmGK2WHFj zq0Z}{fn9W-xlMfRut3xo{hm`ZY5;XwfeIu)M9qW{%cFl{=V z9FmQ8TKHKxt%4dZ-chtYtJ}?BW4;K%2|_e9b+xBaD(^UJ?-(6|Qj=o0B>te)IBM_7PynIYtjYT4k7@hSCjzHz$sYM@R}8D{c3EBc~5XG zm@hA!B|n$`OSt#aI;Omw(YBeNQxEQ%6UJDOK!Tlh6cG_(th_XxYL)g%r>U=?qn(5Y z^k!c0>RWE@vKwt7XKGS9S9A3?@wknJ^hQmWkWkXgZR>2+zFn@NpX(gT6*uJ>`}0~+ zL%U9IHH1DPDQ5e5^s4CEa;l~jqcD0~&4l?Re*)CdWLIyVdfiLyIEm{0`NDB>uqE85 z)JSND;V{j&STbU$dSBHxSvf7Sm{@^Fkt_j?XxC@ct#hBCQLI(`j;_VKbQr?oBb(52 z$C{zq{+59RWYJ|Zc(A|HgXKfc1*J~YGX_b(FR<0Va7Il?QI4VZ3(w1DoxAHv7|QoX zp&P@}dX}(q>9Fa5;O#QlC3v{I!-?C8xJrwbj*`I#qd@wLyY}xHE z57C(a{Am8aP2y>m#-v4gfya40ft82EeRt;!jbN+3a6hp={ z;X~1rmnqDzx9b4z|1@u3)hYale;DpS82n~=!BCb*K-qYw90?|6^>1!|v3GEQyw7U8 ze1#>3y_bM>6+`E|vWPOj%Iq&sQ|!1r98vaqaF1Nw>QDKhHkjgxHDER_wTuc4`*Mc+IzH|KfK_YPA9e)}}{MmQ+tZLn0tSZv}*v$cwc!|&vGm^u}la@zRUBvNvV ztcp=425D=VXnRXUFtMN;tUXVm+VtNw*bsZ&g_Ze*>XO#_OnA`MpNU3+HTNc-!w7Tu zd>gdlqI0?V{Od|j4<#*=_dacd8BXy1Kr-_>^XC5B%d&p}xHy8Z36F4Kqd+7keMQHq zajGPr#$|67Vz!RT1Q3o+kWXe(2OkIjrUS-u)d1?PEido1;`#nDDuZx%rAKMhC!DtA z|GGJSIl-{kG2Jle+1snoL-5ouj%w-A-^xp$pOwCOb1xE=E=6(-Vl)7MK^z;B0uSnl|W!q;f>2khRubYpnuDW^$_`*;Bj1o3=DbLI~tFitsY|>-4Gp z%K(4Rtb>%F{;cFt@0`iY=-1W}dU~zwFY~g(4<_)(Gk0IWr$mqE7cPB&aA)m%539ig zX1!m4cOc^ns{2#_Ua`?DX56^~5T7@-z9rJiuq3ivKTzJ?-49j|8ci>K<#x$cFSF#; zbOrB4nbQZblp#-~Li>K=;}^&MxHZnxe)C~kTtiO$@*+2`T&$sCPrld+&z zfm+;bZd3O%2DuP&BIeD@pjm7`S5brnivj-14lda-R-Xg}~xv7W7{c-bM;rb+!O zSb01yu}LfE0;Bz@sPc2Z;bIN9{i5kv8#2sU+MRpE-7J%c=8amC^p9(?ko$nr8m>| z28D6qxreZ#BRerJEYnv@S6-3Q24Sm@nTSqf9w-B%X9&H-0raB5|2aCAmw7y%_h16> zU5!Lq6I#iats)UHy!6(WZ>;ZkQ3Nz64V<59H z3d!hHO93k*Njha_GP$OuAB@%G(nBjrf2?xXn~ITR$;qR4Ok@OYxtJNh^*ts?RD98t z$aACSjaGEYbE|__Fk!J1pBsyvj%WYXVu2djZ%IUYq-C67dx&Do>`FNgQ;2lZDw*rL zH*wchvoVt7hm3M1eO*{7q&;YNL=+0{dmlo|Ee{`iBV1_)5*=7tJ7Pqs?` z_p-=HCdy!R#+4+|E|CKf$~$CgSFDwKZsNb{8xlEom${+vTO5&Z8CJ%)=!d@h)cz#1 zv`KeNDCPIamhSHUj|WtfZIhO6xT7?(GOot#N*={heqKB*VXNd{Q{D@95p8xemCGx7 z=QY~Zvz2L5F<9J0Q{)yBs7lOKFvBAU;Ga(X7ahziLBVU{tMtIcQLoGch0Erpda*BO zMprd3#$+bA_mV;$S@bnW%9J*J_&;rzP(3cSXZLsyOXI^Sgkq`1oFM$%qkE`1t87y; zYF%g|3%;(8{o#U?EQ1rFZ-a8enAUVgK-N(_{oHexg2hfw4rzL79?bVW?}U}SE(r0) zxPr5GSHaAxqwvx~(LASvZYI>cc98F+^W4`I6AA9QS&h>~52odg~l3L`jpf|chj#)-}{+Nzx1_Xx=WZ!a3%;_FQf zMbJBnc^B&V!*L^-dqRUFPR1siQoooFB`X1BDzl`Zx=5SLvAUz#xHrIWfAn1eyt5u} zP2!=E$enN)a}yVQ*ag>!%|VzKqg=Bba5mW%9LA@jq#`ZQI*t3Zn-9<31igQJ(>VmR zoi2vkt#P6hIrV+iNFZb2rQrSNFX?!sZ_)uF*H_ zfM4h<+b*aNYE6lkd|-=d8KUEYpeBhHnH7WMMzzU0lBIzwm~>tRP7(%0L@<|08@gv= zh_LAv#7`?uNHvuji`y>&&mW%*K8`=pF754WF8Kz)>_8eI(ig?4fLSRAG6kX>$ek4p z9inZZ#=hfUCwKSp!I!cEAD@9eHgPyO?eY6}kjZvIsf{+Vy2DACu6#+EkLrYEhDy(# zF*VXEIz^@fTkkF~sA_CKxJYleSm+(o{}$~7LJmf@poatCA^KDyT1yf#$Ps{q16maugdxnx3 zWVZt0oWh-kR*8c^rIo<%IS7=%^V>hnE##NOaOXNh`8l6$(nNtwZphNFY$>3Hf^1kw zyt^Sk?im;X+rsx1*5>SQ@)SC@6k07V-@{r+ppWm97IcfF1Aj1gdf!iW@c5I z@=(EU3M>)3&`kdJMBcPQTpi^zmOosZH+N};o)P>W>bnD2zkNd4&F_6U3i}g-=P*jo z;pEi+mAG$lsahr@spGJNqe+9pUK!Ia2OItFZ+`J>imtV|z8TXF87uY2+p^EPbdWJ~ z`+pRKqrJx^I^jAww(*6!sd+oTd?q(^e6)ULss5a~Qxy^tM-ypLX7&wk2y^D_`JtxP z(%sqr`6%=uvC-uhb+Te|2{+&r7y~FJTt8VHfNKm5utD|t<06K#RnR%*Qu;;EAGfAo zK%=SW2D-}sNsq;F(>kiijAsAB4O)~L*7TWk%0=25>LU0h{5Zbd8S+i+Sdj~*DJA8< zdtp}nt^sfycg5D-vMo9{BGK&Z&)-yF$l;y=x4~-m^E5&ZQ~JPBK=Hu~bnE91fsg#l z)q&4t#9`<8XP$Cwx$cVxu`V=qAP*Z^d*_B#KA>tv2n!lj~1iv zAx$>33%r(Ir;i*y2Lpt^;l{gbz!aI!_>StGGeo(`FF#>Znl)o}N1#yWId^M>*!b^1 zKvsmif>>R)|3&R4L^m4&q)gAjtj02CjvlaNDJ?}J#d<#4H+0?w5K(RBnxSCA3i8oX z=4RT(YW-leT&=WAX9~!{le7mVTTv5>%PwltD*>Xayj;fCUFRorZ`^eE6S4ojhQAm{ z5^2N|7Z2lwkxU}6rmSp$AAGrmGh{SiKWs|C#C&EGVIEax+))DqnE@DprZ8Z-nYUya z(oP0l$xyR)Ru7W=pI14>w67@JRuUL zS43Fd8j@4*CCQq9#9)I z5?pESHjmirL0$4MUdhY@%sj4@g)T@~MkTLjnXOpL|WPdZ_}R$BhSQm6wa zdCs`jsuDu1NQ9JxKf%4luE#;9BQRG3vu>5ijO(bRnv@4 z5`7z=wCx$wRyQeV#_yIWv$g)K=(8EjoUE zChuf*v^>~R^p0uI(0RKzc%$|SON|zM-~m$&HjMcm!fq2QpC~wYYdbrssg(RzqjQ4i z`R93A^iX>xMz3=YrVgGO>ZtRNMgX>A4BPT7p5}J-tM)SuUrwv~a|a;EF$FSB03BKh zGj+XcBwbY}(LSEP6~28U=lEX3uvAsotW_vAqEyCVKBbQni*!-`O&u>gHO;2`$owbu ztR^twO=`t-pF;A}xjT;D<9JsJQ#{4q|Ph@k!JFcXCx`|j<1M}gccZ{cuyylZ9_H@ud% zjy|{MLAUy(b&@1t7i$Vbx~sx_yg7ErGCjl&EVnTffF0OXW(?> zs_l&HmmPe zoVh#*1z5XqRRI$5OS-iy2`uDtcUzqjV$2BUAHisBZ}1N1`lT`y0a>%qS=Mlm^F;A= z9dS3z-@jBu%V#(YSM1Tc5J8$&*2|%FjtFFHecDx#b>KJ3SJOSG(gwGV0Wa7FGNK{DF{Q-cP z+Ti&`4j2VnRK=zc`93mCf26aDE2gtb;9VTh4Q3Z~nrCXTD%Mol*ivn0S$xgk>I)%8 zZBZGC27e**B$1PkzD>ea>b|zyi}834CUfY+w48|VSQJs`9B7=v5z0Gv@wh9D_Mu;V zgZzb9u4E-|0!0MHkq}Zyw~<2MUpNRi_Qw--G$ipB9xf3pK@=Ji9Okww!Yt;&(mskWKqgFsUGl+cBd_uBR$Wp}Zh!Qx|%l zY*EIAnUz(%@aNBjyu{Z7u?LPAyJli{S2dMs0yvN3{|cMI0hMh;4r%xlN>?CVNwS1L zvN4fQY@ZKE;w?6DF?RTGnmn}TXx(VIf->f&&bL#+zgf>kityXNG81Fm^A7K)lbrsy z%q1oK_-2eXLaEAxNQ|#y=IfjFTpL&?2-0e&pg?=Se0*K+39O(#OoX z*TBoT?Z4iy&vLzrt$47rs(^umX|`@uTiC-~s4jlb3hUT>;c0;^EM7 zRXrQ?co9nwqe*ORZtp)lpz`oEw{#!pTd13lCsjl=>1a=;!9d{Q7FSJ}XPNjzvP7=` zifEhk3IY>DHlv+zC#9V#VX$#js40c@0Y>B|CFu3t@@G?IEzKPT-D(38OYDWe5e+kQ(eF z)-#AWQF;%+Prxm2%F|{0)xYYG#qNAACJMa=D7>1ZE(sf0Ed=_A8)B&ce)OtpA)A*J zt}5`lbX+LC((pjj8TSC|Lr#mGEe;53vl;*z77%;|*4Q+@dnGlCL1_gHxTuwyXCLed$ zUp1A(K8#N__N&`Gshg;)l`~sBMmWmYFybQE=(ggBHA-eN!LXRq!0GT{_qY8sx1p+|)An3WLwKH?19V%tA?itf$wZo`??4jZ`y^e9{P2P>P6APUQVGJ4u!pTbi zn{8tL_6oL@>y?Yj2VCylBGY)ImzXB;{g&!)%}XRYyC=lspQ?3@n=#3@I7fp6lR}Wi zzSdx>9=(Zx96R-qeDXHz*OJrP6L30<<=N!!Jm7y~WhwuKKkcZMY|H=kT{Kw3Rv5~9 z4L>QvM~(fq{;{FUMa+XpREFV?6SH1hB%buLNrK4|)Do+YWLPAOU{vPoabjo6#jdG{ zLywu7T8Z@uQ#O$b_c4U*&e!Ss1AJ!2EN*rmqqx*;H78=e6R>ESrWP~pZa}w;Ku7fv zVMbUIN`%+)uV z4@cRgCex;GSby!5q>CWMpQ4u*Wf_@zZnrM;=H78S8cy=ER#Rs|l%2uG3z^l!6L^y9vN?vA7$V>n-0(Y#+M z5%z88e48=xqw`Y6fXu#Xu%Ht^*v!3pERi??mpDyO2TChez?0kmx1v5mLWRysIWdV? zg9Hq?#8nWe-LI3&D~l+nJ$f!^p=-RsR(-o3u`)X(kFT!)#TC&k8uz5_yS~HW@I%CM z?qsQBg))bWYkRx8!s2z+>1Aq+2HdoMWCJX8%QkS03z>8aowSc|6VnK|HxC*wXY_e_ zJ_a|Tn0U(?npbX)u1TOlkYsL+qXm@wX8(vg6qHYE;e2ao3%42&{q?%v}@F#xzO$QZ)q<%oJZ1*HtCP;g2hj)SDS4s|r`Y*)Qd z?NRqSf&E*%3KpRX+;KlJh0etr8m?rT@tef;0J3RrbM&66C5?O&%xyUZVou(tFOB zMg>(Izlh|aXTzdqU5eCV970f+m8G()3H$?Q(Py^tUYkQ{G6h4O;hH%C=>xP538Z)H zr@swaFV14lgSdxNCt!1HtDjhwrq{+!$6a8P3*{tk;qmKWbm=PEY`1I<=d|ppoaW`o zjS)#=oJTn!kjU_DuS`l}&c7o!N}VE67lR5|Yy?h)-+L=CIya)r%Z_L?4WAH*beFh4 z1`bnmDLlJ9iifC}<>=RorEVi$Lcg|~14D-5tN(dW*D#AmxK^P+ok;DI{Zqw#Tyk6R zzIhiX5706%&EyHCvp8C)&YYj9+k)t~)ibc?^U{J_E6P#0>8+yNUb(MvQ!o--gB#7U z^@|tJtrgQ6*)?{KvKw?#->_?oI$^1k9ELUK^7AH|bN6413u-OC4BFG&AOES?P4}v-t!QGV67FrM=;@V7 zfvM`W&jKbhCO^s3`aQyriLrzjVU@+F7oP6koR87&A=k}(7R&?SaS2^pm=$WO@xVE; z?j(Xs`#RVVU}Tpo-JeS5iIMMq>K>_TU3y?TUQ}0Q`^fQTyv$rBMDA_n#Mi9;QNZ)p zy%&ysPDs>FTr9e7Nkeq4|t#KDS|-V!jm1Gt9vp zPpjs4M~TTP6D`ITF-td&RNxR}woVWbzW|L@{#A1ZLO^`pNr{T6&IjtO%QsX1kUR)y zVe?~30;)t8NXHT?u{K`Gu>h1o8VzPz5oW3|C3nEiqg4YCih~)A)P;)-or`rlvJRSs9sdv9R!x1ic4P z8WbH7j&DV7GwmWBt+>pUx%X2oNw^Y50Y5bX$F__A9T%P4O<*@!CC&atlD%lrpsNNK zytaTBW@rR>byUYBWD%8B_u%Bh3;wy!*XY4U0(vR~sEt}280j15$|Q%@<0{l|)O0Xm zR&*sjI_^+duWqZUQI6rvD&AV zdE^M#fa~NGH{~Rz5mKQkW;th^| z>34euf#Wa}c@+1=BV42}~ z&07w~w#{4!VH!ONud2ki(ONuRg378m#p&H`iIYTUVsjTb3($o1Y?CddVnPC(~mplGoDnYEBblCldlwb!$~ynJS%Z**j%KO|{tY)2M|4YUA{=R=AOVsgifmcJ?ef2hMT`m~^62Rv5kRX!l=T zYqe#rN%4a83&p#s_k!PFC2ik1^@XS$pYlpmBd6kA4)^x;q{7Frriash zyG!9l?ERQcIOP2ylJL;auJ$oDeXu{ijZr&M<(r&sA9Uk+9OkO6zb_xuBp`CNHm&P( zK$I!CujIAjMJ=}3T>;6NS3_9T5KiL1f%bj6TVCCe+f#eHc$6~}q+fh|o^9L_43Ad; z>aYG+?0-YsQl_(@{I#N!s~EyD@}!WWhOPn1x(&5_6IO$@N~v1=sZE>{Ph?u`2PaKv zyhY*h@mF4;hbG9gQ-D4`)2MPw{LtNXpFkf+3nTyKWx`B}e^m**s{XFk>O7_?6*Ary zM9CIdrK@xpoQSNE%rW`YIxpv0AF^4{5NmNfBr2d%Ie%8tb8L|Ic&^|6tz^2wr>Nr> z;0_xEA^$pl>Q_}AiHCgNe4L|ivg5Ah_Hpzl8nGkrUxq8`IL)#;wN9FaAKcg2rqvna z3GDhdnh~WYwb2YkUO9v&KAm=C=PW`T#%ssFDu&Li8g)lhmn3>WGd(891TzjPZPI_% zww0a0(wzZVnwZUFaAl>t_B$nzIeu9wavKfZ7;P?0#nx4PG$wOz{XEdk}c5Bz$xG*jHg zxszBMgRi*F%MzTY-sD!6$h?GGSFRRnmF?v3E)m;qZZ2OvctZRgiZaGG#xs4U37o%d z0M>`dMPfX@dV^x2l**IMiE6;PQb6P0=c{fU+ng|#m8Rg3^zwzCxtK3 zErwn*EJzF@U4hJATNzIi3#3Z%6*J|L!zm86?Dj~43Dgj53{%SyDXbV2Gmj1ET`e60 zcm_UsQ83yU#}?PE2^(|hY1CUxLc9_Q{sl*f_Ect3BA%j|wuGvdgkqh~=&@(&~l zUvvQ$Y(-bzU`PnzJSRKSt@Ypyj&p?F&~uNvDFTGN3ufgha7Z|901rABnbj;TTzXai z&IP^!*xlMWsA1qAl953qyD!RH(h@^^^fz9~+z!h`vFM(d5|2E;ihwFK(Fvzo5p75KKhsXfZFchUz+?zJcOU`V95|w0PS7c<&x=I#cvCB!+Fl$3|LW zm*L3#O5%O54XOX5zj#Na$v+4z06n@V0v;>7nF_?KtpeA0W5|{_@u8N&y^*jphH6;o zuBJO&q_r$2h&X-{P?xBY_fZ04$brZlj?F?4*-Ovdk{;a1=#=%#t+4?3>n?FiSNssL?{(HgMkGi_5$*o>1o`chVwqbtQN zVN19NT>_|lqifP%zvA8ojCO)i3fSIt8*F#d(b#tSc(L}~au#*^h-*xo?uV%$iVSyn zCNWKKCm%=MQ*vt+%41X4@R*1I&-9B# z805U9#)BU|2p)Mq_rugXwXv|Vc2aIg;lPzFSeJH5%eS^pvpsY0y8Q``+M#Syx{_pVUj$|MTi|8A;=C z*Z|&DS*v4P#;Yy7yMJIw;qBUc17pgJ`VKA+4*G;Vsqb`{%=@*U{r(^PiLNI#aB9va z()dx(O(+}qxWb`uqW8Lri)V%;uo)B6s3sD#>A%PQ;uiDb6b2(hQi%4Ko`md=6bkor zB0Fk#-9=gst8`t0R%Pjnve z%6(^LMQ1Av%S486MR}x-Koa~8y^FO<^%eV6DYyDf!}={YGWUMXJjHFz*O@jlf3n>5 zfW-!zNwY0KZv~s00S8=xPQ}YsCBx-J`*8pYmJS1nnkrP(qE{67_;c@-P$6{eDXzxu zB>HDi9l>#pVhZWs*DZ5FyIDD2MCwppVzjV;T(|&Coz(HM$~>Giwi>7iWBN;utt^ z#SxeCxCDomYuEKgn3w9DIhx{JerlY(>YL5wcN*nhl%BM z3MC2Hpv7}?Ic9!8gg<<6)Wo0yS_54AWJBUo)@)!B^jPkT-$h>~`E#qw5 zjkUrNJcy1=(hXx~f@aQ7sVZu)Z{U_Y#x)tHvnFHK>{J=6snduwvzLi z_UxF_WNRNHri`LddwG%fgXu^<&g&JxV0Uzr9?qDsIQ4D_O!RRSn5f|aMga}RpmVQ3 zg?i;U>i@&kIR&=exNpDqYTNd@HnnZrT36d`+O17(+wE#wTW#C!Y8(GNzmxYpPLA?T z?%cSp&t*GE(-^I9eXGbJol1s(tYv4l$}7*>q;_cG*z3eqOMAjL>&T>EpAm^oJIQOs z>!?p7Zl2!xhyZnH7sc0h#y^qi)cDk}+@Ky$Jz3cg9isB%wY>xcB_7NEV7S5MMx+?7 z3UwIHmwDYh@mylNQkuf#IyYQF`Omk_9&649nx#pQ`jZM$Y!ssHS!mmR!}MKpQZRmC z(eYo6MccxLK}r>w;$t45))P0gX6_d+jD|~OGv6v4qIbA}jmspraa9b56Ey3;voSm&&-w z*!TII!7Zpc#nfHNW{!UDQl)Jt?>{Ph|Lql-X0LoR*aFzXpniDYLC>1y`^NxG-@Ggw z0|6zZq~2LM6@9K#-WMN3$8ARmn@zd)HvrxT3*l}_eLIzr!SltgD2|jiw-brglfdG@ho}u>*l9xV=Id=43`XuCz8W+^$+cL|U z-bb68=0`k#jSrzAG_+U&>eQU~xPqMQdNT1|7hPJq;?dv98ZqlPF!)t|@t_E0ijH&C z%(JPK^1KiM{v|lNqEltzdG|@xC~s?T)QCd!I>^#^0zH;+V6`W!4I4ydtV`SI+228q zw$GHKCmyEy6+yZpF9XOu8Q2T3VnF!e7(O`Ef6F}QUvrz$SIA+Hj)8#z*y`$PwMCs^ zog>R0hDxb}SCDBhcrOo5gSrA^4c9j?ym(2|s~T*Mo0~Q+Fxk_YVJF0DhC9FWk3C#N z`Hx%9h$u34H_HsyIWsEb?K2uCLN=q5L4nYo#$FWr)^XnkwLO{y3k6bH<8a`UE!%gS z?JM})%E}2T;8@3f8P_;4lTO-EPbV^fJ67OQ1D3rcVxplh%a|*?ThfGSX}3kq{{87Z z-3pAuNjb!_mAB@UF$rfFQ;KMGg<|ct>Si_T4^}Vay7Rkx16a zna3h^g4EcPny$-mPn{LH-an&?+i@e%W??$^i%)lRQ}pr^<;+3R;}#Q&DI5cSg~i52 zHRZZigx_c9br_gB{8Z4*sE^Zn#r$t(F?ELRaI@U;;k$eEt7`SC)SiKM0|uszaBHC(VzIZD1% z@lNY4YU5<>CR4BslWa5Ea7-KYr{%q~Z-d2oHOmd-aYCk4D{g^-Ajj^HP$Irfb5tyJ zoXOt0l(*N1-h5X#dnuUE97OmGsk#-lM3+g{i&>7zL}3)Cv{%8g5A|*KzvlFqhwuAz z!hi1XaXLL$?&sMvxRgSDteao;^~7ft{4;g*Z1 zL@+#1;hPQa56WQkY)%z?1PFGkL4xXDg9*iGx ztF+JJZV9$`z~-Yus!$>75&HM<1WRS{6rMNK0MyFQ(HXLH3v1VTB3XSMWF-= z$UQx#y$_oh0>xLwwnO}#^Sxbs`SL9NhY(+@OT z@srrBwak(bPn^&kqi>3H+q=6rR8CLk@z>`a{!#zVDI!51r16OHm*Qw^rB6xccL+2g zr{XhTFZC0;-gnY`y!M@6a@@Tx*S4zt!1E~ga}Kfon^1Af_X_C?w%pfY8es(8@Uf}6 zyLHVBiOrNrNYG?qLUNe;+WyUoXZy>QInA!;Wmy8qdyp&U_!0i@6*|;B_Iml&e=;9e zM~5GcEFM=&HPWT)%`PyhbDwLb*!8(y`rnG}*>gM|9YFzFatd*#9S6znrz zoB2^Qjg+a??YoY9DjYnpcsT2Cde8|d2npOZ^hk$-QUS-^ZF?2rXd5meX04wi;NJM7$dDG}uiaWT zF;JR=S;qs0*VQ(4Cwy)sEU_7SDdD?3X$xAAc29Byzm!G9UH8;LX=~eRT=+z~pQ0T* zoE)^DY4@VenNLgJbgB9QUl+SJ1YJQh3)_+9QJmjSGg^#T%Hc-A5FcIM4i6lzJ;s`>9$ySE{xYP z@8XmyP>hLu#Vh!F-Q`W;Rbq@VbG_2Fl0m<9#tiD;dp73goqudc2S4CQ33v{+vF@xn z_6%h5ID%uoBf;EHXJXZnCMQqlAZ6iq>|DPaS*Y35c3G{sTjJ^AA1*3cC0J52{dLMK z_Qnwd(m$AViOOSF#&vOVCq78~0~(Zt%6p251An<}#p5ZU;yd9V=#kBX9X3lqv-A}! zIhA0@8}e6-`m$dZ`iCabG`gL9x|8kHu?h}x##MF$bF*Km2m}|{V4&_PU@DWoZ9Fmj zNNC!6-~i^3`!q8K19udT*4n9=)EV`wop%v01=|;pw6(QcTU&viq)OR*NM4rFl^N|0BbLJ!sF}C3HPeXJzJWF zAFH^AYqS+N_)u^(qW@lVI5;Qth-F+t{NzZ+_ZzN3OP$9H(kXvD8q+dEz7@2Qtd**v z@X@x9W;#!b;s$l5l0hoo{<5(kgV_Hgo408bWezC}CDb)$$~!BiKcv%WFRu&*t&%M= zPd*iEYU0xJZdwClTi<+Nax_Deegk@(#Nq+Ag)2KT{&1xnLyL}0>OJesWEoSp(~+6t z=#E|$;NUe&N!iaISYGsE-h#Z+lH(_;frTh@SujFOa*G}L#VlQ=Z{VWMX*)IRY6Wi3 zi`7y4!oWh-3Ga)W`WG%HF+HF5#OrLYVX^vQ!w$~VKJ1)Ohn+>Z5jo?K17f5Y8EaEj zomdsG6{i4GF*c$N=7<0s@ehpveA%*!OMra^GZe~s-`R9i&IS7f7We7>5I#s4ZUyLV z&3COC^+_-Ucw@iwf8PH6vcobdOtPnfS%}XxcI3<~E7L>AlKZ@foysqE1fCbuks~E- zvr+>JKvmk92UpLxtm#&3G1rcuEO|;&;IF$x|KSlfLv;inVB)%-Be?UDhLzssxYQHXI_b(Uzzj1%_3%o0WAPtzh(Y@~ctEF^Sm$28sFc zIICGetqBFoX>37&(hwO-VHIdna9O64Ffv<(^f0wjgh8bxS>2V8?EUFB)&2+45Ce~Z z80yMmgG#?#gn+Y$K&`T?F64QEGH)iSp`p%CdhOQoa;1F>pO|FxYgVD%o!975m()%| ztl`0^MmV#iK>K_RCT`O;wHekw_^z6+1E@cq9ZvgbKGE6J!43zoU_N!z+C0BJt+%(A z(>Hfv2=}qEb=Orq@8N(rs7=qI)Ge?elL%*bwq3loGlvM45Va4ex-F^6p>Il)z5dae5w&1sIP&i^dw!@9WNL48tkY5hxRg2>c$ONYmJ4c2Nj8IyLC7V#x-LJN zSt{SvhyX!mgiKnY^fWnI?r1EW3}THyo&fQF!1Ssm_~d+X!P+)QltE?OoD$dpZ3fp4UV6kzYPl4GMJ?UcPPS{^MKo^ko-Of3yv{wf zrCfR9WNxt5RUyXZEEb#;fYqLe3JnIkoV+0Y&rT4RNzOG13QCb)EHSf!FsOuUIGOQo zP}=b-NY=>S1tJ||!C1OmI5DLLxMq!QXxsCnQh_^Sb`XJfYU;9GGtlh59z}AU?Y<-W zi*^*`>CyU@UKHD;uoT@C*0PCZ6za&gRen~ftxlhi{{U7W7dhl0k-s{2-v@?ULmRn^ z4D#G*4O7rS(2zIff8`brqA{)FylG;o>NlBn?Q!K6KSlZnE}(jzo~OWf+&?|9JfDR2 zuw2P~TpXb+SR^_E%0lo7IIL2`=BqKa7eAy&g$5=3ZeN;2PQGPixFpN|w2R6T8e-V{ zw^J*PAexCq(snT7;9aJzYQU#ZulMy)X)n6@ycGj3mH^fK4*zH0#!i?ws!r9?Q=#w+ zO~CbSF6B5?=nldW6gt7&9PdrD?ki6MKl(IJ3{{MOtkKQ1jluHUkCX^0w~F!P#_N

      ?Qj||Vmin84WDP;IrE;rjML?b@k`^O>DpSyEPu$Sq~bw`Js^eJXK)acAvxC2)OWUhedA^m; zMob%6{W(3x$;YoEY_ST#rDUPYuRFTCD6vthhAiXfR!ltH(l8zwLVvbvIBU6v9>IGR zd8Bv>wy57cz8|jZQx*%ff^#l6Xs%`BV}uTBIQ27 zU93vyvPD>)@jFU|LBZt-@A`Go!6pV6l+d!(o;mNWWw4E|D z3_nV?w{_XyaZKbfl7d4CZ!oe4n=#uRLYi%^p20Uc7}P)%%Ad@!-LPQEu`s>Av5;4J zfLG@2fJDG57~_I1B=uh@1izN+BMJiu&&`kR%?I{<-YYw4E_}~{KyA7c;^M)kZfdsWI>qsuqg?z31!PFy-ILhV)dV<@E>0yRUP<#Q_`q*p z-KhwfR6`sn|Jn(vmK6#4a0V!!`um|14QCIx0vp-bt9MjKV- zL}lr3>hv2q#$y%$L4Y$^#T31O;x(X%~I9AZgq4E6xtin%-aWI4f;t|6yJ3j(>t-~8borr5+BW&6W&Gc3;FTg5F?KV1Q;)(JB zPMB~|j*Il1+4l0>-yQHh63kPaQ$TKVZcNLTM%e>yc>Gj0>J*uq4;!tw>)iz7zIe9$ zetuq&ef)$YOa3UasoR(>PecUb(^XamazSvzK!piJ*o=3QHMRz?Uhd#S)1!GAX0*__ z&h{#XGu(8Y;rYTnZ@)9J0pGv&?(jy8dhs!3GQILhhPsEa(=4CSKDN;?F9E>3 zT`n4xNw2^BCuxb6uS&fXW0tsF#Qde4r4HZQP#RPqxBWuWyyEMbe+Wt<^TqaE1J^S3 z0q|f;KjLEMx3&B@U7Iu8Gv{i{T!}LN$|Uy!ydC- zsqI1$f?33zz6hCjus{rj`YL$H9;mz>_YMgE%*-GXKp&oOJ}>Ou;exN!VtSil`$Yd7 z*m~kM%i=(Rx0=^9D`nL6!@8<~AuWEcrsonb?AKTF3DTvBaiQWSMS!{((5%N&k$AS)&Vudjf$vUlAlgJNK%vrS(}f z!FSXc&YIBqW#G^f?g=Fd2VG}U9ZteFM=3UPK37a7xP!}K1b(mo7p1#+_N1GjHI(XZ zub8{eb4hs0xScRjWMc^zI9RnNalIj+>3Ov?sDS&vqq*-#*I%EiT6*Gxa(GCCIY&;} zkJZlIaahA10tF-pbf{WAdlhX3oujTHpWB(;D`^Vzb-1hDWxOpP%K zCkkhwXdftx<$J)yW&hKvNvz?bwyk~e@C38_HzdnPVUWOpZ2>dB{aI3m)94SsYBs9V zE9#EiorOe?tNBp-8R#YkPbDh!%IwLxpWNSQOrK}r`yb?&Sa9g#S!OHW?H_q=B`}PY z{T0QLSzTM#J9~FmtO(O%6&s;!-mei0XGzxJPsKw~+~F37oxsIr zCaK~;Q7K0;k$YF@g>ZtIg)LKRz=hQeDFNr19ezkM$uq&fdKY{%H^tFyj>hl?nzS<1 zXlmv&Fz2c0ShxfcAV7p!mH@ro=TJwi5oxaJfPy3dA{U*tsR5> zUF`z{5YoYGU=0r;Qb}5X$(`WXB}w*!k~$OLQ!WjG8ZSRX;k{%ZGh{0XLEbtNd~H-) zrz*=*TEx-Rgv0=l#)3`7|LJR?!2rC$a4r76=|Wos^uQ9DClqKox7JYXU72i0wI{`rB z{hS~jN71Z{&1UBX#p(Njo?4V@IC~}AZ)AnJsP}6i7@;2>#crkGFYgn=|xl0Y#@P>bHTD1N~MdzMxpj;n(A*ozyOyRC5 zm8k3(NUmgR=G|sjhR#4LLkF^hd!WN`g0TvV->}@(UW#X^M|Kv=dve>;svr*>hs{pW zt;c0M9KAk@AY(eTFgx+!-;l5Gkhff>O;)o}cipa?0e?M9_nAYD5ui{Jb#%>8j|9yG zU{Nn)1w)<1)|#IRjXx+pDthjDb_^t)Ddo}+BoFz*HU&F$#56PSkEha>Be2^Wv=oLB>bLw|R*OVy^I&-y{k4U!l zx7bJGQ+3h_H`_;+S8sy{MJ=I3<-Tb;t`~uUQCJdIxGiEy8OE1V`Zc3GP3N~*7yz;?-}2I1!=FIArJ!L-bZe!BBl1Va5mk$Pp3Xr}-Bc=FkF0x?)yLz-61wEx1pNY=}DI<=xA?W7-@u52Z3#9fjRb z-nW=P*HCG(77x(3G~t$8NBmspI*8{=7ar*8R6Srf@@y6u!G<-dw=aVjl<^F!k22C_ z!m73PKV1(`&eUPec9pyd@j}%JkeI2vZ1y4zrD*$3cxAQpY&K&66-ooNzSQk*VUF#Z zN^)+XC5}Y#u9is?J%tWVC^1Q$3icWjnJ8Q4X&yT(((xVpaoRNIIEAhl)S}LPN>?B1@cngpI4X&w=%J62jVOGKcEM+CB z4w;!eZ0^-5%X+@-k@hVYYDqa=lDtrDg!$J~@1!}g>U+jpBdr)7N2;2j^+)s}R%6aFwu zyrfU0qtjpo$R7C6@pPD3^Ive)V8Yz88yTiwjiH9yrg*931{# zr8R!D$t_C@l^!@Dm^QR5oeVD!3?Ttx{{oihn`U?w-{&4mU)rb8npp59CN^2lgJr{g zU@OX9A8;bH8aTNl;8aFO7unZmBpZWI7F$1cQcFEjISv4h!VY}TwuS_04n$L1{(9V` zk^m8)&VgfCGT{R6q${QxQj=;QJ%o}XtM9JA4a_Ercg4bk~GFMT_} z_W(2?1>vz#R#m?NBH`%EyjNj)Iaap$BEEGp;_{Oj>7!-~?l_~7pk6J_qetgT>~|(_@zeuK^%gg;6DeYVozLp9iG9qUc?)!vFWF3xht(cVPz9|TlsQ0IqhvC$5Kglnga6<+ks_pKFw`eYqNv&JXG>#TZ;8z<4bC>_Qy)=++{@e2Bn@(S#>{@ z_^ce*61^#8K9OX6=(lIMNmy&Dr<)aGc0Wo3pM`T$q9%NOWcD?#O2hx2bC~@Ue2gMX z=@xc+>PO=E_ONHaz3w9BCI8|Ng(}RhI^E-6=o}o-?oYo=+H?4?rLEJJl2bH0fNisf z`SW)i{m6?q2kzePa~L_b>ji@I7gJ5{>CwTZx{uT*1YM%CY>#j+1ye%x zOuvqjTq9t7NO^LFit?EuGzPv=<{W3+j1>GM|_4>o=;tf#3j#CG|KL@ zzNY{JlF2_Q*d(ziy7&0lib!ye8XPQSU}R|8u#sn2WAmpdJevc(m|Ukqf<>dTHbikB zLya`WLEXA+TQhTb>@vkUJwh>{W})V4lwXefF$qJF>|h+28Fw; z5j8+1y#|NPCBy1&h|0lnYy08>&VQ@0obi|U-;Hx337VsA{GEnQ&M~W$h_HyYeje<+ za$plWl@DYnJdF}Zh4}ZN0B7fXNle4^FB*24xH9dD>Mp>}m4vmBTy)-2je2Y)^FLk& z=eJ(ULd3W7HMO+HPSH!2RRI@{dg4PS6;h5FdHPiuPq@)-L^7bb*>m^fGA zhejKis%Os+fiLRdWhYplH1xCbR*T8tj1?(w0(V^WdZaRYS=z|mlY{<5TLc9r@Vm2u ztwQQ*3`9{>!2IA3tafU0q$o&%&I%`APte{D@ZKuA+8=p)+V_`8WS>n&l1{}}jyIHK z*Yc*+!)_ZbGxS{MSR2g&uS{1rgzCT8#22W7F?(Sp_Sc>tSC`vhxmF;a`?(YNl#4Ir zg|`#=p%A?M5qvXT`LE#6I9RE&zY=9 zltV@cFxdcB%FfbE`y?hmst*eeY^6TmQ2#QQ&mLAP1v!F%qbhNh7piybk&UbC5$_iHw0563n+Nxvd| ziUj#@8=LC5?Ue2`6YXg|k*-v3LI);qhA&#IpOSc2Mkk`hOH1{A|2`4W;wdq#uF`E} z5lRd&k4^CDy~5}Y6Vlrs6&NIRXoBt;hdw=!K&DegXQq^6-h>>=Fw!iLQMXC*`x}Is z3wbx+wgt3qMt^@if)#M@Jyr6FS4us~!s(>kF#p~bdR*^xuD3#RDtG7Xx2Y?)vT>*U zYpmY_Fku%#RqO-n-ahT{@;)6EChs3wcMp!A0poAzZ*S9g)tv#=xv4$M|5#Q};$O#( zgj`0@#FVh!K>1G>0_X%U%{QbiJUmYqV7}vTCI+9e$Xs&6QxTQuPfNMtSu;leCHcyu z1by8oCn${2J&e~ieYgoye8=M7__u?QWm&0~c&hTvzr7T(SaGU{0lchi^rXeX+KLps z&(#5YG5ZWlg2;sRyFMjJDF-Am$bF!p)~`edB_x99_HEK<*vFHa2!=D!^?i%xxz<%F#Hz zFixo>7=>>+!^YIPhAi)l_bbQl*&LVy3?qz7~C#6zmC7Su_eBs2zWf)mLnO>;eyosV?#EgBG{D$9yk9HJ-43SqE ziKnAeQH|3;m8h%ewLpR%{~BspXrBkEbOP85iUe(<*-D!D8qN@SkCcKYKmMCMSH z$kxdtdJq?RsCo7Y@dZLeb7>h&Z|`iC&|E?~Xa9OyiMhwlD^c9coMTF!+_tFb+AK%k zE;NW>yu<)kd>e!788+T4py)J-46u4Pja1TQh`T&q%~}<6cb(Kp>!nDLH2hOINLb$T zZ9?3q42^ljCM&1I!Q1Yc|Ht0I6I-o1U^-~SMuAPn{1F|SY9RF{ zHt&F#YlbpnTr|R0!*7?Dj?Q5EL6E3*Az`rG95=Z)rG&z5l&M9@x+!tnZ%yi+;rEhg zp3-XuJkcWrC1uOOgMyw3xv@iwj?jA*lvgz@S_dtcpqCvmZS4 zZnmq*xK;aoeFb7xJ#~h#Vh^`bt*Z~|m?U{o^{K^(rORGYf*x**Euh5im~e zK|m0`Iebh}YES9Xg)@F#Sc_hdEM_hW%%9KhqstA5$PIYLvPWhABeym`60u>UxSQwKlv zMkS5r7l8}qp!NDGZ^P!w^Cb6`Rj3$yY?xL;lMzk?F6ghEAaY;riM9tL>)Rar0=Z@# zI|+uI{SBE48CwxHdFh6jU*X=!?q> z=bkO5+iQ`rNwdw^8-=u=yTg3&rOrPtORD?Rrsr350yDp!^RrxV9onPFw_M@yJV)hH z5TxD>L9wI4ZsWVNgr5^o#La9P4rhjyDe4XsHP&+Ay!OjJq~(Y@#lDeHHhd?0rLauP zEm5t0@^MVs%u{3=9sahO)LX{zH^(V){se$>v-}*GtwStDG#QJT{#Iv;1bK^~+xM1s z*QZBpW=ilBw|xEI>OEFRnz0%7JkZp8-oxgRXVIzJ5p=g_b(=H)-dMOyCo+(K|oY-8xr-;GxbQnb&; zML7ze;_E7)C)5|yLRh2~NPTr_iyVEt5k>WTa{;iux;_&{^jW@}!40FXUwed@5#49z z$t&>pCicqf;c)i0Kz?=KK{e1jSuytQ?&`ypTvUE;U6o~39NOc6{d@T;w6MhsYNnZ9 zqR*^cSlQeo#xsPo62p}r>oHmkal@OCWABH47%%dJqmh`ts8*cPf`5-|QiU5MCK6zw zUB=NB&83`<{Tk~0R{;Jgf`E`;H$%hfneMR||DV!vqgSXUScGO<7a2uNoYDNpsw+sH z)+*R?Wg-mk@LD3E&fHJV2PD|y1=6L8vxd!J#fv@&mWy<67I!G5<{iDvqx5^(7<6Q< zX;Tu7xRUL`_Rr|$7-%m@4z*0!e{bYVDwdS;iTYm4~z*{h}IWF*zMD1`T<#s&8aqAHxj#Hpsu<2>8qmr#EJNnT)jKOpa3{=_i z52-G;-0^9m^rDq-!57z4aU#aL@}%wfxqj2@4Au*5@2^Td2-{HUY0)(EiKE>I(L94q z6^&aSlhqCQ<_C57R2P?*&d%P5m$oQaEM6JS1NZmthtXIBJ@ z%qM4J1f~9=X_4*K^gczuzVeg95x+v4!w271sT$QL+MP{cq){CVqU4nmxt;z;8?Q5R zoQ2BqAHGbQh_VGlLH~ChMupy0P-(pM-J}xvJyU}9tm4k}BA9l+Be-F7d3nh(^);j9 zk589U9;zcn>{{@q%efgT>Q{8@;J#aCTYeAQ0mPswNeK<(2EWGRCO~Ng zj<~W{xbB?t*T6bOn>w62VPbX^!PVx09|Li4G-yK9O|lY%PLraUFpa&p^_-k>zgEm_ zobd~!o!m4xAE6(HNN0TCZel;sKes>c0!8LD!c3udQShpw$43=2UE;Sjc|CN9q3mVh zY{zwWvGi5AEbBr@p|W?ZN&xu3*VpQBSb z9s3f;NS|Fk9)lo<0%SO_bsh9vH8oLxn%$;1u^pIuXf}5%`ZKpdM%V09p5Y%-;X~-O z@~?GGI>$7A**pLMD*=55)b9Y->`(`a#1)?TFO{*aR`nk)F)z~f>#Xh|9jJM?pI^R; z>Yp^6Ii9+{CUFuBSV0n7X3v$l%&(K;sQn@*IwC6NV||X93h*%LIPOTjHr+{hCK)Mc$rc1!amza)Q3I4R8=luCfCMA#?34(1PWMFS&` z`Dn2WYT9<}iA*h$I<2miau{NO%%USmb6okC@VYz=%8L~X(%V<>#{|{jv`&wWmo?<5W9b=!sNobIx{G{%-CwC6RIRv}3b1N>HW?!0Y z#R3vok#)RitDy*O%)}e%iGM`UpexwAzFBRTJ4XqDY~&uoX}JZKXMT4qxk-FMQ5{RH zL}3wLoP6dPlHa8p8t~O^DIJPorWqS>V-z<+mu_ns>?QG7o8Xa0Wb}5KxE}|6y5>OvKW6_xg^t$}`eu93y-%^iSlgxC!Q8t3Nk(J< zE2YvNmX_qWxcY~D@4#w5uHb`R#1B-c=Ij9yMNKNnoE8hIVrKSJiVEQ-a}Wd6kSQau z56OPaf_1TbP;Y+%$U7}os3>t>ku9`oWPZoYVJj@ebO2v(#il86?4$be;2LW+Sd*fQbV(wSlotv2Fh$q=!x2FBq=Y{9Zy+VTy;KX>V!4;uy<6MP@<;7G& zLSlofwX;(~{j0NRW7Im-n|xer8EG!lHhU~=;#%noD0#(#gG=h9WWcAR4=fB(v~^yf zmmWs~Te|%2@0S3isQ+yRuXhKKos4Sf>IJib2+&tY-d4fCMk<$AXkF9L4-wz55iUte z!WXq>ILjh3bz|mkpivKpPb(raeg6De`qJD%!oq_iUTsTMsm%m4kkHZ5MI)k<#LsAS zz9aK|8FAKNwK2${)b>N77nteL$Bt08h6Ul?>(ey|UR(c=6ye^m-J|97_C_o1 z%`er4uj*wSkfU{D*A7a)wjD}sbdH^?h+>M|naaab%Xiq{-IF9JpA8bfv>Islydvo~WZ*)*R7Bh|@pn zg*oN6Nl@L)3aKH%f}^?I^DgeH9**nd2vBHrWUzRi=UL?Q&+rh_P>5Fq}1?tId^j$h4eRcBE+g3G3&Hv2`?Sx`LhV!e6d|Epch#gKQ< z81NH&=X)X)CX5RSlwLE>4Kj3N+7fcRrFoR0D3;6E! z@rDLRjBC=nredI^bX3+kh-;lNz!8BFxi_dy6S(4u_j`I#Ga1-d(JoqO_~yyL|IZf! z^w4b<9379$xe$}ss3fI=!l&q>xMbR}X4T%OLW`x z!i4$K)$rj4KDlg~BlVi%=fa_$^Txbk^q~M2-FXYt^<~nlI)}hvrOw{olABVSsx8(j zjg|asg1N|6DRjH<+#VXzrOca>A`fSiqma3)Qp%Bp=5`Lv|LPq8=~T$w^*xdz*D9@L zVgiKNEfZrdl*E{pq;;`SmGt|}_%9af)Vn&q8Bhu5mtp5V@DqCS@j`qc@>h1C2i67yk z`r?2dIW;Ov<5F^`gzdQtF8K~fwnOwwhY+m9kFSDeQN)hXG#a8779=D2vZ%9@y0*ttrzoA>;}=ji*RsbHnX{}xe$53pi_PmL|8GlTDLfGq5^&`eDP(XPP_A;)aquwZmNj_ok8Dqa$ zY@HWU8QfyKtXq5=a{L8-kTC*t*;d!rT==owC5<3+9mjjYu*cjO5sjAv?Wfr5tcH)U z$0lTanM#xQ$lZg8URB>=g8~^BSrHxyb7#YvE8c6+xiu=1W3FBQ7nWPPy8wn?@gvi0_;?PAjPbQzD?1NQ9<2c+8Vtc&8U zmDAQ->z2pTKla#r;nYhGW&gwEBTYCcu+T-K5xuIbMm*8lv>o4H$@HnQKRZ;Uw&tXk z+vLmbED{?IuXo8zeo;8YY9No=wKxqlN`W*EE@~5^U^k+J^lHf1SI=nw10K;m8f2@l zlGvaWzdb;B575IXR!u7_RGMe*5mS{2>%W4`I(b20Wy2t-9W8~WMRQrgELQ?nbJtYl<_$9 zclcvna`)%umUlajINn0`;YU@;L&8&Y1gW(lKzw<#TlZZcxQW5-rtB- zrN=QEW9>!tc1>nk)Sfu|f>P&Ycy%6G*e!Y-X!2KeED7~ljio2H{uY+*E=vK^(lhI( zt;bqBMBtTJgtOol~^Nw3zL*U+|>iJ#EOU%U6F|O2!=Bov3GZ~Qeo{i7?!DvItVp)UL(kxE_*4J;a$>oZhq7*GEF`>Ur1yZo2BeeTI_@#4*V+J^RY z>c+GChGQ0`1~!9*`+3B{bk(Q!m54}o)#Yb7tzOAP0r!^zq=kQOxhJV?V6zGQ=R6xyYNVP#U`<2-H)i{ zk-?pzDeQ}n)!5nmgPp{`^lmuAj4vgDSTmrUUV21v|1Z7l6>R?i%il;?Sy}56Y;$SQ zf!87bJfPGjrU5WYn}wC`L~VRplN7%&IA*g6V#2iyAc;xAfWytrymLKB&`0G!zB)bD zgGm3iOv`!6PS&8e3B#0}3*AeT?C&FBUwJvkPLl45c?{|!6e`#g#1{ArdUE_+`vhyS zi`oZmsEyZ3q$qL~l=O6~0ygKe0sq=)GaLV)7c~IrOzcbeJ6gVwT<3Y_TtjrA+Rv%Q zz|-auCYgHUf3LG=y*9cHjKUb|w#HA9l})5n;j#P4MMn5k=xp*PIF;DTH(=|gbPfHj zdEsjEX?7-Ik!D))?KjHktpMbYpVYWq*)CaG!TKwVD$Yp$-Dn~5?B@HH1Tt+PF48X& z-_jEX-HJYT&}SN9XduIzhtWCbxXg*IXtF8e_!JvNIP}~z_QyETTy@X<#~yDyS$Upi zOvC5#&Y&j>e^lNvH^s|;`R$&2Xqx!m#_~_i{_#p6_p%FAb4r~nmM=|B%HT!B?oV%Q zeu`KDw()CO2j@0BgZpwdwLjH`m1POV`IvDGo2?6Ua?M!%*(%z&Tdm-!rQHGcsME~> zD%w@$7`E)(@*AmnZ~5zS`CHB%%J)YMfM3ce;u(nC{AuWz$_Zhc%Bjrp^BGL}d;w2` zWS@6aPMX@^BP7M0)iJ+Xb^+Q%St^&kJXix2?=;TO)}QMj1_{)xgsHkS^lN9*i;aMe zgc@LZUBlqP{Wq<(FMdl9F2yMExMA1huLTQZCyXC5iM+#OA1F@vU&8pswX~pInqRe} zoKA(0Ne;Rs38o-HG<#}?*&ZSWI>6;RddU$RJfEEJ-Y&M;l)M`=R7nee`)+P`tl##b2;wLiZY!Wp4MU`aA)-=pNELE)t_5G>cAe zDZN5f(^8(J1`uME{@oKyyEEmjP^8~t} z^YKW>?y-MuIHke`X~EslR_#nefe^2Dw&>BXUrvy~y!ZKr-hplhhEsz1sX<}OOFp_K zbCxi>I(5eJlHuEab1JD)&F;C>W5*%`o!TYD5FIEF-8MFsFVBx|lg{NouSLDHmh{Zf z_48D4OSt2iTx5|(WvFkBOtY4TC`O@%Z!{N_O~r3cCz~b4_@~tI4^sue%2{C zvq)m#$_*fm0b6Pbx^KR(;=0e}sh4b`FLzVG=sAoeRF^Z|>A?`P|5Go69GOK=I}e~} z@RO|V`Au|I&ALr|mAUoyZL_ltybl@#`zAA*ao8{bx+?eI>tKr@SZP39h;M$;*m zL3SJZvrmj&7~7dct@3Ih0~-z+|zfo>71__P(eD)?!h9dM{ZE4%4vOT^9LvU4=Cq86tz{se1r~@A%j&7&i7=OLEgM- zhR?L9LgkdAb&0PZS_v$WS+q<~2GH6z&(^L5U0c;`JWpo^)4o6L8;dz@qhwN?Zi7;O z0n&-+d(_@BKX3KmQSEQ?7bX3$YnFV-@3kXbvlz1MAQhd_2|K&e+;jA;&WR>CI-%KVR}zYF&`9&04k z#s*)1?+n0>U7-V*KZT0$?c2Sgmc3)uICkE2?z)2djvzWp$A#?jg#1Um<$CicNT-ta zJk!cFx|FFpNzzUHqn-{+pZ(jyjAw7IIdWKCbVA?OWZ6q@L&*JQJZPp850r9;;@#T4 ze6@Ylrk)_&nq%kkK}YN9zA51ID8=#(khD!$a7hqGdo$z)a}AX_RZV#=*nU!-fu~7E z5i5^&;N~fzX4G8iO~X6Z`157yDfaV1*?EKOdoq1rwX&JiJ`74x`bv%sGIU3E>(KG< zm-wbB15-0j&DWhos!B193@FMH^ke*e67Y}ZegGCMg$MtaPIIx~-3~y_G9(fe^{;>; zd^g=;6?SHW%i=f;j+1W9Rdd6rV-YN_^r%T2ohKd-o;lbe+?@3wvZ*@ivy9ClgLO%Q zcTqxkx4i^Rh>w-bbak@nw&%Il(~I2K!1R_gp9Riq4Xtv+I*3Nw0$e)~G#;=q%#0F; zO}>}U(r4mgh?xz~P8HcgU!#OqVzfFaO&;+e>$vu!T~z$#2Q?O{HfWTe!w%W=a1n6+(MMqdt1RU@>4f-8mh?<>5OZ zNF$^9WW*hp@oMCA*3o=`fOJl8*i}f#3f%?CptLoe4Xzd~Q$IOcdR8N0dmf64$nl}U zHZ|tSOi>(tsrz7ii5)+FiXh?QUtXK~;BQ}dCSfT*kVx>=W${Y5IBpEBb#=oAk>vxs z8&(5=z$yVb>QNO9KbJvZlGPg0>o3ivqOxoFk=AG^< z@_!`1&Hu_aj{V9x0#FCDTnY;Rd4w6zj7>}|ygR(z{3>72vGG>YYD@1<6?Jexcgbvm z1Ja(HqB)H&<^7MdyVjwyQ?&-pB6u_O2SsHET+^PY`pGSRd_J$83*6;WK|drl_2f7i z{~7xK(1m?AXdc4-HD@%6Z0NKI8#h;VaY6bGKxD6tU^}OK#d+qfrikki>X!R!>R_wt zaANzH{rOPCHQz-Lm&h3XDH4@x$F06zc=7qWAa#YzEC*)=c%1{4VI29`HXV!d#A|O5 z8)(W{fc0kvHFw0TpThCNu{N5&qbXocN3!jTbaVxl0h0&!{~AW{Z(JYq_Ar)l_P$}F zBcym2)`&4ZW?}9()l^!w^6M2r!oSfZsp4B6h&9|ICMNnI1@yxq1wu+Y;e#9@4FS>i zAqO6`-y7X3|2u65x`*`BcfR^l+Je#Wp5W>IWJ2z=Np zGDCpXssNh&qP8-BqdHWYov0f_qe^JxDE($(Nr_MZOLkk*u3FSwZ&-ASEz|OXc(7g? za}Y1<#y}~Hpa!q*8W($WC;S^kP#jrN!x1BoyXi;GTcy7bOhNo4r?sp6%cC|qOW1E} z1SK?AGIqX*D=e4%b{8bj|MMoPPb>mzfD?pMJziT?jBI0-7euzx&;MR2R8|^^zRVx$ zG^jX_{io)-U}-#a`@6~8>&3SB^%QTM&Li{QQ7fpA@MbuG( zAxhVIGdX%mX!qI~-Hv`CgF3%Zv5G#7qVq^KyZrdOwt2*U@LHNKXgk~h#+kw57*p%i z(73uSlr;s>K=2H9)~_4&N6L{mFMcxp;f})rfp-*Fell)FwymNonAU7nwh~z^p zzEuS)swY7Hxsy9Kb(d*ZF?T#=G!;^HbJ=>vGk6N}|Crz}C*qa6G2a)L$CgGGw6p81 zVrH1yN>HWp@uKKL!8^D34N0y^3RwXLOX9wc+(!iw)VLW|MK+|u--NbP%sdVLeslQYk@4lAu%aOz3~*z#5>Vv+?}L=Kz!GzATA%C61aM|j4(O;qX;i$Q0% zb#}7q&GpFrOMV?t_zsQPE}I?2Tg$a@w@H@Vy!XM%ORi#B!>eHdOswV>^#gNefTQ=F zTDl;4&~>?6u}rSDz~<|piHnu*^&B{Je6&7p!oBA|SAI=YOtZC3I1uNhGO`JOWomdG zF;U%0OD*yC=gcbRTn`>d2@=>r*1g91!dD_lOzCZ0PMLI?FHuQt)1VbT{zHHznKE*O z=liYn#IPO)pJe1E&IE!FAG@o*d>J$RvdNN-l-_PHvHLB@V zBp%MWSztNtJVvw3prE0!7bX05vW>>=8({p>T-{b{UMU`KP3aPiDr=sE8W$ne_Hb;p zbaJxpX#!D3OhC@0i!-qKSR40VbiIj|!4&ocZnuC{_~#_UILpPzE@www!M8Fvcyq5+su{sz#69A|);EXuyDBMcL zilARoCy@s~!WI5>#N%StF1M`nr>U*;36K_goI#S`gH9;BD@6oz(Xx$^ z)yXL6?GR%s+Lr|)3faXe=@2<1DJG;Hr}vRrwDL0M**Ksw`0)J*%t&y+GjcUos*)93~k-kl=| z@CFRrsh@k{g@RAVlp{f@lI_0xje?LUF~xYxp}<&|bd3`^;uQ+#(iQ4)yz(U?vi;8N zS^Y67@R8uGhdgin`5B`Rft;?42Z#iK8%n`&O^F3kI?V>Ov;kEl>MCwziRcAD6Pbu@ z*&n<=Njr>4#R>w{vZ;C=s@oV?=2=TI=!DK)rGSPFkNB(^_;7A+h>2B%2Wbxv}_&V5Ja#tq~dFSMVA6*zubP5bF` zNi=)ohp;qd*)6Rs4~oa?9k7zqkAG}UeKf+M55gmBqztpnW@2%S&Oi9)!0J`V>>g#; z=XP9Iq^UbXB}jL$zNG04XR)NJ&Gq~=pM{wuc0>qa z@!Aosu*hM&T->KCee{EXq2`>&`5_1mehR9 z@FbfYv4pr}Sh@DktNL}Z2M^42qd8hUH$_Z8;#2>LCz>w;{~I=N9Xo{(-(Nq_>|-wf zE5G61^QHmEz^K4}ad^Vr5^W94dV5ccdl6{(QzT@4*{nV7w^tQs#s3c4d)ba~a<;M3 z$c8kc!_-ETWqsoz`Y&7ld6>{Lg*>gqev8GmJ4U^OMG|!&Pmq)bBfb^77~N*#!jF2; z7iMtEO9_+JY?39CXFTt!6gig#|4PfvLfv)NTn?hYX?zaRzI#{8_MrSbKcG6yNVu{H zNm_%uxz*i=B02MMt_F{!#ckcpZ!vX+FDOdTwuo(o);9R?|W@ zgAj(lm8+{~{aDqq!W{$({;O#^$vGg~>0o>6trt8Sp;7KXJL+WBvlLaUQ)fklBBmos zCVTYVRb~DwkJz9p1H_}8;L!I@w6%{LSN6`{HKk?8l1C<T9`V6y z*nhHjn_3n*LXK3PTwM;gq#Le%;#$tOUT+IBk04&w`B>r#`KBe631)X4ZzP^IZBy#% z0t;%+9{c3)GR;9E&sbC66|F61*a-{D9j|My%y8mPfc0+uBCfHiS;5f)8t6R0l%P+X z`rUDIWv^JoGYswxpf#HxBwXrs@Bx$5cr7s+C(8zZQQh+!XIj{>NDmC+!i0(s*>($; z=VVEK6J+9;h0oo7v&8;|u%8FIxJ>}CMet^74rx?!Ep6&zGuZ=5%BVcwlYpl;7RaV% zd$(6)VwvJpI!Wc>V7KxXAQ8xq54?lV%owqC1x&X*6&bAIq>&!Tb?XwBQpPdWIznqu z1yW@l*Kc(N(O455jezk1z&Oy3ig}c!1j(nx$QyVLMkQupgJ{>vfXkm*Ob$zxe|~-Z z*RiX(V8Xt*upN(*Ta{mOxC1@u!-erkj`(GHZtIY)g{PYGYOWP^1lu%^@@t71nb|@|4C! zeogLI{I`yJaj)`P1a_rOeZn~$3>!7FvL_y_h6h^B89D<|`Br|K&#s5XgBx$1 z@9RygSOz3rBF|SSY_!U+(yvUg>NC0<>$D}0>O}T3 z>*dgVzEXce?PXjkPiZLq0Khjl07k{Z3>5$&JGjCCHd0wHL|@GwylSeq`E@oOt|yfC zI#Zy7vAyc}E|aASoxLpek_ap*e^|RUp%z!Oa)Kv?-q}LHgSkZ@H+I&sI9@%fx_QKtgUO2pACy~khPe+y2# zUH+w@VQa#8^@4}kf=R8VFQC>y%v>$&ic0J3$94ub^{_Lph$*)toqBga1hg&GD68zWi!DMAu$77PdSRQgi`Wo#XLDU8Qo*oe?+pzyv!tLXa9^%EJ zd;4))MXX?R?>Schs)bmhE=(-6mKJxuP`*S%m4S2_?3GSNzrFmISv9}V7 z0?sZX($z)u0DfwK=Qfcwa!tl;N{4C7oom-8&(kjJCNfU zkeevm9tX((wEBm*9!|V^MQ9sCvY2EQBkTCvpv<|;U_e*V6e(Xl_A7#AJT}`o%QM!2 zdqW{F1A!g)^@P(V;c5_gAa#&-RN`Mqvb1?FcnD}>qA1{}5QkG}jpp_)*92rF$Ign# zI!ji^WzYF54v-F$e4i#gq(LeB^OikL3&J%y^qR6wUDK>K!u+(PqS?;%vyMSo&OHD6aX79#l zB2+aReCRVlk+r!tGF#WdmS4rO+g0ePTSdUblXbHVlPpQxG4$l$(U^U5oCda9Zc4a% z4V_c|bax1>ujPk^SP{^x$fTAp2`;+Mc>2}X`4dBe!ph!0ZqNJ z%lDE{g&_H9TLPz%`uwd{RZD6??4bPQHStE2#kSN{ZqOOD?ik?%&8dQsbIJFMLNCD4z&FR80^N};Z}WP6Uu7|5i6Kr52BKsuA{QK+x>qx zY2cM*i{rg&D_$LSU4hv?&|0m;j?L3~f@t(P&xcEor~F*M=Ti5V=pgZz(I0C%k*sJ& ziGo-c*Mi>;21F8-NcK`pl&7coc>903^1>~)^UbVuFg2*>G9xRj#ZODg`5{R^b^zP| zbAF3}ub(#~>uaTkkqJQ^q^#%*kYP)$+nocsdoKw}nC;}YbSZuFkdv+(+uJpfGUtwA z88P3>d4j|orbkO>dU8MJGa{(BO{U5ZzIUI`zk@if?>LDr)%J*=^IjWd>RoB`- z7#Q~}HkHnipjpX`d1^*9xI7=cCb7`Pd@(2kS-C?|t6{D%EO zil)G5`ZD9mBpdcIioa6Hxd<;JEe-hLih3+&ZIDR93~7J7}kC)jaZmnSYeU< z{CYA26sguk_{uh00-fN3$A`NsLoxiAB%Td!Gf|;|o0zEl?mDHHO>RN4@oJItYA3DSeL6j#P@k~8)^+|{g2l=!HOU1RMM+`yiW8o;#Irvh-JU+~x4 zr#u9AS?|4dKSK*%yCJjro)1787@Ng5(fw&XkySX!s#LE80dhzyJY8 z5{N$ouma`{i(mMJ5`uM3z8%N!VK?<{OWsHY$=3|`zSiRo?#j1*K?atF3}He0TaxZ* zkcz&Nv9MbGcK!zWYhPaXEIO|@^Fm}12uM;`b_oZS_zb~!DCTMX^isCz$eCJDiyXR_ zpLk6DZ+Nb~MX@ZDOeS=fuDgdzLQ9i_5s%RKqhxtrF@doWUvGzVx?u$Sbf2@blYq)4 zvmFpVN)fg-6dyHVTfwmc9zH9UGB3BKEno7;ifHjx5$yUdL-v{JV+oQ)uIt|u61p_m zb7uGfw7oB&UD;#`#lB(jhYx8Km&6#!Jpwrr8R!){=j{Ri>WXZF>c*Wy%R9j%Kyevn zHp1^F1SP^RwB|bLY8u4tYGl4aH=r?!a7G5{&FeOv0K@KCPny|U-oKi_&wPRBVr|d& zTp$8pdj4qP4no!rhfItV?-DLe+@EpB<^E&0;TNFFRl4yT|NX#y&=Me_V!bi*;>Yz5 zj?Q!sSsKH>-!d2w(58T~Xw~%cH-3d_ASf3iRo%ptdTn3c?hd1vjfv*KMQn_JX4wa@ zrqf{U4;Mrx4Y-{_y!fPy*1ikx`+JV4PdB|mN?T##m&9na(j>v}W5SPU-4J)f3+vAT zu*5nj4Qc@zg+0SVO&ae-p|tj;oHhfzh$mz+WeB{sH-W2~c#3m!;X3q35^pxaI~jrM z8-<#JsgGRVi4mZgCXNc+!&WxIzw@@yVcP>wu_)%W#b2spKF}cb%+|%4`nc*w5e>SL zRMxAX|JP0B;_BKF$^`rrV0RlV|M|GzWBn+1UeDee5kgwbW=LpDMzt}?zpih$k)qX} zA1B}_%^91JK#lM-xHDQ9Hk$mbN&7BFMCuv#5;5iJc3hD7U`33%7{T=p4fBvdRm|wX z>ayJPlV6bJ_u;;4XP=WUv{}eO#$yTbNO!up73{Uv~#(gwdCEb1&0MJl@y@HlHXUoD%`Q~WlaiADkhvo z>}Si8{cF$3c8+*%yI&S4vkzdF&7K3pa8u_-{2e9XAta19yTy0Ryu);_Vp@L4^D#eN%%?1!fj{hp1Zr!}OVomesZjJx5`6{Xgl3 zS(Vw_7%nPbrJ~P#hXs?#XmmQ=19|#FC(glgNq%FE@iRYL!o$OeMj@$-z`6C(d;=2$ zKPz0eYzl?GHz)v%LS)~ZDx0^GER*c-wYt^A0%(im2_FbfxZ(z1yCffJ1dOSH3a{b1 z{T!Cl4FPTzZ5fy%1r*j6qUQpI;k2VEEa={jpC+? ziL>L$zn|NE`JO*C!8nCyLP;zQSvK1aV67~zu3CXG8*z_M&$m=-c@QG_Peg#&HT4&O zzzj2ONEYCG=suqX$$uSr`_+^Je~I4E5G1}cKCNbnsxKrLC4-I+d{%a5e&K=ln$JY0 z#%Akf6@eiRpm!4a=lONN5`k8=Xrme}dPWQJy6ert2xd zHx@O~cUw>$M>S5EhW`n|UbKv^Q|b$00j;=1CM`4b&ukTqQ`IjQYt-qYzmom<&*0Bjel{?q zd3v6dcH1)+7(6EZ@X{oT52ivy*43CzE(Gy6n2T_(`EK(hB;}ReO)Pmn4A|b}qt5ok z#cq-(9~Rj(66wliiKvzV${ZU0Dh*ijH^SYDPi6jI8W^|y-ekiL7y52@j`sRc@N+)z z_lePmV_W2EiN%A*z##neKB9(-l{M)963P4;_GMJD!}oL3gB%~p4SVzXTpeNBzPImiMxyM+NM9c~c8@OeP{JCbJ^=|Z{uj7Ui{{?Vt{-Mvy! z&c41u4W-l|+i}L3Mz4$mmM`xEt7yhm%8|~(hF9k9pb*CZ7EWblEqAS({F>7I&5*mU zTiE(>34}j2f1N$e4i!_iay-{&jLX~LC`ZdhUe!_I!DY;vJHt{^wL3%65F3;^^mdD~ zk4=4O8d*%^3KAEQn7Y%(2gO2DC~FRZ35UqX{J8@|-yA?}XiZTfRQ0!Xqw5_eH|B%7 zEX>cTQ6lDB6VNA{waN6>dH{iB*0J&B=m2T2J{o~Mij;1zWd~~I3Ml-}Tg>!Dx}Y2O z<`#-fQ9V~gMKJP~95sEikFBfa$)F7(%*n=>o1dd=go?R!Gg;r7#=^P}kQyM9e^vb1 z+FY**2+@rR|E_y~&bVuo!%da6MN97&Pflg_Q{G~X1K3CR+m1ksOfE`*bfAl@{IKu92_0+cH`Evv&e$LIGmZsD)!DT8lfT4>79{%`}?qz$I+E5<7D!n6h z@>)~%e3sfp6z*}42ES2D~?eI&H*z!(|u2RNeFWLj1m=jSNo zY2<&}TDp&pUbuWTEi4CdVh&$Kf@4b%p`4>oUbqj$KlsaAmy_dQimAtudjr6=eQaZ- ziAa~dYe2@IqNJAiN*Ohur&dDxN>d*LG#EPxm_Ivo(+j&SvZ21_ZpmqR0iOe(HU9~i zwwR;j@@t;PQLb~b3=7V`;fZD0^X--A^#tt*CPZNMhLT1ewa5p8pohM?^6n8cs{Xb} zi-MGKBc9vNoj$_N3z&<$7r6rdFAPd+G&We8IaJ+mX;<>@YC)*I@^wp_5X&Zk3#xig z9!G;3!S7pTg0HFRBsj%Vxv{G4fo_ZewR2G7U|e>89F#^zK&cz0yPQ4D)y{;euO*Y_w5;iUYn(Q|@nEpZ^g zI6UuJj)pxH_8ZyDR?D8u_gX-9==M&*Hv21P4L8SYEP$EDmwbEJX$jAzao2{a6$r23 zDE8`BC}x>a6F;r&Q-M1}DVAMgS#GW8AsC4BBMcGQ8Bc_1>c# zN)Q8#QfUgJ(@2c@lS8<9B*2+++yi=^WE+gKuQV7B-g z1HHtKS1Yw{cF+fkeBb9|;n+~a-g*}iNe>9sKUYkwfXZl<*+IXP8Z}))~(E0E0i33kD z1A_q3K1+YKpq%CdLATHAbY&fj*QD~upp6IQ2$G~&z#h5cR4edxD679W$|ZKc%wzJ6 zo_p-Jk3q~*Q!qJ{0v&YRhkf%Dgy3HXcqf66egE+CT3VD=>4*?`p>Oj!Y8r)fP`|8v>roYTmvRnuRQ_M<4e7E z!elggdZwN3rB%P;FVqt4B}sL~9s?8MsHJA_%Kro<<4sbXEli=fJu}s&@7K@%q z1W;~RR>lReM~N4Y$V?ixi>!1zg8lov)@oi5jxtMQ?!1*CW1*hPECWTe0k! zugB#`DYrJfRcbId+duP+f zCg*{@%7vA6)Z-06&|R0`P;j1;?v?qdDZ>ig^%xCSX-G;W-BoM~81%i);f}^4u>BM*5 z)xGdr%>Q6$Y|@U@!s^FkI1o=ep`{+b=KDhD?Odc@pvMY?a5 zZEN_C0z8(^Y%91y2Ti;^+`p1bzBy1S@F*Sm%#Qh;aA^9TOt}LEECIl#29KjW0ogwX zWnl568F%_&fUn&=Ez9`ddb|Laz!C9@LETi*uf`KC3v|77rAjXY<#3f7knm|fuHAey z-dhnuJZ?U%l7NNvt#LuQ*79yXKOWX<;1(9HVD$JWS4Jons`V2SoZ)UEvGA{$LR>5h zbayM@;y+_k-O9KP51O!Nh(j*mQI9TY>>m0dnVYpJtmh2C-H78Cy$4Y1W#>4=d(XgALrWRcr^uS1Vb>3~Wk+ z8Aj@So+L?oiE}AX3KqxnkW^V#Jr$F`q{vgKStxxWR<8zEf zZ#4Pbpw0{7SotFw<7}d0Wa;4&OC(SS39IrMmOFgph^AB0s?L=B;`?p?pam(>$T{8@ z0n1j?Lg(Qyz3&2+3V5>ti+%|jOoRKCRU;vK6 z*_ibA7TO=pK{ThVj8U;#6}YYVXo4hnwItH+0-l=$$i5Djg#tHhCp;E=hZ|8nU=;VS zsXkWn%06?)z>rOPD_u+bhr#Ym3;UTsu=^;Fd-~K;K?Fd z@p`RM-n!n6#Zu6cWn$D>*t*Q$FgKrttNF6J@R&u$1m^Vc7r$Mt9zL zTer0hn{FBlwu9_?=ZSh} zl+$5LHfaLgs8_R9OuDTh zR;_cHflX;{kbF>eMPgkKfM$=YKS<=>vdo_SBPZB-pW`Z1_$%Ly$sON5^B~SK^gOA;LnA}?O~g2#BWe~h z7H#z}h;$b9wdJ*03`BazZyqU|Ieg7?(=k4BU3TsCdc@H@H%RtI#Ym@$w>r#y8tA&m-Fkw#Js zo6-?Mh-6`pAz`y=5TXsBwwu*F>J?yFVjd7Lm2ir7Yh&GwC&k{k7aQ6VP?K0?x4@3_EaNCA1 zna7iV5`K3{V`n3xW~i=8VU#P1mt9CZ;A4l39eGP!besP}PXFll%P#QV8 z!~3>!M=;^iNS<0_DS_zwnBtgQlWImKBplU31j|3(0os~m`tT_Jb%xba&8+x8=M(yqN1zn(K(fhIwEc}Fgsa8dg2F=NH z)@y`l_=Q2Q(T1_X$>_0UE`;$YAPR1oMS5`*7y%DHCBe@F3TUpsx#Zf*;y5xLN-(qj z{p7|tk@e35Dw(?h&2djIaF0l>$W@zVXEMrW%{76ojqPK95*CgRA>wruX|-M45<5Sq z&tD(v8pGPR^Ss{kG}bn)>Asd#gm{Lhd8e{E%?Gf0Jl#9%0g_t#s}yo}E7z4bru3To z&EHJaQnMt-=QpzJ+VNR71nQH@dCJ&if4)`#Dq8^oy<>UgMW-;}r#RFfzsI3m;#uVE zoopRlxc1N(eN-?Xb3Bt869Nd`$2Y!G(LEk3mQLDA)1D!7AAzQUXXzgJJ}@PN)tvIe zA3`vEve6#X@i(QB0Bb)r^{|f2#`(RW%jV{nBd;t=VHDhth6oF;FOX3zu)?M>oVuV# zNQleGSK_SbOtyAs*F;G`+Y24SR*>*TcLd#kJ}=q5n3|Nn2xC`Wn|Tua87U5{j~SVC z3lkBHJf&9F+IHd)E3P)&B868?wIPW;AUHbp0*IlOBZ^BoTjftYz8;56rQeTkI-AQS zrTD09A_qemLJrxi*UC3t=I4+Ix8K6w9RKsvuqv^ysrJvW@;Ho#MwW2J7hT&^M>L^u zlJgTt?GtJ-pbVC(F4v)0b{{R%^tyJJ9+XV=FFbzdee9@+FCoNH7Be2;OmHK7nE0irE%fX;cj{%_z>gld{I4hBdn?HB0dtf*ckF! z4{W&Asn~6Q=BnG4KZ3$lxFGV`5ogvS++B9j%i#B}hM%iz@Re8ekxRq@IUi8nWR8pd zn7u>kJY~M@Wxr1)fTC_vaF){92u8|YU2;1lO@5$i+HnwX&GqlL@_B;hf-%x=sH;AX zZDZKyn*xrF#~|Rm0!aWITU7=O3|~`|N$5fq*7+@U0ghpHDY4QS#FL?@YRr%ou9b#0@`hvk!WM4Sk~(@(Y{m zWSud@lfXZI{qGR*87-npnS#v_f(^b*ATIxh2NwQ8o4=^-p=L`gX%eTu$U~A*tG-Yb zx3)hdM$iNj%E?3T_4UHZ*cj2$KRN{Em;t~7OAYg~%{0oAF+bVbJBHK%~j#_f8 zR*B+1SYj~D5dvg=3^^mzM+^X?V$Eg`dnHb9V2=+Q%aUxTMZa9%Z#q?$>EsW-8ivWF z`3!0dJR5|wZfW(1Ejx(qgX#I|`I3*@2|DP!qOtr-MO4_z`^zrm2sw;$0RK$D zsY=*3`=%DG<3AL@6D&-l)|dL!=G0!&)N$LmMwi5~RATNw&l=rU>-~2%$;&$9Vs~_o zDn6|R{|a`OZ1$%Cxk>}D)a&M_wXHPcIxwfF{=kq zH?m|N_!reM9e5`Gx0nN5@SMdxE#iys;(=1oYj@z=lDIO!(p&;N(D#1rXl!(Elru|%G{G`;RyB0rXKOFEcDuo?>WpgilE2KC?Omi2~YVGaLzr(zZ z9hnE>z$g8{FZ@@h)!^DsevfrGxmxsogllQQOyIIVICu`WdnlOJ?{XlymG zy>I8%zX(b0Z>Rkyux;^8Rr5=Nd&CX83fA>CnpMbN6>`9~9Dr1ip0$@!igA#F<4JS5nnfq(jN4Iyc@X2%w zeD>)im=G9o5DdpRfTs!Zd`&jR&x-WbIr94mHMBqV>Qp_p)R8jpT}HgW3G#}CUSkV4 z*RN0_9jX>%5|w;ZXi!;HzZ;|O0P<;MZ4-A;V>;Q0o7mf<&aA@VHv*O*%$OwOTBXmT z_30=1L5QqQztTAwGVxw4A`_8QszC@o!ID5qby%}Od zo9TCpsspHERe{d zSuxDkJzXHqBa1UwUV1fgXY={P0*1`L`LS`YG7`vsHYOhU<*mh$gJ<}RGLCm6xGLcD znelgQJVJ6fjodW!TSF)hV9nHJ3PWq{vMa*QE1w!|PWxlt|B5>78y zpXf~&=U*ecwT*`?)|C6+Zrj9%299Bsby~I^%s%hl+3r&=av;w~KYb5>{^TPGzQeBy zW!zbVONSQP2&@s=N+$_^_a&?=xZW(|{`X2cZK$G|sr7J*{0e_xbtdd%C>h za}(YH-_+>#XvQ`Y|Bq|Xw>DO-1U-KY=>K6UFjPrq4v4w#$17|F1(4=B4QQ9o_v zcrnYi`%^Ht(0jdAa`SNUe1+sIN=wg$kF=S*$fu3mt-GERca@KjaAB<$Hh*>ifn%t* zK}j2Mcq{gaZmrTUKpQ6)c5)65oUa1b|0cW1bF_o9qqYPv7M{_X&V=~?*~5rV6y$JkgLS-BWB-s5bz<{!H5dUL+>v*-y~?Z0&n)7wX|nR8 z;!IFq%y*_RXes{?9OfZkWK^3%@blkqSQT`pYV|@bjlXGpV#^0a*|IQH*Rz4Q(09Lx zMDo7&x9N4<51?XIH4QhwtXseKK{dclTY)YnZKJ`&XmSANA^m{hx$nH6YAg00Q0&X- zv4CLQKp%Pc(7>0*Eeo*vdmfo}?6q-Rg&Kh^W7$XmT1YK)J^D>5XGld14N0xTVs(t8 zx4;+JV_N8KRTF?Ri+cG2&P2y+d7y5&xW^vD`;bfDJ8tUumf5(!g@S30GbvWlWRF&E zp@O09Z?C17O|JvbjP+BkCY1eDo{zhyu478tQ0?Wko5C15R(c*7t$A{GEToNOOP^IW zD<7ER-2^f^lv2AAw4q;rD<`e$+A08BcG%U(oQE#0FIrD+=mIY*7k+Cy8aLCQ%BWA( zWL?)Z{HFsys=jW1FN|5B!~fITEFVLJ03*k(Gq?p#zCJsCrv2#RqAeq=9t%9^@PM}6 zmg^8hP#YbzUmOd@V-Hfkd$p?kBhWv|i3VZ(@vQUj1BpZKt2_tOs*xZ0u|?;1Aeq{Y z_{_Y8daHia8tc3ikUXU61=xwSU9{0s&ut@C44-)uXOBh-t2F$A#9GP*5ouEp_VsJ5 zb2F<#n8aIsLU8uThI-3n?TdS>yxY!sXl)zEv$$98HW%B_Ii&!G!mrkd2z%w= z7R;dzWDzK}+!8fCAEXID)p-o`9HBvo^+?yu%6;))dd}5F)znG&o5pUsz268(6q(0k zuB>k3iNSbCwn*X43x5ro!!rfMqVI=YC-E(SZH76qV-qI#`!!F z`>{e(2JVGAFViFm(%=j{Gp}q7SoU96(_2drzo|V#8K+r>1*iHq#{az8T(xyFr_Va8 z-K&)!tFm&dEalW$DJ+HX849?qSWK1ZC$7ND8@ibs;)wqd!$>Jy1ly)Fcui=bU(J98Y}MA*2X=HB5xmr6a5!-SlCdYrkC==)-`l zPidNMOlg|tJ5uS?$(vlhxZY``%k5GGVqXND9cd7jF{wx-e4m(FvOq+AfB!6#wM4nD(8dqz!X-;EW)f)n?8In=9L zjkbzJ(g=>IYhn~r69SU5U*HV%Yn7x>gKqHU ziVPZl-QPGOLyyy|UJ~`iHFBAM=!nl`vI>z}vNp#z#D5~|`-$f-)GQ5Fcb(4o2uJn_ zIq{I*jEXON;RE`||55doL2b6*)4`<>q&UId9fG@iks<|3kpd+U++Bh@#l6L)IHhQ@ z;!vze3GNhk`{$YW_vQVV879NrxzD+-vwL<|9>>VN1+(F!Df#T6;lI}nXEprdjbOGV zG#1*hzlO6c6tQ;i_BUL$5|DlMw^AF7#25K6LemYoSJ&PsEzZUz4XnE$RCWIG%OcLa zxXOc~TVZ;lGsXNujm>TP)?_Td!;-yjh~(n$P2i3wB}L+X~>Cw@Sg(w~&(?MYsya!L(X4^dK)D~Q`+2pYn0Azjr3p|zS}g`E(4fi* zwlPTT>I}i(;&~Zj`MW~5@77k-r1zh4gwf=O$hN89z0$YN$q6K8 zxPuF07;k~N2USTOD%nF|Mu1bdwO>{Q5(S0A-#$Y7R2m|9WM^-2C??&fKfcpOnMH~p zqBjlL#`0~H6w)F#>>U|U_rPPJ^)5iVNNrat$K7vtzNk~bK<`7DMZVXl9Vl0jFLfr9 z$=m_uST|_IDCX?hem^6j)bza(OhDuz-ySvcAX08E-nahH**PMC0uj;-yhBlJ1NuUN2BPa|6bDk{xE_Jc_rXDvu>5v-<+H+Te`o&d zfS7#tO;KOc)lqr&Kt$Rus&5SJfBQ$iUW|R)R_%^wof0p?JwiTTgxn-#`#lV5NP27dneWN4 z_cP;wbbqy>xZQ$z!z$8J@7Pu1K=JP$agY>jpL^!YDisj zzBIH~?7SbZK&-X z;na7p@uH@ixP587DU)ttG|nfx7T+1|6uI^`?OJgd{@T#+x%OWc9cnVsFdbG>A*x&` zrhViF&I|FAMJTPxy$k`qjLLma*8ab&gM-?G5r6fLs2}$qZ0}FShgNEb;wcH7hpQ_C zS!OKWd5N@M{kd*zY=WTdq5t(pO@0Dkdm8(_**Mj!6sm0Z4-YwT#6#%`K0X@|rmh&q z`Gr7GBM_UmEdp0s^Jc(IJHeQt)7MoOn5=6XxyUdrCcTFEnYQMv?rA^Ocz)0g-~&eYQETs&rE}x(F+7qwQs%e9?5IX%?dwx zBEj5KUfbAx>`GY5Z((cdLpqO8eYdnDvFDxS{Z3>)r?mIcLCTv|$m5L=fi4jf5HAsN zuQN9@-#9wL!K0SwnR~?Ux+!O=lq-n;UU7CJXF?+%phn?U6GU<2G|CN0jc7ib8NsH~ z6VVJSDM=Lvzy{@8Nch&KQVo#5?tLgc2l*s=I9^K(ZRLK(K=|;j!U3K*eNp`HHuf=D zr+(JgTsZtLE*T%}8by*rrZGfDCh5yG`Am$Rjv9Ivj>MUqVq!LVR(c3#iK%QHvU?9c z?kBcUgfTN6A5(Z6%?TCzstTnKCduF}$y;U1)L<|HW+H1fbMe8}i_JF!D$kKULx2Je ztZ$P_`2AAg%p!edj@Ua8Jn(_5d#;|#Ij1O~(d7Ys4f=+Z^;OS6)Ksg(ChuBye-XI) zEh1^;)2z_p!2TZqgjBb1PYl{7yWo+jpP*yUlkBLsUMs{@NVH_Fu-y8C zU>VDSAiIy^E|S@L`MzZ^{pg5I5Jj%s< zq@uT}Y$X8+9O;Q3R1O!0+-MH#vBmxFVv5GUyVl&r25kS9m!eQ@<>lpVB7S>iZWtqLLp>(9Gd%qTCj83P0uHs%gnl~u>Y?~d=26TV zWm>c8#mG%jd6}oqu>4M*vxaosRds_nWQtW>9$oOHb;DX2YOW%|cveD=vL_o_w`va9} z)%iW1ajaX!4qr`RZ~OefNBE8151^U)Tw9k&v!TFmO(_3c z(|XT1b^|j0sc&!6Wk)}9$7f16wsCSjNTLJd&t2n(KeiCpm+@Fmic4wdHfAtlymNoe z>&V~moGq*^@>+XZbz^M#XbR8MY~8%aQbDI~gnnemC)?QK7Z0X^uOCku_((%7VmnWR zU877Cssf-#^>rZ9UDGj$`2|~sP$JBHiKU*lUKf|rUt-!{Pc=yz87|qL_quJC>_^XZ zV25-RZpSWJBqPPm^UJ~`-WLvCzo!pnlT{b44G6WH8aOKR=iE$m7FohGBlfA zOFY>W)|`HWm*mgG`P-7jk4`zgnGM#cs9zN znyHayzoo`8rgYr(u+wApR_WqZ%>#io3T$+%MJUHe5z+`eVcI6Ex8)0e8(3XjeX*nZ zw&$1<5))j!-J`Z$qiYW%$HnM-<*Qt7nQe%TYS7O_>^cU72$4+|-WsC{)ubrOm zfnxcl0bItPuQ5M~@}J8AC6s6pj4>e-gXn$h>_MJs!MvqUuRNoQm_3ClvpI@l zyfw847rkxnnBcUOcq*Xfw4jouzwW5MC1TxGhgc&G$e>PkKaZ5(w^7@r^2=zC$}iI| z*ac6w%81}gIC8!GI(>+Iy4L0+qc5*edA8|u@ioDYRc67tPaZL$s7M>Kjb))Hv;7f< zkk@YRguJy)4uj%ebWRI0+7wED*9luz)nUCMMA?gKTn3zX@=lhgqj-~lNG(IZfGI0; zO6u@-;(TpZfG^f*6RFP>{_%(1vN#&kFiu}v;T74%l}cQ&TcuNOO&ITK#2N8LnLQC2 zvq${CW8}Vd=*5K_HF`SJLHpqJy5)hMfkE#LwT-Szrx7m*CMV}+i)^{a)8}n-BO2r? z(I}+*`J*5G@+6}253#T{T(y6lqsa(SM*7pDtGFlG$$X$VAd5*C_~I!k9v8$q=B4n1 z-_?y;;ZR1fprV#Po>pp!_$2T?3Gg5R1elRm|D)Vc8Wy2LGiNgcfnOcHF<@_E^4 z{Xv3!Q|N~tWNIC|X68O~VMc^h`^SlXak`+vRJh=L33qtJ+`LIRC^e>o`o_@FUcN%x z!;<(;J}dsDIIoi85z&%;P_imk!ZJMe|xTr`H9|q>d;|}S$@XUb7#ptfrajXwWWV+UC zp&MncO{zy>LZtf)n+(5-lYZ_U@8C^E!)D7PEu@Vr<#v&TMRdfl~#2((*MZYvo$dfPGw>?T~C(NM$XLH8wu$Hj(d9TMi zo8S^7ox(qJT^bNbcaFY$ik7|ew_+5ji+eq#pOiHIYQ%iks{SV+v z*A40~!fuB};-pvX<8KX#fp~blx^wUb&Y4~%o#Ae>JhFb#r~S0O#l*aZo`t)@obSVo4o6X?gBpnaA#0ZWVua7>*FPN$dB1HK>yO|*3aCbEPf_6+LDjs~U-w&< zmo1ugnwOI9o~qd0y(OW_H#*=_N&@1?cp2+e2vE33;%vqnr=>X$Y~Y1Kn|8o48;#!7 zp(}ey#sHx>kVQTW-jt*#vi{gsei7y)`%ki0zAivU;deIYxagv{DBxL`6su<6?ytJA z7qg-2gW9JIOJGBrg6!Z=88z`-t5Z}mB{T6a684>0uS*JHtF=(Dn8aYOV`MQWzEw|e zFI_?c(8U`XTvD>x^cmmauBGd^DX3TGP2K|70ryGr_ba09+j3np#CHH^@sCK+qj+IZUa<9egB+tSjE|3|@zafr{io9cMW4C}8u4`(Je zw2|5t_Jz_iYtS69Xy;$>%TzSVcBbs0V6OY$j16w8KYnix9P3oa?z_mG)ajhmu@kOr!65Qjk=@g^oAR za`I1#F`;Sji{apqmb~$hnF7z8d!%ThkhQM-%um<%Z3qgpIMP;FZn|o8*xES zFB5YjC+cI9d*mBjPi{Y6d_7P%I`ieqD7scBA!I~xhdW~1!HBFxRT;}FhhF+n6RNl| z+eY^hc5=+N*teV$T)Z+o;?2Tk%u;%>jhd$1NOmqz*&H97v0p#8wKQG7P01+y7!(Y& zz4=_{B`fmPho<3NA+>|7Id;!p$}>&URY&V-M@jV}uGoq5{92H@LAVu)0wohzOX{GJ z>w&6uy#jAJf0pO*n3}#Se7n8s*2vbBCzv&xIf1@5g)r2VXM`f6v?3X!<(mUBrg1M} zGyz|7@RnCzw{a>@xI|I9X6O;2(Jn27vpf(adw!{o5eRG<{{1jknp-&(;}i(a=Zn{0 z;B%F0eq*%k@QlMN%&xzLj2>D}a(&Z}TKSn4u!MvH5i*cIbl*L+WYa2& zgVpjQyrLwD2qvqU{GLh!Ta-c1I1MbA+Zebt{NwYGR7gac)=8M?cCmtG96-N4wop}e zzxRvp!Sn+VvRuUZ3PeSvYrvn?Ug&PI;B~;26^v~lQPHp$uBG7*$9v*eHFtdkln0un z>1)>>V8t|isZrEsV|z<9Y$<0zcxt7Lc~oE`U2Ly#)dsTa>1QM!MYc&Xsm5=Xl-C)q z{fW3bOy)}uIebS|dTOg=_rJdTczeKNVJVhZ_(}Y6x%-*p@i6GAZb}e$#QJ0bVA-{?^*Ydzd4|M&cO}5 zs1g*(8263-t=K=+3zI#d#wU8CORvpznmNh&@gTt4uLBKpVBepiGTR)d zhpwBZi+mmhbw=X@_@Iq+6WTU#XSCa2-cfce=ixA+DNGv5^b6<_8K~ZDzjPAYo~SO< z1snn_upv{^8cXH1xJ_8>w;mG<1@WZ{3l{4OKuBn4sF)s#3f^O-_P#k0txY!Z=S3@Zm7YJC|?2!M`VJKd)B-7SFusMFn|oJC@_K% zWk0D!8k%Kyi_9j>W!3qelUjO)=eFQJg%->ouOT<^2LQ}!B!t@9Mj-f`L1I5d9fJ_P zY1~#|)*-h;2TQ&rSDI7G^wg|M9PO1z&bZLz5c-A+Gr64$-f?P0zMav-=T{xQSn|Iy8P}T+LC!v7Ya+1Tq^-~V_(czA^!0Oz3j7NkHM0(-DSD6SB?I5<+k4-~LF zDsY+P;*NNvxTiNxnA8giwlszBa!O#-iV7TU_~~fE0WH5X%pY^jFuPX}&-Wlta6y3@ zfnk-Ex(0eW23ek)h_Wx~t31oBo4?)W2}(eS{9hO(f}S-(`eZJ!>=SgNB|I{QMA6vl zD$E%c>MES=Ociw~^4-ejqs3PE%=5IEp%c2;?PZs=ve&{_1e6|-e5##g*`EbIdTi2p zGiqq-qs1D(!%>Nh;Yyz028DWfZ*cTtY9_~ko-M6Y!m;6H#&`}Cv`PsK!iE`&vhSgC z#8>V4Q(7O5H%`|8ySuxnTd$BWB78r$$YX5=gF37PaBfagu5aky0Qrn_krqqgmTFJ~=6#T9c)jd=AUv-~^^dWE_zcpUDJG)7ihfS-Tf3Fzs zwgTg;$Khs*O8$r!GXJ& zYiqQN9Q}JuOXto($KOXm=$8kA1HXquzGe!)N2SMIYm_j`G)sxN6G6vsC$P)p3A}hD zH@=6H{++M;r@raT*ob2Pq~GPWmPDvTm)$y0-*2h$#_-#^dZSMOg8(v6)T9@Jz(~d3 zQ-kEAhIKi_gU-`wZo2n4kG;C|d$P<|3 zEi-&??(ivoM(&RvLD8%Mg`4W<(s<3{9?O*>+w6oV#45q|`fTZD!4AT=`*vfowGE*Y z9M7&CvHq8arcQtMc?BJW&4et(r?kb|jF!ivFqES?^FhkueW$UrDo9Lun0Oa7F*&gw zL)iU%1%KcCu2Ol0uyK*-J0^ekzvJz`z$Oh z!6jZ6tSkdK!S$Nid%i$Edi2WrNM7(;%u3HAKM(X`>WI!It|Px|k!c0TcPdw#sC)oA z1#tRlV<3m4)b#`YR1@y}A=6UJTsu2~JT2?j1YV8M3|fVV;_A!=vMWF+Gm0ZO?l4K= zqU#JwZ3-YcG5BrEC10_<-z`3I97S;7ep9JceX)XZI;tW&vZYq=>WvXMNn5*rMAs+X z1!CJq6cAOx+TJZART7a+bVL3ZpNsQz!l0|SK@kIUpa_m;`^c+tcQGUx7KY1NH5m?t z%1lZ{KrvuX3h~|LgfK;Pkg#8HAMoOC+k9lP@}*MM>s&N^rjwB}KVtY$X}!Z$a^~**Mf0?ff<5&gsLhs(-=3@v z7KpW#dKkTtpU@BCLXgYV8FF|Nf4F5V0fh-?N^yaiyH+j0U5T=kmvKNY>o>ALu?`yK%nUNeOEbrTyjdDLpWS~Ur+=s&Ns-{CkZWBI05ei2W(6Ht=LWt$ zUY^En;)y&-9SpelBut*g2zeCX#*d`3)>@)D`X>p!g=wxlt_;p2inbLOWZpeFywNJ? zp3I|Lu+Nz6F=l!PQ^{dzN zgPFBQI(+wvP7Z_o+rUftKUiQr-ZZ)0Tfa^=D43cjb07ro_g6yvJPhF)Rgi|7AhH>X6Mr_C2(ikypLP*&l7rz{-cD-(!6+!Rc;^to^y)K5&qwVPL$ z2)gFtw&*H!OEV9Vuex#xH9=4AEth%$dNL=YER0a8QoUVZpNHdsR~&`+?x}UyvMVd` z5y?%4U{T3lYyQ6O2d@|4MV07*YCPHg@bz?wGOHQ}YHg8cP5OD4A8CUNZJqWS7XSu> zrDb2~A7*PXgEOgmh;34GZA?F6MOQ95ykKEl-{z-;(V<>;u|(A}vvnZH*gqSZbLLIp zij_qnkzkv6)2yNN`j_?4{O(P|F!+kn-XeSAcdjEl#W>D)&vi`tCI(-ZDQdhZ2AM62 zKv7o*(tf;`R#N%qdH*q-_yi@S50HQd*`0m}Zm8zf#jBZNLrU4)WXR3Slj|=!6sP@N z>aY&J?m(3NE<7-{7J_)cq3-VCute(h=}ne$me*G#iUY^A&6^Hh%o$NTG3n zr7#4b>}DfSV$;&2EDPv4_5i#Hd1;EwbO!ffD(JMw6Lz=}Mf9y70c?sYM;zWJge{YS zi3AbZt+q8i>o_*XcB@>C z#}T%oqPwZyBcRaD5-SiD%``z$$v%?W`e#l&u=2S`bjkQ>m<>7ey^9A*U+&f488C}; z#v8L0nFmjIl;ha-hf=c|AAzq8N|LG?1%!^?c%Wyjq`kuC0z?hppaEO=eMP?KoeR28 zLrVCQNc>fv-UmJElEV5rk+J-;Sxzhn5DfuyyF{|!C@~Sz&J$-%S#@ZA{P>TZe?uGq zY<#-H-}#$vuR-vKVzMPze#(vB&CN~v*tkXH&^f*Q;2%o5E-QKYO`ohcJU=mZPf36)_x_2 z{Q&wf9(@XY0%+~8dqMyvq8RD|&xvJWW1lnhDwgoE0(o63bt1`h42Ta@BcfDz(gI-k znCvo=0(!n#zau(Nrdz1mKNGf3jG^eK&T8q(V)>3XY5vvG<-2gQ-^|z(e~@bC5rm}9 z{_ep+36Q>|Ye|NhH*z0hi}pND`w8@hq3RV>Zd# zw{Dzo)kA05E7aCPuQ!1}Aa4cB?eR$<3_+8$R}y^a={*7@QcKGjq;saKIMlgx)t6j5 z(NkhnQ^&0mA*OVRaH7hFn)ecta6)~mr6d{iIA*$EUIFSJ!!3Uc-#&z|R>5qTqcQ=f z?_y$l0KEdwS`bDV9c3l6g%XJ0k_+XZ@KJiS{M@C7qaP$2pwbzvkyWqKN=0vfggL|P$Z37#~#r1JTe}c|tR9e;<^vs_D;tqZVwq8Oi?Ponwt8h)P5~DBtlj@+HGx!B(pdtLe^l(k;`=^6UDcb8wZU_!)Ec{(An-Q z<6%ae3ow_|1H?b;;$yzHX%w22()~g0H?=NQ5k8uhwj4A;QM9>6#~U#zCyKl-clz*GXU9RYcNsQ zbP-yVm+2`)xkV)(q(QV#+N*tK7p~F(Z}t;cZ}$9<1p|hh5ya8m9SY)kBOAhYs8)0< zm2#cLnokr^fC73*CRC1;jTi%D&3`Jj?3?RkY_sc{)k=`#l-w0~S7KQ$Y&>6OIjN{; z@v)9-o@WZe2L+VoucO5yuN0^U=?cy2P9GOV+Pu#;5G2N(<7M8C1tAoylH4%K`$Kq= zX-%hP&P7quNf-jFsuJZk@06RtkE4fI62++vixQ+i{&RPH?Nm%7p&*&nV?C?~Nf@e{ zh6h-0_UPb!SwI37+49Wi;3gy{(nZL_Z_+e4)DZ_9073F@{&pf{_+`&0^Faarn)7H$ zi3w<6V~jNT6Bv)(_#_N~(F3)z6o?AG@%@5D)!x`;1I?6)*U0S4QZQ@}IMt5}B744% ziDrO;h#g+f4VKG($h1<7t7bUq6oakh_Mf%%*fxf^0k6VS#!X?a!N`(5rI2ZN$)yCK zxxzcKu^cUyy>=1|3<3Z1;WDr|0v$NVFX6=egBan1UT%UCyC0U}h4z#h?oNqh9X+wW z?s(V~h)fJMyYr3AN??$j24PkdYQvxNWGmROc`=pswLEKy*B!7MDtwfK%APOWC#awn zE+$~!YtRY+gzR8TfDU?N;L~itiC&(ZcYYb zx({*mAwbJ&B1Z^$MXRTc4bTRd7I@9%^-$v!_N0j$>D1Dn6A7=-45 z-OXYvXTwrd<5M@Sh_ERTu}Wc!NX#>Ah@PyQ-h561Q5ItQNpZTgJ-x;?GY-I88VJ18^MdDmRO;QMV zF0*uI-%zwTul(aSMeCh!r_!(4q|P!@%~bRz#Z!fNXbwe_nP{eUPWPFG`a(W&R?|8l z5cgn0$;bS7xx?RQMf9(ybSd9t2luhs#|43s$G=??afftuLq!Q#gu{04qCilg=O6Je zXAj6gkFZc2@R4tUa2+2z6rtcO^6?*I0+y%+5?2;SU96TsDBS~;+4}MI1M0tq_&VDnx9QsCRS>Bb_HXoI;JJ8vqskmN?MIFa zM{%b5=8geqciXaFi9w?)5oTp7MP4?a1m;6pK9>4^ayhFD5!xi7Pi{>sa<3+YN)V?4 z=Ief8n|!)frHB;_pSXxtd~Np&VX@1CZfQgSj<#Fika)PJd?yhUS-VJk$u)EZ?stnP zB8wYIG!)tQ_?!^Jtsl1v)FWcbF75NL?}^PI{o{yfqQr%NTuqP`-CG5baGKBKfO>n! zUBD7`7WB~Yk+}l1o1jYKqea#y#oIm@P%@#lHm-QY!|_uCl#1auZ?~GP-)!Ad{*}LbiU@DA$o=0eG_U%JfJO}a1s4pPBdZxn~**f(FbOULny*#`ipiT}>l8nq*;Dn7^b}ih_p>NPZZ1`aAGs`i;>o;ddK4A!}Eh<;B z*=BLD_N!DqR>m>#4GHfv~@T^)Gn_(namJ!#t`boWkLfgsmXO7!x8WcXKy z^MOCoL~1$t;xhq1`EPUP_f|vpftN$rAg6$OWp<9G9$xc)CuQEQ?P5*!4}d96A_5P> zF`9(mdT#d}_4mUE`zGXr?ge6-9ysT3a6mE7ja-&qRLMEn#`(vrZ@I&9p3u#xuVS7NS4mnBMUpOXKNR> zd_S7ivzZaZq+{I2LMh61L$x6i6!eQMCVa)5XW3zOFui>Dp*B6FH`t3{kw+|=wA&NJgD8B z24w6PG3XS#!5AcA?fR2<`8^IKMiu=7QZUhq-6apDd~#O7QH2nSD+#s2E&(?7^p*WiwRqGW zI@LP+-1&mh%Aa8u7+_J+uyS|2<=6|ysIe_x3!_E0`t{iyju5%L&FaEJ{fOq|=8Rw) zl2k{cy`3~bL6mReJemMgew|`G8SHM9GAav4O2K2R6L1TP+S~SL2z&0SYP62?L*iv#}XADd^=2P(YSmLj3MLcel z@!D)?ezBMRbwMd)%9ARlIDA3A74x%bc)3inJbtZ00Hd_=)AX!d#J+oESQz<1yBsDe zzdg!tJ%q9AWdLk#zapP-af`HWGhLNUK15FKePevF8X2Jm#m;PdE!5vVs;^I8;}DCR zhv&4l`%ZJ!CNeOelk1cEuj_WbH1dZo`OB>bRkLDlsx`mCSD@UkfJ;D;DpD|y? zU)H-3*|hx^r0})(CPg~BVwBGQG*dp>Z2HwoR*pG;>77p!WFw5S#BizAl#ZPBxlDaoa!stB^r$L4z@l4} zJSgt2f5+k>CpF^ll@raPmuIHjFIr@+S=;7a>My(k82&URZ{xzB2-~@1qfYR_s59*q zNM3jr3v3A_i!b;pPDuQo(*Zx>v&=U|KU(0LmqVB!Lg(R`KNhL)GVx9pg`9wsfsI@U zD|I8+4Wc%@TS}SYqQGHm z#swK#KmjVdC=a^jd8Qv8pQ@nNqQD?INP_R)CyrVZ(N9%qGNfY0RnG6t+3MBx6sux8 z3Fp+@jv3}I8WEzAIl6p;%O3vfsYGg`V9e!|RA2r{{>z3i@_LM9|5p#MI(%b-XIQxP z`mbhC{80{Hd|xNWQij$u_vB`mbK%K_*cbM{PO6#=gWa(isy_EF7*M;(&z&U&an9KW`UDb9+@H`$HOTq*SDsl%{#hwv?J=18AT$RfudV6L)o9q2u8j)X~fi0 z{^1uFuqCfZv32yfeM<3bzIt-M|MUjk4h_moBt@B+j~56e&Fz=!ixeRj2UU}Dpy<^L zw`e%N%%}RGS+(A0PVD!AZ6%7Oi7}z~3;F?imaX&M)uX7OKy`!dF5^D0vSx zki{c_$A73{m>V%IS}sSkAdtZJ;V3_ij1~oW5!mTG{?*NT>}U$;G32~+A!^%5&hBxa zVj;XL!_=5b5Ln>A>DqPGrM&0s@l`$0aS7dQp}5*^bnMF-4!8*%|2DQ*W*rlUL=g#- zr>x_!xf4~cZm?pUA@pSWhH9jNY>f2FBk&WldKITS+9OtEf4No)G82(JW||ZF5EB8c z_GG$=OJS}rJbVnp6+Mq(%lypLs zX6KoW3$|mEY4>^^OP4S)ydSst0v}6gHm6Hq-j90(xvx2Q+#Z9T%U-ZvCSQhLB;(@^ zS<>(sPp#id)jAl8lH61G-ms!(YH?_cAQw5~iy0Uw>Elg|h-|FM_kVDSz?Uf16B8}E zy!v(?_bonTXI!+YbLc}oD!z-qcldBP5YCyn^pqv~4VTcu+S-G-iNA(Nc8~RIZCRQW zu`EppEiexWHj0}s5rDAPg+B{8F5y1^J9$QLRISj0{CVpiwb!{g6kj;}j*h4oeXbrK zFgsrsKb;`KIMIvSYyZ&5shcj8%fS|3zLpba^)}Y=HC#mINY?-jv7VqiwLf9~X7l!z zY-T_0T9}x(x{4hsT+!GhK6Te|EKQc*uU!5dvH@3+&ojLe;LZ_9x*CE|fRl-u%$$o| zZu$700_dJ^?d_ufx|>pUe&T;7yNJFTHw(DrwtloHnvvqI)Dzik1|(zBc!TBR(+Q)n zxz%KJXby6vaob3n>irPV1Koen!%^`=cz1>7KY1@mcg~(R0a#FKuJ(l*ydv9zP^{KH ztj0%gj{Vd8I{kcWG#FsHB?--(uH6-x8~@9O?2HS})hY{iGS?`c`ho`2Bwud+rJoq9 zF+L8EM!`;2Wsl+RiXD61Xok+Zcp}k#ofq=XY7I&WpbYMR%sD%eSbc2R6(c;BuOFfnQ3@b5<8v=M%)r?Qgir!@dOSxmP#-4mqa zSU#TzesSST9vjB8_~XW~T%O&@ZIrIm@*UG4EL1Fmx7optkIVeiMUe&G$si-3-w_m8 zMF=}aFIr}DiK=;A;$qs0ba7yP(U~0Nq5CjO`&`F;_Bgvjc|umOO;pf(Qe=%p0+!!2@TIi+dhj!ngFm-MxE+8wM2Gp=c+Iy^^?rymPXX1bvs#0tl)(JCgda`M0v5Ogvn!JNqJ-C3WJ(nT59bVDTHbfEi0 z2i|K|)Ns=&vSuDqRg<{FqV!mULAu~8GLID*Vc@HhNLHxIGm)BvJbpya?%5fEmiDB} z^BQ7tF2Th&Fmh(bO~Ut*3;}u$mMACk)^NCM_VFEWqdgD3tOxbH9KYNL$r`6+lU&F$ zU$n1NpAW~KQWK;J>k~iy#wtz4POS_+p$K!C-t|DsQt3&L#{anFnRr_@tl2mu*K` z=5YkQ%KfYe;Ru3|0gFoY_cjf>o2)-RqJBlG3>6N>E$31fBjgA_FBHt{4NSX17|M2x z9`e&j4_c{e`Oth^`GM!|He#w_D(u&w`QXX%C8ztz$v%i19v(O8M1L#`=ZL>!+Wl%4 zF#BsY-p6(@l9t-PLF+5CESw5LVtZ^ayNpU2RB-;4}5_uq< zG586#^W?c}+~%aczw=$g?wL3$aOg(K$LufBpo$X!s2BA2%;!KreZ#`&s1+`UI6(;G%f>SQJ2I z`(R?wr4IiMF-B5NTo=}Bjj zx?N+Vmh{g>g1u`~GDHAV6f{O1;?GOoO4R7xM5!B;5<}QTX+nvaDC<{7v7l7W|VF)1;^2K%{Zs2-3-}-l_~9foS>joU^X< zzFSV+@XC}E6yV(_9FSb^*DgG}CF)6wjvm+V3JMDFR>T<6)2CbpmdKT1qz%Unb=Dsl zFXCi&$l#&xN0wFVH=@Np{*=IG@#>hdhMNppPTi^JGh{P4yz`4PSbi6T@S6UQDqcw2 zN*U8oTy8mHFn0UeB{Lh|c_HJ+Eb?!lLb zpvNFwD-1MpV%|8@p7l%%K;fYYRXsg6#_U&lGvcJF5@*9;I4%e|^zK8#s-A}=1~5dh z9J8bkiRMM5#OUE>hySULGhnmKw=4|rT%Y}EOLPtVGeD_y6YWN7e7LGWatOYr z({3F&HA^}_6)#>^yLHm*7C+ud&AI*ABwp=Iv6!3s`hi&asobxVOtSy1;)cq6A}A4V z@r=q|k&xg%`eiRcBK6EtK{Z>xY+nP_LH((=dTe=i{bSlEKv^8Lyz5cQQs zhkx{(1Dc(vf(ZY0Mh?@Ju<>UER6q%{5e?=+U(Lcc2sB>N8CFQO8w+7%g~u)TMy6e;Bgl%Q*A&_Pk(kBW3D&;0$ zKzS44g#tnj4s1mMr(NRPiM^jesPV)MMP2j_@-=ydqU9mG_#w52A!NGR%;I?^GGm`y z6$}gzFPyZDF3!mZ07Pd%CaXw=Cj|iY@rfRd&A~NK#kIF zPfHR{_ol6)D0X(+!}p<#snsWVRZZfF9Ww}mk|^wjb7R%^V{ z-zOg?c+v45dv_^{z7|3p9eTw|$na@ZVJa7C1ATQf-KCX}|Ly#Aw6z%+_^`g6CBqap zmW+v)U;HzI>wyk35kS&pwuTRze-7eB4}iH?Clmz#X>W>)K)E!oohSjU78Brp-d*zU!ro}#Gt z|Cu9?x6mM+)O5Xq0P-?^BqT_MBExjj&&U|qJ?!38int_L6<6A@Kcx*)nWIu;fzUk! zEg?2;rf-_v-EZGNH9__rzi?t}l%}ZwLoh5rt(k`K87(?`A3<+4Hr#6ck4n{UR2&W8 zS(%^Nh`=~$oW$3PzLwm&3u)zBWO5Ht1j)2j)Yeg1IKzyBX1Z&ammulK>BQ6Cng7~A z-`PF_W=8<1LWn(}&$yvgcgWp$Kj0r`TB3f+$KXr&FCYaZ{uE793~>&6@q3(n>3-p1 zst_fz?J0Vqx);;ukMEFOZfLZxVc(}Vpex6Qk%_q<+N6MIOFC;lb!C-r&mS9^tLmpF% za6p4mqZw-Uw_lZi)O+-LIkzaRCL;EsZFcwzsdk)P^-Hq7(U|gd$+Mu9I z0>wxCuZv$w#m?Mg7TvSIgjBT;I*M8SowIr4#;sn+sjsH{iQ#t#W$$t|FzF!V&Xd95 za+&qNvp;&;(8sH(&rC&hU5P(oNpZ08!RnUV&Vn1B>%_7CL-Xmc&WzyR!ZwHN@6iDNcX;LEx5>5tf;SQ`IxHfkzqB?ArJLR1|cWsRpUwalMS1i~v`iuPxIcz!=6}pI; z1usnLQa|*C7)oiTuUm~bV#CWp_b>6Jg3&o@DLhBXln64KoZ0@Bh*iAa|$QX)!9 zclchPXWse649w2($DL*Od(S=Rb3UQo?BG*$fBYfw_S0vR73<35%HZ6!tzH@ZHLb-Q zZ3e5CJqc89K2zQNYvcsv#KziLkMcKu@;Gi!V_rcT%y@wKgjv8^$>>J~7xsq1m(gFT z!R0?IxUmUOgZ5LuVwDV~{T<(Idt@PNS@t@TikicDOUzw0EeDEdat+Q4ZijyF;7&Sy zU~lHH3p-5oe&l!{Ga)^HDkT{e~(;w3++Ev$;q`LO>m6H*f{6#pfrbwp`Se#t?#OJKA(Wop`M@~?%*)-rG5#Z7zaJlLTt-L7)ZpV9X2YG= zd+KN6I&LW%Ld?Tp%L%HaMHPpg9YLi6{jf+XtTB3Y+{> z;Z2OtHT!OhV)J_PpAG2poA*5Y<^{?LFy}7=)W;@!HVUQCxM(y*CXCue?q+Lr@VXKr z#9;mBPl$>Jt%LPikteMYIc!9dlc@w51ICay%FkF@`qRlXI<8#cxSSKh(yM1jZ4$Tg z!R&6+Z)Ugi@K)GXnXbMV+mcy_js>6_j5QJ*Xo9A0*yr@$1iOnsK5}T1si?s5&zyAN z5S)UU;#F*n`l8~K2#nj;hO6~^xB$FBn3DXD=#!R43hcx;*VjQ!)NI2Gdju4xm^l?& zRBwM}Qvf=FJ&Ut2T{TDR6e{-)xU}Pr=ZbUJ4j%gBv7b}SNZ|^N1!`aNCvP(E=b2bJ zC$PfSijiDUhQjsI6uDudh%=?QQdE0OB-|ip4|MMREWlLG`nfM*W92-daFl*bm%oyX%Z?1fk5G{0dRjb6kci0z1z zT#ztbzuH!Z)u*>l>XEseM5F>PU?-LI7jT%~9y^(Uh(i58~)369vpaCOK+r z!dTno-P`QzkRn#WFI=0%Swk zqB0hi*|`@PM8kSN-h~@Rgr$bcyruj0hc%59jl+SA_Eo#WVdnNHG|#^z@4G%7A7eCW z5MVR*u`u_QR{9HRW{C4#Tc${_O8VmXex)J$;CSN*Yd?%~np_VjT@ky}epKB#L)%vP z{T)K8tl|8IaAU-Oa=q0pJae%8ZpH8;xwuyPNX|&l;qC2DC%L6hTYRA*nF5xq*A+*S z2PrAe-zilaV;1>Pr#qdcp5yOK8eTABp=kXN$6lx?sSFeQw$uFziAjj^0rp1LBS{GD z#)Vc#$h4?`jHL1?Smk!2?pTI$A#ri8n3v(=#of!$B+dvIP<&*xLVnY?jNZ2KKUY#O zy(jm@RNYt3ZedeBR~Ow+9I}o@x;n$V!`7$VOl5wvPJQTO&7PT^W;Z$&4VC@l#Zw7u z4~yHD7OQrUR~Q;Mt=_dz(RaK1p14IqJ3-7yhI!?{y3Vc>i74q?x|YcM)A)I>L!5Vv zHOUaE{KuvHlZ#SkpkBPEYIzLyBM)A?V0L*$jdxY4-fAQNR&QFgKEvX3_Ii*fvGSGp zND?p68T`cOSgqB_Cys(|`g8idJlt>HA7<_Z_ec79%*?tcQ5g|!<>RNVqUp$(gP=Yk05e@N)c^p_}+;F8ey5O96=Novw<;y7G6`} zz{=<_={V@ot*{sfAqF7&4nE(|XK~195VcAS>o$E{@z(AlMhJb0{)8|G|q}N zYTyZ+CvMdRj8pu44enBXtWCyf+4SDzWKpc~qL0}aF(bcL*;Qy(zP(PGe59@~|5|7X z+T5tj2^nJQBe>v+Sxo_!JpQ5sJ3E{c6F^Qlf?*w7?uH3S3-!Fa%k1r2w2k=Z8U_Xy z4*#kGFB~V+>xp6uiL}*5gS%*Z&@~CaO;6w5E*@~s#^y<^m!~AO*Oa0V310#P`-Xr6 z^_~)4bdTJ|x(j}ppS%>Aqe8+dk+h-Nt=h@U$T5Zn(BqCgdQy|Qmw?H&^=VcE0@Ws%6HFeJjzM^Cr`p-&!kfgIW1gh5tcL+N)F`czZ`VXfB1&rY z$;jET%0X7~+j!03?NUbd!NU99N#F4BSb%M|5r#b|pYkniq-M|Uca!G^1~8or4xB!h z7MB|-Mf|=x8YR8kR+H-^lDozz480SSy}x1!J=-u0J-Q+;kd_|V#C|L;m%ZU+vT0}G zU_n`hr@$%CnSCQ@WFP^2K{cM(QgRUbKJz7(Z?>~Rp=05o_Au#>@vXzHi;0_}ny{YC z*v4?V%&m>vVrj|<9@Zr${T_y;r|wlpAPeOsMmuy)8l!-eXe9)|)zZ?-?UD;Q18fzF zDH#_y60)OW&kSt(x@p&s_|8VY`L2nwEb9*;;aZpY zbv13rvxz@=4}BgdY}9>F{sa0WA6z?teLIW#dm-!3P|)MquI!LoveGOk`_2!L8?ARl zUWDHKar?IU{mhPN2g~hFyz;-@2K5?5oV8(upfHllGB#T@CVF# zrnZ$MFX|V$YmHflrBEtzB(kLVa$p7=SCq)z0cZ zy0-MBI4z4Kl+U23ic5>#5a1Rh6@R4;$=nL`#RQj@*jSzZ$=%ycCT3qJS@dmzH6V2?GV!rLqgMA9%b%#Js zJC4%JE?1bdNy_{6Yr0z7G;iC}?-vj3D4J!PC&|m|vA?<_c?K`T!XnP@f3H6XpBex9 zjzRHk1I;obDfsC+cn7q^_yueF{l;rT6>3JDIK?JcdhpmejcNU_EZg_fB2gLvuNt#H zv2E)y0#n&{hfUwJzzDn4pL@;IQu))7QlfeJG{5{a4=?l+k8=)&UTECfBUXgHukvPS z_)C{(K2z$0{7HhtP=z$;RzA0pfe~`yl0B20%*n>sJ!7iIvM4_1?_W*>R_R(4wf;J_ zby0>j(A{33dwVHrp0>`696MNy*+sm4=2-lP>hLPkz=jmKrxuUAwQhqV9w%Xs?#ntv zfDL+=(kebbtOgw3CC43vbkje3ZB7f8@`CREN~Trv4mmH~phYjJ%@{YKq8eH_B=%WL zl_?ji#zyrDp7f}tc|l3msT%Dzu1uQ=qAssi0AldGM?7F0ph0I1S2Mw9gH{-lsl1JJ z=czZm_0_{AbxM7V!TeGGjTYMUOG&2wKXU=jT^OjzR9iNqz%Pt$*SWRu>Aw|HIuUOQFOsD;eL>>c4HKjaH zm0@C7#gau%9&J5`N1cGAZ?YgPSGtN~X#GuOMxUHJU(>@6oR>p5{$WIZgt`UNLj#Bu zP)lSiMv6J>FvA_MWy0^`6#T(FQe7x$SvoEWrtfE6^CW@e(|&EX{&D{*`D_b!rubLG z57OSwUI`};G4J`$H4VGbCZ-it+Nq|!7lMxOBy4&B;dN7_7;Q~(C{`kf1e(@N>NXu;dXO zuW_SZxS`;y=)~kD>F8z^AC`NUd+Q7*o>y=^YO17cYTSRVyeEtt?^(SZb=Ou_-hcwr zkupZws4zHzS#iWdCBCQf{bvYH4{^loc*Yb9AKhOJe;76cTG!#cC=*?*84LBB$BJ_! z63DoT3K4cgWN{9*1Ki_pfQW)jwZ5^)$PI^Erw&Y@bz5?xwB{TSV4nM1R~n@9Fc?=z zsD4x=pU%^?-w`KE+ZBc>+^m-J)HrpD3~s>dF6jZe+|^Z<-LHKJLT%(9Tys637Id}! zVZr$ocOL5JqwNl?IO)(w#cH$7Zu1vME-jyIAGUh?eZo)0AfOCXl<-6NUBBVKN(l%& zl9@_&8`xmaJ}6+qmOs3tx~jNm4ndU$KzJyg15)i9?%KsY;bFJu+hF|idu<3oB8wRqK za=Z)Uja>bLn>wTYCF^G&wXdb~&|^Laja{(o-@^M?O3 z1xRY9Bc^Rwm{6`K<)!?--#2U47iff+G2e7=uln5FD7$;HpwBj5do^))QTI?snqo!$ zJZuYhHK&-6rQe$;0VsJ8%sU5mKiAxx zj=Cm8NmOHr2f0`(h8c%;Ml=@IoJ0mYo@|l3d$Tx3h|{XE>4n!?rxE+!Wpy`JJeGG* zyIl+J`h(lp8D&H+m7 zs4mH8C^H>q43$38$<}?v4irqy0};GVG5*W`n7sGrV8 zFB1-!Cm|qemc>>X7NK1E92Ad@Ycp_LZvp_v|D?5nyvDK~VUL%zk4fXinu+E`Gvu0v zuKH4zc|?yoG`-8OvR2#qe{O+<`EM4@<=TACbxI`NaL$l-Cqs|^1y>%pME8_;w+?=w zDa;T<4l?dNJ*8)HC~E#8TBYugdsba&ZgqD6iCX`$#RkaCL)VJ;#Ka}*j&>>;){h#n z%9QYB{A>t7D=E{*kY?X@e_iI(kh~is`Ycf9GcWMaJ>i z7AHp=J#N5Xvi!HhN|knnp}1+$UWhp6RyUd#r|w(nJ>_*J`8854k52mTOEQ}T#Q;5~ zSIl_KfG~tuWk(=?L0nd{Z~Bp7BczzAjEA zJ(t#gl0k<$RC4hbC2g89cQqIpmGMb;dS|@b8W7-^r_Sp9d_$C<~%v zhceLTw8sqpX$p~bqrbT_)F(%!*NHiCa#U8dJn59{2@RNyQvjmvzo?0%a}Nz;>$EBz z1OktdE9JEw4)LyW2=LxZQ)CtOW|@u6fB0IkT=4$NKe>_ z1OWK}E0WU4xSNj7w=d%e;w4IeYE`ga6c^9p?E6Rn#gh*>J{B)?q}fX&X%zz_jLipB ziZi`_uP2ajGko|XldP+IH2JU`5!-t;ZwoM?2VaO6XbZl7L{{{igvw{7*fN=O@?yca zH_e;y%`o{EdMU(gGA3%^a7U(_ekd{GTU(vs!+vW*n?-E{-Xk7S?q()C6NZ8M$SGVXp4J!Axh)C8T~e(YYCkM%Ps)gg8rvRHMduz4a@x;Q>R z4$C2OL)XBP+%H{L+GoG@-bOE#Tq8cVK1rJuzq<-IrBPk{^oKEcq;JD>`n*Dm=+xcw zg?OnH?EN2g9}Dc|wOgtwY+YYRHQJqLIbxq86psM9#Zixv^&;+i)6mB_z~$*Hp-Yw) zyStxNHPTgIKXnWk*DS>ZreXB7V;HRjCAr&9)W8S%9~{e>OWjn04NyC`Vp!t zU9PRQbuu=vC1L%y-sL6JQ%-#@*+Rne;=oH)sVwO={Yc~)>$AK0ec+~XCI-t_OP}Is zkjsZdjGW(Tm-ppSzc($=wyW2OV^+b|#jQEhuXw zZp^g4!HN%J3={dSLjDnBcx#c1F~LA+j2sgHC$s42Ir_9SbX-ZAoN+5jOg;*~moTF) z)50!VW^KiZqmuI&^T~gxEj1e&v*+mzkvnCNRQJdx04RQZj`n!LrVY2 zz2%rU6mSG*la$OaV}|k81y9(bP)snYJC~x$pES4S$MLVZo!YyS)$_shKN{(unWxa zlX>0aQ`t&SG z7Hz6~HXu!=*N$er_+zQb$1fm2g=jiN-Tp$9D1`{V8{hX>mB5q zmijK~lpWC25XTBr0WuwRYQ-d5`_W5p-eO^pu=&%mnT5%3K#{27odYJ7KH(soCy)V) z!pB6)84bTs@e$*El{mq|;t0L;?IEUjm=g>#gS~$l?ryKHj&WTABBR}tqCY95V8os^ z7XJz0-wzVC8u;S77&9%&yem!>^;_M@4DVk-;UutnaWBDHSUG%u%TBXE^JQAR0xsdZn5mG>du z6=L@fGQL&8A<>#avnNz6hcEw6;aCat3$g7mt!t(dYujl^?xnH?%#tW066 z2K2D}xIJ0;ze>m3l@<@-^gXGv{P9u5h2}|a{u$yCG?r@WpxMvO>FMBxEQaRaAqXJg z1gZpNBe0+1lZrlvTh(etKFamkS(O&KUQ|4LeA^I9M?*#BQ$thd7aL9!y%JLbSaiVY zJ)jmtbD;g5?nR+f2=gnekYGno!T+f>VcbFAZJPV^CLBbA)%PZM2eup^NPVEWNPiIW zBFP}T_I||C?7=FcV$xr!ip#O2!2SAx&^_g|fu`^-RO#a(7WAZ8rrXB#X9gJ$dXLbQ zp4gd9q$iw&AM4##pZ$-=2XdhD1`d^Si8saR>4;LvzXNJS^AfL71X>2}7x^9@7%5|8 zre^O=zL&W=gY15YX*@f#klGGQgr{Qyj>5h{{)tGF`o>oKaia-DLVyyk8ag(?wE!Czd9V)=iatX!j+E3DEMH}715C{Yo zhQyqE#Eg5yY~A6V);#5*OmLzvK75JBziJq^%KAvVT=smYn8-3($of6Yh!Cwhk`6!S zBU=nOB^@IHe8g08$TA-w@&}m;Y`%%!!Yj=C$qCa&jp%svtYtB12e1)@@5=9={E?6E zUBwZH4ojl{0S~)xzBD$8%eF8p#@g+U{BWZnFuD;Hxbda2#4)~65nklZ>9?({y$HC|ZJn?vsPqr|7?k}i;U(3+jeQFu3-VWvE>0-5FLL)Ce?mYSe z70jqIc=WiZM~Yr|EB0@A}?gpoX@#oe&l+x6+y(7o*qlIJ3s@=y`yKa4-VM%w% z#~jddM{ySw`LEtww;_w(NBc{Fcb}>6rz6E=3=ou_?#JC7e$2$Vg(n^j;igyIK8vjX z_AN#KW!&@tF5CE*M)^c=!ZmrSUf_+wbb-D<89HDuV-y2o7NwYB|5QaN#IZ#YbDi_Rp6L;es;Lh`aw|v|%1t$@g-0+lO}4GRXBj>Glpz z3?5lL*LzX+5~EwE6JX=~r!0h|Ssj!t|44IM^vD%kZI0bvE+$HJ_)dHs7VHTP5AEe9 zDD|{|@uqD2uQ$z?bGjLwg{Bw|jsH{x0_a5>2ytQ6*ZuL5emo@l6D~kD)SI8DI1<4k z%&%KlF(y7uYBEfD|2>o-BCSk8RDtLtEd|z9nP!YALh! z3LUg#62n(C=Mz(F-63BE{1Q#RhJ%$H+?PbhNGSr*lL&Yi#V7<7(_i{lHbU8JpD zAkc;?pF|tF_xanE5y;yxP2$0O4jU}$e9P^=hxYV^thlWZb>Ul&Ecu*1gANs+gZJu` z_GE4#)3Km*ax0nseSj3FTd*FTB0HSYdxZw{1%(?mh2cqsfA1)-Mon!u)Z`un0ZfVE z#}0yFV`BgTJY9SzfUT@MP!-jURG|Y<1@-ukLH9x<(s>Z_jh$T3746 zH-RJlImTD(V%KUHgC6dvO~%;pWW?dsnRvjWFR`hq>Aft>ky9di2H|oklnG^9Yohz| ziRl%*riL38rA0FSliN>;L6pQPnjT)a_iu#{LF=efGAFD0f)*nmIS>nSO2sp6rCe}c zJBKbN2x+i;OsaRib;E#C0CH8t_0ogtd|i<;*YDX+`Zu|R)pKQV(!mmWenNWUk;;*) z>&c$s>(SBmLFM^gwU6OXLS{b;3CQkJK@Z@(^FvpqmuCew2=5;c8`(+MmYWZB?u$@0 ziexy3dPN0vnx*7-_gUObw0DxEd9 zJ{+oV_jHK>pvGE8>~u?ml)C?MI4Qx_4Wawvz2oBU)H|2Q_qbpLnlb~9TTsfVe-u@z zBri4l?-GuG)`6zRCi-0EsY5W3gMn+E=A3bori>XX!$+9FNlCQ&_uUXd9GVh!klRL( zq#InnwWvW{b#k_)DO^aCajXSF%^`pEi960M6I^d1dYe?+b)DfbnVK+|DO6puPh$Pq z^|{jma!G_;Tb|OUn(zF}-hG`vFPnB0?P=G8*$Y8*^Wp=C2y=!To?S7T5r|H%sL#`k zWCm6fhpTJD(%ON%B{r$HT9;jNPN2J^Ni zYt*{zwBf@|4Hu=m?@5cxQZ$%p*OBtPje)do-!FiSCt_z3J=BEYY3%9?x}1uk5T(h_ zKzvHgJW0(K@BY~M}a&ZHUmqUKgSom zI-|o4=Xj6;19ML6kjt!HlRMBkH*v$MaNfzEL{4HqEZ*%z5(S$m{88NFMGGr}b!36B z>Z)*{9`w=AeT|cLHi+qEuR#pqH=I3JJBwF$m9`tdBOZQV-DLh74UU1)V7Bl_(`0WS zwr=5%{sDxzq~x$iODqu>_+$XI7I2cor=+B8@9G*1mDTMP+pS_5kBMyk8+EwD_{C6B zbQnH^i-#>9?@OXjLFl{#YMI`>rPuFn?+v|1+uPzg_D$s4;p#g+#s%1_jgn0RGT7VV z_UtM}Ve>a)k>)4b`cp2)cPDtTWwZ77$7)N=)~Iw429vU|cAESzK%8St9(4#@7}lh^ z=&eeEcpKKIf8MnxDKc9`k{leedHnl52mw8vy(&Mou&CU&^>EYs0Z}x**oJoD+)(*F zdzM%jc5f&xEvHl-9Ee8dZZ+p=^y=lT<+aUitEQ}g|MZ(A{@Xn2#Raw7{mE3IXG41 z3vk#EUwP?;)SSg0ue^*DEm`DE`92jsAaocKN1F-nWbUA}*4+#Dcbr(wT4gnL49WFd z$>ccz9`C!MYQO%BS#BO}-dej;SwHHGZZB%jj(rw}@J~9AJv+$wDJHcenRj+`RuRx} z9~PHhvGF6sv`Z=ImK?2|6cua7)Gr_h2La5#_)-5@B+?(9t*L4XyG^0U+c-Wy~(udNtP&(h?wwMyO((t8Ki*N(jb`dILsuyq&Y4 zzhXVn&`$@@0YB861hm9yxGwrai*&*eV3`bu$dgFn~Jo)YpSrf2UrDNCx z_}thdY5+vwAemomq!)XqQ#8RUU~ZCewdAo}t7VdT^HpAj<0_uY?Xg~DW_oOOn+sR` z4=go~F0zGWy$oefwZ5J1tzq1~iL${GO%u#Dmb3I&8(uP~6;JiEt|DRkPWLGhBbnq? z76VqIl9@t}6{9p!fgI7Jo1V(u-w;qLNY%6VYh5{N;mo-O8I& zq0q$S_KnK!o8ie6RC~@iKj{&8LIqj~wHJDCXwy*_jl)JbG>_BYkF9`H+doHaGva7} zfm{AqrBi;@)~6CD3a3`=1nbPV>~M$kTS5Gk&8Cx347a8-j#V)-?*~Wu61K25LVLEv z-Qv9%D&Nu67JVk7w(T zq9^4>DCKTxY#)Aj-VOC$rW_yM^Z%s;u(vxrxvS%pqn|sZzz58X5rsN%NjiTPKQvGN zE3^LS;5325z$4;gVdl=UdkUKKIgKfR3!OIVj`k)lfV5P)z} zlLimTGjOZm<4$`wp5>`XoL5nN1v%V|@TY>ET{#p9GTQxor9K+V@UQcjGT_9Lw`eSFM{W zi0@H`I!epfUpIZ1n-8sZP)!nVwtdSSIVF{aEi+AhzJR$wPeG5Ac|bf&ZgV-ji~N$b zim%~~7_adll#pqrVM1mA5xBC3U{AK?ti73Sr z-_ip9W7*a|6--@l+S_#*0Nq}@w7l@ZGp*3*^2Mx}<-|Mh89jvgjrA_h3e8NbuSuO+ zSs|ZbV{)VkD+QX{T!3}Dv}oS;a+Zq>+8<_PuS`)@m4xwFe-_nW{37ff98UUVvJsRz zw?QS|d@F9?I-xLdmz}ZnP!V3~JncNyZrmp14NLEB?NFal{Q<&^`SWzSI;n=Eml_?> zNlF`%$Z< zq|c?{TAAxdsngZF=>n05hf42Ed1FqVB9(;nJP=jLc|j~XIkGHJzO7k=%Fk{Ig*O=Q z2x07j=CmkG5urM+X@}k5INZ>sT26^}^Y;zrbqy9@KjiU~aeOcGvAn8N+LtK;F)6;n zFx)fhGeG23$)n$M51+YPo1h7|83;UbbsmDuP*r zJRF2nfFns!`_ENk3}BZMYMf=QF!HWlCPF}oQ!!ZlhG@ACQyH-Ih%>^2N=mA0gpCAU z7NmzMh6jbk4;0ZO(#YN+xh{c)l{jt20Ku6lRNo&hOa9d^jbIK2tD*p;srr>VEGE;$HEAAR*%;7@*DK7brRjm^G=?)Q#eyHK%vV}EZYAbT5iK7?QVJF{h zR9>!|7Nw;Za7x-|^sR$mf?u9yvTo{DXv&I07jSKxqn+8lvG1Iv{7?hFnas!(IY~%|`SkEBqzku$AuO+X{Y3*YVWP36N&J2xt`~NccjR&OW^7{{5h_ z{j$uDd&MRe2s|2{&sue{x-1|3OGRN}N${bR@Nn65cw^*p6Ytw@{$_*JX9@~2eXhk9 z8jCf&|2)v7*Mhr2`?9bhpdNvd$ZvHH-yw9$%a&qEW$ zaB5wP2eVm(pyy!O32u6FN5cruYR-5%u~4#ff1HWa|j#j{Eusy&7PVl$MZ|{IszFCL|>C^ACyxr0;1v zWGcq)!LCEm z>`}FrNNI$+Mq!=jbO5i(9{GZ&CdtHa)2zwgX1tmH-i_v^Fd7sw0e!>8;>E-_#cSr5 zh0mI`(ISb!`5GA5Apz%1MTemwtF64K*wj}>Qr@I)?d~+fu!L66d2lp71aV_m)K+*^RJj^nLzGjHHpbmdHE!?E+ zy<>X-1U68)zeD^-X9Ja27t20=BE6p$?tMx(U07<%_V@7 zlsVZm6e6hBW`iDvjZ1$-r?~j(QbtjCJ!L&uZ*tZ1EMJ0Zqg~!k04F*H;7Y=_ALoNUwG2>2{n?dsE%1#8iNjEi55GvQ|q}qt}vf#2_k@qZ4c1ohR4eW z3aj1SgAhxg)>D++WWxO^)?!xJYWm60U+u*(_q+Q*tIHH0Ez5+HMaCtE{k`T=)NBA{ z2DgQr_+iHR=0zfrD+{lg zZ(n{{-c7qKk;(2M^3Cc1pG9|Z1lv+u_>DvaW7I!g4hSL;Z{9C^v((!m8^;8ce5CkJ z1$>>U_eHYmNaZZ&>zTwEOJeK?=rf^2MU12NKCvPJQ?@8H4}BOdwXa(;_i%*uuLg&8 zQzRZ(DPO5JeL0jj^n(b0+1;{?>ZA|HA$;Il%AVGfSL69?kbg<0){DikWeogeHlkCX zdN4wXD@TcYZHlBb&O8+iT}>VC(%~6+^Qq;j6So>};!Ff~fSzoe$zo}%I@sWwpu89C zjmYzxKsPBT5`=~W?!e^)u0jJdI$=zJTkdZ~F?jVH&G56wfOxAP4D7@iRTLgbSF|*| z`QL5{_5FFW0xTL;VG*X#9?Y3uRko$Yi6B(PMfWj~XzT z#Ytr)5DUUHLx6>w?^x}`UjFJvm`+8_ys*H=B)H4WhCM;U+6NvOAGCuQ9NQP?e41hDUaSHt$}lpAohu(IwpXz-13=`Nm4?J<0;Os}PJ%~(E6)6j}#lqxu{ z@zdv?`4Azf>JPNx(IM0v-}FKnmW036;zGQIwU+hSBr!tJMP2cY{PGVX6vIOoSLnnvd>ztPtW%8BOX#7(Ek1`yd%B4 zqwMXQjCgnwdK1m?V|o)Piqd^UHBawyBTnlD3vD;j07eA3f9urM%&JSdGpp2=Z<;T2 zJ4eJ}4d6$tOZC0*MY=#kiPoxL6(gBX*WtUP3nLhUk!N|Nxby}g)?)qBk2@_5l-toT zex}U|AsV>^s~=a9m(?Nh0<2juQcNl98!UYEkkyc6ZGVgBA)44vfB1J9L>xEt{4y)d zF{HJbDgG`1X&SHN9b;<2>vT04XxS-PXci~+VerjsjXhjx$V#QH4{p_z-_}F*Axl!KKk?Ym6h04n)>dpx&e;IzFaEX z3OkDR9usi{Z~|7ZDFnenI3_>64I1M~7zp8`voLC#i8UN7HK?+h`*T~e``~IgonO@! zv8sCUXBAJ1r0L^B%MJsfZ=A4J_kEBL%hN;Iu%C4siT`PU6n`IXF^Kz$-`$FCYwy~1 z5^BF57p-PE;Yk25wf!xKa~u_kR|MT)sWF9aF*p zlp8pL2Kh*iS>`2HNDWdmQ-dW(nK}3?^VXkf(Vfk3?xjy_LBWeYn@`i)+b;;b79E^h zJ*BMBT+UuREXvD!@}~(jd)fvih*gCNdgoNvN&M2#_`BU5hrB0D_0#ch>TcmgJ^T`V zjmJW8xpWwcP11z9-QqSXMj<_{PE=wE>+`*+_OAC&sic*e(vJt?LyGJUex@!S!qy>- zar7mctCE_X%;5FJ??0;8MRas@nI_Dcy&h$>H?HX??7n8MW;8^;nfZ_T+zy#RI<9g` z3CSy+`4r=W?5yIb7kC(Mgy)w54FboA3*63>x1lQalXP8?{)#@?7>`C7Fz#Vsxn0xh zbs!Z~<5NX(^QucUfF3N2vAs)>c$a|L%}@_m@zOSrvr7orTN>(skk9s;SF{3jEj4E6 ze3xu#32@fA z>)waeW?+c)Rf%8n!m11uF=tWoQO`U_NWF2p%^9>uas9f#z!IX59%iBT)n0GFB75b( z>)g5ra0Cg_P+`$zaX;Fpn~pW|3qes-RIa;PsQS;RM#bZ&>&*;PR`AU{R_QmvN9*98 zn_X@|Z&(bo22*bwJ5y%=qHf!gW2o9A=Di?=rV@z##vU*JmEoTGa-&>M(A z{@m3~O+7&A-{f5vD1ZFoVCXPMeBqmPyRqEnO^9wp^Wei5k(`gX$0WpF*5&u}S2K0_ z{+o}SZ1H}B7}HS8MJe1ti;V4r5ajjA6FMSr%R$XGBq2?Zy4NG}%(9BL6wx>E5nl3| z!?UQCrEDAA95+*(^Ut7qs7xA5uk;fWp4PgaM}dr_zuOehb^$%=w_-KQsz=z{P&soDOO)gjbQhP8`mLeodH$@(ExXK0)r$sOWEBESJCsAqC86%m+ch6JTL1)uv$mn*#274aAD9pRfY(7c1cZ-v!F~q zK414$9+rChIhy>{_1rksVN+w7koil$aONsaY|g~o1VjDk8>6LVFq9ee*4_%R4X_lX z+N(u+aQa=&5&xa(W=x!Kr`f;8ZJV<^)oDskz_s<(aI?ImMHAVVgbmrD1y<}nj*bJ17hYK zbSfb=Yyif98kbzsSNYx=`I%-))VNPzg93}bB4@7kv-n((0;?S~Onw_MGF4k{HUp{# z-#artQ!}1SGaexC!va|4&OUlRTeOFr()z2mqRs3IScHZ4E>}81( z5CGP<1ISvy6$`N7bx1VhH4SMW=qzIT-okxn#cUvrpu5 z&bl!wD2T>^d85Sp2ly^FOBkrOYPPqGPX{HIb57U`}vm9o#E6v7PKpBC*X(jDXQt80$UwGLe%s}LYm02dA3zU+GDddxmR$hoPgui zOuFmi$G&K_6bWGQISG(t$`I9*m(h=-9<*4VphzB$Na3aN zn)-}KAnG<)r8Z21N1W|LZ$seB0$dcmKETP-6GXD)3Q} z1KN(&*_z@*iKQGmkyauxk2(&4?78MgnSG*sLikk;4SpDROE0I#`-9MNh>>nc3t9$( zP@j!hf=x)92J1pVQX`k~u7huTYLJ##Q*+z9p<lSJOKR@r?!!ucASa+Ubz+LOJ(dA}sKB?+%G zg^#sq$g3*1IIB-h!kv*a?6^w5^{9L~FkoFFuyWzmf0WLD+uI?$%z7L9@PPPha)8$? zqVTD8smQ0ZOhH+G2E^~V>y_8I!N{LxusSg%OTq$vUXT2n|I4Sv!X8NaIPpjx8{_T@ zIme>}E&&ieiVaeD7`|F|CD|HV7uRyl1vV5r zrq22y_av>XZP-p9SuYaZVNE6YvSzuF1f;w1fW@`gNdY^4Uu4M`8oqIR&7X_Z3#Lks zZM_~r*^Z4b2(3sGy8E|g;s&g8JaAWW7gx76@GsUFmAPrBN z80@GfXQ&i2zWfhQX8{ve8?9^H-DPkaq_`J%cXxLR6e;e--QC?wf#P1=-Mwfj?soQn z&dp6GkVy!ckg)dmt+n3gX)j8SJ*nwW9*)2Ik4B!HY~E}LBu$8J4MPY7o&>!+eXl^1 zR^Nxw$#(wU!fegc?m9bjyk`e}+0p6LWYND%ne@@Jp77VhThk^YqL5v0APW~s;fJhA z#PYWa;FKc26$BE+{o}x@_e(F^$SEBZ(9Z(=U4Rcr6H9dSCpE+`ppa4G^7N}gDCM`Q z<(6DJX*liQJb|KrCz-ScTMrpCRU-=8n7X49Hv8B3pEL{>x}gF0)(WJ)ul}Wu)JQg` z0!2w7j_XhjsKUbnaf^B`tCB*6_!m5|Xo=ymDB~{4uJ(mW^?#iqB!kES%b6xk_v0S& zf0@4u`3HD((Bb}r7D-pRFkuqR;vEc7zD1}{36g41(YoyDHXotZ(A^avAUvVIxx|+F zd|#U0H4NYJ=3Fts)wUTRn!R!^Td(=C#YBOn$~%MRpy6)H8ORC2Pwo-egaHKph%gyp zYA}9C4Z>j(!_@5j2#ZJcbw0F$I~$gNXjNm}k)@+v43G7q@T+s=D>NJBvX4Tj@ILjuh6heD z5L8#S82;NHjJsxG-a>`_+On7yGOZvqig~mjzPZHu45Y|JuQ*^PxoXkaiN6TDa7?uG zrL#5n_Pc?_D4>^fKTt_c!B9)Jg3kLJ?5M@=Gy(+`>djG-otM1;!$TS)FCOz879^#0 zD6lC|v$^d?NXWalm??hY^C)t$N>MRrx&y~81sf%W71dIx?4I*Sv#E4(A{SM zx^};oHB36f$QF{1njpC>ttwxS^ymHPz*6xv)rd+zCK7vMp8KktM+$hghP$@} z$l#!IYwJLnq=>JP%P72@tY2i(B`OK!N-e5JC?JYFBp0VBc;0AN8z))B#pyjw3rq)(?(x84BSTqHit*z~Q?k+At=`6-( zLiy%xI%faji}XF~%~RxXfH?2Y&W?y6iM4NGHq4&DM2WnS#Uh%$VPVx-;lD9R@(G&! zbEK+&8%?PHnQHcnseoj#12?f}>MipayR3U#(ZW@TS`4j=oU?0{Z^_)R)qroMonL6w z>n(n6pmK)Zanw>p&ktpm*#bZ{tm$ad+eeI9_b#Xxw62F^ahZKJ6{<)Iq6Fat8)3_- zNi-4~%US`pIUPSuT+hoL6u^%R1CR>`lj-7JJUqn01;%LrMM3aI1p`yC7=&o=IR5kx zgQ=^XS3r|O7r~G#ub;BMU#XdLRikcAQmHg2eDKeK_rQm{0B-IToAHlnC}}XcEyOV| z)#)8?rbfZf`0jbWexJ_v*52`GWS9%DHcQ07M)(P!hQc7wUo*zeUbrv156aXrAyl}20;<(~ z`_Sw4S7hF%D=59PmU9d$UjNDz`h@sZZhyI~j%_$+@K8u+>0nKjz~{Sb13bW%Nf{CH z4bATosGUGC82j}SUby!F9q=#N*VokdlnaYSsqD;9$%K=WiU!x!@`ikN0sJLVE0EkG z)-)ty4m3>RQ4R5gm|eujz{n_(S;>kaEI zbi-H`DS@;oT@LFl;*6LhALJ6-ATJ035GjJ?i?V?{o_UNQD0jh`Szc7;qVF7 z?yA<}Ldj)gW{qbu=v&!Cuc;Ex!ZmU7Z?Alz|KBL>yMDN)Lj)zY^6l1d4kq{%wbN~; zOc?@v17mnzi5MFPX#EstrI{DfKKK+|N4rI?b8pQmBFVrgH7DSS38A8C^^q`z$(@a= zH4d<7Q1k7BDGfS5!{SNuq@*a!cK$&=noZ??L=61_^(DMgP7Xq~cJ(i{njQP^bWJq; zVLmDyUwRq6zbiKs`Qk>k3QxaTdA8$OR%lr|)bOBq9R0TY9*pYq@&p8FQ1{Umt=1#Z zlh^^oVOgP&D_R?)q)~CMOPjzxldq|yFE<)SmC zqDWC7Sj7SVQ}{a(-oH>|9ZfAg4rmD>nIyfccb!TSPJV?Q8n!Awu{9b4V4lo;1l$gE znDOn9oxe+!BE)XnB*$Li#Suq2Cb(`$r_$jN$aa#;-UfD_j`q-ctyfv^PloLbR%_Qg z14)R9`)@#vXwxhGfr2!)l>8rV2mmKGUTCf;c8mV))uzP8Ib^;TW5(b*f@D zp$5xN^FPPVvQb}kSD7$4ci0luXfv*rF)})E+k0Nv{`|sjx<(`#D)&jVO0B--5CK@554OA*O8#4^uS26h0q%b{j5~{9${-mi?Uc))q*S#O367@nSm{nhT{ivUCT791fAq&lwJ=SI=>rtM`c~v%?M+6#c^L$ zRZBocWk+QU>Ia~{6N2G|6nX(RTvpKoB4jl?fys*E9vgEilk(GD-aF^WiadT#P>xfCXo#9JYjUCH!zmV4+z#o|N5Xb@07-~RHHBm>DjZ?UN5E1OmkPP)* z18i7(mKn&*G#f_aty}obo>$vM4OGB@raDG(dJQwHI3pSEWZc>BJ-_$*7Zgt>D8^OE zYHZjAkG2iBI{3kT;yBDxRyf{C+LiiulRl1E@1>0Ia>|Xk;w!#)hi}S!_Q9$9ahRUJ zc_Z(|y!1b!DH~vaT$owseG5sjocL4>ox z0K-EJ=u%rZS8q2r3FZ8sAtgu-#7hMpNa6@K`b5U{RY({G7v6y5L%`=AW&96&C6@N7 zL@(a4k_}5FF%`5vXL@_ zP=!w`*OqD)w3GYpdDcgF#wcI6j06Q`gK6mt&N~l#nyGyb(GLd}Of@`Mo6ET>=aGw_Lz=tp z6qBz<<{G`Hf(CX!mxb576}%2?!y&O**MTp0X2o$V5x+2J>dV1rGSG{9*nC3?$`e40 zOK{5NCuo=y#)+WHNS39S1l#pRZ=rFGd;aF6``HE!{15mrd5uZ@ier9h|=fmyF29P8N zw{;oS+s;q&X=uhG6g;GO;~tU2mR3w|S*gxhzzh=`RG)XKZKcD8Oe%siT(#x)ONTP! zwH=p>>TG`DWhv<{reyqsj%o~+2{KY-UirmDe11rCDRkgF^^TK#P&1=c&=Tny41Z+( zxEDR`?BNj%oTN;;TgNoKpmU%hNnjOFd6}Ytf8f2R8|&kCG;}gSK$>yfwag^3wjX72 zf^ePd3Z;$Jz@BHO2O*KP>~3L>aDmtu-Ox4fnk?X6Max8!BUgtA!azjRb5D`{4h-DG z!`<3L5dgy_6u`6%yr`6gh|oha{|xB4it6ZKh(bhEdJ$=?$BV=Oo23A6@9HYRNZ}pW zA4b30ou_*oO*h`FX6YGZ3ApEYU1jkP3b+NPK|Qa(j~U>7k{=7@D9`W5H)5L0ymxYNbFqqUW{VDFe;5p!yO?sPtuN-h z17~3PzI+@1{sn}L^k`3m#30d>I~cUj5{;BxG}M%1Myak~5rzd1{sU3UNIpkp7DT{; z$tv9o!Xzp3T;mMo6R^eQba)~?C6~0plL*~+NP!B*`d+OHJPmkeg-$R_M8VuPmfy)q zOBX7f0}+*+bp$0eL1v4$o?dLjK-2jK9{p+-o@}p`UkWk2&dvy$SAnbZ$UEF(w#Sy; z;d=SS$-pFg;-C1h?^{Hd+mJs%P9iN|JgM4^(wA9~c_w_4YIV0lCC0hTRmw#dQ{Co2Gj^&yz?Mlk#QIaPH5RlmNs@JCk! z3U&f_lpg~UcZ(x3Sp~bcCf5{M&i>!Opt};K)AX`nXhk|lR&x!Ey3h+jW@e+^2LJ@> zutdC|`5mwZDOjs7XqF}!OgOUp)?-ncMf>O{lzbmmnYntLav5>BJISzUfmhu8v?djj zuI}?iQ`bz5V;i6)ag{fMN+ypv`>B%@+M~R_qJbBNmLQ&O{pYwGD8m#ZgCy6d=lkV* z6iL90u7LCKmkfduVXy2=0>k8%dTG`(VLvs2#j&;M}Iyr zrOHk&=}z_gu^7`Sdk%s;KAg$WVZur^3TiHm)vu(Qjrg{3jxR#>I1w1^VwWG?3rS-G zZ)RB1Vtz`v%~p#+Imic#cibB62!teJgZGNeTZ2PVGT0h2r*)m$Bd4gfOd)<~)j+DN zRL*`f(O+lv6y`ORxyl~9B9gyz7BHS*>uK-z^^g1$Om4c)eGIr);OS|g+G?^ZdJjCP zta~^j*KfHy(AiYDnlEPWa@S}a8kE%Hnle4zC4Fpxqv_3)m}oyLcXrsD3LHGof9=(i zl%!DHAh9&B3XZA*b%q7L;15aJyPYZ~Y!w@L>X5g&93D7!*1Y{1xtpP0A$)<(i(Ook zJ0#NkDzi;@LE2Z^n9V;v$K#uFJ*A?73(|1e;cntLP}~klqp(GjZitC zeNkEg!N;9d?9B~4Ko5awx#43W!IG5Qs~n&~&(_CWZ3eLPc`I{b}NK^+N}OtXI_ zHI=jq_mo)@YXsrAlaLYyt(1{1SIMQIg(U=Cr%nslm$3#O8I;1Ul(EsyP2==XAX3oI z2|U@(D-f5U1Gp(WH~_C^5MG(|zi5B2a`!8!=k?F@)t~hI{c_a!8 ztpNu%1aSVZ;aIBzR>Jr*oGGvpQdg)^&t#>#&>FQ0P#@59@qIU zt8`H@s`jq&O^U)izEwxF7=39s@}$UTBO`;oy{~cb z@ud4F#prDGWydqclHo@z##>~(7UnA@o^RgiDc@ds3SIIpTuWuCdj4e=clc6Vv@@TV zEVH}DGhP_iD}Sc!zG}3aI`ac<+t2W3t~37?*}KOm-{0-I;%Pai5_atQ32P%H@MU{b z3C}WbGrO_pY<0arK#B2!8!?v4@vd~&Y}4XGI{m;T&_*!c_7*%1-P3`0zQk2#Z{E)v zmq4VP*XVaR!LE1MzjDM!gP)uU zZ=Y2VAhW|rl_edkNk~Xsu(6;dg6Qp65C%|Nd)<_hvaT2Z;QD`b^b7-uzSbFHZMF9@i_A;lE(insT{xMHTgy(AuzS z9wBI|7R*cnEAA$2-iLh!k^2;iLoGBg+1E3CV8 ztDj_pmID1~^s;vOJ$0<)&tp`Q8@XU z%T^6G$_Jh7cy!UH3gf{qx&;Uo>Y8@}W2m0~KYtj3t5W2+Hone8eS;A;xCGy$n!2mW zSpRv5WeeUA+7a3wQ{(Q(y@zaY(!F{|xAgLZPVI7Q*7OgZ8PZ+g_IY`|N5gESHg^TM z>Vc`yWV`74oClF8r8{Q<_d8%7Z?`gbpQ3!J!JqndyJZQB9jK5h`Euqh-(x(@lz`!PTvTM&ukwGBxGQLGSsR2SSmZJLJ{_LPW(G(w2`vz!ea?b@}QWT;!Z`@T-0H zx#-BMxmG`IO}a@zug;Wt$+VaI4=9ej>W~RahGLWui^c?o64ntzY^O^WCnVblwzs`y zV9yTV^4@>@@0|A;n6Ysf06RwuE>SqRJ944m(OtFehsVd{_{;nc>kmTztLXe)I^%Z) z;g@H+$LDh6opF|ch-sl095Vk$gz|C@5Q!3NE%E{mX)}e`dR9Oey#K@c_CCwUWPRrF z$^f6CU-^?y#kVgT;ewhA0||BIQ5J@284AaXuh)x=O^U_gaU-62-*W1MxH5>o`n`xO5P{YNw7*q8ZgCUNJ3K*bt-zW^Ou1-quD9uZL}D*>s2)KC$cexlF_Nb1clDcC zdkCiAMZuC3Bu>QfkAK>&dfkJKT`)+%wB=xf78fEMk5oGvHth_x$~%fo;0XnLVy18y z_zzj(M6EllH{HkZ{Pp%u+b;Cz8!$-ma%Ven+Hq`%{-wp!XLH=YTWFI7Zffxx`bW9Q zHf%oOCf#2@a6B+d$P?ULuWP|*4RTOzNSA`V7BHBeKDR&~{w0mKEx5mFhVjDfQz6Xv zDXwjFZZ`JMgHk)jaFO!iRF@Xp|BJKCzM%_-@)r{t@v{ zSNk2)TNpmyWdNXU^eL$SzrfJ{5flzx-~9dqDzrH6_)WK?debBzCV^~cHSx^OxwH1*h|L&L`Vau4n$qubpd!`L(%j6BNnqv*h!W$Ut zXg+xC1!63S!j=9WZ|rqr7uB76-+y`{jEj%^VZhv=Td$&QH;8e0dJPr*2Lyq2%p^uW z!`D}mr^3LF0T7<7E5?wtZ}m^ay}lR3>4Cz~(6vTk zp-k5>XgdrEhQM)-BR4jjCKqd9fho9v)~ZGYUO=eTs;dupnRWO69!Ku zvH1$*)pCJ&te#|$i*5S}de%X|B)U_nmklzU=3Md=rRc=ssTquAi!^rQCc_oOa$qUP zgRd1fyV^u;kf+cOu_jQLLyql@gp)u zx;(^JRLTg1y-GbMU<^Q?dkj?s<9V_>OHm}P;xsbTgGoXzu+j2WLa+f*Wgbf@Ks>dc zJfc4d*3BK^GKkC z#JRF#=k*;pV1ui5l)VZI77T&jh)WjiNG_kDg|T>&6T|HkV1ID7!0ssKB6 zSKS-C+TJsjoK+Spn(8!+$nG|uA#dzg)}Pm3s(I;bu{X8?);(U1;kbaiO^?Er+zevc zf%~_G96g;Ji=vH+AYE`ootX`W}>B7ck zq~MjbH7L|fvLcWm_Td0`p)Uo4Eu(;g5=oZ39hR1)XorVvw8%QsP%mo!m-jGk zkiU=e$p(-rD9FQz*n!)e#mnRupaApAkVRqVEzw;zYNTq&4P_nFLYJZ;%FI3~ZhP3Q z!#M(BYF*PVBj8vDd^Ibck_T3dvL>Ur5ntjgRm;J)`}sscaq2KBZk#9l_76Mo=+l%< zCty8k3adEz_W$H)AJba_u$yTX54kHWuIuJP0bM=6zO>byN)b0vhy_}m0 zb6a4_=jAt7fJ4;0QAybPp})u_sms8j-lXDYiAMC?GuP9JE_p7D1SdmQ9l4JXg6WZ( z+>V->sZDQU8xmMTMY|$OuxDrL6J|<&dVVNX2J-9$J(JRSKGe=_A9UeP3pm@w!$&eC~V z!gy&5-8k3O$CI2G`te`~TJLmfdQk!u94y<<)2?MdGfPNd2x5(L@nL;lUKXZ)bpH@7 zpSKlJxp*2V4A4JkYBweB2^)gpHLuK7HDT;;3v3jtM|5Exq<1D5HtYwNg6;nadkz*$ zzX6(zjPub>$iv0u68e@k_jskD5=ND=Dv5Bqoj`W{p~3^{KCb4f#CZK8CsCW`RxP1!&U(1f5K*^H6EN~g zyz7n%&a}-IXS!>b5jeQa8b#^|)jublO+84Q+OV0)r z+EKi%@RuI}!q&64Y4%$k&!%Vley8Qvk)vh-3xq-UXqb=-c2Vt=^+=8URIY^I$43p7 zjI40nnG?SoDxI)5`i{Mu;9JX08S@TA<|=yI)4LFv*8a{Us%d}{Ou#2M=@JhV504>f z{#2nLDk(Y@6HJe*ZdbNIbS$BeJ${IayoZj5twJ2a5jUohVgo@dES0S{nJdpgcVoy_ zgNWb|Low&o^_x)I<`Xj_uLSs&!XAG+N9ytv=Vrpe3n>i=(u5(E)b8eG3 zw+|dyc!R+4tFy%-#BI1Ho~B>3z=_34M7T&;{`mnHs%*^Xcd~r8W*u;H4{@7G?cr#~f{X2VDYddw5dC@!ods+w`Z^mDADdF+vrh zADm(02Duezg|rlDEQ-DsxoQqV#FkTl|Gr6WE9=K{_9779I1`vwcXIPqRBTFPcc4Wy zFAMp#U*%PjvT{^VG4pWx+I=>V=y|=7#wGbY1gPJTqx1CDNUOi`v)>_#YSKuN3I~Hw2MlYDu0ER zRWgMVj!u>LRaNxSQAOZPB@R>m*g?A8V(E@CT7d)++5w7zK9%5X1=`p=7*Uz}Wha8M zT%~X&=@r8usbI%!$zn2MB3e^|vF5eq*Os=n(ZfUFUDTFMeqMB%;`*pM_!rlxWb{y-$~M&v}Fu=%%PPl<-?k1PO@JcP#%YwZX6db zt>mO`j>TW_$RMt6tUw$Q#KD!=hEqpoPFfwbvAXP2@75M03;YYUi&%goiFt|NDePN9_hJKG?BYlcoHQ)U8JN`~Rs>|b6twZGbYK7?N2u|PKLxk;9p4dLTr zs|$J`wcM<0d8EfBke^YxQDl-cCS$qkj5~%F8Pk8D%77i|CWJ`P-CwUA$GCA!Mu0TlZgK;XfQbIF2dPSQOJphM*DMNc2DCs-RNG6PUNp-THC6F5F(?7 z$~2{SN)FKUi+Fbir?~5To=>6no%6h3Y@^-pYQ8!!@GCJtSdxC*F24>}NNcV>Az~lO zOzIrVNW*TlQ!r&`=b>;_m(yqcM2kWPO}h#MuxuTK|LyfBg>*?%yYyzNe=gC9p+{6y zw6U-GA}l(IrQ_5+5=rLI@!NyM-{X)YDVUDRlDWHV*Xa)EXrGk6VmK?*|2 z%SXrZOE}i*CQQl#jynZw1?CpeisY>UXFv2zj8p4%#goLkVo?tfAfA@kht8$NL?glv zP|Q0>ttql`7Zg|+D2-Id=yDf+<+98LOyXp|kN?Vhcj+h?HQo}K&^^dBvwj~$1>Nc% z$c{O8g7SmiUbXz=yKmL`#Nz6ACB3rj^QG2o#||8x=>6dqw;az-=I-Q=v<+Nz(vofd zuY@t)+{s2L#Yy~c^*TU&mw^fwB^N463liTx9AbhBKbp$3WY1*up3coP+h~Y?f zJ}qUVz`>Wu%HbgM?$9kyMc%wN)`WK9zeFTT5%->*CT-ObgvWoTJK~zo+7fW=(qd(5 zQ_?qJw$}n7pLk>RS9nHlt9vUjUIjdSnM3>hRQxy z3_>`Yu7u*eqe0~Cc?*c+a}Hfbuf1-^`_RS8Z7X1syQWN+^fcmxD2A6CQ=>G|vQs)1 z#W`y7b!@;~eSkpj{s8NcGYOAIJjUl3hhOPYAoFhvZ5eB-OK-&~;&;?Vk_y7d#WeDj zZXWg)Zs$N%4vlbWWztVU%Qp*jX>drRgS476*1Rg_y~x$qLzjv`=dM%m^{O0~OxbLt zv4m*wF=677ZURIcc@caUZv41C0rDc6(5*IvrD2B!aV*IPrM1J8sO=Z4Epb&T-i+f> zCvHP-{KZW6y^X-JYqR44hZW@P%xc1&TtH??UlsmveXqFVELGMS`i@x&ra^F2WHL+veLh4V>4xpy z1FWtfULDp=PLTLfN%@#Dq4}V+i6U^^x?Zp~I3H=uaY*~Iq+h&#u8Q05oflFZ)X<87 zVGN~+K-EyiAZF>0E)Ct!YGQ96-3TU(8)SMK93^2k;055jc)3b)X_kN*H-Z&K7ocWb z?uu`D9SM4Tdl+d97MT9QJ!7+hwP4AgeYLYIZnYXiEjyTBdEdj`F|j5xOc3HK1-O|- zOsMu+qnj}$cb%Il;?!zTEA81t!veuEeSqn15Tl_-cxUt5wmJVewPStp^Eoxb-%c_c z(%_bLSYfm(WLRrUg_>L{1o0$r$+E21?kTQOr@wAn+`E=0Q-bPpyt%hT9A(bH(!L%1 zFDJpBj&1+!Mux?sj9XlEx9R!RtD$d<_0pP}C&N`)tPO*zGCj+d{G{rKUdf@>??o5( zE{Wv5rUXdinr=GoYVPWB2nDBlv{U{}iS~zmvYjKfb@WfKxqrtGgTxmNVIBQuKfXZUgHnj__3Z4<_sr=T`Q&&KUIQgSvUf4!u^ZoYq5d>LU#-8Ox~m{*G`T|j@7m;p zd)_WWmci=FU`>`vMo#z(I-&CL%8Z$~Jkc;O(9`_*^lziR@Ar*0Z(ED_q=qkEl4%B{ zx{27yP|6nt)%eO%AqRS_xrnAyeDRCH2Y8eKk$`ZA0Zli$Kc9Hkj59Z_?mK0Q*t zgwF`0Ty>D796X8WKkL#U7^FrZf)ZUgo5DoiKx!eCzYRJHN;u8t1T4qk(S>)qvdLJp z;&j(_ikHvSRTC3K+%q8TwAnLbTiuV~oVwop`l%l+0>!r%s#}T&^FRN~5@xz?Z4BOQNv1sTeFYORp(x^J$2srgJ z+y4axstQN?-wX@z&Ra1)E9RXooA)OT6eiX*!|DZAv(&sMbrJ~(TA?kBM&j+y$bOzu zZq6W|G@FeE9_NW8>q8TF8!RYnP)XT&_Eg(QTsifk%%Z>{_)HQKMAVHx>5t^m$`V7Do-<$7?(iXp8_neMgn4JWhmom^8>% zuAJM)modqHe}B*G{><6+C0<~>mk-MF`MFbvp2ah8k|6`&>$*CP-a4zR1!i}z{J1` zsrf1KcWe-+A|e#za5CraUa5TN%L@vg^si*+x9|3y&gWwr<%L`21B?XXo8EL>=ge(3VFvp_1MBEd|GsUfnAkI? zBlNwO!G70Mm^@2>2sf)@iW!LT|21qOP&Q%(I1;Wj+&3UCHC0ne1J6xatrd!dCSO|% z17d&dprpo0hZBS&tD|kFzxFM4w|tM09FGy7-52jI#Jp^%kShXP_}C{;Ged^I&%VwEdWBnqft1_=rm~JB*C9(_A!l zV#8MnGhv}Hp+szJb~=LL#b3?B3^Q|T@}f>SVR^neUBYia!Tq|}v}7MYc5AM8R~Jy|@rfb`RF?h8e<)w36LxJ?I%oexia zwgA5Ld1_XB_shQyfz|-@@Z$9o3~AM$ffAzlrkjO*=vZu;4tSJ}QMR{RPSfBb_bQ*P zv@2w4mUbE38PhLwwi!Po1@tFb&@TT%nd2fP`WCw%Kqj)H{0`R#@w{MdSbU*f&xql^ zqjsN#qqohJd}7Zi^TVOOMIN}f;xwyTstrWbV?4K8JiYY7Di9NaAPSVywY02!KV={L zN_w}jTpA|J;v2Yv2!?`AIoAP7yMVkfkhDm>87`&rI(XHg z--gwMlh;Imh@CK&AbxmafyXp&k{Ux|oO*sa^00gH@YKAfi~K&@=+A?w;+KV-MzCBX zlR1ATd!7OTS~#k!bHGQSbcYY@oG3YY zTXRrT2b7y5#=y^^V3FQi)|iMr8EC_ZcsBHgkSu+;>kV$V-2nN3)U3+f2C6f?=lZ6O zz~J{M_QMH3{FawM*KX1-X7G#h>i4<&!~F`IiyVOMIx465*fsYgq<*jmC9)n5T4NQDR*8!l|yl0DewE7&{D0!Q)r9D>jWJO!+PkKepS z6bQ3AdksreBk{^BR`BoBSYt^YLlSk_@)=vU;*TIpN55FzG&Z7G1gP<6fV@msx?sXR zL{RpVa9}o~vw|SDJVkSIRK2{_`5jAk;m_`XA#F0@I-OF&5zR%{2ju=}%zXJY)_3~i z+0fORk}8nx8ch^78rslCyI=a}Z~r(z0Oc6XWo-Zs5o0f>l*#_OsHloW6r9+}!@b1k zehR~4&@qI(Tz_?HZS?2H_z|)Dd6DJ%*&d(IpNjve@QQYPPBY&3pJ^1uR1rk%CuM&hrR z2OnEq4-pssNAP>vjm$(3)L3nL*MZ98BlEsdo;wX##zlp=I}N~}Bv*m{TER@7g=3Nn zLs>P&^&_2sd$A7Xeev%RuJ=rUTf-6(c(#>rHeMoYdPuv8)L}@I8lB(-`CagDNb$%D z0Tv8qbK*maHA$MLB!OPbFK(~%RPAH;&(A4d8h^aHe%XH%M_$BVCrTKqF{PX|fcy^s zJJ8*9&x6=@IHB55KTR!J{0ZH4i}yjlXzciin6(&rH%Si(5$qpn?CL^nG2<25nacgV z(Gw6KeKhTQ|JSxAC<`PlWhj4OZjPivKFj)hkp=Vl5bdFdM+4}ouQ&_l&+FE1}plvW)5 zycYI8$wu`zqY&Z4TU)H0Ximb+*VKQ!=0@j|$Hs28K;CLzN$emN|Emsu3c?rdoX5nZ zCnzJ1PT#(yrsmaSYI9ShYlGj~7pi-%I{{?h&VR~%R{Z%DlQn;kvm<^~_T?4(kIzZ) z@AMd@64H)O+aD|C{u6UhjA(zHuEJk^VD^<*vX#FJo6dF$qwlbyi1X)8QS8h()e=Jv zJ8+wG5}DOD#0K{!Q6r`{GUTv31dF86YHE(BKeFPGsh|=&p^*}uhh9Ih`uemAgFaO^ zP5sJt-P4|oW{aln1?vwH49iT4#EK&f z9=M)DOASE6cXY&r!z&D%U$4ecPFIX$X=@YQO^FZqC*R-qPITr}x!TdL2Cmh1pKKJN zcNc+2u7gMa8xU9kW##Qn@c!Y!ay_{xBW8D3jV-LL;q9TX1&+p2 z8UOzMJ9Booy0HNiVOMA8UN?RkByl@Bt8QDm!tD$D&^x{XbrH7uZ$++(`RQxv=E(j? zk_PMBCIbXH>6#f~t|YoO9I#aG07VjswG!X{X6mJg4BfFn2q8B)Vo9;&s!fUbj*(EB zO}45p8H(QCP<~;^i;%(gS6FF?l#ne%(1yJu+??beF{?&^JvPjpvn&IUefxyhA=uR zvA|qOa_wa1;$gHghG~3tZHpWM`u^UdvMP#N@t|0QX}|hH;ivA9jeyo$gTuLl>(!Vg ze=g~~?a=#sAQMZ(UPM=jAL;qOucr&ZT3feVV(LbxS2krmK|IIln94FFkJF~Plaq`t z(X|-FZ)#b{NLC{p*!k6zFLeKv>2xEn%zEEHbWfG}??eE7mdhyMjbXViZ+~vp(WAvD zwD6Ir2DH)UnvO2iI_jo(%uBoPh4Xz-RRV^NGr9me?NcZi`KPtmufB@_kv~#-{yhh!K{yhDgpNWOB4T z-UT(oH|c7qy@174b|U{~q+Qf+{j<%h8|Ai2e=npNJQz$71x14YHgJf}WhG=(d3!@1&Nks?uX{vi=0^BoN=-(y7BkR31ebPq$7SUAWVz%c2xXlA zxWn=8wbmmP+@#lBiClhx?3VXaF6&gE|Go0nG>zM);zpA*xUsrIF?N=hiVOGWNhlbF zudQofYKT@ABM}DDev{c20=zL!(+wSWn4Jo*|Ts=9Si_#{w3-XzS^Bb9u zN256L-6~)$1bRSBK;blgm$X%$bN@z9=Pw4q$bM4&#;e<2kPH9x*6OHw_~5Iym)7#f zH98nE6_ve>7e7%Q^ z?PCH#-SOP!p$dbJ(Xe~@_BAvp)H5Lv5s0!_$<$as_@XFdn48uM2F1MeD2G*ZQ+sY) z&)aPwV^Ncph(!KfKFE8c9<>U!hRI*reoU_k4(3@D1zIEc=QD;Nj z1u^DWsh()3FCJHaZkOkme#5f*p~d(>uqvw0aT=OHy!djt|8rN!r}=_AxNNPNN=(}ROrK&vF}HQ=4}JYGtnIyZ|*UK_9B4JbCJ(asWi zM=?@VVFMIid8#;j%FQ*@;AFNmKoIGGfCdOc-~8isx&N53Qb%I*Z>G%JjJR<-4o$J* z_57S$M&(8TD(S3^0)|A5V~y+c1mP0TQYC}5?m|BvVf<)yur9Z$qhl_kwoyU${mS~f zxzh!Ny?G9Dh9YCw0O7o>Ea-vH=O4SSRuVoeOSc>FgUrtN8@Ao|i}ja3jX#oKBZaT# z|6W|UoZTxj8@CNMSJNGrL1nz~7$Jo6vt(Owbl>G(T>k6e$y8!wphLa{Uo&k6l3$YX z^uE9j5IB&ZpUnJj3hocOk7q@S97y0rYV|#VV(Gaxg9c5lYy2J&j{U;L9`N!Djg1u7 z_a^p&6%<=>21QIT#*p3%MgAs&eO;rQ-^g~2sl0NAo7heDvdIk8DPL~f^XrE*Z;XOE z3xx!K=04R|_`;_%gYErV|J`k6(dbo1uZ3@4s?%lj=eidchUSd@rr}I09&{klLK+~^ z*!K1tDi{^WXYrQlCymz8Z)84%ET~v1~KeIovm3$g6ebsnxh<1`C zG8&cJP{pmZ#na@r@qS6-Jls1g-O)1?+5Cw)hky9@{1I=LYq0+>c@R8x zq^0Z6fqSWZ-Ug&0MEwokXcx>SYMuGMb{qq!5`tti%#S((x*ZaAxZi;bqRKgmy$Rs6!Awa3_~rlNXwe# z!Jm}QF|Z+I%Me^xR#aym+c;f}6&3BDn2@Usmo)4l#P#*hfu`J(I>y^Ozt32%`=_{; zlT>q57pA#va94YSlzjh;k($<8-93xBjBoCQEYYX zw&0tvpo+vQR&DT1;f z&6e|w-JQTI3x%}FPXuQNt!_tTwjo%zWql-+gy;H*3wBv(Mhoetyq3YuN~uoIlYOX0czi zX*`V*wBpWXCydXG83pRX!{dYZ-4Rx|ukRU`!XQ-fYzG{!oKZ~CPf8`3IdzJ;vfHDB zu8Ohd9E3+wr_&`SlE43Ro}BBocX&cb+8zHL41^#o)M3lV`NPZ$K^~7UZDL7fgVExiuOJCWroyqCZ;qgQ)>JJMTp5$aaVVESHj=AwB%p>d>SeFI02~jRPB-kG&TOVRsw?$7 z6u7)?F7nlxE}emY0gXZO#@EMy7J_kf%1`YS=W~$v$is7u{NM*#*|^rX$??*8&E308BnTA z@g$h5r`J;3gFcB+rQNEuT6kvkdFKr1Ne`0Lpn9KQrb1SleoaX;q%T=SI^gU2E5|0-TDEjhVv7aR9b6`GS5YV6w>Ex z>`G6G-9!Bid>&Cu%wa5U#L9~CsGJFnn_#{;TBn%X7#-E7wl=Z$`SLM&5~05o4dm;e z^z260DThm(6^zlyRZ{sh@&b{G1F+|M#(-@~u!lFq#$x~de~sjx#{&MQs%eWW*m_dB zF6@x`+`}-nS;J>5o>=&H7AS=#Sd3TF_-oJ3{$|HLccr6ab8sl`lu;f}MP}v!Gc@Gq zbbHB>+t=+i;aLG0fNbdQOTfGE;=r@~ZJr4xLJTwEd#JI&0 z0fp6C++d{I)cs2LBo2zy57Vz~>NqZ3)wczS<|bIMwG-cp^bZN=$3q*X^hk(_8@jt0 zVk-U#{kLV{B>>hY<4rkL>iO1E1ZmDW2_F2zi5bo>J}~mjE@1+ScTzG`XhK&m#9z;@hji6Zz`~-I zO0EQLh?O$x%MVcn=hH6J+GPuSgAb{I#c=1zTmm=D&Y{K(hJsAP0EdRnLI-<_(E53MjVEh-=N&*=Q zd=$BUX7P)J>^Z(E0+RkMf}>yZvdAl+PvU~9{V;s_lE>6Uf@9CM&_=)^-n>p2#}36p zybgOfk|@<~Y+G^Hdqr+C25V4b5lhn+#!oXgS9I~ou-ikg>(X?Y!A^9aYoGl?%;-Zc zR`lR)>k%H%v*H5=`dD-fYf=}!NCb&?vhAS{_3Mb}IVG>0!Ez{Ic?qqluU9>Qo4-a} zht->X4tD#d&(xPTfN3k?n(w5BE`qScPMFJ*TKXYQmGT0r-=qcsBOA9xx%EMht4T!} z&8gxNOg8*o1)=)cMYw?=PKoB@mXm$0NfAO&YI-IF(iznwcIdy9P1i2prah>v z(i!O>xOKWpc;BYD`7UK(m9mekrA67;BM;4pgcUg$PR>sK($zrSAI=u62oO3!Hff26 zrK~N*8H0T$?j9M@4neD@pEtP{p#>~kyaLVVX6?+;Ro*@wQI}?_nk!T zzmlYHNT+&Km9?s5lIkC&5ga~k)}OW)&@Z-GlY+B zK2X3ApUf1x~rPk+`j^^cxMP$2$+`QNzQMMX2qKr zVaOD}b^Rk*U)QsQdeHhs|40nJ{!jAz%spY|Y8%emW|B7c3Sg+TU2>Vi)DK z@yXYLrv1HYFlvAP+N&gIfJi`XY#)tQQILp{XUYj_ZHgsgm4-4jDU_A?ZY13Y_FJ`n zwqYm8f!7|$2DP~{s2F_*2UMy-Mc3qJXHGiKoF%&Oy^r$EY+MbHyA7OVvTb1Xa^2kX zCBSvr!*$u@6@qfr=DUl4;hF6}*WO5slsHiRR{UEg!NEKcc*(nrleE#;G33Z*7S^r5 zU6LjI`y%sI^Bu>#k{@ooZJ>0yG3TWmKHS-YA?o zMz*n3Q4~=AEeZk7*vx)4jl<4g%h!i=32AbxhZhV8O{dy8(Q9&ONXTQ++fEApIm9O) z7!;GL?6qUL+R<1%*o2#mJ)_`P(zE$uq{QwUzma|E3uA2(kU1X;$L2oI<84@7`8YNEh1`9rUBSC-pO zpe_!0jb&fBOnut)3kkf!fbc=?^1&S7S&_HV6pLRhkemF%_O@wY-3kwSe1)V< zrW=u6++|u)?aEFKRG6m0ondVMdnCP5hOAz?JZ>;spbR)#|_2zO$3;`aDG?~+(og8P{3${Vp z6tD?yg~Ut9;_nInqH2v+;HG1q^N~)(xgj-zZtpZ?32gP|b*Y$IDrAR=ysNU=yFsdV z{QWyjuF}MzVPI};tov8nU$E=te+6%gBNr~->g)0AmBCrc`|(kXZEYNJYrKQJCGAT? zBjE#2LEBzI;y<23gA1!%Ms}fgXQ3?EV6?E{F~g;V4JFW}6;%&$CDGN9!Heb&6HeS^ zPFyA_*qL#6(rRW3VH|v|<EX9d8+ZFy6XE0KX5oBnV{k~9Ij7*(YzRV3 z1jTP72nHmIG$~Jpmaz{|~|nCKB))!8uWvwD7W z-nkU4`%Fq>IlUCfea(_*m3BCbtxPlN&irxZyL8<0yG7#ZKD;+l6a*g>c;qeLIra(K!$8mx4VX9$lTiv^AvI-)!|z88C$o1Ka9mJnh&7aYT% z_~oIGySyf`2QIFI@D7KFC&ia-xZ74Hf^(HEbB&%DD5lzvcZ}Hb?b4k)&);2zg%kPR zWqeaDB=hzM`4`5y6pytc3+Zj)LxOqnwZdmdM&SQBJgRv2p#O9YtQ0*Ymdu;Ke00+I z^$3FaS9N`n{bm{)brd`XXDoXfn1;_gd>n`?saw{`SG;gn#2CLm`HIr?7hXO_e7*~! z;;nb+7tq7oEBaFS5aB_}H?q+FPCPr>x$5xxR(0wx9K*iR!)IQZ7$?Nr>=n;A5i14z z5dAg(Vfzh{_R#;xrcPAH=GG56XnDHa6&jgn7hg?RYZ~n1=`%}N!4DIH!Ua`$HwZ9yHE+?im9RNDTYFYl`!~l-yS%7!!7lLtoHu3 zgBtt$uYrN!tarXQ?I`H&5uzJLtu2?lJi8kKL|7RPWD=wxS}1AQ44ftVbsiH9tvw=2 zib?jUCS(3QR+8AUCjEX`7{LF-FXFiTi=CW_i4kcrOb$lSTZjv}DVXQu$F!Vy+TOM{ zsru#8Wa_iabHG3Z2&O3(l|JNHD`AOr1(F5=gREZ^)ozN+JstCl7!e15mduxK8jb48 ztL~{=NYTXpEVjNNZRQHJd1<<&R3?*pSAs{@^)(LYe8-4P1{(nfIrzSE4Lp3?gR66q zXoSV6I?du$dKza5Os%0^U0*Nui0i@KtdJUQZc4E&-$gP3coYJ3XVi9nQ}->TR5s4_md zAVAt7uYr>x+o2*5e8?9FX!BY6%?QE*u?jeuG}^z-e<#kR-CnBI10sl?KXbQxR@e@e z%H#jHE<(1!R>Qj*cx_)@&u0CMe@05oN)+GNHnNh{l(nND$EGCg02@aZq(qDZ2bDqO ze!T2wPDdYE5z`ntg85xElr~CcF2R9kTi)me8gye7m^q*Ak2bwWI3aZ~AoT(p8`mi#x&j;%Y&4gmOtdr&Z5bK%LJE3iJ)a2zKI9gCTQi+EpstVYW z`kiixe%uESu^1JTG5tRZ^AIo^+2hb7DEj}LmxU(A1@Z@SoW%Wr+xqhj_ha%nfmy-) zc?G%vaZ$WW{4cWI?wa>CuIiAK;GK8AU4)QPgiRO ztfNI9qd{Z%!ms?joZr%tmI5hA?MaSf;?Pc_3aU=22YX`(xx`NWuPWareC%o;*;2OTocL5#aNyH^#Fz*h2ev3{T1ez3I3y)x zBn*#~aF-TY>K`aH{UAG=S8S7ArKB7L43{b#!)&G0%a6J;I^q_nnbm~9rT+f&9ll^J zM`V=DO{Rp>v-N+m8T9yT5rR$^E>TR2dJ8oag5;dh)a(2s?i>pK6#BbW1(&sl9!mEjFwNktVF$q-!VFZbK;*oLmzTO!E^vKW1gd_Dd3qTZTYj0oO*s!#> z?`3PfeOyW{vss`6p=BKvvll*=dvFt{-Y1NaNVKb^nvr zRVX`Hxp|jA)|+YhZh!7eWL%I+YFo=#ffGr6B9`hAfWJ0tqsavt`B|BiVKMP_j2=ad z8UG;+i0aI^=})$YlfSmiokqIaxvf`udwY%@`?0{qINUkjr1mch#>fYx28yVXc3EFt8OndLo0yOV z=Yngwy4s)@pBZUpTr71)%-Jm*9rL%1#|8!xLf)Z5whJOv^tI;N{UCBl5n`>>Iz<`i!x=iljlONx>#U8zcs~kvQG`7B03tD^s=D^oZ6=qAbZ(4=VmD+P!L5 zC1$T{9~mRfJ3ByzNVLVWaEKDEdDlLFoZ#_|Ki6T1Oy9_;eEl>kK$^U@OB7h2><_%Z z{_XWm_kFy$K1yUo9^GYgXM)Pyp6%GvrjeS-yEX zd+KpqLYF(8Gn+|`{h_Rm-o!i{Yr3;67Y-MPiB0N&QFyH(MyyCg46`EAM)vqsT*st_ z3fbSOAd0MEP@jvvD_diCq6dnUAprIIeUtC{-kWwR^@~3S+_!h3CGDyz_~L>tn1~Gf zJR#4xE{_-*wH%-7USM&w3Qxkoc>fP^1u~vBX6`7ogWy6UvIECoEiN$@G8i#ev%YY zSwE`?Q?-Vm#V+W@x@82O4E$xzzHMvtjx7RlHR^{dObvSkH|#7!HXN@ePV=`<19vnw z{2|;HiPuJNmtdZ^ll<3Rzirogppyo}PA>?0x#b&yOO3WR-#x+5^??Ue%y|MssVMjz zUKhm6%mzEn^}U0OllX+6&)72KsOTFZqBbqH_w{$L9s-0XBaXC0s;eZXya>TmQH(Uo zIa_Os)pifvH}vxu`V1XqY+p8?REgygZpEmQM%<7yoR{?Yz4Kcs=YK(mlR)$P z_j+C&mH3R9Q5JXjt|81Sq7w*F2VX@yI%+Uc#E3@}*C0z3WBI=Ns=G__oU81^6`~yd zGT>L0V>!b@*s*FqUV=)gGuKoYpCnYZKB9ywgp!stwAgc3+Lo*8GR;yPk0MN+tQ@C3 z%_*9`Hxurd_#yvOA%4LjA`eRs`g|Xg^sFqML=J-Z4$$LI z0gMZd%!$`(T4cb_LZ}?B?ygi1G|A@;y{+R1FZ_UcFDI8Dm;OMqwhFb^sXJdhw2<1zVOg&P+#@97PO7 z3%4ilNigw4Owo5uG(9kM(}?Q7^0;mqGvf4k%#|(&p2B*3-39-hcq4e0j$?_Ns;+aq ze7(KBjsVK+uuEYeV;6<9MAp{))jJp;9U06 z{8tE}F24QMtkEG)Op~teR+SjR7b$#W(`y$xdk0h5|G@$Xz+Z1^@Th2BKnCvPd(2o3B}AHTOO>3{IV$jpWp`|CoW5yy*MLb1f~h zQygVf*3p8ustRuD9f`%8?mZoy4|7mmJOQ(NZLp`Er~yhgO9PZM?oPtdqzNq;%O5|j zPTNk)KJbsPkQ40}$5wHhx)i>K%@|eP4PE~f-PkJzGtvIc=EDkGz`qGiv?dCj zL2!Mlt$}UAuflDWMJb_5i~N0$LdsxSq0H@tF zrGBqR>VIh0ptAq51-B1d;!7d4*X7Xb+bQJP$n}0rBjDzCxshmqACcI?!t3_@@i~NN zV+$|^y!{G1oN)oGBOFp@L^e9H(mub7c!g|xjTOJMc{=z5u@9dhZ28>*S${-%!f`%f zZ3ey?aPz#rO@W@5pMRISE7?=!tX?<;(Cn}M0#dL0hN_p_pWm!z8i6MkL)b6>m~o!_ zffWAWGMH7x$UxB-MXOv>bcy2>nn7KuTa+2Db%6c6>FNF?C ze~6m986ow{?(Kz%DgrWG*KpqKp@X6}j!c;JYDx7@s=lCfifTxki1fBDPrlhfVR3r6vw=d-ZnF8Vynqpp$-#5wBE#u5Gi?9C3c_sI z_o(*Vh%ckx1VJCCcsqX6=4CTq|BxxS+>DGr)NVyw{Icn^KTB9XiR3%S ze)^=f{L)!k#LeYyV5&c*TQ3hAmz0+T)T(<)`a2fWR631(szm5cE2Z^(tBuqstw$ivD$kVy}xUtnz=@O z56(?~?^W-IbkQhBG|8R+I_lHB>(-9P&D~YeKYPLJ)Ga?Rfidvz-NdZoy|+n~-20xh z|77*S-@(@nt|qpeWm&X5+PuxqgAGsH#dCYPx}qEz=Qjd?`!Tno+UI z39D|iEkGR4iE*z!ar6FbxFMoM++;maIU_)E-+($eAc)b&NOGrJ5nv$L5+#^^pxF!g z8Ss~Rzp9DA;7Hpd-a9RGQ4&X&8fyFiwSYT;K$15)MnqdMglxwwRH+mK4Mkgo^Ts$#V2Bsip?fhwars5``MK#ADm~s*<-sLEI5z z4Z2fhe`5YcAuSZq#C^i#<50Ua-~cJ$4=tM~^sZy$^@tps1f4m=;#Ef;iw3J1MhSrf9j+~I<|$kT5-9QvwFgHAZH)-RyaI)+`jA(=B}MV6P^q<)mfNq z)nj35iOx2qbX~nu%i?qyn7~rYPK=C54UL>WQYAI=peWC`JpVg=JSzDN)qw*v<~e4b zp6P&v%H{R|&EfA;0`O5zrF8aZ6Cr)R zY~Fd%tG)&(PQ|G5hoNCnkIj{%a9-(PCJQX1K;L^IKNjoAY!NH)k?PF zxDhP&Q2GZAm}ZOTWmmP0@WW4ZNl|evB3sEvL=ABP&A0~5>$w#F`6eAS9C^-#JRGkN zyGP}BE8uwZ0Ic{I>jT0jtvsEmh$;qI8R+{SLp(ctADNAwCzNm00?$f27i)uAgC0fv z`T^Gogah>Y3L1Uvd;AQ3F?y}`yDmlfjaz{pq~{s_cHsC94|+L-5aY9)smK(VyT?*2 zFA9hM4AE=9yb9sjG!Y!%GmGaUfSVpp4S7;X{h-xkBmZ5LmQWduJq`io5aud}(b_B_ioq-9^VX(uMEiPi5mdlMK;B6iwDVe-ZrE=Ii;;Zpm%)Bgl8B&ITa zWiSTof)MH~IRyb>{&;;PeM$E_vE+s&F>*uPiK!mTyTAzNfNH2SfsM$W&h7p2d_oM* zsv$2;e3Jj&KZdZhM-yD>8wGc+eLKS$(xYEKb(FoYLGTvMm#c>sbKxBuVjflK~~{<_4Icky>6nZ*BuA~ioI|a8cU2W3- zX}-lPZ>a_fsfiw}(;7?RkcBlQkM!24?ae=8|4Qv}{U-63Bv)2>u|?hpM>NYFR#VRI zJ{rXtsdr@UMx64otoe1`;&FSuA%Eag5)CHk${+iBc^cA2$`H7I444C=wS;R4c-z2Q z_LJ-g4{tTiT#h>QlU0g!%P8+cZO1CLZ3&

    3. I)Vn`fsiWxR6bEhT(^v1@(5XK~*?g>FWe8m#Cr<;gxBI z>hFD0yGJ}T+^i;kU+uZ-6Q@${lT23;xzd{2o5V9dNUMmNrg5{|6Yfax_wao8`wa2t zYgVhiTy~Cx@B32cDHP>vJf|u~AHIzY_uT%5&U1bzkCNLOF`E&6@?@21wFftM8r4LJ zQK^*oc2Z1ErSg1wTcX>v=<@|ooX#*t#-%NB*?E6CK+<6BdXk2_Q(1y}d6!Ou&4+i$-uwrJ}$G@$vsvQ0w= zVa(FbwaL+0uIvNlwGS-9@|LZYgmhNT_svF!+FLkh6b66v5a0hkFs+L7hR#Xw$&)8K zZ!^kTp^{6qvWr4sSkzOw6CTfNwyzrpro%2;7FUS1M5qw9KZ~R3Pf=@Gc8B5^&!QygjFT`9C?tCl4yX`RZbUw2JeTh(t+gD#vMHy_$jXXB z21s=)JL&Q=ILOGp9^Iz5MqI{0>an9V+CM7j|E9Ot6&TuP6v9SD1O!f=y{KZjW^F9S zM5Ok%pw@YJH4 zc-Uv=sEn^zHTRb<2|d^BO_$%E*e&v+FnRV6-D3Dk9a(>vyS7izgepyesf}hEhVsza z{y1H5Ut4`Zr!wF2^BO0nK{2i}@y^WxJCV)BIa(@+9(1dShBm-oQ6HVzGtO?zr|GNg zR5Rp#8ZRqcTqCe}B6oK1l$Nk5afr$I)vmdOl3VW53HX|egyKKpx z-xE7;xE?LJGQ#Xt+VI=H86{q**cx-NJUO?i&Np)we^>FrF23NuJtoXs7EAavwc;cJ zZWI@cbf>Oa%av^piw)bTQH&}M2{Ji=36jUs7r(tNSe!b82>Jb26915HUYv3!%67(w z#ylgGFHUjBXyjeBPiE@aH)hPAQY9@9Ox-2@t)<0W8`@MiFBH}08)*nY4bo6B!VL z6S9WYGM{Mwu(GyHNGvO1*a3bcd!lm=+R21jnh=h zCkp{D<6IT0!L%b%?08(a>!qiAcCFQhUh|h$y-oZgY_k*QAC2szTc$SUX^Uh~TQC%u z>FOTQwEGXxYe{1%Zt|Ip6$tkeP&~WPFgi{wM%!#Az2^13c>Q83jI=aL?&Hz#0=$`F zKw-+OdTgL{2oj-G>4Rb`I8~Bfme9rBcCH%+(fuNscRH$cC|O2ExLDQHyi~Q2uf_BR zd#)ef`Mm`PIFCu={#?`6$4%Q^%IXjXSpe{kj`Bv-B?8YYsHOVg{=O*E$vN{B4J$@( zkBV@>{@cE-SO5Lpn8b>4&mx^26O{oX{%B}jwZ?dD=@|$m0vg1?;mCRv_#!3zUmTh0 z?l7u2+8AX>`Z7GEkr}YJ@u9v62)=otzH)CT@3tnO;BlBM+i}qxp7?evSI)PfYq3Oe zPf#d{=Ju{E1KF8gZ~3u&{ZHL2yT-m57u#P-w$%cHN^1^g$90MxliOxkd{1k0HHEA` zB37>EuOua)bnldX-Z{N)ra%A#>G+ur)eK3&+g!2l_36aQGYiQ~3S-x$*5Jg$R1u_- zdinDcFOCNL#3%2V!&XUnKn4A%Z!C95&|w}*)%g?Jypg}iJJ1%iBOQb@XEm0uCB*Cw z1AkG62gn&W2x6gvAc>Ih+rqy?_`aa@$7hU{4gZrMP3l>7R6w)gp@Dxg>ao%h1wnBB zI>wWfdHYh7>xe_>myGL!kx6@nOB>~9bz{EZu|i~jWcC4DUg;mC zn@aSkhEgD#_gT$o?hS!tmPF661ygrgDJ4w-I38T9E5g3SpY6(Zu&p(42W~zSN4YvX zdAlt;&t|li#4wH&wM~t7`f3;5n7U8QgT$PgS~T6H)%pI;E8L2$A;Gha1>$sOMx#cd zhxRK)wze(<3qD8no1!Z8Qf3lXW(O^je$p{#88u!QB}xP^*?>ID1?hdZ6(uFbkM9{1 z3)^hOQMVn|{?l8D%6<@jhTSNny((x`QHYQ3=r9o8T41&Pl;WLL@o3|{dls(;r@Pgf z*mIV`52%AH6?zJB9g>Tk)!k&L<(@YB%niE9BF~tl9d-K#nBxYeB$f%b`rIU8RAfZf zN|~@Czu)*T^zFK!vx%93Y-z(^$V4p$F3iq0+^;@cqLi$wEJ-4Dn$6x=9MjneMy*%; zr=!NxI>Og7*1j0{&p~?teA2hi{y)mTGak;b?RF5o_aI1=5H%r)=+TKFYP1m{M33lo zBD#o9LWmZte3Eup;c>9aad`NNo8WTz&-UPkq<(>}Pn4tl4pdkVlnt?@ zwe_E9wAB$10e=z)( zH%4e%6dsB4GTB-^uy5GtOXL^JB$Zt805yLS%b`>k*)+&$yeee!P8ULRz&ozQah3ne zh8?>pu8dtDx!UulW(#LD1C390iM4nWQ;&^zIvA>kha;it(>O1Gb|*d?=}_HKx8 zx0>6Nh}6$`PJA>H>MiOY7YuKmAbJ8MqYI5bziZUHqBOs}D5m4cGzm=7q-7llKDUwT zpKs$nb;Q0CPlK)^aHdD|NQ{5JoL9Pr$IS7Jb$L3Qyr|N2Hkx<}E;-*2UrK3=%JAZ7 zxHDhCgCtbLIklR;2Hlv%(N@J4a>4!b6dY_#! zja1&2(Y>wLP4G$TKFgGgmBBV8Ardk>GZhZs3ATM0^d(9EjTq;tV(ZVLF$~d(B{b|N+(e|Leq7!uY$WIv{e`z5)$8tyI{@iyNr?jn zjOU|~7n^owfNNf8XlQmMlSEnCdvWX8D!U}Wxuef_r~jZ3%d)E8wd$tAynK9v6o{l? z_-#_-D-SKdgt3F)zut7+KhkW3b%xwpFCm{Sfga#*65=g@FSE(90-s0FELbrjb;B8O zqB?H-{=GgAs_7$=?1prKVznBZA%39wDaiO&pcJ3r|JId`?SQVkiTR_yzdTaHD=gid zU3ph2%R`wm@sP=9CwV4vA${&DO$lC->!Hmhx;3Z|C$NFlk!#!woLd|RVl=0;Cb2YV zS2pedMf1SYbNw;hUeB{$7cEoSKlrQMg+5oBhpN%=N@731#fFK~f~|v--4QpXlcOKL z^}|K+i?HwCZQDMGFkN?EQK^QZ0@dVp2dol>3~%V4pKhKT2~-yh%$BO5tLUr%r?4{Y zSl8K7SNbdvu}(bq=eNy6!(F{$>7+9v7gki}4%vjxvSGuVON~>TG!GQ(#)q=g(xjOe z9KflhzT$JRDJw&H)bv}?yc;+M7;R~m(JNqbUwRy;Fy(!#6RX6OG)@{Lv92p6YbNAgvmO8Dp zB)Nsf&lzsNh4-erOMJ2*1fAcZs|!kw>H}`<-Q_f*Bq|PfBovIuBze-iHxkym^6v9 z)cageVDpI7k6eZbZ?4Jb>K112&(;NJ6mMV%GR-B7h4cv}W~OhA%jop9Xt-&~y}J(& z@b#!s9eZC816VKxXMxKdP_WVZu-U8&f1cv_Z_u?Lf!2&Y;6`*Ci76}VY_KxyV$3>KGv_YT2b;OOgn7Bv>!~MBqQlmbe>My8lLHJGS&s#?zrg zg-W?x525kfn_np`^nXv5Ue*cFQB(V(iPyScXY$y3$5XjHG^t zSF7ii-_cgSCo`>~9X{=et<^YmB&q`>y1ejW%w1 zG5^s5NEPXiZYGyly3$J=rW`~0kjxY~<*ih?FG1$4qvZptV9)sVrJ@v*2}xgi5My{g zh&gAH8KbB(eso9r^ms@Lu26ju&-}!(`Ade){6#x(l<7FY!X)D^*>)ck^UpRY;}K{FZ}W#US}bvQo8OrC+|M;|#Lm(`52dVj<&F>Vsi!hNJ2?{bb=oJ0RIu&XF_*yFvV z_xqr5FL}kcOR5%AVj&8&e@>8O7B5oa=`L#*edy;ph5%%<7nA;1HQ=AaT<Xr)Axac|n?IxuN z5@1SHZqs&xY7qZ4yk10!!jc^=D;GF%vs)a!wa_8B;p^o-m(1LL+@*GBpj_FMFFihO9Q`|f z0Mn1;y_@P%<@5X+d4AO|YlZt{-pU)Ym0X()swHbL?bHy}!~o&yLS^f)P{!b%cSN36 z&h9&v(|elzi2{5;n$zbezgLm zu$XAQ#R=U*9@pN_(@IPxuOKQMk$a14%b)63`%3iACdP(Xyw2!QN_S9!KU)E*hI8lA zCeZ;X;A!|x9Eol5f~stPKd@hKaL63sMXLtnKSzeQ@Ealn7uQb;x;Lh4Yx1u-8lhef{ zTO5KLg^_5x+!2Ke#B6tYIeO^oJcB{fY+`h@%oK$@bX%?@RK@kL3T@4~_hWwJ)}fO- zkfu3}d{UL*4LjCnd8 zFaS<2mB)VDt$1U(?&HZR@V4Y_f6~A+#+xen7afYAhFi}a+D0+vqjdav8`oP5A4kn& zWmrP{zl+A&<399$;oI10PWxIO-Eh(EWK4~cU*%;#CXiRKni75T^y&Jr2jb(GKX%My zYqLN!=L|Clny-ma_i0pMnQAWsfSsPQpOPA){F zFE`f-6<8{3ePbmCj6z(*?2Zy-iqz1g2S@h!%D}VYafvw` z7_L*GV~P^~vBvtcN;S{#C#KAFy|4 z%`%o&)AYX@6c-essb2+r5@5@CAU&K;$m0gDD_+*4dHRNWx;sMO@RswNA(KQ-a&oc_ z%xe0cY|xyHd5I%HE0Dp!c-eRF@&*yhZEs|sJ##AXhu@|+XbbNW-|YAU>;}FbO#N!3 z?U|w%w*7jsJ1xlij-p8i*Uw`rT=Gzco1MLbXoA9p*iRXb^SJ8I<2}8F$7}k+u6SC~ zu{WdLBq@5B82zjjJG#0$SNHy@M)PPdq0fcZBm=S@)V%K+k=}?F z^%(EmG3kBC*Y|XHy1eTjW2X1CdO#o-YXFSbc>4~w$8@R1|Kn5(Qv-JQ{{|i7OC95g zJPS}oNQh5VNx|wH>(A&P?%s^gYJ43s zT6u_*f1C2%lSyeMl?&RPub+JI=+TIOa|zSOQGuf+UQi8gql6jzw%%BbQeI5Vq^Wh_ zhML1(H<*B4(9Cd*M2|k)rXkP~@J;KaSWt5H#;ynhlaxW2hi;?;aW`T74C9)Gj?o9t z@$Qo%HCIY?U|o2pudlCid-UvM3)BKNT`DP0ZF=Bmt8Nv8c?z`>k zk$v@jp&K*&j~oZbkNR!~jvIi4IQ+#y>P51^=%K48bmfR6B;}&LI$PfNsn>%TT)4LH zV$FohM9#t4*rW*OyZPedMh9IxNe44)t{O3;3P2z(C#wYJaQsK7vrUEOdh^U>oJ0Kc z1M64d>SK<@iHWMm5lt9|H!U_uYRcOM{YI~n|6n}^WqD!h68MJMf#0dyp3wXCQ#>FJ z6^DdLriIB_wpLqnn|(XYjfLb7Y6oV@Mk$fF5+W4z#zfg=pmX@Fs^-5GnxT@_GWD)| zD-XIpvK!}oz0JUos39LHx#6$;;07bdfspGe0~jVdF&?Xx&H#SG)TVP<7{IH7mD@vQqt0UfcQv z>d^U*{tq=#!Re|xvy^#Ca&i&(9veOG;~wC>6~FfM`AqREv257rO$~92q5zG5)9V*h zZ9iX@Ln>H%>t@n#%c1`9vY|FT&Na^G+wAt^st(}7e@3iU2Go=(q++bCFm7keOejo311C5`$TGyRsGgCm(WvK5Ab zwXYy2XMX6DAvNU+Oba((fkHMDvxMguzOXR_?kqB?Rad@q0rU%>Ai*gqDdl)e+Zd9^ z7mVEu`VQc>o)&(S2CJo&l^A8n6yEj4)m6^(uMh9ZOksYuZ6#Rw^QXuvga5vI>YYz) z^}VASNxnc#ko&(g1~*%$C6G6b$$>q4+&n!_^tto8^*!h_nS! z_5uI~p|dtpsY2}B=YORpo+k?ziThZk$|acK=Khc^#m;OXbBR&}1qghbRNu?3AV^o- zEq7vyTWxP`0BP`Gyg*ON70k*0p_2n|?dRo^;?G2W#uSfG;}YDj=V8kZ`VLb3snn*} zcQU}E2it1bsKqWj)abobB{v5@hwchH=@*k-!or{hJu~5&P^Rqm61Jr72-E=iBd7G0tqau2wI+D4!;V5 zJ2V_Bj01z)`$VAKDR!p!V}^Go`rt3Rq&Q)}W_J6qi&^o+eHi#t8E?^{>)6bY1zx(X zbr@}nr3=0$;@r&yPvkIy;3U(zj>-4ipnHspPGun>A@-u8qJp4f`)$B%Euzaa1$ZS; z5Nm!i(*MXng+%^|{F{yYZ0$fc&6erm3!(f6+ON;=Cfb}3Hw3({kK(8=@5#j7H2lJq zR`N9CwzA9;Py4r*bbx-A7zKIHx25pm^iem%#fI@2v!qn`0dN zVfJc`$S$M&R%-lmNtyadK@c2Jw)~h^cyrV`}rYJ-Zl>Yvf+rsC^A z8$LcIvwN=DR!Y#r>ujm>xEdDnj^zs0~UeN3_g$8y$pLKN{7? z(7kI;6$QR;;(j6f@C9<6RL5?V1581LDbnT|!)1F>>Lq4c7$Nu4i;o&G_{TC2={Q^B zeArJXnf67Q{E+?=>Q4HPO|U-Q3;0BOQ;acT-l%4l!aPUPE-@|gYBMvkScXMdltnM7 z4A9IGY|tfvTgK(DhwjcwZni9fj6yff+%6QbSXbR7J9shh2g@a>25{iQ9PEw=1{Fq) z%Dk+knP*J=w)1i(?qbXZ5i<~Ivb}$l^haJaOjO^ma~I-=ReBZ$gU1ESKDM2D2yuEx zdI(ye?)^$XVM}@Q@yFUT%WslqDg-lg?n_JD%?J^sSF@lgHh6Mrbqsv;wouvDF_E8L z-6P%S;lSoLjL5I(iSZon&6<$@C_N>9_a43Uy9O0fxrElq^Usk_vFR_(>h!e;^N(!m z{o@ctPVY3IaJ`gsKS4;{FfO0A}#l=Cx$3z{*cMZ}fo*Qg;=|^nR%&J)U07QUB4VuzUcT1EXr(4_643 z`1I7$O5cIF;1`wxDeWV?!y*0g)HWq2Ad_p8HUk|H+d>tiytW5q0fTdg=|80!&Dy4{tJ5%XoCH1!$Dqx>dQ)?dNf zeEGWam%Xy4MldMEl&X1Ww>87mOolwKqHNe`fjZi_$Z33Rd%Qqb>{YJg_gSlr9qc3H zoe!3aYDyXFnJ?`5|L#>UssPzq4uw2b>QAMGB7-ztyDMqs=@lUS(!-F1pU-_5y6@lo zjVeVy&U*TIV@R>B>LYA-WY)fZj}u3jz%SZpKQmG?|JJ4|{%jd&Fe~>19aTC@SKJ)2 zvX2i+;An%78R2gpj2H^D4@kVf+N)-ci(Ow48c5(ZRMCK9htu$ShF(4)v+cvRYDVat z-x5TPM};hx?APMgXw#IO_-42jGZ3<<{z*WFtUe6VIF3WB2u+XzZA@8!ebc1#q?)ycW}ltql$UBa4; ztDlP9cRpWug`J#ooOF!ED=#1fGZH7i8fno_b5-1aWY&)1r*N9|ol@jH^X8X#R1%{Y zL1K}%s5Xy(Re-_aeVka9KEmI&I6S3jf_<}as=&XK_3~q^e;Ne;GXFI73HV|u=36R6 z^?)pS(sSPY4xLzkix$uP5T3It$Yr*M{NqQ3Y;o8ljrDmf8B@^crryKt5mLx7XKCzL zb)DbUlWk^nXiqPSJDw^3+P8w_T1CK0y=EtjeJ6+_j*W0F?_cyqH)&rY6%ClBJUN%q znty0NGbR3FZ=hZtFULI7miC8ZxG%3oj(=zs@yoT2m83(@n6tK;(vw_Y(c*};sS;sf zquw2Bz)n7u@He={H#I>r4D0E!o7}=UQBUrRoAHlOE+=QA)<;BsjFraXuPnKj z2G?J+^AeJc&r+z;vV1d)$^R67A{bN4cv$uZwoR4q8qlO4^R$PdkjM05$?i3Br^tz< z@e9}{I;UySfUGjg%32!w9kB-d>&^c9u6k8eJw#RN4r%N}EIU~3Zl;;+&F~l=S;nj6 zjYn44FJhnRm~FLQP&-DBWSI!mqy3(a{OssjU@Ge%uC4w!>5B7^6ZY4#?6`5R5cEB4{D|=@!N1?St`dfQEJ0 zjnrkESVLHhw()G6&B1096WV&6KYD7MN9B!Z!953CcdXRo)M_jgvGk~pMXN|TgQX$T zu*5`yoGuU5zvHKB2={HQal)?UEdnZ^qTd2kUS`N0l(En2)=dK~DR=Io4Mr@zM%39D zbuYD#u*J(j%g%`1e(=;+{oHsC*lb7!7_A9f;~Qnu#lON=&x;kzjh{5*<@u23y&6T` zW>0L?>tl_8>{r3on&ZyuzlRW~r=15hBaIP^76YdE6x%DOqVeJ<{pI{m0YAc69MEs-qwq z?^?)_P!~px_ZgD{Mcl8E5DAPlos{=}-vhX>5#YWbg1v&T0YZu-(6>8=_|0x>b8F}{ z*?-h~$l}u&>WO{w{AbcLYE5`=jIz|y0O@5V;Ys`ku99)z>8BFqg<-YIm<&yW&q}ri zxt(9S6HPp~BJZmuxhLO=^y9sgCH=J-3Uvin5EyU2UoGM9;yfv_Kr%E)6eoT4s~H*D z5wfkj+WAK4_uJaf4L(?{kx^}}Zt?uPpgA&EqF305ZnoBa?tg)nrRt#7tbxwY0=y)AgS^fzPeb zS|Y!pucv9q8W?rxbgz3!uo#>J;oU?pGJ5Im`)yPd#5wAARGUb$yyQ zjz+ggBo8GEmak{N`H^zo%=*XPow(HcVg)HyU%d^2J9iX3Olb}{P4{Z~UrTWZ!Dkdf ztW5p2E`=1rQm9L3*3;Q|tM2QZ6z~LZ1*>WEf1_dzo55ns(a=%6G|B2B+wy|tGp3g` zXmiIlq^m#J7STE3e;GBZX#6~BQQ)V?*^Hja#ZV03M0W6FdWiq5qi?3GxTz`#{#9b_ zBiTtk7q}qi7UVlTjCYyewJYzub7Ond{u@O!`Uz)0f#XvJD@ zv6TDOT5pNCR1+geE3h|;^*`R_1mF@c<2dS)0DzPU0HM&+%QQDQg$ldEmZ@s=IhlkR zO?Ky~P-R}i%c52B>xR_)w_{0XW&!?z-fvi>JN>< zSDS2Z?=sQ!CmW-hFpM4e4GP;YUJ;6T%R+yu#}=DgtnDmRnMBTuRVThhGVB_!9KOO> zqynd0vafgLkDCu1uWJoKsF-3G>NKYeU&>(|uWdeM?u{MxyQ z@s0aU@EP^rYrrvIw>b+0e&q!rznkhxfWv)}S>*vb^wW3M-zD^d(bpfUHpQumjR=;S{7kd(5{{PQ@h9PL2%(2BIazT%dt?DdSoqpq^#qZ8`|I~S?6fv{q|UQ z&rKXP6>w^7Fb;IEaP9=&=eHdVcbZaz+D;3qexSyJ9~}NHly-jrbN8xzloCjwgqU3C zZmmpUxMCsX*hyvYe#OATQ%*)k#J-xg1uaeysoKs z_cS~g%8n}1W8G`t*XmmtYUizQAA#S0k&cxt0LJt9CaH5F#TQBQQ;M^71nn#ySv4D} zUhTlWX0^h*Hx+Ywr0;?)4#1vZNl zZ4ihH8>Rd9?F7;Q1qQ!4c|s9sK^KQ7OoUhlVX`oF>uYT+7e)Kp?OnoQ+B1^1+PjM9liUIA1Ljve5~D=ykYS+o9%G3h!)bZPYZ}*@LSEjs#9 zn`W~0?;emwY;__kb~9kqKrm=@3kroOTZpPjH3QC}r6Yq`jwskEtK=ntOHB2}$tpH+ z5yUxMGd|O69Np8a+DlEb7NaG<7(UP;Cuh4sBZO*nTyysQf);WYV4UeE0n1)l5Aa@t z!hpm>$KYDc5cy%TJtn8u0aPZ?O3x|vCGI(7#T7?Bt5lzPC+(DaUqY%aq$oUsiu zpE9)9x=p-G#`KEXJUo|f=}4a?_v}==zKL$qp*syH97E7XzCUr`WXx-@`Gtk5tZfCm zAVWJCFo#h0ZvgyPiIHBm^gKv7Jq}S#KHyD z3f$d5wOdWSzWw8>VG08;<^Qs%lt3@cc#(Z0a8LOCLElt>?$IDo_;2C-y79Wf9Sq4a z1Vk`nndY*v8aS=R1`#52zLf5bh0@K`U@RD>W%qR|Pa!NHCbb&PP32)t<9V&D`o=Ft zu|iI;$B4%LLlz8;=xNeRlnmTP+RRFZKMczUH5%CcDq-Z@K7U)33q2{q_B(u{_%~?# zQD&oYt$_W}YR_7>`j4h4-P$M4dfTVHV8vyD)dNKPxM({n%t5%ZOtPgzp<`6& z$7v1^^6m0idTG~q#*6ZW?pf16g}^d1B1{f%pN5Cew?Mz3$73gIhi*1Hu^>2KC;&#O z@ul|Q;4iHHL3;zdNWg+Gkrn2e%kBXSz6*?O)&a95k-F3f1G%A~DW8>F=5BKgGk+7G z%R-(!8U`83g(Z09abbi__>-}Nb>tS^l#b_<&XAF%`V#vD8yQ4QyCiys$sWu_v2xFV z-nUU;H*n}ts-S^$rte6!7&3h0$>n73*r0V6h(q}QjKlwp;^mxGqa^Wf#`WbQ^1Ei^ zaq9!)T`q(ynQ>1-52UuZ(J?mD;?07t)H;ovvjSu5_w$ur+^21h@zIVR-pl_o1#2pG zlddSJYrbz*|55abg;aEu+P5s;kG{Gb?_^IL>?Z$AVZjzHv@y1q6L;-KA}-~-QkVD@ z|9WyaHkOowHSRI069g}21^L7Rysssdv2D@x01|mKZH2I={~XK(2;OA|Gkb3j?w=*R z)d(2?Wh6to5|dswr~CbVUKGtxj>(4|1tTV}f_;G%z`}|1Sm^cn-0v(+Qq}~L^71f| z)#mfS;x>=Je_8PamF*^lLZaQKU-}#wo|@sBr*T=tBaK$LS45k*^`9@aBiK5Rvp%Kg zLY*#a0zr;4;kv=W8 zF@xPHeJ5Q}RPW!dEw`-;aE4j!-IggZ-Otza0E3pk%{Mx^HC#E@QuFAZNmuw*C=d=l%7@N!Z!GWt%pgU|Y5O&Dw~00b}ne^xy(v>@kobI+)6LL6oY z6O)5rA(?(|gF@dP$S)iTO?hbLe(q=0wT=I%$HutCq%U9%9ARp9XVBqLxMWe$+nOz? zfNR)b6p_*KVnHpOAD>~k-a%Z;V-T5azj#g=`KDy1E2Qi_wp?LO?whso!>c;sFshR53tK0EFS&T{Q>qXkFjI!$-U-2obs(Y zN$taXDgS|1CXOJz=64f#&Ih*E`wT_D`XkW?<0??KtJ1;rPgmi9D?0Ezq+lPKEd0H+ zRP$L+FOmC)lc;z6ay+2bw7^tdp9NUTf!$^84H@SR@u>2Si6ewyEd7@jsAyw8#@ua* zftX@7HEG2~$q1>-{aSfS_k87@(LdR{L}TgXr>2mTfj|bCv98TwSYBBKRuk8rz?cuD znDtSzfO4`}RDijMkP%~Zlr_dUp#sNRIwMPD{8jd(MJ90B6$W+7^K@|am**WRa1&cS zP+XPfFRhsVlbQkAD^V_W$sv@2{T5duLg&Ut*LE@WyffWvzgDr(u=)kfTYR6`x0dl$ zcN$GNRy@yST~jkt)`e|N&uRPyuTQgC4)GJ|h2QbB}#af$JM+h`?tVgMrY%RL$^#i$lgam z&7@1HL9}V8J+2VcRQk1)C1V`wkF{&IFR$g|1xct0KQ49e0!e}A4rT#vn zUMQ-}&1ZFu9C=e3=(w>5)`8q*D~Zf2gzhy&2lA#~{<8Hg#;^`flge<>!b_MF+q>A; z2l9mHMk%Yr2Dn$m6o5YvnZgGd+4ww2`}jiR5Y^HjG0i|>v~Fd(u?3WR+ktq&R#eTM zQ!iJeCE-2w2>pZ`%_7aUdtsx{0I4?qWiHbSGqJl$;EZ=aJO4S`6dD>KzmJ)B zvOQdL+<98SrCn&W*S#yxkmHqPFtOGj!nC*TwpeYc*P{;qdu@1xd1g*Yv!rw62(rc- zvMua-DDMeatk%}p57--NLWvY>!o#1y*%#Ienv*u&O744Qj`GHvKV_qBN;VG{xM2x>gBnkF3@+giD%_0^YK|bUz=~TFNWEy2CVi3~NQK z&F|Fd&R0{W@k@RQ^!apWp0H+bpM*oMGB>tjO`#5XXeDzctZkugVMSufvE?rK8Bj&A4a_EZ*}1L=k8j`nZEJ+%tQ zTV|?WtlS>|dxgY-*;@I}g@BX*l@I%~>;Ou81c}^wgZ9<&moC3s(~p6Io64ldaXAoJ zv<_sR&Md3_;xz|>7H(JC#y0wn;%`-(oI6RC&fRZsanzw~9-lg-1@mDUAy2R&I492? zB_iefv%)_2Tb1x3h!wIPO6QkB;#e^5>@xaOZ-rMrh^=_7wjWc0vD&RX18KwPBzIxh z%y@AW^!LL@*r4Z*IkF%}BSc~d;8a=Bqe*shPy{J&B|ZV~xu7I^i$;g?m{i15voT1` z%}?UPvV+0i!T#i{uqhv|H!F8sFsmEuUE7_N3M9K3QGpii-Q-wLQ$$@d5QyL|KJV2Y zXYbsBK=A0c*|5xI2Ou+{zt7ITtj3c_ro99dgd47VGlA;F0FN)Bk7B%E-c2b+y8$_Y zoPj}-I^$tS`p;%yyuF6qqiKztiQ>v|#c;$>Tw`-M-SU#|;sq{3uzVhXCjF9^8SiXj zM!ufzO~37P@IaX%tzvhYPz-kMn9u(_X>#P0yQYvTvK62{kJYUy}BS(x~Uqa^Oj-1huZ+8{t z*w?AaAHH~E{IcwMwio>gc4Et)4#d~~4;mJc?rZ<5()&FsW!~`gw?Dl6t+(OjVQ{c( zXjoX&*$E-6xOz=E z32Ff3FoxOL*F4knyH?oE(kLI+1i(OQ?;;Wnas#<_dXP+)(6&K8 zSoSa%wb7yZzKYZ%eX!~lOe*w4kIQN7kwHx>r|~s0@$n^Ivz`*J2XiI{_sO+E@S-TAM^Q2u=qca*SZX|vn=KhdbBuYDuE&C3cHtcmgGqoSoFX*DWy6%I z;JM4s#o}+Hfvpi}ff?i3%y3(SHcj?jI2q@rA*?gr?hb-F^vfJ|KR!Y;sL|5+xavw6 zhr5Tt`?YKR*;K5;6WTU<_8ixSS}U^`8(c1~_uJc5&_h7aWHuh%$X*2%*V38=mZoHf}eH{{AAU5dwEr`ttS+tjdO#r>|vT z6BtNBpGQnQ5_9o0f%0-gG(WWrPU>p661aZ$Lh=_i&@=VChs~#b4{lm3a2M;PL_RulC7!2QkEK%yG?mVlI_oEaD@jXDTkL?l?e*O}bs zy#z>k3^tBTL&v(2WW+xOU6g>*R~K+WR===#dtw1_^yXHG<85}hqXUCBPl4k^UgH~B zyLtuG-@> zgFD839)kOsh{`7`-8dS(lWbmIf#MjNLOH436mU$rub0qA6+0mx5gVg9-| z$O2w~8Tm;lp{)c{8bH%F<7gtz4&Kc$$mIB$2@^55PU69bU~z)nC4LqM3}5mVt9?uUSQNlH^Q2JG4V-fHkzK^W&UazUSe{rD@8iHDrcb-mSS=T1iTpbp8pZ>IM5pwV%Dj1Bc9s}&7 z>;jV@rSxh9GFmZJwABD$ZUF^`equMr!A<54<`&1~15-3L;wGmyQKhw}&Hn8Vw#S)b zgHk4J6m}Fg65CzwgkRj-VyWN`{%{qhjyD<6(BhB0)Zbsj<|6ORhljj&V`gH#2PlNu zcbC(l$}`^cPO7XkChtDb{MB{Azpg75ldZ2uBtmT@CHO zfy^fSLGbm#7%2m=6oT`?3^o%?$%Bb=oyJea@X*>I2K`Fvv? zaMfU94ISv~)VpPXA=V5{<}kjA?sW725iL7`R^Iqvlus0HLIo9=_@;d|vY*Yv3QOe*T zmt&>INr!jzMH#C=xtUqXTDX+sb9N{C1zFhNogqzQ`U?43TT@VGoh3^p0aK!%|8FLD6#IkaKd+LL z`ky&5z-j~6c6(3_!{D&SQg;|GuPxKdTpA~1yj;S1oaSec*A3)yV+ZQm(OD7U9@wjF z4xrXz1#QR+Ixo|-;;#O%QDW<=AY>i7IVG9VE-Znpm;PSlQD{4&``$w32ag832lOy& z)Di&3gj%ojeY0uB7c>!1U9+`6?yzh;t6d2OsnV|SRJjB=o_z3yQP`;1CG(4;wGNIS z-YhFCQ8vH7S&U@JTf-zi>S7{uc@P=Ut;-*){ee$yCXiC&6Q}UrSAyqlwsh!A8SVX; zn+z!v9K^G>*y;f{2XQ($h)r_`-(0Ft9c% z9~5}^ls(|3cko3n2kYtOYvb!Ouk^-qUo?T+HOh7pcvVAZd@AO~o!ChM!882e>>=12 z>#lCwBCps7N`E*doNkX(Mo0G=rPkS$%6|fvcZV^GIcoI~|75s6DPM_ZIk^_dAGdq7 zh4^-BAMs8>Xb2}T^48zNxErDV6Hs))1Gcp2ph@3jYk)PSe}c!Bq)5*KfMX)f1p|%w zayuGR4mT5`&q82@H9mhYjc_9KbB#`$L8FzC+yOoBuzuBevyi(Wan!!uM{3+ckO7_;qk`$Zz`XAlsWfh$UmAd%Jr$p6jv}v~pGogdt#-;PVk*^V*HXO0X5wVv#tE9HxFU-rGev|A2vklg=F%vVi}VsB4E69Ljvlwx4((81U* z$Ij83=UeOZZHv1)Yq&2(!4D?L3-&OzR0vxR&H4tK|!6os)=SzKOMS{KsO!}-TkL$|9PU5$;F~^^ zQC_8ym`oH+J+ZgsilnKBX_=axzR53gvMLlA#67*#C0)qR{4gN5Xdq-+%M5!d)S%O9 zAUaBuB%Be(DI*R~$TznC5x7vq5b||KndRxWFgg5z%IXkypG`-g8Fxoun2r2;!fzI_ zdc{a4YQ@jD-#0T({ghL?fC5jW8E^&3Tnl1y`wtBg4Mh5Osm?-E(eR^mPL)M*l}aw1 z;bBv>@yS`*%E6jset7N+O_vxMskXm*T$-AiE1yUu$wcOzwNig+eXqYwd5K&VT$Fy|U|NX$Q{?eXaOXtrN!|TYpS58P`SZ+bng&+j7=+P5I3xo(#rR8Ebe5kN}fyrCvk%losziv<9 zOPrZ2gd$j)yR8id1lv+RR!3Mrc+1lpSc1MQ739v*e=X$JZ;-Cm(x^K<4x|okijVJ} z;w{gRxn52?BP3DBN;h74#&;K87sGp!*dubUin|4fEN_Fx{1;y=YX<;)k%9*e{*A5h z0tUyw6tRO-AA0xSL5Og^&_h)Zbo=;0N=t!NwbxnYC!}N(q9Q5f^Bg`-89VuP;_eD+ zH|<;;CT?A!XdT)ws$?qnwD5NNd;zhuA^je;7*;EuFxbt?byoe+$Y0T z7Q`Qh^9wy6czqrr99a4ygYHnZKO9sZ+Mzj{d7l3aeZ}3>Ox=P9axLX_IsUbqwfZua z?9$To@w=Rd_}B$2OJyp^*Q;|!9iy>f*&x$6eu=BR6(tcXqT8}P7pYzVPALq(#Cphq z3tbo!Gx#%0_$t?(=kJ4+<}5R;sa&wJ28|o7iA-4L*_vOv*_>yye!3s^HY~D5P0HJQ zCJvd|zK?96O8J6UTU!=*bg~rX?$4C$BxVb3r8M>?8Dv<41VFhQ?1NJ=(7rYXd0mv$ zPo#<7$8B(BSlqvJRE|JaUPok$D$Wt$Yc6_{lmxsWFX;Sh`l7hkFn}yHrP%BN zwr>ldnV#9bL0G${6JnW_`>WibK+$n?>c~Lp z;{8_-bbSq&Fgo;AxHRsj&VXSf~`01K@iz&#q?=vsawX9@}}&RJtVQ z6@)779EZ@>rg(z}(9}%By%q8eb8|-7$BPTQ11+&~iS@WHG&zpp6QwuDUkTI173-#- zQa!Wv1)WY<_9h>DM4)#*n-KNP7Y%nD(jgdzK3z5mFmNWWyOcm$5gkv;S5gm`l77Tj zrIbnZnjd|Wbo}I{#+TMWH{Rk)p5svBmW3Fv?DyIeehzv!;ftkt93Zt-07$XUqFGdx z4_$h~^24W5eR!K}_UElUGNd@P&vE_Fr{1pF4EOEQ z4>CjgXDP@(r5cTS15NTS5B@Uq?1)&4EG;%IO(MG-UgBCFqVR8TeqB&1HMBTXn@cx^ zg&g-Wn1E49s*_*yzIlf1{AHip|L-NbSP8;pe#cip6V<&XFPNG_TC4T37oAP1%SJ$( zhD=`5RzKsEr6Z7{teSw= zO%~u0zVQU)KB{qjHIP#NrLA6`fg{BMRv)LZ!H*QGLw?U29M&3SIN#3w9E4FNyNE=U- zat-^I8oHG;R_zunq%zxEU=UjIWbM0zbJ**~^^Ygf(aMYP!AUEyzV-xK|EWSOTBQZP z?ksKZy+Lt#>pu)*YLuCKF$cXDL4^xOzPU^S=;MXX#D((4?es!D#j{l|HCP*p!Yi;9 z0bLlefcHJsGdIs#9WF{7t9p>g2b>&=fmMlRqhDEl$Z3_9zCJxLFrx;R+Nu@oWj!^n zBRU|ws8I<~YioNMS2`QD&MMsMSox%C!(`7vYDw63!u;8ifF{hncBSO8wBSeXz?*{C zI^fj_x0{-QEGH=F%&A)oerL>3KNdOa(VP9pR;l5qY7D8i6doAB=_5zlG21kJauw@% zD?~=gYfkwI7_PW9M~sXmz%S)c{Th7}^MAALSqdc-b0t2t-~6lT=SLJ?z^t&j?5S7~ zX>*nH##cl00<4;ag6vU)Ud-PG)$ubyr*O&uhqs^qQ?UrXS^qhAJd7H;DOP#5g3ym8 zx=)~r({zryI~BLWJ!yxczSc|D08`FkmL8=`jLG6a0bJ+GZ!o2qWCA!V-}Bj-QLvd4 zeY4YSI{#Vb^|}CgpMxz&hrK!p*BT2THOUC~&@5nt3KP?v@WHX1e+* z3(YaJz?T?O=WHFJcP=Z3bE$SNPn`#fCD(hLu>q??A5)1q>mJ+GNt9c3-ME-;o84)7 zX?1jbPl=~ME?6pPBkNF`LG*Qs$N0CuquH~kPW*SU%oEIjmWhvhZh=?O;0I_yrA~+p zhx5?aC~h7eRQL0E<%d3LJ61=h@9rG$mJQwT2l$3|oBS<*8qCGt6s7OLiqTF!K?DTY{rLe`|J@zGf2Ti@I*4TFU4 z*({$^c!J1G;SQK*v8quQ(sM~$tUYV)eZfcyx=+DCo%~B5hh>sGSv%>!-r_La zrG#ev6YCcTT1Hr)d8yF3Z-8dd8?hhj6&A4lrdmFYf5y|zr@@{pydD;^_H%Pg|B}?^1IwGxQy4&lYIuVW`mM$QtbDu28+)a zVbSh0O$|=_5Ox(y$vnpafDn0n57i8^Ok{a7>vB ztcq5HfoL^Y9dAHQXs85m0(x#MAvc$ ztitgW7h4EgWtyx(1xym7#`G`$TVk!_pal3q7hSDS*6gesjfv5aSs6 zaMDerN7n(N^8y$EmSyj9iM`-Cj{(f31mGr> z01rFWFfB3FzPZQnYzmw)&R!ttK0RvzMxPCA$e^#3hD@WBqAe$dPWy;OFYiwl75OLV z4$30@r|V(h74oE3iinFF1-*#kV^Bxu%REtCrxdeTJ5A(Ub{#3v)?P8MuoEU_5D`*5 zUA!vpw`tkaHD=36zo8#-o^Oiwzg8Qf^6v0f&=t=aRmH%>&Ky8I$a~wuU~JZYJu!|f zz#rW6B7t5+0Q~=~ghLzUrHb_iMBZ9ydBmWgqDV}YXS0>hA($H~IDL<{R3hZWD`I_M z56IxjreYq{%uxtUjl37Syx0jJNty4Y+hn)Lqc-k*hDMc;cmMZ}p|Hi#dE2C@McC5m z?iQeWc-Aem@^RKLqHZ!=q}uQw5{j~gdNW@X3MSK^j4;`(%HPX|ycM+x>o40JcZyb&_KMi)_!LX{NwTBzN_xk)bPbyr@{RjM%k3&^NLaXJ| zXy1AG>qZPJ^)^Qn6^@tu9|=Yz=NIZn&ODH>Fs#+k9mDSwb8j9xlz$6#TCA5l=M9I5nvQNzf=T&`&LUo?bHGCrqf_wY3E1bqeqj zZLBlmwPu3SvLnL@*=IcUUyjM>u1*%brce9$;lN;mAN`Ol?Tc2^a{oRhI#)dg^vLo_QO32B2Hyq($sSR0gFM%Q0jk*xWprvF^yUPA-Y0kP> zsM~I)P=k!Ct3%Y?6wPpd&TmqmjWAbl;QB%L;H)I_?gTcEvxjA7QM2Jgf^i;#m;fay( zk9_l@G<}B~GbJl)CcF#1S)aZ3KFA(Y(sjedoXYPYoUOm-pVjkszBxZl zv10X<3=yL^B7zXS#b$yGVumnN?}XL#zZ6&FXh&HC3){hpZx|40 zhI3!!dVJHK3my}H69R@jIpR~8V1kks#D3m8pb@3G$G2gohX{pD%vwPVSQV~`U^JltF zq*6&5$&6O1S0Yo)h*QWMibNT_(@Y+I95&xh!0#YJvm!v+Dhlz^8q+;=Nd7@rqpuWn}Ae(X48W$ zsCDS-iAF&X>iqKM`2A?d2ihxcfxdnpQ|=j-+7yj8>>j8@3?1nwV@9e%A(m?Rd_t^# z+f)33tw-C_)>W>`?ZULRTOEDUvqBnv3wqzBXG6Hg@o0suOyw^Qe$zDJy*9f;d^JGI z2LdI72h0=jTQLq&4HY1|;$35$nZcCx$oCJ>hH?SuH~5je3Xfs-ZsMSi(K7>)qTXJP zll8sVST%#XfB1EpO)}?#Mg)xDJFpw$5hHDU4#gt`!1Fhs zHBL~&akn`JtTt8#C3FOm`MN?~UJemUvO z&z?A--fZ(qN}9nsWc;=CiCPoCd&$Vj+=q-vO#OH%<0%sb8AQ{>7Ll}y_O}8b5n-Mb zGV>t>a_CmJnrY(tuQm4|HYuv{wwy-2E;HUh>pS~XZoeDOWQ75PPhhoj1IOTF#9g0z zw@#wjnBIpRyp3Z^-|n7Y2q6GcQcf(mAU`ui^6f~OdZI&p7hF47vEL@E@y?Ic>)bPB z#~!sy^KL5)yrLr}B9PfbwThgxK+Z`$Lz~%X0$6UBw)FEok|Hx#=o97S^q!vYX!M;; zVqr2d&@KC0XjlD8%dP?G6^*R)fg~j+Ccc0$bMjI@A+b;BHl+1OGkDP(WoxYx#K(WP z-au7kb1F7}u|m}1zu`E;A5#GK&VK-Eis1S28*G6^>#vVrWl&vdsjOtJ2ac8j!1TGZ z(xKzlO62?d0p*ro9MeZ219?3o>mzuW(UB$rVkcIypXJSth1WR=k zL45RXvugs=hSNh~A>q5%XiD0c+gMJ>7!$kgTK&}5+L0Evkl zA{is=L}F}4Z7(NNud8tf(~KE(Gye?^Vf317g_0bALc$C;oqPe*9`7i}p6lF~KN`DF zGez+bysDS|mqxzXR;-o&jAr`XZ=0XI%?B-aS1?vLjwyRht=2HXz{&ED)J6h{Y)W2{9?gy9QMo&XhyLm9Qt$AuGGNI!*uaDIEir)rO0|j(oRvPHA z8bm5VE2-xm-H>=ogWgDtBKp-Ng zdX=yPeO_VH!0ER+c0F(*C`T8Vi#&#glVjHw9|FP=ImTW6_sL|RslELc#TBA}qpvLb zuNKLvh!H}6(wq1-3_e@ec}SjB3Z^_r+wzO$b$SImKnf+M-}fk@V8Sk&0aK!e7e{oG zJ8s)F9;}?C*WURq-Z*}`o&y|6b^uK9G5=A%w4fKxLqzX2aVX@qut=!wYC)>T)lOoc zTcma)9YJKt(|Yjf0ye{u^{!P(O&{@Zb~V3QP`SH<6>Rn>Ia1BG3OgmgFhJ%-5TmHM zG_~r`cwc)7*h=A{hnb6$WCP-0LmyF8t%zVABEh)hDL1fU2R|(K-Zcjume6V>X*nf< zJ?%w;DSV`XZD*bXuY)9n{gx%=6;@f(yRRg8C@~u9Uw8-P9z}3F=7Xzgl1Q$g z&MQ9`Y)@?|qq4Ve$>qb+^wO%uXZfB3_2;%o#F82xL+kcSLpzR&zA{+7Ez7ejcy^ET zeL&N=;VM-0!_F_;_A)hf=#RH}P{s*tp+uHxHAnM)p4d;QOcSNIZtjx_{ zl3hzSCoRw{)6&&?(cQ-e<^mex!Lg4IbqmFrBtiF5sL(0+aGfW@x}lYezNf*S7csd7 zWLw;;07ZS_GtTNibzS3UZ|fM#Nn+U1)+FyC-hh=l83b4=}d1myxozIC?i zkySN#_{j-{uM<{Zsp&AwCFPp?>{5HDi#yv)ke+qkG(u=7be_cyf}9pRlHVl{fO&ueNSQx7ugx{td2+zD9Z% zuRGdAJx*bn1X?8;K&PP|iTt9K5EK2V(jOr$QfNJYOy)Ta2H~yk0;fCO79`p&=D1uG zq<=J8+|KVI*WL+prp#ZE&DyEcbB#05rlfe~(r$tE3st~i!%kc#0KENpF5v-lI8-RIywX>Bmk`@)&vZnNCX5x1vQyy{ZJp-S zNQkegxkd7wb0J%Zo?AEW>~KSOs5?aoThDi|>V3e%Gv4=FaPCvpJu#;*go6rC7NQr` zrYhh{{IBvxZDvA`ZTVf8&Rk|&n*TfmxEkz;E?#~#m#ik8tOMShM~+;fLo@i(+L-b~ z1{BO>3d-=-G(sp##rBkJn1uR0z1 zG{XH)eOwnml=i>aD(OTy=BD>zSPkah$w;2M=C+t#x60`YFp>nqBxLQEMEy zVQ7bdi7$=-GBF;$2{BYhw$np9an~Wpj_iB%BWW144b3Y6RU;mV9uf=`Pt_9^l9Q4$ zT1AAeIR%q&KaA4r1ei59n#}8BCU{4?lD@JYbUux5-P{xsy999KGce%VwVxoY)wB69 zYYbGh$}pK<{s8SQ1Pw-2PZ7wlHwmz6w)jFLdq2d|F+&t?cZEqp{R#`==ekyUOQ%+6 zrnJ#`zGLUMSM4pz!6C)=D}@MTyy=z!-B5ErDW}bfgRX5dRt?@Y5ttm7Z(Yw5xL^Hx zN{d}>oX&3=0;5~PY<-?y|nh|J%WF2)V=~Ym;2Z2@~q|@ zNuUG9@*{UZ*O{OlN3OadJ#N`v$M?-yq2TT0!$WYUDy;5Wi=Muc-9rgMIvF)9c59x0 z|GsF=?=51?UprLn^kR}rQhK6}Xfh5{lP?mqFL_hiVC6@#2JsIyZ_NbxO--Ztn?1av zrj9B%_a%q?xN4iVhprc)Gz zz?^n+@k8x6{pW1{rEh;VLNT5sOI=w^LYVoZQ7n~iPV%*5;PLUpo3}b9lcfvw{CryI zc#pO<_TI^Nu7)J{4+x+WcOMgmpATlV7_B0>jhUFgwZ8WwU_)+{H@=U47$F2~M^iVU z@^td>GOPTl;E2~B=D%#>htC3-(dkikDZ5?Bu0~J$-?Tey)c&)fb+~SlQ**@oz{KSB}Vk`*9HaPt@0{-PgwQd%>pqr|D#ApY*^=kO=!ITe>}z;~ccQ8;?}4^ny9T?9^IddjWB{Iz4FQoz0X{{6ewmcu>RPbz;| z#u+De=5Gc94<-N{Zejs_$IgzBS=?R=2hAPrAn#;u_ z{Yk7bO#}Ibuaol$1V`O{`ZSjpXO^$K-q45(rnoc0*!mFduc)_6kGds2Xc2Jfn%NGP zNS2a)3JfhGR!{NXwTrNCha;?%%`yOwx=kb72`WP2!8Qi(!pWTBr_E3iZ(bDz&Kq# zKn8C@1VGV|t?{d|E28BaV_)8l)wsNP1VHV2zpb1!QfSXP0(7)t~snQ$L$$~qd7Cfjd zVe{bvz>o_Nn&LghL{sR9pMpc`k$Q zs@s*W%y&;d^Y{RAStkQL(mEdp;5Qn6J33o;eUD(qNGXe0i8YVpM4 z4S)d~!^$C*pevnO7!5VrssBr{3s_G&?n4yRb@5HMHILE`u8{(YF#_rWM2+c2sjof3 z7-7dBNlXi1Ug_{P=;Jg~suVm75SExTAA{+T^uV|^cG3FETnH8u$luHORO3&@#Qrfr zO0zigmZF0ZeTZSSCSg6{lqPV-?w2< z9c*QmCBjPQyl5i$hfwSl3BveRv+hhQyp*`&-fp-^mH^E=Mb+9g$4`|v)ttmI=q^LO z_X*wbsVze5>TOeKTEV-7r0Nr8U&@iUrvBsB68U+&;3e#x0>jVab{=7bT;)ac@9?$|13s&t7);W>kuG%XOy7(5-7Rm8%Oj6XHOBn3U9y7+gG z3$1?tt^iuc4Qw+0RjhzQxTx(n?zz91UcriZP||8cEMk%Iv7Jx(BpwlP=Sv$XN~rFU zXujVD!(laWY)4=S$`N+HCC#71m_=Hd04a_!Qv+yrQL$}J%JUy96sjO`ztg%7MKd6d z!N>`^`(4lJxb7@mSj|Lg&F!?D>*IPjk)4QPNKyQl20Lg!#4pvroH6~n%=1Sq(C}zou)*m!e0{885dLb$*=H? z%WO=wNs})BA(~OQuFgqb&H$GwY=vAKL-KwL&duGa510@6^|YetSa(+CxJ@&L3`cgx zbvL)A3V$9JkJSrtH|<*f;@&X!f6p-VS^6uc$w_(8 z{J5!H@I-JdQZqdFaB`dg>-eG44%bvi6cHf=Amy8<=a~Hg-9+f)El^h>jwLWpmxe1H z)Ox}kz(Bx-Nl#=ZrzaRyDy(q;`_+POC!@h=C_%d7X$Uc$mWUd_CwdO4j}gY7=y-Yz zFrr?rg-8N2b@T6GE_?rTY z8(=gji^BF>{Z@sBJFL~b67X<2G}UjMxMm^=+w9D>q7Bg+OJ1)S{WWafjC)B}NrerZ zto3quamFuDoGFd6(@_xBJCHe7bcds;zmOROV?4iKD$!cXLH7LKkk-rP3CM>Z*Rxq@ zVi#hr(7a!W>iB7z*mwp8aJDOIZ7FRYE}XQt;-s?DeMATKMbimLhBkc-@D}xSTXN{o zao_+-no81aCH^eMN3ITBaWd7P0Ki<9dpb>okCJx4 zFm=8N3y3|pV^o*OoTv~zdJNE2c?3x;l{u^!)4uV6v{$4B_#}CArS8g<69{RVilujk z0v>MzTYJ2iX4P#bY`Z?}*)r8y?#q{aP`6(sMnBN|Kx;92HsMzBO#8)+XW)Nt6OLi} z<#x0byAing1GQwB%>HL_`(KERjckjC2pbZ5a&3H`DEMc!NWCptqTAfzTCKp|?#V@F zEQQ^JMv;!muL0YJsB^~m4>jj2hW8nICT9vsC#zbR_sg|X^xjP52+*{C;tEF=b=k+! zYSW>Q3rcHLuRO8sKuc@IwIw(JKh=tbjN_T&6UVdrti8MzvMu2|<>`PrgG#S(BES^= z%ld}9p*B&(t&KiH>lWfl1qNv5qfyoQKZfz@>PJm3TWl(tMyDAGNEb^B zyJw@;B?I17Q|JBJ5cl>-+AIS3`Q^LAxv#e~oIfo%-=Y79RQUyuB0Q61mgCk&-HA%hXIGum>tr)%92F^jDoWZ zvvf1~u9rphBk3=;h92G!3R$15SNpbQ}e~Ya*Oyvh62kP`4hmw7qe#ek-*PvggD}ptnBc;t_S|CR>KvIVG#nbAnFgG@nkNLDZD_aA()+_P@&BK+xBZj+ z9zV(=o$TAWqg97910VD~fXgG3bG|c^-M?Kp*jFxzRuh+E0gbi&K0mLDF9%M!&R(?7ntW<*S!RKR)ogZKHW)1K@g;oE)OyMc9dH~}|+2Pg2pFF5}a2h8X_ z7~z4&qBvw52$~5B(;W^WT32=)5svB*27Y7pZ)}E)2u8$t8xcD#ZWM?U0j{&EO|puX zUycjxm7NP_X@fszLb#hH!}U+9xZ22P4uS+ANJuNBjjuASb^5x;#RBVI9Hj2FeGf{2 za8@*H8V80SAYhudE?-75VF}Sf0phgVf2>swNlGBb#J^O;ROLzzZNevO=R8A$ws}h` z1L`x^<4ma=8WA{so4h@T*<$rvH(XTe$EWOQISlKc&$hV_bg`wNK0Hes-D=$Yt|;=4 zTLaO||K`?kGtA$E@1kehVR{|;Lg@l~yz?;RQe)5AWX2r`*ghc%$lr}`k>%>15s_l8WIVTf2S~xj7q=obn`%#p6k3A3<}WXRhCva~NCi4e zrB)b>+Klh=t?cN4?ymFk>&3o*kQ4+7F6E_4%ys2Q;C~-5(nvR1#GXV6*rUTN?hBt- zN9RY)dfqGvH`&rTbSaT6erRO7x{ilVocCnR!&$@%W(jFA4t{o@r75Brz_$2IN{fH_ z(!joV{NL>x=AY$RJ2l2d_$$>PTsEJKeslhzU=s&E=3*Fa%!-pZbovEGBF)uqzcVKf z`lvlk8R+ey5a5MU8c&d?h2hgxRqxNf{G>HxM_KZ1W1_^@=#t=*=u~gfy`=sD)G1>` zmw6lf^T5j)CiL#9&o|%!mcn`F)$kthBG_rK4C#Why3iVBYELRqRz4V z7?O8xdKYtLHTnKmY!3G(O{k3utp6tu&b$LYzWvszXLto@R6A1AGFYPLMK49Zz>aY4 zosOP=zEWCAQ5{X|2+=7aY?*QP{*Od z2gMA55Q?Qpd`T1X(luSz-vc8QgEhBDMhMHRO|AxDIJp{a%!j4pHgBoqlL=DkgOrT? zfKpx<3w(=1uoRHo6?kxB3K_y3pU?8<*R&ceyV9gZvgMyfIlT5`{A z0q^|16OfW6ZxhztCxGF+1v8hidne?W(Y<)!p_2YWLtWj6i*n>uMysnP73!t_ePH=L zL#TE3&mUvH;I`_dy(~;{lDuv( z)Rph5GzNHv1;8^(^|?f)rs%vlF=hW4&4zwPRjzGUIE!HPK3_~<$j+)hn<-Jq6o1m6 zI{)s7Z*p_Gmg|F>)uD>ciQG~%N}%N>Ry__I6({;G+N-|fuE76#hJOi&=n`~%DMAm& zm%jKRbFc%K9+mffP_-zR6xXL;hqn)H0NL>m7&IlU980|CAnsrehqo}^J|{I zYb`R|YhZbQ`B&-b>X`G20=m1NwO8tMmgsY2b@1mf35-IBJ^W8u*~U?Fia~eC&I|U3 z8tRJ!7uKg(xr#q8vD40n)GAYN_uavCQr#9C84-$#1{?)kITZ+CJyTa&JE{R6Tm@H$ z(h3~p7X79HxI9)d*X}JL7zG|+guOE2{Au|H`pphBEE9`-v9@wfekJH;?LBp~mXX0# zU&3!k)>nPgrJKHtZ`KXf-v|61Vgm4K|6==5xQAl4$?>R8dcw7F7mz<)j%WPK^JQF^ z?O2wxC}+YN_5=q~Jb622caS+&ew)STseDFt@)w(KPYEem8t&9x2OcSwP$Vt`-J#hB zPPx7~xgO5W>Rc0V;`E+9Mz!|vd8sjtR zV+E|>QfC}@=syCL9le$RQS0TgUr8bz*WIF>2bXZ}O=YJYHoThw&wvY(E72s;m{KcY zyN3p_(4iK#QtbB2l^%%0iP->VH#@gJ@U9vLHRE_aFB-i)-Qe<(+|8VuHX&zdqz&DP{j*9NKvpJ#oq4Rdd@+fqjFNQ4W@7(G^A}hID8xPA(5>uRMhqHqlvxn<7{h;z_5*L!}1U9nJbU^q#X!gpAi2TlaMbu%zXi-#)4GaXjC4iGVl@3 z!WHN^7ljvbwv??=|F))PlyM500@&KEA~1>sc!2P(4WLnBNXEAOG!TEkK{-ZEdJ1`o zOfDuy9`S`9{1vQ*g~CsfC@>)!U!*YE$8l$6A@zSdor_nCd= z=#tOzW@xX%?)R(7_wV1A+YO6Z4y4#DNMzB}{aBz11Jc*zkB!1v2f#}8`z$1vq6}1| zax!-%hx$yRZbZfeRAyP94x*&7$bV_FhChsAc)i5HHzfOTCNG7P8s}b80&1B(Wdn&I zl>m67BQx5-^3=OMkafNsd`}b!u~ESEGU!s2S+<0n-dK-fE8M7M2{}Fwi98_^%KHIK zmz&5_ao?bcymF&k;6yHSnLo;ADP!O_Wsj+WTWN>&CESOAeV$<{{PRIAixVo@m496zAb@zAsJPNMKZ4FmR#82 zwd*pnD|(Pu+QkR8#JIk8v(ew9p98+6me6r$s9K@7gva?uM^D_0*>N0HWXC>dtRzN|WY=pf`M>(^`@}hx?Du z68Id-77{N#$=1EtMquU7FV*1lB%3=pZ>8J#Fxm59+bJbnY_$WiH3IeejuSy7SdrN` z+5>pt5>tlY?ovovlo-AcyMRe&?%ZEf>cgL-lqzHKRBRG?qx3Xr)Z1Wg+_`<*xYFg~ z)(TJh8tH0KLS(DvUszF1`#S*95Tu9`r)mV)M1O0u$|!i*F%nSEP6?aK{JjR>;;YtTn8(tQP5hEW1PifC;2_; zNn@0NwNms<7?GRC+AT4leg1?y2)&abAiuhJ`9a|Pu(vw)LM8Td`>=zs*%VJ?)k|01 zl5HWH47)bxVpf`OTjCr#k|VUJ{rD1h zeY&BhAcAMJsSy3=>Y7URqXIH4YN53sa%Lr|_4hv1aba+?z8G;14%C_TZI4s?_6<>&~mULGfdp0GaECs zG+H;|wG;&+QLL)*a2wIg) z%xBS~n?d^8Y=OuT2#u^IwcpuD;7!%q=8d|!b7#w*{W^m|+7H4;S};gMcTLq&*9$lI zfru{^H{j;?`-&=}23)8_={L4Lbs)gtz+EM>U(>krWQf~Url-Q}HZG@zsX+rDNFk6} z_}8#Xo9)VNu{?A3f4>^51n#RjT*wtS1khp3ZdgC%rQc+PAj01zT(a;D7+w{<1>B0+t>&uFZ)y5?NS7dk8eUX>exxDU@2kKYxNof0l0-+G1(UjD|Am&eB#P>K zKoE&@)A?HnmkC#_3d<}!4*KS}$Ey@N`{6$7>W|>1EL=YycPP(HrdyB6f5x?!=j>gM zH&USaO3D>{h~J_hP*v3(DvpC0+SI}W8bvxPMKVjs7a;*sP5~+P(=g>zd;6-`OOMk-f4}P7ym5t;f?OT2c^ zw#!)Q7Mpl0mDga%OU&VHVeiS!(+wm+<$5>s9zzxBZ*s>_@lgzx zgfO78-$Til#!+HehpX&P^9edg;pO)}&Qmwvga-tkly@6HXj7^b2mg`)_b*|Ib465D z#!8tzX=`MkmGjlcXS6F$BFG!>woK~Y_m*x;L_~e)U#z$sh5sn%fnN$E%V8Uo6V}0?;xD{jABuxe@xnNi|-T_4s6Jd;G`I z;Hyem2~lKH6MNym#7H7rSx{yD}`pI)@rf#l%oZY?TVgXNOc@26aT)0KqBbsQ~ zf_A>m<>Y$ao!jip@!1*f@(&ZQ@JnfO@DR(aI^762iL~$S&)jw1lYYQKxG)YD)MQG7 zLYsq;&4FH;IBhyHH+qnOo?e@UWU>Agv6{JgkRb+=g* zrV_Q!HyOO%y68D5eB0n9b)^ujO&>ec;>)#_t9Ev$tIUet7i4Xzo438EN^C3E+S1s= ztBW3vhlG+b@P|F={BTkI1(6t*Yc{tOW?K+cXuA?UfIKI;9QcA;@lI;6;tOOMk!aW7 z4UrhzJCh71gA4_|#E+=G1}ScYU-;X0pP)e3ro@)T(^pD!P8^2AKn;o0kKHE3Q?HHJ zDs*4RGctCm$+5f6fFBy*fcNNr83w!8C1&ANO&pcjv`a8R zj86=s7yZ_ogM@nL?cQR9-XzACJDvQj_WK9RXqmu0&XQlRH2bXB@gD+7v`|7##I)Q( z2N$PqzAa7N9g)5B-;17!vay$qW+=M>&k)beX!q>?f&s77y_hR83DL7XG&HV9nk}y$ z%u6LfxaN4kOFg7XrQeM0fs={oKw=i(G~nZ(y6v*(Yi1`gUqZf>1_;=xbKE@i&2Hif zymh;r$?3dMd4klN78XN(c#73|JCt=@GKFbZ$5vX1unrEw6_x7T$U zswnv)M)fLP~EQ-!mhq1FOb&KKbEw{zFqepPZ%kGL^3m9A#c5fVlsIr zXj&5X_-L3sASVeIUxaX>klqrXJ*IWBA_cMJ@c{qY;$7@sCx|Ckp-z3~MyhgZ6&wiv zN2)QH4uO%DmKp_(-+1|kByGr z^6}M#8k9^ZA3^shQzH;6i406_npwsdvq68v58`j~;T134P$umvCX6lZBnTFvyweBX zy_5=g_qjr}aXrKVcu=`?BoZU@DSo^mj*bFpi`3Sg=0xKK)m1b)u0`%e#Wf=rVk~0W z4UZdqe@|Sqos?R2%))dwWa=)iK0P1pyDRtHrXYj=DSeBPr(YU)jyW}4G`LnZNVjSKhfN|C@^MlrO$2r2?SCTMVntttC`AFa7ZL6Wwto%W zn>>z1nz~FZdOA+{Z89ru=ep$naYtV6{q6qpZsu{xjd0%Z^T6*|r2kUTezO6MYV}e; zu}8SqY<}t}xxmq{w410tz2JdMl(jg>r6F9Y65u)Xn8M5zb9>-|70)m3KOLlnMPh1C zC=Jfx{PK9=9FQKOcabi5YcF$bM$#KuS7jDi{(Q&^M{MFPvUA`$IN`!r!EE}mg)EWF zbRs5e?-(!0R{MFo*JJSc_D}JzQ4mRBc!KD50tNfx!7nKz>}n@IVZ;SCiwev1m4%HigXaQFI0Ql#T5UvRMt1Zb&m+%l$Q*HfQ6 zM%*YjqE3C{vngrTn2;KdxPreaaBA<}Ex*aF z^!R$|ZCdafw4gBhONxhk(gbclKT5#-)Hq)Dz)Q`#%*BQMJtl30N)1nn&XRN4!F=Ma zcfM}s^aHPM9+yR*BzKN1iuxer>OP^cdqrg9l}MY;Ugz!U#%vLXpFhw~oeh?RXxN@O zjJDVAKVA9xv3%OTPB-%J1AG`MI4pRsw_n_i?U`-0wHEyKOGQQO)Ga1+j*$@>if<@Z zR({p%!*B7`i-iL3ZbfA*RD!DV)8dz$r`E%>K+2PPUpclst;qC}ff>mMiBt8eR9j@c z8l&?kI_U+~2^B6GVFkaUtVQ)2I~SEa?*7zO_c*JwV>P_rF_D=j?P)V`*PEhlL+X*= zTqkN~2FgTKw!HJ~?;VL0mcxfdzHV5dCx?4WgCHzpUH~s~w?pPyd6{404;#%XI0MSL z^ZB{#^}rshUH%rpC2%9WIfC=pAsXB&Vy8b*L|pc^_=@iaIgoR|QfHl;J$Kj{X5_5E8UDx%~o6R$-WHY9s}UO zx2STA^}xAoRQ9AkQIAaKMS8YaacyUV&?$chgo1%D)n~83?G_rd$yyNA4ua2&TlWx= z80`J|U~-8kX3;5O@E5BdR{WH;XgVaw{oP|V?At4+I>CnzC^bO zbzk?hpZDGS!`}NF@>7pmYtAvp9BYnGU41+ydzMCq1kP`iUo%#h{&Dp@k)P%9SQfhm zSTqvcQk!G@7eTZ^5)M`DQ%a$;_a|*CrQB0k=TR-l?0(;+b-gsu|2er<f@7}4@k3A}*70su+_aoyyV z+DCA}8d_g=;}m28JE#aH$m3HypcBMp5G3RH4%`5zx}m`N1C4@GSgAc_7;3;s$q4E{(h_9N|W z{z$TkmE~VI)BP{>sV3veg*kSEJMF0=L)}{7o@Rm>VAtXF#6NIyvCuf;{={5yoGTm< z>xG4?=#js=8zoaOhfk4+Uw(}wL&zTBg<JJp#Woh}&)1KZt4^U$8B1I^7(XtHX6G(hCdn}6c zf@1qtMLaUbYz^_OuY=WjQvz^` zg-^$wXoLX#yOGQMZVk4njK;(w7GuUe@v>1`Bt3l6SWg_h8D!}rT?z~?0S_GvA{(Wf zj?|m7M#MDwhO2l(Msm0x5ydIyfvZ$h_>dJ?TS_wI;8xB%EdX`~KZMy;_|Am zP2q_ReHxDD{0|QZ4k$#a_QP?V2*eRaw)tOgB|d9vllz8kVPqKcS5kUrMZ51ww=h{! zOtt@$`j|1e%sk)snNypp(L7{^KZP>wgU|qJDCkmxdn;*vl+lx)5~QMKDsvOUN-x=! zI3%FdE*tf4{%ysgL^Wp^e)lNCjE5k#88I_!$2V*@_4t{%cbHjG!WW#+Q!;c~+TJp- zI%#nikw=0hH@l9%UuU|9avbEdnNGZ!Dl< zUf{&Iult?*{h;jC9{~!S#(hMmBB|Jf!$IUD=do*9gL;8;4f2knW7w|~>jMwu29xVx zV{rGc`|fs>UGQHfAFgW4WR`*`K?HBYF}#uhS#+02^t2bpkP5t)mNv;V64uVQ{|D*~ zM_I>CKn;kkmA$D%h7ku7E%ML``G606hPF^RO^1q*4(941ls6Q0S9!2zgg({q#7joY zQZy!RmuV=k+JlXqv2kSMmg!5q#JP>=aEY?B4nio*eQ@Y#YAp7!0op!iq~O}uIMT!r zdQ=5_{R1x!$oV){;JXq293$&?#r!m9bnvA=eyRO4_fS7Q2u0f9UxY};1BgkCT9ezw zzj1$_k^}9lEk^+x-H*sCbkAii2dYrd^wKG8-?ywho!biEWgp4sf zX4A(s{O=OF`!7G5EW{OkDKX%H5G2Y+ZmRP5UiP{y_CCsaT>IyTL;X-BGy#{# zkOqP9HExL0Z(Gx(Rmu-73YLmZ|(D?o%$z0?Oc_33!y`V3> z9`#Z5%`CsLIN|JH5v1JsM0!v?HxyZzz~0SgnvlE){vf6ZlEx`7{Ot{_-qyK0+QE3O z4W}^>QjP%9WUz`H3H5)!nDq0@-AKZ!B^d#=)*82;wOF#Hrg@A#GF0EW~ zeP~WBNyEIL1>pkX>#)m{a8K9yg6lEP4^>Lz#Xfw^ue-;>uuoPrCo1`w3^JO>SGZ=y z*o(ErZtAQo!Q#h<7C+|w4rNB1b?h0pF5;IWO6_SlVg*$o>2Tk4jix#F2J)jR;W%ZX z*T29K>|Y~W)yyVL$n#IARZCjZbLL=)LVMMDr1Em+b8)s1N(Wlv{fId{j!ThWobT#p zeJm&89WiLHI54o~GZ}(qF{;3(1ob{tcQ-~;)Y)Qy$N_>lx7n(QS6bK_t@y>JqUq(4 z1kYg5>M{AZpXuTy{T}G%rl%v+M6I~Hbj35DNcSkgzrG-N-sZ!VOCP7r(sWHnh)rS# z)`uLb>DlrMlK0cbEq2rWxQr!m6;V}J~GF=%26(3oCv!(#C{Tv%1)1I|E z{YEnSK-6=+E=iQlT!|;6jY?~}Z0%^Y;w2o7JD38nrRC+qFzsu8@7$s*Ycp`3X%B3FCsu`81F{9zT|o#dv?6 z@3+)T_yDNhpI#j0#Km2&kSLIvo3{9QX;Kf2%T@@SJAT1j(xwC;Lp^(m>5C7svjGdt z?p0iExv{ZBoy@2R=XJUaUE!AUU(tKPVeeVvpVsb+Ej&5!@1Nfoy1#Xxa9f9;j=lZj z#b9*|ltv(!31yP=DJZ3cSg^zVz3ir5cQxvF;R#+=IjIGh*ti%dt9x)}xE2%ktfsR9(s{>!EW7H5HusSHwA|gj!?L z5FpE}SyVx%2A4wj5A^kp2_7R2wnDr4r3?bA#lcWIhSY~RsXUs;s%6#)SG%e4>^8<_ zhLOi+S=;tVj)N3U`=(g4yYytwrkF0tjoSINj$m$cb_dztUdtHD!#@7!dsRW#x&OfB zI}Qd4T8H|Li&@$odm9JGmp0#UXNU$IYo}@~9e=$+jM%1hZ(k6qNtL^P zee~o0K+)d*2i^O{h8O;4->lm{Gz4Di=L6&~{f^6M<;c+$R^94W#mcdv@Sa$`Ui*gnq`P7DObL-&T9J97P*@jOwPo^_C;(jTu1ij zkaFM2yLk{VN@P#T1HXcjEL^ZMf$;@ulList-!l|L_6#&ATtQGHpJ-4LkJ$njBQzDT zMB9vH`9M6Delm14^CW!7<~a0!vq;;M*{VsvSVftPh}WCZvNwj6}z+5qn!s2bs3Iixs6#!#pVd9lhMFv5_cSW82{Ae8!DAkLy zadIiBHVSKa&tBSFR^sJER<}GyH&VLrzbhqRsOqQwMdm3Qiy$4Yi98XS;ZSq-ZCco) z$Q1r}BOQQzNuPN$EP@l^BM4G+8ARbL(XPNPh@5oR{TVnbiLzciWBYg-y8XCFsRH7m|i(1oe+if{5hu- zw0?5cOe4B6Pe@k$3KhYpHn_{g8b-OECxHMF-<4s3OzHItowp~>OxUCZ@(J}7$R-o6 z@US?1XE&i^@Wr}$aV$tW_(%pd5Q--i(IjVlP>#KW8r2n&rhcd8$lR`_81~nRnEqI=Gz`8<5fjZ4#p?q-q zfu5a=AODr%-@WPMwCd)9@gSMq6E6cUQ|+L=@>7H6z5YG)4H09}l7U|}&S5-&=@{r3 zGDs5+bU&&>$NEm_6{F!T*ydn0IOnr7Gg!ZhoK>}1TJnYxhA~KR$K0(m63iA5pEkg> zyzC9?wDsjlcb}Nx2N)opzq}8q02id-=g;SOw3q7QaZZ1!`p*~dk#r$yX|>EuCL2uc zzh0hYJ8*#~%8{ta;J;DYZ*bMf?udnAp6$QDEVD$?=O>OKF+@Pk$?doN<<wl-oiV*v?U3%<;GT z(F5tC^EJm3S`wGHzl{HSKn#=x8n}Or;BF0ykY|9doqvX6}XKys;!{X9#`4k32_2C&e=lWo^-`mJ!`G^q0RS?^?iCA-9&a zq7Q>d5@0~>mNVS{e4EX$o1szG7*`<><6LCG)puxe$}X|opMH9=C@f(+vWZ^Y(bD8I zTJ8KaZ}xB4C4NEQd=xRA3gI_J&(_y}olb_>Z-mf(Bnh<1F_GKOTv0!uP<=P=u$}Gm84kMeX>)XF-RJWXAD8( zN%*Gof2#@68c4+76?e$wDkS04np<6mvMAjz=kzETls5)ZT<0EZoC*9l$5rHnHclKA z$FG8ed)mT4!O|t%AuoV-BL~q?7IPJP>OX)bHaR}$y`aLNr4{Vae2q)H*-!6#K(-9z zWDK%&6F!eViCzWA6F1t;w50uxI5cLJ25tw_CFZx&anrg^Zd;nPGXl=b2Fxm75FLAs zn{W0l382NuK()&=ge@Z+5p;Uq@>l|MHtfu)V_af-e%e_$;X@(4SkUp{~x}Hih>2Y^VqYS zPs(M8dSL;pYo<#Bt3NLJ+r)@lMr_~aP?~sBr9^hPt==Q|_j+8thbcF%QX8)xG%)1B z^0!NySHJ>p$FcjTSin_ccte8YeK2lUs73QQu|YMqV9pQeN@7X}V0`-tlzA^%k+`5| z1^5nx+<_292#P!k6eeGk*jrX4iHDv=+yIvFMZv)p^|^?9O>-y8g@5P>7V=f#K@D3u zxHfM!Y)nxlTs`6~Nj)yOFa|F4fAz^73Q?j$!1czf9m(7Fm?ESd+DYw(${7*YP`bKt zLI}Lf2^cS7*xApd5RC*2R z!5zCD(8L+kC9gq8osA4gc)Q>5&t?7yus;f>V3Y^1$kSbilO* zaSYB9EP}BD3Tc-_iGdHidr`hW z3AQg_V2#$?QXLRbgvcmaP-yHhTZfLXlQp)ida-@ZI1y%w*RN5oYDMaLPRTp^G&;aI zr_5fWsemi4WK}RY>O7~s`=6Wz74IZ7;40KJn?qH^5JOH_iMhHifF>IWo=UcMLDKXG zluE2WM504^MULUFucWULCgB&Z*#pn!@R5A_7P%*=-U&1qoMtsx+ome=?V3qn;(xGd zpMsCLh=xkQL=mZO-A(ua2O|6T82=^viN`aVY%q$UtLPh(#zld>-VCMWIfbOlm;a?P z)qbUdNS~V1u-_LG{DD+PzjU}eV#SsAAod%-oP86i__Zq|^-+jHBDwy}O{!VKdXezI z#4z6%Z@*EuVa@+$FnDNiEIUlmRb~#nQ?xnx_P?(dloA!nu3N^7#{FI%j5}((E5`&M zLrdtwv6~b`g5Xu~UN*(O1K5}sAX@jB?UT!qHDK6Xeuk$BpcRG&H>yy-F;`*1iOwcm zL+@h1t;nG1nOG^9^32+9c$AQ{M}2YsPpk->bgTd92=-%G)z&nrLw1p)o!&3f->L0JNUaq1*HHN-7_lMXp8}Pl8puK#D1KimeM8yRXl2WVf`*R=C``28>$P2x>RIpjBlT|M|JVJ}KfRj=AjHmNJ%y*TE9qQO`fh2Yd{!8`_^pUh@t>WkD@`5^fRD zuEmjqmS(5o>I36D;6ARax&HTEOs=iTx-;(Y5jx}dMNU_@BwmH&M*-ws>0mBDrQ}`y zCyV)tykU6GOWChOb`=*i2SM}$l><;>e5@;2iBex}M1G`(66kBve-mg=%}OZ+Y7sMd z7h?u*mcZH%Nd|Gp^~vy(2PNt*xU;g;a?c`m@JT!!d1gM6swiT-wC9ptk)uO(CnQIR zCS>xzv6S9+{X#RXRW^o*5DLGz=Vi06@dzaq2R=}$UUZ8;YyNo?1Ra4?1Gud=me*ID z^dhlyCg#Tnc9C}P@?LBGF@NzeG1}F zU^>lZOfetrgc{v9AquUsvNfSWl}i~WgQsyNdE*yI8=-)f!dr>p-p^U@T*aKjKH5MJ zw*ZCF1w-2mR%Qn9(7fh2P-s9vp#f3!!=vghSeH}wHDdZ;6QiIZ78OOx%4@4D+A)P3 z6=iWgQ_BHw-7TLB82f?UsD$Tl8>9K<{Vr{R05{WwfE!r_Cj(l}P#;s{8|3 z0Rt@qUCfoCjAv*-6IyCt#})x$sKg*8I~;yRc#w}r!*QUWK$BZ4Xsn1$%|R%0)eD~= z6$j+)rOIUd62rT?wD39EZBT1~mI~sr3>KRA`{w)NcoPuMBxAws5nLGdUo8N*kVP5q zP#mdBD0F$*|NHV2u~*l@?X=k_S41tXuI%OF(6g%Wqb(Ok-9b+FwJ{Ux_zCG|m9W&z zs`6C&DUa03voqP9$!Ve~E?6)G6(y!6!1nTQc=4vQQE2cwIw0}Pzf5}wl$Jx9Y9$4g z7$6GcK=J=Y8aFpeib^nAh#vS*g-pw%o>}`{cWPRA6odBB|wLiK%Bi93j@huAX-u;3eBp-58REv*9^qz%H-nT8>K2~ov? z&2Wu^i=%bnj!H-m?dWJIdn(=!?E>WxI@n6O=+<;$5YmE((Hpr8z)mMJfx9svR+t+9b2q9kc+h`po+_OhEG80XW_pYA!@V# zD?ggI0zi24ElssiwT{nA{NJxVkHT&dV7f_)pZn%}v~Y7pOed*gz)(EAT-tKMdIYmy zlRa*nYw{Nz_`XYAQvPy%mvtyz{QY4jj4r<~f%9}=LwJLZR>a*YAYpION8u7exta04 zU$+)9tJE?d`>OLo(Z_qDu ziPd~HV#UhuC)Xe7mE&lSZFGOGe!z5t)lZ88HVX~nRMFk^d^Nol+Fg*lUTEUaP^tXV z8N!_HL9DV5w=Zn;+7tmEln=}Bjshs&*4iyWFa8RKCEX>hUeHNUq{5*Iy_Lctkqo5=0)(=r}S02L)q;IwCr4AKl@8cSa-s3f`T?Fn6 zX*7g=pN?-%&IT|S^{;i+tDK?Nq>0>|A z^#hM7o!8FHc`|p%YF1!q`*60r;|2T*Qx%YYNp~cxT~7$>F0` zK{`Nb^F=j`+?OX$%cs&sr=6 z{aZbXjwhuFqIoMp>lY%DU7j+36aC{_zqIuDf{4Q1uy}cgc3N&)G=3+8(`Rmz+B-8f z?pn9)Hs`FME~=Wtpkl*~$%Q;mH5wLAH%-mks|40@$@3=7*`>$l7ub@^ta`EiW1Oaq zp7A1Ej|4T+voAM~9z?KfP#BcB-gfM#`(JH_H;oU?O4NI_Ut8zhp$0;M^{9`>6lR z-IuWE7ur!@Rg;vwMaq~KaL=P%C$W&<5yZa2R7-<<1tLO1Uy|7neBpCnod*^lOUAyk zJ{Yex`0R>)%71SBHitL=Cra)rUVwFh4aOukJS&uDM`_w26{DpuOj{`*3!r4U>dY_- ztJP%x<44JEjE^h+u;lc-pZJG4y67AwlJi>@b2ec2$@6d$cm|;(;(tX6uXz+fx19l~ zP{t%Id)0|+ciM!+fhcNY=y9Qr=UdIMnlwME7KYAlQyv=c+YFs(d~z~rd$bW&G0(F# zv)RCsyWJ7!FZW!uV4}*x@b8bJrTD?_JiRaKt#ptI;Hv9qUYpXm%d4KW57U2Q-NgO8 z9OfQWK1&s>xHfx2adP0HCE|Gfd(f5b*5L%E;2PNlc=8mehwy_Zb{8GJ5MRJ&qWr~E zFyqpyvd*Nz{m$(Bq&{=uj;6p%Z~L38^ATXAloy6g{A9e${Db?-&j*=9D`Xfy6WbV` z>>=Eh54@2Da<^b`R++-z#w7BBKGAPB==N#VV%v^TB*EYU^+pRafU1GG&)hjd)XM$y zuhf|5_fbXjv$VE1+$3hY(Gp_P)XG5tKoA@n#OoRGVmLz{YgZ#F%TM>ebXB=9a+s@j zTbG25A87+RzNF=6K7cGRGj-mHAuSjASL4Nw_p1>@l*MsPp0O*-nM(kM4>U#9?mzw- zO)UWq&Z)-n@=wm){K1UTYU`%M=K_Y)tuOb7CoWHS^5*?F=2&Ph9cHju+pesvEWvP- z2d1SXeGb2Bv_u?kkbPJh&&@n3>)&Eo&Qt5}T)IjZet4j}a@pX%+EDT8cyJQ*Ue?DF z_iXcyRG)0}7S-7)rq>?;q+VzO|4_6Zgm$0uyJt zmh#aSlpHWVC$z!!Wb}ODEeyO0WBzVI4)8XLLvD93H)bo8Xf&-_Qw;#%ggQa%a@x$T zm2gHG$xC-!pv+TgBYV*wzrSuMGKKy0zG%LM4SsQ{8$b@T1jX^Kapch|Z*0WSRa$ zts(01(nuDXMu7)vDh297T;>PHt%dV2y&&bQ-W*ZaIYdlgE@42+c-8Hkq#fe6I(%SI zd3I;BE|;;+lZx&i+h3ac|%ccasd1zEun%v|4Z;J{B)A@tfw8)7|+Gz~zfm z?Y`BI6pcX{Xi6D0()@0sgwIa$G@}|BEb}qUj7><^iK&b1vU^^P9Of_IkK$%M@JX*R z@Um7iNI@ZdMwG_NA%!d6b#S)cP5yb6O)L$4@An%poiWdWjk}y$)WsxcCaiuW#KX?6 z;8_LJ#xaZN=ka_E>h+a@?|u4n?c7=O)+=mZSz#Wd_6&Xrf1}mS&+$jv17vSrUfn?^ zAQ3bE2_|rHCW3o`PxwToHft*ZwaL5yisBvC<#9xS!j0SpY9cY8l}?r+l@)yqR|=83 zKG7mJsDbL*$J%pK8W1ycE|Jv-M|K+TD&ktN^S&9XQ5`?d#O&v=sH;3P@AU(#n- zPsvPj^e+~dg+&OUbc91HLGz%`&$_p$A|QF)Jj3W8y%pCco3YG^Cc$h(xBa1wsLKg5 zqL&5TEzyc0$hh_RtH3g6wvGIqB5f{5h-S;3_Bbg0d|p(m+`U?CbgrDygKtA-D&}gV zNYWucPuH?FDO={tWm&LxmGV%#eE2<>C2V`?c2a3xG*;j-#w9WnM~Z`m0Yp1MKhdBz zww)(n-LDdXPo7d~JH$fm@zc z;Ob0aZ=`^Ei|5Ag2T+TtvPs@4R0#9!G#IH>2&T%pJH4S)_?8eN)AJgehz4#ml)?Su zVQyqH+8&oqPPh=5EQ3qg?tp&3o$@J(ADA2|QV1r~JOwmdULvd7lgrcH4{`L5dD5l) z^?Uh&lb1k6oUm$a0|tVc49VNtEbD#5pq$NeUF~?QMe*LyKXGUu#_=G&9ZDi>2&8NO z2WbZXJ=F8fZ-_L~IJiPVAo&tBF@b(w!bCD@tbq+%-PB$QeWlBm}E04@|Mm7 ztQpwy-&EMS+{gxIx|p{prOS`5mMK+O)H!eXEJerrt&ZIXqr7M4To*Q*nxx0})O6JFj`O_kas%+CyhMd2heBK#)MD7!c1UPwMZ7ue6mD_!9oKI zOBS+Z*UCtK^Ck&QSz?pjyuZ3+BB;QJ82b2;Lj024ZE;u9_do@_Wj9sr-N`Ctwz%xP zO-Fef_qL#GAlq#v-Lb(tnr^Ob5Id>cL1Zarp_Z zlh%wnz00;&e>+QNn|zp)c;fXepDm*C3nmA|_bd?{?SUfvi0tH5kTe6J=jKXv4LJ}g zNbC^V0;u%E?;_+Dy#1|}?H!n$^iP{rN~+!jz$tOi0Ho4COy>G}fw`ZiyL*xt= z@5Eh)iU{Thk>3mshm`zyRuJ%VZbSorv|t0J<;-ODBP+g*!JPwq7|*5D?lAdft=&}R z_FTO5?U4R)=YrvFhL%^cQBy~Vy@!6*O_(v(z|sk~gS5O~ug{0x?N4N%xW9K1&(l49 z(SK_G+kU*z|BBuG)`CTM<&PMs@^LVreaEC*WA`g(Nxg|)t0JD=AE1|IpvQ*0xLH#oJ?b2 zXzXf$hF;Jn#-$24L8(~(*idU=QnGr;d`M+gkJu7s>P@f)AH#JWjEoBUg^eZuA}P@m zaW$azcX5AN6Nz{o=AGY0@QKd0Pp8ETTU>=kQa^Ce9Cg3`UtxzSMzi{jLv(Y=S6Nx7 zPc;vIYm+np0SGsvf%!r`Dwa4UC@|jFS`uP8sa}#7#d&>kw)*=?*mdJJax}{r5g|z= z5WSfwk@TI9n*E>F(k)a#!d|WFP@=X$CH=GA&c8i8GtF+y9yOo5;!=vVm#=^bL0}+N zyhPy0U%6S-#Xd6#oac-ltqM$H0~RoGXs9M_I?-J$9_JiEqm6u47~~JA-2T=rr>%y> zu%2TV>Rsb)$J0r}Gjl13^uFB*Wb;r#gz2)!SsOPvy|9ltT@SZE1no?!HmTXllL3e7 zxhhBFg#CGq+Y-I$@2i&0>{R+LK1X{uXlti$zdqU|Z&B%}SmNi_@*K6%mFDdnU=kHz^UXtd8aGpg-zu*R(RQ%%n?6{`K&9 zYf?95)k07~rszCc$jhoe5mGoZJrnq{i_S-vz+^LtEeMsRr2P0%*=q2$X&rYQ1XTR zmIs^Xch@K7ml#)2YeuJqS?#@))WxW3k@Ra@m7lFG5?wp>;`l%K*wJE?SV>?sQHZ}|M4dps{Nb#a2j!s$AjU_%y-1EL8`(o;x1)oH7Kk!K6^QDKz()&Wm^sB4Kj|iT;T_-+10c7QX=Z zR~eOk98GP`hj_g3E7b~9(av1o-3srE7%PDm#{w>1mHuZc0JwcnjzwjK&t6T@Ig3yL zJpvzE3OE#EuEvdx-SwX{0$==qlHxxHTUr%A`9rc+7=s1p0XfDJvMhV#!`8I?`Is>Pn?0`pd zsDQI#MWT8OwBRt--k;x`f(Libi?|Q4`XbTkuyAC9;6-w3c1+G;3|`joK$JpG&*AT* zC!AR9W7*fR1pN2(Rg}Fs5+H))XnBbU&<)EmHYt{}{rpY|v<3fZff4pbC$7>|gYxqS z(skJEN^(C-23iFA=p*=TR|nCaOOa*=TK(hr7|!67IkMQ)z#EAmEp(l4t;E1Y5?4oV z%>&5aXY~zHs%Wzh=CW-IbWu#UfytB~Dy?J*DR-$B9ex)i{LYq-Qh5112BnhruL*3NQvGPnOAwvn9N&wGsCV~q5+7@=sW z(+O=1^s;dm{W2)PomUx;n7qwDR{4?NQNa;1N$bfl(VwIk8S~*AfW0b%(}W$_gk5GP ztk3MQrOaHD@)!nXWuhV?)}KiKE;XHg^%I!gs^;uvJm*21W`KcVtG->nj7#T>iY=kr zJlQxYSQ+rPj?h@GReOkQ@c>fpuLco;5~pbA(M+!Og)C0A&h;f-`C$xrRoODsPL$$8 z0|OHQ4>ICV~#|kn!||styQ!CB@Yz{W~>B?|eUA>nu25o3GJ+LHT@Uiv~5O=C9E$ zu{2z|a106lL&rN-Y({jwzzBdkL^rH3YQ+z03W^Kecg=Y|T$n@p0gss35P82L8>C?@= zhsaLXxxt$VCEi?WlC&v|5XW3$E`dl=t=UGeB+~C|__>vIMu7l68||P`b~;6ZrMvkx zx(foV+Aj{qwZ@~zqBIzxT@v{fuh!3g@W0}|S%mG!HR|}qEmrdQ+?ZVFs1DzMPAtAF z+}YT^Z}1WWmFO~w#&6RG*UH&Y&t93P;dKo5T?ge?%l~mD5PxGOrAz)%ewqq7tr5fc>9sMCt9cc(H4He=HIWL4T4QWQ z|3@59vzynGAc*DyHEX8f`?!ErwqV9^QoIQjOP3C8EIuz%ekbQoo?4j0K!c;fO}a(I zAHxs)x>pmc!<*5C{1P;Zw&}yYlGrrvsOlZP&2cYle)+6!1!h2OpYQ}=w8Q7UTq=jq zxZ6SLKZ{Wlo4*S!InIX*b=lWJ4mogxBiip@2jfICH&MD%g1=V$S(vcPFYsdh>&VYk zK|-%^=OeRyuL2+^pn4H@14%1!$UqOvv&ArQ;vT%M-hVRrYTvZw`={oN``~Rnpr#Eb zDyuKr;EFbw#qOTX%AS^)#9buMdk zJPZz(^4duLEF80?SF#mSl~<&l9s0v*5$t`V3lKn%6Th(%$tb(m&{_Bia@Vlw0~RW^ z5Uh~nq}<7?CmL1?VKHMi*P%ZZdrKSPY2MACF6k<^IErmRwR{b1Dslk@*4Hik?mMOR z-LIaSsNT}hiqQT)R|F=qtS-8lQkF~&TY*&c-v(W2F^lkos*BPHYJ3(8Bu(%#xapV% zXMS_Z;dT0p9bZH_%<6i_azWROWbNNVJtPSA;EDp33~IA1w}Xcci3u)2n3KdX@Wvv{ zx5krbwRssXUjL0C&jq8N=PT92QgFt2MBe-YR$_gVje`W&GEZemnm202{s6sSH^Iy5 zLX}F~A<66NAC5&}Ec?j*(s$E4J*AI2KMv29n70L0Qn>vz$`-vhiC$5{?wCz$U`K8F zxH4BiG>@BwmO&>3 z2!KR_y*0IKz~g3%rAHH3g4X>a56_C}^SA4gE&A+_UEFtOVnEmCDLvG}q4%ImAl;(| zPkce>NB0r>Jt~wG0xymdmT|))OR1Q*icA_R)h4o>@tFj{ylaP<`U=m@6p!>*@GpoN zGO9Wy^cZSUO*EZv+)iu)jil5zyOq)JZ;#M>kMSawd z#9jGm9SdoquF!ET;Jr2j&=LsZcik5wMl3fX>jtp8w?V(0K@Sp;>-}Bnpg_HaN=n%N z>MuxnUk61*OwtJeT8-olc)R{^okw#Skc7j{WnkM=H6Bk;zRZIW`~6R`2Dc!azeheh z#c8ZD`&1%MA60JTymJCCPo5rcs9f=jz-wtAdBS&Q8kY9oque25SufD}f)pQh~43>X*cG8%>u@?1;R&0p5o~}#dr4->MH1sCKzD9 z^qt=vg5Jc)uP@5~Fv5_{gt@a7AS~=ExJW<`7@ULUjD%j$CU`-78rkT9$zj9fr7ERg z{}xHncki;f@3StbKNgLd+GZj*pR=^1#{4_O@4ERPmx z(ed1E&KT6CMehwnKtPxsN-Gr)d*ZcYJ1r}+w{)rX$GrlF44-39g zAq#8z)a?>JqyaUZF+rqEL)$xhrqu2N1q=$u|7$DHMN?+tegv>_{p-2Dd5AHCT9B!aK@zy7hQf>F<^FmI*YNP-31!4 zn2IU<2gerH)xKz@PY)GJSw|SQ8kn@6VohbDYWw=p<85EVA&`20F8ld9O7b3cA(e z9PLgME_jsf(nzJ?)hy=h4;luhMV4p}AW;-G|9Or*^Txfw`=4>dLOrH5Z3lo-;NJhO z)NoS1ksBq;HG6^p?u*k;hG)pwgaT!sI#`n`P{T7I<2FH`^hsdFvi#D0vhuA}{%wuY z&tXn19X$C=IRDyoUD*#c;>kWRuH8G;w|E<;k_b^s3u+tn!Ec0zU`Tv%c5YaTr&4n} z{WYUn9hN=2azY$G3-iJ95B79P-=`N~)_5+fS_)#CAvB>dwpOkd4Jjp%m7u5a`Q?AL z0E)3O=H_;XF9$)%a2l;y@gqXW1#lU7?f9L#sgTe_RM1)!VQzO_K!0hd3{Dz5_594r zsOwYs8v2a8$df<8Os8NVMmS4}p(w)Z3n9rjKdgWC2P=bOIgi2iv&oKILPP}d@2HG3 z-A?~R2LA4qy?z(!CruUFRKtfhe5>hI^^XWz_xjxe0Ij!>q~x}IH33?2r#KUFSC}E< zphMifWhAV?V4(9+!}yg3{t_5;otG}*!^TKAlp)1A01Wj+Ee$@$2gyEvR0XVR5TCjk z#C;%KGSdSH*8+I;}hJg{S0)<--4-F;QDx>+$;muRUHY8;=4u9+N zTQxrNG4eB0am#!Q{Tbne{$^S!mP-76O#5qGTwDRhVs3$``Z-|PlB#}EJMdXt_X3RV z4;-nhv(!8Ojw~bY@cL5&#Gh0VP_`>2FCunKyu$1Yle1ssS$3P6Tlv~hljEk?%P9oQ zzQ!lC5Io@)-Y63a?%q_X0Dqiwn3CaH5la0g5(tlGWT0&Ep%V*Z|p(x5h1LP zcGZ*aV?4moV}5$~JLH)rhV`a<>`@Oc`M(w z&=!4r3`A8prB$U6D&+9|7Zn;NATs^aW19K73lu~BsAGq)H?Fw2LR z>NjlWU?xP^l5=~N6$W(JYZ*TTgnu-E857zN!+@=?<&nj|bBD6D6faWN7FcVy^dV$P znjov#>?8Cy&({ufI8p@xTb%~=4QAQikoFA7G`@2(geSwTU%jsYJhYYlNUmzWmj@>0 zTpR4x$^*?e?wska(GZ++w#DB^yvyL@r>n7yunI6jPHMKbH;$GQR9KvS{O}IQ@9am7 z`{}^xCP10RH=QFLE?W5&c6q3KVBCoIB7(W`%9Z+DzA7VYH^WPmDl?cIs5WYaxMdYN?4Qgel)$fY7m^SN#|Ni?gj@MdAqsW{(7wrnDW!=f9o-Xy({)cy;gOaD?bk<~whND`*!7=gSwAV&l z+Km&CSutBk9GrGW-~$`4DolMM-e!V5I?X8!JdfB)7;-JMJB?_~)9$@lpNdEQ$N&_~0N{?zq=f zJzG97xr=?B>_T0X;FJ8&0)Jl&yzs%!84F5_`Mvr(n{xufQ9E}*F(Bcpa+QPnwD{PG zBwXj3(SRLT61{j9^)pJH^Y;qf;p)@_ia$P%SL*W=latN$Z>}1Pq=huZCYw43^czMk365;09y`Pr>W|~ zgvb&X12AUF=V3NGzI`}0PLhc!lJJ%z45c$!0y(-rf<-|{iKtcV1=P^G9DtGu zo5}wO?x2wJKa%-&-~SN@S+x3puN^)a_|mir9ny%LwavG@{k_}9A-%E9$lb43?DzT2 zw4#IiaV)vz7Z6tTV=JAP9&CEwoiYHbpy)f>bj}lAHqRfCVITg#tAZpp15O9Gt7|y# zueey*a%FGYIjX8u z5|~tT@s9KSRyq&ao|q>Uaj82keLtG91xzi!L?7O@+a@dKDXQB`_@qS{|}Vq-F2BMoWzJCWEf zO5J*mC@NCUhQBZ(B0?2DI$Q--rr8euBLu??zb(lKJW!^#W-7}$Mufrl7g5Da`pPeV zCx`=IID4Ot6&bKHJ!$4)PI#9|^3T!Ujcl}pE9YN1J&Z8xjK->%BXOEqm)XWwP1cw1 z#Df4kW38Dfoo*U?3Ji{9GK6{8RXRt2!s~-77wyMl z8ik*T8^!zOl=At-7t!RH+xpa>Kk9VIBOd>QU>Yn7^xx47Ehi@pjyPJoH~Tp-wCbP` zMJ!lwbQ`2gPJW5WAX-?I#0IqbxbnjD8eOPktUurU{HZd{rhc)H8 zQOq+?-LR0fKSv`o>bc9V`I}W#F=~zphM9nuV{}ie>$7&uVCvgY_cybt)u?#Qj7uU~ zbO|`eZDz85y7#mG@&Om2q&Mvs>$IbNY}{ z7K7p&*QnY~M~6wUYJ~7p)Dg0swXwl7R5}`29YoUbOhu5_`p_ol^jzbilW+6WyeCTW zb3YCRm|#+|3DU}yyvDU$pEI}+3Wo`|6_T$OWXuv|)da-G)~h&Z`=*?_E0(^;+g>b2 z^FACMC^YsYn5uhfVq!7~nlSfT0ULY2@t0Q}@aX&+`{qdJi;|v#1os>QCx56^`AFRV zeQVjB$4={2r+=g9gX$w(^z$yyS2LqW&cw6xBHg~}6?sP@g9jb0`NK`H`Lc`GUwS49 za0U|H$cLY^Hj;jfp%}Beky}JjU_xlFturlM;E0zSsqPGcr9FOv^+;P+e65s?w>pTi z52efUE!pRvI-Iw`yyjMijh6q4x_#wu>mDB8Rp!~*lS}!6>zk+^g7Z#R6XUyaK|IekD`l>Y;D*M$yen!vO#`$dw|EFJP*np zQ&s%q*BlpEKKafuT*ge4$YP_K5IZc{I0Ad-FW*7D^U~^@?~SEqPY9GDc!M9#hj=bK z@$!b^GVg=g2zO)D;U2Rh=Q!#}E2s}NRsE@(r*+?7v2smMq1-i&RLRY3JWDQHSxCN8 z{8RY+B*bN6CM=GpQhU9s>`u$=$f*DNLsM*fcmv*K1TaB#mXIRc(}uUfAE4l>i@L@o zMsB}{kolddQQPm<8|)YdSPBH0tg(k*6s+#E%}#g1rL(9t>wrZyTH-!wY=auS-%n;O zp)I3VrANB#7h%@BBk@Emk1#CWgmy~ODx(8(B>yZ87kaY{U8a~D6E+`%djP%EF`P>+ z#N`p$G(hjDBrPma9$~#LnrAaCBbQX=-L_QrXsbYzYL9E7?na~Z*fXgDL&Y9GsE|CL z@8&Ki069O8Ycjo|AIN;%#!;QN-n2p>)!~-X%1QTfwxF%LCz`xX0qM2^gvU{f^(iR& z32pc|hkuY~?psjh{g>&NshW2w&X*FJW&aTy*)(UJUbkzVckpVAkj+|)}M>?-})ubGBQLYcC ziVh?eMehS}8_AWVG}S)tFLk*)5Egl*r8coFXHVtnL^kTaT077abmler|1frzK~=@? zzTbP(-QC?FARrx*0@96icSwVq?p9J71SAFN+DJD@Np~Y1(wxPA?zwZ%+&AYHGYkU^ zYw?S3e4df?mN?D?&o-l{=Z?pUs>qq;Cx8+P^veKUpf_P3nD3@mrkXFsL!rl>OrpF3 zgumW7!yY|(YO!mvfXRyO8n`$arNoOFzs+WXrj)7ORqyyJ18pTcQm)2(j+`u+wO#O3RFX&;WkCh%7UZFfyFYlkq79dhx0G{H# zcYi#E3flRLZn#@2v4ld)L^W~GBSJ$%6DyYcULrvUyY4dQAwo>C@gNSDxH(YuZ6il(|Ke4p-nov&`_Bz` zltT;c@eYe9c#N7nlZOnqnRS3D!Y-x4wMDZ}Y11%-sLb1SF{hy->Y=T24W4hG7W)7s z#p8qM8O_?aYRvoHqR`DMcen@yF&2TjUvC0DbBo;HZ}=tV{4IsJy{MLPC1g2Kdikut za^f7|wuk?nDnhb>t8V-hnY@Tvm3q{UKMaD4uyj4af7~SYnq&)PCm?AX<8GG-gd1t; zNHbbfzFgZAj3h@-w^Hg-R0~`}xeGGW`&M%-7+d2-Y|)S&2e+zQOXu4}Kf~S=B?2q~ z<5hAox;4y~KrZywHQ7}*&Fb7VtlRmIz(Acx$}Jj6Si3M@v{Dwov*)Ijijj>H4>pqm z;zr}P0hCok?Dq2~f@sU5`@|fl|C>6bKWYL>sy>8V=~^Gx+cF3w;jsezE^Dok+IQ4` z?UIPUB&!bL3>xk3mAZ&lRaPeoJTtC=>9(V_PW^-XhI^ygUZ6&dkMMxbM|=O7XEfPj zq>KoK2lWfd_Q&O?r+eop|E;)tl)+Pc@I^OB(+qp!u;93?^GV`R((@00)Y!>@_ouF=-ho3w98fZ$Lhabc z>7QUd{#_X11d|SK`eF{MiT(S*;!)~Z*FF+~WO>2C+ILI8KyDHv$|X%gzXS|KYxH99 zWy}!H|HxlUCdPgYu@zTn%9|jdH?oM+mqbQ8PpkFxnh2C4&2n{v00^s z)7isoRrIeaa3^ENg8-FPOXz9wZOI zHLjkhw}B}=34I_2n7qErZn`f3FaSny$UzSOKhlu$$z)3lya!4*dQmx%akHbxyR+tU$6X5-jC+&FKsp}Q^nr%^Tq7=+OsrKy;Sh$k{=uw8!F-dSkYwDVtrSlB^&t`2R-^8QkyLg?yfrDKWSVdXh=F> zwQ(3U$V-pWPp!(JGgrw96%XzNnHNp5{N5Z4C&Cw9Veb!ac$K)!Jcj5-TFuSP-C}Mw z#{8L5m;0m1bVRaw1LPY0Hwj{dk#+MXChtR8kjssDE{#$+ z!u`qs9qoBzHIjZ##A!HC7O&P*$pB@c^QIHqt;>X&9ZPpo=ADGlKVMFYRM`z0Pp+ki zD=pRmA;k}E>NemIi;|O=L;dr#*Ac_XJ8t}w;xMK8-)T{=$AbRa>i{Yyl!h(8uSWB` zx`4v5Jl6%07j?|%kcZwD2|UcA1Fdtotv#f3RBgIXy_ey?`{ahGsLRiK?Hf)>YO@=Y z(Qc7+LaTh)Eo4L3SB`h&lDU8?ehPs-{3K=g?c29Ne8}Gv^We*%u`#v%x>&}8N6Q<4 zE_k!BJwXh1e(CRNI-4v!_X<4udh|p@4U#E-%FTZ6wH9t1*U6hmX$m!m<&DOE|Kce8 z(d3YafHgP0@#B<~NBB|9xJSHRt%)atWam@!-+ygyjsGqd*bX=NiQhel-#oMbcBz1l zmk7;PEU$Ie39@N>w-ldraQ`^Jr0OUqz|lMZ`@0+If!jcW3c@RB9cp5vD7j^IrcUzgyVT<_K7=bmv}$w_k< z>jhDQDn4xjeSaD$j{#RA6=TFFZh09tLVvthg%T7z{6nn5OEc{OVPgQBgXlt<@O5pj9xG`r7L0GF&~piai>M z(Ndqxcf9a$bmW3SRjZ}FrUN;>&iX{*v1_z4besu|T_ zYT?e`SbtmdM1+dG@z~I9NEs$f?eorkpUw~SXe}A{ZOH<_m~HRpb6)E%ywkF$%&50H zQdha(xBy!DGM%YgT$b+?irmvH(n$zWLYazCB=kv1YVGsu*`niVz7pwGN>j=w#$oGK z`|gGWhHAp~1%)()8p1au-O9A2yXEtF@u(%upkf$H&PrXcrRW&BX6DDt<+&>+7%-8b z)licWx=)h!(NHM9HIyiQ`wns;$G#vY;RGk(5l$uqY`GBo#4g!T-Z42Cvk6kWm1uXf z@BEOozQP2uCz3rHED2z0Ol_zpap9*2uUyMIhniTP>-;{bjNLH16!Z*pdi{-$^#&m9 zB+)45^3`&(qQ)nQ`62^r8||gX48rPOyDx=a#pQf@PM!O|$x)&15p^bn)g|DITBS-s zUmtW4Q9F_>^T)4ZnL$iEP#MNoIMrD4_W$_TlL#_9gCDer{0mFyIn`(y{%Wf7ggRwX zKmkF9=4)cl)6FJUb2^!4fjoIY_;S!C{GBv9P?dW6Dz-X_y>CDfw!2rn#A0)ei}HcO zK9C>Z95FUXY|n2Ed2lYPu)sZxIh8hX)MmbR`wYl)EHg?q^IUz6cOuLwY_<%p3nhL_ z@kQ#%sauZCN6qc56luVI?|y^oaCGY!_v?zcU(=!-n~-Ue8}4y~)cqe-S?MVsp*u1+ zOsQQPKF7EGzvQ35^n!JXKUp7}h6wpHhw+7|FQePPJ;!tfBnDy|{}rF|)baZD`uB>Y zBS0VpYf|%_3EV2W2{+ZyyD;VI zkE5kxqYKBce}G)}&es><+Qp29It#|qDa5DJ*}%ixk#QCaYdr4ZyvRH0h}aavmjHKlw4UkknIodMs!O z-iu#vqZ?V%^Vi0*yj6}z>7BrS3mD^;3TTekJZ9`VRfas-=7NNGf3DZXvAzj;91PT= zCF+1|0TE{Nt1~TP56TB4$9zHSEw0mV1#(gFm7ZeMYcC_b%@Z6eX`I?CjFUKGH^F9r z0pVlwGyrlxtRd9@*#HhUh%S*NISH9S5j}YJh!*yH_>^%H_sQ^5tqf5Alq2Q+i^k*$ zwu+N>xPaA-ck+hg9WF}##5acEGepr!7j}^c*KbCm^GJW?__<8AzC`w8-=TZU({CZ% zRS2>aVN2*vS{oZ-S5a#Kv10$Oj4imkX*#F|?k3RgbyLl6ru~S=jz>>0K{WWVg}24E z^K@7ZlMTF-!4Zi*c|FSVE)iyfg<)~tHL&z;yxULOC0AyhzwjzDCT6(V^Jw7*U`kpd z3dW!t4^?zX(;t)I!|*POl=dJ4krLNjV>I96fPc?aOjlf-0OyOH(Xj7%+x37>{}*BY zy?1J0ECRuZ2%;2mW>=k4FSc+1OcY*F`49@pm_3-o2L@DN4m8QmvJWU(+#AtH#B)Zs z%?}c4{NP9lO#5x`E)a}#)|z9ucZ*qkG@hMR%}KcX{UHQ63gFc0XF{NU@7@cCj7uT` z+y5p6EwuRM94P~I^44j01z$lJUy?UvUeXr(yowv1k5;%m!>?QYc0CsmXJ}iB3eBcn z7vmpC!dBRSz9x?h!~Vf=8>6IZ(RPp&MvXv&W(okv^#hq@`pV1QCERF-@fSL&<BE&RD^8*CFLp0rX6*~{ z-jb0!!~GwkLv_I5s(?{!T#m52emxX+cRiG51ofgao_yg9kb@19VV98=|B119iAwqg z=OOr@kbsBUcnrPd$*5Ziii+7bh_VB3;MUQD36IVML?7X+z4tsPP4I#erRPsh7UMQcfDXCewgXsv|d^at> zM=IwX2qzBRvXUKf;U7?z7!#T$B?w85xd`e(kc{(?6t;M;@y+ixU9FGrPKJ=j><_7> zC?oE`$|v&>W+MImgF~qbGM6H`nr|xNkFPVT+)&M2fyvfqme}p5!CU)-HC$xP6UTrm z`Sujp@vz^JWfAslaSa$*+-_LmAgc_Bq;sTN^`=lLOJZn2;DSCxi`*8{-X+l;61`kd z!RIJrIsTn-^&hsHzZ~~Xu+=&(*Xs(sL=c%5h)OciqW{eR>5kwk}N#?mFbI}n|iNtyJ5=(eahP_PPI9*#0Fh6=fI!Ph!Nk1I@?EjP#2-Z)^P8(EsUQd%HY{?SY)kAF2J!iykSo+74FIaz@)tnyY_|q8QB=I7y^YTsU#jJr z@R%@nWxej=O0R08nkK_yrHqpq+li0QKuru#d<^&t7ch(Owq#$>CMJsKL>aIF7v)hY zV`>o^J&-LDfaZ2OL!~8_W+d26YD`*ZmAA$2qgIkUkP-sJa}Ss%X_YZ#yHfH5^xjfK zg+K05%gD(Iw+{VP+eui;11>ZF%xp+xMu)WZrU zmD50lXsJ*ROD|V9@$}#|QuM2zHWgGtJiR%tR;I|l0p z^T*#gm+#cFWIC(}ISrW|=WAuU?s4x%imF);ow_By6egMh1!8IVtR<`!w1KC-yBJz% zlR_XFSd&?aaXQ~;xyD?sxrsKm&LMx9)w=m@Fgy=OQ-+j&eU!QFZh~20Q7>x(+L3J= z^z13n0iI{v)p0{~9*FTWO@yzMoM)T$v;mIsExBQ1B*kWAK}aWtJEBn}*i|YV@x&3| zpr|X#h=qLDOcYIHefZ(^tX}<2HQ67K0ER03-s586iXwGD+UJlPzOOX)9@1tk5=ja% zf;9JkC`iz39y=qq?m)3J z2OJI=6&2TKv$^n)I(XA206&nSge$XJx5YU?n<$-_Cn1bIu<%!J1dgO;;*dd|DG7uq zC`+)J{T{D}d(_)Y1LB+UkP3%t){J76h{WE^TQ$+oD!mRT{))CQz_P3cIH zIvln~>=#5u8)?R$GD3S~V3Byz)UT$7*ATx)Ru~`Y4&3xEgjoD*0LO%n3d>_0YNZ`7 zw{VVT3ceMBvPIP0tD~@Jq>`)u5o-Kqpp!5)m!bObE+?cBb?o=tpV?|-EN+9V9trr6 zM|^^nlL>y-{2a!JK3UK0^j4tHQfD7*6YzAqYkB?=m_zP%{bof2NUuaGRRR72aytBn zeZYAc+~Rs7Y#9ae?9Kk8>wOUu5s2Jq32kh95~v|({$_LUSE@Ce2_F3o|1*jEIAyX^gk!N=wpiPeq(g9!{t zd~dRZY67qEMsGinZB>n^GizU&@G89!#A)sApLn}XLR2bxYlEmF0pPFl@xd;~nZOHm z&%zz$y%dGz^(8-KDcJDe@E26nAr*pkULii`x>hvKMioKG6Oe2XgUh`JGKDJZ+hZhP z`02^hp;4=9Bs_W?Z1TAewnRW#$?{Y?`>%QWT9GF_uL3OTLZat46`a z;~~_ATExNWRES2-0ol*tjGBRsURTMdCvm@BFr!S;(|Y&^w=t4IYCU*(d`)~w6&!bX z?%hCNq<{Z3l_G9m6>Ka=m6*Y+sY<|uB_$DX2;doZ8M<+a0G?$1MP++;=y8Ugr)T4V z&t1m+{=q?6wVjpq%G1@!X1mKELmKfmr~PJr1SL)w+~bXbIpkf0V2Rmq%A2fqaRUjipFXRvJXa#< zh2ev3$mqQ+M5cF}f-4@D0k4C*Sy)0;Lpg7omsVrrr?DCAY{`9mdCxSCsV>^^hYekB z;WvxX2j3q)zju|1XXhU z$=7dIY7^jH^zQ~fD~OGiXdw-KmcDo$8| zU)-A|YJe$dtB57EZ}6l)w#Lrm{bbV#Ul||CXhe#QAY5 zAQ@CQI)^-mOm7K)&hUWn0J2jZls$h`mhJ)Tmy)OnKxA3$z(GJ6l5mvwO;f@{9E`IQ zC9mvLmxT730nqS?J4o>jWSvg^^TF#w&pI|<;D;X`a8SA0xHWCRHG=-1-&sF*fUTNS zj3wC;maeHPJP~#vYv~DVkU%m~-#RtXDSl9Vm*a&m=RfY)jP&sHJDIDPWh8OU^bqB* z{25{`j{IiX?tML#Rat3^54K)^=W50P=hkejceX^uxrUK=GqH!0=-rQ9u0$QlSEwe_ zdMFnU1Yg75RaZ8+<0?aRsfZJY?+<{M;%oQt>;d3GZkmt;Bfx_ifTop|c$iRWUpE0~ zH1Y(0DoU31@e;cL{E9%Qe)4n83b?J}tqHe;7MhD5R~hKBL?zd0Oqq(AUb@Hk*JEZY zSDUpiSFED5Y2UReaGykcw+Z~lb)#7^0u}pYD35Oh!gf2YX9aQ=df;6~+#Q&ifh0cv zknbI-JfZjNJOf?@-#HBl|DE4I0$jR{&pH@0h>5DzgQ`W+#=|V#Op&$j)Y#-w{7O+ zN4Qs7rYv3`>XID|(BZstiCW(A|FPw++Y}3pfztmF<~^ltz?u^`fx|I;H-u(h$N8gC z(76VEZ5U&f)r74it;O8JwMn2mq4l~~k z0?M$}KR1Dmz=lhtV>N*))8!zp9Jaj*{ra+?3i6W1x>g!C)-~X29;!SiyK0LjaTFhM zw==oxf^aI+uKLs+$ezbBL=_}nyjn^XV#;sSPoJp))&AG~16yKd@J1mWks2A20a%;6I*ma*)EN*}pc3!F|6mED-w}d5wJd7f+yl{Fl9@LQ_}HFQ zg{OZoQV5>R7A0XJ>s&KTs_gAM(Eb*)bP;($L*i!t*)J-?NUD)z*{#9ui;vl!;V_sUYM z#fbf(IShYbFFR%9iL;(L#PPg}>L&Gsw09&)|4G=WVMdaIo3c-4`&05YQHqEDKMsy( zHae#1l@7-4jHe|`>%}s3cP4DFkkFrrL%oeHjzVd4ChN{UAcLE)!-wPi&UA@NFY8E# zRrhtTY^N;sZ=3<0Q=NP&7fhAkpH;*J4f4|lIzg0RK?!3CY=yzV;D?+1#J}%&%E(j^ zu@MprVok-V35bUrH_F_;i3+^JK+tc_Hl$(fFR&~65O3bb%+&lSrVdWrm?=B`ys7#a zesTC!z&VHRDN*f+7atR@MlI$p2)5Lhuz`pDUN}&rGqbNxlyU)~sqCcOk4g;od^-*u zd0I1n6CZbDE(ro5PP%reD*S!@bnFURslf$ruzV?|tm)ZIy?}7Z#gp4E#HNySg|t=iZKu)vQtzlAKbNey&Vx^=I1x)CAF&ew@Rm4#bZ<|<&3_{bjxRy;iPm( z_9^?@5P<#7r>xF3mic0M&<|ExvHyX`m~94EN^G1h8n->(-zqKn-w91Kas6Vu@#3Eg z0sC2p7(*LfI-@0m?PKKRm<(E?l7>~+ehNit79;i9f7~0lhO%Nzm@%aOhk;-?B}lEj zYvlURUw>%AKu@>{G_@FL@Q8C!q-k>1->4KPwQenZ#OS(yEnBQA%}+b+^7vpXT^YCy zKNFn}KZ7M+S#~%u4ashZ4{_ACZw){bcq6pk?CMUBGoWwirZUcZJgt{ikVc;6+E%Yx z6ITH(VUPrj2BjN|34;wbJ2+N5z`HR(2%mP|={gp^EJzBtK}EqZ)U!a(Ob7H*RLw3w zJnRT5Jcb>g-E3tT;M+3r%wILwohZ# z)VMAv@H^y7q}A1MsUW2!)P7LKOipmq`aiNNk=w1$vhxSM)w;j@fY5(}s)3yPlUr+> zK2u(vbbXXopf73beV^bB4lcTOO$4_57mP$c?rg>-$W1MO;Et}&E2_F*3p9kKm1j{q zeE1_-Aw5RS1%gcd8(cB!m$L@We2y;c66u?__dsTlzoTgy0b*9O-h1BNf4{``fZ>Fj zYl8dhcIYGPrkGqx>+1oLd>fsCVS6XxFxAsEA!ev85^{7L#7>V>YV88O?g|10k3tqk zT$$}yDo9rR=6FxN>(;oiNr~gksIbTMArIV zMx7m8jEh6tDVa`M;R@te8FEW3gL;5f(SRZMifr0bawS1x@q^i|IwrD``1FO&L!rSG z)g9A?TBy*avPdQrae7E5ivK(#E9#wI-X~YJ`m_`@qD6~rP6Tu~Z$X%U@yXglpk=dn zgSLY>f7JF{j@#H$mRt(qo)xn=kz?rfy!GOcPc)F5H7WP+`%)x&CbJ9zVGL!XoAZGCe2onlf^xHZYKZ$%3|GI@KazsNPpkE$oPZ{;i!)Yp9TP%6F0QC$DnzPq)u;gW94# z8&OYeYSk#Mf<1Z&7#hobz;QjMz0m~moy?o2Xf{2hAU^i{=>!sFC1DA(hv=HOy0A~} z85cJ8y_<_-+Bb(aw^=iRuukn+5*f*AGGw@+s|~p~H)xT&1@JlTh9EEm4pDVXy{*&u z0KBOd6*Dy1R?<5@Yr0~ako@)ZUyk4L{zw+u8gFrrZc1Kcu}X#BEDArbZjGucoO=?; zlIIY${*^@2D`x0h4t_PCllJv+GD1akEY?f-$!NQO0?pJv48;0l-aW)44MdxH1~FUz zgEQYYdrNlvAkIE8Eb^d$I>xUHj!1|q$3=OO|>{oxz z1z8hY+sSndXQ%vcvq}RY3ltIQE2Z4zn(}L0Nv`EyXAiyiL|7)(VZzM1Y$ED8pO31L zk?7KT&x;)MFr!xGK}3o^Z!y(ZH>7W$C$So7Ghxr1WDNw*rMd#Wg1b?y@88*3lt;LP z+?wwgS?|OMk3QRSdh1;|vrpw@^>6V#q>P(zt|a#G3FDaJ$_#a_(r2PC5|9Ng#RrDL znkh^dJK_T4B#dOKb=IoMPI=zsah{^T>B2(NGN{Gs?8CB_sO;i5$s{XXCmQ}FP}+kC z{(u5t&8)5e>HN6sR3)8CqyMkr$?Z_pOV4GQ++-`nJ4|j~?#=wTizxn03CwO!y_26@ z*Q$jvf6rhbJ3`;E0_=?NmWF*?bus7O|Olk9tdlKApcgi~n$&%A%u)&l(xmH zYimxU!LMk`_^=UunB49fvigg^1; zPE8i}lSR0Kt@odWX(wlPz}s9`mY9kP?W_gws^H0Y`0B%uk)Uc%ld1RqW~RxUdGpNB zGqKq>^k$X5wuOnmR?Qh0z2A|cVYAeDpSjiS{OvpoT;=rtD;HUB@L_nV@pByf$4`n* zx6ien)`O|t7vE1lr(_TH<6kWHlV8F7-CBR%MLf>l(Nr-ruKpr?lFh;cc0=dE1h7Ot7%4^6(Kh!ZbirVlFD3Atg`ZKpG-`$t|n07Qq*e09@V^B!){y zDQM07gS4z#Li-DBgT=OQywCBbaY^bp^%Ox75|8n%XPfyNoT9Zo)xBjEn15e)6Smejnp?18m?U%Zxl5;wV5MO{Qv zxYYizQ(5eb+$#Dh2uAPsxfL9}ei9Q9R+dr^MTORcVaLR5pZgfI5%XVURzzqjU^f}z z_YrVBDEG8ZX^?e)o6Qc&q+g;FTuo|B3w17w|Etgb)u?@|Y;^+Jx=$l*%b7l?a3nRZ zJgd~y(2W5if zOf1-6ky9@e$|d}Dh5S(?lD$}*DzeTu3sk9Mtam$MN(BY5W2r(4jXeJe65jazLLf@# z|DlM?r<0Y-%_uKwA09%gqc!(%WTY4yw|J?SE8zjUL1D^TV>fD>i~aCR-~!8n=@-!j z3cU6`#?I%*9;BvGnJ9RCG$Ilnj>ixG28u5+s@pXt*grb7Rw7_* z=&9q;Z_ihjSv)zmRUaq$Pj!rhsX@(gZA^-`&o*%Ph&5KX9)NhpR})6Po;AJ9Q1*;^ zX^b}+)$bm#_G%WNKC9a^c$0w99PJGD{8-KKn1+^DE_2rUK_qN(a91X}^FUc07V6)p zgWdr9F|=xPk{bGVx2(2Pi2c8_0CYnJ?H=@`Z5SStU$=U3f+$KqsXfcqLT%XZi3Y4@ zVfbwx3dsLCjtpTuuYN9Cwypi9?UcB289-a47*+jLb@wTk_v$;vPQkA5N!#Y3u7RM> zf0Tyino|Lvw5p?wIEk*8PjtPtBdf#tfg@jld=n0X&@LN?c3~o{A)3(HYSM>sT;Z32 zUpIfFoESd3ZL3n44*WR%Z2;@z=BlvU)k-oJ3 zj$Uf`8%aBIIr^b)T$dE&H2**!3MWemeKdxO&MS%&C?1#S~KC5r5#zq#2Y@Q#!W z>C3#Kw8>LOAVooFB?N4;5mX1;%tF?rYO~jXd7PMG)VUHfyD*y8)9th27y1qyJsVo-5X;&l>X-PQBv-Y9J@3yC3&w7KlerjF=4aN+ViHb^%z^OFW0VUj|suh zHK6h(M(QJ9syOC&(zsF;GBj4uW%LU`aI& zb`JbtlBrLoYMgJ&Y;1Dy8?gZ^f4ZpC@WF`=ER*L3RBS205ZV2*U9@=OYIB-(nP2GC zS;AgU^3^7HO3*h%sHR%4BZP7xt{a8#3`JrI)IV1!bRefBxx^ zIpUZo(yvad?#h$}_uv*pPk0}(bp9-J{Iw6n>78GuQPrYPcOR>icNa_K^=8=W*u5vG z*B`0on~5}a^}2Ji+;8BrkW0NNN){w7oA;`FwHNlF*>GY@!Rfqu7P{TI;<5Tr67g7g zF(jUJkVbbZ2gzC{;eppq?;zh8`T$O+h;gg+nu{pFx8Y%yVKbVz=?o zyX!s7y?G;n;oI1o8p~(-{$;_NeA`CM7U%B(X(fOxD3~}X^p|may-^U2onj}=fpG;k zJ_u0Jd(qMhZ6I&N!P?u-F3H>rr+|b~S|CK1pAcfFwQlS}MU2%sd$s+>K|rTce|vyq z1Sg;U2+Y7Thp4K$c20T*35O{AVCtE9&Z@0%N+bN3GpYFQzB{BL9h@ z_%fwA&7gNQy|ntV8enzOHW>ZnzIE4=#BQ*HBo*T!!Rp zn?Py*QX#%GaC%<#uApD)W;`={)HwORMn2VCH14uh@pLBoHT%dOQ}CrwH&ty6Yg(v9 zVp93fc1{HRh;j9L(HfkAD`b4Dn^w2^lW)Er_P=5JaSMxBmgGv!A3NhNgggbgIUKw1 zlDWk0_fUWoaycQoI+xI44=>@!*QvbQ8pm1BqZN0{eI859r`ON-q(6(HzYE+_?1cN3 zZ$BwrW!7VyHgC2lwkVN5s~H^R%x%^YFes*t>0aMYMr$xZCwchl=kjYl@A%LCP`D8N z#OU*{ih||Y$MTJ~q2SQd=N!WQ6Q9ESgyDy4fektQNA^6%E2x z=BWj~cSJoDL^$NwH*X$WXG8CkMArz}Ri(h=(&{Ln)ao22a@q(XfZwGyIw+}7Sbtp% zviVCjO&gNF^6CDlgPqdnIZyKgFPicLRle$&EzB#CIU|#l{inRDWr!wf)xNrY zr$V=;i@ClAdGH;lZco;3VwUq`3*R}Nw{(M0Wf8JK)7otMZ?vaea z#86&6m}svRwT6GmAA-QMIU0IqNEq=G?k_LPR(k9qnREG_Kk~B}ztrSN6$@V1zsaB( zSBdB0i>igLy>=cb2G(=6Y~no?k#h5Na*-naDYG#>ES+e<{l%8B`|QC4CxK^!vw?(E zFX|l3Me_uwmsg0`84a3n>{e&}6K7xw8DAD)7tnV+ROq!ASd70{MtlW^Qr&G4>8yVI z=awC7O!TDNU|b!arc-9<@h8hzAa=(is2qc`_4$}rzd_KcK5%h71{rJeym1l9^Wi3> zQRuRL?fg~+cFDL}p0$~&dBDZa>^{atw(<@qylA`dxAU}5Ko2iPRfp@uLris(l`<`% z#Ph{_VUIC^sjo(UQ+awJ5n@-0vt_{e;zrIO}64ce}!`fxS94YW1$8B(~}sO$=@S9CD1net6*BzR{1_R;5s8@ zmnSb%7gEz*$*Wb$Yjk$>+8#c^B&_!mEm0IGVqeIA4K(EW3g<59bhY3yw&Vr!F#Z(nsJK5%RfhK5B(P|3=wf{JRh%|Jn1MAKKD5$d-z>Q#ueUVKp z4RtMziuEALrCtO|_m1q>HP+3u)$+ntHT?Z^Rbu!4xF>XUtMr4$lfINvd}~we)Nyca z$Jd3%iyyq#$D?CUA2Jwm4#c0%uvQ)C;F4eD1KBJx;2P<*zmPMJOfLcn!+Em9CU^oU zo3!RDla1#) z*Z^hM)4Us@bgZh-D<5khxzPF4DJWE5>M3(~{DEQh!Q@fk-gC_-tMQy8c{65fV1$YlC+JTN^H2sEh|3Y~NlhK^GeASjl;)?O@dI#6 z%Ko}4B0A!006k(w*ZSk}lHlK7$iF2w%vmBLaNuy!zbr|eunWR%u|d`Xw875#jYP`iJ` zwz=igMu{eInzr3Xusf2Ul10ifJ^RM@AEvd1kg-_vvR><2V7C{D(^r4S`Lb!dg!JWU zbD%*lrpy`w>Tx1@A-6bB8-9l#bKi!)h!*jq|LSLcsQgf}GF$yg_sR71>0)eeX*Vr* zXNHQ~Zba7sKiJg8<&hs_2vfv+P2ym~1IfsGHD+97;WDg*N=PfcdmWgJl2I|qglM2UoHCHSLH&l8#a3{oR0Jjkdiu3SU}&i+gF!$8 zSLMC;b*}rEAR{I|{`b;c2C{(ZDbTA{k3*~JQV9*MtvfZd`!LuD+&deuE^(ou!&u&h z<}`M_4UoR|NV;iX?7Ot)5-Rc-hLF2MS$noO5|>d|Z~p>GRvBvmEdks_hLwU_{7%~c z+^}pWjI_`lgRIv$*0i}KKpWjGy>FF~J@|f;+rxdkI+!V+QS|Ny;2&(V+42UzWU1MJ zf60XuY#!i)5Ci=y<_~IM4Wkqcdqi;rq3GardKY{yP%6CpjwW6MH>eJCl{;ljwey7>%t`)-D>X^n@MP``G;`cqxqw;>zRm=4}33Sv~C$| z161vogTB~lC)_T!8jgv7W@u9VsQ?O7ujimFbt7#e)w=V~%DBCe-xBk$4H8tf$Hm-VxxH9v+u-E~+ zI=)G+9euQt?X~9;E;rtvwEPEsy}wv{r-O;nZE)Z} zF3QeN@36j$Xz|xWo0M`kS;)UPiAD@Y#+kiY9#{C_A)dOsi}>_D^qEV%RxEkc-?VfA z0EK+i5-idGZ1(>5mn>}JuMyug{s~>It{#yCU55yaRqGb72HCt`)VdH`K{Tt`B&YeFi02a_m)YmcY8--tN zoP=b8MAv$CnYR`WiV6I6^AWCU1q2e5;h_J=+>D)iqHa@@leJoP>-t@u!8LF$%i3hjZYM2h`RZd*qF?4K zz!DEHN>`+HU5y0j6ygVcy0tDul=G=1LVlQw{(%{Zv$+-wu~$5jS#m9LoF%Q^mqFS< zk&r{EoW*fmsB?8{T1UjQ*L;8Z+4IF{FBF;eVLE0`EWCX!_m$`x$;>tdW)z%)=8^mm zVcmoS#7xla^Qm9kt~+0|w*+{X43xKL~$08{!;x2%Ihf* znssvHcIj}yfN)hL_Ip1<2m8+392yT4R3SQ!h9fjIOI3Am$5O>HUm|jCinyU@ z90y8L4%_0)HW8@;vkc}ybpMMDX1?qFLKTvoxiR!YqfmD91i8IwExiJ;jVwH zVElZp-OV`q?^4`2xok9N<>MY6*Za1Ivaj0B_xUIrc7G~i+vO)|uIqvhw;LA;<*U9| zVUO`A(~k3dD%Pg~qdI~=pwOfX0PbhM?=1f378a44;XiZbbs8{8_+kuW<3y4?v2JNa zBBR44gEyuNiEfa{H*wO-5{bSQvhtZ{6O5rLwE-Rbx54`CbUz3qH9-ZXVrmqJvc?L> z2-N7;xWycO63^{7GaV1-!((5aJ8aji>o&r7oQUHlHS>3NMw4A+Hjpn7OUscsB(4B3 zC6*s*JWea-RDub1r8zvSy}DTA!rU^mITPp7b(EXVE}p!o4Yt>}9rhmFZ`k%B{3JwW zmYw3M82`oCTSrA1e*dB~Lzgs2BOTIGl8S(Ul+r^y6UDDk!BNEa`hqQ=* zboY73@9%f+Id`3N*IoYMTHtc6d7pWoz4xcK?}!bfl)>NGszYWS7_>JE!F#NH|745N zC1qxIlvdDc`wR7LRnTo&jsHqRe>^+Qg~}q3+e<@3vdisiv)tK1h1XYl`ysg#a|W!e z;^6rzTY8Zz$Q;KsqYn@*T7!01|FK7P#p`-LjT#~{1B)vyEE4l(bKB^iQE`26O}6%? zzgUv?Tg>WgJY88~Q-%YA9n4dt$0#M& z@YU(m5#PzHyG@yUfd~pO22fIQmT##NCPk@{!BOd5p%akVfq#Rqlgm|Zk?mBX&WW2B z&K}Z=ROtOcjxN&;TJBB_Kn}OB*oU6^4J#?!5r!4<0s*Vs27`DTa~>oKA^ zZx#fWEj01^=^AF6X8tm*H?-92=HgJioXsfS13N+jIwaZkk&O@8r9^Ln8n|UQMrwrITi>&c>)j|e(8^wMMvY;hwe`sTUb+EC@D8xe@-m(e!Jyk{7$RqO zzjCs*)Ve&dfzaJ eOOm2l$FZ++Jbj3@&E!W(tJGxq0*odbNWmhnWdQaeBMNiF{Q zq8OTCoNHEiGFaJq8K%)UT?rMv9lsMTKbxqmuxHlL_(zc_+OcVn$twMTp4=MHfZAcE zY2Cx>F!B>HeYW=+j(b^<3%FF+zIVUEXkjIDWHcvf@vdUyWFXt7j51p)(*4rrOj#C{yK69zi8m^S?GMi111c04)RiSQeu$fox~@-y@mn1f$}j+h(_4 z3zA4=tzkmzpsXFg4+3w(I)CWKY>4Nid~hSX^b6Dbq<68i`JVBa2S8Y9Fggk;5d*BV z`ztiIbMJk-Gu_EbIrEef(O)TLkiLq&$0l?*8sfFa)gZ@v2bV z8}6*Y(Y^@VPc3>*oi+`-zc*RKm?XcLw;Q)MPj{ZLu4MWWQL0ncSvRO8mArWVT?mg$ zt2`rDMTOCA+x&caF>s{3irQhZwdHSalpH5Hm$tI=Y_;wDsn?AoSh_1Pd38miQateQ zwR0%qR-f8oI&XOX&}2A!rO6SxtdPT~fCPq+YtT7mZi+eN04)K$MTQ<~_xNGwktnXt z3R5*{mHs?7ukp%0(6X~?&Y7Uu=@`f=LAy(yK^yc%M4;Zv=ZfRf{E((N=92# zfdE}_O$Mn(Y}gYF22)vnkk?3tI2#r1PK+K}Qw`1K*@Cki#ABXm2{$90weP4k*s2L4 z&aZ|SbjzECKGpOeAv=paa4u42)E9kXOb1-0CY89G2SvyHuG$3;_;q&~vf?)tsTVgL zO44t{--vV&j;nMvyBPHYbd<&>H5Z@3#SUQ4DB$uT2#S~7Dh)wk*w!r6%woR?|5qEH zIQ;bgR-ljYH=~S1$zF~WVdc}}mgS#;oVJ5xr`*PJ0EVse+%-U3(Hj18K*-7(-Uadm ziH7)tW3}9GXq?-L$B!vNAE||3UmgvLk2K6kb8l8~nDWZYnvicPLd97o#9dqvLT~+P z#J&EwjO(tri#1eSx8Gm%VT}y(jV9J4P#iStIUSn-yvJ949C-Nb?#594u4QWOLxnG; zXOQl{pB3rF*T#UDaGFtRWF?nhczQ2|HlLlInF+Q@XmfF$rQBrFeG>Ac!PS2}qpWM1qNIGxM&E}73{uN??Owu)9w73`6< zHA^yR|8U${Qj%O{ywQF(Z!f-51+lssisk&vI9;x94srv$Yp)gngV58iK&CMOz`K2A z3fW=1Bph{NZopY4X~x8T{f6R>ULgI3G@FO!3^PGbyZQFlYz57P~7zjN?cx~w1*;;=$`_}kAJYkxdS>0N(KtN@V|U(9RVB& zihhKD2RQ`Ug9I8LB5}cE*t6@N7pC$qB^H(!XQiT*63z8M1_-05|K)a>{7B1Y+)sjq zw(VNiFt%_W&3k$>?{-zt%G`KhQjfe#?me*QK!PdUz@?)CdM-Ykj^I1P>9J_Pd64MG z6!Dkrd+RgVgV*q`ofn*~eShVA{$gOdJ4xEXYrDgnSJC{>=4MIn^g{_~e!oiL|H@(@ z$2sWgy^`l&Sdu21<`_0D=ZZ($OR1aK7;Z3$n?^-AhIsoe)XK2LX{+f>z`!K`G;Ce- z7V-{`tPfalY!U|~KL~Kc37X9{Fr86nn}Dv?dLlEAMe-fTfe8k`s4)YUZKK$SeoQNg3(c-L-5(YJJ`Y(5Y2MgpW|H>i238zyO?` z#BFv8DGv%bU56ANiRz}v1wH%zluFkN5wD7f`g9SE?oyNV^W?rzUCy%ZKy-Spzqn5y zaFwh9`ihTz3jzAejBB*p*3trF7G2ue!ttlQ`hWiB!wC1Uezm> zV|jiwJNDY@vx7%(0coG#ES9t9xED89X-l*;3l)Iv(Bjj8wl@_5BgU_>3{bQDy7UVE zAq)ewPx>*17w4zWzz%HfvHG%0h_~n8*&nh-s?Fzr@?)*aG{ZTOaRCmv3msS6p--#0 z%;88$tejq4xHjkD;VhGBB8-7=2i6HO1LqI%ZGH<%7A9496Kkku^epjnZrRW&hBj4> z03@-+h{|evhCRUSD9i-_F^E(tgFgE187O?#Nu*A$GuHv><)m}a-jftJsHs$ z3|wchaM`YvDgzNvE%4e%m}V^`fy6NN-gp%5t?OyU1Hm|_7-!=XUg4RLgQgSW37o&( zXYkGs+%k8~v*PzRG%v!3Ht-VuTMMB7mBV>3fs@Ix5ZC4LBU4iBl-0=!=<)?_TfA4x zf_c05y#iVsw@!h0=2Iy~$C-rIFOVc~+X;cou=8`WuU{aLNSs&XNWDAV@c!5%|0_R?lyItH$)Q;r3|#|HHuk8jUqurKbv zqcFJ)Jic~*Xo%W9sPlr`T{0l1km0E`#@8d`IRPM~9aV9F>eDCHn17#DN5u*=RIpbf8y_F{ygWS!&&YO(v0shkra`vwal5Dw{lkXZxO#Fr3v%!F+W@ls(Fx0osT)bc2iZ(V3=QK-!uOTxC1#291@d zavvB8Ja)fcDr*Z!AIJsyWQB&2(EGQJqe9!Ml$ZugN;bn6%s}W^pw2n7NM%DsmCw9tb4j8&EwLmzt z^!z!9sJGe3#SXzx+_g-o`aBOg40%%jQIpR8u_kshhvua153}@c|1jD*T~lYBxZ0I& z`yudpz{P46Q)`9B}VX4cu+h-v4hn(#&y~}1=bim>Y0D#Zw1)5~nRroq4yA2$bNr(V+ z1duO1pZpMl2(hWX#h(J4U_ZDX`6Yi3#Z5UXbr8J_ch2E$ni-0(a9G(#3^MmGGLgsO zno{MOD7Vv+e(3;4a<^;Z@Po!dkpn=5e)@N)}U&sC+`ltfhqy)BZ9-9p+u+@CCxs6fXaj z@+f23Hn(FeJeMn(yeOZn$hkZ5_ApqNE}zTwGF>EGm_|0y9ZfwvQ`geDel}#js`Klt zFvz^d410rS*gjVB=%Z3xm@*AftXV6tzF1)^GA+6J_OOp(1d#9k^*ugAXAnTtx9;P5eoJkas9eS_tCsl`mKt05nSC7u4;d z2qvFbME-+PBWXJ0PNGq&yhtt3Ff)W)tf% zGJEDgcklH&6TVm3V#C_NrN>RkLz{;b|HB^(HVw(O=#H_DCL zbYMT9f!j|rrpll=V+&^OdJVMFQC==8Ej)-q_a5?w7+5W`86ZZ|Uzn}p9_(khj|kve zg^VCOR-QwF z&;YP#5sB5}6LDG>G1YRqrT9a;y%Zbkq508=z>*DnQ&u9eNwJRl7mp{4lTuc{Mv^4C zg4H!ONb!CXp9;H!x~+n$U(XF*-b`v%4~xNffTCW&P|jJ-4r@W_7~BEthy?K6aa#)9 zcic2lzaO-nXjK&Sp6psiuY?CrCWIietlaY^x9Lj6<>~!=o^n~Uc0PWUsJhEw_5C<`bq?+>K>3b0W za?SkEx!^${Y$5}&M}JLy>R~7HD_=TC%y3*hhrTZ-hoJE8H1ElDAc)Z<;8YvU4Cv4_r|+>I()-s7^}#P)5g&2mi)=12$;kH#6~Bocry)EQxpr^$u&eABNpv%d@>f+H2 z)|@iV6C=vmQrz!tBOJDHcaVgvA;-lvkc}k9tPtfA2q5WbQj7g7C8PGU6d>69#F`8Q z&>fCcG%eXBl;`4>>N;TLk;f=1;S&{(B409^C%K7C=r@$6-bC{-o>7!!x<6l%3yX*> z>`_;sq8qt;^qS!z9tDM6P|ktQGoI^k0{#r&6WxH!Ibec)&lZ@k+KY2=23E)qdEzHy zzG9fL))OJ&MbN6^@Jvl)bMn$E5YRMPO2QV+-|l|;?g(&0R=b~N2_qkDlVauY+JAJ% zrxNTQg1Y>8_*$2bET?|@l>99t@a@dn=+*&lj+(>ziVa8L37yj3uf9GWk=@lkntj!H zn-zOkx2EB9Wx6uDcr^RGu|adbMe8i~!Q|IFFzosb{^qpY4NxewFW=17BArEDzm~WK z7i7op8@gBWgHrB&0MTwENGwLFpD)Y+m^}dcXqXRg?rcJV5sY%8f}ho^l9gjWl&cOF zF6fd>lY}F1|2*lZ$tq)2CKKYeKV0)&BTwf7RpphuqQQALM8r|nh}DDs(23$YSiMkM zX(ED}1AkVoMu~*)#t+C5HAk|#JYf9|M4@B=_VEc>lM##p0$mW2wMRa*+n0Z2 zxbt#ubsE;Z2gsTNPw&YeC(J8@6-DY6*L{f0C$*)lsysXw;C(2&cbUK z)F|2A(s0nU!W$qVNCRj7rv)MVFL!v$gCJqflwjj_EwC9#kMW@n2^7 z&TR8|1c1a=FGDVF)kIXOS9%m6|HW`gK3X6`uzOCOuiev7-PoD)f`;ykQOqi2MU0JY zj&S(DyD8N(42NrL=1)k}JdQM-FLFS6D|jI|AqZSwxD755JPIj}q+%qv289^wE5B;@ zE0eIFu20-tV3oDA{Dko|l3ay2MOO=CL{khul(A_Yr-H%f3L5btv!bE!gVuzBIyfo_ybgJMN z$rKk7Ok6ip;+iX8&M;uF{ex0Te@FO6C5yiu!qvF#=1FSBh1cYOesXCMh9aLn_#NEv z!i4iAQ5>gm+i|))^%(H#)BH)dq;V62dX!BQaeUyEbs6d3ncS4z!=t>ATX&ZPVotC; zL@CMI4PRl$g!^*L0FCzo1?2P?*q7poYOa6@toGxYB-_8{DO2@=VzZrc@*7aTh3kOu zhsrN4yM9NsfFN*S-E9nTWk7$`v^YpAaIs`EgK0yc8Le1Xq=T2@Y;pHhq6cNxz-=@w z{@tr@L-%30yq&?=eCs$#+to$_EuBZt7N~1PvRxxDC*+)2=&qT}248S!6s808a>-7Pd z-(@u)OpVsbqw;19vX~z~wRECNblpb=13niv6BD=K!8O zogi|bc1E+~*Cp9^S?RG_}LNn>+@cuz^q1nJkO3!%B(WS{W4|YmjfNb)e%y3 z*fJ%?f$KDcsZn2PEgxke5l6{d=NpXbh+n<~YLDu>7mj|Y>!+U#ynLWrD`V}}CIO2g z_{df&pO1VYfa7wKM)a7Kb@B4{d}pJ1TmgJz{p@gHza(J%j=IJ-W%Y@T#`IjXz%Zo? z9;FRN;Jk?`dkzr>XI3RlQJXjaA%-N7On|{J=6`WO8)0lYP{|_eydqKaQkIAP*B!zssJ{CNkIMZWvlDD0vb;$ z9wL0|i8QdgOAt1`HTa_h4#!n+^p(w7B*26R-+IwP?4joezW9gT-e!E*+i zFg%=-_vhH|B$6?pcgq5PXAXEl9gj(%sH7PCnP;f4FU>@k%k@5Q9L4;>A%mQX)UTAS z%Jq@>P47bmt_umCPZh2?<7G!5>EtC@XYbExY|9m2#xC1f*Wj+$5D%PR^V~$=Xah+1 zf@9cap!_TtP)RNU|0~pcb1CL0pbLKi5Ei?OZC*vspLoG;xL*iiY->}_&c8OL@zJeD ze7l3~>)iZ?U|OeHI7d@=@M^Rq94btqzYS#Tt2jbG$qU73ek%lPopK~3cA~WdfAs^g^nAFc5pL zt3OokHRmC2RPVFmeV?8ij^*qDx(LRdiqGKDNkvQiKgCf1s1>(6qg({ z&ttJbSD5Qm8!>(@AYWuA<0*GL%OFdNP5LrXo7i*iqI+_& zdb#^F>!5giWb>!m&B-@vKFM2`;>5xG5@P_M`sT4C`qOP8=NgeN;Aoavvybq(dH*dd z+q-9~sr;%>N|f&WZlTKSY1zI!5Y-|wA25^bew(jlP1Ui{S*j8v5z zv+Kk`P)6DSj61O19L(33rZd~sB~Yt*8}E8tg)d|mZ#O?mA%MCfr?LZpxa5f=!W`u_ zcRfj~zdLJox?7zJ3pX@_l#u&Ya3l?e)<|N&^@h0Vg*xAY&1Qrp;tEXamC#%xt9R~0 z-kbl?GRB6|gHI!Km>~5_WLk!vSsi#K#^RhvQkqxG)az@=dmu$+4rw_*Bb;;Up+=Qn zi8CT6g=^=06IkP)qw0k}$@~5kj4aBQHJR)si?tu>TGpemUX|+oe*nrMy!RIN-yn+X z5>v_|^tVa1Zb-AalWc@8YZVQ36=6nD`f_~R_WFI~nkYBUqU$Ig?jD1md)Tk@g~|Bt zPiur>ZNc67(%XxCHQ7V-K2QGjcs9@rzbBOWQpwS>^ol5hN8(^0A29bv-c8v}E(LO| zn+_DBIc3b$42Ij<(o84&AI>SN>vg#4H%MT~JlUOocFr?p+xn-RbX1SuS?&GrzDE6p z2EWlnK+7q9F>$kRKa_R{?3LCo-K7=XxE7eQpO%)rm8fhh7z6}W4TXE*Qfg4m+IL$~ zmI%HIF^?m5o;PnI>8K@aN5TlwpNtNK?&S|<9a?VeREf1Qc*$ii74P#!r!~$tx?S#* z7pY#B`|Qr2Hu31USC3Q&bx5xU4`Nng$lh-xcn0V`h8mc6r`CgfbxR;Lhc9^)2 zsp_6ME|u=4xyB=|%Re4~pbqG`W`I0n8IQM_k(9iI0Yu5=f^3wzW9+9{E;}J8^3pmq znARy8QUjN8qq`J6#EwXWfL=!izW^~!6X1rzJ)LILv8T9@gdeeQFkd%1%#8y{nfKH> zw<>h)LGa|y1Hby?Sq0|S^N4sJDZlv(5wa-%0#QiEwJ7Hl7yM%a({wS}0IU$D@hKw@YH zmn|)C%&s&X>Mo`Nxk|^)e%}blDwwPjR1Q6aS95rRbLfAd?Vk((<(x!_ zCSB$lG0MouPCa0vsIH9Ft^;E&x)%4 zDX+dZ{&)BkeLsW8 z-+6PtyrNp8Z%4W~3|wc6YxVa@Ji5G!ouOHoX;}!X)1y+Si$Na~-?N&cQK`$7FO(*( zi(bIMs&xA+-z%nV|Fbo_iN`G+H^~&=LQJ%*AWE7o5Q`RKLlKJ4enl0 zD$}q`KR?`AD(P9)uddL{kCi`6<*lwLfCrYy)Bst)v@lKW?}sOSqrXagwVtu{_xqmw zd8^e~DvgO*mI!0xn{WqJ_eD`L+by$qv*nb^PEJ@#R$%Z#6s%Q*9cX_x(U{(9K(&Ua zSSj*<`9yT*lxvDlV4YT+3Wa)aqeL7WrU|MY?^5xuFiv#Z2qc}u^_iXt*T{R|HBSM2 zqpay#P9p)WI<$}8uUyj}tvR(1*czU4?2`K|u`lga>@U}-$n}&NJs@cp=y0;+srqV^ z?!F2A{GQey^V=1Ff!^Q%RYV-zB{d)H(22c^kUWd1pel}_Jx_N4QcOM(*oWI}xPIXm z)4&17UiNDE$6^qy@B8!&CCHQ2Z~cB1i^1QN9C0}GJdWNTXl}v*i?Gs6#cooxtkVld znXYB>pvRw~e(j0lmIL&!X+l?+wJxD;Y8@3Ox7CJDG;dT7Ky8|3!vpSl*cWys7{FCwi zdO%P`LcTxZ9BAy--E#z{%yJ!QGEsM=zz?$Ba?`}W=SU*&0!O?P-iXNMS{1$-7wGnk>J} zlkLr$%b^6(sT?)UUi==-h9`5#IInd3p8V4!b`eA@Kqa5Z8Lec_4$eqU&vonjNZ zlIi@tHxid4iyMBMx^748eamS<;5P~3}7G4zdIm>hX>M?2j?AE=l zu`*yQX*hjAJ-f+Yt787N*+W8cYpi@AvCV6bqr-IWY(^!K*PcW&;QuY{PyQwRzexLK zIzDv7Soi0JSdK`aHgo^Fffh0-g6vh-C~)s0c;p>xipA31rDTp4U4feFl0S1i?<)ei z6h@_5z=mI$vNe5oUkE5?Wwne2?0T+l7mvVpg>~AAVT9HZxSnk-J;w3Qt3kl}^fcLC zO9=U;5lfosoccI1%tW%9Z~D%ic7=GO__<<}$>VAwZ70+)4(NL4K11s>fjzwfnm3*7 z5#z0EyMy~GD>mlRXEwuAjq4z?An71BVAw!B+*#CD4q=)LH&p3m^w&jpf*ly?DFs`iDWK!yV1zvTsSg z(dLX0W&(1Vrp$W0Y)sPC18oPJ;svfpyLUca0%*kv%T?!2gW<+H5y+uD>Wx0XKle4N z%CFQeURv6Fo6z_p0TG}sb64IY!&h>>4PEd3#IdVY1J~mgAoUBvzp8wJ7h}13ehu9P&ik6vVZ>Mx9V-u;dM`2a^7Y>LrErhoFnhH zYv#pJwlC34iRQO%25cHmdZ(4aS+P*nNJW?QV}`VD_&V$;!w(2%o0Fa-?zLHU28@pQ z06Ie>H}>}t5bP-d*|6{q`mV#nKNR-M)h0@=H`%YoLEi+Qw$C1__W~b}R?h8%CtSK` zHu~>3CbWMi>D(!SI>|Ryz)3=XG=39-)F`4(a#k_@_$9^{fNUPUxN91APT(?{uXyF& zT3_k0H9c&*!5(ls2nBlh<%#>73AIciKi`R5^>(qtqcW$p=RTf4&|MpLrk9VV&Ig-! zIQ|d1def$j7SQJfk;g#|{3!`@cr)#faJCLehk4l>%Yt0zdp*eCukQ2cX3jVc6sSXG z4rULOw*1Ztq>pFsGpBdT1My6*M#Gl9rCTa&m_HFR6OrCby)gbsKgx6dRbJ{X*cD{p zl-4+3Y?LI41M&N#6$yP0b z{ZKA4(l(-x7S}lCHYJ3D%wV^WPqBx&PlszOXZc|DX&i16{X3`lCp-ox_FH*0zm8gz z-45q#4<+Td6F(gedzI?kPP4!w(E~l&oj_3ri6nTcagOzvT|mERU{mcD{h)Z=4geK|fL#M=pSWPknPd_nDNp*DkZWfHd ze^4FL>bBk+J$F|p%WFy>&w=^B*Gpd8`FQCvo(hqclRZ9>R`)@m!2GV z-3w|sKgWKsC#snixCyNF)N!g==BRr6V{_1YYC`f$756RHLo=V;{-K8qWBfuwa;A=~ zaKCE|5el#IiNT2NbFw+zxeID*ADZLb3&)io0d`kEzv@XQ@U%UL?YsjgOKdm?W?#|} z3Sd1Mx1RiNj4bQ&_3gfZ714&-QF*6hY-<|(?c*IJHo$hllsIG`d~v-Y+_o~!*w1A2 zl36NOJ$|ccuLt)2Zt`ml{D@WRViqCz^gBrxAc}#jYTN=|t<)UNc`Fo%?XLjiBLnFQ zw+5(Zt*_G9Kl=PK7Wq}^S52{lc*)gyO4OS4YUH-5az)ATODXsEs2D3HLj%<;my7hE0Lr zhO_-IZ<}j3xM)ePv5M8tr*Cz5?>l_4G%p$*mtE!h#|wp~EA+MZ$~d!yH~mLrymuyq zuCLA)<;DH`Jd#gXT^E#!PYiyRC`CG!>F|~v3=e%#jj^3%At=KQL9l$3*qmJF&AZPI zXjr-3ZrFZE!yETIbD?aahsj^!WGnetxg^NriEeQpHId|2Ti0u_(?*koR~ehWlib9QK{K}wfEd?QfE<9m z-9zOQ?FVdD1V6ACB?R8$T|fcHR!Ml%E=sBf#EP>)V9Vl_MZW#+CQU4@F^<$1keoBZ z_rILmL-G?%r(9ITK`Ie1$Up~rb0cn|o#Gw*hUT`xxE`6Ar+}Z=ZrH%1$;ji@@%ZOTvNzZx+t=b{nNoJN zV|V*hyHcqW|)UTot=CllYGQe z*k&6hVJ5TEV%jUfxRcnmJUFuDdPTTA>~ykHy~%Fuddefd_uF@Ct}jjc{MY;9#(nQ# zmY#HSK~CfH+d5R=uY&6P>qee(lWJghqmkr2kiXn!uF?KjW9_r-G(RanS=xa991?p- zfOWKOjmfX~jCT~+FY%QV5-^DOvW%lIkvOFV3R^aq6TwDbeDrA_R%0sW|8PUVRENBL zUZLpkx1vWqQTZ>zBuKZN-a z62N(ZUMJIJ%CTuN3^LVhFO3ruT|&og0GH$Lfjdg;wJo1q*SsI=4sQ98{L&FpICt=} zh|jF7#(cismOR!|=I(do`9 zPj-^kal7K0ZDkRpiw8}NQT;K1O*sn%3In^h`_XS8xNu#R>2l6<@#(EcRqYM1Xvn;sdH*!RQ@WP^72)og;s+DL!oVp~0k zEh3>jh`6FaKJZqx(437%JUPZb=q(nTd`M0-K?yqnwB|zwBa!GHPZi@hT>3uXkOC~& zue@qN8IO7+yBWZ*E`ySQ3Z9T|>BkCWv5g;OI`m=0F!050dfSvGO@8f*;ge2y0Z7E? zb%T|@2X9*e518Jn0Hh6!*=rUC7f{%AD_umiY(0u6T6L}$HaiD`l{QfiRm%6oC5V_L zd!cls(QzRP;hd+ORM_?C5aRUsQ+1kb3(1iv*Ze@Ot((|NnZ!Ph3whalEln1_gaDBK zK(^idx3HQR+0%Jtt=!XsQ7m){^T};S12^k6ndY-|kk7JNFwv9QFL-wO_dJ^KHF_ zun!-8h?oIGEFii%z{dYf5r$!~F(}VHccK!y91ji@xSw%o(H%S%m3$JseDFtBs&iQIHXEqmASOir=8{1>#w3Z&Zw`4_;7HQ6c%D*t@Yhu1dqp z2&zKm%I3tXB%uY8pAFRh>uG@|w*N47si?e;3Yo8GMML@}`|OJ=k^v_C4| z2RQ(5k=2h(M6)yDc`7=K&rz;^;_tIp9sVYXu%?pk_n=D9yK>sFII11u>8w;R1J2gZ z0BvWpHLRDIjGINm@+o3KvuO>UYeg}#A`nGB$iqYTLP~P}4ehyuwde-?L^K9`+9B;< zp0z$TK`u}YP#_o?beA97AR0t(eFY4KH}D~K9w3=k^{Ai>&|ww#I9%H?6IlaH?=Zkf zDEBE)z9ebpGA=$$OUE3h7Chl(RQqnWS~c@>-Zz95;`+@5Nfq(hDRWc`4-Ckyl|Fc` z$ojyO>Cj7(C=fact=GTWFXrwpZ-H$DT#)?-AF&SJetCcHd5~=XKScLnBfzA?H zpr37=_*ogHi;$18wuskw<733?&=3O}eHRr3N*EF6o$MfiakWRhvGr(+REa4v?dis# zE;)ud+iap2l^pS;$yz7Lj^HF^=XLfP;Z5TTkH20 zZvQ=6cF66oCoGEjE~k|LL03xxYvLGjXe~1w>KQ6buaU8|4vZY?-$S{?H7!e?Sgbnd z<)y06_uF3pyR$TSi^Pt+%}GK5Hi;#JY=ITX{Ea}#(_6^j$n1_}JpD3IX(VxQe4-We zU+VP3lX_JAKT-~TEfkRr{_PQwGQTNNkX5 zVnuNKv4;oF8VNDIdYcI{h@6}Y3%c0|tjO-5> zKU1bUetPMLkc2R5Qdxgp*SPBdy&x+@>z6kX>-4pnF670UNj!*%Jav+xad#xb$c2 z=r|4-_2A!e29OBO{73S@juSr?AGqPmf3QNh zXBRD*aSWLTG;9Hb&5IX;3=JsewIAqj87eFnv}xepDAco^xV~=z)f%~@lR$zr>vgJ( zrJyaTG-x^(;m^q!`rh#;>`K=usJet-BkA-Eb zm&Lo-I3=r5o~1!|fDe)v+%AqU(WCjjd870*lu3B7^^s6Kf$87HE_h&GGsa}8nXo~I z*4IHjVSSoDh@vf@G4{Y=JzfH)({EM~8^tyPT0tFtV-Z?l(vA0rW?wJA=jmi%!+X;u z*o1`F-V^uammw1F_&+I5k7Iz0E5P$J_@c)rDg@z*IY#fqtl`b%QjVWk0Ks+Oi{I1} z=r#x)gnMB==sg2pV>!u3=)4pw=2CJpS!+JA!Sb1v(b@)-^^Y_#z5qZTvGoLC!>*s* z)pJ14dx0{*yg;=CxNfM&1GfMPo*JvZK%P+ela&G?eeDpm7CHvK{!SN0wOw?L2rDbA zOPIBO*O3%2d%e`_3O|d?7tuJ8Xjk;OAZ`bACm~*k2OJAc&Xn3h{7;2fVH6i1gDSZ` z#)^PEWA!&v4h40zuU~K4oDWJZXE5+b_h4dR)5fw_`wi9i8_WWlznHl?YoMe3D4I4Z z0w@`&_@RpmIWCGw0ta0sj)SnSP0pmQUHM~+H`igBNB%isp#v{7F=~Y$Oh(VV*HahQ z$^t&Nu{Dv!albfltujIL*TqbNtCcZv7$e8R3LcU-sisYj2yX z^vP7t^edgy&ztd*w3J_P*8#YHgz1XrT^^1_02BA!uPVHwLT@^GR!7(`rgAFntH@BHeqfDno)4^O707T1F;ce+wtZTFr zRQwl)$ZiDW(xg&W?WRY|2BWTkU^Kh*I@Fa?ip_$5C&)z>4HH1VEy*Lom*;D0LmSdS z+Kmfn=dh7H<&ykm2m?&(j-S(nbsGkesq=8&Fy_!%b$Qg%uLXM2K8})4ut*ReEQ}zZu8BWn1_tGr^CvH z+|leC5x#!_H9up@n%Z-(h#RSjm^Vw}qaTCUx$QGE$G@7;;svcon%B}f0#`g0&=}8A zl<&qy%krYUdxrRxj`OH^(NX448W(u8-GgKsd>U`!J;DBSPn2}Z5BRcdel!_0*ogxx zV84@_VuR3q1+8E}bQNL2J8tRseU;%`VoARJAfZK9%oVQc*eA|U1Ao)aj(R_o=o2h@ zF(U4cqo<7_yuZF~!{#L3@Ssf7;b1VsBlwsynR6 zUp_Q*pr#rMFTYut`lMZ0Sa0ad%(rmgS!r3{8n~Ezqitqp>qz?C;>nmn3YUB4)Cg!Z z058a#@a=1QAbzFW7WkB$x)r+#(XxBMJ-z%hyv%V5^(n=fh=gvY3XCMp){&T>&^*cc zjDKF#LAFR%7t%{Kz?*+e^5VicPt5snD+uorQ?PM8CSCvo z`+ulXc0$Xa2AcADaKM5j-*?1FWjzB0aO+k&Tz$aRbCg@NofxeFelJ6lll~#B6#cg_ zuIurbDB#FLU!HCN-luBf@7LIq$-Fm@q0?a<>!{2**LQf=VapclpVx#_X_b~=-W4fy zumm!Le{$9WMXc`wS*RT9t{Mci4WXiNy8LKaMwA$<5Y_2xd_rX^WW5_#N}Ux2dBYR8 z7X~YCVb7H_pL#^y+X_B=b%g=@HUN5vRd5O=^A@sd>e9{4CQRHUF4i%{9(qNg4&5!7 z=OL03xm0ydns1 zh5hLPKGn`6?~s;%g>@O2iEn;aoAbRxjl^TBEp*k!+1eveC`E|b@Gw_gSNMhs>25gpa=-iC`#Zn$`^FyMIA@IY z$1_~`tmnR;dC$1!HRmKiHnyEAZEsRtpOhnQNPe0saDsix6@*x#r7XJje)^$EtP|Tf z2%Zv&tY@o->QORuR`nHgK_wO@LO*x2f$}UY95tT$Ly85BR}>LtJ1t`WSwYtB{#$A7 zq71?2fsbI<`dTpetK~anB4@K-+dg}?U$mIvD)hne}Iq#l*!7Gd>s8AKn-zy;?@lZWu^XD#;-d1W*E1BPRh zWGCdjSK+4hzA0jI`t+4p&!S4yl=bxRiiVmthIUvtG6vehh=v!WdhxB`vIVW+HV0~h zkgm3CTRan2+#%JAHJ_j|o+XI=aiH+$_!$GtmhixfP~#-$WB&2InO#=J-qmUN$cAyg ztXv|0f>8-+ipr<}Q8l$%U>=BOK=IS&eVH4bJ-6vSg{V#JyJymQ84BG|8OE=^+R$i? zmpB7(ejd^yGMG@JMIU5kE7E1G8d`H9DD zJRq>w7c?hEp*tu|ng39Z2k#?aZ=6d&^t5s$N$Jy6H#)9Wf_mQ(P6&zUFY)5A1jyFb zR>tZsKAJz}J*!dgj^V?t)3w~UKYj;tJ$Taf^}zszkjZaGWCS>z94`1s=hZ^mOo~i3 zyXR()=i9Fn!`9>(1rZA~-U!?x_+4l{;uvehKCGI(ki1dZWyOA9WQh1q<3^#;N4le` z>^Ope#pX?iQbIzx@e+2y$le@#21zs5Z;~V-3Ou$m$HA;c&lWjqQC6khIQQnTj&Ra) z_o#%|KXP)E3tV+>XH^TyEjZVi6gfDnyy(sKUh;lrzQ63Ci+tp{Q<`f0du^j(WO%6H zcD%Vn`f7Bs=2f50bbXX_jWqeB%6%2Blg`MSed65QJp2R=b>Sp7m+?>0^wbLHd$ZG) zXDu<2b5Np#>dcTaHW$p$jOw0n2^VJ<(JLwZvLb~Ma`4iaN~WWvkl^XUi1F z+GE#ybiuJO>5=nr0r4_;s@a~ak@b9c2Ia7-lu(*@Me-&F!C4*+zFX!Sn#&eL!4uj- z%qa~@he&dM6oLlTgg1?FtVUm#hB)KirJ~i@vf~f&CWGdh{n&E#?8&G)brdn zx1;sJ4dnyy>iEQN);c&o;ZrKp{&{zDHCiKe1>U{}-qD1gkoLKek&tO?tKE%FOhgJx zET?XGut(lJq(>RxXZQKtiwy}RA8c*ia5SvX*1`SZe14{DF72~&0vEt;#DR}t@Mi>+h5Zj&YND)&y}v?-E)F2VH9X?gQKGivn2S?p6=$Va}S2{X^0XupzmEB{;M@R!(6 z)@Q;R_t{SC+&iF&H*-2mHD^1M)&fRHo2k1(-ch`^qHR7K5^!+YPnC0*i)w24?cRu@ zI-ZxJmiqsWZ|Xo4rgIhXI0?i>Hi@Jbi)ECuAAEv~qLHeufgS;$9v#$Ujly+ZC3b=z z;7>WhveMPTh4VqDiD|u8HMTUJOGaD(xpE}2AV951*8z|?RSr>nqxhgg4$FvbdKx}( zL3{*ldXL1@iBWyUq!HCEKX=iFk`LxF7r5iQFl;npHgvqvr z1b#-DYBeuO53vBeB+?Hk>r`Qp+mlD7Ymbq}- zwKLj?a9}%={dl1L6vcIyh>*ml%Hue-A*Jq8*2%u8n&q1?>N{e%lJ*6LvWK{S55RWe z;{Y{@6v2*!nu83d^PBGaWtKruozo__l)ege-7T{`IaCDHoDHt9L>=F}eM5MgaL;=K~2FgRl zv+tH;d62KaM@F(=L%+yiKcrTqxwV;Td+rvW7B_L}L|?GMs_WD#s(&Jr0Y;ATR@AxK zKN)YDJh|-3DrX~5QS)p~uPJh}w8j)HooR1q#n6zht%;epzv{9n!06IQlKtU$;8?MB zy=h=6?03<#zVmx%^xUU=7g-QHb$)*K5|T?d-{@X2|Erl#8JcRKC@+C7GEI}Ws82c% zEJaUUL=z>>1HYd%;LI{u7_s0ed%(9mC!8$QtGtfeg^w*SKEbx0knf3tI~!pX)K~mE zoWwI7kPOZE_GXUfhydd5v&qn=H+DPhyTR~M>{0u|^||c?9{0QH3TJdA3nJO`M>{v% z?A!xkHSx81C$}OZ1$8>mDDx5zj5*?&G2Xm#BJJ9S=fZA?Bg^j5GTJG&%! zOone;Z8G=syIOR=*6Mm=Ve@=ujh_>IV{!zW&ordwqx9*BAs> zVN>-Y*OCq_LDUeabzD(hG_l*kOidm!qzu%J>Xjci`dntX_kJ2xZbindCT)L4`Rxmk zRtBSYOSr&c`1A3tM`c^$)irmtySj@1`im*!)?e9h zyP8LzFY@;@g(qIvkkJ7#N(+mjok6M;spT#p82f&z>4b~dYqvL*1%SLCUWGXIwq`L zY$rnr`-6Pxjz-dZh2WgVVpsSi%!gb33wddKH~3lKaR?w9(C0=0<@|V!W$v8=dDL~z zr+p{R7NmpI4Yv(_1~P_i2^2QsVne86H!9_U&AK=b;QsMx#MP$|B~>?ERq$}hs8B}F zoJzObIpB3gC1unyCwtxeKJ`STP4D@)JPEZx=-Lb7>@-tdv)SP&^rHnFt&sXr_1iN8#J6ti3g}agdmKQ8Gozc?` zwpgO&qEZN4lPC@j^@GC+frus4#EaeBEl!9bqMxymKm)`!vbgu^Z>q-6WcD=Jy zJ;I4SH(MQEo}UYgCI$xSwTt=!C3G@IILd7BI1qd$eKx|smraG*`%RUFse~&;H)*)L zaQN$5`SEHL-0;>|>bR1Kt%l=5v@X@1tfUswl>{(^oj4GcMXLuaAAEfuwCQb&y*>V{ z4Hq5{VSKaVK>F4LqFC2zH zmHo1oDNgt_Hgd4}@m8R=0>k18Ww@XrQ&01^&Qr76)+!B*xZWqz(@4bO=X#e{`pMq26L|X z=hAG#+gc7ico`+W>(-k!wZoVP@ZE|)rImuw889>V=hNvg<|43VqdCQ*uR1;~peQTp zY<_R7sUY`DL%is%2)>s=2n^SK7agJEE}9F zA>#YH#V(8&Z19L;Vhr$+<-F%Z5}Fz2yL4mb_uKUe<4d$Fv*~Iwn#XdX+pq4uTfS~a zifI2r+maPac#0RD*n!J*n6yDt*h3rAq>)xr+gxqnbvE2n6$ ztVMC)=X=Z=5dll;2?c#t@<#L?4#Y&^UE_-Q4Rf4mo8BdhQZE*~ ziY$;dul9wVe5QgAE$8pj9v5u>9($gXTcC4NGoI~s_X5OBqK7xct+*Xn8f7=F{_ro- z((2y#(GHnPGU6zE!H%ow=L4Xk#L&TYwr@Zoc)X0qI3hW_aJ$BGR;f8Dq9e9A-Vm)W z;n+7VG2=Apm9ZzMsO;+pSvG_4T~~*TDl1g@Hx|+m+GUjUC!_G!~G%7E-K34%ZHefZ&GkI!N5j_JI35tEC5xd|ef{@X6fok3nYhBC>; zHfE}F05Le^K7a4&9s(8WKsk)tfcxN1Nht^R+vF9l5l}Y=p+F29r4i5mawHz0K4XNV zyZME|Kk>OygcZTeXp4wU_80%FA~ISc+~p#~LA(YG;5k1e`jBcODUwYNY#ZyCb^=HR85KEZOoY9Hsttl z!AQquVvco4xLm}MZ*=hhz7)iwY6N)f$UqnVn`-#W(cySp{7q3OGlmSlBbY|QMnn7i zATNZu<}gur7kK^%`lvQ}Q5F>F823LKtjvphNk3j(T)>hWksy_bBPS=vj>Dk)7TC&P z4+SCkcCT6uaU$Zu76c8YKLzpv58iv;1Mv?*e?9*Lcv)$E3CIF)MTzt z&*M5Q@UtL+--z|T^YdS7Ym;uAjpn|6WogNv z(cr<&&cmZ>i3cPdleJARTldx;3sD3}Iw2!Wxg-D`sItDZ_)3#m1_(2eEEVLE}jrY|lQ1 zvDXemYwzsjmisR`SOSS^Z zRxQw6?N1R*%kq9^_mG>LyVPkzkpnagcns36qhn*Qq@)mYRSTXFi~0x=b6b9WD52>t z*{OAdiH4@pQ=d8Ut^4@RawPBszF?7wiyguaN_~8@A=tqouwMKWd`*~4Qo%w51}cYY zM0iR{DaxqEJ=xK%`;eD-w-8?9L4!JhiT~qDG7K(yD7}B0+zc$ekVQ zBQOm%8f0c8K{d6L1^JgRUphf&$e^mKbNXdFcO%eza>@Uq2XR5b<+r_2NpiD1QCLvW zlJ%MuK+$ZCffMMm)WU+3g9uJ3BOJqLL^zy9OmML3(U2a(!Qn)pfa{}gVf^6r$)a+l zPvn)~?Psw|Tn*MLAv?z(c#3~?kQwB$p4boIu$ksM>f>GLY(kvErkcFmUS5`HX>F~k zuO}xbpOvClN?mPR0Pt2c1|drXAPL~Asj1nT+3V`g2ei&i_Up2;vMMquDk{O;w zM$v(vojg~e`4^o!R|i1|39oH$P{Yn*b))xnl+#9kBuMQ!6kTe<%p7qb)Jvzj7z2^P z??KywtZy(Cc-r@p50+W&B;X{0HeMA6Do!ZJND;g(D)^qQ?JnATAF-m!^7Ss?h=b}a zXQ9}I#frgd3fEg#8Y}ab1*DU8$>9Pm-cnGQPb|-RO@+8@r>u+vn$_~SAFpH5UzE;O z^4iWW(vb?fGR3(rfyoq9fK0aHdRRJ&)e&A+c5tUw>%7%cVYbYK>nBHXLC190=yO}! z!am6-e`AtML%?#g!0*E(j8x{fHJojHu-IH0K$ZE3>Mj=J@p93ZapKQ#aMCc<^e6+7 z1gwUJ7F@q^+(ZFd4i9E>q=}XgQJ-hdiRP~!L z-9dw68dIPx`C;Zp18sCD&F3#`AK%56`erLGYCQ^sg7SF$1a7NwltVQ=y|l6fe1pS@ zrY2wK-RT%Ei{Xz_GBObRfL&74Eo#Ly5d~)#mmYkGhVEkUua_@hF19U1K9z|AQzGn- zf%My)9^9C*wdoDD1ggRw@V~`k8J;~G%(1gR@=|V^>=BRtFtyJ>A?u@?I?a0gfh?SY z-~5<{GgI;P>vYZC+N+uZZQ)_lUX5g9Q`<|$!Rq2~zD)lC82jiy1Y;#-d~Wr3?Vwz` zwTsvNYkjy5%fkzm3Zzc76-c*Yz5`&ZkN5?OF+spTjCOF-TsC~$fe6%fJ!O;B)EI5- z>R{f}0&BwJ@@xb$N>%fSu#?kQnxZ>br!)=^ld{mHw*}AK))}^=bLclcu-J%o zhd8t^j2CD*JtsLjKJEfEgI8esN>>b{TJ>Dt^z`&9_)hyyukv`JrRBp6T5s?{zg{e~ zDuZ2pUOx~T^(kp1pitr_hADp&2_F5GSWNpu`PVw`hM8#;qH$jL*XjqlM#}oi86inB zs;cWNPx4~>?2g%(+wC0>l5tml^w&Q{-SZ_U7m34NVct#T%dV?BmmMio*}jd*`gr9~ zBC~sn`A~0HG`6@S$M2Phm8ivuSXF1>T%WpDI9AI3#Nar~%Noxg{fAGNuo4qBKY3;@ zyJ=|5G(2)!O6Dgn5H;N-^Z_n;mK^WGcBu7E+K=q{0`KKXDnVS_kd3P7qC}P(m)m9^ zf0-;jsN-v10fv_96H@HGg*>vx>$F&pitYNKFla-AE7>i)!>*VojxtO!;Zw;LKZ3mi z)IYD_=2sK!6;L;|O>&l3vXuO+mz-|n_QKr7c{dy+T+Tlt5HWuGK?nMq_IZF^gv;!n z9wQ^;o<3LO?j63`&FRSrjp*$OZk*f1-X z2spyCU!ULKF5G)NE^0{|?abBym!vxH4f`}mI(*@4mc@xc`!8Uq-_74(s93{)1w;Rj z0BGXik57#$d@Uw=>N#b0P^wpQJ`3Ib6qJ7eP_K)B0HB*x1s_U1XG}*<^Wp@;A0{TQ ziaL)zbwJ>stTNgN*;sj^6feSPI(*;P$h=AM7XZ3Lid1Uee&z3t5~jaZB=UTq^lt3; zTziGmSsByZ0`K1RLf4Otw+=S2{l$arFYTLR+`l8@1T+}B)7i{(a_UaZ*E=jqGh(U9 zF)r(2f-SWUw)F%5MdP*FG@w6rT$-*Ae~?1*rK=XbY*-&gYQuH~vclMjnMWX$rGkWatp zrZmJh`#`R85YNsJh1{;HZKjs(;1W1^zV)Ra6t6d2VaaM<$vmr)Bt}B~ngBdFlQ0%9 zkbwIK`lU<*PcW+P>PRez7#34xZel@V{92s>4bm(ITj)ID{B51%n(QzX0@3IVWq%LC z2)i0TfH04^V3fh|QLtRA88N5)945``>g>HQeBR~xXYhv;rICG5nf}>Xz1mR9h7XjG z!n(|^Z)Qqqo9%SpZP|I)2N>t(r^fXsx7AoHSbx;3>%G+qxE)H6lKDhpt5NlHYb@)S zpr)qCs`%X8b}`wPm7eBH+L<1U!Ry-^?_ zE@m+!JNsUj|2D_Pef)AD8h7=IS(wfBUN%J2;Yt#~LaN{pnLTfPgAP#`?}o>#Po-av>?R0uKahT*KX<5^x&N5u5 z#sxp&pTzuIlD{DSeEVZEoz|L=jgiqjg&IL-D&5hdJkbXn27RoZyBIhdBw~sAW!3>~ zolh5el-oq6AAFf$FO?AkIzBgx9r%Bju;sl9LLz4F-zQ$x$Nn3u-NG-R*iCPzCw@I&M)Nf2K15wT_7tTQ^=qHfm<`3vOH3Mb+$EfcJz{ZXHeX$vAvr|$?yBrBv z;LpI?V^6%uhNi(Xl@4(fJH|GZc9$bJ9g9VEGlD#j^83zDl9s=JQ?zh6ltZ=NwWXTg zNy_NOL!A|dgN#tNk(5ZcMry2zRzLOd(x7*Q{}*Ial*QKi`fp$pJgTtVqI3E!KhNmM5x}Z>zDPfTfFT`PIU3O?4o^=FF|{a3W&CVfasRO+JkO zTe#-J-F+~LWTn&l#|lfz+S>W!{Ud@kkrlVcC>GBv22urV=ZYg;2;@|#a3DzhzBYic zF5q@tr!}r!Xd_fA68A(>duEUv@!|z=`WL9-J%Q8z^D77j7}`U-z_k?p;76VYSw>u2 zjV;M-k)b-s=$m|C$x^)*Zm)ljF&f(0DaHFHL_|P%dlT}qRZQBr52@^XMPPVHNpHW;&$sHzIj`$%=d>9a zlk(Z48yk9$P~~co&-NxQOHJ1#CS;stiV_nA3|fxAE=F8<8>EkSgiCSZ2SVor`A#z| zD8BS0nKea35)v?J#nI$4gBZdKAOUd$Lw+{Ejfw$quwC}kUofvW3RhjS4qXIm!14Fg z@KsmtH2y=@vqHV*_bqi0$n`GoaFL#9mvHXKR1m5fgK27QAY1?zUOa+%I zfoo@H$6@sAVX4cuYANU|GhAh-M;*dX!;v2>0H8rakO*ba42VZYyntoaT)wFo)%E67 zZ!f73Vt>cBQtftLfxi{{*uEf}faw3h7aqW)d1B2Ua>2uu!jP^rd3I`mob;j+4M(bD z3A&oB32G7s@n5M=`xNBV_{fF#ozFoHOLL0dEe@+%u+ZmWMhWiYMc(2z$-2KUAMiH1 zC2#QQC6+5bT`-cfmaF;zoe?AY>i`G%m!#mjLsdqsWH3Okpe(4BXdGMb_S8g-=C zwDYHoL}d)F_qsKXpPaYHL(6UF65o4xMD-={;tC53!*GOOUkr#DQKxF0=o2_h(24mS zY1lb9s6EeimRxtxe|T5BY!hsa=HfayJJYzjx~>A`q7C?6=5`hhf2 zdSTBq8qxb3&h$&PAp7Zn)m38_q>tYQ5yZP9s3b*t9hO>dPqw@;kA`V z$G`~k_eZFbBsxb99zg5e<1paZj0YpDXDf=Ek7MG{v6Uspi)zkgAkaqq2~WqW5wep1`r-8~s+7C7!dENo0tM#4hqcW zqTWbDF`PwK7*2u@5!QKfniaAlvwex4ocm&bA$_bRzMS5)P0ny(YHuOL7;aZjp5f_vk=Tt1GDk@{ zs9vIBV)`PVDwM#-&mWnSlY_ln6c&bshKWgASXf9yPya*yFfORmT7EpXqNlTyGK7Gc z+Rx8#Hf#Z(QPtiE1qB5{b61M6Ap67nnfIcWmzNOz6SuwDgqza|J<{+`7=(_7_Q&ge zK}AKZ7GPKk{aNYJn3`TBFt|>JoVZyiSfri1@}}^mxw+3Ls(i^4Tcu1~JGE5^sSbH7 ze{QJyUJ9U3Jv*}HLOQ^JWzD~egAi3ugemZCN9IFEM_tPxOS$OpeR_X_#tPwSKi{9Y z;E?}jd~gTM_CJ8(XYhWzqn&=VpE;JQmwcMt^)=0a_B<=B_$jXgU4c$gy02#q5}HLKmth; zz&EfX@c{8%yf4z}ElNjH#)j)NWku(# z<^uRC91ej{>P!hq9A$ZMqVYLxi=P0XmuY6Pm>i4e?r5!xgsP7c*3*#XxBh4u) z`_gB#li=9W=c}4LQoOcb?R><-+yX$lPSC8oZ}+Q-1@1>|uRQd_xa`kFZ2C>~bs@xY zWo83WKDSp67UYwKhOTU+V5r5`Fzs-r4EEk&4fOslNs@@1yuZT0-A|)mkM5{ca(8mc zRUXy!ISn{}GFaq7oomR2zdw{?Q{$fF)zChHA+I!G=h2CIh=7MnNe!;4KS*%?eavto zIN<;fZuicl&R0W2d>fB=3QwXVGVh`X>*dJE$O_^@G`&(3P?h$A)}XP9rpfX?5SALr z^>|Ds?4p8#T^aXJ#8$CaerOdM8uAeOSvWfaf_sdh#ilAScGI!3couqfbwwi}keDnA zN&WJKJ9uVmdv{l1zR|m9m#FaV4=jV4k5*$pX)~3BMZVNyd$p$LWpto31JPiJ18z$9 zTF4)OTn?5lyEJkI56+L<DE~feH|TDK%sU=k*yU*zImooeN}mN@XfIq4%nRsF*<7FJu;cm1zz^b`02cEth5~Dw?hI}!+kxEx){K`7{7@up z%3c(>F`B`TwcatRp^wk62lL8*K5x^**Omizhi%gyM#X_iYzZ6q$$yVwb0WaLqCZN9 z13w{(mY;5lCc<#<+gO>+t%Uw|jqdJyR+jyx%kIuj^;fiKDl))N7%TZD52XAC<{T{? z`niB>(0u2DkxcXi8Mx8*uyY~g%SM6tF3y+A2|z;L%KoZK6* zatVdzYmjniPtQYd^wk$Zef9`;7d-iDaF+u#*j@1caTn}V1~MN$Z1`YB-?bZ)8i)p# zzN+h>z)OiAe1}zFW)BS`W5{g1d-Ue^b~MO{L_L4|9p~-aw`c*YI{2c_pcUD1u?ddD=jQ$L?rxu5 zKvpr3x(#7xjLhF%F5qfFHEjp ze)BDf^QS{vz{Pt1AEMKZ{~#VSQQ+M1!qH5oK00Uw2Uy$#GMAI_Bp0eSYg? zray%W@Om!UsUe;Nl7ot!iI&|*ap6q0lAzo=nhIbz)^J7IjKymqJ?ap|aA*JDH}4IN6=mOPrSwp1D*^z`~APp)pk6Mp9lHj81Y z2onhoqqR9XyhF8l9@ViM97tX;*E&cLEegUQ(2+NL<0rOO6#D85tI`I|o}uD?;z2C7 z?|hQp3gNjs3p10emhmwXg{fhm8aas3}tcdb@?yUcIdC7}mE)ai9HRJ4tKMj}K#H#cNFSXX8DlXkvq{^$3?euYz}Z9V4j_4TLafV0I_X%khm zzxk;Zo&;-mVMneUyJ^1l)5ed+zCK)&^kN`oeW5PU9G;C~o3<9P_S6Xa}{@J@~n8_*T z!aCnypifOr{g_<>e4LJea%_{(=%}b8s$EGi7v&>Ox zC%T2>eoR;kpKctTSF0^@Kg7>gd%Wrxm@#>&bL+u>$jebxa$c3MWl^I)&P9RpBNjW? z-cz0Od#UGwBI!~oE7Ryy)j~uTE!3`|Y2M00hu8N`h$#%3O8hhZa)Bb=&2GlJ*5~xi zMx^*#P~;qDnESJh!QWfZweh`3;o--vGDEuC1?w{z`$8$1&m=zF8LZbQxEkePT4*DJ zOjbC_e8{m>99m+tE;0rO4=m;4Wb=Kbr_^hm$XXUZQNmMpi`ypE|ir5JNg zKb3y2y0QsXvwF;Z^c3HR`BmsZM*XY#h)-OPKGxL<(l@EPK9aeqC@rN1*422v-aWaA zL7QCYeG{2xTw2-yTJ`zf+*4v=;;icG3*1As_oQ@q7#lac!`T=$z$fK*-63+Yw_kLm zuCG=*6D3T)*QEH~qxhg0i4CNqlQqfG8vY*~>b; zX}7|}vb@3V`n&5nmSXD@q9hT~gs%j@e%V*>k|tgY{P;Cq{IpJIR`Bbcj@0rd zPt`DqBIL|c=VkwNR%V{oGogsMJcR`r?6=!!Z3~df{1Q~O)Ipok>Rbm-2?9Mcn+~Ka zcN$&35&Jz>h?LS3&YW{Q64$-$>9T!X*CH)JnT0PWC|77*8d|c)5tI7Ph;aOmfmN2d zh=+NocZdgz&+mzv;DPx_ctj*6v+TMy_(p2`US#3|+Tw~}_ss>fpub!(s{*&~klRAc zNpdsR3K0+tKr7Kd2_Il0A`2=i(0A#dpLIe+uPY0Ny`?sD|R>4m=b~Ob)ec*bSeU0jR zml&UD)}ejF1+}3_8=ouGdsVL9U@|b@uj5@N8`7NJ;Z!ri53uB6$%gP?$X=S$!UR`;p7>E1%;G>_G-=%bQ;9^|K27ua%%(362I zz;WcBOMDV;zBIdjSNVqj18oK2t(e$63|$d~kEa0dr4aUB)NbNQ!Sxy9B!U9r>(65u zf z?5uDc@*m|FJ;MUUUkR-PSaIz&=2t-9{D|smJ`RHxMBAHEbh*gLgoLgjsI}U`bVc%b zR}%bT9B;ZW6*#euunjJ6^#8o56MA+ZW!m(C6U$-uklERZS((uPE(^i3Emq0i z>QNCQ>^dnEgO~c;F-3K$CcW-d{jc4hc!e{eFuhxHS`@)gVx@qoJ*xMexXp z-*7{3yU*tW>L5(#!^vp6%zK|5jWfmr*k2+*{Chfbn&<#Yi{UAt<##I^QNt+uR85LT zb+UQLN&R2f4|K#h#gl3ISBczTkw*z-$k=hyPPfHv;!0-FMyVV{0D!3eiG5R z<8y$fnCxAdczbzyq1Hj|7DQS=g$jqqiMb;{`IOr9mK*@DIA8CFVoG&6CZJ-_fQZh(6q|+4ZZ66mGHA2F?`R|hOUV9ttBJz+B z4W~fWMCUFUUn)>B-SsE&Pi+-pLhJ12i7ObFW}i!X#OuiTVT;OB%s38&L6ceM`={}Q z+`m|Xa;0^dW!t;4;>c4ihaCwmP^AI`dfY+0w2@f6FYBYVT znpx*Lfoqj(R%8i+v3#a>c)@ozpe1uwadAY?To0BZBY;@kmsxx2Jb^#TqJlue%F7$a zCny-5oJENFqG^JQHej$iDXfIu;W^zTRKpUr z+0PCKBB~pFLCka-M+d|9BObwO3QSh7Q2qz$m?6K?4+zWhy-ca?G+AFgUp5W3UVr%& zzOz5kU11Yky@ekiINK|0N25@Y<*@!cv+qQ#7TzG~-*Pd+kTc^H1Mm7986<_EIv?7u z&ApVQQ>5olu>$sgin{N7n?H%DMS!v-t^r``H7OayvnZd)h!iJ+7wqa$*n@QxumVO9 zF?QpN(t+z7Quxo#lUn8DHuBgGNeaE$so6i<7hrTDKpS$ZanP!;lpY=#=>l*=*Y){+ z`(sFEMn<*dqIs&g?FNhBmr%0xU$R@}*!a6Q4FGB7MP>xNPi+A-)%ebtN*k@Cy*WV+ z<4&BtgPN6&a3{l4(5Og+^y1f!@5S}uo3;V{TqqYifS`Q8{IQV6&%mTCPs^*`G+XrI z7i69McXP9~x;0-1l`n934X!7x3=ZRN>p~@OsY3I2?;B#g`X;B^nQd-GQItx~7aH9& z_YBqSKK^hEPwK$hciWkRs4ufZZEBx=e`SsZUk}JaaaHMl20;6%h(EwiRS_q4f_bKX zVypsY)xx>28tJJa3@2r#sudSK4>d{*k>U)~tE=NrwnhR#y`94rN!!$A&sFIelM*X# z1Zbk61m^rnx3sjh5kL|YpPF~wj;dk4L zTr#3xAZ)_TQqhOE_f$%Ihlv@woP}W)Iu)kRiIMkXX$bAw#o3B*_yjvk%ToqgK3eyp z-#NgpjDRJ9ySxH}gIstpl;5>8tgp)2Wz%o3@%A3y&EhYmo+U5Oydd3kS7(RH8Y{B5$z{&Ul>@xJv=ce2)e0w6pFGWch|tgUBO4>L@* zjW+K2`gVEdh_8XcFY_yzI$koOqd~`jJ`~1vAsk2=;`%+PTSuQj?6SF_Ire+#rp|V^ z{*7tBmPZX>(qLN<0j371rj%UJG0?d!Ckm3ROiZG=O^2)EG{_BJwbrTRPK+ghR26Dj@I!zvf7X?exnXNpVQzk^ z$adaqVWj!_wydi{l{v+Y>$Y7LQ$gWXp9H90B?D)@9s}(m(4atJ{rTjg1=8L%QhhQe z?xL*f3NZVIjch(t-#nki!!M<4zl90X6|@x&M7|WT0QM*w6AdqI)7z5yg-ZD?9{d4=>8w8Yzap`(GGfMuyy19}HLFy&tZAEDzoUYp z=^QKw)IIzQw5p<71F#|SKT6&1hV|sP?u@?v1pNJ~pD&Hb!DBW8w;$s$Zr=*;%&$oX zakAvgefCTt4%Xk8(qBIVSjds>3;50*`_fT8{OSU6%${~#QMATjsO#))Hvt4ctn>rP z!$Y-Z1k_`IY8itB<-ZZ)ckG&|@pT#mkhm)<5^hvXoBQ=5*)k&0VQDXk=FfS5#~cij z-$DE%x3}^)4Vgy zmxp_av_P@;-No+9lR!e@>RpjBkMK83=XCCj#rAC821?sIM{NryC(f`$;}P)AyB0Xr zDRJRJwc%FSQAO_~08<7@5+TBH4;ok{gM|Gi04KlUz(hnUUY`aKlT98q`J0(UwpW9n z7oz$mvpcDjXGVNhpSh38P(vY6v=$7_zX$WL0y8t8Drx%@55r;(X7LkXrj!YQBM?Iy zbpU{sZ%p92ga!Q2yF{?fF<7F>C~zuNO-I5H(_MrL6w6Dsu{+FDl(uglqf(t{reEYS zG`(wA3WWZAY;l1GurC8;G1VtP&wI6J-X-Nfzwd@*@$f@PQu&(uMH_uOYSR zmDs1V1MTn_7L>L%t58p%=dx0yEq;^gZ;p`#YQO5up`ra>;@fkM+AIR|5n*B-ET-1a zb)x3+hUsh&2h#rHGZt95ER6aeg-l=zxcT;Aa}23~mB`@&kMs|Ck@A27c3u4h6uc}C zs^Duo1H2VR^kG#(Kqv!?HkJT4kY_W*fjvI0FN%_MDCrIWOC#99|KmXZiP{PhWh#g- zVC+3HZrD0P`C8?0lvQA0Blpn($-khfJK)KxA*q2H0{n*p+Tb3~qQQo)=@6ao&lPU1 zEa42os*GCci^!FAm6nK6y;8x~`B>nG|Ng)p6&Z-K{@@Y^IG*56S_n$yKh#Lb7H6_w zKbblfEa?WpMbBG`C(7WvT9HCuO}6O zC3cVq!Q1%jNqsLuxB)nDfaYg-g@ykzrV^}kda#B4?+3%dfsv~sUq4rp1W-Dkvx@up zV(G5z6``mo$3#)|8G}<3e(~+|%s~Iy(CQ*0g{fSf{twCc4Ed zhfh&#QjJYVpEEGL%hOR4t%}K$nf}5b5)In&FQ82m65vIwiQZ4ra2ST`j7Q5i+|;{i zf;zJW0lvzYX-|ZBb8F<1)Rqg=Qpu9M9X7@>qZfF0r#I&2_Frw?dDm;X)%kD_8Mdd* zoby^t@2F_-LnuT&l)bx@IFnL@UFwHIHU^x7LxMDQ{5|+>X51PHOU+FlSClAg*9C_J zzqGT9BmbH^HJf(NCuDvx8SsIfh%>G7?Dj6Z{%*3=Ob=G&87wF=?eCifq)t{A>lVn; z*AKvg#!!E;hpBrHu!D4zl@PX!%V8M_J&L>amuunyc*;=-DBPbrO?-EdAbdhN2{l7-jc27JM-8h z9hI|}=PxG2;W7sXbn4fmXpAzkK?#qT_TfadVjBZG>N|Wt6KCp@`^V}kzYNIR>A|6F z52q3WvK)ctha=Fv1JDXwRd>DMoKL^&tD?@4C2rQd1NA9kCGU@vO%BgN6u@1tU4TIR zdtbtbU%+v;{2kmGi5lzHg?rsY0}0EU&|aIJTQHJOlO>+JucJA4O_E`jT=nh!KFU!Q zu1xg~28PSoE-#Hm*S;2O@fnQFYHn_h*P%D?aBOh&1_zVCsNtVnfT6h=o}@xh)a-6N zI7)M$o=F~r`+H+biF<~-3N5+#&2>$wP%}$34W znoP-{O|MOn4oGb`;!|W`U6tX1q!u9LspRQKyr=iXoh#`cPV;&8hrl{WR{DrO>aNme z`Kw^>K+pC~P4xINVG;i-1>04o*{Nrhou%9UB3Hg&$<}f7D+>c_od0hvKXaU~NQz*4 zT4=?k%c&@UB`?g-e`O1Lc)tZ|5wiGxSQN%q?|BT7n`s*6UR__eEIy|XCEj!pSP#6- zzz0Y-86UOI8&4Umo$*6}kJp(%ZpiLthHDB&DCQ=x1>bwbd5;hj(URc;0Ot+-;~?nX z-d+|cnv3cW@&WlgKfptYUR_-+b_MkzS)Y)Hfudx@6g~k|No8t~3MPalsFYu8gA_74 zZ8>a1kp6`FuiuVNnokTr$ICK!HYZbjJkd5PB)D$)yKwm20^R=);WmH1)XZ+9uu&ts zeQ|gY#LfvX?O5oVU&SdY3hC zt`N$b=q>7Pjm=tH=ZZO}(=$EW=w6}9%DRzWiKQ5hB}GqexbLla6DsVQGylD!hpb5F z6_;nq@y{2pUk}NoJ!g=cCFszt6s(a6FumQHRlS`rMS2xFiAATJ1 z@}|8I$D$+?B8{l6t^M-F3uG(g!zya^YF1bV>&=p+8PM`;R5%hkeiwN{hj?AMAoXk@ z@f7?kKIPxQ)93G>LbQJO2ad?}ShC_km`SE?JXd@BZnI||p6yOvE?-vv!hq;NiWe3i zZS958`KJndXAmaE*S1f#2^Bee{_my#u{lBi4IB0)Ltv@@>NJ-PTYgTC`Yt%H$_mT{ z%To(sc8xaM(>xt*+?F%4I%^zp69nJ2DL- z?B|M7y)hB-5p*!l^EQA~{M2|WxNkgs3$>aUV#VP$HAjIjg*jNUTkW;h()|30t<@X>MRkr-jq`4JXpGs|2ArI0H@j^o+O7Jv`=OeS zuZda_iV~WKyi|A2DNDBv*W;Y|_YB7lwT&_|`>UZd*ePGzluqE_EMU3bSjsCkbg>RKhkN&` zSVZ@ZE2XXP^qy3RmZ%6+L`(L3M#!Pm;^m<-2`Ncv518w*Td04%KiO?L2s7qck08e& zjkrIbo}f1#-QiJ(orb9;bnm$_x!J1V6aT+xdk>(fx@}vyyU966$%u&L3`#N(m7E#` z8$^Pl1d$xN$w&@@A{jwZkR&-ZL4pLqKn6*YBsD>3plROfbKW`czwg~!|9$n>UuAvO zepdDFz4uyk%{j)HW7co#%)in-653@6*3jT29L@#NZ6Iw2(!qjmLN^BCj}dDq{mCUl z+I0aWO=9yNfJ>hL1Y)H%nT*nPCbX)2@QR@#N&f#Spxtqw+k1DM)PeA=_kE0aIZvUA z{`vF#cKWsdhJcm~_5TD@c+@4<_a0nJS+{>Odd>Gt!2jq_TmtPr(Ky`fJSV*T98JJj z{Wn(3O|SDfjAd-;<*N8p-o0~R4_3jPS(a|()B+=A?GH4qhiaws-GPdCc=~HXO1~|9 zEHW(WX%mS+%Z}U;w=%EOW>R)o72#SaiBuE9T z=~pr;eMS?s827XBB@=W8>!YWaF2k?`3=rFd?q5qY49te-XKrpKZN7^wH1$eij|< zpRgiiz|>pUwIG&-*t{g=0A4Wzo3ysA%M5%2Z8^01#u_6QxKfb3|dOY{=|IW&3Nuc z@^IWpyb*2qt7qvnwndOH`gr+Fl_<|0QvgR;o5aK;?Nf58euQ}NpH*So{XdQ5V z_O+-aG?X_|fCiT!U!XVqMoBprhx;P`Khci3D}m-K!0QaZ*X^ZmylUT=L_@uSW+Mm! zHOvX>AoC*WBsjQ>*hs2`V!r%*x?K8)MKO&szUlSJZw4Qmw<`uAj6?Ze`WS=DG9Nfs zQkF9}P{aBS!3GQJMi{=-I$PuSAT2DfG5)8D-ez6d>)+^=@z(dT^1s_A{R1Bh>$I=Y zms|mlo*-#phy(Wws_ZIeV&;PmCV>QIY0H)JJ=Ui$GCxvcqjp5E&_4hvA^QVxEj~U* z0??reGy9TYz?~%1_r?Fc&>uPd*9u5S$0tWxKMzyu{?U#D{64%jw<^qm!qwLoE&N|z z5!6CZI$M7rMv~mQQK&${>?4o2AdqoLuMFD)iFL*Qh1L!)fzjE1uR!ieLuL}QnyWW&XFM)jtTm^32*NbVB= zl8N2$zu;V22A|_tIte}m{v53A-Mrw#F%#82D;R&Y<-&Za^ntIsOw8E(nx>I{{F$+_ zsi~m2bqycTcnT7@^-|u-+oXiACZ(4q248JLfC`xHBbdNf=K&~y?RNM}aImA58=ty75tS-0&n5Nr{GiKK=9+xLcP@p>axR&zB35nU*IWGy zgf3%~dN*6O6QZo5i>MtA6WA?Z5dMk@K*Pfu6x!gy_Jh~LHW2n-T}jbF?EUp`H468m zXm(6r-r>BLB=^u}iRoG-G8J;Fj{%)j3!Lva~|9RT*M z%24#(?Yj>5174lAk5N@Amz3F@Zc@L8h&}S(D?>HVG~AT=L>ZHp$9ue#q<(8F)`t?1 z(*H9k-8tYaf;89>x(EJ&p0#uY?!dXm+J;?N@@_IWjUfoE%np4I7G1%parYqUHcsqHz4ywC9d~B=c?Q?0mI9D-O z-o|gS&paHnP~D=&@1E-9RqS}>01=P=%^I^aK53O9?hHN_PtC{ERB@mhPI|H{KUMUULaH3GIHjcIJbi9T7&Kxm>C8TDr-T zqTigC2B@!8pdQgxp}o2nha#Voy)tS?a>ilv{*IIqctSyh*G}g<2m*tVJYgr(I1dV3 zB18z-O|R#K_u)+L4g8-z8(aQL%wu>8PaWf_spf7|eJCzE=}H-luG&jArX0q-XS=h> zB5{X2QN%xwqHFl}Y=!M!?$k0--RGX_rq6tCzXG+bk7xNgIXQoW-h^9*6^q#&jD}H( z=7h{Ly`bk7*kdZfMzxFX48*4y^Sjfiwgh22k%uLaW#FKl^Zx=fEIw58ny}N!N={Fzx`yQSCrd#;`1eX0T66wvN z4~X`=Bu0_jz$Wm<#H$bADaa|5o1V#BI+Ov1K4YoB5axFHg3M3hB3gpVN?X=8+4=HPtorr!K*^jHiMD zSN~kxe{A}GJkN7_O{Hq)!`rSwDU?!6{2!jwg+z6RwyVyz5i}3XE(lXds9XDHMp4V+hc!nznZ2lW=TlXGg{TanS!F z?QzHQAu-7HpBEPw+u>AB3I#gqzd!D1e=6L*$ZH@vO(EOndd;@l_iuD9f0buz&)d|s zPZeK)X8bu?{j?bd9wkuOmVz_#O2CA@I>6RA2%ZSRAfKj@wA|2$T5e88BqnkxCKMAb z^(U0Re1>bWjgsP*$7@|W(q8*dz%_Ta{r>`78!@D1`6sxB+ZmbsKLNE*Qh6ZVeLOxR zkR1Eff7Km#T3<;MxBArse$<=l^RLcC6Du$crr}kSS6kM^*UrvA$5SJiADv!-&C{pF z#lPgIg4Z^EgqX9BkSgNcPU2CSE@;?~Wdo zLwLi~1=^wD98(9^iIiE1ZSH%0kA_GN)P z(DwY*0Asz70xK}h`AT?F%8*xWkHHyNC8LpV1LHrC0NU?VL-HW4KKtm9DjYie;ori) z=;7%z#ZHoow(FTpvp~(}!vjTzSk7$U8$oB4xz@5U26F&=t7xnfpH_UH(72DB8; zd6d1pkn0NnmX&rQ#(6gt{cbh=Z++>`@87Cj`C3QXbq^izK3I9V`{ec1)lC~Pxc)!7 zaIWC{^u35yiG!5+?Qu2dPbuR5(7E=~rn>&9>8LC$ykEPoD05T3wkFmYd9CfZ?xX88 z!Fr%(KDnv-^IRWM^B+TQ#WFUgqUO^>^q<8siL|$MeGY$iqT~m%gn&$ve6d35o5o!N zK@Awb_a(sqYmviv+%<#o*YJNv7(aY(bd4b*JAkTT&akZ0w(DsuMr`i|^5+N56r5 zA81L93Oz@jBZzNdb2}u%?P&;`)Qpj!J@UoZ{<>qv_5Z5s>Y&x5N;1Ipwmp>fY2VcD zuCo7_V)knEU!Cq^t)2gMqdR$hmYkDERv(f55b|D?bm4G&J9V9?^6A5j?Mz@?3Mz5d z>N?Qjf7V?8w=wnEuf6lNne*Xa{wPiFXZC(BVdOr>%nZyOH%yJI1SjrRDt^Al_(p5L zm(c;1adC|OuH2)?aK=D3(FxI*2`UR_%}PE2o#WN!fT1R<3DU>c(gwSluKmp#5Ibsh z{>mXXTEAuxHeYc?^oDnhIW!DC)g(izCJ}}v4S|jvEQ`>8rlQBCze|ONlwa%<84&u@ zA*&%JCPj{abR;i}qH|XsPV)cNv(K8_<;Uvw_^D0|YD?9}LxfeXI=){Pw@@$q_$y-A z3d|XpsC%-Oo2qs>|95Tyo#|WUWLObIgwGUe8-Z@DeIbC8mlaJ8!T0Q^lZcCxxY|nl zH%}eTYt(wI?TYdz8c4XGK3i<_F^saLecfhu_zGvWnI@X{o-peD2xCm#!nLBEhB-UNgz*ye3>}l`S#EiE~ zLSDD2kc9a`6FLyvba9T3j?y7_^eSONXD9NdCdHIQx0I0hmX@m3jn#sJf->Yez6>}# zJ;vjX^^U|{-8eXS;TMvu#c*czbj4)pH%a6*5^3C7@%ADQD`4e8E|Gp}1N+XQ@ZZ#p z^5;Qx=jM*5_@@sNTFPGJF6{1qDO*Od;{%5$KrhOxq@<+pPmD;m%rp{I1uZWXy}54b z<+%NmTttJ?!MG70*kVngZj7VnSzeU_AKg-mRbENDMy89GP+M zIb->;v>`xcs_lG+M=->Y?=3@klYjK~)Z(v?NBLf+&XS2LPd$9UcnY4>V_YZkCz4(- zwROs`s$Jm3XuiApmvfGGG5}lo!ID@k#lKR)3!Sl5?*6N?-*sURStsv4z5ZjawtC+E z^sW5VuLf3Ig9C^7Hv4pyM>>W(l{W)RTW5UqFQ=9;8G6X64e4RTx2JITgJ zpKEC_M}JiVPfC~|9)fwSzKzDWEPgkd)>V?%eew-zTN*juvKZ5pnSWVtE@*iUaNOyi zzggS1bMJYwW@M}<@v2tRUTf$jIU70_d?0+(d}=nj;q>RT`;3Jo!YJwJrAcMJ;3eG6PyFywWRnD(sVgxS7?y64;f#RDo+)WBrMC4*lhf$#eTYk+8~x=M^%<8zDG-)5`qL(C+0rLlU_P)Z3%@AUy3@ z%e)-S1jRgJ4Q}QtiN(|Mli%aY1D)^iNtJB z>=^WSMD?z1ZnvsLzabe%x|rksRC9s*;AfFfZ(^Cnb0s7cqWj+dxRkJ~;w3Q1FTLAn zt`!ian{vN9m780%mySnSfifgwv{7oicSd5O+P?M|?pdK{l3Mt%LGE#{=9j|<9SHcb z!Kr8bG|(!1XuWf%vRcCC_miBHgdNiJYE0PkOkE52^S2-GyUks;ef#*BEqeG@SgE*P z5z0UmM4_*H>k2qcE?!52s7J%KW&GGvGD|!5VW>*QawEgA`hH8^s>sxvL@7q^UQ+tX zm#YLpeD;OJBR(z_7}@7Nl~iZqsMlZjCB(Ck{C@0gWCDrIbOIdvZd%@vY>m=L8BH+NqeCBXD^}nLg(hf&FRo$xV$j`{Gs#uA1;~e z;{VbDZ23MOtM;q2SIlLQS(%@2S8$uTyzguJMz-+ls0AU4s3FNpKeEYdfWZhSr6AtD z)9BTc@GKB6=Zg^&BCK24e{4dd*(h{VVC^Fc+^8+o{6eD~=x}7=E=?a+%;gM6V}=N= zi$1_k@^EG70`wv*{&iLsRV5qWU(i1*#?K!r|9HX(_1PmGgFg%O+54?)QT;&IXYn%y zR0q}xYg;tCi4Hj<_N7ZzLoV0aKY4OSfwzXkrGS^A&)JE$y$!)w;B<*jCHh$9IfiYC zgp0JY-EYB{-NEze)03ZX-@JJP@qtzv8+>1_AV+??Y9}^xRV4%mA0gsn-GcNN+M+z; z&7ZoB-2WWI0K<^fkp2W7u?NnnL z4*I)Dwibl_fnFa52f`9`zDN&^4sv@&*=J)+{BWy&j?(Jhce%b4MYR)~B}zNG&gU6X zi#lag9G{waG6qK{!))7*6LX#i45X%>C+ritCV`JaPb`~c`EJJ#$WsLLTHAP#%@a8F z@4)`mo%x_VUT+=nCYs)WHxY(z@~Zu=qYGVT84Ar59hMDweQR}3(xow-N6AbOUmZpn7BA5v2PHX z?3^4c;6y-zOe>rwgQs#Ud1$yWjoIr6tP$fNMlMq|?;$qS=ya*YehTuqf7{^WPK!qIC)59O9y<{2)GBl4U-Uy^j& z7u!1If2Uw{Br!~@a=MR8`>b@bKTg-(BNS4IjDM&wT-osC%f5cD@Sd2K3d?la@LV{{ zc0g{o%TD3#*aTdwgv#)I69h^83=_m`_ z-y{{mK87HTjuZBcoIx+|T>Fscf~wfb6z7IY4J5fuWFCqu%P&e^v4_u8kaqTaW3dYn zzL{+3qI{=O+bV~fWdB~gEA3XoGROEdW$x*&O4zE8ibJr`xod8hQRX|Cio=ry*%gvu zIB&y9L$6m`Loodj8Dsz$Dv)=)w$qFaCPDA){Ay)7%=-D$4Em~5m1br}hg2tg6a%2g zh+y)H;$XZUnP!%>L)47I=QBUh4_9{kr34JV4LTi(8oFKAFLoj{TsA8pwW#+X=3$8q zx)m0X>|P{gskA+pIuV=FmGn{Fp1?36VmpyX^-4Pe;-X<$lW=Bo^;J&IG}*dZ{sQno zQC}bZpyDY)6`8%FN+<2Xe*{z9O-*vIiQD?yiWU^{?qf1s#c4mZM3K@(}1v+!2D`iNl=JYvpQWj?Gj^f$2CMuPNzSSe=w&W3qgS1wu(!6PFh!B>1H5R^RGp!9!srzpY=Z`e8IG zpM`6(wu^~X+c89y9L8dCn#6tx1foNaN{S@I0gxd#f*ltm%NaFj;VTO<(q-RAXcILN zP0w^8@{kUtCb3R#P4QC*_gDquoZ=2}h#}AC(ryL@An#e&N*FOm+`LkSQ7|Q#5$uoF zKDBxss!J(PEn?L~h3Et8GKU)%WI4!Bi`fWuKQI?+4@E$w*!HN~FH?YMxcmAg+ja3C zl6*>!heP|MxzKCHY2--LV=_oID!)x-DUSLK@zRA!s!3qjqZcwFqO8F1xO13Hpu_TX zLh=AbMOH)C7qGEp_z=6%HAkk?;~&`mbx4KiUL1z47nzHRmu*Ltvh!+OgNXM8t~*SR zusC#>Mh2)1FIZ(X3TVjpLrbE99}`uwx?O_6v-ab?!x9@V&-#(tkdA2O3E-9`Bjt&y z$y$1XcD0Gxk>a^S{@X+QO-W}3bHj3rXvIt%|L|SB2gMVeM?aI!FQC}0iC#IV(W)dZ zaO7J@pdaGopG6Ys+xU)9TrK2sfk-s!#oiSCb@4;lP46|{B}fcP zsO%Zzf}{7v&C@ z4XXHZ8)S=nJ=%G$IWTW*%#3;><(zSwAN&6Pu)3_Ms2^Ej(GFpik9^B7JqfWI!RbK5 z2|2sdLPe5g_g58iu5B_FJ))=tHEA`M6_!ZKQe&6D-~DM#g%chYxG-g8MECqdoK1k65b|1(}8*?zA`5{)y#%w4`=;-BGE z7)RDlhjoaE6wj9_d%zNkzVD$3kL~Ea#2EH@;Z7%KIom=PlF6I21DCPU>mSx}nKDIYh6 zrcD4E0Hw0?q`GYpUr#+eLXS@g_oH3mFx1}Jr6#{}Lcb!ZE(G~A1%hg&7NqGFk%pvL z9Q5vPCi`RBrRYe>dBu}xM`=7w2@QMBXW7C^SX*b4zx1%Fe-z1Ix!kHl8Tmz&c&Iu( zM<236N?kYMWDnVOk(myrAqed(plBQ1%_K)w-6QhvVQ2D>BGMn^;NzTU&*#eMf-AZZ zxvm7Ntcv15b|D{r4aR`4a~(IRysViTfkqX2sG=Nx6?XITur3rZ@F>`;r#l~0)sujA zd*q-p6Bb!sh+(sP)&XPxw2$y;J71C`$yb=KdzN)MjT_f})K#RL7GWxYLbHdj4OrS@ z<3e^@iC-n2$@B4PpxS^vsOkmPfEtfIqP9>~6_p787>aY!i&3tLz)*|Iq1W}IXJVdt z@-CfzIG6v@o8ek5s0w)(&+!75&cRbC5^=#C5DBN2_jDC<3AM?w-PNJ7nl zf7B(zbB)VdKx92V=yr5c_($v6rP?=XRNEB$a;pBg5tY3ek!*VN%b6^flP6nh)wj3) z6_4kDPZm|LV+usmK8LDds@ieDP&?D{z34wyrhrY9Icv}iKa_aMrBVQ6sq!aYa8xNV zJ_2$>DWpsc=k4Xi!u^aqKB$^Dv4A#jbxd1%KR0`B|m||G%_U1!<)pl z82K=L-m%_FHxgpvS1$|%aOuz9@g=(QX5=|n=?|`lKfHg4sV6$8hOk`9@`F{SJ4@$h ztz9AVV6?KrQXNr@kYgA%PL;rQYRTsu?-*Auve?37@*IXB1=6%u#uU;DW#Z31H>8BD za##!#`H`xS;vz>C#e!1kzwl_ky8hGdIkhEoegt}t+C`!hp(!7xDXH-+FjsTH!2xd_ zgyQQ&G)!Vwm)NB)m8CI(l*r+iwjZgS_J@AiF$~YJH3hP2d|@HgWjXG8oD>^|@idVf z+5Pmp8}DZ_Gv(TXD>!lU4=?5qp{&&oy@@PhuEj@w43`}?{V9+OoG`biMW-5Q3|TyN ze%#pwVPlU+Bo+f6+7ZzSUC~R7%WNXilYSF1$fbjB&>a{_77UI$)$bq7MeW;^5(Fd} z`cmG}2Y+QjRfsK!G^RK*IGL2m-A+2gBtt1A?qiY{dlD{`nH1|ifR?Skq~78PXls{K z1*^#j4iG-d+nOZ0P!kO@LUKzLoWyh0Lp}KwuW`x6Y)yXB=Euf)&X>rch3PWM$;Y1$XmjlMs60&bcj| zd_J#RK)38TDh7k5q_Tt441}X&Yxu*gH4yNCSZLetj=9+6Pj~HT)X#7@VnwA1--Xvu^*Ck`fz4>YiAYn5 z%G}5}65VlfV0!;_I=P+~`E%n3-M1|w8{YPF@qE#lYrtiga+`U6S`{sZtjfDd1?OM- zNjzWvz(|>zbDnw(tpkkpI=kdAYTV0iLRBmSzc`AJ3{X{zHE@MR${Xag|KS|#Q}Tx? z-cV8%XsSyd(>$3Ye)?PF0Vc0&i`qc<#ix?VFqW+&Dp?Ve*kWN7CrLcl(D(AZ`=HaG zwcHT5-4)DIep4mCJ)BMN!-I*mEJo$Nov2V1KG&A1bp!q<7Z|-qasXqqI$3DoU($y*UO(hfE@GcoVZMDduj^ z5q;H#OwG?eGd|`(00+uGsqjE@cnJTWYdGqq9!h+e5K-H*JdPv=RV-T;V5k39UxK%? z&L4u*WP=o@OEy8bqRfTMZrF2Q=|pg?Yb!r&|Dbc>Lnne*&TF1S%}rCis<1f>7lrm< zf}VGQJ($l?24_&AO=en#L@bQlqsA-bqP2{!UTh)7Mb$wTQYqX7?Fy*sDItxhzRD0% zyPaOyve;b?h-$lxScLSY5iB3z9fehj@AasB}I7>kYPKFosV`a zUj@?Aa*Izp_Xg>?zeBl3gE5rK!fD&e$%fnwqh2)V`(^Vu{@&&p_ha7~U&G@MVuE=7 zfq)||OgD|M5H>3`HH2^og?tnqiely?F|!1@(w`|~eZq+pLh_6hf1@At$A1#FEUyIa zbkb~WY|sxdshD2pZj^gNN)L@}(0ON)U}5RfJCzAOp4rG^Dn6O~wbsC+2y-)Hyc!a3 zQyFnnN}-)xgGt&Wg&fH+$17U_bimO*Ld{g=`o~rAA*OO z{F>(o{d$O@mWrOgE5#ccp;osimB~^Q1}Ot?@=ExY!H@^P^i*EFZZ;qheo7dH4v zUBlzZxFqR6=6w2ui{z=~B+YE;m9>-St6!r7%Om_akT-iL1hVe&KD5ogfR?wj+Jqiy z%8$*`56%g^3sRG>O19T^>tMuB*ZTXkpxLk6!sD>0K*uqee)VHEcs`YYs}zW z<`6K-Qwz4nSh_kmbkV1C;=Q5PyF6uY>=;OI+heyPN!+_*=Z(&5Dbr}Bi1{d8?_-nW z6B1Yw#k&|?0VGG+fj9_lTOG_4yp_;fWeahIdjdG9Bhs#znvX_Q0{h|f?n8L>vM{b2 zZa+zu4;%Ra_ODc(3JUGQn(V6}L6R%$7u78yrVO=A;qtrpd|SOO38IvWu}o1gi$qse zM;h8;dt1NC4o<6QGYzX_so>Ybo#6+u7WLo3WoGGb(YCp3&NcEzi!>;s5ck%OqMRXj zh;6!DtthTW;`**#3azUh zYW}*)1@M|LM1We2V*3%jPGag~5;>ZuF19rW&|5=McMI;1<+M4DJ&BSQq(!CcSJV&M z>rSsyB1PxjN%c59Fp7p2L}N{pP`w5LBbIxGxnIZX>*^%3GBY0z1_yP?SQ^vh7hht6kx%jS z35j9BVX~itj7tddFgC9tW+rBxam;{f(+(o*hzA?F}*R8oEg4k%Qdp z7)xZi&}#~j{0&Na+~{AHqTMuDk%j^Ii#g^*<9DE;;V{?jbNuN}S#aRO!D|cQhTIY` z`33|huA7*mwqS<2&6{E9-(ZfB<25|+H>`g6gFaf!J&hRWJ+Inv7FK9vFwS?;M%6A6 zBNFGovW(sL`Bw55X9j^D=uvYiCG*d72$^V@Y3L>sA!f-HVyKY|+aP2FyLDYcu+{S*W;Doj+A@Jv$!waN{%=iSS1>(QjbicqnHUu>+zUE;Izbtp`n z(`>`^OXHukR_!-mhLUN^IB2AgSopA6r>{-o8uL-axS`0g5(*POLlzCArf0be+Schd zFUG^wANf;^wQczSYL~@{udW?J)dm-cf`KPi*^Nj_YB#25BF85ulp!Mw@!!9GH4wZx z+}HkePuOtgUCY(=cX=WA0V?GP3@e@dP^24Q23|^j0#=bSz(v*jHQvycM1vL<;=R(y zG@KySnv~E!jK$e-Q_H`lp={5?DMsR8R^K%I*i6KQByh3C*|XgM7wspdX3w`4G`lUz zVq`bm_rsG3H)QJn-jk3*+yE(rUQDrrW}fPEaj6o+XeSoYtHOh4US}NK7u0B8GWW57 z-LMiH|5L{ekQ<8iEG$zuA=3UHCfqU4>%7a=>T}P&O-v}obv5p!v#Zw(ek3NVJAd$l zJ;=MWR}v)|gpU=8LH9A>frqgsxsp{GT$;b{!8tyr;@vgf9~eb7wOoHcKPg~rqydRF2`7sHsPTu~I;a_1bFp+s@|9I(Rlm-WXP!69IA2lm@+S^Qv;W2F8y?Bmv|BSuq% zhQAxRDqQ)K`LcNpLc=!awiXFxb!QIRAwx|yvx;QV>`KNj^`I+eE zvFmR|i{)sLUi@nx%60UYE&|q5oRAe{NYc|Jf%x##L_>5zQYZS#w--JCk)i$U2NCX2 z=Pok?21w-@M*g-O*T+MSm)XXObeR-@Cr@#6n*2B@SUv$L{S%-9r0(9mdp$hons4<& zS2PuC=u|fK<@qcH$?)s(`c!TzXN@DJeo@2ba4f8I0eZ_oBnJ6P9LK_Y={d~{z(bL5 zz5-LGLh#4VJ^&u)pAh6pOyItjFb=)1@C}>s{oF=atZDDnu7z7gW}-;^N{eeb0|q^E%tO>FL{n??boSOhd}Y>FCwrJXw_y*lz=UeMc}@ ziRpyJ_Lg0?3-4(jupI`?mKjDo)_nFVAg_NQYEec%BR%uK*s|zdK2#@rw^@l1KY{zm zJejx8X=(dygSA1My zJ$qIwmWMXvQI*R3yMOD*w3pU0=vbg5cA9~cMbud4eTX3X+I95TxZe)Ac_M=^at*$x zS_{#Ko%A=It{8t``TKq#$#YKoIdh*PNev_Z!_~lt*wRPWPD~6r@qfOzkc0m``UW30 z%V)318}xe3xJA5MJ=r-2_?@c18{?lq)3Gez$PT;c)TK7b2qYOW7|f=}FlDK*mzLirkik zc&#(Du?a&qlSJaqUo8K+{u~&Xtc1ZZ6p6L%UQc%4{dQd+W)?{^4YtZ#(AA^( zPxfY}R6SBFV`2^Z@+)Ur9Lvb7@E9(kb5q|XoDezfSzM?IYmeq1Yme8f*>3;D{N%+I z+e1gKlfX2d(3^rSEf;{NxoQ<$%K6c3^pS&J0w-J01MJ%K`p>n0rrutUD~XY%l`x;Z zzahWZ>TXpsa(X*u^>!Y)x>2#;bCZgCUKMor+dEbZc&Fd_+rLhIp7>}_k|vyOTfwd0 z_Rh4KA7Jp@qj&U&Wa^@FCx5T~-m}Quu=|&GqQ>QibU+8 zX!YX7Md$Al_z(-4Qs4OCgZv2Jn|XJ0Yg_U#fuu`b!d(N1Ccn0@z=W$u3R|iaZ@7w0 z*S5tK6w9>)%Lkm-{ji~wY{PjzX78R9lig&|2~DDOp(e2Lw<Ovup?=`PLfB|BWpYiL?N8{_u?2<H)Crwg*$aoE8=q!bYW@eO?9A(wKXm*D{3j zcHG~tK;!RMRaL?GI#w~_l%m(XnK}^OEJY^)C&=r$-Ysa0B?{t9!i(-+2w%!zuWpA^P3xGnXBc;$>2le(AYMmz%w|Mal$T9fZby-j4>~tXbO!yZ-d-6`ln=p zWmKCJ-`W3!pie;cq&R8Vaye(jE6tTz$#y)YO}@bD1))KGbLfd@DD=N6+MWdjB~-3Z ztn9NjqlGoOvW=AH;LH4j0edRmWK2$sr-8r?ZT1*}y0P!Bd= zR=$m7kzhQ$xVclvBKpSx*~Me}-b4th<)9uWB$3+O+zd%@>_Eg5onC@4YrJ^Y$z?wp zuMEZnTVVYFVI5C)#FQ_C%ZSCWjSW_kM@>`0A#rMpUSa6elgr;N4KQp?^97k@a*uvq z?(j~jaZm&ckAb4w&!&PydQZAp!ho8^Kj zt~sSmLS)#}6W|Q+^WmSt?!czM90wdVtzP@D9XER1ppK6RT9r8cc|%LBwyqQh2%~kY z;jNzMP89(Oh!1FMUhB0V-zwHKO&8LUrw+4;b==L}&$ph&{i5~VnGtK<_xOEv^+WlW z>iLQT_G;{x8zFl}QW@;Z4T0fH_NS$|lhf+ioTj5VbKe#)tFLzLdw;X3p5D_?7Ua(K zig~?#`NRC}iITR3%lV#IDh*{I>W6a8ld>B@6;BBw0JqPca_lH(3x~b3v7%Wu9U@~* zv6@@hZ-9A+W&k60^4?5oo^QTx1}~$@kx(W(A+k8D_MbEt6oO#y1fI3)tF8b^hbPpm zFAN>~C)`tyte!xu(eOdMAl|obH-HkAk`;~Ws4NRN&m;HpEaO}vy%R-?x>o5EZh-kj zp+k$zp{1qmRQah-j2tyj{5b(ozcAke9c!47tWs=$?G4PDJG)eMv2m?`F!rCT9r9pa z_bZ5T-Qltg-Vhu~aykIf(%3N+!VGp##Bw0-FeplV#O^#5#ZpfQDV4p-8sm{YoXUaD zf)ua!=Zy|RxdSn{ljYuK|IxaZv2E!h6OM^Z!Umg`_rUm5cKH($4FiUIydiJxS!TkV z_mj5t=hcy;`*Rm==KSJR+eO_73AXyyE)quS@jf;EFp(pR%}j@BhF0Q74 zcr@GP^=KI7CdY}i@jq5wGVCeyh$fb*F!WU0mx`?zECefsJ!rCUGEqKxf_ z#@?}m4{RGhTAn<1n9HDuO+;8U>bss-pW>(ap9I~lX|DGBTgP=E8$m1N2yDEPPr-+~+ub9~(Dw+dad? zN1isEKTvt`?iS_mW*BEQ8lV@ud4;IM1gu2DHw12*Lkkxsc7 zj-&y~7ZoX)h!m7!;-gQr>3Sy|6xgo^nXLRuL=7tnmFG>oL{x1@W8d-ae-CG!qeLjN zL#dXYosSKOj{9tM^WbYMzeYw%h3r%bcLl=?VDnIhumb-1X;9ITAZj6>?|UdU>~}c( z`Mm%f>eT{j11CG)Fe-8eg(X=ljO8ZTDchl75g24lg<*H&onIs!YXx|}8XLcO*swj) zlo>xYJx#TAJ++t)cV*xo=kSK>X3pXf(Mc$XWm6|ER`Rn<^!SEncVjFq?Xg_W6m-#szzE-@9{E61BEM15+laaRW;f_CW#bYfWW zTJ1OQV~5@r@lv{Q;vZcfF+YRr{4<(;L;-qmRp#wY=A4FiFOO!CKHTbjr7h%0?kg4{ zP3OPmi3{*ze>X=y?{rQwrH33pncV)WdfGkaB|a^m3azr;KltrJnq6ot&)H6S%jlLjI;U&4s9MC9@Y9u;OOxy-e4?b-|{Hbn3T9 zgr)|X?YVrPq)?tT2kqJ%#dryeu8`umN8ac=z!{FV&zINpLNbxMna9RfCVYx4;P55+ z8F>n2zytjN>m!|13|kxDvem~gVBx@BzBDzmof%&tLPE9dbE2LB_t&v{_c=q2Tbx(( z@AzOWjf2fX(Q9n&P!DeHMj{xD_%cjM;148Dj*c#AxLg@`K@nBCLiC_xVwY1lLhaAJ zqJM@i(GMtsvU~Sfgam27PByNLs++jG@CXW>hBz&Bv7w}|VX4Hc)FEmx&Lw+xu}DpH zi&6*5l+vRBLS+Hp>GYMf(dDz_I3bk^^R5s}7U?vG2oZY_Jtkq+OeH}|J8jx}XcOIb zAO>c~)ND5h>Sd2f)RE^25k4MTv9Ql>(T}w%(qU)>J z<0T==osKgW9`@&+?9UL4uc3tUdKoz_*`b6TE~pUzg$_{Xn-Cfw&daQv-jz7jE%(2Z z>+kt)k-O|3?NmEugXVIqzxd!ZUm%E%KhDc7gs z3g(r#^gBxW&r~)wo(DH8Ozup!eWT&?n<+xj(Q@I@?3$|rR&KxNbG?tYX4a(7j?g~d zn><){i!aZImp&S5so!&Oe3BDd4V3vW$Nt{6iB;LaaPI_Gn#~nnqwrqX8BXhID7U#< z(dK(|E~`{=i_X+B#4MV*PnvT10|-ojYglDuy#q+DA|a0WGm35G48osn&uF_BAIprz*_bkh)0uA|&B z2Lxx8^YeC4uC8L(p=CBJWP;?@;X#DwLbNIgU78(3eDpow^vswqZ6neCF;py>qF&mA zF4UCKFFDdKXCe-g3G$}{CQ#LGK6K&5)a#~Q>O@0JlEEn&G7o*vP{bHWsTM6HnW{2? zco7;Hvpn#Us{O)Jp8>CbFxVTAS@Lp+n z5k)c^{;K^MDLv6#K12y3hRLBYf+Am&+mU%h*tu7>q^UHOeI?PuSaSa@DVL#K6UCWp z5nU-&2Z8+eT2g9&dYUAbx?Wn)!J3ZV*tq zyK4bTcXxMpFW@}Oy?=Y}cfb2R-+Qj_I)9R*-mbV$=vF^?GuZX!t98ZmR@(cfY_&^2yAAbrZ6TqjhxhMK0o>U|v{0Qw9ajeCKAVv>hv;=N? zfbQ`P`7ObL1E6R7SnAe-QSkSie^TXNSiO8UHtK{<{q3Xm8(nm?kHkvCJk+6Sqg$_h zpj)(}r+7+lMIgMs7ciT0n3CPCqBIm}$BscJ_EQfI-^<5H0vegCd9Rn>3#kb&;lw=Y zM|Y|g62NXe76~EFIe-83=mC3!(Z+^j@pBy(Hb?ol5Rfm~##JqJ^IPwP%&Cs#E8Kao ztMp%}FyZu8Sw24Wx|{nNX|%u3qd&rTi1_Hg*4^vcN91-{e)ii4oP*2Nv1>w*Vsl|CzLhGb zO&O}b>TP3tLi5c!BBDMznlHR+S+l+sk=7dJb(dAQ3tigkrA1_zYunycGUH_R zgwV>DJJmYTSbs6+witTa&q~!ojE$3`VUTVVhfAYOKRH-p16v5!OIr|8P3qqB=-KsQ zAX47$^&KQS-(bDiS&8@5j53$OhxtYCmy@+u?@pHFOm+W$K)2l@G&hzre_?sRgvJyX z7q5SM2AQH=I}08%=!)^QzSt>X==vrT{?^SlHh+3>Ey&Wkt6aiB48a}_q=dMzY+=KC zN#3E{u7!k*1iB&FowTuj>HoG+1Y2dVhF2Orq^kCia(a@|7h8Pd*UCisOBR%9_=h~y zV*eK8Ybb{LG!6ijNr)tLHNX9mt4n`1#Uy7+pg#Q!ejBZ7_<)NL0Gc7}fZ5yzNBzN= z2Q@%WjW$jS6bCCCTNnV7hYLP<{y0*q-VIza#c8r>wrN&Bx^X^Rn*6@*Z{>Lk7*gRJ z4^sgN=V9pp8=Pzr1}_Zpf!Z)()4oOB0G*>f*{hv2-OifxNGVM~>THPp9qLLp_)P6v zecHF=0gR6+ai6w#-}W3s<hoAad)y6LGB)TQx{8#Ezt-!;)SSCq43&h4yi746|?Z4QsAY~Uj zG!iNg7d>%CT5~7V2ZuC~)5yOx9BWu#g;A)ypgnl!J;j^SiYCKq%P~{?rtX$M+QK>U z_nu+BQ7|F9u2!wxCs56!2PV6;KzZ!9e$z8Bhzam102TwEhHL@`97M#9X9Ir=Hvuj(7>o={!t6 z;Yv;%o`38V@0Rm8=*il?jJ~NP0s;Ut6u7Glv+umS~J&e$IAF?db)~X zAcsmtZMzxVA_vB(RLn%SWA;+?C(&jayO$v%u_RWVd1e|r(~6+3z^gKkB}}$NXu$5# zQWD^CfJ)MfD3n{mx!Ud|W^dve>}M|CgqmJVPNcoIi%^LeJ^Nk($NjLd@MhRD84D4P z!dT%CJUSEemY4?T&eUpy;)Vu3cn%03AK$+)ZLTNf>~VvdcmlizG&=_@Av;p~793n3 z1-mu6waPrx`~=26Q;`)K%$asYl#SLa0IwL2CaQH=&(UVr*2KFsPlOg;&W6EoKvf zM{mGShP`h5V@TKoPjpBxJG&l9!{LLb=iNF|T5RewMVaqH@Fny%1kE~;CXl~RkCwhR zYbtQ3OT_!gI5S_Ay7{}VD&Mh1&(O%Iy)PMW21#M)J`!7l(E}tT2JdgMby>c!$V_4VD z8N~!X6oKMaqo9Auly?vyKwpNTW-_9IM?4kLopkgzyJ&S5tV2p9M+|0-R{23ulTP zE>8&Bl{^&6r<80*mT(#xE#(T85M=nRxArR z62<5~WY)NFb_$Fap5!il(e{c~%B3|imi}VYb__Ixsx+TuiJtl)K9%K#?JAu7SQ|Y4 z_yd}06v!L1!8Kg(mP`Yj(=i7mh!b*}F{T73=LfdPv1i~73=;K|^UHyQTvU0h5_aEa zAsw%&il`r5KYP#{TBUHO6v6e&2c{(}_xr=I{+-hL{^LA!gKLwXb$z8T8rzmkO37S@ zA0b_tYcgcT8k;6Na7+p?a+NB%qsQd|NygKjZ6i0P@D+LxJdG^}9?ZQZrv={t2lxhD zqdwcX02{E;V)k+BkBQ9y7_axX&~#lCf=%E7v*QYvmyu4gEq5MSkAMKfeK%9IgPsCw zRpV>!wbP4RmFhRwQ?=Fdv)`T0V@{==dV0`sKVH8Vj0f3b`O}FtA&A5noYPtKgbM!+J}m9WLv7XfZm!qVI9>2_VkL zz^H!E0LF^!kFpH*MC}p(_}qmu$F{r&l^eZiV^B{|kRD=_SHy&0ha4oT0CEi8n&7=5 zg&o<^!Mv{68Xsj-FnVc~?WE(b*RNRBxkL$ZX~Np!qM_%V<2(w#Fu_u>`y=>=*=vb{ znGck2Lu~MJ>`-IL1z%)I+-MxJ9#+(|9Px|r)W`{kb4(pHHqx5v_ee)sfAsqntfYQe z{mpKT#4!{kExjyes^u~`vLhU5fb7?e`3ehygOH#A_F=6&D;aL7_TjXcb3z5ozYbmC zbMV>mFlCLeHR4{xO^toL0I!bok@|3KQ^NIDMu=R`GOBZ%+71Q zOVFGcma@{g<7J+nT2*F;)h@hI!k_Bu@aU^R9fR;O{4~e{lR=1^Qu_)l3NIiyK$0aS zNwQPHN0b!PxF4p2Y!=-m;3^}j*yXYSwu~?PB0$OyZZuv6R9+qRE7MI8L=V#-Jv zbYx@K6A@RDbzT^s&ni{!CuO0dqjOkpLpMzK*?ttwlNIO;?mN#L9!*FI(mW)JO<{}s zr*yIT+!v!etD8#adk2tL!hKh(0o>>NGo@lOGMqFP8fQYG{DP_eA;gX%HfqE23c-ew z&(>X>?)JL+mq-bEdwO2e%I7=T6ilJ-g<>W@Gf|maOj6~i;7jUFy44$XudA&7Ef7Ta zJ?5&fr>j;}9JtF9gUhc(T%1PT3w9`nE5EwdX>bAr*xgTwKU*@M!)uwPeR4;WCpeVzhRmqiLQ$}ua9@XKTY}bqO3x6My zr^%>y*Mr@}{nVyv!Q`fF@GwxT77edDCA^wNNiNxVpOl+%6>;BtcH`q`-o_d>2AN#7x;97Mx0_jN{(u$l9IYawOgpZY8AXS4Su*otY4nL-= zr2{|8MSz*d1wAavNYz=fxyX^5=LkVT3Q$xUIo|iN3I`H82j1E!AkfV{&96l(Vvvhr zFD};4fngY_h-054XsTKYY}W5gmg91q+rPNG46*-1$`R19VN&pLP84oD!>ZpQ2 z&2Leu3%s8Hn!jeQLgOgX$&kqzGSD$hhjMN{dBfJyUH8t-Z3ZU@$u@J$-AN#GB-^@K z#6L9INdmXhEb$>j>WjWN)r$5(1>+s(jRrs8?=uM{Gr7Njy^UU?6mOXGIDp|NvKS1@ zdi*bw)hI5srA~i^99cq%A%keQQ%>Tg7+$%M*)I1$Jf?U%7Va~M8p6E%e8$r%Q`H8& zoit?1dZMeDqx{vI6;M^(wl3`-3$;6RLpmq4-?NxR9}88zQEGpGDvAKiW^Cd80=RxxW(?BC5dRYo>H^=Sn@+w#j0VM~-WdWCRj!Ya zlaY_>B^#c|S}-Ut5b;;eqgtEIHoX^`Fu|~fKxOodYA_dkxGwHtcmlmDtT8~GajV( zV<_)fF;2)h)(WW)M>m3$Z+jbD5Ym%t2&+ilGGyqP-YNu0nn4)mOw_<5sj|?Z1D&-0q34#=;r)T*iWELrZ5$1q{b`1nlhetLE;L z(v;;hVW%W=oD^fO3~-(9jAofpw!gMLx-gX>=rx`AtJ_8tlBZ0{BRYKEPagzbUE2vH z-a8P-?$kLq(B7W!&s9#=ua7*eN~nmg6zBKcG9J_>aj%Omr#apl*i0lsQ&%?(+zrC- z42jlUdM~3n`MmK?>8=kT9kYAfmP19z$QXAzJutQAzGEY)LzDR&qm>;Yvj-%An7IXa zY5@T_x)QYB5v;@(THk|d zHF>ASs@5$@8MCsOH8n0QNjWWvZLO>Z%)%d=*qH7-t9cO#z?Jo`nVctZ+scS^gnRoU zp&8nvQ1_}&gra5sU($uilw6{4zn{z&ZBk3*#W=T$y#&VJqxa#F_@HyUZPpD|W7qXH z_U^IZS;Vf17*}hyqed)}N{49qhRFGsYWZ{3o@FWxZA`Wj_XcavsszS%ji(QFx>YR) zrx(FouM9`h5Y2VXQFb+aSTw1ivf(QUX=(pDHVzxB^M~!f&QvZ>&kgE$?DqpA6~r@A zsDiDvYV5S#?+Ou~u&x#HGO0Q51`3@u;|Nzq_(LHP5t37E4!b9y20utZuyUVxqHLFd zQhe&=E}x4@V$GUp#OuGf07A_&2dX*VvY+JN!s(HAT*eu22h2w8#76dydqLp4P^7IL zz9l6-OfJ$esIcoM|ATWsi=`jQiL`%TDEM}%ketv~1uJ6H-tZyO_0qHHbH;c)M$I@- zXb^$Nl+5?CFRMg>vnC%->Lt0s=v!6#u?8>VAj0iXxJVSic`%|_Zqof;`B^H_!%glN zFb0i6H{A)py2NyW{RyAz{s!DnckQ_h8aL_=Ut;~6hgN5a^RF6YBv>16-$=cYtNeI2 z(lrxNkyBD)ohiY7K9Qh(s_ULm6>PCH&GK&Wu$vay5oO+!Cp{Pvsqm|Z)%#*+^$=0c)R-6mHvJy z%OoD@ghgwj$_^KDlPH`b3nqY#)N~Gdt^O4WtfEO!!dG$~o@m_GY_t24`rg&WdH%*| z{P2EhSJ1)uPuP*|n8<9hOq?siSgZukLAZSmksU7mS& zOnYZZzr55sHUh*ctSmb&wi{Jl9Yr}W;Jss%dWGG)(~XX@v(8Qk{Q>F!e;J`%RCvSq z(a*>(w()PA&u$w9g=ZtbM{ekVb0NfK$v&H`Av0a8=y>;_D0=X7R|MiDPz|w#=>MYz zHz8cf=5)y|c#ed%0YU9I$hc-w%*IOOcjw+7$%*v$7oJ_KK>SUdqq{0KFQbGfRj0bjV7mkP%8A>tX*)5W&F6>8)uz{_YKR^^5TCZD*42vM z+JmIGFR1^N^~5lgDs0WXrHXklLr09sBda@KD0Svq39-BX2>)h=mYbl{h64FKzYel4 z9J&d;tH{$kZ)z_Vmv$qCxU*ax64IHOEz(rdUrcA%-{8l-=;wB8ci+KS<9DE(#+?<* zM)eFpy5f9O@2PS+xSU0Ndz6S$MLE4DTO%5J7F^fu15HiQ!5G0w;q_3}RCZTlOXW_# z2V7%`ac^aKNK6+i#DtsyV#9ZC%pODCNI%6^V-R82N!T<$iV+V!R0pnWgN`KzAg^G= z!NHLa3Ti+<6Ujy4>>qnH_wx2a#VGzDQKJohnNL8JvWX&qkf`5RHjLZv+*(bJScw;cCK2aNP9^2e}7y=%;w(QsO=uW7q%n(7)xcWkN^3O zThH2ef2)uC9EpoJbr<8gS^|bQeQC&e#Ct}qSk(;0wq=D8bzEZL@Mv!932Vo1~?>;f~kRd``ucVf{W83`qiMLp>(**J8hPHpUv}lUjEqde ziu2Qz<_*i}n9oovox!p8vR}TgRT2d&?+&X;nSS=hdXwC6nS0i5TdhdrC@_RP&CY+T zs7(P@arDd1NDeP>l)DtZ@WYQBu)*X=HcAL&bA&9EzZA(kUS~;_fuILL9w1|IsIxn| z=z#YU*s}!tt@)z0t!H;z2C0{0!Ouw#=IM5!98L4%=R2Ee()XHz-PC8;nVCBSc^$j( z@tYmaLi!zvxuLTlym;7Tm?vEL$7jjuWN@41YgnSEXBY;ScRfpB_4}(NbfnG z=j4trjeMQ2F3@iLLAuYB@$p^v2u>_1YM8oYDZS@ad6(g-*_@pY-o~{>@C>$pkEc2^6Ye11);*xa#A);B&FGisvowT zTB`TsDBUX^9&5P#GuHU~3jXVl0Uofv|HnpCn@tA)hM|LyRIXE=qo{%Cs!j4c3s0`- z;F3=T9rnNWnF_CC=@9LIO(UPLTAHS}deKbLF5Dbi%uRsnlU-r1THt7Cm{~$EON$1` zY>rc*dNXG`6N*vi&#Gb$sWm4mupT7JlkvGO%{W0=o`1QF?@se zb}f#$+k@TWDI;lrC2@~PeT3JuKdj59DQ-Dw5|HiDuom~3Eh%}^`w2+8W2$5x@i`a} z`HX#ahX;2vrSDGr4*Qn^>D4O?5^K3>c#vs}bl@^qbUKna34SJKq<{U>?+*^x{mFm- z`SAymv`3A?`z)D9Acc%fb*1vEz~1W6&aDGrhi(X`_7@L4Pwfp%wEua{Kko3Sza7BS z+wsH>I0Y0l`St(UCA7cWB{cLvxSRhsF$eI5!dnsF!nG+_&U3i)NeYh`|JmZ?%|-U# zTb!^SU!jV-$LhkiR?+;@3YyQYzshIK8*ze$h|UeVBOVUmwKB{E>EI|$ba!g3Zz_>Y zgQjuCv4OMf zYp5+(UZ1o-iTC6OHPmg`t*Hcp8b~2(j;`J#x0tAtF3G_yr99Vq2Rj?*JY#32?!Pw+$k7cP zOBuQp;4J0QSv}*%G=0&V#obKB*XqYE%&e0_aa0ca4aTV zl2Za}*r5d0a4q-y$Wu6K5)XG_&EFZnA%ojJmG|IooXM9NY^QK6=g;+Sh2VP*Z^Dv_ctVn& zYNZ$q*IQZ$zFyFpLPGXGJ)2U!#1E=GZm#k{b#yI@2w@fm?ZJAAXK8x+%Ww6({h@YN zsBHQqa$c6a_WD1KO_&D! zn=w%4ki?@71XF1}{cA1YBo6q7e*%E*c=33Op$zIq9by+qS1>+ep_C_w;>P{raY@oi zk`ws1Oa6AHKOA)Wr4C78p!sNwN{!};E=88W^w-P&L(2cYcpD{PeNUaNO-#Yfnn2n| z=-)r__Ya04K7_x?jn;8Yc_=gax?0^!3`eQ;=nvVRr~(0Ly6G)x5L7BoFd51inta1CoabXS7*?9 zgMXi>f$-?6zLpJMNCgsMvrb*nU;ZWxAFWWU$9C1Gey27)B_&DoP{uD?@O(}6?Afzj zr_PBb*H3iwt3Szw_kyq4*jZSfwW%umVctBQHKIQb%|00Y1S3;(9-EcyXc?AD-N|CVf}3)u^SRxs=k1CoSP_WN4uE zG9w|+XlKJZl7g>(t5MmZ_dgWHT>USLVm#-G{;epcN7g}8_cE#q@(oJHIU523qpCCS@E^96)F_(Y#cC90{UmCSS(k()HUwZwDKIGKaD&TmNmxyoUXmF3}8z=(3 zcX7wvtJmY95dD(joJ_UdLNfKFu%M%7&KwxT@h19g0fH)eYBxvB21n;2I;cAADR({W zk2G7Eia$Ho4l>TAb1o-&ieew%ygvS%f1WQk@>NO2#=5Wgg0g#l1~+Qz1$cfmoH_3* zu;$RbcA9rWqg1=o{q5xZ6(3@Nu#+?Am(WmG-I9-eBej_O?NNm6j29gTgE)|{h>jM+ zKZF#2KSPGQ6sLrjb5-<;8#fsp#~Cu8$+G3^Kje&0V`Q_^-REP85OCG#Ly7CW$ey?Yu^X=T{vXka>J>69AWbXOS+c-5OR7U8q z&9^Z#G8sf+&^$j()e?v#^K@`vZtk!(B8;S+^4e0nDDV!nY_{Oo=c;HfFto@hi0Dt@ zRxeip^eRe=u6k~}tF<=3<8pGMdpY=GvLr%6bK@%=&w+N81A2lEuV-8Mc17g&*#~;G zpdF@!(JiIX(c{I+`|D@4X_(QJNa?^dN{l}MCgN#1qTRB|K(|cfA4mSJte4=xGc{qg z`5P4sF)5Ycd7%Y;@( zSEqW_TpDFbxYg4-c=RynJCc0W+}0dr;QA{lP%vVg8!qVo(f@;iUQL730gYNuW3P3v z^Mydp1ZD+%_hQ}?v(Cb40QeT_8AhU)8B1@xxGQe--0cImfrjSwWD&JoC^^BbEa zTcvS*z!Y|QpcWrb&&4(QU_X?2rlI+;_(sX&#(i>6diJ`NmS^feKy;q}fapF$HEy-l zEMeL2EVjoWHfFssf+D|Vo`)MsI@yAEBHJ_{?gw@m3-Pyq{H)6Oe{?)FG zenpmf;#%769cg0oiXra3Q3aT2AJgn8s%ESZ-n~l4AooST?rj+13E z{4zo_lqul#RJKyk(_5B|HQg&=Z`f+RVuKJ(PgG^7??rL|Y<}+=5>S39hY-0L2J}8OBwv2rmiByF* zc%9csvQ74Qc9V9O_P%|QX6?t>5~0~-z!P4m@fNw<0}Zp){gR+%!kSsH*h%VMQcM6kZ08RD70(IjB%$`w? z`-2<_Uqk)=ZP|9Uq>2#uUAF4w=56G7r9{Tut zpW>~PLdL(Qqtg=DhrEgWoJ_Gx=r!bfGX}Qm3fy|M3Ae8{X5@ek85- zzxr+5d2dg*vnG(%w5eb zFHhb7%01TbS;;%Hgo`kn)TSZ5W@vEPL}}1s-b1>odp>zzU(Pwc>%9GaW^hW8rzs4k zyL20k2`CjpXr=ym%OKbN7tW_N{J+HclJd#*3-M4-*FTP}sGH}0yrhf&xa#tMLwRPX z76#n#y7I#LCHWP#fPJTV-;68#{|V=7@BV2MPP$9v80!zpjRn}w^OlL5#%T@*;uAGQ zFt@dg`p-OhIrsT0=0=C<#PBS#F=)u)yqj9me>l28kpN>Vk1#ImKAjL(thFUQM?Kte zxilD^lKLZP*O_fsBPnvWo9vDxzVF+VCW;2l1?7n`_62_svU=phMy`i$kx#Q_8R_Ww zXx%F03yF9MA9Azeq!A6JtL1q3SwEFp$M0Vr9Szy~W2QkFEfD@*hS`5Z2QmLo=%Bm9 z)rWsY2iu(f8#<^IA8P!3I;zg&>BVXs9RlwFp(B;G#boVl`)|@FEw^oYjft)u0D-N{jm|C=|1T%JfH;^Et>>Q|OmHrjDDiXVHez*K?rs zS~vfuw(@|>d8hbzs~4HmgYSog27lp)L3=;iDOnQvxAO3e3Ew}0oj(HoG#$}0_!?vV zT^E5{Tz%@rF;w2VA6<&czu>VgguAJgny#TV{0Zw~Ohub;eA`+5iDt<|*s9IORh4Z{ z6#{39nhkz_=8jv(%zCkWfz#E=@ggY&KT?#O-h=kE7G-w%G=6w&4N!kG5Zi9!erbLB z4?IybZeUi!T=?; zzxMc6#9vpKJGvkHD`}&}-jx+NPfPdzS@3^B6jd+iyfi3735SMxb_V8X_vPpC<2vpa zoGLvZm>T@`lk(xI>2!QuxagE4>`3^Qm1H;TU-3jFPobxKsyRmrQF84s)Rh==l5gSA zwdZ(@A)MOvPt6hLi?|njU*y>{B6pv%z%P{DLcUMBH=LO1^)=8_5TJ%7J=Vm9UFN8J z?uXCrP7v=X>SI(z)pqFBlJBd|*wYbP^$k-s2?WKPM-%@@y^)AnetHedI8ds<8~oPw z=Q%%if&XcbO0Uw`a=gL`p*J1N@q~g<2$mQ7bxniQ->J#7sQhl~o~O=ySym`F!adF- z6YFu1cBKPN5H(aEOi%Lg&s%T69P;kU9I33BvqH(5psd60)HXu$;$m5!siSA;TS`M1 ztF*dnJ-T%*LRxFbbV<5XiOpth)^nAq2Pw~`zG7t5WnSJUL*lJ+Rs1$vkjIEMUAu3vzA!B!VN$0jp{9T@{yu7-zNPELy`;A3sd6mO) zGLHWIEG>kh-0s$H`UjNL;nnV{nW-tB@NXzRdd?-2+~WR~QV=~yq1w`5+~+BsP(q^i zS7cr5{luJ9)3Vv;WNbToW9W2s>gtoP(9cO76L%zFnnTx)qGaoHReEU}5q#mSwGP{t zaXSo>I(68lsYUbTOd;l+&uL)>QyXK==AuL0>*y5~_NX0Wc&?vSK1obrMg`o{xwpu) zhxF*}Jwz<8dk@ILa6a5($K#|AW9ydT`UgJEjCc8!*xFyacMtefrkyW}76wm3HEpnn zB(w^`dg<6c4eo5Oo<`nyciMcc0*7Gm3~+gA7fPuwe&wZ>&Bw94n9u9#(&5}^^xdYZ z%9_x7{b(J}-`*G-?%tkg-Q7%G^_*MDw%Hiep1tCA zwu6cd8#2sk1-dwW7`kof7FAFKycI%xuQS*V38CZC%3koEa*IyYD$u&Kvyux37>xgPWw9kog)` zqVADqJw3mj%Dt4CzS(`gAfZU#r8pPA>6JUlVyQ*F@eU<6y2Sj(0;*27sp?>pW{`%+ zQq{K&Jc`XeyTnha>OP4l<~SFWR9$cpo5E)#!on(!zI=AcEtcS7#Q+x+6C|wLgllD7 zQE{`NZ2{DSbCtr51T{Gl68ntNl4H5+X;q$;CJe+L0c7$AZ1y6>bFCJ96W9lqN=#KfjF}7cO{0@rn?H8^INTm!El>tes!|?w+_Q7+&|L74pOewjhP4xLa zgeQnj2fr;45FUX+uSgxJGkGsR@Agn1RJ~t-IFi?g@3phn8tg~KWNoUwglTodCcX1v zl&-fiMX;NQeCMpe({gsjA!Gc4E+&;qs^SIph0s>QU9hJ6;v z;mg0c0F+7Zuy6ZbA`gWxTnB)fS$Zx;BX=|n{Fw^4W=AgXBgJ*r+y5nv>kS%5{wCeY39#+qLmN_4* z9&vx}gegV9BqJw7%Wi3@z}H{6P5!1`$@)6Tri;SsK*f2DkizfYgAb1unsKU-;5)pE zU%ba#=pCqjNK}fgyc1Ao!<_IU&*Q#?$_)z>GA2}s4aHZ-5b!=a7E7-y zr)7Ox=@v&uR%xcDRA^B6+!Z5o6sm})d^eQAP7K0 zH0l;kx?USMeQ(TX_Aud=Mt$V9HXqaHVZ-}MVIg2xjpQD|HK|H z-B_|~2P*g;Lt}^Y8MY56C)HM=C<&y$OS}mQiVqL0mj=vBksc^r{-RPl z?53ls#Cq%zkHNaggkof5{qm7#rvbeyCsZnZwi9ocPcx)>2liG$W2xmnlGog;q*>?bzv`b!i#ql`tFPTH3#zQ&Bn~4(jhTF@at#yVs)QoJ?|pj);}* z0G3gihnWy=D1L|{(wCATUfN5!P?496sGkt#2xdui3}2>MIEr*S23 z#Jep2I^+tzT^;YiKGNgLAp_wr0(x@Q-f)2FpZ3aI9sAKoo@zeUG&Nod{GbAnLsdu( z?&*=kMPIDWmMl*wbDlFBB=hAo|D$oEO%`Pp-(T!TC2Du!%X2o=q(zW-U%S$-pYW9C z5&dejkVGpzv_=b*;>0pwSJ`|~}>?;~7WdYGy4n$}7x-_~AdDbRBZFtQDZKGYJ#`}2td zB=|*q;Obg>uY)Sae#W+k|GZw-0KpY=9zu=ps;h>CXW`m?dqA4_Jz6+%m^astUimiS z*RnhfejfGNQQ?{rsn>U%FM=woZaxEikEp|es8A-DKgL58rv?IqLPa9z4<^H-0)66m zAFfXxDZX4-U^e8CI#dpCa4hQ-Na$pItXnUNNIXv6@5Sv@{NdXW9)5}AxvRv`3U=wy zxNL&U%H@=omsf%0UB|fC(TvO=IlKm9uzgFc_Zdsp5WGtl@AXrj2joq>R!hw|=LmnE z^aXbz0IDgj!O3i=Q20P{390ox-jvHlmE6w>ZeEU9sp#T97D$=W#%(=z;IGsPu9Ba1 zx|AEfGX$+h#WONbxE~>8JOTUbm~}O|jGWM*Idv7MrrN-dlWdi`7lKRS`?eKsvK_&y z|EtONY9c_|;e{DSdeRpy$veM<@x>|3YC2f*XVP+wf0&z z@^qQC`c=gs{sZy@O7JH3=eJJR++r5>{Y|6=>T2ml*V`!_wLJ3Q9>br83EyKZ8sH(! zJpHqivf=k|ZX=T1RPYpP*s*U}ZmbRt1cVzOV{Z*xmu`*c753ut`)*Ht)8)mI)daT> z5wU7+4jW%xAtpwrR1Oe5v-( z|Hxyu=nsw-olK^c;wm9vC{?GJ64aj&;J?XY?8C;;DhMhIWPbOS87Ybj))4!&h_$$G znHo7uS|&>}g{%w|(}nbt37Ge++HgrdPHZ4rWM#G-D(4DCGOElj4y&-~BugCy$3DyYmcorRzk^d1u{3RdK8>jzbJoMzJF!QR9R}S4XIj8j?0cW--0bWaVm<=rj*%G_nTTiFP}A_%Hg*YKush$2 zt=pT;e8yRR78+%Z@t+d0^)x1gofKu?pGQSInsnDJKn6{$J}vBQ9S;0#INn}b(me~# z`^2yWVw`|0<(F%R<0mp~n?<(W( z8uY`XiJI%X(AHFyu@P^Gk5=*d)9tQI>fpEm5(3jtHXW=!17B?`22j{gfYJnp8c47E z=~2AD5wfjL+f|lV^m@Bw@@3S%2i0@s_PnfN>Q|z{^^r%I0{O7h_4tOVsY+KdpJ~>W zA45kbSJt`E;Syh0Vq^>wyt1qQA4EMwyFJ_2R&R*8S(ptlMT9cycNRSz*ykIagO}sP zSatnFNw38tYCK}YGnY&uI}-2LTe5i|XQ*eNMweQgeV$IkdH?S{TM7l*y3e)xKN zthYbMqpSF z2KV)Ljy>XjYBP~jme_Mvv|dzr<9^(@aO)e8b-*L3e1hS2b@46|Csy}NO?7f55Y^KU zBA3vfW@Bs1)zhCPbm$zCv{OQVg@p41$nl0|Q57iw=`Z+q0vfmQT}2C4W3rIjGwz{op^pT^p; z7YDPed8O&QzPI{FnDdsUH83nT0Rw9IcwmM z+<`&E(XO3B)A8p3+n93swIwt=Vb0NCTA&q?rm+4pH2EfShSxPKXxdY56=Qey6B}gg zw?}eAqxcNA9la0D@q(q#**%%|L3|4fouq1~ZMNgGz?S)9v@D{%ncBWJ2N*-z_nmV> zUef(#Y(tx*Y%7iLw;t=9)!lx!ROX+nx;_?4eS_xkRI6l#8bat~Y(XNq+ zV!N3h>}<48gCkcK$T_i{JvA&Vicb^p-ec%)A206GUQg5nAEv8P5{PbS5MFzf&IH0P zm;2)!J5oeZCGe5XzhKTg=X3?fXmyl2o(qVSZ6q5Mco1@Xjxj3uWR{ky=4bZ5cZ?=m zp)eq`0v7uoLJgMe?}PEwoURYnhs58%r;xsJUaikQf*p*fD{XT=SLr_ciRTtfyfJrU zsQ7vEXuc|ikb6iVr%bBs$)*Wp+i%u|(0C$W=%jL%@Lz2S2!38q2_muO+6y#jrmG>C?=SX0){RJar(zHY!9+8cD#Yo_ zp)3e&`I(0uxrhk#d%^=;W*A?wYh8FXv45||ietgY3=0D~PvkS>`Te=wH)#c~A!M6l zX`bqwrRWcAWz`Q_HLj;rr&k}HH)m#?J;m;^*?WZ-QwYOzW1gndMB#&2ovl1y9&X2+ zVtIG)Jw-+HDW}01j&=JBRm-W*;YoeTZ;bDz$#|qOZreEH)uO+L$K<-QKX# z4|i<9wc4gHXwh9ypd3#dc?eMUJtqG1i>yo}`eXoW*|ba-n!w z?M^{_%fdMScxQ^0gL~+t?ipH3W&88bNywo_3xG4K97(d^LtLhR_^_hvogy(DdtYXWy zcu*u3hu`Po-p(rQeT130;r?&kY5dOQ(b<@6X6l*~jELm3bmZh8=@jl?(po=a(CV%x z1c$9D3o-ENZI>y={NPo4?&YzB7Bi zeG`PJKjbJ8)(PsP?k^=gdzKX-EWicJ;7=B?%|DD{)^TMHNVu_mQ7;~l$bwvTiLuL^ zPc(V;X{L%5r=jzmnLf|gy6N+ztI+w%?1S+Ft?o}WMUh(pLINmkY%GjA4c}8@+Z`Yf z?ia^ewbDwz=351%%BIU~BagkFQ|OMFPbs);kla;R{1Puyg7$4Q65rmwv6sBoLw2m% zpX{ew>?a8*>@>BM!~CaZ{4YTQaN1+S1ji=oIOu=u6!f;@$KP}d2cme3p%M`g;IEKx zz30KaZtBesnYxpR z5eXPecP%|;mzj{YaZi&Q0wDC4HSUwHWLwt*mXi;$V3k7U-7n|Zf<%0b);b(=l<$^U zRd=S*kw7GC3L;svy>2X-gsWxGvNfi$gc!Vc0%3giFmSZTkq#}Uyo`2j0rvkkg}j?n@iA_llZ@~3;A*thqm@S8ipZ!o0aIp&IEAuQm029l#lauAf zfAz-StIiWC$|A-H2&u8|4O4q!u5X@z@5X#p4Z<Z1CGOQ+Y3S0^+vT@ZDDzi%honW)5z(0-jKxi9*HXYEQQaP^wxrgDl8jCLu%- z03i)>MFg<8DL|oUPfzp?K)@P-Hc@wdAxrNtaK7v>zubT&q`OUN^#>B_yhxE2osjHp;+dQG z#`r=QwscxaMBN$Xv)F>1s}psXl@!hU3_p)&Us@)NxOkP{1g{Wy)FY-e4{a=}1K=kH zxWK*cz4ZCoMXGgt=9?|?eW1#YgPxIA-o(`Sqz}?^UiBH1QSbe%lEj*N3Xl89k%f3E z|D~utyZOjPLs{N>+P2K$}C^Zirya4 z@xg+u*zuB}>0zPnyZTPK)q%8z+EeGF4UfpoUiJDq+|%M6TTP$wx^HaJNM)}aztj_& z#w11-G(Q+-wB#d|O1iOqufwSU@wgyzb4pp&D*CEnbw8+UVOmUK^(5tRKsY_vq%$P?tXk^lYcYwB3Nw?~ z{^TG_jp-CG5SHt#?>C4`Dg=o^5eS-lJ4Mx7Hi4UH7|t=dg2lygITbq6zk{M#8+^Y^ z?7?Me$kO0l_&en*a*fF?J$Vh>$*Z4{Y#5e*U(tESuo&)~i_J8jcvC~na0auK^NXmE5Z{YdhHj&{d@ zyWKPNGMVf)V(Bi7UNr!g{aL9Nj|pg0<%sL@3@unvoKPDC8s>N^Ry5)WzYFManp{WA;214w=3(C#^s%Aeqd9-u!+$-H(Xe}ij$run}S-9-QXe>i*VsHobu zeb_=!1XM~%6#*rsI|M-iDd|?a2c&ZlL8KL=rKP)O=pm#*knW)yhRy-LYmEE3-}m=? z>-Vki4_Pc{*!$X7oN*k-dG0b5*!ug_jPncIacT8N#C^*TZ&DGt@jdZAB0Nv3V2xkd zKB~8%CNN>_@@T8KAhtf4ns$oqpMd9@Wq-`Qu1n^`XDT%UBk1?DqV`!~)Vj|!QwQ(v zXwx6V_OG|aAZqW-e}nW8N%L$5_&4=6OKEt5u$q#L%q|rDWm@Q!`ls$6?d~lUp!79x z^82`#ivLVxfq6v|Ko26%1WTgIhb+v@NWTlW zUC+)GY|yi%Rg@b92i}M|;1@#uC-Wte^nz}V=Hu-=cC)Z6IuSaF3hwtkw`R|Q%+548 z`roj%8h6jNc8i@b!FMLi9|l=(un*#m5q3dD-WK!NsDvL>l9-EZ{#_rFf-Mi;>=^;+MbXfmhESY)#k@)H(E9Nfg6X&CL zX7hyxytJS61wICmHbyPs(yYhT7vipTOBrHW_c3U9Tq%6~(8~zlKKyV<*UBx(s)>cg zMLU5`X7pk#SMZg|D;IuY`3~a13r|Ep4*~}MCNscfoUUTx(BJp>V#h6ffphZ7r|?&x z{}u%LQXtTWd%cFa^E&Z`#a0>0jKr$Nj@~AvI4YZ|bhR=;HrzFWnt+5Zb+lO%a%b4r7z)AS0)bT#0pR~?h( zydB1EjWIT8)zl(Bd#irC8X)Jq=V4lPrzeVYlLrG&?ve0a$!Cm{IDNVTqd7N#n#PUv z@q|!paK}?@>{B1%J<*xcf zNK6jv(CmM02}r-i2qNeU>D365H+I|0K8z=mZLc@c11;;nz8O>OH7I3HjvkjHD}GXzmmI z=sG`zf2EGnG%G%6k*29|2gKl#;Lis>YIUd}JmSA`Pnx_ARn24S9Xj2UH)M9g?h;Q@ z1)G2Hx&RpnisvLi(z?w~xCFSt3m1=W+1MN;ik2)Pgx7C%b#<|_Wu`Yy&Y5g}qvtAH zf3J;4hT+dZqB~viN?znD!8?9dK!5#^XS<5?FGH8_6*a%vdjWKSXz;VDH*UTCjX7 zT^GAddDGWhwc*x$d{y7l)2j!E%N@-!qPi0~kKg=A=}A7S?CfX5*zAx0F0b469g?=zBt&fp1l;82|Stm zDSj$*zurnkSy?6|AyClJ+&YH7tus%rtW|$DmX@mK7*B4ve0GYf-Xca}s6@#k@feTH zSWouFu^J#Ie6fz!g!2dAhwIinv2omUUh0`Vab8#& z8bYOg8)fD84yrQ~wVn02A>NP}P8#FGrJ{m|6)uxT-?GX_$xp(1DxR$Th^z7TP%m?~ z9)Oj<#_{zDXcU%}~@Rx3Lz z%dU;&vcN$9fXK*X>-#I8+YEiz+B(?Wm~$=dYH9?9QuF=dSar(gcWn~45`AEy)Z+sy ztH!Gn{e?$Wo6(EdF#_r0agwQacEw!Y_#Y@7SJomQ=Tv<}RPG;iop_%RP$e`JMCC3~ z9`0_vr=w?SS}Q3mZX+f>yMFL)VJmZdTpNF9$BeMnw&FHfuW=Lgm^|K5vxrph8Ow=F zdRM;HYLzqIPHoxS#(dNI)q{<3!|J6BGY zLn`jw744Df%{s~7^@Xw6p^9^Z|xCzxoT_ zSNQA&h!3K-3uDFIRJYp*qNT0kOe9?qk6qvc_0jxhQx3ue{sx zRRF=GTzb@aPv@&`a*#fVZB*8d#8F^Y9%F4zJ*K_K;`dAAf}^Z>A+cV?r_l%me4SVT zNG~(ZW>?h4!KPo7hY{bb4xv7aEj2%-n_HQfZEy(ruk3|knt4s3mi%SBxUxq?EGW}A zQ}N>Xe1UFZ6*@{X8TK9T0~fu?v8=~T<8KlgeT|Dttw#r~;eB1_*f?2w%ptNt%e3Jf z{kHSz+xXl#*Bxh0#ud4Css)8oJ$DXS@WFi4+w+WcyR^S6YT#ynr#BH}5|QGC*aUN!n&EFmY#4sfeY$eY`Tiz8T+H0QcNpEi7K( z_=Okp`=Mj$$3Bgic*}0-E|NqFdJDMQKv% z(7i=7;kqktu%Bv#FHNI$Yt6#IDvD+tJ1%n6;Kh@Uia2HU%5AmHCd&dF+TH5X*MOV(JG*5q5-imvR7$-LAY zt>Y1ZES^?EqI9>|6zR@stmJQ+$06dM0rb7CR+k0DH=5niRdc=YKB()%VZGZ7tHF1s z_Jdy^b}+LTm%*QGmX*R}g>Bep+%sUZl0fDBV)O`A@nqpOf6L(2v&()VL2*J*jp{%T zT<8JS>4xQLVQ&S4ak(TPFpLa~)du|_io*uL;*2T?a)Eihcrg-ywAQy#`1eKn(B&qV z+uW9WdwAj{N<0Jc2(+0kxSkV0>{z<^I#W!wUh$0RM~^&7Db-n!=p$l$8X=BX;qtg} zx8FvimSP-j+{fgKpVjAOR#ClC4BL53a`HlZi6yZZziq>}`}K%M3LWr+{1+u|K-0*# zT5^8VAW?`Kuh$blxIfUmNYX@&M|>AbUx;)O7O!*)tR@@epMnRQJU^24yssV!71idT znceMKqW44ex9pgNa3!!WSQPA2Rtg?1K0EZy4)WtG?{YE?eKXNINHAL)AG0KjuSqi| zH9k>`>W89_fs3 zrUBVfX}cAX}N=5d+O@E%f{p=8#d(^S9 zEz}*)-|M_mKCK%Z%h?h1(aqND=;*8tp~>`hM+eExyq)ojYsh0?V+iS`wq^#)=WJ~npj$G-pH#095djd^HiRKow zy7Y>GClp;5x3xWkJf;H}(W^IDUv# zwX5pZ+Ex8ECVB-|ZU>AdT$3L*Fn$x!qRj(c@Ns-ju;ysLvt}3CKS8%*-Od6M0`sF_ z3aOTW?Es7**mmK%5XiCsd`FNl;1$4taeI%VMFj|uRE8aOpX7T7rJF_j?D2IPxFWeP z0D-o^^Vk*I!8V&T`HVD5Tz_2LHD){xLUb`N1FJeyWXSN|r)RM(DQ>hrS5?e>BW(nL z`rp!p2#ChAH9+iG0ofs8?t5$ZmXkuj(PeV5`92pThxqAIz0iK=Sxv*qkgJ=EtE3JA zkIAK}e5#s+w?HJb(99)nEK&Hm$P5s#OS3OU+txb9GID~4b}~ZA1j2}G9r5KJlWA&> z&#AH6i?e=(8IEdIxpZGEMs37p%Wd@@^;x|?n;ecQjVj2>Qn_>MyqNRb0su#QjA!O@uEGBmugiZY8DVKhdq5EkN4W1JwHm_jt}3Z_t6KF zW#;EAS`Lmf%n$pLn><`6Xa}em>joxD&H|1#tG_R_9+OEYjoKe@DJ;HvY$(AzvH?p` zJ31bc$NfZH_t1wclOYu&=yl3ND(&56)%mNmxXBfm-ea70iD6aTX^Rr|Tlm z^obTG+oD_g;ZvCt*;yv+beuUq_QlY{7?ScKm<-|MxaZCeZHwgG_*^Ep3NOP;mBfE1n)7044K2P`zQMj%0?d{FQqc7DOo;z@mJpjPN}C6n{7JwsiCTD)kZ z6_b5Ny5#bUCBD8>3ALT7L~@aMr=Sn7@}XaY)F?Hmi)qjszx-DS0*sS1qo`Pqg&{Sz ziE)*0fUeOP+osHBhsW@@cP+7$q*UdSuS6GK^DyH@aQ4DhT7s$C%^zDlwOQ5iJh>!7 zGxlVT*oItn{vI!Y9yK`QbWfLIw>!BBjc@~xM9z7wlWTi&Er32)=OHBrSaX2hsDV&_ zp*H1`luJCT#5ySmGt?PZZZKFQZk;h~j3+PtYh=AR&d!;`eawMPlW(6YYjMVtkdpKt zid!={Le?fuO~R&}f~R69S##mUI;>r>#H28byy4(TV#ATDlUiEFcyejy3HqjzN0AF9 zJvvyu{qHO=$GkNVOn?u9%a#>z5!Z}L?@MELBJMwl-LEnsy8~3a{?F-GcnM6Q%*i9n z5I>arV<{m=s@f4l-@L<<^?=N;=vXUmjdxn|VUAYg&81U?&fT;lNOk2?%h==lbWAoi z53N#}F#gts_*V_UA9|sDMz8)>rL8@vY~U&@1r2FMh)L#3O4yMeZ?rPy-Rl0TGg?9I`6Kr8Fu$fk&b?&lWxQ}s^W<&vf)twz|(Jx z*>8)Lqu2PD6p8Vz4Jvyqb$uRsg`#xoJyn!hSU5k*PUd80ceB`SZtl-0uBGJ1`8RPt64GK)8gOG=cRY9`x9&uX$Nj1tP{b2K*`wq^FB z$%j?~-DADXSymtp4W8`uMkdH3=`_ArNW z2!h@C#{eTxt^yH4PW&A_%!+){x~Ro-?rF)5>Tl^H6~+?~an#;i6tiW%_F99p;{mt( zkhs)UX?z_6{MeHQVQ=qM=n)t0X;6CkTp?ePnlxJ(Z}|~CU85S?sG=Z~`&qDnzW*tY)cs-2f>CmzC+t5}= zIQGZg;hwq=Dm4jEN-!I!D;L8%NZ;NA3$cw+_*0o+d4PRl{t`1SlEEK-O-q_r zO<*Edo)~>$Yt9V5Y9V)IdVthsj$A(BNgY=`H_$B0g^3&#R8Mq|Eh_eB`SjEkWPfZ2 zGC0PE^>$cVk~sNxXJ35jSV^Lc$VqQK+Izfucq4yiZJHgN>IHzg8p#D*2PTRS9C^m) z;qUUnV7OQTb|1_0JP@;s=49*YCs06*)euU&mxJ~y>%BycFGX|zQK*DdHD#qh<;v{i z3Ge&C%30@IcX&K;sl|sv*LTL!*=HMHwwcdg2)n4ZZZtbR`#oJl5#1AKmg>%kdkech z0xqV+C^aRNVV>vdN(_#j?}HU^H$#l{og^R=*q&cTdz+tQiS*aW0aB7%#+(4<7Zu&W zioOv2{O9?}_Vw3iPfS_5^!NM`6wZpH?_vO-)StRMHb*^g{LqU8=e5Mp%f9~E1E$EX zU*;G#@vBrR{f7e6ASr$VqlGUh_(@mK(KjMOOOH8WDs+B}4~(+>D=}u25X=gM!}|<# zR{j{n{(uW5SXX2suG3u1dFty|x0Q)wUDRHOsl#e53^ydddX8#a8FMh)xdzL0l}dD; zyHLJt`=*MUT_ZPl6!yCStnJz>qp0gGFO|%QqP9OZsS*^g@T_2}QSQkA3t8O%Ob2X_ zYQP&t!0$eVV)ntG0hp`Q!VTV?x%dKS zZT0DB{L9fNM?F6{Zg*OP$nkoF(GsKJ)ty?U0f(JQ`3Ki_MA?mn*o}*eqeGGcm&&%( zoDg}Qyh2EMqFZ^`axtzl6qIMtE>62JhBQ}P{<-nK;+$L5$uRS0L{>=V=7GfC~l?UjEGnVY~ zs}dT?+VNL2s~o}q4d#nz{sByWec9{P^{F0}w6Bgg$S%DFvL8(8;$$?qw-TvCASN!S zp#1`-ekB(}^R4ykzy5WrdyAJq(yA515>^mCSDmv&1vX&|xO(gf2KX&DR+^fZ*h%L@ zBJ8R(Y!#EGXX!p@G*-8?$i}dp-#;hGeAN09sAQ{-hmJ!0x8SiRi02t>iUxFuDZTTRBPG0UxjYX_0ehF?*KMP%X(HWg_9!{`5>S4~b$Wc2uTe5IH2$b> z#?2c(j!{&5#&9$pIgZPwrldR=XqJsNcELN4>gnra4KqHUUX-UY+h6N#ZpljRn7!p0 zzJZ20TMq@5!uRmw{SSvm^F17|MakspawDu-ms2AlVc{!w6-}0u6Rud?jv)mL%(`}s z4ei|U>{Ft$MTj4Fu;d~L_{LpSHsPCk6>?T_K@aj{y-}1$PHH<7V>~0Zu1Ed%=moTt zl(eeq%8hdDky}bLe(tl0$}Q)k`p&mO4QRv#TnQkGtE2}urIIJ(&aGc)>!S}Bgx?bz zB=pGOJbDin*$zpvT22mZ&VwY8-L#0mn~LpU7odig?zXg8ZStrZ(W!DY~eVlUs=UO ztC3BzIo<5&sKVR>aeN#S_&juI+01MuZs>HBZFzp@1II$xetJ~d^W*Q!18M6+W?7J3 z?eQukWT@7zy(&mKIB-!;b7`5UwF=6U?4m-DC?oHYIywS7ipJ!yx(HVdga>_;iEQkh zg_jB32MHkMpMI#v8r5;1J}>6=I4G)UF<*(LCD>>t_t6owNYg6Nos8M^d4DxHmPjov zvG)T4w3TDm6-4<75C^%jfBy}c*+VTYa*ca1)O$S26mxoJiNZoUzqYut!b9(rE z12$o(r2AJvdVz@iREgLqC@%AZdorfp0`rOX;UiOR?#7*=Z#Kepy^H8l@ zTMkz*=}5*(130LK-Dm+_J=0MBxFm72Bay!nu^a@c!TzVHq_bO%IbqCkEPWuKWkYBK zg+8#ngJ2>Y-*+rKTkud#S5;}$^VH*|!0(2j`z`E9^H}gQW7Gikwi9J<1v#d2V_^nP#y!_;a$E!)bHt{!LD>d+$DYk6X9LcYYAb|K-aP{=Cp*K zWviK}g)Sm;4>{zr&K?*P5(B)tsSA`IKPm&~JHqvt&H0xt&6K$4es$=9a4e>z4wR-@ zY~-Y*yn4ItD4mp0E39_2<*$r2{DQq6xkVMlbi^;M`&CCLG9!bbv!>Cms*XktPfEt9 zv;K{Sm|1QFlOEJ@HyWk8d0EZDA$aC61Lagaytci75r#N9aqbzY-q#CqxB22?ppImz znbA*qsd|3b-rJ|T0PBR?3eEGwM4k#3&W$!wWzwrUJuWH2J?ClzbYIk$o?K9Qqjg%e z9cAskEhWW8x)kdH?sicVIZpF~D)z$Ix`(=zR&Gi9()9k2g5Y z%~ro~T94+wP(D&)O*C_Md~#rAK8)6J?%a9bVB{k%JH6?oH$^h*#fLn|%4Id6mkoWb zI=J14H15(e^qF*beX&`&eGnAXC!U%}VLVCmW^?Evk+mpH{TC=gukLx;exW1SBC1k` z{Oo$ZB}wl2a_WgDG*{b@+=aQHb5-X9cT~qbPAw8?;S6*V`w}X@PJ&uvH_zc9WXTJS z7ThDD%X`)4c!yPIypsOl?xsTk;D8E>kLpg^X@TXgSRhXYh>8zTLilR|sSCzOCGHoPQZ_&YIziV&*1m@m>Gwq6z`i${AI(Gv-oe-2&LP+qH#^I`^0q+AE<}%&k zyo`4rx-^NdMnZhfc@%anZIm?v%zI7Iq-dYD#5APO_ZWn>ZUwQ=kRag4FI?Pkt2g{8wu3>Zl~Ht9%0}Gs}ONnMTJ*COc_%*n9e{^&yB6hN; zAd1aSxAh(5D9_)h7g{6V)2%Iimi%@ zkJpR8O`|^P3On`Y|J4G-ACHG1%&KQX*E2oozP4kmuA-qQc{w%pgB)DEOlD zzol$OArW8KEJFfy>>%86vMqu?ZiEeZc)Jp5fecK)o7xoAN*_sx2Cy(jvy?HH>C&}}o@)=J@Mq*+O zW&EM5Jf^J?oM;{X#N4`5H-p8HAJ(D!6jk>AB3&3Vo?K{UT+hh-?IAKkQ9Kh)yS*1P zeptt#xuIHu89@FvSkCUZ%?7BuP5dQeR9cRn$T`r1_n}|MKTZU?{|!rnCD{f8-QCkt zp;zd#x-^Fu7)e;{%Ntn#C8le`l>Zswhpf)`4*HE8aP!b>O=N|ya&*98pzKD^A|7AZ zF#J?l#$xi9P9a^$Kp7OdUU37LfgVWNBb1l$0;03xZ1j%88bK1p*aq1*2(fPCWE7>oHV{^6v?&`!Pd zA!eWCpD@?G?L)~-XvM&#?mtE2Sy@qTq$D7UIAVlm$Wx3g+iyMv zFC|`pv?Y9(-&^5f>U51tKSR#%7#HXYTRo!Cl-cLGl(rfR($q@s)H?*fBB=kliS#k@ zL^swyT9=oF{35Td=2Eak>^kH0HJB>>z-MxFF%XBIo+|EEKF&PoBMWbDA;5*I!b$vTAcqGLRo3( zA>ydM*n^vq*Wb?-;6#njXKXbj9LIJOo|w{ryv-7&SviG$@~N*r@*AXbg^WxB6O)n@ zj1%!Wpl!M_6~$FM?B}d!(ntpcbEzPq`|x(xs@k!yudg{!x6gB#8Gl*k0&gUJYA296&)3lB0dr8@VCg#w$Hx&%Q6$1p_mO$D4JxrXEM)wTs_n6-? zT$|!3m$od&0r1&X@U;Oi%|?~0R$7qaT~Pk|-AYwPrt03llqzWAr-*+k0JI=b`)oqs z0WzR(pcXx&-zW3$h-g8?qvnrC3g% z^kK&+>&$_E24dBgs`G!CTkx3<_$*KUB0u+VB$_A#8p;<6F3T%F^Yg6?lv9A?>^(O*+ z#%-{JW=TM@43vV?kiE`lvc3r7z1o7f^$U1-T{Efo6-{zXd@_kI1z=n{+rqUP3>hT_ z#yM~$&>RDVgHiqIym0*i*n+Nf+1!nK*0yXN^)I0>SGfn7?9+ZFI;FL2hcG2F4C32(xPu;z6h7+2abWBAnEv$ z7UKSU<~+-AIqeX>rs~9qnB-!^vm1V^YAo>f7toxJ1smt!IL?lhpKf*UM{pzQuWzg~ zGN73mm<;o@*;^J~wPp=Ml*0C0s&7Z?o?fk37bq7@tTI&zQp63vRPXr>xDncQK1m&1 zjyCtGWDJ)Aif|`Z`Ea9`;e$K%1K;v20w zs8gQa3Za-9oLvac$-|@q`ap1%HV@)>9n2Gx8s9Pi`#2kvD0DOQO^f~B$6m_7u0#e9 zkbEiLdq+*`Le1rY~98^h%8 zm$@kZH&H)eib_h08+@)?j|eZ|`XT(ccpL!p#6AkMRT;tr_ARopE`3S1v)-iL2}`+} z>~Oz06V$ItLV26qyIEP;I+Vd4ySwCblHY64QB9H4ZBFdfYKp{HvN3yy!Myw`u!$U) zA~Oyp|96-T@8#uv4IDJAxF`0cmmJhZH5&DdrJ-L}Q1)w6R4r0UP&8x^ZRB*+r`<6B z3Zq~lB_YYwmU%G>G!tsYkj#|9oSD*uHGb(XEf;M9g!(8Nf(Rkyq z$+@9KlYMiGv5onkcArhITvqiIX$=^=Q@p)@)$a5kNl#ID`twemQvT1#$-feys*;?R z#w2l47BCerE0$Urk5jL@+k_+!8PK*qi+AAu)YlpIRI}Jg4K6Mn>&BmtX z4HaBp;_h{NHJ1_rZ625&qZC&X1Ey1&cli!G$Z-@g8NmM#%YqD`o#HG^rF^f|eEb%P zA!Ix}*_Qsuso^K|eQej!n>97>97BOJEB@l7dwT1KN95Q(s5`}C-pD&MA$B}VENvU?w_jVFW%BEX$JDo;(Hqtiwe-1EDN12F? z6Z)N-4dzO8RI^x5aD2yu#;hJ)+;`$w@Rdz0ITS|xcqcS^;O2bbSYoG!T4%F1J8l~! zY(IrxPA$O2=ztrT^l$tZd#o(=t89Lg$f;0sl%E!zNAygmFDGyy3DYSM-@m*n!-#Rm zJ-u`Imd8ZCPXeUGbLPBP9 zyWm@tVJe3m{T$yy?NDPt+xi|~k9TQpX3JWl?mXAY@@T^72nDo+l*@?^^BLQpiYj7! zLi@|)#Q(A;t=eEske93AvChN~q!)w(B_i6fw(?@m|h`xt@}vi-G)?^E}Rc~Gyw zKb*uZOkY5Mqx_Ec&WDUp@(`7wo=4KoktH%;VW7R5wc$MEw#E^;`_^DB_n;$RgTruX zKb81C*}}Li!#IdSjX#To(p8j~0i$pXKb(sk$fUt-$7v4dA9rY1dNWJ*Mt6U`WvV9S&GvTcx{YVqvJ z;JoTCS6|qYk=cyRD(&g^|2Io$l>cz)0For>`1YgfdFmkFOc@>9C^)T$xsuaP@Z zR5wEc^+Ll-R%bn0#8?AHci<`S*A5-f+p|vl=T}Y#+WK?%;=oDf;U`Qelz;L%a(0YZ z=e^f=aENH>8bLfPssoxKndrpI2K~+*iKOmfbfkTH+YVt5_Q*W|6tt26BAx&SrdIkB zG?{D32n9dAfQ%im`K0u+r&~o+mK-^5*n2i)-zi3oe>U@vlpG{Ir)`p0`?wj%j2aIy zdtb(9Q%j4e#fiFJbIF@8;ptl@es`zs}tD6CEx z!g2m>4kq=CQO~jsPuJL(I1&0vzNzJ%9*G~Sr|Ue=x?^YD;rl(NfJgCeGH;LE!}a)Sg6 zaoiROwnxpgG~Nbx&mt_khnH5<1EFK~#y-gJQHK^6-&Hbz2g(1z)Qkm0!L&eOTokPU zavw|rch3&QpB-O`hyg#ZLIgr230|z)AdTg<1=C|Zji;S~A3e5M@m-as+MW$DVgwM6 zZ(Rpbfdd93b8vBFXEXtU#&=mv6H5?iWKx2Q421}2f;}fp3Zj1sCkcJD>;&j=8l<0+&m9;N z@Wf!Bl0>*)j_=_UX(OFWu7JvN2Wa_m_r#FIx9QYrW( z!f}Po2IrA4IA3Ye#y9>1YGWcE#y@7RjOHe$m8w~c zd%UuMkm#?(u^lYij2yTisNDmYiD1}nT<`JDG_8ilb@FuV~4w)%(zt-GKbRKiw#&Kvt>K}_~XUFlw6j&m#7l5i| zHbfOequ&BK_t%$KDu3@2X?m~j*J*KYZ``@`7SjaMIz!U1h3>?)Li;+OS1@MJR{!z0jxaxh3k~Z?s1oel2{Kuk&G7qztFt9~#mDpqh z5_##�pufq?ve84>2thLiw|snRz`}Zqqj|gII>NCNB_7=ITtY{!8$X!(cBH#a##8 zDt^rdJ8@ld4*UEwBk&Ohi%hG_@s*i>jK(xx6M$LsI{Kh|GW8-M9}BSXIj_Bw2Af7z z+6Szys1Byz-T$%D5f~N4_=^N-@Lp86v;NP`O3io&WI_vLtDxWHGRsrFE8q$UGtBvf$Am;YjyRJh3k_P^Yikb zw?V6soGc3>@-j}TL{6h0d6-60IFZ4DA-QnZ5m0ad6toyl=`N?`*NLLQmOht@IkRM( z=E_X!juVh`2&%R*rE;Gur2B^KEeYl9*BKghEcG8!y!GopOgw^p{Z0~Y8q`eUhI*db zJSm`FpZ^*gm*MqA@_WMy$}61{V_&!Aa8|tT8P%fg5>1TPRfH}4w`x|=`&Y&;yTL~# zggh0*66m6cc^Ez`RO!AyNu}?+&JAY@|7Lkov^iw5NVmh)LCQN>MQ9%OMx@u4chbk-Z(kIbX#V5|MT6-{MRxbwH^LKI2 zE73)UlZTFQA>uZi`n(eFPh$L_tENfIT;9ny<@r(2|k@ni;QPSp=ym0Z#P0@e- zc<22vX?ePU-85IBjiotFqobnLs&^w-p*F>;lj?lup zlx4TPhkR;0Nu6S%qvS}&jET-z5;#U&f3Eqn7%xP!#=^}>jg=dC6>;7LQuECz@o~{g zSezxs?Q=nv?=lJ_K(Dys@a7v%cIG{tf^#cIImR1SkjO`h>{~?xSIoXnN*wOCMVzL=EY;sIekk1|=fSnu z*tq*fZQy>bG3DZ6Py;dx5t>&K@9EKWYOtekY1qgh{%Y<0w{9cQbWn!J4Sc+vFbsv&`? zlCG^2YN!C8d;hm5TRY%=NMEQ<4WI<~r>fz$2SqgPn{2zy#P9c+zgCiPaJn;&Crvzz zXnSbAw>~xzT5hquconG=99t=*v@ekKJnjR1C{^kCSxb=^g0R8SN=NB<=*_7RSrx3h zOg|N6HbBT>(OVFq#uPu1q@q=jBj)9%i)QgSBqu*r9~x+bJ%3Et=ZrLX>K4Ic2bTQ8 z`ouu$dzF}N`O|LS^;;r@5Tx84p?zL)&x<{$Js_)rq&|OxmK%hBjUJRN>2ltO32b#Pd*8wgR9AP%Z+IKs3dOO zxJ~f2yi)eAVW7v_NNv6T+$Z6@CQ-Ca9Uk>oN%CnGFXbq_?d)ci zz4gL4k{s@JP2a9&0~c~ik#ya~mg z|8e6EF)-DKTK7agAh?Z3FAq#0R?6ZZz}5w36BSREGW}fFwJn^8^eh*~3(cIv7pOir zr!V;PkB)Bl(W9AQxq2FETDqAm~Zf}l6(Sq?0|;5w_38D{wR z_=dC9bbH>S@)*_j#GB(;C!w)cLw1)ASbYAFqxnq((J{>BY0@te<1uGq*6F>#d>};=SFi#AGmk)R&If&=WAvw6w}GQ{B;(i5Bxl zIVyqb(aMNGgjsLyK-Vsp^`acP3EZ;2UosmL$*++hm9&~j<2)?!g#~zG&e7s1ZijfX ziIKv^;Uf92fdQ%VBXXB+=QM>z)iUnQmINv4Gkoe{*-Y8$i6SRNy-AB)4D{5FCGk2` zpv>OdmibVuLeDeN)3A;}1gW&1qvkd(;bbDOX+n!Wt=B3)a(gXbmW+7GD}0zybY6Kh zmMkH3@W~>o1BcaPY;`idkFWvRz5W1cA_-0ihi0k7g?E?03qu5P$0LjHVO;e)_Xl;z z`Xj^CXu3;e_rNhhu8ooyed2d*usp9t;)N=#tGSSaW`pZvO*)xJZr{06ZS41okLIaG z0yq!53x6heCp53XtY4-2`DZnCaHvsRDy<(_A2OeItwySqmN+^8lq#RkUMuPL0tFPO zY&;K7N2$g`A1S9>9zC01Ty8|t+GVH*mibd!^aqc7KIuW(bwe4@R?4ZCi_uFhlFJZo zgxiVgV7cm1{tVu7t`B0zB&bA(A7XBBz#U(}qFr=!8n~(qT~Xm)rQ6lnwO5!U+j3-| zhB(IC9N)sif%0MF-21qTI{2#vNcsuRgi* zua0bt`%ER{dE(Q>7J0q5D%VOpfvYc}KVR71n9!;*W*+lp(y8H4KwEc=isUs1AJ-aH zTpyI*r>a=eQb&ric(M%Mv!2x~2~5yU?hl0P^Stn7$7?6A0UWHzcnNaqq`fwR#{nDf zuFG)-n-XMwvhs(1{}a?8t@K^QXpx9bXqt2nV`ONwki*Nqgh^!LiATHl0o=9E4^hOX zSSh=zaqvP`>Zfk0`Pk$FvyefAfet~XdajmRRET2)B{k|$?+H3<6D}K0M)d}sA9aQr z)v3~%7;W}H{mAM;&RrPS=bwtbej8acppw^^Q%yOMrG=DHTFk?F6_Uebbc-tdIOA|6 z)$gw#&{#VxxAJx?j443P3Un)i}|nG^uW zCC+7-u-l2QC z*k2^hy~UbHjuv*A^h-Kex=(FzpVNw_`iU$<|Ls~ced9Aa&be%%8l?7umU4EjDltH)})q1t{9U|sPinn{k{>~lc(aAsKn1$&NA`1*p&amv38}+tI zn(XMbSYw5LN&t{U#re%BR|mV19ukBv&U2qaJ>I?w3%S`zwYxUXA#Hh*wdpjS>(3py zh@O5hslL%aagzP=MHiZ2Bky6ZVt1;}qE-iKm!+wN-g=Q*x99yDA5pjNeLNBxzg;sc zU;dX2M5(Cu9mntKTolixeXxI;AD zr1Q=@Zw3%n6qIKOaGx0+Atm}&1^rzuzoq8H>8p+0Ux`9y=-jqA#^2vSclpy`uQ}{p zPs>Fv!!rWJ^M=Ht8RGfOlm}@1_D7qWnu)@tjlzoO8JqEsT*f7ebn{mD_(*LUOzU@T z%fukMB`;pOXK0nGZ^6ZMkYfmWjXRd=)#Z2cYR+##hFGGx>i6psto9WZ34(!4w(Le= zlrv3r?nZsVtnrnI9Mhd?37fmV2z_e(`00U;MFGk2YaF*)7;^OH&4HDALfRuoQq=1xwNH;jN zw4`(lFw))448ynQ-ru?R9OvB6zx3z(&R%=%wbx$H^XzwTE?bGpKb{D&HhQ7tI@52! zN1bg+9@$Suck2l1gi@!0KjvOw7xjz3{hZFhjNgq;$1;)m+$e z@E-iV##2P2`pzlLZ@0IQy`!C@))Tnd*x^F8pLImeVP?a^n@msh-~vhx4-6I`IyMQVWw z)fcl(fJ&l;;}fEm5F930pf9*s;FP~>e}fC?TxwAOxU65dQj~sv*Tyy{u{_?tB;hz02h@LW=ZJ{J{VF?N1)!|850gCpr%F z#QGVYMcf&z9`&n--FZe`cghwi7h*{pwFzpX2?d$pzeMrBF=3P;`WL$uOfQ6CeEB15 z25w&|X6=q(gT^yNz&0Vz?{dHOmr(2%8@`3Z31Y=ZBICBJrt{)v$gon1;gb{dwOS^8PfIizE5B1}w%yn%-A$HclPa&JyM69ClEy`}5MPz&a$l_`{O&(ZB za{%fHx8tM2p4?DvPN?_;5zq5o5C6|WmUGAZ=5i$>C9e7U!}HhfFIYNg+h^Xwtz75* zChE~#@Y1oHOFB`6D<|^qgNfo=sg8sGz>X|bqH-_%X}!og%`r^Vw7057=xBRF<*1X6 z2BEpTd-gnxqQPdSY_sr3dBQb2cwM{0VzhSUXKE4V+JFKTD@Ce6C!FT7_QQRvMBYdxDh{d$P zm+kEZ6-IgxIy!NXq)(r+rYnz|ez8XI8r%`xcnvi@@2W9d$~Gk7RNf0$pTOf37IJB% zI_9bR*_=qc-spy^Sm_E!xbRu89mxsb9#AGY6s-6}jy)5tWzW;Y)Dn&bJL3vqG#8|QwT}k7=A?!Td{?#P+KMYJ?50*FCvBdID z!}JpPj@LRVDf%<-QKb9!@@W0GD*+cCB>3RiL9os)!T({1l=u#^=ykDQb@VOp0jODo zYlH`~L_)QikH6@Oe#spklZ8{RMb`TpGYuJYbnwlH2;TMQwxWc;az4T41Y!!wdsA18 z%xq6TyXU*SlDz+(IFRt$H$p~DvgJn?{ql&U>Vx;aJvtU)P0JwcMVVTUF(!o4OEf=1 zDz3Nb5!YMS)|=AsauIb?|4dlJ)@ev^^e(l?duH`~+w~pC_)9Kt{v=!oN0t z2$LOJD#p7ddeLAfwajqsSYvb4^VewzcY=X>mAtHcT!pPpX7BWl?ot=(*c$%wk;99$ z(LW)?qY?j+LL1|;ZgOl^Q2d$}dnPL={sUi9RnB;>NMZfcw_GX9YV6D*{ry#*hh;PAikyzc}^P!au;O5*dss1DRWP`_^d4nss+~)`% z{<&u%!Qcw$#PgH1EgLHS*Y1vOSK-`q+?6)6ha_+N#QijBiaB0cfBHPx4_Q{s=dnB6 zmQSv-@HU>P5y3Kgs8by3eq3!we9#vtQK%Y}ZbUfUR4QlpEc2EfcCpAL>(M|?x$b<^ zkd%!%r}px?QvH$ah)>{dg;1r#mXUJJ#=bGR-F8=(c9-?Zx`>5aQ!%kQTq(l&aPZV9 zMR#nQbtdWwsTZVn?T$|EX0hXW-#DvZ8RG zY28}UI!OP?)Zxm=>W%U;zSO5;0IPRv|9zc6r_pfI&dAwfHzD=u8$+B%QD#PFA6{u+ zUhFl*@8;@P(5tCdtyDC154sNy6|~$Mn0>~A4X(tqBPwZgHw>@4%O7-smj__eX-=57P=cSPGZg&~R*(Lc>gNMdm z#KqL-oC>Ms>{`~#I{jbjZ@=@gDhxafyN6r-dMs}}WAZ`y?Dn|m(%B*PLmrih4zL;X zx^VK?maXQQMS5`gDTVEJe)R%3a3U@;DBYR6Do4zOx?yB)3jUn!wu7F ziRuN;Z+Ap)aPodNuf18-+&$l(8*{5$jNMpzqqtOpBBHDiZ=NK2~_kaxHoGi-fi|1)#O!bLo8 zYk!5t*z^m+c^dZFAGH6PJ%6X-Htx9IH$_Va&F{Z1C;PjgR4vPcZ=C*@L*IBB+8bURnQz2ITbBYk5 zX*d4NxP~f6PYc4QDpH*zhhs@LpM!Z!+Pp*H99w)%pMA8jURJ8MDgz)-)Fu5Nm zsIbm&iKIUNTRjQ#gr66O*a>2BcDwu=lb}uVh~)(j-(<+9DKYi!mPX~(l5&U{++TNr}9HUiW2%-8BjuZaj9 zzwheO;W~V;XTi}uOw7~Q0qW0FxBZWT7`VYJ@zU&eLU7~U%~na#(G(=&T@oM<9vp+4 zz5n2_DdY(oG)=8O+PEd?v=C78-o+BlQGsh?pwN@)Xm!{T&+*F6EMGxcz4(I!_WuA+ z@$g?2!)hEYbN6R(IKw=5*1u6aU1Xg!LDE0wjR-v1tHI3-h6+Q-bPL`+9cWdjI!4^4 zq{v=SJ7H7!fmZSUgG!%mH=jL^w%*Kt4r-h=nHaN+3nLNUFN(yMhi?I`HY`LEvw$E( z7Z4op5I>SYshkEn{s{-8TK}m9Qe^nF2U&!#Bo2T&t$gJ#FdpiB0hZW{w6LsJ*RqoY zPLz*vGNq`IJ{-(V7QBo?!uPxWVt#0h^ApxRhgqeoqJ4hhRiIm1@=3|=TVM^_z!+z= z+oAzd&>1##(+>%NT5_6eB=ldr&R--VaLhKqr9MQ4scw%2*D?%t+R7!@6eOiIHD~Iw zmm3Wp)=AgT~FJ<%m?jzb&OfyNi(K@aa@bnnCiJZ0FQ^Z~eO z9iUJjZ%4_$@cjRt6n?_=z)C5;x0V3VMF3YV;jpD(BnL4c033S>YFqCRb+TYVf0nZ6 z2=)`7-$E^g*t`Uvt^NkQqNqU2(2Ty10P|J?`x@hU=6`?2S1gqn{HCLBa{wS&r~qIs zCyFV;@G>m~?S0RX{z+y^KzN+P@{fDy4K<>CQizW{-=sD#nnpOANXrTN-{ z#n8^efd5f>LczWbtklyf;-=&>j+Z!qt@D^!{9h;*HQN7iN0zih=P=Ft<3KLp z*U1n22nrn(K{y|8P*7mJ=b$Y%)B;b(#|jEtlFRd1Z|B|Dfg}>MdGH4*jP^^T*X@2z|i^!e6Y zFZ9aHM$idAwcP2vZQchVYco;OtZ`jqo!^#hbZVNrxhU_MSFd2-Zm^f@N7RA09RY`p z4K!bOJ(-ksqQQ%jN_YI?r$KE_>7$?-akta;0BwGWBgF9*iS3s4SoiqwoT-jgsK(fg z|641ek;t&HkOviRTMHg&Ws#cC3TR+HcN~S-t~tMeaOSiiTm;6|?cLO-zP1X{$u-2q zeq`2t=ve1CJRf{NsiqQY&$04$F`bT~KY>M)<<;@g4N`(rTUVz7ZB7S--zCw-kE#$F zW#`_|z`ks`p1EXbB`)_PwsXcgTP^#GKRolYva^4X6^+lWug&mnsXhSwH4_N3GB+b`^3u4cL;Yn6uPZK3~v(N}Aa zM@9D&Ax-?sO#ZBLFEqQH3g^|zYFfLTH>6t=soc33O?@}1#_C7K!n*5Skq16}ulFnv zq+#Z~a)w9Wvo%f?29zUZ*bSi0ijI*tOS_%`xXHdSFkUKaB@;Rt5_ZgY8&K!y6GT*V ztH;d_0uoW)jZ{P#){y-((m(o_Dr>3Ym=Dj8y&rqECnEn;sx!Qv!#=iP@q5L3GyAL2 zEyNd0&o)j2E&_j1a9x9M{lm_g`Yg~mHCNYGS?ITe$ZaP&Go*9`zUS?PI9#C>O z=jvxLyy6k!^<6c{0432TzCRwg<4v+d)o{;@3Lt%>_nWn&Ob3mQW)4w=e5C|wq}m! zVxeqrM%&A>JZ*7)hQLK%P7wC0=w%BY_ zARn_VzQCRG`NI6=g>-UUnwWJ@#kD*kI9l8em@Gljyr#L>gC0c-#B4^;2q;OrK@&^G zGoq|4Eq~;XIfQ=XvwQv$8p^lbYR-)(kkFHCRR6O5gi&07Dk}T6>jgtPN!sZJtVlmV zw}Oh3xdjeN-?Wn}Gn2_a3e%H(;NEz;^tlRmwqw_g(dE*b*J@R&L5;*;IGzjx3X8^o zC+9jO|M9R_32eJr)OG+s*ZSHj5?eL|EIg5?V;knzLO;}>QJWLCp6zJPs*t+Bj0N=a z$l)6hZdftbFK4^y-O1)S-TvG@{~i8vCI-%m1pJt&#V&~~yuv_Gs)+ZeV}wc+`Q>I~ zm4xL$_pd_1HtU)?d9cyCijmqN`RUZ$p(lK2rCX?aU0KA|q!pFJrUL~ULre7sZx4?S zD4UQt6#dERjo59lP9a5*#mS8^k_676 zPwFrLVG;h-Z}yLyQmvjr65n|3C>mcJ&OvW-tU<&0nq}cf|EfQxK|etKW#)2hdGW|k z&Am&l*|6`Qq=lx_mE&J2%^*hx2IT8Wj-2FQd3)~)E(Fu$SY(@M=-u!Eh6_R3AH%Zuzwn{7M5Y0~S5xn`Td=a4-pOlZc^&Lr={b@;NuHR_ zIq$e^@T1b_9&*v^pX#)Lj;tGTFG$pRZlt4k=>TRjVP+j-nFBRVyf<>lX7|k&PF~Vh z>Qb-SmC)k6HhMfb?9TQ!)s~OI4eFE$A6!Ve1Gd|eAvRtc8xMRHDMRuJ5FnEcH4t5uZXK*OJwo5($dm8Ps#gr^za*$iez{*B#SQK zybk|iH6`!MFye3u;+K|`cyPb$?5ssI9QOmNY)rT~o`-2{KI_t~2#NGT{uFbwOiFq4 zZ1iQTooWQ`({24yz{2QG=4}k|p*GC6ZMLU$|10XG*-LRU*!~C zjDCVnK>>|x8;@hU(PMN1#1r6l)^ z73%46>=}Fux!s8;`U8|22D}yjunsV%c!^Sy%`=sMUS>2Wp{$HWv# zHA_NGX_OlMslWyh+H){0e}68IA4xTcXnoN2R4q;S>Ad?9V5jG8CMG6Ja&C51Ri1I7 zlxSoknHp5*@bZX&=|Z&fNpd0>@{wuhNpBS~I?>n0MYTaY365yx@b95b$wufSTKZN( z(KEIk+bcVetp&bEYGZu!+SJaeObgd_AeN;^F;`6_t=_qh92sY5!W7NKPSPZ0Thg-d zE`}^DiFh1<#KFI8y-MNt{<4aR&V2sI7sepkXnt!LNS_1P)oEGhQaFD3uX)68avDtU zXo5Xvb4JEa+}tVA*>cf=9(9TC0aZ987Ff9wyFHU~%l!5q0vfM)KR%REuqMg+2Ry?6I6L zQ@66P-x?Zh&mW5C6JU!<0w1LamB4toGl%V_=5k-{&gCY$2LYR`u}%&7%xac#A^1lR z%E2L_zwy3GsbC-3T+>J zvnW-!6aEjl5eElM@*y9k7o;~|qGRDyS&TKVp@eVbOx<}4PzUx*iQE{@HK}cyejF&T zqcf>EG4tpy8i^Y|6{AzOF6SK*kU2q+mQeg_Tf*P^vzI2O<~8KiVE+WV>H_w(ns&t*n!OtL0};*??NIYir!pT(l`Wg?k80y!=LJxyM&j>5$x zIBanOL=`L<2clj2!b>TLflVi$eD&x>?aaR*#&RZ!P(BJDwlRW3%=k(`LZdfl9kN&1 z7)$Fh=%6&#?6JywpS&X{HnvrvX1Fl)xf~uw7x!wKvY7)LGT5C9#OXN_$CkU0gkoac zmjgT&e&p)tsOEvW{G{5*7Bu_rADYd)Vk=qCmd`OlasPu%1rOz0uqjI{l`u-Ca#Sl> zrazCH0tf`L7XFx7h=Y(iMo*FcgZpb9>@cZIepBR8GDvH=O4mFgqW>W(P;$HxVyp}o zr?)H|z+tBb+aMIhSZ`GEec(ut$!;#DKlH(Yj5vNK#fW8ETHG)Nlm=^@z%w+f;w6uj zD{fyLop_{2cOw6z=UYHy;=pGPjMpscK+RG?LwYMPrTy6@^aOY=#;PnVA8)BhY_Jm_ zHGu`jpH0#ebNnr^0>v}D5z<|d0LmtH-haC#0w1T*?sIf>CAna1TtjEq%Ya60<#~#K zdYdll1CXi@V`c6i{`oR4PNRAAp=xD-# z?#k%&ztjaVF7p|m1BxQN(s$^;?NQ$N4mM)ac4Ol~=b%Mup6>3BmL~B+(#N!5rV0`ig>DI>8!Y#^VB;dm31-1_lE$T4MJK>FE9a!k!Z_&>xi?PcMzcekZCd8Dn_ z0@bXF25zH6^4_gLdIS2QqlAX&Pi0l{jEg+DvvvyjL!ubHrlrN1ijXe?>)&+NEf&te zc?sHdd+boH-1wspCy3~#$;xaN!`G*PIh9Sa$LRSbtf#-uhy!y|=?f#&GQKiQUFG}Z z3fL|4)%Q)e<_Y9TPbS7nzk)kPa-p3S7vlIVZGYlCB-zY8T_DM-F1NC=;i$CI^cS89>)Yzn>ya(Q(r+P`fhO)T# z`L9ujLJAFf(tBgAMZy#cRat4i{1X2kQ&;}`|L{NjhkyLzAOF326JP)M$A9zR{o^11 zumAP`{olf#O8tKv|M-9YFaOgl`E#>pWu5-xpM>z|(?2g*(M|I|3GttoOWH(f@^48Q z=404Q|JJ56?1VGIJZ=A;^6bvCuET#`Wb)rIIP^dIIQ~z9hfhwlwDa=kvsSjt4*Pb7 z`k$%mpMB%{PlCe<_TRAo363af{OzEX3x;E`;jl|C$29BUGWmDbpIfi#IF()dr+*jf z-!A`#lYfp(aagB+_QTbvn^89=>G=0l=-lO>g!E60gCl4oguf34U)r$wd#MS}_8#^(LZvWYo{yFfU|3+dhq&1p~e~t3r zTY^~qU%&R>$7=ld1@M2TxsDbao;`2UOokJ_b=tz={}R46te3wN@@E{U`S_Q7kKNKH zDVjeJV}2{jIeqtGj85M``e0u%H#K}iOYz@_8=YH+QCjn1{LO!D{Kgy3`;9fhXI(r0 zl{_4+(rF&M@4rtsEFV6s%N#Af7@i+3Egsh6T!NHve-AWelAvz#9dxLik+4(f#-L^D z|LSf@I2FH#`1SI4tACyG&kMm|=s#Tf=jr?KKMnccSwOc=|FypUk0j;476>Knnsgoy z5Q=|YPF&f4`@0_hwLWS3@6>MpN!+i@-+LGTnW$6jzohuDr2mOdX&{U61Vl{=aj{_g=X z3Fi=W^`Ea7xo`7-UWC%+jn{@fl)U5MpZ<0V$;si<2YrI#*$*iCPpm3VtUx{4#pfF4e#`-DbLKxUe7=S$x`q>cUiJJZe45aAP1+=`>9=2}c;a=p9p^@H`Hg>Dl@rhY zw87mu{{E6=C)LMk^;73&B>3H@=%E_hcA@W*{k2uDc?Udy$KEgXD{y`Jy4R&WTxMtR zqR?TdIT^tm@*Y0B!%Vw4i4&_gFPl4OUH_E0cYFjYms`B_eLk6zH{0n-7SssWz(XYR z^+wI~r{j(1o~ua=`*_Z(LH&dA@`S3x(AU{4FN!E5}=%^N{)N zB%uev4Q19Sks1`n#^EbH$zmP}e)_Z5EUQJwn!a{zAc;&31r ze&;=M?VavzJS%Jrc27H$n-W)s%+~~nAa6tO=+_uBNJ#+xRD#9{=*m3BQ z3(MhChkM*%n4!I85Tx(#KyFEL0taCH(RpPjU@$ZxJPMqbIMV-r%>I8mW|*a|F^}X| z5BWfQ(xAoU%VQU$=6$TBAxp0M&0jD1c{@$9H1dN}uVQXIdhY>ex{o{%W$q^{&#hwC zFZ1lb&v^XC=ttNO*~+C^dt(+4is`P&aM4Lf@i-C}uXt;(uy7v52J0;2%km+pX>}MM zTY8LmpjC#FW6H`gA|_ehgMa1SA{0UJTPKZ>S=$QD?G?eqICA!6)7=(%d-1s-IR3cQ zZ!!}?@$JE(VEevP?m8~pnck@z__(~uP{`p}fL1DM z_?hLd5MK95uczb<=Q7{YE>K5q75rA0KbLc}q!zc$yum)w#tGiF)SAPUJm5)7f&bG`;~rGVZZB zY_hqq00TbeMCYIauXzpd*k$er%kEEZE}hV*Imt}2e=oU zdUkS)FMjpmj;%>PvyS+Z*j_6X?j4trV44-bY{mUMiKnTDvv*A}W5Ow=H4+WlcjZ(0 zoOY~;jA`38_HW19BVU0+VH_aV+dQq0q3gWAr5Eq;e0w=B!H!dG=<+YYK7yCt zoMACg^Z3d|Bx=wGc8wQHt%{B02KefiOnZN)6`tk-2Qwu}zTC63 zL}#oOu_1;b#mZ(6ZQYLE87H4+)8%y-*7g*i{P#H#Wa=)L=qa~g+~xIC5_AjAXJ-3# zhI+e6@pYB1RdHnn6g}RyO?x!9-o^$UFVUT1)2e&uuR*t7yd_fEXPdy#$}x?ENmXY7 z#2{cUq3%~0<|O;|iV<5w5jq@xks>;ad7A6`yky2^nETbJUfo%2S5AzhDrNiZvk@O7eb?C(v9d(Hd2I4hh|!Ag7H>!(Z*3puGYO&{VAetV>hRNi{z>GL}0 zO8&W~>Eo=c_f-*I?ak%yJWY?^8$7g3V?BA(Kcl=5cBkgKfO{3b5_J7NJ`ZqaWg33= zy_nDqZL>Ymvb%W$t~~il!b1Iafq+VWg}l|;{myl+z-^wu`2*W>9;hW4@U{L*Fpn8@ z@M8L7jWng4_%05Uya%h_;YKyl)OH;XGG0+^4%128q9{stlUVE8&9>76?ZrK51Rv%a^$j+I6Iavs zytANKp)%T&F*{aLb4KDSC$iallFE|T;ofj58M=;#)2W%Y28Tnig}}xKJSwm_%Oa~M zpbPEKUVKTzep2P^?!)_d+urCdHze=NX<|=IX?*iiANhw6PjVtG%D3>$jjy+7r0Zy? zpAkWf$gET`d6ES7Va+?Qsid!7leBYQ-;W}xwG^9n=Y+N$zBV{FD-J;wI7gUd5L;oz zk9pE^&)@GJi-*(u_RINpfDh_t-}>=IUo>G|r(w6V9=Fl65rieH@3`c}!v6 zdC~$sY8U-AJq58O2BW_$;hQa9SbV#+RnFPxwsB7`HwhYb-XKYm7SA4|ubF%eGK zG2Wd!e?F9ZX*H8SUP9ivB=(dpmQ7_l3(K0g`M#g=FcuJF$#;Sv+G)+!O1xo@6(Fb! zzb|0?zWvW4!dE!U?-hNhnh&*mAw%%oCZ?(J)H4Ggedg)IvXLtpnL;vpbnJYIRN13H z(<58xNDMXfqqF3d!+QC_F0ElpYmZM$W;}iW@Q?e8dlU`_@fF{~B=Ha;A)!MHjqhDV)*=Uqq1z>Wfl}j> z0_E-_cHw=reJ!@Kp6ZTyMjiEq1h44Tk@-tr>7 zmkz@{kh=WhH?*kAw@0L_I}kTb(>^8OhL5{+WC5v70w0;hkbm=g|GZ!5&upDkHd0-a zz3cd~h?e@LPwp7*vk56taDB(y%gH_Et@yn5Hgl;~*VoG9hQlnP7vpJb1& z{BG}7dW^4~1V53OY0s&#sJ0%wZC&O*#A!$4IaLKG^Z7ZJ#4Zi{utmV;WGgW3F%xN% z{JsY)KHuT!Y>jgUllQ!Vx)iaTeLaO`fe=tIm?xNz%??M88paXJBp$7cTz)KA^mxy& zA#tDGC=Q8OBinvcs@Gb;nv&~{S?qh!7y6@j9;IUmdOv~1(@DHMzMim^3TW2de$%o! zf(OEne0%O!iOc0qzjvS~J=r=aKWFP{2R(%RUmEEnPjp8EqSll~4$V4Vr)z9PPbIL$ z-~|JKv|?(XY500Sy!YvO)}f%EEXt6r0WA~Wd!q*k0vr>8Q?b+tZudh1KbmdtnV)+a z1ePGQ3XH}30XIRbiIMhD>%)O!Z@cKP0XX6#5=-a;p?<{sO1(!QqK?4mNO(U(2G&%p_F{8r)H%cabnu3^wRoB%LSA-hx zhT|MYE6hci8p}LiI7~sdJ4h)xzxsTQTh&n9j@@szmGhi0c#R(B<<5tp;w`g5A(@nZ z8`z%GaY=7nCkS*9Kb2m7^ut1B54G)Td=~fHlP@K-vcXDW#lBqwy;9$$B}p~F%N*BR#QKUW@_AHLTKBD3pZ(A$k?3Dn zm^7I-v$I0B`dS%PM^X8;?8>4HntSPXq5mE{!5vol7t3*jtW;z=x}k;^1Z=E)t)*+% ze-?-jZnvIJX^4?N!@xl#CieyF(56{U6T_6S+61sHawdY{%l_|ke3CV@DZ-}Re-8N# zHxusS z=Ux47UXGzS7&mwJb!E~$6>}9vg6p;WU3u(^q3s6z_2lp6x|-zG%zmB#)zZuGNh^dL zP2ks#)JK1T&S(dTo!z`Rv5)fl2Ag5GpZW=%PuANP`RmIEJxcxouNA|2Xdkqq(L-Nv zd#Z$WLxE~pAkqORK7K$iv{+ZpDDV4u8M^VFXy4-fx&sd2dJxL#k@$)5tkJr<^kYHg zRx^UA<(!0%B`BstA%7pmAn31foB&(!%k`TNwbzAjT;wBUyMKC72?~Z=@dwAX*^=Ok zE#bPJI_HR{6;4XqlUP_*_V6jfmKwut_U6UNPVr)n#yIwz9K1e&tF|-*&k~#-w3vhO z7UZ+CP@AK3YecYY;;cgtRu~TAfJL-V)Q9tY-(KrWmcNNigADOlOCz-dC!ye8Mw&_O zsc5&R+k*;w3x z^%*@IS-Y+aVlT6e1mqU{wK&oFUdI!)ehtspX9VAGVd!k#u4j*)ndy0 zklMJ$4qpVq5=nLBg?cWeB#H+L2*yYJ<2-7|wwO{p>8oneIYNQ2+|?JZ_mO#6FEMBQ zsyU4S1Ly`;N;ch(r0eW_0c_4BQx4??sxhE&@KbHyWyT0b3`zY8Cnh<f_&N4^6Z|_WE0eh(qN8=|p>;c$P2_nI9Z1K+`8Av9&r+tP?;{ z6uW&-I|tC%jnPK-tp=hP0ZtK$9MW$TK4up3Dicqry%82DJ#~GSIfJX~!G{M+gX0(N zUcWJdZ8}dN%ru4xSa}C?e{fBgL=w_=YAHMPoHCvw!e!*hWLY2ySx?3t2y=^hkYwcRabv^_`c^{CTzOL;J$}z%tk0q zHCKACPW@gf09|t`%zj{jz&5^nsMx$rn(>C7{MkrR?Uif9t5^&W&I7EUu4qWlt*$#U zuH=M=w&aUrYuOj@1Qa)=)kW_@uDDgj&I1@IK(Htw)C5J-0U(3wlh2=q2;&3o%;{q8 zzf?9WJQB0Tqlde7OF2wK{w&;hm}EQ~?;kZA&dclZvdHx=hlIo_3Q2%o$-OI)Qcb4Q zKOBT5BfUBLw7Z8LU44=EYp;GtYuMPEzV>~~hC!3^?e>+|=+7gTkBR}9!f&FvO$Zlv zZ`U^Xn2z$*aGGWA`BM|y`ub4s()Wtg0*oW_pt1_T(8+T9J%=oV+jNUFz_Gv|kdWu( z0m?Ce_Y^@?moMr|P|>`7K);~LOHdO#bOGr%3QeT|p5t%{QUL)c+C!Hw9k-viYXV*k zbME6jCK1Gdg)VoRY0wYAMn?6;C7xei?@z@6U(|x*tr(kOPq&gq-JbTBEK_=+y8zmJ z@0^sG54&a1{ASsbgFC=~7cVosgPbNm>Kqe|n7Q03m?g1gE;qBS@EW2(JXqHYos~XP za9^J?ed^^Z!d(~_6c<1q2|xX7AgW=wg3}qaj@DEaI8A?LQo$WiVtMzU%>Z?A4;d*~i11H~2@oITO)u`Ll z@5KF}4{y7ammDi=z%~GC6k&aNW@L*BR(O*oLP80k+&MA6$zhrz$FVTNa)vZdik^lf zF9vaW%;EV4syulEhXa;`ASnsPC3_M#v$ppSab14ZI9e`mNr*(VW6KP2Id zJ8tYjZCS2&9lm`a(Dey|gog?~@6o+J=s!zS_PgtiqnJPaf|RVW;-|c@j>}t-9P|{D z@=p4`T_3laqD_zbL9^gOof2c}=Qdf`Q#1qvdE{guKXEM0+6U?1-6SGZX)NnL^cy6Y z`qk7+GQK29W376gm!LFog(J;-aSuHip?Te*SKh5Xdm>o;XS+|45{O|GMCPY9grZaW z*tHZ%1~eSH*zg~)ngtDL)^DCIqzD+!h)uw}l5t@lAxWE01{4&YP6L^U_Gcl~VjRb& zp}t-S_Tsv_6s&ykV73V`cTC~8I5Mj+*R|zP?qmN^jH`cZO9>fI@SjPR(gC4Fxk4ZbZPrf7{y=d1rpnDau8ax`rj`U@Ml z83!67Mt~<+R{j3a9fijh7S}x&unGX|T2tji&CT4;&XrNyBmd&@@CnAaiFVw)QA}g5 zHqN@l<E;06MR(WoSh(Rs|?AqZE%Yl{X%ISVT{dabr=_n0Y zE=XnVR0T%Ke6kV7c|*$cchMj1=SQCgG7PYjxItJ9$$}d^Mn`6h@==!|L~Bz5dl#p+ zDy0RsR~*o$FEER*A!IYqvPgBl@1hF< z?OWx>;M&N8Xe|fr#63e8bJ-dn&%~85f!k9FmaG&*5@^0bmss#WcoI%Ai{mG!!Tdve zC5Qw4m+8wqjH6eHkS^}D1kw~pE>^_^Tw|BsEr;~IFOa^bt6T}d^4I}>1hxV)`0T#F z82toQoTk6Fq1&^OsePvTuh5h3-iYw>z8{=~T_Y5W%@kde*Q@1xrLLhG*n=KbA)OD; zImlV9F4>70vs*nO)h^#v$gPPQtf0>&_<}bdI=deP_dpIZY}Xxhtk9>^ z!Yr%>>XL6Fyp_`t2fzi6+Xx!rMSfY9rYSmdW+8$^i5WB~zfBh3?*p9v>0X&%fxc>J z^{vC;CWm_;<_R2j*Y_b<59AU9O%bM)_Ow1%R^~dHys4xDnochBPBLwRy_oJ$I~@dQ z!3wk(9(ts5h2YSdL(F8#n$hJtf+RNx^dndKiXyf+J%i^5Ev@X;L3ZKfD5L27*pm1c zoCaezR)@rnOL$$<;8;Z zmcFU1bvJVPKaKfD;`+@4{+ zCIB>2JXenjA6N*eanECYY=N*Z0_fi@Haf{qnq4j<46~eL>40c%vZ+llYNP`QS>)k0 zTBptE4!H22Ww1O=7ErG1=8yQGoYVdct1w(BmV2Vux}z`bEnWR_i%}NBe1o*0c3@kO zQ{wj@Nc8a@A-J!ELvizIUo3w8l$t2w37*03yu=T};L!CiG+Md!yWgw2 znat%}dR=~FHiTZPSzJ>E0Dx5U-v;jG7vgfo0ZR&Y&|@(;=E^TR&&2JCR?19RlTUn6 z_#pFolEgWCdtpJ;`j>$Rti>8wKUi;Iwc~+?G;KLh%Q!A@HhA9?fdgoq=h+=_iktWt z5n@RJBngqV8jHXn)R00ne1W>n-s%SvWZ>eeW!Ul>zjeTPV%OQo$GtbNml!>8GC47Q z(G>UPaufjj`eRa(pAuTmLBGbaE>P~H#Dd4gu>B*^CFVqWq&l{{*JxU=$x zH1nUWHJ^5HNg$!Ou*?Pc4+2%~d^A4J%RLXka}M2MawF)A%<2eZTKYxO4Jmzq8e^_B zmS}IMb$@HeZp;^Lw%kWSh+KX(Ly{QP8Z1Rvkx9XZ)StLdGt zM@$wVXJ31DSk``I_T>fNm}kBw01J2kKwDV=VlJolmV%fr35bUZ*uBbc1{%T@R|`l( z^yd8(IM#WFjy+_Mot)PI04YhEFLa;*w~Clpqi&G*a7~-Gy+%5~ImcIs@?q*ZLxtE3 zARzEWDUFlAV}3{gYjsaCxD-vAWv@>LH)BVCD9HC0pnRuP?Bgv&ryV_=dN@8@W85k{ z1fO*?Va@T`xuqt6fGu{m)kSUJ#%W>2ZC%$WEds&-BL;YTyYAGmtlBp}eIT5GZxfF4 zg`Uf?msY@~%E-)J?P7V9P>1|IeXMTzwaVOwbzds}ak<^Ur5mj6MpEaDCB9cc7zYC* zhx^r3sn_>)n=W(=DdlUjQ8MH?A@%bSO_HoBZI@bvDPhYOLtZAz%QEJ9o|GPFkH?Bo zWH})cJeV5mzKjb!p2g)Nz)As0;++}P-|4h3XF&E|cKB=CWf_gdLmjBOAVV;vR7N+; z$WSm4EAaZKRe-aJYaTQKIb|lT&1?sEhn9!N=Y%Pq%gL=oz=Y%kFr~|l+hSu=wu?)< z90nN(lc%sb^7feYQ4_!hK%In9Wm#a>$&Y%>Omm&4m#oC>N%DHX%GB(Qmy~9lfv0_i z;nK80R9!xp{N2-DNi`?cc^rZcc?MOEMgqqNSS>tu*)9QNC}L7>fo0O|{n^^EUjrW3 z^O|KHCIY&b8*Lv3pqjuQa3l>lro}kiphjaHA%$R87tI}Iu+A1XYXSl2EA;qAukaf- znjuEExk6?^9UxB)D9)>1)B&P1Nvj9E>me253RC@^mK%&%v0o4Lb^VIg{aO?Lc8gYxX`n4Pr-~6x9$3r4k>p@6t5THbA8$} z&Z;C?Ypr^x>C*MKL>iB|zDb1avW|e(STXjeH=Vw)P` z^bQN$>vy0M0KE$GYltNSzC}2fdknY@fZ7xN*m~*t?bpB+f&~0u-5s7blFDj?Fxd*% zP-+wcP~fwfPPiL!0pEByABH-8Y~+7m%rK8)@?lwvotJNa0c9--8VyM33Rno7aYfDx zY={>t{LI+b1 zt&T4w-tv;mAt_pX6iWh{!-ZasR{4ZP`?)0U8~esH#~c$lVE1iU9r1pp=NIxYBOM$n zuMuj}v+j@w_f`5H)~{$CwTSk8{NqPpSP971DwOFk1MuVYPp2C__MGH?@k9UflKCn1 z@A$ea>TUuF=u7kA7|fS$Wgoli5_AByC*Em&hUwTi;5dn z;RCWY24utSLm1==OcUKY)a{ze1-Vp#pg}AicTPl3x-*l>LVRW$JRQ~xvWO;dcQ%=z zL#Y^^pxx`Yw^pAh%Xhq)_GLDN6Nq6H1vt(sQr1Uf+DH9fUq~8VSG2&A12(Gx#`?n7 z?9_#J@Vf$3=&PGpu+q~(DQJ|xPLB1j^hh(k@sW?mvJOTxht_|Kd08H}p?MW=V!+$C zfW6C9tZSV0SSV8w?j!Box{SFRqXs13+K<6LN-9JZ&}Fx8%q1Ytpm~&It45AK;w0eC zMZao%XB1--Fnn?W(<6U4`t#_6dy44tvduS>^h4Vr>*mTvL;;K1 z!+h*_#t`{pfE)W4Z*Ral0v5+$A^oRUvOjigHVjh*9F_sJ_A(ETDXU_{A9NjD|7B+& zu5098{dN&b6+~4DoT*b_tFa?IYYm{&(_Bx0Sd#Whll}e9o}#fFIsdjd=36rpUL>v) zIV^9^0ElhBtYi35DmqJFj+WX&oYmjH)A=DbZ{IhvD`A>n^N;$1gnCGYfXFWipwSew zqO`ipKg0>pZg9m0Si&j^5_~Y zkW8K>x=&bKV(;{xiVQYyX~5ARp}CQy6vc2`LLn9VjzPsh3#?gS(cM3*qd8#(=+>6* zKr%dvksPl~s9&^VSFho%*rzlq^?C3>@M||&%g!qaXIv5A5KQ(&H$&FP3`c&~O1JAnpT&6I=uc8lXJdfgx2p~jH2gn$X8uy23<^6N;c0Bs@;^OL0B z!xm}fn?4?XsqLWP9Z|EO~IPy;XOhMk9+{61sbVl_eRVcY#t*a7-bH4 zQ{E8#>BkM>2FZ=^&?J98#|y?`f13^2u$D25Ua386Aduk#$dQ~v`p>c4(uth1@Jpic5uH4 zrWj<{252Ohm-*P?xJ{Mc_u5A&wnTAh0S4`ag!E0KVnYR=8E9C6496jbjprfoausd2 zz|HHtC>p!Fc%B;s1-+~LL;+r{H$F@mXPL?CDKMZx?xzfVV2(0U<#IYG7bLp(Y^^ zAD>}@)yijUtNE}pf%N*~P>2F!Bti(wT`S0zW#|;Ms4p4J4w3k4Jg1_lzEJEJGNblT zQumDgMvd3#^<&A8ak?zCp5mAQ9%BBgZ+&9+17dmbj!-#%L{c;qC85Yro93Ki+znZj zzSwN`V=O3!At?eywNBoEft3v}du?o5*d}rZ83vd}b~mj}R?j<7HR^N}o38hb!VBwd zpCBE*4=%QNJ*)_FRE>nk;5vv4dd`8GAqh0f^Y|3N?oj?zOlWyu>lAQ2fkp9c8H8CO zwm?V!84V~|dcMF`0Y54P@$ zRvZ#Sg@ZYWp&xwPR;3X7#1soZo#*Jx1ZmkuGi;DC9jZj$G!f80t`u#|ug3yf~U+RmjEqs)*qn?!))4jD3+~(VzTkc=Q?W8#=q3pZw5o z)mH!pLLdtfGAS}tj`_?C{3#PSzsfvXz@DLR1F)1HD)Ka&j+(zwcirrVIZz~7jBx`0 zbT7^<(|@9Mb}IrKEup6`#=)ZjDU#*dj#o*^3!o8;VemOLnM<1Md})ArHaA!DTX!BX zXv!}>Y>4TNqH4zEH;n1VT6KYMa4ANLU5iQb9KSPfV#y(U3mY>X5@geWRhdPI+bBy& zXkb%Ulw|`?e&`?fXw1~bkLDi=pMW^k&BZ=$DASGV1Q355aUvzSj&okX_|#00(|cIj zcZPk6yv5SqB$F>T0=O96_Vx~KAqBw57_#x>l5F~hItw6jl@-!N3HUm|ml7x#g1RCOP8e04rDw!&p=-mL~CflIE$`VY<-z!FhR&{O;kPv@JD zpGj3Cv2lnmB%~JQCsE`;X}~{B7G>YTUdT7Cj_Llchbzz$(;8EO|K?}fd3PG%{S-J) zk2~W78ELfch`(Y1HMB;)DkP#-Fkv;At4EJ=FUNSVfeE*PXXg@o0!R?8>9?TyGC!{4 zZorz5PnZYU2(v_t3+BOiZ4oDyENSbVFx=|^ergYN$IF+aZB!efY-FsZ<@^xWRwrvq9;_904QvLA-hMUcE$JS~1g zOmv8lFJx3MwI0_uH+_g3APVeXfujCF?;>30Z&;y%Q!EGRCB&IYZq^}(+Jg_casF+cXW!Y!s|aR*sa{t)*U{XPRie?0bX*^RBGaJL zqu0w@PJ>nCKJP zmOAhb!`UB6`h}6g*&yAB*m$TOYD>?Hd*JcsrF7IUF;3i?lLsFn4v*V6#!KpmFAy)^ z6IUTo6oq0K2&OCKi}2tf0-pQ80l;{K z>t-S+Y|RX3WXu{8#xx*%zzfuOh%D;PhYb7v!U=){Cf`1U=Og+Eb*Db~^$yJ7`niEe z?CF0vQWEejIv+9}GN}+^mA=Sj-eHLXo1VEe7r=5rNqYUpq!0o^9$&-;S3~16EZ{W| z*A8XsVH0jn*!l>uN&tZX`b~K$<|qIRIF5j=yo~LNS+59KTUQpaLCizu5DKxd$H$CC zU^G>Fu@3>J*EY1#KDOr_Dhq@5eoT)OTEo1rQ+~mufq#n}T$DAu)`12~B1S6=<*CJA zf|uzOE30?ek1Xz9Fgl)wPeS-g7NY`m@GvKEq*9TgGDu>cBtsVIEe}vdO>-ve*mgV6 zavdK79{~L@P!Vtd+3Uu<;I7v`Fu{(<<4n*Pc(P$Z7dW9$AK7Z5W~CXV*Q*>@9)>Fd zyMgc<@eS8845vy~AOc_M4$H#@^caWSba)1tKj2A;g|6;~xuHLh;r?xM7DcF%1ktea zCuFJQIZ_CS$4an|1ymAn4}SY`)k<*}?*SMk&a+bSFu+d{)5gPBD0d9#6{3465Q8?| zAt*$zfdV2JF9Xfnht}UecGv_py&VJAjBk%}jj#kU=@zqXnoV(f?RBTd?j@_UjABf8 z8FGySE=zbg72BMR42(Xxb#rne%HA0((5 zwS>^#;z|`@3W{g_&1bWJDeS84&*iSnA5?FI>W&aC7x?>)7I9+!G>c6KpozV`vF;98 z1`_=6;mEI(EHOwG(vY`}=KVMh3>V&!cUhO5HVmTiYxn&oKb4V?xD{IIxLwF~Qpi<@ zn#7BKdSBk#R`q#>GAa5++oAi`^k=Svm67qAQofAadePA8tNhhC7g(u+xu4(_@McFs ziZs&S%NNK7(=}aR-A39edP56ROt%PrU3Vl`0aji)d3--#rM@hNq`WHO3UQ)r&4dm- z(KO8$q}d_Wgimc}wy76bP$%gGA{QY3LjXK9#DPF@mU?DVP)U~&zt7SG>e3D@5S2TY z@Gok8k(Xu1;RlQN1K2T#6o}H}eK(`{;N#2DfhL{-5UV|KKQE6ToT{I~`p|DPl~$14 zo<<{yluv+PTrPN}MGLf3&E>^REFivOSPmG}FTOHQzfwafF@ZSdK&Zt-o*f$`O9Eol zhGU`=iV4X;?Dd6!DTJ!9m5&;K#`iP;(wFoFaz~H9a6E-bN$eB7JU?K%WO&{;pfA8U zzj&HmK}{6O;%JbA9r}T-qQ_eG`!#?47|iVYxyW321;ivk;cCcx)%b=uq z)j_{`?g-J=ch~LcHaZNk3*Fsv=#Mmk^Cj~EkPrf%gB(&%w*CuG97yuMA0JzM+^pM> zA_la%jxTT>c+LCSnYoNU5iAAyvtK6*ts*0UTxwlTAdd3mLj(T>V_CquSXwb4_%?xc zG7)FLkxz=Pbc6iv18mQQ>)I0?_Ypk_v7tR0qQmRL#lW zIu=zzp$H1BHU9vIcRP~-M_vY0Y84Q5n!&8pw#8=k6vydC!l}QF|1c-zze%vA;TTfj z;>(zF0A&?IkEVa55FKqXaCZZM%Ab=;?b!8U=JqDxU>vs3XxkL%aVqgs0a$3RY~J4l z1&xH<6@bp|h~vSia)d&BN|a3=pLWgq-3z+ABRuqMS3tjfJ^NS}0ae=otz-Be5PF92 zJ_iT#fDpk1fN$0yRXHAd^|+zM2-_vXE<5gBn-QoJ&X>8D1f_t%EvHuzwSb@$FaV$F z2Fpg+RGSa)qJaupzIJK7OTeYxg7xO^UE5$(9yq|-#@htwh4<;n715P`kQjfVSxR?> z9(Qa5VhRrsWG?3Q%&1u#U(78MGEA;Zrw-Sw2>*NH))GF(k3F(<&{xzYh> zW#of*fVrS75&AnRP&+#G>Fa#zo>^7!9)Jf_!72PTy;oo(x%2A%@fLWzjk9%~UHf}II>sCz zZxb-7adQ&@F>Yt?3{a&`2~n2JdjhqKkmKX~n?}asZbD5oyqoEZD*Vwq3Q(R;06rlA zneACh@A55VP-0rd!uCi~^5Nedo_`c8U_YFBJXhV7dbQY$iGF8(O&v6I)^TMtD><=) zlxFsJgfQ_sut#+Ad+AI`!9GwZgsSyXO>-^F1j)cle(q#jc^0SLSBvs(3(1)~#mF=J zEj8SDo?njwn%{^5F&EUe42}wq66yOD76f2rh=cQxpemyn--&h)#{@+K3ygZ-BVM04SM#2?9LBxd**YE{;PBQ(Z8Mnkfr7ew zy_mp8Ka__$0a_L4@T!yt`0mhb9@AD z3UIr9O+IfI0QF083j~`)@$hUR3q0z}L<+X)%%IVq8t`_^>jSFoP%UQ+aXcd5 zA4+)AoYF!8_Pk>kqloM8xA%M!U>=~Sc*7_1!0^beFemVsFvC#wxiOV`JU4}d+Q!D! zT&Pvq)Z{>>%gs;n%GxLxg`!@?13>s*)E=2oN%wuM!2EElkLe2daN3mmin3tZ;2jt} za5^G+V)ii3mM^4D_OpWu_*+VY4Je*kUJhJG)AjTyY3xlvmHmbIewp>=BsfqX<*?G^ zT_ z(j_uZrV5oe(@mBpxdO`*$XAmid5MRJ6b44VENm-0?-_T)c?w>Mu;>tHiZ+y#UZhKd z-at@6VV#e^v@j*B3eX@AQuq80e76I7#ohA`aBH;(4$b!l00Z1H!+=O1hS2keZJ*Q~ zFqg~bahnRvD1U|8HGcFAf`yzI&!eWHvi4EiIFLZQ>j>BHav#^B_;3dv3g0zgER@`9 zLpBbte8O?S&Sg+J@~c5upFVNfJLGNmKub5MP5orr22Un!SJp7Id`qG?a8<^j1OTn* zGbvd#OJp7|I(}+CEO>y`B}VqAv2ru(&d!k6g;%41FV%pfet@h?#jkp0K$RRMcCnJJ z27O_?paXa{ra&PKd*BdmRBOY4^9n$y1xj+}fMw*J15zzZ&QpX=$>1zO6~RdZIwt>k zn}@$tA;$5+gLgucPS5FeLt|*3$Zy%xi1qlUqcht7RD005F*Ra80{?60{`mL6ni=+R zwt6mcK1HwXk-gUtG9klGvlpoM(9dOs_sOV$vuf!V5fFI;fQI4f(}~cZ7zBqh4K#Ub z4e#MA=yD2g=`SEKc0@b*<;VJ9MARgu875Tw+<>QUzIMoE@C~rW7&ZZFO*we#9oGQ- z+yzbPfhCzJZ{ixRS$$8XeQu-*yJ~Mj!Hv~kcstq3D?9h28s<0vSP<9oh9HV3w?8e& z%~sR84WWJ=K)B$o9V(zFU>Uric@j9+^U@uv{7xvTv%Hjqk~f}i!y|OHL98iy-u}K@ z1+j}DNpAII@dXa)14#Xdk!i!bP5xBN%Ocd+KNYEJqH?ojh_iB(t-nlcsooSNjvvKb%n^&`f0}5 z9rZU44CBw|wE-~kV5Z>i)B>>gTtfcLGKZ54HW*>rsOjd5B40Y3Fco~<1Nx)8mI#Vtg-rEXqz@TKx`w}Qi z*^$`#0@#*I?RfEZ7pEEjc`4dtf#@VSo|Py*?lf^lHtW&u00jUFL$Wt`6VMEP*ua~2 zNWFFC<#fo_A+dx2hQBlN2vUQZ9yRUpv^(SzlExFUygkQ59QF$0Jn=`8CZGZvLjP0! z81@%;OpzL0Y8*8eO%cObL8a>O);OdOAa4Oh9FICZsg%Z1V&|7>hWe$~9sE=;O+*T< zNyuAIOOhUV)KO64H7R@^AoPy!>Qta22c^&YtuW3Vqy@C5+Zye(yy> zo)1*j^LhpE<#~>f$oqVNS1sDWGUmtZRyjMxr`itcsgX!?hMq(mGpO3@n%ia!Qu*9U zpqn4hG~$`snn0&evOOft$?WCsI*A1l&B=RNp254R;8`jtz^NJ;Ri`2T-qeLRPPK9{ z=YKNG_cCt(aE<&anxpLlxCnmlT{Tc%HUGvY&8ufXO(11HS;+u_#|qIC@FWg-)&}4? z0!g2RSEZ~H_N1{yLfsBzxoD8W$RNLldTx)z>DB7-;7%;DW z2TV{^Ae#tjiZuZckIzsg4fq%`1llr-QWCKJs(02Ph8lkA10(fZZucEt#)ICYRmOn1 zDL}2|ptR8)^i({J=QN4@M(1cn6;Hh3;C)kv;UAG|zHv}%#ZFR^DSwq}&az!%MtYq{ zkbbDb;CZ=ZLSMjDkR0A{01gSfq7&eq06DzU1e3V5c3B19gtD79p7g!!qQJT}b$f@h z;m=12J_CyoIbhBf1#TKW-q;De(?QjGSYzBnSZqv`bz3^}HG*QAZ?_ImSpaXhmmLaVKYpfhd%$SU(3cSxDFOJIj3UxUa=P(qtDPzI-mUUh&}yPY!W$2{;XE zfm1rrJpUU}XSS{=(sk=w0tAFZdPG1F0pSc#8UayJx~tzKR@V3LdRAp+Wv<2sB4*4v z#yiqtlTcsD9cBCHL+^SYF}6`JpxGtRqw?B4PCDo}&618)kYdn0O=SYDGw4mI7?1z+ z7=k7s8tPuG%7v_7e;@K*_!-dUY~-ZsH^Rft5}Uu4chx~Bk=0b0duUSnx5Z%&SDctX zILs0I%3gwPXU`aN@=Bwxbr0m8o_nVx79r^7Rw8axF7-q>7P)}bnS-Z$kSi>W*=;xIe zbkxc_BSotx8u)5_JCNC6!!gwBo5+?zbbto5v`Xk*jzBq}B9y7?ywR8A(R(Dc44@>b z65H`e>h&OtasCz1RsL%$qYDG`yS)BR&)-C9*e^NdOwVU>Ii`%q)Z&I#-orTin8eCh z_v(WoOF=4Xcs1F7@*k4ohzUZw|*MNpnSt2WCPFfRK6HrvU14mjiiOcY}%So`=2kB0V+#dUo zOct7dAAiVB`m>Vx1x))Lm@>)EH9}bn&weC9Y#(Y_kZi;FD90jGw3KeH+c+Z2X&7J)woh_KM?+9&7|xCm$i5 zCB&#kxKz@3y3?fF4b|o;4f1vRzJxAEIrV9_k#iOtsPUC&_9PIuhq~<`(>b0M1wMkO zy4zjv5AxN-a}SM~uc`C>LU~Z&{;csK#Db@RhvbT=-PePVg*f~Ulxa@8Fpkm5|FfUuq%uE-c0r@_%O#E z_mSGV^YZ=8_rmag3Qja`Z$6T;Me#HHypL!AQgj_*s-lmq< zmGplOeNy*v+p|o{Y#MdZTHu5}Sm6)Hndrz8kcCi!>wp*RWP?t~y6_+iSDb9|CoZ`= zcf*-@`o8K%OulP_b9q(Shvm#>7^*&G$`8*${v&r|#2Ih@QC!5PP=d>vem=Z?MWN)?qc_IbQl3{k!R=1K zl=||#H=WRjjtdIN#;}MJkBk2;8gvkcAPw1c$}EwD?w?7=LG&9wq6-tAK*rJ!ed2e<*gG2 zj|dYSIi))+A*dX%U3B+;31d8Z8!NPadyp9@QKVr5{eJA?iQAayh-~ZqD9NkN%w&@A z2cB!O)a_tgH8xVS{SMb@ZmugElUEoY+tZN8JYje2l4hvC=$1^AfvzO&N*eiVTbWgdhuzBoKVOMOlg1fRcw1JH4C zJrDTgp->No5vY{=$(jN6LA(_|85KcBV zNm_7Zr3rSoox8^y28D%Uk{2AxVizOV3+b~Lm{E}0iCC7&`61W;X?UR2`^^bq(wWcC zaJX(bv5N*21Q;E^4-i0NUMN1#;vuQXdVNx4Y|y&;y5O#mvox9kfHNnNKka|Z_pgQ_ zx()_^N%vy4+Q;*cvn8_)pKNfGwVPVq^2lip4TvSqK#mdYTfOX|II4eeJ6Z|8vYUO$ zxuox3ptt3|RZbdDHi4`QTa_ps%O1B|Z|=>$>mE!D0#8A3{`gE=t(LU6P?eP8C+Yj)#) z4o7BF_7R#lcu7G|UegTwCVs7GfW*PUp;Zq8EHDc2>B`5dLmiuFBvTtF7<&h&+?MyjfZ z=>HC4dRc6;@O_i{dkm_^`-ycxCf-D$n755lFQ6<$>1_sw;)-e$6dA&V_{WYR8j9o_ zkJmqSC7F(+>?380C-J0X7V#lHih3e<3woZI`aVAv5GeYv z*y)$qskq&4bzw?AI{FXWl|SETh%Yk80ulz75;|e8HubW!8Iv04kUhK`|E}B?#DV=oE0FcP5|CVvtL6fK6ned`N`%`rfs{yW^(3)~w4uA8jX#o8wOmOc6 z3wf5;Vg-Hjggf(<)YL?^6mOx=U={XwS7enY$4A_mWL?<+j%>fjJa~sV7$7%6QfiES zadRUZKzQ%X9kkrnQ$&tI?eYHO-E)s=aD9GV-`7hV@B>@$FIqMOb98GZQ80NB=V0-x-qussMz@gzW?xtO4R52F>>O|Idbd z73YPbD#=n`lJyTFYy2}1yu}}G4S)Xkp+ElHi1B}4z*Q@Si!G&k$G5CHJUZec0RQ{b zK^)FOuxpD|2vqX7wqP=Jq7bj){>5%s70YI1nmQ|Gj|+7(>gI7b)r;X@dsV}Eps z^A_5rq8{!hS(RCPI-?4<*z^5&5h3g`qa#WrbUJmja44DvBjpD5@cgh2I3O(LMDu?h z$N7t|_U?B@(pTQ1427KN&f-OBbFaYIc_!pZGS$N*TecjsTHYEUvbLSyG-QQ=7R;zW z8TEGx`lLdSZH;DVARff@ysgR??lg3A!?jPlu8%waX*Jlj&U3EybNCgPRoR247UNr0 zMl$q3`~;ezov+1@U$zwTVL zLR(C8aV8)yP3eTSiIfGHe*O$_0A%oc7L=s%Mp(f_EV-ZTNbsb&Yq;CmWM|^Vl{Mp! zUam#~R1)QBLiJ#@2ka$c2C@PN*Snkcj=Q5!FK0Al?l#;Y6hx~08FjmSg(`ptw*{T# zfi%(nec*1_KWncdWJLCG$r63-A8j10T>v2DJd@F{#wQU1{AGW7PJ6+lMESf&&tN;J zfwdaF`1ShQX*_N#OGa!^20*h3p7Rk(ckMVNtR;h5^sdtgzfO}Y=iR?EZBNV>hC*dTV#pSF~rmE zRB_-=YC_!%aCx~Oj_KrW@W>~QlU;FFuH+#AWMyg@PCWkf-v`gT5Xdv^905-Kk<+Lk zb2D#G)qcOsa_H=R4 z?YZ!MaSeQ_kg6DQIEG4^q|>?a{FYC$2%rUVym{1nQ=Ak}f#eKgFb#8n;p z9Pfb@j#6hJ@$jxIBW^K0dQES4w4i1V<=t&70RFw?mz&>E1-+OSH1SSuVo4$i3;h)Z zd;Y2ZUhOF(+qU}W7!r~tKAh3-k<6Po-dqlE$`$W9i;f#h=1$qaz4kN6nZj3BSEa;9 zfeWgB?#NVRPm>iJA42t)3~>3O$9JBdpPANOEbGy6jLC~6Oph)npO;+;MNC^F7Yr@H z5f4}Qa>xSH-`yy;7bxQs<@UXLY^U;1YnDC^KdW&DNbS_u73#A5^!V^BuuV*nACak4 zg%VsmAj_a%vN@BEIoXng<=Ygs?1uI_nEeb zWDC`%S;tU67MeSktNwV7b?j5^8EZ79=zqi~sK9t0P!&512ra*F`Ht-UsS3nJ`M}As zT)vOQP+Xld)iQT(q#8;e=+Wo6GyM6x-#A*v>U{={85~uB<%y=adxgQ1~=5=DXqcJ#n9)IaYp!4jPUpN)?#t5IP z$e=v`O{>Spb*;XKQ(t2(*R|)HY%V86+I-sVhd1gv^CJF445s3KI=Prz)g4-*kNEVU zZcP|}yeLESaGDZwOP#b5zxGC2dMP^1h2@>WdnJrxT=M9T*ut`=5BlJgzd**+E)2W!5Ss> z1{a5dJMlU^LfQsiB;%m;R34i*0Ou$}_u91#%*`~c3}+y;J1NVZ7inbhE%V*VKfWOH zZ88B)5g$n(za1KRsnUaJ!px*2WinPJ7Hwhw2beNn{`@ zCjX>*V{u}mJP)F!k8oFQM(@QcAC};_JjWOEVrMpD#r|8})0bqUYcleu2P~(*hYMcj z0d<&b-=H;PjdYzhnVc48IoSaHTwc(H@%LpIq9gZO$^`BiY{{zx^+-Fr{O(?S_{_Upb7Ui6)zJu^?ZOgXda?0jOa-Ns{n`hD=Pq z>YoQW#jaj`r*HbO*UP)Oz>f(1f9ZZXe;?lY9dY*IJN}`&e((IG)6)j0Ght|gLuNzI zg-7OL`sa~}b_mS^=`PpsqU+5AuBDXYBM=rE4FAcL<#NDioLtF5G9^D#!(~naTJUQ{ zn3pM3T%;4@b$q|WA0jzpM;&qILsALogHp~D?UCAn_Ad>@htSzKD}6H*{1YJo@WiVtPTN`+TW^jfUD}?=}lwQuqJ~KTUwV>->3jYf!>6 z7<9xKE*Gz>aDvzU&)E#H=*ydiCwassVcJ|F#s8`?J*H$;>p!+*g}HL=;9>LIz=)&l zYix)<1Nov{@ELHA{^b+&k0UrO#(x|$$ky}fyly*pWmN|r4dS%AqVh@dxADG{>-$yH zrRA8A%v28Tw-$H7+u}^VpgfD;0-GpgZI_pE5W5ol(UsC$&!8w&=*aCI@&!ftDq|uMBdo!VH^(e5=(G;b|P)&zc^( z%;;VT7^V2sVTJV$DWrdg2lzRpQ9*w;Z+`oejdQbk)c_2RuzncHmEF_(S@4qLS#(e*PnZZT7 zdQ=}^Y44uL7k?~tsqdB8p@%`3M-54rS&uGc)xM4&5j{2-Y3rpJE1T@&`1p-14k&W& zOv-a=Ki@loL#pSdnPmHF5h@b}+S*lw)BR5s>LF$*){RTX()@(37Jg)Z>&ANY>O@8rXrb)~RR^H=MT$tg-;{=s_d!XbsP*;e|4sKe0bf-h zg9}X*h<1rS$nEHEfR+k4o485z4TqSWxamPgs@vCp?%k43M z(@{At7%X2RbplQ4{yoA`ndWkO|8V!0R7{giJ_(IG5v@Z9#Fy*^1RHV~D zG#GDZV6*pr*Dy<>!fd%B^VTt$kubKer+Eb<+1+Rc4;;h4#$=L5T){&H-Y6bRd(hIz z3hM3E%gQ#0(i)zg#Nf3R@CBesL#E>(Uf-nYfp)x!aVn#!XC?wy@kgrhO`!nXJ5lOcdkI1 zUGh+G3W0grdu%(^hidicZNx1yijsLnlApHcA7+*cl&Sm(_FsMssK+Sr1my(;aR?kC zl_i*dX)Z?U*9r74Jn&ME%}0(i1nqJ%rt$f~w9@07>y+>yfnrBwGULZhUS4@RptA_l zFucWQ1VHb}auq$w1G+cPtSLx6W*<3X#5#wZ&`7}1nm@y0>IvhhcHElol#+a@g|VEpy#@K6tN}iIDvW7O}?a>Fzj%7Ddc57r4nbuGXyLPgw)S(Ay$}0 zCHO)E&XB`GWSze9-%${Mx&n;_k+G?g?`^{1mT)CZf`x5?qCt2tUpq!a8GQ+n+O&5i z+*oX-q#&K z8B*TmrOC)EAZ8OwN-lgX9(8pU^}JCHZs=sWt9} zJiy^|+O!4Qt8Akpa@cuaLX!~pkTU#NB9`}H_8ZsUlNtDbtRMD1u82^<&)1)RYlQ8o z)L(Qn`ppLg(Ct!TI#_(}HaB#=_0EpdDV?~cvW^-U2}MpP$h*MNKo_}!thhvFNz(X6 zW4hYE4FgtzPztKoc?%9HUU%ahSaLjjJ_1ycFtx&yX&Zz6fp^j*kHorcD0AyQp@*Ww?ILCK z_RF+Vwqf?2aTXt0dLbHM1ibHi2)s~LwKH$H-RG?Vl?;dji4|E9-T`fp-B$yAcPP7> zBzIDBoih?e+SAeN(sOV8olMr^jm#_Wrz}nPGB3uU+mMr>xlZxeY^{+{WZpzpP$9v8 zAO9E%DpF@Wr$v|3ib17cp#Rz)N1MFEX^-R*-O_sZ6Xr~sy2}Sz6KX;?SBHjVShuPL zQygPnlUo^yXgK%on?_vfM3W-D*10|**jmFvSAqeh$b7zTs&0j%e++-_ef4nHgj>Vd zIw+xVOhCGW;)@rJ4v**NKCUy01MTL1Q0pRB^bEmhIwPI12itJ_(3jx@TD@xkh~8rW z^Bdq=$P?IoAMmeq_mq2ucy~#b)`F`bgWS+#u^7v6Pzczg$yL5>@u%C_$R4Nik)nBJ z@`}H{u(`*o#wtN13F#V{97*EaPM;RAchIFirwD1|y6t}uF53_<)Wg*1D<6-)^c}b` zzkv~B*9wlldkTDWz`v7M6KAL3<%ng8A56ooy|M^1abItUUes$iMchO&WalGg=JQBO z81+g%cXuW4?2$A)yBGHT5~6129c^ar_*Uh!6#`DNNTKth7T@gN9Vv$U5p}D(XfGr+ zpi3ix2fTw(=vM5w>*qkGX)d3L$VJe%VE@^*4}%X7BwG1Mu!1CW-AH z24ltsMh|ca5-YrSf4e`{B)$gE@l9~EgX@7NFJI%O1w|VB2Fy8E8*bzTQ4(OrzO#6A zrLI6Hb3t`OTy)BQy8X=^$^4(B@A;sSy^lCnU1_qPBNL3I_TqI?t&`TKzr*P~pRB6$ zoJT{ZUF;v5giPATLgW%qrCyo|6V@Ro_q!2*eXH5BPd9X>>^sZn15w#jP zuLC;X8FE16q~#XNPA2|(dSD`ik@Q|fdYz+5BpZ@EDN%$k{$JODxY)0Y|e|^bn`& z3QQ!SUm&pK_uGM|nU^(oSYQFJdi4;$5>CXPi}1L8O#5JCyEW%yOG0?)^+hhv7=$PP z3Z<8b{$Dh`V+gPb-S-UE#R3gKWONvxf-x_Mt)TP=QpY$*@oGOR_ir1}YjO%#NiIn@ zh1rDkVY1)ucLkg6i`{q^jXi0Q-is1PHq7hfg*nX$qblvoYQt4a?BBL@ds_BBM*1#t}SpF9Nxa!{&1iBYj(jvojyx@454N%v@GUD zU7Ml`gA7_dcC>eE^P5P=R$pMLF%*iub$kKp(5Ji>)u>h81phFe&sP2=$zqY*DZi`t zBqM0`ejm?kVAPmifYxb~JELOiiC(Q^^QE3nj&io+|dih6X}&~{pV z>_)Q5B?<4F=v$^qF7{H{XUkr$UqCmJ;|*z0V!~Vykol%_s7E}QCt-kvEx+=8$$PXG zid=$7)`6Lt8EM|EU*Xz27H8xTe-p`59_8xZfw zN5}e4CeGZd-Djc;AbX8Fe3hQ#-hEWS6SmjJ*fU2`4wl{kg%A>YZt~@vSy0n3IAuN0 zDEaPPqHWjkh)o!?S8}$aZsoNm?|{YM@bDlz{K}n3wDY~`@4MS|hzD4@viu$h;4a`( zi1QfBdR!$*5I{a+y1w+j7eZ@pLAmAc{paF}b{Ye{{=tCMR-{ub$S?b7U2eUORUMv2 zQzDvI^4!;Tejt@XF@Adu+B5mxy^-(frp|v3V?u8Oqi;=xZx_CG z)LaOaAMxwT6psSx=q$HB$ikD-h5rVx5$KmvKi+xEBa<2jnmF3M#nd_5Wq>r(zj&05 zAVzlRR?+Y-BjloBY`F$K8S+>Zi5;|SZttkPp4g{7UCfP35qT<(=y1 zKhh$pf6+s0%w~r;)|wO<>3v=MRRu8p*sp$|5T#bw1TuV&Ojk*LF*!lX zMU>%xgB(}AkOQ3vZJ>gX)Qf`fh8~Ee9=qrr1CMUw_*eXmVxn4j(QSp|cZOoREsnc8 zd>&wF$sYz*P({kodV2hzKS*=5wqbHV!W>AvwQrGhSF`XF3obI#YLf4O`$qpW6?VkoQlNg*)fw%_ zWg~O|yx)43a7HYVl^G*aynZC#7r{H_=&s^)LfUa${odURQPnIBOxmBGkm%Ppj2uqS z@JMLjIvhH2;$cg;Jt*XqO4_Gm_w--Bxee*8hk%p9lZL-`$)8U8D2UKA4eS%Z2suk+b z``6ngEAxM8Fc(nHXh>AiI%kV?7u`Nm-LCgve3 z@b?Gyj{Y|XCDIvr+CHA{f~-}GH-s=NQ2`LYDg&~BHJLa_A-E>tosuqwtz4M?H!bLs z2cmkVh5PRq=`!(&fv1s^w3^T7iOV=yKIjR(Jddo5A(h(SmA?h3VL^Uc#wJsR#ds=m zP7!~|IRsrn*+<38U*#hy%|-@O3zj|d(Jtu^3L)Sj2DO@y_}RxL;vwX*#cC-3c^l6y zk`$mgX!pM>tj9l$0T=TCH36GjYxo31CnL7jo13qBgwg`>WRZNVz(7>-_wLDiPfL*>*F*}Hi6(y5qk^0cK?0_lO`BSam?TB0TzE-$ zmm6{Ooz~mcwpt}X*LX!4p8YDwsroW~BKe`%?hHm{>si#P7Iu+qpMaEBK-2P5uz&2_ z`dqcam-CYRACGE(_Ry`^IU66xRGrWv;Keo}uZTo9j$wC#QF66sZY&cLEQzg( z4EDT4&O``7w7`{kvqGYlUFUHeM=^OgBeG}~4*4^@)y#Jbj@upm#(*L@S}h^hwO4(UCn?(TE@O!mDuLq;LZoZ<`y z{_}L}EzBuF&`iIw@16&jB+rqRDTEss-!b}5Q*_-#v+gAB!5_$bcz=BN8TD>;AMxt4 zb3KVa2dNPVUI`Ts!%o&n!9le*Nf-n3* z9_tyU{rRH;qddNj`IQ$tdgvDj1MrmF5}0wKWz2Q=tXoejM)UKyfR0B7!#O?!Pk7wu z%|<{uQ7n?_8s~LCIQ#0qnkl^`q(4Ejpbk*>gH7U&)uL`)`mR5RAGuF>;+kA;`;%Pq zY(NmFAW4WfYL656*qBpZ_Ua9Q9;-Jc5P2E2q)hYu`uuDqMO*nV8Md?bSUou2N>_bp z$RR%%`7+|8-@ZLbu-;e~dgdw*gW2W%+)kOQ*>Gz)%_V>{gn0Hoe}U89AGTST9Febi z9{B@L6G<=zFU`&Ew%>Vgb3x5O)Jvp8|3|(gXLZ8tq|qs*1zfx6Zc%DmftInoJ`s1s zgTXa`J1$E0uf5Wf*Ta+H8i7mzL%KgY^%?us3~EjGcvidBsWo&lA%rJ)dar<=^!)72 z<25$&PqN3&g!gzv*Zim|S&4c!O^mB?lvm7B(g%6pdI~4OgY7LI8Gw?XN1T74PbBrI zFr(t9;GD(U**wqXU$y-m_Xsva6K7x>avGm}ez*Simhn4L3@@{;tRPt#%3y1e5v&yY z17<1wGvM}g|K?;alxJkLIvCot?G1s`3&b9wlAh5#rgy1AP83rLAEFI0v`+f!#7!Xf z08(6r*SRW9UPQ6g?%o~mLxm=C=1Im09&~_A5M7`@NKMIoh0i&6x7PmSe2e6Hkt~!A z8AMfZIa%G8vD`v75oi*7C=hII2Z|%yyyB{xDu|r2)T5 zfl*PrAmACJ2PhY=*D~@9(DBvgFy;o#-OT0KesfZPee5&(s-$Lm&SL!Lu90x;7!$@f z2+qaroQ(HdLJaXx)diRq_X<%&|DE=4&xN#!Sf1JKMrh51+l+5BosoXmj`)gvIbvi9 zx68AuefosUD%uAA_i7|A2E^;(y+@$r7{7ovZ;?DZJD9q6Y`pV5MW}pnTZos8KTRl@ zsNGmMgD2hjYXi~bA1@5=!ehBCA=PRV>gPMuaKh=R2S4Ztu8HnF53AHX(30v#kP6<+ zH9*4chLI6B#HVw!Ej&7+3<7em3JUC9wrDySx{UpFq2GP)=&=!S5{~LTY!u6DzU5lH zIE;@eI|_kPJzuO07;|z-GCp&~%L=1|Tu>|~!~m8YF{Avwkt`TPa7+%)a?R|YGpapu z1@FreDv^yJ|BQVn^77v@q*-4+SA2p%FoUud6zqBct>raAk2N#_6YE`>(`P5N`Nxw3 zE+4wq6i)NVJVxDoK8UBi52X={fA-mgCJ{6QHM-CDhnYhU7j(BEaiD`BtQDdxV~oq5 z%ySAz4`TH1`1}yyFnxWLd~tMFBr>~X!$f}or&&)xvmAZk?pxkqf@%-h1wm(>Z1r)t zsR{cgTdEl@Ab9SJ?bqAKwoSG3>x&56``0MXya&u2ScPx+z_Z?qqF2_YU3ws2R$-1m z@0afz#UNpVBqU)endu-r`IaFc4zn8WIq%YU%^c z!2HLKw$7k!zyOZFsyOl_h?bwI{JN%bbcf7Bq<1Wm`RQEITEnwAJD`KU% zUj#G?j8A%CBjix6*NY}a-5trCXTLPQ{9XGXSHONsp>ziK{0yUxhQLh?2BV`@SdhfQ zO!B$UNX8|e$bG9Vu}LY}Gl?*dW^ehPp>c}Cc@+(u3m^LU{goj$p2MG#o0KiTF^qZE z6i&p^PS!x{B$Io>*)IxVTK@U0V7i+2yEiL5N%G=9vZy=#?wgmKqOy60Ju(tckQE^| zjCHR8>zyGm#p^$<9&M@egn~3 zyK^BmxH90QqbbTz{Vmu~UmS%?+&)SLtYs+E1$+m*41W)+B1hmUrCC^TNnsN7&WN*@ z`vav1%N2D7oSH1mM>u+7MyR$&_$|LeTX>8gS2X1LQ+cq9&2+jk$Irs{-e*Rcq+~yiqL@ZNcFA#K)^x$`C5uvkq>PUD$83VDL9u4G)mCaQT}qx0Qa6(!!HE$ zfr$!cUn6>Z<0=()IP>!v5JyQ7WFO-poEfv@~@E_b1!Dm4_!vBy-ssz&QlF%_4U3QE6_H?9L1}A+NNF!7z z&xt+6$e8g%`dsigh}1AO;rC81*oPR#$j)=cJIYVKc`VNB;}~J~9aIM>5B#^ZvtIHG^`*&8 zQl?iGB6O0vcnmJy;dk_|F{wBkk^+TZ?HK;D5p=%nDa&IYH!te$rS^e&WD9J7cbqQ2 zNAr`+1JV7pjYTx`L zv^rF-8m}Fedec6Wca9PoLpQc7z<-8F9ZYf<_x%ysgZNE5YKwU61|dLWVf#eu{UG8T z0`d;JsYlB>>dG&Bl%mTgmkQdhLq-63>L50XANsx22BTD8wI!~} zakoGW_(+7S+Hp^u_P}i5M&m;p&kbU`a^Y}+kmZ5nK-xJ1aZaa}`Bq+~@KHdi804ye z9el7$BZ@Nk*|Md?myr6BHv@kB z4tp=UF+Yxm-v9JH!4W_ICVCvM2tm5C%tg)pqXoOs@v#5FneG3!(y{n4GlIF@I?TrO zik!78nGhs^>!W`B_5<*(CKR04J81iizIbjt_k>SHSQg~pb@sae+`LeeK(II9;=lwM z#9ll!NW}YJ15S&S!qwxe19)`^qr?M-j)vU(Ke7~Hc8jv9kl`Qo&pKXa{a`bwmOw9x z>|Ta%-yVNkdnAhI?t?+v?fs3T4uq<^ib}76wM`}TRx+zhlkWN+c2iR!4``-AUO%^o zdE1}guQ3eLf5{9f_vgPfjPE(B(M`hmG&nMAJ(}m2g2ETnxEGU35+_NcBr0n7#f^zi zTYr#`sw|C`&@n?*3{IH0&e}$aHd1_e?t99qBo-!>VEEBe!!P3qP2KGRj~p-o+^P;z z1{1Pjy$RohHjgf*TA-%G{f$A2Gxv~B@~cPI2H#@Mm(qrC4*)~w#(o8_qS|tb55`?e zZXnQ;ey?B7edv|_^ZJlilqo;}VZmhl=S(NLX6NjHIRo%F=H-$Ypp0vN1=8-aa|`GC zLZ+5g>w(c6kyG~o4F34l_a~9GwPm8f(BKVWkVk5mfnoUZIf$dQ+o|VP%8}iksTtmZ z)<^sR$aZ)VTk(>Sd{(!ly&+gC`s;)(rtiq&#l%Q{FnbzT*>Ow0G5mj!3INivGS z37(PT1&T#0ihSp>^oKN6>N9yE@#SE~*_NRxtuj{cw%fMD5c1A?EISq{EXmbb$PyOg zO?in={R~EKp&*BXq=x-X6QtPbq63kMDNF-?>+*Kdtb>&m}3T23!^+e}sLH{3K;c-O91TruBxV78&_|~FAqU|%+W+F)A$B_7`kTegE!|uDn z@3GmEWWGN=K{fC?##auGN3fr51v^68o}4n}}HTy&sPUb7B}ik4Vx z>#d^>TwQu|79Xka!=Nww@)@XK6@tJssX)v9jQX$^3Q{=NtyD>%Qm_3nY|;yFu3iIRK@EJnt3N9L7|x6JL7Z?CBER{pAOx?0AT)VfWA?-{&@*3dg;e9CHR5} zD&?V}J&)UI_o0qx3%LZ5fvFNBe1Uw14$(O4*4N7|A8YuK|0Akw zC@P$Ff?5wR66VGabYf)Y1`uXXD0y9BMJKjOxD>J}b5Ucm=cx z@(=sU!@Wjk)o=xzZs$%xT|piCqO?B0NYbhvlZm|n3$>%xcl`h$+f zjiiH|)|Sj#iOYf1Pj{~R)DS7rwenCXXE%dUHAb(ZSP^2te(<{XG|EcgIL;?-ZFpqC zkQ!HN2f5L1@*tih){R$GFJSRw<%}z(Fop8te%!48gkbNYX_mG}yq#uC8y7WVovQ3H;7!_WpIR@nvTw0bL zx{@Ty;ScEH7(-$7# zlUdh%r)h7^NORsJc=I|^t5J7ti~ND(C=ix7mERu*F~mOH@DCjF$Tuq(6kJ$iz+)$Z zaybNzr$zsD3hSqMyDQGVk%8HmboiJGvMMwWUE5Y1W)%QV_ps3IHHn{UCtBq`-;R)` zATM-tHt*XWyTYF+@SV4_b2L3pI3d9hWzV((9?Fn8#Dw=pCLTC~4&AD%ddW9^-~a4m z31LiWWB8CSWR627jDM^pOAc`@=yE(wVpxEQvSka0JzM_d|J>a<#tKi&Z#x~y2CHg4 z2m_Mj=^!TN_(rZ2piyv!NaGVTDx%L(;BwNCz>*_46D>w0Pq21JoPS{MBsosX?OQKy z6fJ)86NkakTfOpklm5Mt6pNqxA2uar{C>@ax^+J8yBpix{d)Y);}1z=3tWB^g>)e8 zyeD5F>MC$y9f*@dyS2A(uX0oIJOqTKb+KdktG{VKN%4HuIL@>f%Q}gHa)F;7eV5Tt z)94;o?k(6Z37fuvzoAc*6(H6-|GK23eci!kV>%lvEG+sw{~(Q{B^v z6Go^HzL>S*M}FL+%**#$)CT6t9ltBBPlBp4(21_d&K}ILx?}1C;Dw zhs`(Q5(oeEtHKOSmWVq!?Bb&=Wmv8En88a}l zeqt}6#7I&%3{Sr@aQIk-pS7fXd;^l2(F)8p)TyCwp<>VF=O?~lztI0=hHDks9LZoi zAY#|K{M^NdE~|>=u(@)Ad=de-6fhs6F;PyoBwdEIdXh91QkxQ5w+l@ud_^yR=+Fds zb>}8n<-=3EomKr=ecfH)w@05rZZcc7=2<>$l;6SoPOPO5^ZR}x2IMVUHTT5DGmksnG5_Xkx z`oo!ppVI}|)^Qs9osUY(w~y~C{DpN84O+Fr`}d4$7=Ik}i_yr1|HDN8!_C#iCb=Uz z;&j;GGVtJ&dN?CEq|t&PxjlZzg5fOuOS|@Go%k(qcZx)c|6iLw1^v>2NyK`RW+kP|7LOJbKJ7-Iz z<{hAK#M~*E^Y`agApE-@knUT!_y<4ML_h%^wECoBI9jqIaQO z=E-boTDL{#X4s719DwNqyq{?&W3(Rn1ynGQLwD-)dA*Z%%7bgxw$B;=ho8Xne@TaU zK=@E?Bnk)~Uh}1brBg11D|I^r)d&d^sCHHV2=9URI40`jctUF5WiHe4Bpo~nbRCv| zo_QrStVaVPN1Kqr48G^edhHo!omK{*Vb)71%eCtjyCgEvPb`W*@`K4S0T0IYt`n1( zHQTHDn@qcwu{8T2e2sBAoDik4Zu6B>(IY~t5;>PLCz`pLw_Sp--|>Ha<+*~wWwzqD z!vgb6Q)nd~^xULSH9efZ)3*5bnz)Y|1Y}M!x<69z;3F^bOHHWwjOXHsvSkT*5lSg2 z1Z{LWhhKCib7L1%y~l!nJm#6y#yZF=Kfs0IG|mgUMU^C_A%9C5Y@b8XM%l`*r=DEr zhM1wq%7I59onVHYj+ zSyzDGneFxN@0uc*@Nd}^=PzsiBv!+PAWf1CGRq*5pYwrxx;ywt0*Ub~`cfmem3`Z# zOhOd!J%Yj4Cb0K#p?&FeC4c+m1td%dpsAbKU3Tn0C3S-YFZXSTQ%Nhy>4Jmq0IUH% zYev9d0?`er8)eqS*?v~d)YlI6a7d9S>6m9hva=hi<6_Oz0bWl4VM|&F9|+wGjH`6zO7BUHg9m+ zVhpxW`@nxNuVaWp-hx}cE?}4at~wPWmkn$ah!%*x(Fe^Ty|FhO&30tUMVP(PNwKf^ zadRW7lKH1I!XMM%GNiK=J{9+ND=Ov(k4J*kxQx3VK-?!RKtm<;CH7vT?t4*t(*0P^ zvmfz*xLooi{ygs#>W$}v-uK3QY%cG>ImW`rd~8+OiKfr|5@U>h=bf){Oohf2Y!gm=?H z5r_ZaS;9IR3pc_{*ZuWhh436~QX#mI_tVVP^*`w4B`+{`T2RW_Vn(JNvMjNV><)Ss zZQ)=(gpZs(1nWny%K0amWP#FN!}rq7SIK~lk#+g73$$Q}QZQQax7Tt3<`UD8r%*O! z#ynGnG=E$L1LtAO)bNIfsrL@nQMvhjeB!x74uh$(31|xckEiq6R#fY@@GGfE@RFP) z2ZcKk1Vpk5`1GgGRr^1!xp!49T?T|1#_0X)_=qw6 zD|&c?$aM?Hs690s{^mSlllO(iB#X6E@M&*5kM)K#iPeT_*l*vHv27RU9Nu~;4L#I= zSnS=K`3bu`Dx;pH$q%)vu?|o=h(6#GiI=Ou(qG|_KKb`8^MoG@*K?X zgfU8(?rqi>7Jd_UpYK-6^0`4QaFy>rNW{DP)Bl{bIC zx=7IWCOI3XXgG)zGK{jr@q?6vqJC#U0OLrk98U@yUugBG*LdPX>h3aR-uKc!rin_J z_1Q1f_Y~r7-XBp_4|Lf*n`q~F(ulr5vvR3=*WAZ9`L(1X1KExGIse<;!lwSS3ULE@ z4==WyhbP5Qdu_^sr|*f3hf(qhfN$MF_pr&jfKx{W6%b~bdiEFYigEhmsdph2;}ImO zA=;F3f4eo$^O5HTWrdpq;jU8|_iwCf{YKtC{;trJh~wtJgl{tdHR0^lo4rSx^&a&N z?40262DJ+xQbWou_f&fd?k!YCZn`f4zgTH(Vxkb1eYWNqj3j|OO><%v|$?QN0N994butOoxJleVZEuJIK zMGPSB?fgsGHxGtP?I;{Zc?e1zBb>fKlK^t2J~vR(g1a8{U0t}oD+j;rclzy8$mr{@ z1$;8Xy{QdPACipiYWw7yb`eR(QRXuu6dnZIGw&a|(-y*`*V}AhS_gXHfx6 zz`@+65Fbfq*C4fyC+&&E=RSmQPeqI6>+Me18NY;6B{{61WbYzR3L zt6!Y7I4?!K9gEBLx+9(avr8W=b7)Zxm|Es_&G=g>jCd|c74$pQaEK^HP9k!83SK?( zc)u-r!L(DeoSGLe=gHrpBS9@|097ytC>kc+{byf)Qi-dm2^l7x({Sy5-|p-6O!yxEt9QDds0PXgV*ojrw+FM{^RD0%hgC4P)QG2?Qvjw+5SD025_(lAy8gE6h zyipxk4it18-L|yF5t`86%`LaIC8m0}GyU>^`d-x!&X)@}7u>`%hKiVm9*?4G#K!^u z156WCB-E?8zkt9Ei{kn#0t6BM*nO%cd$Klryz6=8gCWEiWzf=F>+@7>NbM1+af#`b zD6T-KeZ(&1h8;KWaqsXlZ`)o4YGp)HSOHSyM z1`I6X5*zFAx}uD38cmr(aj?;}gmxe~0=Thk;h2Bpj%1n)w`}Oa_VjB%>_!$9F9p_u z0R_?Xg*`MkINnjuMeq6bySGzcAI;?-0`Ud>Yl-SNLZpoE#3aesia9)D(xjuEWw%~ zteyWS!=CW1`#;$B+ScolsYO!HH0ibdMdl!VEh`?_1lH$GXDPP(oT_bEQ&pkK+j{-T zqJXT6KpVu2^6#V~%uti=UZ}`}r^43cj63`-fkGJeKi1*C1=;VL`|J3CbIiuClgN4U z*6aDtMQPR#D`>e}(_K2Q1I`2i%*W@FO?}DhL(%cFPiFqL5K+KP0cAhz`CysBt_4p{ zJzMJwbR;3+(LIA-4=FP~@KJgSEzQYSRB;c0A!bye<(Cya0vAb}3h7AerLF$5a;@Iq z6w$M!UmTs-Es5qaK?X^6j-Tto{HN$8L#TUt3vpxL5pN*VSCeRdp?YE9AupQ%%PIZ) zJQ8j<5=YQq5wYIVpD{*5Bu1{Ev|cjKW62uQNA|*c#Oe7_Rv6zmKnz6)w_Z5BF2o5_@cl zO5={wx50CgEvb-8#_?(kasg~!du$&uCeK7$ffpgQ65Pf^LTeAGU|-&gxpHRR1WoS% z8)qNipUSwF& z0?T-hdw!d+tq+R*X5A=nbbxO4pj%Nr{SKY+@m2-bkv$fL>En5stu1~&*^8heza{DG zc=^!z;J--1_P!~g>;r{8(m|NhafGq%<Yyxh6)y`y_Q$WP+s&rAyiDj7{y1eIRzytb8;_Ti$qY~^!~=U zG1L(^hg1y&*Q>%f&E8@6$y0U*#S{-%KPFE0OjOwd)+r?a?Jo=Oa3+`GH%1tyj)h0h zEUv}1CteBO16VQW;=mksTwq_+nt<@QVZ?dMddQrgZXC3Yh`9^7e%4Fn>eIey%WwL* zS|I3{NXHIdO@5g{YlXEvdT7`UqI&!EqUIB!pJ%teB*N~BWZ-I_jsA}U5L5-&O8M6|$fm7W%<{33@PJWyrz5#{z19Wg>z|nEX zc4~bh=t)I{P!9&)r?OU>rsgpGZr1g_mLT4kOC8a2GiH1*<@$!^t_t81d@RIac6-rBt{?g~CUO`{{pldi#+ zjMK)z+aq#n57J(&5gUGXaK(n`Rw2)@{S_ErV7Ix{zfG2-(*$E5;>>{lo^7uR_M?ho zyh>-m-M)}|IQ)^{l^ymBD~x+o(5N%`5#$5zNx?_`SJ%QCLe$e>vM;67F9nOVG4Oj; zIRAwEl%CYj>G6Hw;S_7{@bNmNAEBlLYSyb>hYP8}puFm;eo2f}d&Vy`eK21nx1vPs^A*?zyx3 z9Fbwb%4Ee$`5MYjcR_?t1pibmJGeG znsLo~fpFXZX*J_cBJG)(e^#cJREk-Yxtu zIL#*Xa@4^$)u*>Z0}z99ZsJ*E@9q}QT1O}1N9s#F@g@JA42fzCm;Px;&Wd z+mK~rvfa2Rk{*QV#|hv`JPeQX?Wm8gWB2C<+wLYnhrExrM3CyRw!OqzvKQ{6l0g*y zP3nCh{?Bj#4F_BiaxP-!Px3!H2t!n11D0kBSDoU&ons@oL5ETqiEaQ}UiQk3ovbQbo$z?A0htNkz4j7;RIXKp0x@$+DPUe!OZgF7`?Zg<2bUq3fV zygYuJMJ^mc127YBMk9v??80c3$*Sl%@A&qA~7ARn3wAUG9E-n;w;?*<0-Y*N;LZq3SxlsrZIv7fDx(mF$ zeNf!KgjNHJv$JjpoOtFw!Z^C13)VaR`1(#tieG=$?*l_FxF{199{b9$#|9-7pbwB4&^@xaI_u;yK4uaoE3oh>Vl{vEB23v^Bg_ zin2%~zzD<}nQW1@_{g3aRC)ic5zya_jQ!@%NCD$eeIfO6o1_$A)ryD~NHul1Tj%zD zxi86fVGh0uDUyk~N`4^NY-uE=6HZK`XN9OF@K6V7fn+ z_T_;{An_1F+^#i@B1U9>Y@ooNv)vVyHSei!2+bMZsqQt$e7E75sKXJZ&@TN;4o8J# zdBYpyBgvHPF`m8YfGdSP+C{d_ZxOK2%ve6+HE}1Z??g=_4GUMKXTQKgzKh8u+Z`X7 z>mBx=3IQogfpZT(G*^F(%=%=`n=m3w3h-3{T#FlE^rHqGT%?k#&HA;s2J4R=i1luG zY;Zb-&<$8Wfq!;PYwJxP7`4~75A{QV&P6+M+veKt)lY_||IvNXG&!G;*fBCAnsAwV z{gAav+~|tf zXOa?*3n`&}8Hm6?B!yP~q01%cp?J~=LovkGo*R-&KH43$AQTH_2?-M&p>v<-uUbxF zN$LU##rt&vj}h969-O&wb_0Ee$R#@V5#TOb5Qyj?)LW(ss!dvnK3oZexn|%Xk*q$U zgJU-J5n7e(rNzGD#mo5n5Xeqnj~^wp%Eh!pYKoRPMK7*4=)X+K9aJ~?nhorcYlch|X=5qs(^^OJCb4P~xedYZi8Ru_4IS-@r zg-j^y;1N>`PD{Yy#ss|){NuP@!zK@Bn8?~`thfCbqq~>|k4ARfuGr99KoB^WEXhT*6?>h$d)w(fxRoSh7#6n>kupPo~<&Xq5Xb#60f&1IT}5k zpkNE;@|h@Mv|AU6e_js<27eupma za@l{rih8n8;XE#X+3%~LKfYG^i>7U0oMSUGG+o!ZXI^j#L+)u-vciu_tG#0D zfMx%s-xKu$(SiQazZSC1Fww`udgL4K0onPFtFix6dQca-W057PxP9&^?a(yS4zKt? z4xsMTK(Z=)Z6u_ZfL-PxdE?b_d-!Fc%?T3BH}UDu)Nw)%TkAe{=pVaZ>jP?$-2!|2 z+AlcJM+6Y2MKO_cU=?r8HJJBx)D-wql`V@uHl(HW)Vl%PNfP`~XRlPVqg5J;R2V#z z+JP>^L%yucVBN+8M$Fsq{qF{Ix8+@ z_4*>r7AVoc1mQte6Y=d-?>J-P)fgWS5M}VGh_)J56z zcKnFPW-m_Po4~`0zU$p#Pspn?i)VhR9w6o&P&G1~pPeI6fXO#c{$S5HKt$Ho0$Jkv zK|9+xJh6z~2E3CDgy7X~&Sn7p6T+Buf%G5+4SJrGE{Qx3dkDlQ8IVhYc98;ab$j}P zBB!9Ba_iGKqY=^~92!DGydXB@ekGZoBqhs-WZqfCNJwpxmq;92c&_i0ZSBat0=nPO z#xo_W^O93}?xC!m1d{XzUdoNz9 zoue^=5*FjuU4?yb8~M)*&D-rq(^Zde(Q|`R)`E3x8!r5z+7z-1Lp=p`iY;m`Mjc19 z2x^XwbH+lxw4hftoWuxjPQv8Wc)I|)c97bhX=(((>Yn-A>4K-gj_wV;BHrg;W#nHb zWPqwnD$Z)G$mIyq-!9!3yrTi|pkw z@=pFGXpf)-+s)86S_Z0nmo7cze_^}B9|0;mK;Chg5h6}w#!WWb2u{FQAyOfF^4L>U zB(2$@9v>fOzY1wuLJ3XBc=yR=@R7(D8jm;L_Jg3I$PR<_orM{L=+90c6hgjN>|LIv zGotGB&GH0ienNgL-vTkdBlZK@5K!OtdLvi6EB#z|CV%kM2LdS1CV#KS4y_-6n7lWJ zh6fT$AKrvEBQ&G^-zhG!n03K?{A}s|Kn zv+w-PM5QD|c!sg z_WQj-MEQ{Pq0`2Xi^p`A-ML53Zk&kOlK$8Y38H_rpzr4pz1B7MO{exkd*bhTNY%Us z<-UJ}m|T&4+YDn}3VQ5QOtsHV^d3Xr>1KS;I+8@VC3-M7PFg|DEYZx7JKk^M10B{G z0TDKu=l3;zF1M60-mD$E53g1xkwOu1h()gwysc1~jA_p>H#Khfi`=}SAB}!jEvi>g zKR&`AyKPSJQ9dm>0R3y=jaat6$RSRXs-<8Ak$tY!)yw=(Y2E9vdW!A{KBWYXH!i51 z(=k}8M#>6s=FM9B?3Y)kOP`^)wy=VUavYN80XaD zcVo+~NR}bL;g85n&Z?I;T2~LRbKyJcCt)N7AL|-7?F-Q5-GdCu+j^Xz`gY#Br%{Ny zZF>D+aByBXjMw^q~)A7(4*4Tmd|Z-V_3) ze#yqG>Zdco)8HeNWbOGKIS2&UI0^YO5U7c25HQjgk{3V$sc-SSx|Jus&Q=H;fVlha z|FZeG#m94V{2#BHoVh-8zLIO|c@P%`7I*37kEpGWQi&3S3Vm?KEf`xBXwTC%(98M> zrTn5cyG=_nGcV_K)$C?=YURZ^n1BL}%%+A#7I*Z#r0*wL-{bb3CTzA|!SmJxmfAK@)}tvUcrWZ% z+~zD!SBuW6%7p8j&<-taKO%XOfwSb3n$G({|DM3HA$Lx7FsBMg@_J&e8Y2WyphphF zyrL&Io>8GqFdPnyX3?np+{sBU0T^XPh~;NiDP=VQts~q|Bfpcs#JxbJ+t71Z8b_iEs68!m5O?CH&DI;+2$9d*9EK?!fR=lMDLxg(HWta3b4bMUat zgys+ve(3RlP=8M3BX5o0YS_~Myd$Gt7GpTXYSj243c5T90ea8y}19a`p{( zQ4$B}kMBVrRn91(K0jRXB^o5Wrfc^5ZRX$dGX$ZctZBiwx5LNIy(Qem(cY6ft$IE| zW3to3y;WV?JG)17{0w3QSpcqdWlTE0u$}DC3uK>_{k(qQ|QyZH7W03t}5RuqeN8H+cAgdmZ|lSkhJdt0G{dpT1^CNrdp(tEdP_C5e> z=Rkgea4?fGB-gNR>;&orYTDKP&ZqyT>J!y`UWk50wIzZ{^^^2do&3T8xuLA+he+$J z%+?J>Y<5<qLSO63SWNH=6Cd#ICGL$BaXZMnZ^X7bP1-) zNle9$ffX;l=YO=CD-tSjEV-d{}o5!2ux)Y$f57s7cZ$VM>f5~IyTljbD-1%H5 z3ne5g*b5d_7h-f>WfPo5O8P9J9|q>N@K#5RFcC9t?yvFOY9; zaV{rptrFeAC@2Ja^EJQ5rB=wOua}L~2hH-E(r7LXN0l^LJ9$GB3Vh4JPgj(MPV&)Tifzd=mWU zonn-mEq}M;5uaopg=0keBaerMCl-Ei?FP<_a1bFcoOi~0iT%4%z!@O$gb9cC0#i@j zqMP|M-P|Rs{g!i*bv2$JACPMWj*usoBkg?r*PIe`a@8(mK){W|SdSpz%TsR7k1PJ3 zZ){}zW;kyuGO6LVkw4Xt6uTA*xOoZehSCA86mU-EqaMu~BP%8D20)_0IFkyFoT;<+YYUs5o-os z7w#0CXX9N0lq{lOejQ^^Op~D*@LQT!(2CljeSJ31$g|`0D)gVI8vbNQr;D=Ac|Z1? z=-fDwlkf-b31isSlS49lfW%~loTTCQOA-g`i3uX&Xi zzv!L;9e~Hr>5i%(zzuEkNKy-Vd?#|G1@nyIkUxD>;Oyv#ZHvbV1k>U3$6HgL(c?x> z6ot^!E4wxHsm$;@oQ?MK`7<&##27x3f$<8`{_xd@M^>-Bf7VxZLF}h3HCB8*7@RDw z)gY-W|L7zczR^A6!Vu1xu_~AlH#$@8;Z}6&*o*Fx>g9@yaz5i+zEdd8Y02lpoDyN7 z^{{c;boI`7oW2$JAy-bD%t(O*crea$>d5&9M`MzYo%z5}Cf+MN+~ib6UX=4Y+*V!7 zt(#E;j%_E5`vmvkt^$6qcgsE8&KaC^yV4q-`6Yud*RVoE<%uu*#qSR%!M*n+?Gn;jm6in35OTzD+%PO#X+ zl)UdfAsPsa|CY%~BANsC+Jal;Rub<&*SdfJav{qC+)ktp`K(E86*n-Y9}f{u75p6~ z6-{$iKLn)I%smR4>*+m^~;dzP@8{qb~;HYI4Jj2u`Whr zAHT=HhL>h*4)zH<266)aRe}=q*DnwLCC^~aekhqK_dEquDUb2lzX@IHG3{{38Xgcu zOjC#YEQTj)$?mg3*KGC*voshZ*oL&a0D6}!vk!@aXY91|g9yBdMHTw<^tBG{&Ys{XFwtOu}x z=k7z&!gsfO@N@bNGYX8~1zyT4nXbv|?zdFcWOGYBMs5m z52np6^RZKSaXceFVaQ#`MR>)y@^8KroRCHCfemSPLoP4k>#e0;f&;7N3~KAighxgt z`u>*mHVYA7K9e0RZcnn7#I1noRaf0-vLnah=WIY6AEfG`Dq zs!S?Rb0lr^_xy z`58b*Jcf?|BK>QVI*xpD5^OzBUN;_E)2gr3tjA*x1(=KBn>;nMM{jrJs&?Ma;^Fke zHU=vSIMrqDN`p}Q2AS?fmmCHxf!1c^R%CeYpLGS=3lGb6WeLRR#Xl*VDRQ4>i z#BjYHjb8;J1zv=2qH38@ihHe=OhVIf#wc5KeMnA9!#xiMqo%DFCJZU&9P0O-rwp@o zdpi^AdcXZ2z+2qSmwkl-&(*evl@tB)ppi9C%{&Qc?(ahSWrx$3Ty~D*a(ALrQ7TDE zUXZI{IJ&(IgqYxGcmRn%R_gZf-!B3X`o$QA8RH}1cxc&5b6e;9CWfD$Z!g9RLC+N5 zz5M-r^N1WZd8mN@99970jV8brGeT}rJ)n;6n_;yF01~!%3S(wx(6^xZ91OnpFHK0s zhU3f5hpDOf)B8TDAjP*jnGbMQ3AfER`Xlwo<3q)RlqoS;g^I7I-ke>WagSuUd^~FY z+P~-Vi&03~pRQn|HG#CXe@i|NKl!FaOzz}Q+?LyHmQ3+uz14Q8%9R z?y>;FWE9<#`r-M`aQ)e80;QjH_nFrYWwJpwwh8-QW9JR;R-7l3F?y#se9#d)++iCd z$zZ{F5k08f!8wsh3l^;SqJD~ z9<=RBr^WKnLO#&vdTI}P`K<5M6ubW26k@G}6am<5ZaXL4mn6LI_qh@v#1NS4S7&{2*6zZ{8DhbBfAHQUBwSl-Mu!)xpdAiz9YY*@ z5lx?;4Eyvgh#HwAR4aD2lELJ9Zm)j2{>IX~p|xd~N5?JWr|Lhk>HiEY^<7+?yoz)T zBo&p~{UUy$BR!z8Ekw@W@=^PlzYU7Cz8Ml+5v*mMmFkD&4w)U!+PE~eKN|)uX9;E^ zGUONZ@?z=^Ux|PfJ!GQRUyvX9CO8U5elCUcjrHT5Q^&`yq+>K7j7#Q$gPz+Y#GiGWph1=Ni57Sy?p` z#wiF{*BVvf5zq1!8L$9&iy(0RH0>&l-93mKe(s$a2|AIMM%^_kZ`}mzN!TMLqnp?1 zmx{g_dTG?vl4b{cO|M`Mh{<<|Tj7OYZQ2LrPo7l9;=YQU+~~n9m*?Wp9}OXtfHHaH zz*v^d9kH*3@b|n7mWPHse#-q6{i~VAgX+z}>fk19=jk=K^&bUo8~_r%aTbK_!j!+v z`DOV?C?tUM9Lh)XCpPK+!m1BmkW77amx53I(TY(uH(imF;s*w|O>_ODgxvGR(*Yw% zQBD&Z{k4TR@hC{%)i-cTJATLb>7*WsS^){CmH;iY@7eS@$S+$u!dm9)J392$`yEeB{22!$la%2Nfs#& zb87}G1}AW@75RxSYu)SY=E$zsT&K4r20rz^3j?J{s#5*D4E>6 z{xwnRRb)K5w9yDc#JMpYz$dqs1UNV&VTG1vh=2>L!Xih zPH5o{N8YQj4E=`|vHk#G9y` zQ{6i*%~-u{VGxfLUG&r3I0p1V((kVxtW~-vVX-H?hNskfY5{gWbDH#A=&*7+F>!oR z+7?PE!H;-1W;A#yZRX}bo@`Q@6LUL5I4%7+#pn-w>qO{~>FTu(LomZ4#W$~lBCfCF zlMAh|6H%cUaDLJc);OT{1&R`6=0`HHO00^6Wn^dkL?Zpbu%Vbzn7-9h(Pcy563xSm zjXe0MIuhTGM5pfuXIxNbQJr22SG@>zpBhrAd3^GshC&BO9WNVw)>i`S%jZnew%JQ&i=zIHN^c^AH;p*s0lB7em;*oyH|T> zyqCZ{;D>i>8r~`fTLry)Ey16q<3xRf#H8FvH0NRQSgs42qvNjB(JW!&rK7BP=VQD{ z01GUWgm;BIx%5zM-~Q5k{$^hbY{_{8t6h1Cpg!zl+c3DQlz59@g&&v|h@*=?HLj!2 zE_jz9W9B}B zh9z=J`JuM5aJlJ>3}_<_Sl#LJLH`AIRHQNN@v=((9u!mu6z@r9rYBZCEUQ9s3o#$r zXMarvX72+Me3a_^!<32+tzE&-bE<_scU{*=JwhEwY?)$-ImRg=_yaf`Vh-1FAs9wkBhJ z1nBl?wcR^Cvxm>Q1~U@bF8ty_{kC$MT8+~8h6FTnZCUvkt-s^v-rmI3EOa_-(|xtF zN10<})r=^p{TE<*rXF#q2Vd~xSTs&KP=_k7xdk(YTI=nv?Cl(puY$#BDUg9eK7!#H z2f=e6#9o(+!+~r;(37)IQf03x{v}ko?+Zsx1Kuooc&8Alx4(yg-&M;cjckMm=!#fR zWT4P~hXy$;2{0knn zy?tq#)?!y*JzD5bYPaXVT?0&}XuR8_??%VAXZSSd|_#}WN2ZsP5 zny_p?}xVub=VOK>uHAe9+`C7)yI(#?%Q6>AcPUG-2s4^wA!M|JoaLk zTai<2%P+qveF*^ls2>h5p6#CUqZ?2wfy(B5N9`N>uhee4UOWy^G3I&||=$x|U>)NuA~ap)S&*M_0A zP?7_OWMWh~nDbjj)?y8BKDUNyVw>2!cHi|LD_%b6lBcgYG|CjmIOUWT^*ncDb-5l? zeSsQ{?^t>x_o&OKWA{)v^=AKk%IRyb;_6U6e#Qfs$Lf}P0`$Pi**r#A?2yd&*WS^vyX6ef%JX?bAzZ4+2N9mNwrz3D8 z-J}_?ns+;|ydo<=k>lP%eyV!q3)uLam&dW4e-js-qb0{QIS8=HOrY?9t?T;@A-T#V zlD~WUcT}ZlIn}3f62E@kd;39@N;x|0t341j(Ur#9`56QWV2)^GZplp*Ld6fK+ygwo z|MiGB6N)Mz$4mqO5UNk(S=z|&(z_6w3CuBg3j&SI_ItW}ea^wTepz{m3m3n!ds0Re zgJJ_z-%kkM@JBY$7Wvty-jeS-gkaM-A6DPM*AJ!UYhP;YLUy8@x1-JcK}H2kii$_h z9TvpiV*l<7_cZg*_k5NdB(bV!AmwanFs}a@)pi^zD#?vi&h%k>3>~)N$RnzZeJ;QO zQe9AoLUwd-$7A`Faa#T2o9qJI?P=}%CJp5txTY9R_rv8B?sgNIroB73toxc*3#1C@ zklBzq*yOAiNZe$uj+1n#zyTvWt36D$8`dU&7F*+q+*lZG4IoxBNs?AjV$o?4uF3;z z*b;e~2x|E0JmwQ10S=Vs2R5?w4*Zv_wfM8=4a-bxjD@TkQ{avWm$RQf1+$*flU195 zL~(kTL<1`CdG)~l?~DJO7O@M-vwP`cMBnw)_+4OFu3AXGdymwl+0TdBSLwxkk;3t%I@iaplbmrK%P- zE(xH7Z;*m-rzd^}rc86Ees|QPn?TZGl z>ibk9ng=@H$}q^t>BK9Knb;Uw&L()Px@#kJOnT zf&-Yt;hrvxsXg4|m3$+Zp9HW^`T&A9HIN34lJ<(jH+QffOuHiYRFy}ifKw>)HtQE}(bpt~fY*&ITcqTxR68O#jQuZlqz3zj-!X!1+0qhu zRk11`uJ_^^aR_o4#IZtkDniFOIpw^_`GE9Xf45mm@a4Nl`(3e}cO@@_D8lQo=W9Ts zjQENw&vz3ud{g8!O68t+9b;K5u0vAT;@V9 zXcK#v)}cRQjVzdT;Dj~Ijwq zLGo}I{Gu+6&+92m5SPuoCW0V%4-SW1;+Rr$WDwWg?FVMh`8VVXa*%9z5E3XIraQ}j z?yBlSEPB`{`zMXks?+Rn9SbG1Sj$?;veO&o157tAYnbWx25w^FUyTo3fmgBDB-^+z zh{{r!fw$7`(rtq739f=#Wy>YljP9;w32>N>Ay6rEc%nNjRseBjTHum!*N=Z=swNq{kE4x%C>Kjb8_q0W? z2O)}`W1SgrPQ+f1ckQf^6MC)fha{kg3zErC1+kG*8+imw7}75BCqX4@RX+*^Yu7hz zmeDlEQ76jbv7$mm=<$!zEqaxB>3e+v8EkbT6^M3eefUV@rZ1NhuQrR@eQR)V>E97q zJJgU1#F`--|ISk|axckFe={ni+k3Jd;qV{sI?|OKPBr)Cf1#~kF3S&&70k!Gr)N)} zuL@|$Ll|5wyC@anIbUdvves$Gtp^Q6h5~^YOlSF}g?z$(Znest(@L(T)eJvDupW>a zbM-UWoI=Sx70u0AksaW6c;jrrB4V~wVg4gmfyfjguUbw@n!0>0&TkxhU-&HiK|Xxm z?@HMhnz2lg;Kk^;->3`I)AKz!2Rsi6_+YkchIx{~YCiT-QDfF*QJ=4c0!I7mA?kKY z@2m)_Ql7e{OUZV8_!Dab&JWe>>l^%n+(sSl`Z(IlYLG8E^B*n%_;>gB~1TtC77Ffm?N|b<||WMsucM zV_oC>@SWY@q@JH-!TczYdfexQB1VKySP^=zQg&qBfu71=K@#$T(66z1xY_m>d$1@B z>is4$nmz1(O!pv9g9L3A{_nV7LJzu~S>BP^o#`M3^aX29B*pOOaQ2?<#I=h0US&H$ z@mjuEpQFUTgvN8&SM`qb)P%LQi|t8C+5jk^;G%f>Q@J}O~>UL zy7~>}LdAV~(*v8*oA|wY^nM5YB;X`s-tvNLh?mpt0?+w|vNQ55OSgzanh92z7e8qb z6Pk;H%G%!=@Uac^8*3F2vdL?XQ|_9s#6e4zUnA+IDnn=yeDQvk=oPHKqVfYTzwa4( zhit&#cRHM&q;GiZ!Y`I!N|CCM8aT#?tnA~aW+kiCiJk9`gY!lSNo<|AOQ7fwa_DNwvIlTC zn9czd@KKQDat+t4AUXUCBThZ>BMK^NO<`)bEb`rD=h-EHu44Q+^a1iAw&Df>X;flU0i_nfqy?p-03t- z=Eu^@qg(QC1zC+8zf;Nutz${QW8AmG67?(UcjswUyop_ym*a7QjM=L8J9+U%#OoH{ z^yvQd%6n<2SU$h)P2kut_R*ah_a|PuKsvZx&%q7hh^sdJ0(}j$`J|W)n!Cd2z+aF^ zXhuf{s&H@jhNA~`g#(if7IaWVRZK!hnUcxA3}s>Y(QpaZ2mp8k8Pmwr&+5+T0LtY6 zge{a0!|)prS(L-GyYN=r@+(XGl;+JTES|gx3#fCH-TpYVLm#D*+#cQA?znI#Wzug( ziTu!hmyk0+d45v7!RC7Z2%E73G_A1n^pcO88t7O#Fq!bi;0>pPn4}dh(qMNP?VY-8 zZ+iwv&jsn~QGO~^{S;8LO6{GO2TP5?8GV7p%1}Li{5)&=<|dx+uNU6jOVjH>PBgUQ zPgs7&O(ZdiwSYk}Am!~T0g(6u)$vwcF1hbUsYa)9b-V3*^=03LQR=%=FFRnlDn{D5 zCZ@I+k(C+dJ>~kwxrHdq%^z`2D_;=_x@w>vKGm_%I5IUN?wbqpwK>;yKmzbeyv2D6 zE~t*bB6&dl>*MH(ec}9dy4v~6IM>Te&@#wl%vRP{r#FI7@jN(c8+cvGp&a+tSYcHM zl5WKBCEiUl<%T$NbQZNAR@os6_graY`F!zO^o%0$9*@PVrL>IM;P-B> zulG-V`4LJUx5X6Xvz1O3>BxGye?XcbY@^G2DDTCgkJ;<`Yyw_Ij#G;+DrG+qlmeR( zdqzpQva)?-&X6V+*m&J{iuK)%Dvd1P{r$Wcb*RmE(2rNM3YT#FFp#1 zc;j>Oe2o46&XgmPxk8|_6db1l2(0l!(@9v$`v^2}Vr zMH496C{PudD-ZPu^7j;rVg8Ny3?);UFA+ZMq-RhYaB;Wd3b9hxPgI$+)~Br{+;D6 z;&*IuLt+FvA)sTEd0M6SF_P6;WS#K8$LWM@$z#M*7uU)V5RU6Y9KY-41yFC1E=6W+cjD^^hBS^T> zPrI!KxS;q>=6aV=X1g3I)j*$O!JJTf0bVl$(jiJx5Xx$@zk#!}CXB@o>=FRlTlOwX zJV(@J@pSD@+iiC#{5^Gzf)RzBd$!#Y=2^S#^W|H2wjs;@X>O3S@r$Y>7z}C zYW2r}OjLnZoZ0^3#~{ZoxtJ#|QMAA{(`{7$9fIT`6j4cGGZV@a^c5+DDQLw>(f!lb zqp3r8nVm450o7RNC`|?M&#!OoUegA@Uy41G%VAw~Pw>cep3_$>mYb&#?qkLg|n%t|BwPaHb&N#h<#=d@4CBs1tXcjP*Nm zZI*_&tioy-v_~~SJ&>eyl*8uP>a$IK78V>mBL!c)W7aCVdy)B#u;0Klz5&>ZnY+RZ_2mRLQ0Aw^40Y|DkL7IX}cAZ@rPBqTi1#(?OFRDp7*#o7uT z8yIKLym`AM1FkjDRG^8vVc3|bW8sgeHV8jN(TdsCKw|?Ay1l7M@U(Nq+hA z(fKe(^FG_|fX47Hc6h#>srHpz_irw4B>jLWAG5L6xmCKJrUY($#>frztwE5S9 zGdAyKoC0Wzqn8?QF1&bmI=UmRdMP}+%*G3?R?YsII`PqhXhDyGIz~RituON9_1BQq zJ4``%C#p}{Y=!udTLy{r>s#&BKe)F-%uhp{*S#kTXNh=(uAL;%z7>) z!@gV+AVC1cLW0CX-u#A@*!TVEe?O5Csgz13)pXZ%tHvf3$_yT?1pN4R+`kV=ZAY~f zfT^EOmkI<&O5&K6T@!27?Ge|$1-1B31;W&X2f3YX3uIl=7IB%@56Eoz)B_x0UVrd@ zNPIo{&>)hMLf3Rt!>T~dRA1DmSJLOx!4gAqa4FghZ46vc&hs(;`k4IGz&wvZm4E_N z%VLXEb@vB7Y;f{i_DvuXW8v3o4bI*A?Y6BB^1~yPlh{;I6)^VNBSL|W-S_c)M(Y5wz$GFPXE3{=CF#5q z&%M02up?k}rnMxMKo?|(a>|+sFyNT7CZhEu@bz!XmJG12lo4_em^KMg`3CQ-Lg_ey z&cmt~A&7;Ftv41O-KL^KfEVxI@&f#nBcaKc;+4K-2(1~Yc)q%A;NI={;S+89l;IRO zab^GwFSiWJg}RPM4J$K3K)7;|ZR|cJXvr3889s1taw%B%ZXpaGg94Dj!uER#T}@#=O2;Yy8UR4w0TN|n>hJgd)tAsv zi!$uzC%`FiHVGhqi2+Y>T)MXf>7;x@sf2($4y~V2fT7qi{6}g06*yn)=RU?~r-aHc z*y*C#c#q1qB>-eUn*jE`oY;qP*ic}=s%}AIwy%Q)tXCK4^;d4eOQo@vxoq}El`SQVI2Ye9@J~s!1qZ+;8{uMN^_;-VY}i$ zX=KBioYJkrumq+LPMiN~iF~L5tpV_E%xsIu$h&>i!$50w-webKwn}^-J)+#=Y^Z7$ zx|$9HMMLe0fJ&1Z;QQX-I|$HG+&-ZQ%khKO@1KF?%l961IE1tw^u%RnC@s=+o~bN^ zaVjtHqnSqR@^}D@Ok)8y+Wv;xa*vt-)p4MWIv2zz#_c%CIVLy|fGm5` zkuOxFvUbVoU76@!nIb^$g5LT%M@hRJc<3&eNFGoFw`iH5NhF;Z;qQ=tyrEXAO|IN?Mq!jt{4)+Ei7Z(6)uLOXo zh^J_^QO@S~v^~50$mH*n}?9lTcw@mMI6Q1!%=gwRYIY zSQ5yOJU~PGLzud_S}%|vJ1fsr0gzz>cyFMwp}U}N!0y;Lz6SnW-9BVTC~_M}rbQ}% z=ydk-6>=&-mSv)c8&GpBYw;}CyLEg#TF4Rrw*r6$YXD!@M{Hvp5v{5=W#Sb8#6jg? zE3}0U{s#{7QH{pw^6Cm`yza((5BvxRXuSf{oC2>i#kX@6wHy@EBL%+a06XAAOB#?o z3@_kW2wtNS97|JYqKo~S{Q6=52sHFXtRvLCliZ`7j&}$bvMJ#Dv1gV0007}p~N+~=uGAmobY(jV7tn)`X zfrvB!wn5+l@)yoL4t_OuK?YEqK=w8BOv4K(sfeWyz??)Y;)jcPhXi!K9e_9G!=}o> zFl*|12lgdnsY|S$0Kd)zwi5aFgm-}8g-E9a_#TM*psTWA#sT2;Nx2wTzpMc5;k7<3 zej3(diUD!Z83LbB-wf0@`r6cxs$pqj@!X(8e+L{(@%D0!{D6dx-d*@RmLh!~0DuMn z&SnUF?mNS456E4L1nH{z7$PSjLNUoHzG5#}UIl^?$gCY==jc-!0FCMo8_IhQNV8sZ zm7J(a8A_3d9#=@K&q6wrk6YlKAH2kCKvvene!gb_$Wk}Jic5xLSw$COQ)vu7KB42| z*;_t1H~jG`yd-3fAex1WKM2KRr@V!@E}yb%e?#j00=39W!&!lvV(0cTmsL>%49i)F z&jrD)xITk>1ZQxvmLJKeqBm%O_Kmg&;(O?1%159IYfAZ+s@4Vk%*CKQvxNRR@**A8 zN4N=x>3RZA?D)dO{BS)MX=LM|JcOwNv;lyV25<3n$QRYjdmU1-?rR>bb6|-%KHhnM zz6kCM=B^M+9CWmB>Rdrxtota_r>kU;U4{xTHdi@F+cF0sdjg}B?DGYbD%`v00r?iq zi-&FzwEtAa)O+r0KxeAm<2vSQc73UR6BEiSdGJTvdE#soC=S0Xeyx&m37O z#D4Jc#Bfi>j{~8o4YRBGQ)c9dYjcb$9XLSCXd;&=IuOu@8LxXw!}9_tq}P0ha=kWL zy~SbZ9E=0xc9{uQ2(7aPXd>!Dk_n`{P|3LjL^m<8OU~N`K#2~jXGyLM)K!4NY*xnh zawY6_gB;EAL}`x$p*>ENb383(uD}AGOSUq;654JQyC%yLo;aMiKbqa6dn zYF~A6(DTD;ir8Xg*lJ3*6;#A#JR02ChD8S?DBa*Ld;-K9@aJwjrgfpkr=t9gJpPS@ zy96DFfdPu^5seT8{%vTE`w^h^ei{L?)@cO$SY`gXDWr$e~_V^_BWl+@@uF4U?0gi|mT(Zz>x1ERi<#}r5J7)p0O zKEgUd+Ps_EFHgUW3Vk!xQH;)u!?XWoAFXNH&%rzf{1brqLFe?Rv4Q=7RRM1M=xJ24?7KG-xTrhT?LK1pMpff>6_LMvk^T35`E2Yuj+TCd}yW~O5HzR z-|xR?M9_!cGklSE{3(yWzb6GMAMJ_6;M*BLrqUlv=C{f8n|ag6r9Wo#k7psUzmn{O zy+q%1_RHz>Cch2*Fd2r_Z_&1_^3mfEkUq&mztoUaU7H~rGiU+_p=idjsbGhHAZ~vn zNa#m|KR=w~P-bs*?1*NK;16vaqBoOdE1Fxv$0ZM6qv-vA-o!B-#}-rws4-+JmSy=F z2v(tIE^XSMBh>K#{%D45$+rVwwX|=d2~G~WoIzNkQU$AN(p1CC=?B03sc+EXKTZ8l zWc*VY(ElI)bKbt;ir=2c??~LgQm^tD{WHQ?LGJ>|I{b#S%-`!(ocKJkHNpvlLt5M@1`{Kp~I1;hi?#m>i@qH3}obxa)+sjef;@xh2wX)3>lkI;=5eyY71 z8UOF6`Z8Sv8u?V5)e6V8>CbgME=^wyKer)l{l$YoHwgPiAEp(3`1V|XR5|~^PJKTaRLCOD8gMXxRzTV0IGiHD60sRXl>r>e>+|R&K^66Q9**J(2 zm>>W9bj5!VMi%=SD)zq3h#yt&kK=zK?Mr_KT|X$rUncs0F;qZ@e+3G^gbly={18KY zcljfKNWX_C=)=_?L3biw3+@m@r}_tO+J8PO_&o9>Quy@skv0R*|6dspfL8ttf{rV36gFwCCpSM6z@Fu^0r!lzr z*KNaZAAZu`2>K)TLzZ5LLRP35qro#pqkV%~WWPRrWhLm3yaWt`vriM~oflQeim?^AV4omaJJw|pe?>%@0(uxzT=l}Lj&j=kiwE? zV|@Si^kHy;=kYQA;h~}3(8<30JHH(FqbG(&zcLSK=U==xwBsFtiXdP>8^2xTn~#Pzp)dbK0t5}A*zjxYBLnm?2xH$~4)z)Kq0x`QAD+#p z!}j-^KIP!Yj2b*ukiqXK!4QJ^*Cim~_O*e)e-Mn%1l#wGzuNX`8-Lk|rp?zG!9afB z@Jq(+bL$WChK~5kuE7D{#P?(H*E0OM-}$$~{yj?gHp{EzKr69FSRf@cM3-79)p@ZrmAYLaAteAtJ=h5+wR(yCwQK^c@^ zGQ@v;2mc3>w#;WT?~i=_Z~28^&w4cH|G@bFH@sme(8qsfKW+AxAIziKil)gAo-a-^ zKhxjB@^62Ce&rv%U#hqdPr$DVisO?H z3;i42@MTcGh3!8WlTTCfD~<81p!r7w@{9TS(RiSFOP(0?AIQKzuWo)&CSV;tmCNVq z0CJ>%v?~8dzJ5P||1QPDUyHqg#U%v z#IH$A|IB=*(a?NFSRTK55oki9p&#GE_tmq%(hUB+6yk3tDlEWd?SR$;{$!H=T~hzo zQ~VF+@Gn`(znjGj=JPoF!z?c21Z69K>oR;>SNKg@^7|?T81K=CTp?NvLw>}6VIqIY z?Z03m|6l@sPhh^r{zCG?e#-S9&DtK2po0mVv_F%Ve}#Bp7>&hfo#{)-|6e2?pW5at z|N3tzEuV_)LZ?I=h5;nd|II@4J1dG`>f}e8^fmTZQZZnDkOlf9p&5I?41S}v z!T$~&!}u8Xv6lT$>6qwuR*e3=%+jacL5T|VBK{5a&SzNtM)V|c$KM=1!RbJnw*nc6Q|Kk)S z(mvnPpMPJ~`V;>1k7+i7U||ga*|<;n`dESbt}34^Q}499`&ZfM1vgR-SGSfNh%_e+&Q(&Z}ogij!E?aHU=d;U3l-x zhVj`iF1D)!7G61bN68>}uNL3HGBV?+-@&Zoak@74G<5XqIy4fZwrAz@uBX`%K3HYR?| zka&M}2mY~N-D#wS;tk8(LL{xu(XN%elBnf=wuNVYyd3ocy78gkTWT29w_Ev+o4(<@ zkEqx(y)R50V0EjLP~KdzTaHo+U?oim96i9ODn5lfVQu(1B%oKKsYBGY`S9{I2Vh;+ zlot77x3LX_?Qnq>T*g)~K~0?pQ)v%|(lb9y%mrW`Yo%ZGSe2kk7~ro8^6G?&8sA^m z;|cXDH$q$&SYs64vE};7W!UcWN?sdl1KO3Ax_Ae75TGCU1njk(Az++%T(0DSrvQIh zl{2~_O09HKFF$Q&Lp4B4INFSV&2MUb7<4=dcMBFwrTcmf#bU{c3AOZ`6~>z-%_s4} zf4An3>h}f%xO{h6b{?HJ(RB<-AEE?1t6>)Lqj;(M;M9Z>@1QVHV#uSjCKOJJCGs)uv<>zz8fDzQER?q0Hiu{ zOSoY7WPCOqG@zrKt_s|J*URhmaz?ev2z;&Ln!dp%-o+pA&xO-WuX+Nf0Jl>$rc8$p zIPUEeGakC)^sp8t4b@PoPb$_vsO4mE=ONO2+jNj_u9rR zp}PjhINz98N}m(k!YsIp6UEb+AkkgMZClOmiwlDw15zJCYmzU?*G4|=LDsaud_GO= zUD!`5W3ShMzb@$c+ym$ zKn+1&*g11539Ij@@x6Pd9QuNQ!zG+B_qt%l)xMF@j-*b$-*D;}8vP@KPauF&0v-C> z?k$Y4Cktb7DVIg2+0-491dp*tl{PQ_)k&;ozZ*yq7(lQB2g7gv2yD>SxOLB$$c@3S z2ozK_Nd1^!s{+{9K_~$8w+a)0p0gLAxrL4JLwN){@X0#`T?nWaC)$_~ej+o~4b2Fm zuyr!LZQFR|tMOr|^p36y(1$vf?Xz)x97Ry1(0eQiK)f+17xd~<^=#)gX#V2@u+1<4 z{LmDf&1dt4Cr(jcwA|&nzGhc=C>s#MTr57@~=vd_9X?Qai!&BswwtNFY6WzSp z-fkvUUc3_kJ6Ik7J_=?0NS0I1`_LKMy$aESa1Ab4_&Y!uCpy zt$4|CK>RYSrI7ZRNL$(NA2|Cyvs2fP28rx#U@YT9vw=yfypt8eW*MPnB^t#;)4hg( z1M)|E2nU?9RHrxA|c3whL4+uBmT994xBWQ*-EV3!r-;4RMFCH36)C~7@?w*oMt zWMnhlX*E^#2vGEJjV{;$6ud81zrXW<(QA}*j;2#FfX;!|@`?u>lXdjSIOqEO=1(-y z>hn6RfMT%JOgcgt7$DGv2k&ihVh10LoMH%zg4FKOXpMdjrs5(oAqBk+}n-FT#mPe4*gex|(a~daZq)Ewy&3 zgL@@ znOoOVi>~klqI)Q?%MvAj?yo)ss$Tl2_SOlh5x-(&=jNt|+sb=Xz$xIS!LTQMf~{4vxw0C|N#O0e(e^5n?1 zS|$&`Ttib{F+aL`;3-n(nqM?G&-qZUeJphmVgrWz0d}2aEN0tsGjhCmFGSHK4AtUj zn!2mB^hMa-ij?mjZ;d$Vtj%Mi7c7r5#0$>OBkB4QZ@lQC~75=AHe1B_#|PnZ;&R6XjE*!}^P}(SD~%D|F>WT2EWPJ(eD1dr&?xEdvg23zwxryq zULyPyQe96*ugHnncQ1&XG*cdr?KV&4B>Ap@`Y`u9ku?}$CS&}eMk;IGwCiJO<*FMD2&}&Gtici zg{oS&EWN{si*gF}rdPaLz650ithtJO z#Qot>*onkGs$TACIiT~3V;4HsPU`?1Zi$*xi^J}k{vi~j-m(qqp;vBiB#k(ZEDqGV z2}^*4y+)}qI<_cpaMil zSXnKYopu$vlD1q;;ku1x04A1+kXd>Z_@H+VGZ_?Hb-A4AXFx^;=Sc_}%B3q37@{8B zqF;-Va7W01YCUQ0c4PRpD(Ac{uXbP&PqPj7Wo;@l zPi`P(K+-ZKbPDi&DphA3}KR`G#3InfK3r%uG+w#0a_9G@$Ub4z&SvE)~>d$sa( z^T5>88Rnp=_#|=pI?|qOJ1*U^Dc$gJ=%n?UTxIk_Zy}BaL}af9JiHZ8r>dZ)gCZ0p|G#;f;|3_VyY_rPs$ocY<0`pwwNXL{O3;63n7 z>s>M-amv{6;SNAy;{bT-=yp0x>Pg1C?1uYKz4rk)*TW1!GmEp@LSrJRu?#tq&j2}%q&dgUeCiSSF&rU5X^s_he} z+eA7hfrdiPz&3`K^;zKf1N;>rdb8)OQTph-I<9J%054HW7BBLLEB|z`5PW{7Nnm1Z z#XBph(71A3(P(gtEP-y|o!2dXCi~FV;Mp0OKvRkd9P9v!1lQ6oq90%BE70^!MX2IW z4!uRgv*|YhVk13PfYvlApmrWM!E+@aP=l5}DC;~IYoHM0k34DI-IsX2HuOhkAzBJw zEdek)X@KT@s`&V|nhq{=@7{7950EB1P3;IkxvmMki>9MJPe2g^(>9sQ{higVwVPnp z%bs>&fI46eJXl&M;$g~1avtpHnB3T^bs?ca<-0s1G#mk(2q_wrF4@kPW)=tr8wemG zfSDrBm9glf75lpro5u(R_rZeXVPDJKgc|~fDq;`hp~g6ZIqQbQVbPK}1b%qFrqGj* z*y8n_RNr*G;qoCH;P%ruJ)`7UeKu-64^p7oQhUS^B`86VQAX0G* ziG};MmqSv_q#=vY(~p4fx?K`q+DBo)0d=Q9qBY)Kg;vMbwE-e2hk+;D?+eaMZsU`E zm>1{W@+}z-{QE4tAvdK>nk2vGQK+|^g#G$!dEMHYlC{~HW zJC?SW*cYy^y#Sd?N97p50|0xna}3f3y1kA;DP4)_2p;)U$Y)@=IjwJfoWWNklw2?! z;>_j#Ekp{+Rpk11&$u1(it3b}9c|I&xFEuN(~Hb8H*Y~@IG&j*9p}(k0SLZu-@Dl7 z;`1rZZ=N}9r7u+wQWW&7EOhN@!Vc2JTd|PKHQBm}Z_4IMKIt@AV_rcfErw+-1@iwE&&hw<4bqi&38$N`uBXW~N^>8!n`2umunTZ?|j|D0e_-H-KN5vq+jJGGc9)kzU z*r;K+EIS#ari6t2KD47 zZBCa2n}I3^q8 zl?Q{46(AI6OT941u?Gq)Acub|5Q+Gw`B~YwF64mj<03W)LX&~%zJmZVY;d5JP{A0& z+4~STo;sppYtaxo>Y|jR}frhyHHlI^?YT#ym|K)rOUNe2|VC z8Rw*0xsxXl0ByF+W^x(zt9ZL=xg_H_AWujAiF?$NtaD^!JgSAdUN|RKnk>5cs?K@D zGa>jsO^V(;N{XhRw2Xt`LhAWjl`DJTNbIRMkzCuyZm1ZW_RF~lPRqcZ$}8X%YrQbp zcm;=uF_nruOETd+Pm(3Ru!I46fcuL+zRyKGSNQx$uVIy-czVGTk>||dV%B$7bn{}- zrmJL}*RyX0$8p(?`E~P_Q`iAqo;(v*(~|oWWUy*F*fWZGo@gDIfiTAo?o;62yimgS zm6CX38cwl~^kdAy1Ib=l2{HA}?^C2hAUIKR>wr~ye07!B53T?Se$AWoIeV{ncN?gq zykW9V^!1y~UVw!zm{kx3)1j{xJoW)Q93I7nRP*Bv!0QKa!;!s;$(t;@0MDpuuNQ48 zm0G8#O04osKDJtg;pFoqpXMezu=k9iNg5!NfUBi0kmqI$Oxbe*pfkt8aI~%^q|C|t zO_#1%b-w{erID}>I3k5?y(u-sU#`eIl3)@3O^0?LCtptHO$4HdlE3pnQFn=FxF1h; z2AP3LA!I6L)NjD)rjko&LBv6+29NnY%b020AL(5^8S8U0tlOPkw>nqTTL3=3yT4EL z7%`Aay6#UGqPA$Hxn(>^l4Id#@&GyGN7$E_jh#8Lfx>?8Zyt@o@{#>kFz*R`A=%41 zUFtUSEAWpv=9;&|9T=V2vwuHu(vslhS}I0qd}z-1R?vcq18ou`?lAQhd+A(QpEwMU z)9flWuy8ppT<36D(fg$#+hV@K9i}A;Q0FZEL_gmO%#Hef-T=yOH=@GR|1myE1U;#5<*YgV_)v^$BfL(k9nmq1sPQ%iX57ddQmeIu< zfHXX4Tz_byMM!S1_ofipyh3hI%&*<$zPROWxOwlGA!f=1<$LSyiVvg&#LeCTr61jV z6Te5rFr!R6-_^%DM=JKRZcAh}BB|6(yqRUp)TjHs%gL%OPX){{(D>4&xd1+RqJ#fw zy)OOj7W+*rBqB`revu|4-9o;qpLci5Y@Y*YNyFl$^rTeFW)#=63k^Anpa*707jN_JmgQ@Om=3|JE7aw>qJ@Ng?uORC7+ z2YT2i?|>4_JjiiMjRQDxfD!FJMhi`nhu7Q2IqXzM+hm&v)U0TMq~O5zM<8;T!GmP6 zF>lA1yThEkGXJnZG_+ZS|?*Tb#lCOFqTjjIWrm&J~8#6F8 zszA{@z2Ea~iS5bdfpw&&_?}ec9WXP&Nf6K)2}+0^D7IICH_Ve(dbWW6Sv1wwrB-Y3 z^+QD+A2JXGKAH3ha9DV&Js9}LaCj+Ys=yE zdZUmX1ob4LxGL?j*DJS~SMp)WD+@FrIy>;*pzLHLjXZL(4n@LIZig0mk;9^G9jn&k z>HSFbcW^)p$O3PqAs}}Xja)XIfE=*f1tba*SdiWxb8-k-W0XKO#4D(C@9+|~hb08+ zF6_W6lfeGS@p_ytinmo^2rI73NRzVAVG&J?Iv_iwtSSqc_46la|iEnCK`W@)VfdFeI}pd=JUn zUn8A5G?-&9KRJDyUrc}%uRUu6-08f&obH_xNn>yVR>`>|H}ECrE!-xv$|=cw*j}R^ zfu0zinm`4OFb!X zP+kz}Di`3RgldWo$jg>DkYRILn_{eb-aPI#3FImCu;8)Becd@#4Uj{T?5|}Rg$2?&Y?OxkNG8%|925;`w3Gmhp8R~5 zoqzT-&aLF!1-*LZC#;KlN3lad&K$6mtBRh4NUC8!LVj@B@5P!Bz}E#ga(*lk(4D|< zk{3hrk4%FEmV6-r%mEOutgk2_3T;+gGa@^WGcfs}Ndi2#J3IOjBq;zp?A(ZLjsy(0 zn7cFGlC8WP&uighArLyScO6*6fV>N6_ufy(%Y+46ie4<>hykEz4c2)2u2yJ*Se zI2)%0&9~|0aSBDw`Pyyl((X9ipj0$^ouDl1Bx6M{KcN&u6Cm6HqPpF<4$Q-wR8Pz*6?$ z(X844RAG3RAWXAZ>FPAbz!xzBl(=`E6)rQ;6MF8fPu}4dxDoi<=*7d8C5P*M=l9UD zq=%THN21swP%C4vtN*l=K5rVw+H|c-&rjf99eDpnJk7KaQm2nyps;(ZRKgB3W2GSp zhXa|+Vr$!WbS<$A+cSW8vTryZt_94;5dLnP8=GMfT_MsvwO)NLx_D=yDkv8-PAd%x zav}~fNL|D0NW5B^Bd%Firl|yV0Rg@3cj}=-6-`m?trY9vfEgw*;l_-^%8obIp0B1? z7S>5+xhipfz=PyTkncN-2UZPPs`JvikGA7Y0yt(2RM0KlrZCmmEQblNry$M!p3 zAHn-b+>8Alw-%323$g;CTkGbAFnJ`-=4ifl3d&~8MdG}u@bLsEv$%H8Wyfd`W`_U==qHf`A8gyq z-u;LYBjij-^DMOUwZJt9{vfHD1BKa+z3I!_i=mL?BL$=~8Pe3SE?Jw#ndcd=hL2I& z13!aIJZuvWMobI*Hd6Rx-_j8lcP!HL;Jtl=>+LP)qPoW$d`YP}zd_~&Nk{_&Ump+g z0_ze^ANj}A5o6Ix@b!FCXlvO|X23bu9jJ1>bToM8m;o>kgrB=oW&TU{mFGp?#?#B> z8FS&pHLzhB|5?QE@^~9>J+a|~JwnYvj4Fe!hb?geFN5S1)Sz6?z)EiyOwG#uBb?qm z@S|yv^k%`KN1?S(Jz1*lq7&^i3+Y=43uVffg7aXl_VeB5<~i`< z8}Kz)4Bp~kWabe_<3kS4O1)~X#f@v$^#_sP){TGOq7!DzXZv)999;>Swri<8T{c{- zX<-y%AGiJO5}SUx*jflqBSaPR0iqfS)~^^SsJJ6F(mTxUHB(U<59Vu`i!eJJ=i$`r zr=A9-4HV>H(S?dS8@2+^rZDB%IY+ivzbFg?7OFb|Hc#@Pkk5@Zzpg0nU|)(SV^XoJwa3!+CYhSRm@Nn733;nE(G z^Tr1+@{;aMKVK`F~ooX6q^AD<_n)~-ow2| zC`yZJln1noM!DsV=lY^RWeb-t4?!iNx`+>ISSn(M>y9BC%-sS*5;Gw@^VTjLC7|0- zt{aishG88|HlM7AfD{w=N15mBP?pV7}Y6Xm-HOt<4po6(oJM!Nc+~Nkf z;SurS35qWd_I&G~ipfSSYsETt@1>5&>Nf#o2xpsSN4SfP4+qb9PpA4Ys^leE2j@tw zM?q%~{G%-n@wl!nD*&tbM`&aDIVtMIq4os_q8uT8CqU+LVq4?Dp^(LgDnSg{;!$at zk%YS^0gnYt$o7o58DelbvB49C>@TFYw>pJAl_gkpJUfY)uXQ-SQeHa&ayk_^FOosy z*bzJlPjfCn+zk~8Lvm*7D5xXow@I(UEp)Z%rLw^&BHcq(@mi&)^?JUZawk=>{H|RL z3`#@tL^4i+id>WDe2Ija$QiE78HlnD6B4=GeTDUe-YbOGTMO`XgxxX&+MHcLw&cw7 zq!JU;1szM1_oBB1Ia?j`z#H;19;z;IC(6p6ku?(X!whBN79?Lu>S zbg5T~mxHZUGYz!34*!N=qNITQz`?`?f7=Yx1d#_68gTKGF&oQvTd%wMm{e7?t*m3?)bJqX~qj@XPy6!OWO9;sh@LInNYO%6ufQNP1&48O&r&;8(9GXbRW1xwGRS)so22=ea=g zdoBi^o}FP{s8V{V>RXtnCg1M<<;F0bwaTw->gjzlHDSIL;(b29Uy^p{xss~e5WL6a zk>8aG*_PRS#ihGASt2gwjk?jK_BhHB`y#MwT0Ne6!X&&z?Bh z%Yb8qZd44g^$nn;+l3Ruw$}s8WR@l`yjGE10G_UgyKX=t&(Z}B=JP?;GUg0X0W5Sp z14y-;SE%%1p|&Cm`3?}F(3KDTP@y_m2?{FM!H~<{)i;KH(rhf>NfF6|$7HqOKwZU@ zd>DHZ6_P@&_(|&|Zu3+s-bH5u2G)&Ihx)ZcbyI&nc-ES&_A8j}iD#jppL+$#s}A0; z5EvP(6rqdl7j5U^WY8v zx7wvmstB@~u$2Laox6{uExVAY@Y468AtfLNBD_(qwLKIrFTq&f)~ljcoqbO>EH%J6 z{9JlaQ0I~YnPeB8Juu9Zbnf|!S5X!s2k)8d2}Sfxo~@jl?NV{i(=88M`S9-g6=(R< zxf=N6@y2uG^p3hi=q2O}svOjS%}8J`gR6wH!}QDw;wu=*P$Z-_N_&opYbK&*wt{k6YTSHKNrj zdIF<+_<$Eest?f2NF@d19WGX|fXG(XN8$IC^O!4Sk*D4w|i>>hXXfIE!#D9y8zk(Ll~7H`wikuo_q7Oh@!uY?x& z{y7K2IPu~n&vH&_0cMHaRE-bK0MDrBcjMqmQ%et_IRiFSL4{s{H%dCm&zB86@i|#ITP-1Nw79O*EbE;q(K5$eFyeVVWpW8 zxjf+ZV6Hp$Ws;e0jXxrOTcIYr-)$&@kSyUZ2YZ8 zp=AvvR0zCM3WSu6fJ)2P^5qDnS4-Rzl@IfVCZ60myd*U6=fFv*GkpK-RkFOCDKiv( zyqwr6Vutky<{ln3YnWoA zi{z?dFV{lPV90#KRl>Nxqb%nWsBmHVM6BGVd!MM6Lg)kuL`tk z>ksAYHW41L=)jY~{L_Q%B90~GBi*8Apqw>JTA3T}?Y-?s-A@8=jY`KF!eBi?v-s1A)+`mJgutA_8m#k@I!i0%=R zKCueCbGgZ(lPk9!>kfE6u6e3Ye3^Jsm&cI9n;?d}fN;cB3lV$%VLR>a}XueK?XtBOq?FhHqukzIh9x-z8{QX{r` zZYoF|EBy%?01w!((ub1KZReO8hWGf=}qF?$Qn69*hAr$sj9 z40{jB1>OM&8l2q1*C&`0CUzVwBH%^J>%fWZEKe5`d_&;R8+@rx?ZeZWD)w|V| z^0hlKYJW7l+~w@qQe2$MVKrDRMPbx>H~Wdv@O}fg6MBP?Az0~w#?wH;4c31@MEVZ- zl(-{K4wDx$$KBxTrgJ*(1W!u(%{IYZ)Drh)g0;=B81i*iv3lR29}XN+9K42sXuuuh zYiR%urLhiBaF5ICbJzvbp6^?#NUmMzC?s40poCg6d2Gn>#`Z68ZjfPeppe;SAbEMk z1zm2NQH$A$p){tQron6PcjPJILZzlWbciLB2w{U{%*?umAy2SX*H z%j9t(PGQpf!gvZN&8e;jA$EE@40DtSC?kn*9i}s{&M2w&qcLRn@lmP|MC)(cfUY@p zM%IQljgjXC={!CQG9+G5EVHkmH{`a6^96PYV`ov1_uG{O9&gz=wsQ)EiZ{!OULyhZ z$b6{}d~^yNku1Vwv*a15E634T1(CS+J8B%Hi+6%NjdWV=om(HE7T$?#zqI37!vxH^ z3Otppfdi8bQ-%>(w@xiA=?qEY-z6uX>ZiY44^(JhEo)7%qKPL;Nch{D8#)yJ8k4Dj z<1W-~qpa&b2vVD!PSPc-DR>mZ7CH;0gdmq71&`%Ahyq^5Z4%t>9sU^P-l}JSwO#29 z%65QYEz*vrO49a=2rm4iJY5)zD1lSYOioGPKm$=tH@K)DTC3d_ElF-xdb(4AjcLil z0BUmrg-nm!Ex?T4Md5HwupLANlT^Zcg-4^HI|5ooBz}o`!=#a$A)Bv!9OzD- zWMLAZ=tI?FbTw&DZI&F#+PS?{9h@iuHwzTflvl`<;a4D%XLKhz-DY^m$@>cQahXHU zBgxe}P&Xb{oKhd#Ci!oChjI`#usp1u8;WC?qoK$oY2Vz2$qq#R3fSkOy7Ud%2|{~@ z+nu6O@Ici8{i2EiI+_njf%`O0s@th%=UopI_Psz7J!g*7HFn{mC4c|e!!1aYKr zzz!6q*@2|x$5nq}Im6%Ui+!!Uz&;`C&yr4$4?kQ$yMF^5d3 zPaf>&;|`VL<|ZwJ^rE2@zZOJF1U@;Fm#e6u=SVDJkw?)+?y5Sh?J)=L@LpnOk@u|z zvLW@xu+dxbFa6sJSz(hlvlg=)$`dfA`~TUy4uB@^HLljxid$P+Yu%$&@Uj!FBOwU{ zLKuNS;>_NAF;ukTsI9B+RjXBNRa^*eX|-zIRx2_@tg{NJb>P79zDsfthO^k>tMok# zmrL&M|NqAC+Yo{!v1Lj#If4|#GwS0QGOk5HWa^2<2p_eW8T>G_f?5gLlj8m#3`-eqA(P6B^XgcrUypQ$XuueW#TMSW>_Fs z8AgI3(82KpjwTLFPL9E8qw>)6aUu>xIZ=|L6B4AMR0|c%Std0+B3^5ilHe}s4ti8j zNI)Ptj>mEkEpl2g7v)+?IFC$Z5hYG$s45{c7)Oa?83IjCD>*z`NrLI)Tq?p&;2NBc zV7t^57ePb9Y-$`;W3=;F7A_PTLfiwq&tWjW)b5NV3AhX>7nDK4KgAgWmR}f=p;Jrb z7EN5do?$gH#I%@TCPc6p!Or*)S9U8xvykW}8aoC`NX0SX$`B}up%~<9Nf-e#{ADn8 z)M#hh0>hQ$I2#X5YG81z@xd&UEh5~Qz>#s;!7M%pssn@glIVC5*BJy}8H7fJGU_0T zl0#C60y$D?ERJh4i2_|&uY5qxWQUW+mN4-Ve1n6l=7liD0xdt7r6VeNPBo9BG77ma zEDCX$cu_<=cr6VK6<|`f3a@3$f{h^-vqQwT=)_@+uow+JhM?5|WFpB;I%@!=r$kD0 z7BLGX9s|{0P^&Bpv&UE!N+B6FQdn?2(8AHgCvaJMeV9xaLyIC>EDn~$$dD>SHK9l> zPZeW9bssxa3-+lzlt~H$c4pHJG&Q0%aDzo+GvFMDR&0!>>a9@t4+aY(+z=TejI}~Z zf*}$S&_!%Jdi4N#6q80b0|pgyAVt&}z=K+e$VeQUMCMUh<_JncoCSoH5u_S}Vhtst zdFIpzqKK#F3S#YYlQD`P80D}!5oK5mEjX5`gu7EyB?M`lR4on`1v9B;MvR4Pi4EmM zXl)FOwN)dYkK9+8e2v&r{ zvl68mIhV(?;&|N91V+3ficL`P>6V~SxzrfMz=@+_+Oq_wfYIC#{-HRayn+-V3qmX~ z0XAAs3v!Yy;Z9n#CY%sJ38RqdN&`+T!12jc8B3_*()n;#a#fszA+RdK=RcWQt=2MoF}iuqb?ZfY}hqHX{L?C@l+T=1GY> zxyh_!vTaU*g)d`9L2fHfW>-YRP-~u9#<5V80BG1+VklD!!F91*6a;XEA(Cp@ToNA! zty9&i1SyZ8jf8}IlnE|hFRnkL4hR>0H#u9 zG;3rcODNeKBx6CyBrE|@g+XK!G75}Q4CsIW$#wE*p*q4Mu`&cQ8z=)2lgboCYT`{` z@`gZ(nU*coO9=>7iXu&uO~+zb!=hj$Cn#ZB7*m6YH9R4iCqpr?2p^{6+V}=&7NRyQ z0z_)HO@)$*F2q3MMU$iX6gVlsKnfuTNi{J#AwfilkV}Q41ZWl#(DxyZ4r9vAKM#So4iTVU%tT2oitq6duC9w+Pu|YIaEDk53*yKtUmx-#KPz{G1 zWhJr@RU{1YX7glr4O0ghx(>34qBhHw5l*|778+?LhnmQcLaT<-QGzy(CRRK3ns6Eu zGPQK<$ar}yFasM$4OAv*#lW|s|$z;)i8AYMu z3>=-2YnSn2tl=`Q79RyQ2Xa%ml%wIq+jxAG?_!ixA&mC38oax7H}1@aW)a?`2?jciVu4%Wzo%+cmt#*q720h*M`Ug zHAY1Yi!KxdMsd|RK?q_c^HgMrzUU%YCaVPU>MhZnh}`X zp&GS7SyBgyD+&o$sg<}`wLB8?#seHt5?+i$6bi*WQRpQkTAeYF8zv5?*-S7EJH}>q zfh?zhhYJWdD{N-Otc!~hS>vPS@k+BPC|nxrFoPw{z|#>LD&?pK15*r@6_MnKP-jpq zpDfX`$P6{$Y+Z;gTprGkV&cW-KnGx)SQG@saug~O(+D+vG8I*ch{HILRVb7jA%lX$ zV#$Mr5T+Id(4wU#yPju{QrV0=li3=^5F@w}Lne$6p;w0`4TiJ<6uyhY z#Ri-pDgx$v$5;>`?p+pQsIYC7b zC^TWrAbJoU2kF#2jb6jED|HFtP(49Pj#pC+;IzRzP4alF!4MOLGwY%9OQB;a6k%q& zRVQFjOawhEA%-MI=b%Cf1pFUINsw@YEmDO{5|2P?G>%TvIzo94s62!gGB&6r4wX__ zws@#Vjf+9;6^&NoP}nI(vkoWF2StTJ@{}%0XAYM;_#D2go-qa=4vAs{9nJ)`t28y* z*C9NFX*Phwink_c^_pn4I2!C__%i6Jgy7=?;z<^hQ5qyN(#RZbppp{nH0TU^5}AdI zAfV!#EY?$F)!|A5_Aa{C=y+e0YV?Kp&<^AK^pB!`YVG5#gMh#s|wmZX6Pa}B!DQtCo zkeQE{u)^3D94moOjgh+i;tHtdv1^5Tt28nu4BSm@szhwz#;T2MlQPyG0G%-6W6g*v zM3Nw7DqMA+09oUdT2q3VOSMKDrFeL13Pi1F7A-*#5f>VI6u}A(IZkZ1ia`$pH?bqt304jPFC;JmVgzyF0%HgoanVx~ z=pYx^bb>k_uN8@cLb$TXNE#|c8A4o~I4aNzrEW@-Bv=y;8DByf2Q@z9Ly5c)v4x?t zF(ouEQoCl&VOhjT)IDI3YeDfvHpo zwUR&y*(jGq%G7+JEJnl+m*6CNxC>s=Ris@t~pU1XBfEJ#L z7-(}Eq&g8H5ONK2{JVuFSR$^nN)JQ?veG23Q#CC$fMW5pIR z!Vgu@F0tB@zO|@svm?yN~6@n4AI@UvGjjRu0IJH?b)3aZ%6< z#T13NQt7NnvxEzkm~4(TCPc%RP?!u$P^2a(GEfA#fEyo7i3-=pGc17&U}ghz^P-rc1e-hN zr6C7X!Gp+Uvk@!HOh&1P9IuOr1>d|~8$*M}4smf5rH&5?t|U#Qo&#S(2?_<7!w85~ z1rWv2Y7V#paCV*%QY~o?VI0dAU@;g4!EiaK36jYTrf9JhX1Z%&x1czWW(bO)#xY4IvNklqB4We@8+qtEf_BUv$O zH8V^WnZRR3TjWBy)fPx%gcF!VyO;;2Gg<`07PFvdK_tZyp(dh+p&?cl7cVqLN3z6F zc@8jIiVqH8b1X4}08$hTxyS3{bWAQJz6AwCsR@qF2{lDV$J!(CbP9>D4belDnp6}i zlj8-@vI@r)kpiharBG)U5ET}LKn^Brqcj%4H-tzvy2N1`BHh8GQAm)(OIDl00y!i) zgGdjjb7lI3Skzz4vO#(>jD+UIiXthz1eQ@~gOXW?(N4k{qImcyo;aEcS?PABU1Cv6 z;qmo>1fhm*CWi+pB+%847Da%TJr)%yng`uuM6qm3q$_x)4WkA?w2LiQK_d=!2qn^l z8np}t2O5fTV<>W6pgt}{NeYy~QbxwG#E8hoP$&bb)_~ARU6>G@zYKMlIW{0(4XenY zu}M%#6~&RokQmeey9~1EafZk^t%(^PYLW1Hk%4F^n4||Gt|9Xy<5)3qP8oa-Tnsdk z%A}1ThKXV$5h0!qh9#6Yn0R(pv|blaB`L&;K&Z@TAb2Lh9!}CzRV9l4s`O>2hvFtTTZ~a9Y(|2}h#=aSVMg0)x>0BJm`9 z2v1IfxR4_NrBhq1g%5ENqbdMuvL!60l@Ua?={X99IXJ-*5(rGdAO?qrhlJV`K_XSG zodvhX=bCvCW3j>5=tQ0Pu9;P;N0;tSbJD)});lLD8lAt0vgrX)9q#Ow^ z#OBoD?3MrtR}=#-+Mqx(i3jPjh#0EA6$ZL1=bq0G;P8Uu6;`esnsT7)i2_ciPQ=i} zi70VF%t)>-juSx_Mbn}qBJosNphYTU^5U)Gkq&-bjKr>B1qcNcRUpyD+K~}4G6_41 z7Nu2$P~nRLqs8H5MSwISm?;d$#W2O(P!1EM76WE%!?heSC}gxkZa5D|HCosP1Jvn| z!*S6}o}DiPTuKRGO6d?kCn`ft4A>?{0v*vNaL5)*pdvJYYfjKHL*t?Y6_GRv*JI+d{qYMoH+no)pFBb-Iwxe5Kl$W|NbeGLU1%}+Ei(OZn*D?G=wLRu+zNBh(M@` z^GqoqCs0cIx2O6(W%ey>t?Qk#QNZOU-@Y8BdQYXmhH#>zk;E2TRbza;r~TqwH&U(B ze#=od`bXtC#%1h5dM1%upFh~wL#A&B`{MCW>G14P5MCXgVM8G84l(J(1_R`mKZ8-w z-FX=aTV9Zr(PD)b^yoal*FMp&0+HF|akelRa;vtXGVa-QSDpGAfpO17e5txdQzucm zR4QmOE$pSNT~lJwlf1<&t_IGHq<~kUg1Y9*Ezl9+Em6VLOc>ef!d0&U1R`WGLcPg| zM(`YX6Uhi;0WT2+oibe$Zy_&KBbVBY7BI&V?-|$V!&j->YmUgO3?RK`c(@>@>u;~I zq%}lj5vUcYi&Di1DI9@V6&l3$vIZFyREzsVz+!S`f0 z$e;`q9fwX}l%2yh8cm*q8oA8|-Jud-oEcMWhh|;nM&HUIcRtp0Ci+?kuMt>6K!WgB z84yJOK(zx($WK9!?oYW8BRWI2^vu%FRXcw4SS{Yr(S6lwg^uNQGz`{&g?>Sm{d}lM z@o3)XLq&{+QKEq51xf3opub_XBUA`-c*|=51s)!&icwzVO6WipSRk+I;HBe)sik%r zhBBx`ntvGt0k4nyZm?^+7tb?g9KB7{i8g z9J_R4(6b-nHH^}x!t$Xj=%vfL;K@3G0&*+@E2Q!|jPB5NUHu z8xyLYU2Y>N7bT&-FE7>R8c&7(jX5;D>;O25iCI*PmS^~AI{?!!>;c66T6U6p|Hwf z`(K82|9wt@xK9O6VH+(lZXU=Qfuu{d4I&co^8X(7Rlx)=s`aYVP_2aeXt>Hgz^9=; z!n4%bi|CWrA&NaZw}K$ViX?pD4{Y=e|31iW2hnN)1G$t~`!sFL|~C zR*oZ9A`NU9F*Yd{Rd{OX!|zhyr6wJLDKXk?Mm_A(Q~Z>!QNhp?Ljk8?-$94T!XR{D z?5PQkRy~83ZZ$!$z$0z2skADa%>=Fr@T{O|JbI%;uD1DGj8=c61wxnE&z}Mh{Cj;-3DO4H(kE2q-aZ?_dL;nb>Kje{@zFpyl-dq$A1ldKOa-S>0FEIJ`|#PLcUbwqZC5`9Pl6?bJOEI-SRoqrIs^ozl7Ile^Z%8A z@NA)1^a2Z3%hV1q-O3~f7OU2&4RSxMmco@`hi0~*Tm+x2kY)!dNN6KpB+6(p+tC+Q zhD1sO*RD%qA#>DlEW5gwG4tjIN-8DbzEBwapNOX5%2H@wAf8fz^J;**8_U7S*iZTNTkxk>kSDJ} zlM^rjfvpLGPFg|93EPD?*x>i9XB9f!D-*0bvgVyoh9^afUG-K7_Liz`cUl{!w@VLu zUA%%WM;X%<#RkxzvO!BixAXs>&!D#$Aw>gCjCT73UPv8Rot1{sSEZQr>&Qw&XcZE} zJP_fvh%0@Zr*Z_##qcZ7zn*JjeDp>prO{qPe}gyPXNK9uE{_@ND0z;Z46ZLUrsoRd z!E5)&p6xcTK6HTT{O6;C*WfY#M-5?oMdvltI8`#dUxNxIlgSmmWq1Vte`O4Ng7!7R zh;YZMfQ`yr)aV~5d@1!_SBju}3SgfR;d(=bk{ha3kz!b#W&@V%`kyo#@YG6TrPRar za%O|uI;qkQsC*5C;<4&p?iw#?n*8h4c{EQp-s^|x8nl*lDCCmcNXLH_^4<0P=IPy@?j+WO%t9>NIAsO zJV6~VpDn?kKp~L;tU-bkk%T899_qk6_GkkJ0Bv{@g^UB>NTw1uOAi z?)I~`UkUqf0;9xhXZ;{b^o)9!f514$!FW`Em=uAKad-lej1WDNzib0Z{*YlqAp?cu zNI0U0SG_h6z&s2W!jnlv3V}){(XeQ=_XgtO95U=bg+K%?jZiS}LrvO2OaMQlPt2<_ zupbVVwR|H;C~|lu7Oqlzl#yRW?eQXx(5fp~{BZtM8X3XU@I(^O2Q)GB@UDk4Nd5?k zjHlr6WD1!=z!5x*?@bs~NJ}Ficopj+0MY_qS={5^e4@Zo z0INyXza&RjKOV#({x}>SME~(Z)FcA(sIzAg&?`g4YC{9B!^opRhaWHisHi0X9VW`>(cvhNagT!%GZ;1n zV2^-~Jw-8+Hvv@C`W_nbCIEanEJ#7~6w3v?Yk-x9#Z9V>04ivP7qAFkKrp-x0)Qk9 zDvd%Vkx4iJ>X@?wlK>P7*`GkBQlZf?g-XPLzW4r|ySUMRojxokj?K37Or-zGl;<%3Hbeo(1i?HIorx4&wP??G^weE9Dm z{Ob1iRRDPIe#k%*ZW^s3L7=ZnLM&8IYm&c7pt_C_tG-?RJI2<(vELrs3IqTI&7mb6gh+5C zaH6~K#UriJcOjBa1P2>PRW?rh= zokdksp&AviH=YVnFA{`D$d!;92~`gWIL?7S+=SsJCSFKS*LWMugFl`n`fGrqra}Y~ z%}#?X0JW-R_^dI$}Rim25XsmiY zqAvae;R}Ilm{|p2yRw#k$|*HzPhY^P^@b_wYTRv)l7?ofc(8*Yml4vC2^1<;n=NMs-d$ZsP?fL?Qgr^{6C>_UF?PY^?YUFH0 zm`Q+5#eT+=f*7?7h9nc1=rn@zIa<(%TxIis5OT?2LLk;*0W_=oX*}!(9tY3kVa)N$?GCW=uGibe z0&qe32Y_g}`@qW;ieYzKsfZnVzm~rOtsenTK5D|DsAgPDUJ!uIWz z3w!_V8aN1(yEpJnkcF>brj_=n^#k7`r1*Mj>xF22uRj@vsXV9HzN)5l?)9z0F;|Up z60N*&`TyQjIf(%Yk7R`AGak0bIP9%ttRNY|VeP?(ZzUrjGQcKmeOv$_{O9yiLhFEB zr{NJbI_VntrfQ!kmc3Wbpm&$0$zc;y;xiyeX6 z^!hY*)a#I!ssBQ&s6N`-g z2SV`0djh$?8AF;iWoi*LS2$sv&K~W3P?} zN)w8oZ#R)Vk(M_U4?sMq5{HtokO0PYuME1Mj`qPPTIssr33YE7cHLKoBL6(SN?28k8@#|o4_RA$%fX28R7j@lX3O zqcgyxO%RXg%p1N!?km|7 z#Pi0lkcv}YrPTlciH=~pG%wtWeh2zzS?f2~U#J0re*YT^ zTc1j=&-G5dgjT{N_#28wtJF#rwZm)CN|jMC0n1^Z{p)K&VlsaNyhA5=h8RNGW`i9b*uP#jEY_Val9z;npmbJJm4oxdP3i4Ygk%xr*&JqnkrrO^3@HNZ61jt1a3W*JyipSti~d(gF(6VBObd28A{=Ut!Y1Xzz6$+d zUn^|w-}m{Upe7c@H2-bS-BZcY+xJ%Grg-r7n~HUCl{o|wh1|=5QT{)Lbufg0UH47E zI&>yq5gK8Lr3eHfL>)mKsw5=%;XFi94(e23-Df9`>9Ucp=lEVHQ z(veE8a(p+YnQ_=Py#yr@vn0I*B?*#&iNs1-FW4^rqbj`0*dBBNa})Hl_M^Ngb*j`h zIo~9P!C3^R(;`M4Bwj-@%0<(jjlC-R6slB^<=uy_u$h<2ggh*nSWZ<);U-=@6j#>P zA8c&`0|g0Um>OpB7_gNk-m^)$8gfuQl;wv_!g(%XVNQaYL`oia<+Df$sKbQPjm`DX z^E#`Q5gxitt(2waRjT0=L;pgT5B|l;1Eot0lfgGbS1)&CuZnb1nKb_e%E3Hg zXh)B-9~{+#h&+S^Z95@rr|bu7Ywks7Xo)Da1tb#C8YD8cs=6~crR*!vR~58jO^|0; zs_--FPF_9vxjG1vjEHHjger_6b#eu2grNFMEfwqNkaCI+{IMBP$@>3Di{Og&`hga5 zZnk-8TC9p(Ymz+laL2Rcp+#lXOYBzI=;x@_>YzO61c1oVHkAKW$|K?{P~IyNo)`7j zOd(iRl&b>Beh$4=YHC^?1SkU)ML{FL|5XB{pt-YUKd-EXYq;dY!0EFjpUt8c87Ki1Knq;pCjSo=F-!s|qeU3V;7K%oX+7-yB{dNfVu4>T zatsH@tUFz`f>?aINBAi)O|O>8TvQBhXmx_eD}kCTp0TOmq98H4keH~{do_QsmzfM@ zsx`t~^%xxxprC@K0bK-Pgez3axz#CVa#W7O(>#Z~T_pdiFS%-;230q8HC#`M1RKnurA&ExI_-i&(G zeTcF*Bu1MJQb}BiCZ+F5j20Oh+Ce|yRn0H8TVPteO={E`EnU!pe#D}bbjPD}tCtC}Z$Y0F`{&bFTm=@s3or;eEetY$P@8I~EgoV#Wrcd~$HKD4 zO6&LB%U0sbiDEKZhsL=D(@;?1sJt4Q@Rnjg=amJ<+@m^)|oNt%y<(JKi+N$ih@fKmdMOa`ld)aI#!g8p^9+dSeQ2f8G zFHuDLH<9UoeF5D>=OwSIAWsz1y(P|uI4VPNXs!w>8oggU+spsPJLmr){pr2bUg4H!th#F>US6}g z(ZCzIEl|1!4P`81nHr7dz6z{)%ih4erRaTc}pm+$iGJvdJ&4==#US!srA(uoUhJ=5HAOSM<-T3Qt^6! zH*3yaWcMFT-G)*q7${1@Dn@aDhtak4gnp1`c zFrkXHs0wsbRuPI7C`)xlJ2b`q8?`B@g7S3CbEWNirBjBM^liN*5Ad0CpM2Z^1&!M%yTbx{Onjcy% z^DojORL(>54(ta<^rV(!q7W+QVW?~A56L4=yl4}xoTqstq&IPTAFn|Kip?GLBGAei zpJ10F@;JHF?naf6f%i7?*gYihZ=|VHo~3hPa!D0^_X$KuA3&vtH(_DN{uQFCvei@N zOm+8Nm*ukJYp#whFB0VlPJ)Lb4Ub5~(Wp`>@dZR;X(8YnpnhSFftUKl(>zU?F#StI zo{Ro!pgOLSFg?QDOV&lo#WJ)S0LF{JZ-X2h?4HDBcv04_xf1=ptqgS+RaE$mPLZj) z#sa_@rc_Z0h6*u^z^HhCTIri`Qf2c3MvMJBa?drIz+yzpBUoJ!cd|X)itB&a*aB#J zr3y95&{n5j=eXYWG@$gn;rRdndZ=?pPgTV&Y+S2W`&t|(Jt}TU;lc(BqE6n=$X|B1 zlPnhI&s2;FCq&E|30!;AX8@u>zO1ZAI4i-9MYy{k;|K{f^TU z0!I%%aC6c1i%F-%+4w$I<+UAzqxXjwzf*W7@krvgR>iE6Ly1TB=d}5hJ-Sxi_O)s^ z98jxHvr*+=HtR5TEF$})ig(=S``1qHV69#0W1cVjwbLj>hJWgZ8wOk|e>JarFtx9Z z_nF(e;{9M}4EO{tJpHK`9^i{_@RTR2HTs=*r;2}FUEx8oFRoShX2bSAbA6t6;aa<< z(wf=oY?)Roq+Z{kb7QJ{0CnIfpWPeVME0&*<(k$Seed1&KIfJD7FM{(@D4vEd^~jB ziSDo)qrdJj3OO`q@$&C0oCI%muanp*>F5^?(bL|6ud0#Dge;~_ZL?)t6oX_Upf}pF zp=nUt6YqFPWwfbz);8x_x!io(u$etc)dAMO6>pSJfTBS~Qk*g2r*Hcv7S2_EyM9W) zxvJ?Ib7aj2s|J$w8~29J7mb%rUT;0p`vi}6aYl=i`}eq3tJ%kO8ty*(b-ig7NU!1N zqm$0qH%%IOJ7QJd!)Ds-#q*>4Z~iu#_UEwN9fW=9#ynk*%SY4F8ePiTyXgJgKO3}L zcY@cKbYn!v0WRjqS_IqwVeN{$x~E0f^!eIAd!g>+N1HbIk2%_-_(ABZn5-#7hs*Ty ziR-$3(spp+ok4CA`x*At=SXZbPELzqCk}3GE9zap^!xD1qa3lzWo9fgXft)`Cs$FjuSU<;7tKpacN86+*1uDO<*Q?jeVo@U z$&wRYLz^_4_|3#L?J0%L#qRC**KIbAQ=faM*{A`{>&9it5=tpx^njLe_x>1Pw4c&{ z-T5OWp`*>$@^&0__%9GAj?9*&E2qr-G4Iy{q+Y|bZ>CZn?`2Qgdh8?O>S$Gl^HSl& z78B=pOv=|3WIik$9>y@|rnk-9Y!1-o^!#RV*6OjHT6bxY*K<$(#vd^+$OYeRY4I^i z@ZYr@;9Gx0@`R@4rQ@iuy7e3P-F={)+3hZ%IbV>?S~V8W31 zow4UGO$dM3rDH2f?#k#kx)Xc-1e=Dm)gE7J?%Zen*fiCd1N*~m%Otlh9Zngv#j>8X zHyXW><1^q!LL1C7(97RQQ1U2zeeKCL(hu?<-K!lk+I{c%-9t`{7{5W4ZT;$fKkA$=i<_TSG#t?02gpS1+eMOGUVNW@XY__?+-=R9 zX2_Ox>el9RuiWL^m3OY5>@%RNLaEF>nz&*0@Y=gfzkRJPJ~87|(X~YX8;dFHNprik ziqYFPw1`=oBP+;!bgt(Z!MJmK8xLG9N?SS2XV0&kqmu_jjXT$G@t?ta;O@eg?#=8S zgDyeC`oJm3-qGDF=&HJt2Rs@#N%vDb<9bblQ?&N!3+m+yFXrW@MDCeb@dKSYSKp(ygv|kd0_6k z;p=xiz8YJQnKEp-y3x4FutJMFp51~x%zyGYru!(eKBv{a)Lqy9craq~+0-fT-0DEO z)gkKou)2*(0Go9w``kx$pTD+rmyMgYWLFH*UTCk*MVAOkDAUgS~{g0>6hoGt*t# zDflO=_};Z`*Wb^{`f2n#jUEcccTJD_4Z4xNZ}k1C^X~st(#2bIEqNDM>BNzYq7L0c z{HNia2bj4#ZxBjy^N$2Aoi`xAWYfUC!i$Q$qGO+om^kUynDN)w1zz8lJGtQGsx0jm zlsg8je7AF`Z@MAx!Kj^6JES*#_rozIRHWS(w04n?x-t`8lGdY9x*khObe1d|6kRZo zIZNEL@4f3QGP3-V+77c{{e8m4o5u#NcSCE<2plP0>$E;po zT}kl&0=9f=a2-y|abx9UmTjet}?6BJl9wMj4xS^hxzA`0jyV4gKJwt@y|J z&fL7D9lzE0@ohHFzeOjwG97sFLt>V#b$K~Cfb(vUFL_Gb8diUOYILqvH2$%2=8B2t zyN?&yY0D?uRry(0GuNu^1)1wW`OH```MaUpi)OcV=*rOM}`CWxl|R;~G=*#+H`} z;VtT{K?-xPs}hI(o}|CFWKmJpiC&w=v>|`GVP1SbcLS|u{`#$?)YZBxJ?B%LV~euZ zA51sqi$N!Ce9*W_dT;wGVNvhs)kAjtn$e|Yr=-l3nB50vHJ%+lXs2#rUSG|Ug~W5S zKJQBF@xExwr2fJ?n&^esIqla7H=X&+QK%FOOL!j-z5OU^;En8U{`2M87=AY@Dn4yA6wMz!$ZG*`Ci#dwx3yd$=Jm?j~oveiP!G;(m&d( z(~i)!TNU~JtmwWgW)&USzrJW7$ndeZbceqXW^TAoC!d=*lE+?rV23k9uk>kaP%avg z?l)-jv046uH6gQluI~~uJL?>)QKzJ#I#B$Z?i5hi#k9|Vy?SzO>*imcEIOOhe6jDe zFYk2hh+DxhpV+%dpVg&l?!~)(XH$rMV*JuAZDtA6R%X1nJFN|6;Mnh{Oli0~@`ydP z-;-avW)yEcJmq2jcKVq5KYlF8LCG?_bM2#J7bkw#pw1U_8;l-?YShHx6PlDhU)`|- zMvDL3OM0@eb@9oVuZogx#pJ9Ryv?s$qLO*-HdS%bo0+q+pg># zSaj~IUQG^6ZRtX?w+8v{Y6X(M0Z5=S|3T{xJWe=qOK|@z+mS=s^udRFzYcq%ZJqA7uHbRp7uLKk zm-`R9p7CUTTSu07eezKfDoelN)e_IK{X(oYdRU7Az7Ht=*LRi}7EfyWF?HQfi&{IH zp1Quf-l7p7&uMyS{GXI&a9^YEo6fF{x_g%;UfcA^V`sC%StlZV-wzy~o34*BSaDCQ_{{eB^x^k!P6!&*Dw}Wq^6=0b{Y!2h>{YbAQ9{;VBPOp?E_!lc=R?V4 zeQZYdM`WWR(WxAG-?FUm_K7~iwL^*)blo^S;pd0Z#SgN2rRe7NEbHf?C_lYhsP9d(28NKJ3goHbfDSFmI;6 zzIgn2P0n{;1!l887<_>^b^d&9{)oE^M|}RrJGncHKG=3KGilap@f!3A&UUDsym&nF zqn9X0@uGk2^m<sv*tvLla3(bd-IE&=fEhbY zje4iN?r+}~9a)-ZkNzZ}=W_&?jzubh6)tSpV zKil(*xfkkQ>^(a-qg|VpN#{?$i|WPNb-ryBaQtCQ-^PZq1Kxw1=Qr##l)pXf!M<;2 zVY0V74Q^%soY48?!$XGu#VWadzNzlo_WPL^CulO$@&pCuUkuuOOa9}rduFax%x(OY zP8|0$Yj@G)q%(4o=J)Q`-XGZnF7*>1y;RuuA!hkDN707;)4Tn!IeK0Qsdmvj3{A#| zyO5KF>!*sdOnLo_H~M&1b-@02lSRIl*bfG-yfA`yVRGX29jCrcEL3c}vP)NxmD%y& zl+;rUEg3{~chB-Pg7j z_@DTs<&4{1!a;epp;=@P9LU~pfwSt)Og;!0VN~!;3@dh?G+@P8@$nU{hOFoH?q>~m zmOT8qEpF4!#3|XQtcSWDMoP|VQI(uH;O#v?%)yb#RjppNi{C0Fk`uH+0 z#Q;UiVFRb$+uKeYi#LG%zEKn1BkRdr&9A1F+{-f?LEs13c8*EZ~(bXD|Z zdIQmA>6Fw{L*q|hI&^Q>wZ|hSx6RAZ1y0U>w02f{w=;(~hesLqn_dQmQPqX{N{ea+95k0ee~dAYFLpo zgLX8Bk~fSpbmKvdfHZJJj_yLn!QAZ^FBZ)!VE0aJldk%07q9n~&a-;V*3H@cQJrSp z$JN@^OgsnIt3|SSuaEs~p98yt&yJr^%SD^*L*Kp8hq`k#3j~!uZ>v3XwYpQu;ZY0I zB|Ea0y>qDFqcy8X;C`5Q_+I|e%=H0@eXd;iIdkpM{sqSt2dw`lY*juxFLB$XtxrDL zCOPKV_FevvgV}QOFqwMbx+OE(o?h{#e&T|i!~a}7KIeDiPF&F`9_sczTMy*4c+QE3 zd3}BMBex}*dTW~`i*M}h%#c1Zf5oR;?`Vrl z=-XCbZmpOJa!x$^@sS5Ce65n(SEMt0#7y3?VMPx>RQgjx>|Y+9L;kIa@mnc>7CCKX z#*_ZJ>qn-|Oo=+#Z}_F=+y1!Pqo`@pX8f85Ti!+G>`36M-N=&`Y~ST~8`TxhIdeYb zIwl)N4KUZ;^>B6Mp!{#{Ta(2)TgH>ei3KN9zY6_i$B6^82?Y- z^Ihxiz1#9q4{#5B(pOR@mc9h&xp!YPv2UAAN7^>s^f>TPT7KgLX}OF1^sDaPUT-#z z@XbBkW%Jbqw~lNg31_YzbflMH{r!k7ywkTy%rcigx_rd6G2m=&)O~SyQ*f%+^3V-g-{8APy*HZJc@)C* zUH->L|IHx{cR$+lXUpRIw=NF^(>?{H?uUe?fByNn?yR0d$%7>WzC-HlNW5FWiR;N_ zsPFK%mS?XgZQI|^*SU7b$blD-Z?Y8`JJzoB8@w~;v*?vGX3RaYC7@56%*1a=#$k?v z6U$QQ1^mJ^v+Vt@^~f_B?Z>SI?bMyaM*|*Fi2S z{+{VOF8=n!DQ(3Qke(xFExk0cy?(R5m@3{?SDUqNF-f08B-K)NX;rst=selQgR=vD z$4NFebioY^sIEqr6VK2BR-a3E7N#F8&f-5ICE5>kD1LP4Nf-G5Fft8(oz!EGo>{l2 ziPk_qH(KL3cWhwM#QuX8dTv4oySn19KwzY=YQr7)9Pnwn1S!l+nSZA+o6vp2gif{U zUfX;g*uB=?(ali0s|$|8b!Q{uZXKq85pyJc?I+n+1|54e(Ng^L_(cO}`w#vGucJJ= zm@tr7)M1;GnLeWA`|L%FRFc$7JvSU*7Se55-_O8$#?N<)xV5#CJM2QbPj4&soiVNb zhkGkIR^x`NN`-njd_8hvgmJ{!5dBxYb2|{3BgI zfApQ-xAzzNi8gj0$Deq<&HbN$xU*@uW~460CtKfZ#Gt+X2A)26X5`)T_dYxCkLo~N zv!I2@*ByK_deMC!^sTdB-%dPd(9YjK=`*^0-_@HFeK&Nb75{Z`Mvwi-p&8SbFKYH{ z&pPx6Z9ndMv*GTcf!cdF@^d!s>5-DSXlHuK5AFO;ZP10C=u|X!{@RT{zq2*B|Md^0 zDWbHSwz#zX+v^(D&;H>1O#_ekr=DN4Mlv*Pz8-l0uZ?X#L!EWaLcuTPdx@BoEKbOv zHXC=P?@sa6!Bfw4Yd%gqkM`rF*5Wy$GaDhsuoN^8((edde#_wgmZc-eiPP-8FLm#c zCQm6kz2$^uemkj@-DFc6e$xZ@UM3e*XNdcby%42;v!6 zI@QHb88By2^uv$+lK)tH`-jl^iboF?=`KHcR6BQD{3PL)iNz6hrtc#ck~;b9?)SwnO+nH!Yk?uM z9k9$%{f)Cf7hgQZPr1^(t!{tQ6Mo7Pa_$c6_&Zm^4;ZMuaz#X>L_R({BmXn`(XV?c zXAgDE&5OHLB>0{^sYTUJ@#LC1#G?b#|>{8Rm86EI*{!@BB$&BA)mSQ6Z9T*;VB{Dq_a zpPb(L;A)S8-+!DABK9aaL1mlri=Byu>yvVioe$1VQ(lbSG3F3ihuik#B)+)#!Uo6T zw4`+Hnl|d0pG8kpU+~{{TXJx4$;wCPZ?+}N)3a07ek{p9JO^A$LR{Wa7OHYuKuC(| z+ZCV0u=m=9MD1p+`xNet+x*XFWLUUAzH5$0pP+MdP=QSx_itV-p55k&&iHj3hVvq-LDHO=)A^({44m{>KVFm+ti`IQjioBkrgsN2jP9 z=N7HXCiEJi8oZTB#xF%xZ%}Or=I%o3o#^Qs+TQ1Gy9Oh6^#g~NHg9WMn)*an-!aTq zpLT;AqTM`31Tl6vytykvx)hdl*2jOX7N!u4p zmkyGBd2>>ywd)7>$;`QPS(f`_o?pj?hxrVV9C`L?-|7c+5EDwy{MgpGVTL zgX>YCbY!B-EMM9Oj95yi?aHH{B!b0W_{8vuxHYT2xmbuVxHsQYe66JA zt>neI=azD&ua@qcELbm*bqa7XO)GH4boAj<^B(Ho0|j>5S^sfPZ?|A)0X5?L!`;|A zH(RQw@A~Bf@t;L1IYem!n)X#a+5G6bL-y66K1(Ae`{n<3cyHLfUAf~{G)6b64s24x z-F26TZ8or6*g)ER9R0(0&$)93MsqtgTblo~STY6S9#QFYHtv5MzpsDCn>RX?6yD-w zZn0jzKxC$%TyqWpG1GT1PQNR@(Jo}c`B{@A8e9>N?dx;GJTCr3H@we|KZ5+=dg~h2 zz2Y>j`?Xcu#=DR$-=~Rp*IyOAN?>WT*n#SiE}bF7;bWcGKhbxVsW`dNk}UqUe$Pp} z8>1A4OzI~3VsL#>*8v*GT0o6R4fTYw&SLx?Q6I@mSb)UN}_8W@kqg6(+Rtdg+18V7`0y80XXP>tzke?SMf>_ z%Xj%iVo~y!pdq;5&&-Jh^X+1&7H(eS65wAWUr%Y{bVaNPE>=BsYZG&QC!dhyuf8HA z!-oRu_nvI%=yQJ5Ui692z6)Y(>QB2Tz6XGL`EMNs=yRR{s_E#nV=kw|ih5$-FX$bA znE|A-{Ns4lM}U$PD;lEkcffIgJ<})8sgKfn-N`79@ZHRryLuFe!|5lx72djhbW>)^ zz=8A0`ftWAOn3*JcD^@i-^6{Mym-nDHJDeU2K)qf{0_N&GU~`^U$5@xAB+?8ZYi7Y zZgq&-Za#VoBNmJ-A+=q4mxICt)(zPA`bO@AhVa=@LxD6#PWxdndcTjG!_q!DHS?E& zY~QX&kY7otWLns`4SCK^&B>J)het#Pp550j$@Wp73sVCkPpLZibqVn8cjtG0dcqw| zpIe6rDX__ViX%QBlJv;lr*Pfw!i^_*J&F?suXA1>a(PwMkC6=qEn2uxe>XoVY1*By zeQ~>1#;pB>KkyoB(Z~lshR((Bc~D%WUD(_H*>5}Q4PG#Re!=i<-}UP}XiJ0E?S1-= z3Tlng;Bj>EL+gKIfE#Ys9mJ@(RnKJcy9!>zUM$~h{Z$PEo^-|SG9?usoZXAEfAjl( zqSz^5*L*YwuA09SjHf^(n8==udc+U*%2;qW1-!h}q_qP#tpQQF_kIZ&mf&;y43~Cs z$nBy{`8gnKKNeb%{o}hGU@5yLFHXAkzIYC`WJ$94aSrNk%}rHKd34R0 zkvfm0?RsW&AS`*`IvkgKHh4h$pxiHJwAbasgFWb1w=U4ffc6(%tUM#EcLvZ2Od(9iDA?)>D&?xw{M!^?>XY%2#1NH(7N zyvN|J8^O_cvbUp9)o#S?X<(rEHPtTaH)3_jZ2z%MjPzYM{utjbJ!Rmg9B|vo77f4o z<@9AM;&wi~8Pd)A*X2b?>99gVaQhY|x8#{-HNHIbo7E%LU*0@4m#}c_jGtF%!Ikyr zFH5@Yo8C2a1IUk@UKtN15Sd$leoFr{A5jdtu+RTWP8qz7-0M<^|CV2_o?2^c^nw3I z@F(R0s8~>(wzOpP`N^peKUVD?vyKO(OCs@G2Hwb|`6~Xa0!E7p$}Eu6pw1{?VibtG8&^?#R4!bWukB;%^IaOQc_&h*8J(aKOEWxEWW?_)C0xSCrqF7`NJE#i+<;a<%RiPorgLE_mA3s zb>*rBJA;}8w^+%O_nrI^>A?M+#od2jBuP0G^oX1NHBfT@lET!(!F1s zlb7S0wf-LO6V2;)U)IgPXn%L}XTNpdAOCZ`52*U?jZU;)_!ln<*zdw-$VX|22W}kx z{TOetj(UNT-UVR%`OL4tV2%B})0$sD{~ulN9ZzNa_m7*QPG-s;IW~3Bu*t~G9vR_? z%*ftE92p^-kdc{@8AW6iDmyZgmB=bPtKaL==f1!9{rG*q|MYms!?~{OeZAkW@f@#1 z5OGporR=i9u&9n^{0+{%L@Va`-_Syff3W5JJFyOLUE+gN(BJ)U5^3)Jh3MCy8fhC0^E#`j)G2sM7Iqb<8J^R@+Dr=n6Ghjz~3$`Kq`AbI3exsMQ}oN24j(pB1=g z=K#HPrr&A2%G>Cf7|f;(bwSDJ>{Ie9 z;at4Ax%pwxach!3V%g?oO+3^aa{Y9Z@wfP!o8#YKg^*47{K)L7nxx{mF6uYiVM0xd ziw}$sG8Xs$ba_M+t4yhSKFeo5t!J@$@8$OJ;JVSvXcnolQSM(an-9y%%$wiHVv7VC z6EwuT8aRzwF~&WL7lou}9&%)$WPbB1)3LaAvd1(I4&1h0S3K9`ne?YH`kI%R%e7gW zD9limwTim+nUV`$6m7PD7(OY{r^Xkj(~Lb8dK`jL4`tZ_5zjSF1dFqRV$TBtH08fTS6SO`&t`%rt!xlBs)D9W1eGb}fW6gL|WbQWqu@V}4F;`7f zv`&YjT0AGZQ1j`kfXZ<2g>sC$2>vPKc!A22oeNzuP26X=P_?EeAL_QI?{8z&-NmZB z&!a>RZ{d#Q*`&xqefH5ZN<`QN?trmlMuh^&KwcL^v71$r){_f4Mt-KZJV&j43JuR* z8G`Wb#!|B-TSnrLWYyVZHDolg`MI#c_aU>e)x!jrIVG|xOrrW9NF5pZp?uvX@kA6P4w2DQ_G*d+xLPo53rISL3>(E}6tjp@B(gIa#8Dwlq4 zeslWziq>~QMY~mtn=I()&ySvn_I_@fbC+E=!K(`<6Bek?k^U@xAImcyFlXMk2A9~z%H?B=f! z{Ro+dBDY3h?A9<-fU4^eO1`7mx=UO^k+c7MX9*$HWnM&dp;(iu)E%o5qSzI^K!F!pbN>(mw83d_>?c~b3otJ`k2(&Z$5znb6z|H+$tkS@*o!NIG$0yub z*$lvR?w$<&%Bh<6uD6|37vhlG+gTULLWztjYx^-=qqx+KRZOi{4smbMZ)8! z72yfgz4BXij%f+SCeZEM_&m4rJJPus{WCUFA#uhfKXJQou&dJPY`R91he%tEOjgyK znh9f_BIj>!V&)!S8mJmDYw{H%u_#iWf1PF`J|QQ0`N9Jd3QzL1K5ttl56ZCQ*q?0= z;OL0P+YOf*^{ksT$=I$*WOhDpcJSvs(o6hY@VlSnbiA5n?w`PI_7NXB_ zqC6-cN;sA_Ga3`S_kFZgd3Pt@o3%&sy9n5GzK>MW_Zi4?I(e;TdAG`&^PFGTE&q zph5SF{&9Rt#04dT1857(6-|$ev_mMk2ZN#)*^zeQ;6LT^jxpWIx+kBw7ui&@NoGM& z)#^hxBwxg`%;~dhG-)_}pY(rCjKxn!JEDk!uZDh-T4~N?gLPar@EJBY%*q z7?r_k?>ptrYPn%Ur>eDZO_yTQ7jIbp`IxR_KSj~c2R~Eh;$FDsKlGCgPX40uOPP}Q zLy^Nsd4aVbUq76Coe67?u+PPQ?aJ{Azd=pYLv=0PoLZlFtEoQ4D=sX@@}g~51^;-W z2VYmAbcWZYk5A#d$m*L5`!o5aoSEX!T^>%hX%T3ALk+8xmabA zKaZQ}zYI-;D>{5W*edzW)1a;zs~nBjNpyo*cJ_wf2A_^qXw2lkkS>xj#+9gF@>-Ml zB;Q5-iP>xI)q;!Qh3jMtTe_7|VfBkcMwOqJG)EmFI4#jK252f)NNnj=D1ExRCC@#f zI@QpsHB#(EcK+6LKlI7GrG9DG_*=eZD#9x3DqJcG5ye(Ri-k{Dl}!xkN^YpA9-96x zIqlNFq{u3{P+RIS6yrx1J{AklQK2aG`7-s}y@6d?wAt4qKXz1<-%9?6URc@_W#(p? zG0WShuyi$4TrB@u7f>+#hwt1~1TbU4P^r;&!~x3_k(=*J&C^}4Q_z_zbejpkFIVxD z(y;OXZNM>k6Xl`=rVyG4w`N~Q@9jArf(>G`-w1r+`W_~G)A>Gd(uQb*E)YM#f^(iD2 ztL>rM0-?bg%3!Ac?-y!6C}4S#yFGQ2GtjB2YSL=Y_)e+LKBFajq(~@}0#{k#6+)v{avy!AHR`wl|x1G-tK*p+1TKX3bIf7SLKC#W6qt+t2&vK&mFBLcDBbaLSjXx@K50bi5jaRS{!iTUg&0iIsMotcX^Ep zD_wkw%s#UhM5Kh*QVB~xSbRd zn)7o+vVX~_LaCzyrD`2IpAt^m_9f8IR;==!?wb7G3kB9VqWlG~N74^eRj{-U*gn!4{o@4lyZ0knF>knYtlyNn_D@01MWwIMohb`lPqVyj$?fNey1d%0ESd>YZ?ck0xuu|WrU z98sW2BT67Qd3fQK(s=_TTd3Hp?M4fJ#@Qxx>Szb-4M_6vwEZ&wyO+YDg+B8&zpup5 zO?iC<$LQ2a<3POimez4KUWZH}!lmnHh^mWFiL{DXm!qJ(XVg!RjzTj=YTVC3_+!H# zn#_*uJ`93-oQpN>2EyiUUukh|xYKUi({3GEbGcQQ^wHlo^Oxm51vF*VpbXFJnkLd0 zjl5X>EUI{_?TOQ?uE!yKUSB;@5-#(VQ|lYA@=ts9i2V?i8KJiJitvW#Z8aEqm@ka0 zy>xSpxZ5_-YB+T%K)FI6n91gcNlk?=l)5TjpMGSYc~mPrM5_z@$$GLcHv@Db+94AF zKFhKN09Y|-Bd|z@MBkebiu06x*im_Jm$0T3OY!d1D86`GYKG^A6`n*P?N5cTxp&{u zZpDb_b$tC|_JNkuIyZ_R#YtTAGClIOOseo3G}F2bo&7}&bA8UoYl46EagmW$VXyr~ z#q+e&^qm`jU!UyCDaYv53SHZrJ=%T>D!nAp6pGv^;rDb#HU^>-b}jpHJp>VFmU}RlIG@Y$>E@KY5YK zkx_P8?NFX(?$hmK@g^2bgTv5XQKhMm?zp5>>u+%W27TZv3$8!l-j9N+GoQ1zLm96+ zWo#|bHoaLZ{^ml9Q>O*RMp6RH>n2d&ZGDOcqdD0*{XJsMXvTtK3Gk`hKRj!WRmYlMB}4h9t=JQyDB)a7 zDqOj@Ze}H^y!94un~GwZEj6z(b=mi%KO(4Fl->t9&TaISq-#8jG=iw4oVl!Sqg0H* z&-)>*+ZcgT4Q5F;ZR)SiR~>|CLUXL*lM~Nzp}yw7esJQnYjT*<#aKaQx>rzekNUo& zw-MctlQYOw*^qO+v476~&#TvS25xdj9@L}VaY>G@VFirePF-xA`goB{=}}UoRVDfD zep8(*X4rtf+U}Nwj|tC)g#(y(DFsZMY3RL)BU{6&t4>?f2De_?EGV% zVJEJdDxO-IlI?dx`-H><7x1ks9gc3ndFmNB^xlpM<3jd)HdS9YBdr&IQg+9=A@2|# z)Mx=)QFT~7{K_3^+Zej6PRSb%@y=?6bkO=hv{!hHzOQ=ZC>wC`ES9bbJ^E>QFqop- zGOAp6lp{Xbmo8B`zP|sBNB4!_x^#RT8igaT(&8ByyZEiu^Pgje-UP1-TUz7usc9G$ z5nKOgNOO-@ruJDS>tMLbJiu;rrU`AN)>Er~^TQ11dQG%}>x~aCoLlHvG;I=9VQzkv zxTu03$16XopZkAi6Ltr3xEan_i;ZObl9qV15Y?$a=U!o_mw>LuO0t@vFl|!-^fio90(WioWst{?)oueKZtqrpR10YqNZe0R!_6 zQ1bkB$}p_I)buf{N%=78n8vd^>N<<--#?}LjAvHM$kfRomt}dYueg*yllqDIDlefH z=UME+g=<4u2KGv$`rQ))gm-H&L)Xq4`xY;8o=&oR7VbeS_-!a)HR4_IM@%Bxd$V7O zd6XTSAFZ^59)~{Fsz@PT_*2NuOG-7R`XNiLr!Kl%sX#yxNc7;MFKFW6%t>nE(x7e= zrxG=$`^gZ&e=9Fq#N{(n;xl)VPwn#5+AC_xDjIg0GM`s21oW~#{n@wfyRyQi&4ZsO zfM$L+Gi;K9(Ua_E((7Nh51`eDy}e=h+ji2St2VSmn5UK^N0l!uXRqKvG#XR8Y%Hfy zaW$gt)P?#MDxuXJ?l3`>|+&Fd_80Hc#dr zX*lQ`q>%HcihGo7U<%~bWz=ye3@Z6Db8GQlu|tWj8f2f&(gNPyH#^EmC7Xi90<(q zri+p0G}2KD(W+n%;EDU2{VbbI-ny4>R-0Otq-P;OMc8<>f_iZ*Twi7*mkkwFu)yM* zD@ayT7HU;azN*ttah`}0*vle+sGY2)67}xt0zHm%MHf4w zwC3_-)owxmtJ!d#qp>v`P^!;+)~{Q?)tTX*Iw?=aBsl#!WzJYz&FKLe^>wgsYbyI= z*FwU>Eo|hriC#gG@M+HUt!v>#$xz*tql+ix<0slu6FZ9cF7?)+Oh(6z$Cd-{%?ubA zlzKO?#_#X87l2#(ybkegD9IKsprjEdoia)YuzS0 zr~}69RwU?z`dzik>>vOA@RyH;wSMiEpZ~{=;86z7{v#I|B*gxUqri6DE2vGb6FB5~s@q^lW%iXOf%fQU>PTwb7?)hyw=o)B7u(p*+%Y~4I#u^Kn*(YZC}ZmK zE45D-kd8>;v{zV;a4)A!o@T?2TdvY6`Hq}u^#Hn@fYTj1M$c!8P+E6=vfJD*oej&Z zS+y~@Jx`3}`UITKl%i#TSjMRKrDhU*BNmTfk!xjB45*bI8;k=A5Ys zD%>_t5_Q)!_SzBn*o-z>yG)Ja6L(iGjO0(Ktgov9+)G}whN2jq^Li_k@%fCwK{;lK z<$mN1A(EWAbGVtqk0QOI0sVf}@2(Zr^k#?+j`|s{8?Y`YAL$|h{{JRgrZ}M;NGFrO z$gTA1bCOCcCb=@9rY|L#;%8KR8c_%uRU7mZ!0-hD&1P8hQ_OLIMks8H`wkcpEU~LUm+mIFC*V=Qvv%n|wM+{n<QE;wW>e_>~Z0+N7`1iV=`0hlMHh*+E41*K(RD%%XtyNEqg{asZuK3jSI~oxA%n# zB{To6IG)l>k6?U&%+YRM_0H4eCRMt5^H-9-o3=J~rR0k@D=ot~P_>0Q3K^=U0Kh7| zYJE{ucg6-#w*Z}QCn#8!Hw9lQm#Ubm(vi~(w~s0b@#F&<`K8_9pjN;rEn|jL`}yJd z+EU|IgMpNP2G(i7#!x@%sV>8z!mmIgbrU%zX^S1Dt0J*=7bq>87>xQMlevYnS3Rkgl8$@o*6a3PPGJU%%_t}Fo@iVPWa?G>GLBkc~!M<@msuZyxy478f<&d zs)_Q~tKv4_-rfY$PXAf*)%ZDEY*7Fz%Hc!PW^Ua5|Iz|nALm@q;(An}@!Wv5rv1xG zLh_RR6TB6l-R~*p=^8IqC!72xcM(`<}H zPulSKOJ^_gD3`x0JEnyJ$Qz)1_y~^16%A9w0mk+f=|`^9fdq4q8C(B%myhu#cNG}Y z#>5)$$BPqO6VDN{ZPiM%A9K*sxuF)|aWD1_w^-4#gv#Y4O_{?Xch@TPt-*pDnE_kq zB6OjZp7c0zmnsK+i%&I?Rm6TTk1cZxCwex zc@EUyziQt>!&tdESSV2_&Cj7nva--_^|BETm&OT8sE9KN%|ha|pS&^@6Flap5uVZe zeM~2!r}c*21*!p8Y2sHGj-_Y-)85=vwl%6mXC}X~@0DaG$fc&cgDyg2`ExL1 zH);s~{9eNwJ*eQj9}eE+k*EaZu!pyqn5=CEiB)_oWP1o8)|H%SFX@m1OH2Di5xKkeodvNU83|qy8ZJNdHqV?s z{|Vj|2_@;k+Eg|g~wWt$qCQZ%awAbRS*V`4Gp&;dj=#;ij{=u_bM8{@zT9k3)6WSXDG1$m9*zo|de-e#p9XZ^e*TNM{GpBe?eZb? zb>mswg=*l8MY*}I+7EU9NlspD`u&cvhx+@wM~pTE#(TgU?kcx9V~ZRe$lBS?ZDUaD z3zUpViX8$m3g}d>j{7^2VHY;=`uy48E(yg1f=T&+{t5b#HGzcN<)LG11y0Q+k|kPsF_i+?P`iv$Vh!k=Kw+}5!IBK7#QEP6ho6~ZtR ztR>Rer!qlrYT*=*)z~Ev&FImefF=MF9WNtfuVVbYJ81=aUKM*hnZF0sNZ2>7vBkb; za*G}`(9nnp0J>s0Pl@6=gjb#MLRVx1bO9Cx1({!r_HnggMTy8J9?!4Q(rsflBdst? z*Wmdc2#bIKHv%N6rKDy|DYrb+zR%C6w@Tw>6u=8 zcl?U=-9gHK!IljUiCHi2PXzFaJBes(^@uV{LCD;7o-x{&3iLb{9~DGou9#jdT?1F! z$H=J;m+`wV)5v)i$7-Kfo7UfY?Wu9X0-#55QSjU0gFbxh=x{CQ$7dPGFBk_{ih;2_ z%m3@+K*g!8NXKJ?~Y+OIY3WIDN;27z75TFEfQW( z8FmluUUi;yjFnt}nDD*G6-XUKD=c~UK{uR@k8D%#*QWFU2?+sRNl(JH#=l4Vce|=8 zmP_6Ie09uSk`504z8hP4`PBhrC>K@-L%VUaqYvfb7n7q+#PQXJC*4uCzYYf z0`Ao@`;qdM<-0}ls_wE~5Km|A3O^^$|D5Ye$UKB*JjbM}x;i2L>w+Cg5sE+>4DWU# zKCd6`^|8mMZ_aw%;|oQE1-HSK;U?XpQp58^l3z`P=dvP+W736NS5_&WxVpM7k2^Ql za>PmsU&bFihK*3{Anw}a`1I|0r6q-Yh4P7NmQXC_Jts}x$zypJjg5t4K+IX(t63l? z?j>_B<*26xGD~>YfX?Vk2=S?mQu4#s24%)q{CDr!RJ2*0u@+O+dgaG`!KChER?v~p z(zoVjH?~tqF$LC$0VBF?(1_MKj_NRl)a?7fu_O~n=0{A0 zU7+o<7zTOgd_84SGc54YI)&>J6m668tbx1OLEd-qI1rp(wcbHAa9zI!rEvgqmwkS2 zc#-p~&hT_zth7C#ckW{nAR%7{A%LdJ_$5dop(*!Sd-;mHAtuCQ=_U=i9z#_653LxA zr7SG+5@JU+-B!7=C=Z59>D!AQn(L?JKUe5Rnu8U~q{=E{BR^L+;ic2ppBd@?f4-+k z%wT90_Zj$JYZ-;}8Q$_pVs`JlR&1Mo1@;ytD9CW$zfO{6qS`hYb$tuQ-q*2N(Q$c^gPiw6${5JA!w265GC+O z$?Uv+SOZ~>lN?&9n4zueJD*&IPba z6V?Vq7h`fmb8?d?C8tAaGOWA$71csGS2nYj!fO&P`5$hLFsF%m|C(y-lRnzLy#xx7 ztRWPO%XzSM40{SRGf3>04%l90L*W?=%%;J~wjbeG%L{EcwBA6rYB&ajiK4eaRaf*s^&=LP z;Aq6>#Bc}H^u0dE@m_@Kzv6v6KT5w)0}}{`wKVAOkwJ4{Kp}mAWvu)oj(>pirlH=_@5CTtwuLrVVHIiG(1Agsks5C zlgQ$`h5fc2xvLF76b9|Q{`UQHlWqTbhyGkeKKUF$IK?&ufsUs_Fq=Moc1RotB`T=3 zL5X_VrPZ4T+5Cwb;yjuLm`%2KZ`T^d47xX>DFP+Vo`t!n5a+2#WSc^-8$_e};oaEK4LHqs$u=(0GqS`TwA^(LBNrUT z>&o2H0yQP!c*P7k!UuHE=3IkB_6PEn0Xx*mv#O_#*L6w?GT9m3(3~9_0p-h3CtYG_ zr#?eKjYCw1P$He+M9+{?;;&pyMS)a?Xzlfy^oO1vPv7w>Yqi(ET2BS6H4qgj6sUq| zd*xYz#<~<20lcn8h)0{r+_lHfe%U<`4HxLq-BC0ifAXf9cS=g0?u7q+(%y3fFwQ|J zK$}gAE*SbnZsHz9Zs;gYn`yed6F+sZ&p^&9J&{uS{#i?b4%~b!Qmw+|G@|37Il-8J zAB%H|e5U!4v~81K%@@M|GZK6i@s+zbUwhsyl!yFK^YUBZIF6hdDpY+nAMT{zyT9MF zN~~9DK9%-a(M-j>757?QR#WEL9nd=K%9}0N=qO?1hr+?PAVxZJUPvJ8RD;bwvqi0ujvPXjYu`!eULB7GcqK3vJKYtw@`sMh)0WN#dT zKaqlG8%s*^DDL>PTl}zecM71ijy3xYQfW|T_r?#IPQS-36))14$+8I%faI<6oSFCA zS6*vQw_dq-Jy)l$1jj^#KFg1O)XF{ZDii2ippEd-d z%n5585`n4PsoV+7gAQw(pqkT2?f&%|Y>H)|czS~?b9~>Qr!)>S?M%@asqLFcjZz`h zFA4~-#J?K!owT$mV%EkZczf(TIbm~!ON<%`wq3dc^FOI@LU}W-DDGcSERVs-{<+Nl zrP0UD#=K1@U-gfMB1w*VhG>76Hxyl5n8X9v`1C z$_t3w@=j$qb~C$y9@o&&pz#imvx#(hvT3|PJ#EISFq%nBxJg{eSx&JfHatlS|NKo- z1*)4(zO@0r-ja9%-8zc&PUS;1&*F`2^)z9P6Quva*p#M%Nm%Yx{n1Ob-rfK9cXCI=mUkU6 zz*KJ3#fCX*M0vU9f-D})T$IVu@5ESfL7Id>Ne9O{l#-crRlh|Qfqkw$LHon#Gtwjy^q0!|;R zpwDJ`j@kKJ(A4*zXCw92ga?q)wf}ca=a4kUC1Yib#D6GZHbX4^J$5Unef=N1o+E0N zw}95(0HQL#NnI(;W`>xX?1%Tz||q00D+1I;F@pK%Y001@#cL2$9O ziaeZxH7mu3j)-7%bhOT8_PRq~b}&uP-qzCH&4qp>c){@~`dp;VL5ig&BpQfEk`)9k zSH6B;WSiN+Vx?}&tCO&6VZf9WBtrP_B1{BOG7C2iUwFMNti({Fu*OM;rUvw~hPO>C z-}*zc=XBV)6TFg^!Lr6w|7xPL0?N$e@=gfCr-V2$}1l|_AcF-Emk!dvF&I=%Y#_=y=4Z3jkb0fF9 zsEH`Hl+uItC}^ZmB*7EPsrju`eA;`e_jgpxe-C=&sJ*`@8LAiZJ|8MI8Y~AcOZM?i zQ0G^xHvsYH<01u6r00;f(kOH?%tbfJP7omSVARF}mBjI>dxkhQ`(n*oi;1qA93Le( zilMPBh%feOz;+tV?$p}{%v9&*sF|G+TSJCh51DIy`-$K_C<~3kP;Gtc6a@c{4G+Aq z0)(GBKFjpiEapF^)wwU~NWd*@?7hA>EobwsB|C|P)xWPxRPV7s;w7YsLd^7BJ#h@j zf5s*PuV3VL#^QgEPy0iv%of9VwFg=@jSO2PY1 z=3h(X4Z>876Xt#0u>Dt>b|$Ouj@OMoq~cg_Mfzs|egtf%sVRuqe*J|IlXmi7w7h=o zNS9-~Luz#%IRSaAP>LLFB`32}vJfEiINr1PfsOPFGFQNboRMto4KB9<;HAcT#0-dF zI~-EIqO+*yM%4vtEnr}69L&vQI$~ zmqS81TS|bX;}&&#ARABS4}O&^;D9fr71SISwiYxbcYQo%3Q2(G7|%~VykN{%)@H<$ zrZfe<7ZK)R`O*I|b`^`TFtbHeB1Do%l*6;k&IP)D?&01mW?q`>{4C&qgg8?Pd z%fz~s8@C8@HOZ^iiTpU(PQ~bKeV4IL-kZRl@7+vZUoDf)ld&XroZ9+pS1j+vus5W zydbXtGf$im&&%9+1a}r)8h64}==LfFN&V<>UQRS($X%*Kc>OrnU%2+~WARC0WHET;mXi$4Dv3{> z75$JS9y9B|Usq1I=7%6dz6i}RR>Si2|1?^Nmh7ku2L|o?5u4%&7bh0IOpSIdA` zGl0mhxukjB8r&onlLJ2iE|*v%1oxYJGI~j20S?a>=b(KP#4H(+u0)qiYG`a44NXWv zhe83(@mjn$b+2R|G|8}J_2etL4%1hB_tV5zIc+~&W)-YkRORb%^^ z!c50GbJO$qFhj`4BEXgfVHUAt{pjNygHD5h-gUp2<=C3D>1+i`HqKMN+slirXN<|2 zf&nB2%f)PwZIEol)fETtFWB%=7-&sDoB6ih5vD6_51Tl{oIn1%5ZMd9Cy28ts+Et| zI{dJ@k>x(1B195}iKf>dGku6W`zNacj(__=2||+9{|-s6%TSe6R=ZZ{;j-pllgn$9 z4QvxCZq0+)+|3fqq$T>LH~Yaab$A*OdV3f#Q3c@DD7{SvHk>ukTV0D1Cxlgf9@UCQ z9eUrY3db7X@De}fk!~Yd`cBaz579PQ@i(2XL-G3GcJGpG{@MvIkQ)~)w;`@O4awgM zV5@YuOyZh$@)Gmd#8-~2h6~jJK4imNmCUtt#+o@Kx3q2MWa|r2xy79gWRD|#+n{sL zAO{ll(qy4vBg<1~MQqPddSUZ1c%U5>P$3^WL#BWsZEMFtX=Zj$BiHb;K;JaG(>&Jl zvY*$^>etsuMcBiF;x@p>uTH{bXISoTF=ih? z@-!N$Blr-CjpJxD-*xV>k})7=DPy^_=N^%&`LJL_qizSYgNX4R2Wk6eZ8Z zWyf?_ein9~!m>5?zqA0Ge&hqv$GgxQsT}E^eWYJ=(dIw`($_4v|D&cszHMc>g{vExN&lm63 znxxb|FiEcMCP}Hd$M(uOYYUB>cWz9;49yP%~a*N7G(Tqx)aZdWx6-`bSwP zKM2J!p~q?hTG*Jy*-Sk^+D*oeFI6-<$sGK8pz8u!uu=#GlUHY49w9EQxtwG}H8kJ& zFF0=Q8leWog9W7?O^xZF9d!y?l6RIT9jd>5brLb#@7P`z{xP?bV&>a5I`TMP8a^Lj zsI*U;M91MBY)$g>1js6&knlY9_F};jtiq3XfIlun-gp6lPlA?$Me>W-BT>ii=?>+U z+IiQF7F~@zm-F>Yw|*yC{%pOtwDTn;_HJ#Gh?h7?kuAL&Bt*+sDN!MsZ0b-#-@W#w z4YTW(N_vd=Ov%C}?-2iwOYW%CRb6u_t?v9f@&f$PNW0ZIj;7gQMN>Ou7B{ZKD)f9n zEeqwQ*NQv+ZPSd5QXIuOo4tM;Xjc6`Mq*WzdoV7Zg$Ox~Y~WvfAb$7X!sf!WMo@1q z2Cke){H{BG=?M$bCfV!cRG@X!51$R(R-XMy+zQ5DdKVgcTo>b=OzGt;hSG$vZ(yZG zz)EEBWtYRygLDb-JP#IXzI@00VVo?eoXYUg*x;|GCs)%Ik2v!3KS4be^PI)$J(ap~`uSKaz>5H2AluvdFMQPHhw)loHJC*B{b3T1OEcYaNq50J(A!T$B9PgxB~o7xK*7~?Rt%PK=yXl zoWZN)Su$2-9kl`=6XcF0<EukU@K*p$@b8||;hqq; zeQ@0IJ!$>Vds<)b2GSd>c|grBXFOZpdV|1U1(o`T%?ImI`bAoA#qQ+;O|tLNMjJ^T z5g*=-IhcRqyj=hMxygnTE%oa9l3|$_xePs2B+M@DRAeJc#7ESm37E~>CX_(!dj$@N zA4i>bNJDh2S64%17mg7PIoJuyc4D3oLcbXK_85P|Ry-_*0hux{4A5OMs`fgUltN;D)PS6;fVrjXyjRP)WA6hgzdB;91oW zG`D9zF=12p#8jgGV=ZBo3auuWXRw+$Vu6fW;ccC$2n`rio;D5Wk zT>(w{Z$~8}>Tl&Vk*xS!VdQ`8lpzh{9{ki!p~SHSZ)P)C6C$m-QLdy#3m(#8t=oSE zh7-!BUZhQg$$xc-zfvZFQtx_pBsp!va@B{7X8x#OS$?aPc7p|Ce&_h|v_`}B{16K` zdvTi~d~wGa2N*&-96V92SJrqos8? zDtzE|??SOtuM6K?@H~U_9bY^(r0e{R9awhponqxnlkS5ze9D%rW)N=diqnKG+^SnL z(N)JUeO-LZgN3oxg%(GpGMSF0SAKj<+xYuMf~NlYyR9{I=CHU<#G5AHlUEkMLj5@wE1 zj9VPh3dZj4)c45JY7y%N>*&b_V|mM8^%x!h_?IucMeC&;AMqKwz1LTPLa?@&f^L+{ zUo$5jj+7EIf?}O~@?P8N-}u{W-(-#gzP$;!Q6zK)<_Z!L{5~@Q6DYp$7T>rSn~je<$TVpBqU#Jf5UKN)YgO&I^u()Y7}>FU6jE zGL#G;@UsfRSj{raO8u9>lngamG+G!{-Kq zlkDtmp$xaZPt34){v|ohaAxNK8H9!JWRu~7BfEHFk4n`aVEQMsBJ>!So(wTAO?I=u zIpL31-t;WsF<$@kDeS1?V#u3(%7dEo9Xq7SJGxz8#gotla1Za zXj!BN3ewVDx2afChXs_S<>4fjB*6vN|M~IS!hd1@`NFnM>HB8drjhuS7aE!3ttn&X zu&$fV+(e7g#Vvi!0hF6rv~<2NAD)~+|z=EHbi1t3V6bX7(fSRTPB&ewm| zCQrXiAw1I7-YzmR~}a-(YIgUnntZ*zCh6(=E?_qXGJmnfN;&Z;L<}LioK`hTYpVC6QXy+EI21< zpKU>kAM-IV3_>*8Jn&C`@O=n`@jzpyUq{+o-7Y$brPAtWFi?JeAA(O8jAXenDOBA#smJTR3r6;e@rUXZV5&adOdgk@twCiU;nHb^P#hH>w z?_l;|FoCcTZevp|w*_<0#DL`4$>YO0B?k{F^mwT4U55tQZ*~B2%Awbj55~4K@WJNN z4JV`HDha)sNX#11OqhJauE10W`=5#6z<(mNJ|M*FCFO znKnjko~BhM{1|2!*#X__Gbr|XpRgC6?~D6of3jpMz;?Q5{LNPVJw8e`un_GI0oF!Ibi~2zgiMzV`wGdTZ4}QPj=XOk%dQFTA zjUq6^^YKpB=B)$01*lTb@tPl1_}^_{5L+NM%>NP=rUuzN9xBD|&xYoAC429Of%++o z2{`KlW$nt+Gr{aEi>1|qLJh?(Z8Oiin=_ZqFZD?Bu53PicvOZhDr(U_NZ>(3?H#_1&ami@zEMu zYYXM9X3(@LgIX{e-EswQD(Gl~Rrm5y$f*k$84@<>?Ju|I{p9?iA7%JP0%_x_R-BZD z8||GuXZDy5M(UQXUHyGY>AI2OGC09a&R1Ry2DrmcuhfJ%72K zY!uA)mAks>Zv#Hg`#qxiM1fKxjXgXMC0SZ=n!3R`RPTx<%KVm zdH5m;+?rQ9I7n?IK?A35CMrv6W>%Qt8i|OXbTs^C3(aDmhMY>-B5ad9yE;k3Uc-2LrZFLaAe%!gQ7}!I|YaY(*naa3G;D#C@ z!AqBN1)Xo3bQ<=*eg?~ z9zL)cqL4YTX!W3fK#Z#k*yDOS4%9iyqST-)-3T>Bm3$gQBrY5{Pc}iMbtnBIh3#g? zZr!+(1fc}JA0i=K{Fc^68GGfVO&^8WDSYs9WwgY_88%MaMqLR`kyYC~ani`*p|rn{ z`IO*0`K0Pxr&qV=?^q~bkdnmfKcVag>|1)V4tfrz!Cd)9nC{&0J-MC;DBCO8?Up%_ z9#M|ebB@V*3|Aae5#A{yECmaYVx8UFD9X9^>$G%t8nmcHO@py}ikpmd>(ntPSF|sg zy`d7Cx?(MN=5n7{@o_=K1F7y^;-~H42Cb-^m9y7j8N>SZO&;M0;P4I5N;Lq1aQaJb zC#BhgE8m`MokcfeL1;AF5=X#tpZI=Om_>`k$w<6@QZYUNc}>A~dt!T<7!hx8tW7ky z*4dK??OmjO(lv>{1N@Uqo$4hQsz4%`84- z8+HM{41qTCR>Z=_wHCXRu{UkI-_#}x5TzX=BZofF8k#;H>7=Eb=QQWhG=R!z^xy>U z;PCre(`6m|xN|AZH?SgRk&juE{zW^k#R@?=q)^^+BV!4cT}cCob&#^I^Wn8P-I7cz=_!q z;54=zcSW+|qCbD~Pdg=h=61BVBEhNO2WkeKVl)^9?#O&Ro!|$lG<*a)5RmTYGT#X< zrkT6*>O#l~6xnx@lLRK2pX>3fyw6zT$v;VRnWA&nvJiR~m}C3s)9)0O@E3ns zIv?2xjy%1LC-Um?>wbpGMwlWa^g_m5*CMqdWLiQ-y`?XWeo`zZ5XE7|-W zMfGEYkV|M_fvya)Mcz+gwujmrIogxZL|_VR>L@-=UI?x;u!YTe));$N=Hp2#zrSv$ zPX~0ybqO-!Q@j5@5v?W2Q@-WxG;atU|I<+BCOa#<*gN|@z^(hyes@@-3{k!i!r!LwQh zMk4ybMLt54DdPJ13Ar-`WE+=b&t1UF3b1{YD?O@rt>;oui=^1~T2)uB{M?Ow3_dgi zJ2Z6hGp&m%pS}@4DR@gE`2R8X-QiUKfB)7oj$>pV+1Z3cMud#Y-h`3}m1KmnMOGnO zwvfF;B%>3ul97g$jFU8EMzVg-w?3cyzV7>b|MC0Bb$zbu6X(3&ukn07*0beX(jcSU zNAk@YM6^|2^n~-EHZTi88Z4aPDR?%|{M!qmejG-ljcTeCJU-8kZ1=NzGXY5|N?~H`{`9|`b@Nb1AFT%iyC7BNuBpq+Y!qJ$K>L(-`OVub;#FTTHco}k3 z#g_zs!4J{N?+2vHPEgDTY>%u(mm`nC4;rMODqb5b1=|h{o6q&|?(n*cC@FdC!j6;l z1fLAkm>DL@)k0yY#Vk*7naX~8K=Idmdm?nIT#iYY*(};eH;CBNOC$lUoz|}scEo(aOWx8t7?Kd9$~R7 zJU@^6k?>^V?CuPc@!XT=;w=t4LTZ(5o)}87>v>8^+F;q&q}8jPgB;K6IuFzrLGIbyFTVJ&_7*X!l!po zId5x(Bje2IB@O_OPTdPu$S83UsW2d6( zKqP^~+V50IMidL5w#KzkDnwexT|I@;doszabrzL=Z48PJubqs}xfB^9!cIN!^w`F6 zz=yt0G*%~1xN45oZYMl;NLV^NX#D1oQJ$6fI5eet&)d+L)=&HJ@S*`KV$WqwomivgZqMh)8D+BTFZ_kGh0ZqMhfcn$|8hwz z-es7vWq;IAj!s~UNviz?aSPTR#Ks%*{<%V@<$|@DO7iGqGQ81GEAPZaiZ-bew=#u3 z&Z!=YaR5{18wi-g9<2~QAA9ffp$TOc36=8Do~W;a#ey>gG)%sOyjqX zS18Frb8rg+AaIbtN6Cxv()LwZ{%+UfeJ?|<(^d8 zy2%zB>7^55926HqYhop>pd1tJ@u@M$Q5w@@j>E$pp6>457-8WKBuYbjyK=_P&2JAM z=Zn%_rIdM(^JpxKSbB<_WpC~X<0hXKZ%wG11!suHmy?_ljo&<{58W!d8a8TL*B`v~ z@B8yt=wNM@b352-jS9|0`?OpiW4QkC6Tq=j-xu|L1kVI1O5T?hkmQ&N4+~oz8q`4N zD6?>_;%Vz=qOF7c_SZa6`R`c5#YR7cl_vTp47tS^d3uc45iOKgJ?jg2?)p)Y4N9V| zoIr2rX}VEXAhO&_KR3gy#d1gQ1&@c*IBuoWxTc5@s{~Gk*>0nFK~oaBtNCR(x<5=8hJM7A3iNnp?P?w zo9SYyNnsS)$^n%a&f`f(^pgZrCuQ@Vhzl^bD@lejY{&a4sa+yrMJ1@zAFL=ZWJS%9 zMeHmdhYVBo=B1m{FHNVPe6V4(QMm+-NpbT=0a8!zx~~m-vq7O#Zd)^GVT+yoMU0uH z(VU5>IVXW18u;LB$S#B<%oIQyScIoI*?pdpbZ6SChxH7~zH0=AY3&Yiz1O$Qy|HGb z`GSo)5%5pWYIh8l{}U&3^qA?jJ<)i5%G%5XlkiOcV_ngxvbYnkWslYiiO6{I`Ip2Q zLuIwagmrz_O@;Ag%WGOt5B$pNvRv@$H}v-Ux8ZXNHs2~h-~Hzb_+X3xXXM)fQ1x4L zwel#vNB}JH~PE2_2Lg+~#&muDF*=J_rtDujoK_ZpiU7d+I@w9opVGk}5 za<)OG>Z)!4q(PwR6M12-h!}4AR{;o$)^0;>%oOVG-L|TqoMZVFOJ@=_XyiT*26;^1 zMvotd(pzy5-7vkd-H#_7`T4MdeS{HRq$U4FiY zSuhIJ$7IWfa7pTUd#wO{yeh`Km#d&L8iA$Taz3btHtlN8)Tc^4Op`y)TJ&g80v2sFEFT~D|+0M0-&-~S|{6sKUX27pWqlcPF zG~7-JcBXu53p+o%@-p%hVrIt+J2Of6Lf?%VWU2t<%VYMQP@j$eqT}Alo8Qc~AeB}R z!}$;Xtsfi(8POm@$hh#uROG127F zsUPz#Q3i^{0R(9)@eXcpe-$zFkT~(u9-k(vlh~nl*S(@f5)sBt2R4feI^MW}NuLVl z_^p}_+G9Bp6>Kvf-kYXS#PG!)Zx66L8x2;Jj16QI1gTN4|H#uD_I2`?2Xi=6BhC<= z?fX{?5cTdyX(X3l&kq-LV9lqH2RkP(Ty#~!gybT4ulDHcmJB(UYa4uB8B#V%oC>k6 ztYJo%p^~#swP{QgB}<hYmK*lj^@jV*JdTGRE;8tcT6Fz| zO*GUeoKX?IzdqBPa3?7t^c$vJlSN$7r1O-AUh>6LXy($qlSi`9O+SO5m0ONEwl{^M zVCKq>KWJssvV4g;5H`ka_45lBRSKef<$*^oxrY{4J#Fu!B5qmZS=jT><*B1Qj~Zd7 zwJyT{`h?hDNr}-wbE4((sq+#Y9VfSWqtcCY z&FrYDX_jw(&n7g@gqweV$7_G?{_5|QIelSSf5B`iS1zN{S+s3~Ep~{4sUA=NyUWJj z&3Fg({Y_!CRfqhPPe)ewxjLaC8lM;At0Bxaua6@qO?@C#{=owv>>G~>aSm4@o&!2s zKBZP1=kSoBi0%gsi7H%R8=|5EH^OP53!(m5+@d$*7oYv@F309I%;B@Iy~Z1!Up#(} zFfuhCq_e_Q8K2P_rlthg>mPF}1{_(>7;96|4}pBW>rW;+^M%luUCRX9U!{1Q<@dZt z#{WeQ#Hjh%4tPuW?KL2kSDRQZaYS$yVqOSt0=kY(SQchyx#t+Joac>7GJ}9kdsiY5rs{ z0BXs}j9ZgdFzj;us#q=+g?Zp%A&&AN$Cvn4ML|w;21UGjCHMpw$c^5OIp&~6t;J>{l1lUO)&9fmsZ1-av=i4 zb}4uoaDMxZ$hrk8e{!v!J(TPCV`s8$a~BILJ(Gv0>)FoiRaSJVKefz$ob5 zD9FmoYj2;vE*hr^@VF9wXs&RuTmco~+soRU1m%Z^)lC!Lvj@e#_?>k;$C=$bDzLe> zNHyA}s9qHcQ!$%X5?{yJ_Jd;Axn+rnC+vuQi&_wvGccpgAlszDkbI+mPtDU=POTbx zB}RvoO}fvE&!m`8Gkq1U&66#( zM1y9h1=smgW}47=a#2#!%KL1`&Oj|8fFNbWp$h@9A2W?^VV2GYdx4%%|G2xTZO=GK zzLb36at9ZTvPj5-O{9?I)cg2R>bDtxHcasKFuiKrAS4|aA?{ws{5_r z$SS6@NpNKEX+ZVlX?wSuHRl>Z@&}kSdyOe=Nsc&@VlMj3pptyXBKS$gg$%NU5mL<$ z%d*fA(njbjcq5j#c-3Hr&BJ7N*bl)9!WMq;?a}25ZgQi%g1c_TF-U)9!M+*Hi{!ed zJ`O$E_a-f_4!yuJdy{bf35A(#T?s=EE`~RT*d35uu+wRuwYALEXKue7%5W!3m{ZdG z=@po_J2cri_do(!B(rt{)YvBrB7Yf~cphSny|$H0uO&zFg@Q!5V}qEn5%$?$$%T)C zNi`e6bMMu)PY{3HGk0 ztlPK_S%mAKKC|`Ch;t(nM;C{}5B><&#J{j!IN8C;{(CCGpHaVF-?OGh6He&9|4+ zOjy6Xe9Can647W@UZU7#JN0O){U_uHmTVefva%Vf2zg#raxoShf8-3vvGiXsv`~xm zw_|;@i2i&88Nj?ZQLz_3UdmJ{bgraEH-t$^xL7YeA3v1ol2XsCE=7DNn5w<6_eyUD z$^P>3&e4lueT>&=D~K+w`Dc<20rb9CD>PaiR>7gNFYVK%X zpNY40L9aEo#Veo?90C6Aph&0o7msKK!GPUGHO|{_nU*=Qe`e+%F6G0E`nLx;$E}(z zt5l&ge8=nI+wF@YKUKXw-*ZI#^je)QG2`uN$>JF-8IlNX#|06ko$w@n1mJ3bFc!uU4ZyE(3L#*X8R$l=$Sei;14c*;ECW#nqXd1E8{tF zet#cHwO48zqAfJ12^OBJP-|Yn;tzA8^ zCLxpe6Gj-djsp~oif|>1?va94KBxdS%n@;3{uxQfUF&sJMg&O*303*)G7<$uw-RC( zdtOMXSOlbp=a3(M!pILYCmCep99BcCb-hZs$ptoCk?W2$$0=2jfg>V{$(6?R(f+M| z*vsYCK5=x6xOELj6zsL#QE$5+pf|u;=y!8CLUk&Ni&@>1^8`pd;GS=X!Atux4%5?5 zEsO9qmO9PfHAC`FWb3R5!(~wA7q1>q#mWV7Uf>4MJX>LDd^tailQBpS>rqvN$60)C z_s@a$(YYA;%s$mWXJdikx$*1$)EluHfsOAT0uqV;cF0D+KAPi3K|TUowx08F!FIva z{+)&scaCwvU#dI}f9cBW41o_9yt9|9M@qVsz{~=$r2Z76g>716Sf2CWMUZ(`Bk`lC zc}BMg?&#~AAFL=WhzCRL+>0~(9AF`InR}ju>f;4T#P0TH99_>=>ozmZeu7$=VD;wn z<)vcv*YI29`vj@g1SerTx^CA0?^TcBFD`(;JY|0yoge~Vap9%PYAvijo3c_DW*vaZ zwnQ>T$+kd(8xM@;{0ASFD@mE|fH-?}b9(oHDTL!>9oV4XCZ8#?bRSg`td5~E%1I{dqPcKnc(Te1^Y)l2cV#As z_82(7DYysKsow8KdU)0JW#rAT|H5QfX*(*nEkf*SsvVze7UPGOn1}YvLu&sn`z>eW zk9Xv{c%UNG&L845l!g^F-ynI1{>~22_}T!%k=ZUFVNB^|JrLr;q=cb%gmqeY-F<=v z*5I654f4!hwEBh0N*^2pocI5(al!$taPHD;JK@>x4xO?KxguL?6Z~e+WI3{+-53Y*Ia(PR5RM?7NL&GKi#f+Z`v>mW`Vf(Nek30UoqvHoq z%x>gn;ND4cc+MoQwW-~@pE679C4U74C+KX618)zggA&2BOZhI6+6AUr6cbGWFd;N~ zCHs9_pg$XEjo((Dm#?<7tbWmQSleS2s31a`eeB9JE0^k?gU7mX>y?vM?f*Q@rWJ6Q z#4j=D$9{#3RhrBo=a2h)#8OnGE_Aj~hZ*5MLytXW;Ji1ruj4gyLGOG>9(BT{$O5z) zau%3@xb*^`FUK$FxcK<yXEZEp2&(Ff8Dc;SgJ*T!*9|+_6&-dEOAO~jNL^iDdN|Qq0ETC+xy|Zt+!)d;7 z3`Z#X4TVuJC<7c}qcM48#cxMGTmo7gGy%miTes0qTK9g>(Sge3iUWKz7WItwYiLYp zorh0z&2uR(l`WGs3)sDT-?#}=%-A9u&XXGPw|9S8uqpY}z+5S#-&2R(c+Gl^1=$%D4drM;5tMHaLuOz?2my#X z8FzZO;OD!GZsaTs4NbreJ3*QT2W0*m5b01IIFv3^_W>*h9F$I~uyMPiJ z6(P{_o2{q{k84s5ir`sesPdKjphT3b(#~xW*N&RiIV)A=M+#94)2>=^a)XJq8I&r6a;6cN*>BH!6K9Vqroe zavjId+AcJ`O}GkY>mNrm1YP`vi|G`&SfdSU&9wUQ8qxTqe-01NjHWsMliX>(L@&gG zGx_qKBX}VUYS4i5&@nexmWzQBHG3t1_%N{-oQ*P5_gJv2yO3ii3`)afP{p&wNd$B8 zzBDr?BU+WD<3beUR0`zdME4OBL7A9z1dv=O1#kry+prWawusITu=vSf%@)buyO26y z52p8U{vfy^mkfSw>|7$&@bE-ZWiPu~+Mh(kpi>6Irz%ljRla`Nl{}?;Hc`Xe_UX;B zU9{S~n+FVga{xu#yj!EJ&9bp$PBj=LUX1MaD$hXuo($j)pHnkjCMhSR?;qS~w~mS7 zyvog-xQg*LG9NBn;j~7OmKWLAz9nq!;xT4?Z@b&&Pnh8CK+mK%d`O8BtX)^i`et`G zLCr_)whJB%9#9*{0{3ocbDT@?=?pCh9Rv%KFZh+( zR}x8pQYx25^3F9wo(-m?z>=CP3eoLkft~^?>oi|b1nR=ce?M{#Ld~H6UTzm=!V!qQ zA+v1W8M0|sLEV|0z6%h-(Jwjvu0+ftQ}H0BoPyJ5#q2{)Er?!cE=GYT`YZq*f`|&z zTHOQ1Qj3;BLB;La*u&qvZI&S(})c4?7}>d~39&X>7364`ir!+6irX|!ih`PYzF zkd7PQXTjYoo&~d<(>O|1C z(aG=R%w2sbw|r@Rq+=O6d^!6P5SP1GcO8kl4$g~q*6*DbQZdU4ws{}8q+Vj1Qv;!l zHPLq|H$o>X;`m8|Q@w~ZoLjW~!6Tr5E>4~8b}_ukYkO^ql^|shd_ubK=TtzSSLSi) z>9If}^b!owo;y@!p4e)p?B^l^WMR?a#1;gJA8y`j%}OBAkbL*H!7OA40W(I13~hVZ z{i8C?s%<{Pcdg6ug$&_hFxe{zdh>7v62!d@Plpd(q{d_~$ITrbIx(MSALC6lv<%r0 z@_0cuTo$@EcQ?3bBLGhtHsD zm03Qoe<~#J=N+7|Q6C;>PAP4(KJfgVO%)&47?aEmmdO0TH@9n83V3GRN-Z`(;KgpF zrE;k_!Gr+VoLsm;Rw*Bp`-K5A6I4*g@QL3=-tBP9YU{(4f0*u&063Z9k|7%){z??; zgJy7zNtn)}TO+XWf0{tl_p2l}p08z1+5&v%?rD_>TjE=bv z!K*wFFI;yx>XYqAjp@Dj^y+ZFPhN^!+t!(!zzwTU8j0^Z+$SbZcHr+-eqA&wweZo%_usY;J4$gWf@jZ8+n3Bj_dl10F43it{=Gtgx)Y zz1CX2T>86d74#2CG^)??WGo{3^c8taq`tdqvo$rS12lfdwdgWc6(~~H*{~$*KF9Np zNUOSofHe^qE9}$A3qCX9Tg4>0(RXCp zff$O*sk${gd0q5bQ00~oN`D+IvOC61q z$`y|qs*E!YONl!!Me?|f)xO->6>{UbeLK4=x*cE(ZP?h#6K9+5sGlH0MdXN|=4Uqn zw$6$f>1zn#7lXB-H3%*lFA$B7{I|qQd#>z1 z5-Q{Kz}T5UXp%gy4v?ktMzp#V7#E*od3s?-N7`in1b~5xMwmZt1_B8rVOlyaCzfE= z4?3q?z0Z$(&g+q)<5d1!ozdX8eLEQMP=DfUL6RP=psYFG4Fw(e`u5(J&2v}xOF_AQ z@P68ZxBRoPw0ffP34EFv&pT|`Bx!mzenTCQ?3CEj*5cI}DwVEjcL|XRoJ+Xc@Cc9F zeI|;VEQ_1R#mpoPU2};viB2(NSyU}uq#4i)yOIpAEaSD4(KtPf+WhCkO=Kb0eY*Xfz#W|o z=y)%X04O>Q=biifOli-Pd=~ue(pByD_jczbIX|vLlWNYvVy!ZHP&WI*LIbn^6&}}L{JD=jy%TZD&)#ObeMY2^V!QE^X zqTbc{N>x+?+)U@YdYe3wuZzEV@I6g3;ofSv4)g6SWAccX7_}V8Bk)?9 z`beO;b=a;Oq&`XHG=~YTPlMGx7)bfGHD+a~(QeI)a%<9(tn6U3pM=s}P;%v}lhETZ z;U*c=c|Zkxb+IMn2)(35ozL5QzOkI7L-oS55cU|74!rn1+LF!#WCFLE3Waiy5^WryPw*0Ly~aIp0Le)J+#}#5Jq$aiVOPzuJDFdSPte~KGVcAaPrIYD?Chz{@H|} zz~B{tv$pk5Yj!#ipTFL|Hwy`1{s-x*ru=4?RDI`#3TREBFMna>}PXZ>_6xOEUTplvm9()*H&K|pYbTWS_rG!nA+HkavIH zo_wAz}k3ytX4pRk1L1}48c~9rtQ+oiP7CLZ1ydTsYk6$iqc_3u$g$zmYN8BQF)WCg{^HhykQLw(y@85AqiY2ugz~G1m5&bZLV%0 ztP7Qkq54*zI{n05>|YT5GY<2{02=>-ca&Y0K)2X)dNGv+L+J-AsOKUL@)gKklEiSB z@u&r#`~uZ7dIxkEQS0gx5z`_qkc>Bo$i0Eqp7aoKL7AScknxuc=fcrSO*>vSUQ%xs z#hHD$ACm#vxhz|JduNWji`}@DqApSVEd}^Q;F3MAg^y%9$gfg^NwCnJIE4UGixScAgK{( z$VK2D>hb72Pe;KN3v;xIx*_{F)u|Y)7eyD_(4UPLeju4Ju)H3oaT||q!C+ar{mb@f zOr5dV;R7X3ETY7LtL5;AfV|6j_!^_WYt3bidxdr7Qnx0K{7vehGo zJpov)mt=&4z~*9hHt5Zg8%V;Tb;)yt4(mGQ7^KoH?LdM~Dx zcYgxy00H_6gKx%ng&5-F?+Csm3GWxT%43}G4XBevMU08E?9D;z%Z>G@WIWOz9fQcE zuA9P#qLx#28MS~H@<;Uftt#|&0J}TV_>q0(D2$8Q`19=t_|S4?4m4ahXCYly8@l2( zhVUJKFdwH>xBV&8I}yf72Uy!-z=BM-gWI>4o?nD^SOw%?H`C>g3L{bej(|5vOavXW zcFGDjILcJ0=pg}^D(k!Uz*v$FcT$Zih$AWQ7J3X4GAmH5uvK5HzEuL1TXM|h6YyD@ zsuatY{~~EV-qo)Xpg9vs<|;xQ394F5TFiI!5@>Smsv5w+`1NCRqY{L}IcAJP(dDo_ z{o)Pe=VWELu=;<7Tp{-eJH_n50{d|WpPd6rt~48>R?MzUY}bxg|dH3;5`+nWmTy} zjPBAq1dqY_4@p*-1la7#Re~>7N_6@^!2J>bq%T;#g=$5I;9orRnl$Ujo5EKOT;W!m z$)Bifm=quL+2#P^CT(5-QstoU3`KPva90k=_Tb~&^(TB}yH6d_e*xicN~yXbd0!IG zl&JwPcFrJMj||H55tjb?4l8bY;H$Q2m9@gxp}f$4yS^v0uBtN-N+AF`B>VR+{(%g7w z`LpOYxRU^KprQ)|-1UK!mk=VKbWkIYuwH^p_6u*QreE(ulAg~qZm=SXULhQY)2K<{ z9aXqB+#h+|u6tWmA@hiE4{%7Xh~5tX!{6SPi`mrPfBPoKoH#)}j0eg5H#?pq>wK2& zUZ#xGB_)zA`SXvCqrVib31iU04z9iEY(Q)jCY-wC_Mzu4geHMx@+BP1M;#Xo0Cu;r zE#ZpDYo0u!Yzt4w#wOdE@?fVKk&62631qt9)OdU$%Ht}wyqEPfcJUOmR(|jY zsK-7(TWpv>@B&AMKS|s4gQ<`xf#!-B!{#o-!j|(z1N?Gv{w;t++5jx*HLEQPd(pZ= zGMco@xXjw40P5_au9N#)hD{(SoV%d3(#eRZl`iuYa0P|;@N)Kh+F&54ue${6;UOpbBNBw*7DTjC*?z;(>E!l>39JUlWjsHGlic@ z5Cjokcl{rTIK>9u7#JpaVQhO(*~d#9dQ)eVcwGj%yuuA8W3H5Y&-j%}Xuk4D=Y`&- zt#_t`CGhVjkzVZ-?S+KM1Tg&>l=Exuzxfpqal7l>&Uvm%@Puh7DVsA32OpG3EVk!S z<=V(q7y5+nG~6sMr@fTaO!4389aT8_zh_?0`J{>|9ekq)(c@Uf=mp^e7Rl?DXH@#%Np-eJ~glf;@7i=Da_LLi4{j%e8O8>Rh*wRP-^BU8Q@93%3vw zb!)k# zGOG{-aNHx0B*wBh--h<=!JC;Mnjv<_Kj>?6UVvu~o!if!drSR5_y^t7kXM5g19hQ9 z+NXqrb8IFCN(IM43YQflMF)h*=~8G+LgT_x&Tw04X557v(`% z`wOa<0p}LWN5Ih^Equalj?ez5h5V>5`^z|^19uS>8rVkCVOwn|5-Sn2*=u4gl^A-(T0d%il=0;ewyon1H{~O5uuglO~zJwL%i-qv0@rVP1O1Lq;oSpz84z|G; zpw4{2CT!Quw0RX$BEM5TB@TxRCa3f$hoJ6JuQ%XchpEWsHl{=wFoY-Dv4z?t^qXT^ zYJHxf6&%?bjqGRtlU)LO6&7~0S}PXHa7nYbatHqF<+H@q>hU4|K1{LT^M>Gk25x=@ z6a^jEQDo4t@-m_ow7L6L3Ee@7t|Yn_Zh(yU$h|RZJzq|Iiv>)uBWy0*sTeB8FWUg3qi(k>W7QBFHHH&(X2gz zyv~vEW8QYNv!$td<%=ADLjP&Q6fljhH&76~I!Ubvl`Ja7g53gDivZ*#9ToEWqXuxh zH878?Ah%mGGu*ZTps>_}3{-3Vz`kUWH!v~4s>W7r$7f*i?;V0S`*G9WRTTk8CuNuy z>=~%Dfh4jhna}El3<)t1e;aVn2Z4K6+u+_;uJTAdM}pbqRtz$~^eZF_7rFl0p1a0ubK6M3yL&{0u4I9ChqM7i zF{e6A*P!}OLa_ZJ!-o*bFiZ3dl(FFE8F~t*5M@m36 zTJAE=?*6hP{vt%_UGNq1ScFU45E9M!eLgDCjP@*@YjovA_0DZF z{OD|sq?RVVjmfHc%;5@ykPfor4J83{*_jEP{oc#9V=1r!UlFOd87O|`FSTiXrjWdR zgX_=8X9>OQrmdJ`t|La=f5|MG|2P9+xt(VR`t)P2O^hD0UnMsZQW3EO0Jvf$$dl6> zl`;<~?fhO3DmFGljn!pGX;og7ZjW!;)!<{Q1eiM&Uz$F&m!mEOg45^Ak{6l8;o#8k z+k&(7G{7;xkMmbpR8Pru&py_Q?YR!;1K&4C?09AJjp>7`V3L1d8J7S53pf5PAJuT}ohaiaJ=wY5 zB%xwdm|3zbM5A!fn;cR!6}Z}>I4sG&q+VX<$9CpM_pWU5f0Ne!7enm4mPl>-;fb({ zUSlr{_J*1P-q=T1^i|!zO`S71d6A~h!#J3PU+ioJj&gs z9mMK{en_$m7|$EXQJx6n5?T|E5f!$69@HvAV!uXDq6?*AqM6V-lKwIq9B&;4Lr+@2 ze;({^9=dg@6@$d9;A_swFd^0QKa}_I(>K&7sX>79!P4IdRcm~3c3j`k6^;X}pwBUS zJr`QMd-b`BP5EMYia*e~ve|0&;9hEio;-&ULDOl#}5Rar$4;ETyj&Fqp%ddnU1~5>B?dW^@*$NuCehS=_-Qx6~aFJhggId1; z@(9)Q(gOOam((Yo`?1Z}F}zT+IJl=ynEqc15UlbQD89Ty{iHx-U{g}!a**M$oQfnJ zGpJi-+f|1>Tjk{jHgK^3O7)^dS2(K^`yi=6$20~hYf0$q8URa3uOR?iIJ4T6hj(3E(F0*#+-L&gRCGl!RBW3{1>p z`^#HDIiyr1Nftmmz6wp~{O4b3A5_;J1`j%tp~cH4|EV#Gsk~3pG3{z3d8P6sa`gjA8zeyBCQ9eh^KCr-zS^uda1sr!riR9<-QIG z2FLe;M@KoKkn4JX4tjR^79bR=s|O6gYZX`9oC-TsFsODYNq??|J45Ya>4I;2L0}M53SP zGQLZYdLR1hi1)cR^586pZ~cB*__F%bt>=5cB#|J9H#rnNlq2I!EP0)@n19%tj!M>3 zincww*C7A@=;LzD;_qfewrM}yEDxd_J8X{im zcWb#fU}Stp1zQeCwmf6FH9&D!p$gF{358N0MSuwKQv?Ut_|=Cqh&1;2du>fN<%6e> zM6$>=c%DJ*mXdCxzMUbhh2YAP~;K`JK{>Y%|<+9^k9$ED1Zd~pPS z>c_{^%UXA`%34c3IND&c0Xb8mDXNz0iP3^lx0n>+ zqei&)df^Wtxi<%DLFYXDKczKvd1@1R05p;7Yj7IgV7>}M2nhBUurJo+yqSzxal(>+ zL4yZkv_mH&C&R+{*F3*;l-CW{+)?*P3WPZt8@}Cv$y)IH|m!6y|ttgyi1S z<9lucC};7-p~15Vq;S<=CgvR>v?wpO*asa0dD=dtm!;bcdo{F(qfZUu;R@~zrBk^Y z<<4IRz2y{>I_R2N_fWx%#w-8gh)L}fq1Uy zDxg9vOHsH>N>ojeJJ7|fJcQ2o=luSFPOeYWp+pQ$@A6;v#}UqH@pYLCPXxqmxUG-oy?kH#2gv~%Wq@)fkekJe2v+Z_a(qqhgoMi+n1u{Rrym{}_oQcr zff#iV4%bBxC)lx4dLcChz?;{j9*z$Eaj@@x6sr^pp=O`um;*&Nq9phB$7cezTmX-?37OsG{#S1dTmQDX z-vl2KXFS(mXT*?HauhWEoOpLI7CnHaR&4gZ&0&5E3f9A{w^mP~X4FK5+r=OpNZ<|` zhWOb2pAXM>7&ZK9TS!zp>IM{bgM;DrlQBYu5QuaKLa0ga^o!8fD+Z)Y1~3#RxE=D+ zYx|diowK|l25NgAxzBSW|K8^uodO0dlDcKb&Z~~*pQeU?dm*ar0n%H6+{%T>WtigE zMfXzk#9gDQ=PC$1_M5!|X(w-6Tv_)!Ym04_eaD7EluY}m2w;|rmT`|*^ijWakqCHz zS>{(GT+aq6RTMDvl4z&|aC-Jj<&Bt7SRY3P2c`Wg>zD)h6j%xUiLc<)6a&O7ntP6% zY3kO5i{QSU)cqR?$A(GNTZTay^&we5xftKWm7MN);#z3dehU*oe~Z#_PT`O8shY5;*$UWRC;3##y; zCoXn`eq?!n4cNpOtkjWDf}Sc5cl;(VRzQ`Z16gDo51ZqPEW28owqkc^Z3 zPQW4j?k{KvV4XGAMqSIzl4K`t_kIWFZMganXW^G{OG5T?w0t`Z37^MiKXMadI=Q?;!DJl{XdZ;cQ-JE@<5T){QtShoW;W=qMh^N?nm=Zb2l zX*|UO)S0)~Eg{qGmvn&=l&yX=a40|TW;hQSapz1yN4zBOV$3XT4j0UWZ++ie4zdXD zia?jrs3wX6H_Y3pctQDyV)mKKOgcBtJyzxA3N64s4vrTcERB&`F>>sP3DISeqKGG&T5#NIYvIyTh#aP`Y zfIa91P1p5lfe(zTNez_R^VlGYG@<@P=PJzGL~z@VdP`Tea;=pK zd$}=n{VG(JT0pmGeB^``4!lYY9BaBhE64Ocl4$T`RJOko36^VDeh$`rQ!;_55LT$<7?*hW#L>Rcshx}*J83xwNyUv3vb@phUxo2VQ_ z5n9L`JYF|jQAEDw04`{$hwUC7Il=bG01Xs__O|1urnPOpkzrLQ9(Tw z^TSZdT4c53CjOV|Ho~?}$GbZP^G+{={qDiBL8Xza-W@dZJqYCpQvvI?J^~OY1pRro z^^KRz9$yPnGqU;tDaP@x5uCGNOa^g2WTW3F)$ov$0H%#FPUf0;JK6nu?A#=hss}~A z1Pt0^kQDVp7(OKCF>llR98yHIelj1=hsVl~urr%s2ir%W0=5r>O+YF>{s@C6m#@Rl zcVMcdmQg*4eLx3&Ey`>teUKG58?0*^jS3^8&m2{@YE~8eu10As;x+23;_2xraax)v z;{CFjCkxSykuz1@qb*^Hz3|sl=!t^@l)Y?|^pm1QWGxoBo3y>8%bT zF?m#KEh^$3=bX!CC!=B7xA*tJ4pzEOjC~IQ!9Fx3$HyjqC|AWnoyLx(U?RaHBPkL= zn$@j(`usEju*+0ricpyI+6jy;(%Z3P?-lJlv|oO6q3-g1;SGYIW_eS0uTnNV-3>Y=#Zcr>N@5*rOQ3WEe}kcM1a(6lSg zQTBH|R^bIgJ;`e8CTSait>&e+W7CHWb%`Y2J(OC$SdL_$jJSFwr6%T;+7k+H&Ex(Rd3iiGiLH-(%w>uMO|6ieCx zu3e3iw^1{dcRyT`?(jVHJG~k-7}dEX9Rc2>4Pcdx~-pKUMd7JDc(RM84X!V;SirMy}S&}-?65Z8kX8}Yl(N#*D}O$`~kN>7Oeiu z`1?zWr{owC(v_-?SF~{_+r6?+8&+s?a|MJg31*zPr3?lzr-|6htgy>|2`m?~3gp>% z`ZQe${r-jvpsavB|1In_DW1h10~*%t@yxOv){5dAa*Q}=fvT8XSn~xpho}1*|4~U#+W*n z;fJ<&iy*eAunaPLYRtml`j(T}nL>eoTa2aP+A36j6BKGoV^o-xWm1;QeO6b$gt0Ph zP5zcog40O!r<&GD!UbJNCLf|vOVzuZtaP)+@=C)!E>}FYNtS+#7FpSjYM1qiJ)T+pZ~WTsH}F_;`P$1zl59Bs`cxx_4Rp9R z!)th$-n{W|=czjt*AJOxXwh1FJfs2#OheS1aTGe;&%m`~vjE~eT z?_F;PNM_YbVEXwHMh-~j#1Uk{f!Vt__UxuJ>4(x=_mLrxKH?r1NbT2v>;B3N<-ii{ z#0G4(Qdx7`h25YL7V{7jP(av~R<#T?697V9_{0J~9&U`+`NLh=IYK8X6m{G|I_k8M zfHxA(vNgOMr6beQ-t+2mM+{Xt|N8OtF?vI4N<{l+h?a54&>RY)yZQ(6wEJtKtQI;; zLs1cdm(1h7>z?*KdA6RQyJi0V)x4!s5+{KhsG?+aRpBcZZ0(ihijL(dzIs;u(Gvvy zf;-0^V6d~jkwRSL@m;S5om@kB{n;gz2ZRQB;_2utyYRo4kJOtdRz~vf8twYP)C0k= zObXv%-gli+)R+*ui*aiIY5`(>{@e(R_m2Ng5vQRejJ`@)yC@z{i8k7NLyrvJV?ekCdr_FQC;7M7Q ziB+#j_(GZSrxE#4+`93@h8X@l527F5Ii-qfGVFcT^&G+wWl}En+FiNtt{o+3OK>L@ zv{a?!xpDTwtyoGrsg}n_c?uXR*(FbJ)}cQo1hFXIDEmwnLD6gAOPwx`E6~^&fUr=# ztCB>ScO=bdT_Nf^K&dyFH#aU2RlpbU2j_)N4H*uAk^nbFW#;^@R^KiLJK#5|7hu|MXewF_=FHyGh%D8j2 zY%V?S6PN%!m2B=2WIL%>5&5lMpMh=9XEl2DvOHT?8XgwrmXWbz) z#R*I#|DTU(ABK>#AMasp8Y2>TPZ>!zYD9Ttm@==^e;LHy`k9;YWz8(~t4k0-_cbW~ z(8)JT>OyLy5r;0iek#_y`JK?#mL3VAXA9k*pwLafqX=1+~AZ%Re!kCaQ*Kk<_Q$9`r#vaZOJ&cm7Wk;trVk z)fIM%BykcOOpUwRO4(Y{^R4Jp4R?~|0s)4cCL$E5vUs~4l_u)XO7)umcAeRNqM_vQ zBuU4~OTo)jRsu_XgO8UQ&b_nD(LfjLJ$SO3vUAzvtFeov_$2h%7zvz%LxF$InVDQT zG$kh4CFJ~~=vG$Ie4IqLGZ|dK(j$2NVc*wqnepP~L|Km_!Fe5Vhy8mlYaZS6~CT&5^df3K}J*@lI_a4F8Y2>S%uo`S;mnR zXOT4ZJccJfm}|lfAid5|O?P!Y!FiBo*^?_t^rFKC-=FUodHiy!C2z9-XMZdH+su8u z)jV_+0cXf;??~K=-C~;si9PN^3gvrW7A(25*$WODNt*9avAlgT{1A1HiKhKT)?}L9 z6NKBqtha!t6jS3d4*w+y1!^Kt?qN4G@(#;y#rA%I+#9o3MWN;>X{gU|k52g^C2$GJ zFme`peUSTca2gWl z3s`1=xh)8UQ;`@KpXAvaX;j!fwpVxLRUh>2C*7}w&aDTTa}bqe%QS%nK@ft$t|$O{ zdec|=JD6JiMRtiI5D9`_8ZNJ&hh6Tvuvr6L=8gS&^SQ-QUp6(AyK{@R6EJi}GCGw$ zXrsz(|B%)%tkqW*wUIO{Bz;d^r2PM}_10lc|LgzwHfoGfGGKH!N~uVY4|?pIp_2H=l74-xqP3?z4qEO?)z~+V(p(V z9UTlTe>^7f0c#!^p2#oQy2_(DYIT0>Q&q8>Ugu~PTgu%U>ZLmFgh-px-9u;WL&&lC zzTO|NH;!j|?8(^`Mx+y0CQvH4Oq0^1VceUTLs065^C~rr1MAfSV2-Y?Ttjs4G`KPwZkvuc z4s_^qKx3t-E~>U+2b7QQ%(t*JDu4ztVwd{!Eu$w>&n74Wt&BibQLL|Ev@^5e2#%e; z1#f=w7n@FYmH<&GRjmj23wr&}$k1z;oEU-4b9*eoq7;m8<=*8B;cWndGi%qX9;bXW z#p#fY38uLZLs{E^GMvbW*vX~ON{>(FYJi-)0iLB}jGH7h@4o+J@{!4{02LeAebJ_K?D)Qg>U(g9b+R^aY*duO|wsjH`HmiKZM_*gxl zQTPeecbBr73`ho(2L@Rs^smNqp6`vmEBCYz<+C5Q9Njtue2=GH#EG=MkAUCw2Ms(Q z&GKa>;J}7xSo(mM7*)3;i$ly3O*!f8h-j=@=_$*U^HAbzSOjrl%w971ssa2`{#(Y$ zu}G3O0?^}=A}&!z)JiQDgpr{!&)hQ7`}zm2liA~P?a6!mg7%$%uPq@{^kga2TcLN+ zv$o(nQ+;V?k`viVa%{Q(3tol!F~$$Q)m;V6F*LCJp> z52~0@xWd z?$o-e`uX0iSka1%Gr-Jbjq17AHql#i|7h)9`sHe{ay}kshn6TtQ+y?=kQMLM<9p6} z_C?hFdw3#y?!KFJiSFC~hgd?_vTd6H{oTqIuFCk0HEX>W%t8YQbPof4h;yB1IycqV z=W{h8e=P#D!7w^8qR6zGN#5T)rvThm%hSFTB`=$a#_Vc?!S`Y9uk=#;fW^261U_9< zL+qJVD>`m*^5^c23hm2ivxL63V>=3Ly1-U~~sx;pRL9xnn#zu(W z1V^m0)#+a7nFZ+YZ&f@oHINgaLAu9BE`n)X8m}6WR}ZMTX_A8=D}zlH?oGx$FQ?lI zXb4gXzJSB5Zf-F{E{Ag80|~#95Ecnh+#&$Y9CP@xvclzBfg+CF;60F_cFp%00{%?V z;kazhdw`xhZ+HF$nQ!hi00#s-^Dv&q&o3|ORkZvam;OzcV%rszQbKGR0PuA)Ff*W6 zEC)ECp9g=atkt>hAuKW9fzcd^(lO0Vk~jP$L7vSgR|)}=?6=-vkzaK!X@qt_$|mCF zuUE^QW+ZM(VBWJ063-}kmI2|t1L9(NnNT(8r%#65qG<+jdyFhHD+pUPo)Phcrx)e< z!EqZ`Aa{aJ2A3o#2~8#p@=LDd3)oOLDB zyM;ya9k6c&IdRPx!@c>D8P#-IGzkiu1QO~P3hB9rQP)Hp=oS2zF_^q;Fl#jYqu1os z?9*@|lk6sL*OqN1CO9qo!2QJblHzj-;Lms$PnZr;|2oO~HG#pe2KX<2#p>A1XLa`T zsXzNlECn7A>x=1^D^cc9L*lA>5+ipBkkf_6b_;k#RqypW(J~w$!xSH2e>FfK^hO8F z@Sx4x705Tk6aAga(d`kbHm2g|^itn2Hy5iZ5v|S|jx($hu32DSF;eY4L1>)s-yT!k@ z6z2-Q)UJMC8BtwS=M?ma7GVh#dWHu%8@p55vh3%wvw;Hf2kwK?-|y{_R-~ zca*i;ezlz%F#RPbi!;SQkyr+QsO{YL&lq@ng9ZQ)7lfFgB8>4?|n5F%ncQs&kZwD zIvUJe!G;V(S|Q*wf1dYIh0*paZW6_=g}mN?)NJ)^l8kopv?@J*A`e z7Hp(+mX~tUE}XT(#{}lt-r)!Pn=fRL;OW{=Wcb|SMCkr(D z-Srq>HA9ST;7rP(M8gh?5uYBu(@VXu4f>N8eR+SUoI~Tgc>@V>9dhkq+N!Ob$28Kp zf5Hvst4SaqY7#Q=A(2&J2KiHW$j{dt1E$8r{D~L8+gQ1?+JtZ=PJh8!;{lB$b*OJG z&~;T!6pOZWb}X=kjNe))0vFcn216?nCf`c!x~pTmueyo+E*~NtqBK2pEF$V%H`C9riT z7ukLL{+V+5g>8NZNNO)IB)`5tLsaqRu*}xI7}vR+*5Q54g5>XPj+1%Pnq*HM#cCB~ z3lL3WSf3#m{AJiCewnSt)iMf3b;~_J^8V>^B{DwcHHrKW0iFh4ONzwCwgG>h? zqmGDz@9Ls2a6DNBwrtH0xMR>>>g)E3iaSOv*sWX1XNjpSSQVlYL2%(k^v9UT!Hj{- zy*@h5PU|WtW?sYmX}c1j6=>1j-G6}MrVz1f8Qpv%Ksvf;e0>xUbnlvr@JklR+AZ4w z_G%#^`O>;MmUDYpgSe(1RRWYnQaei~q~FWI;rG>0wYHA4BPHcEd+;C4!h|91wl}00 zmfO>5ED7xtoiv-jc;pVjS$DfR7;s>m32KG+lVZ;!2$DW_1P0({L{C}6E{RdS&~IY0 z6ka~4bNMO5eN0cgIGHw_WRbPIW&=cbUY^n+Xb^aEJBV=An|d<*gvKU2DQbHz7o_ZU zjckH>ODwb5?5X;+t!dMG<7<&P^*W2_)0wY&Kb?KKlWNvx9@9Q2O3D{(cYlC}z6JJb zL?x?Ulh?A{Ci|A!g0#LXP)nE>4H6PK!LnBXb~0GESeP(MeMm9+mEYtq{dS`G23Em= z8*Eem5v$$~LvTJSTpBpLdKwjBjA`na!mrmDuF=IE{SwZC+K8p+WtAY7)}d82uElY1N7 zl-*`{(s+lyCIa|VFF-k^mr>-@aerOjS<5DZNO^=XB- zzL*-mBE=KwRlN-Ggd;GGjt%$>aDns0kO>j#56oXtfNj+h>k6BRi!KP~PG+X0%>wLd z^fJX@d(Z8(?=%qz_`6(Hbzs(~-)Yl!zXYjoZYElAu1))B;qdlkW1S)}t|!MQMaERa z#8~#kDw}!hZXfNLsD(K&F`GP(G+8Fq)?XH3iU6}qN&qD^@bG$L({Q;T z41|sGD&_C|Qjx$NI0Hyl@O+Uc1OO`|X3kr;zm_r%oH+Y2HBt(69X%biRwq6G-Qiv@ z*VS1V&ia-DN`%|26r41RkEOguwos&WL!6L7mZX?>PJj?{-4bv){PcZDqA^ChxaOFW zq(o*%KJtKQ`pIs7A zja7TDV$ahfLs&|v_eBdPvGcL&wUIXYr3w;V8Gk{y^!$J&`{7_5o%1DPz)B&22&kGb z^m04gO10DAs8r2n#=RzNAC5nGd*~GWU~XYz^_A13f^qw1hisM5_a!dmRYpJ?^$3Eb zG_THW;{RY!mZa~t1t#UUqG3kgN%@>oVL~VfL2tlHU<{`5_woUS)b{UfhnEj9ph_AL z-Qy-xhD$7lrLk)h3H>19)@B_DqYKs&DwlwDg`{0d;yLiNXd@J^oCtd zSB*(=1@^!uN3zc}(3fas+C}-0g7s?eKTEpFPg+Eiq}}3GMq)(ybrd8}p_~{m+0~w{ z{fIjaoR1bfERqYt2o(UsUJ8L_A8DV=1o z>O@PXA<-sRaI~PLG=9JjKGO98yz`EM`a6O*2-t;vpUn-YZ5iE9(BtH6OA^^kTy}u# z^M7Qa(?aV&kfwvT4M6%Xp%h^tY^|0^h4eC4 zbjx=E;)1t%FP4C0tmbNv=3hiYewrC~^Me|EkuqbV2m*yN#ni9q7QpZi)_GzwmZ@)> zMK5u_0fulC&N}zlLHo98PyFJgcYMhvAY7F>4x-K~I<)+uE_J32E zWEXp8;>l)}yq0QqB(6(Hphbrh!{0|1p7`B1dz3Hz6Er4#L~i@*5u75(N=X0{bmIKW zHgkTFyUi`^I-!7g8GaHWzruJ+Tn&ORqlT~zsNgt%?|@c>6-S%$tRFQCOEIY%ArqeFx02yQ0sNu00uK1&I#|s5jh2=Q^)r zb3P~}PK0BP1cT7hMXZ-R(yC1(UbK8lzpp6bp1N}!4xD{&-h64ru>j`YAF{x_eH^v^ zw?rC=aO6`gGy*DsRDrJTG0pFG*D zc)nnZH}#8%XY7C>>avatQKYUlFU;vmZQ1jX^gsB>2f!_Lp#PSK9`qi2!*z@Cii)A! zYyAXK4)KB^{Uv5&1N$axCNWFNjhegn3|<+&^&XOIxZ`KvsH9v5s2SC{tekRl`WsJv0zJ3jw*5NFF)*Fds#KqYw2!Am{u%Oz}xk z=KYsj9^4BnAVcJz4-8PDe7drdYBbkzf1g05U+|rh%o_Iy1#I-4pHjw?ds=hrW)q?3 zz{s>yieCO)8JDzZSu0qRSHIdYW! zLc_wjY!8H<)_m056cjMzl`#C*%Ai5jFTO30Vr5;VI^I^| zlJomx^s(-Z-&@HGllwG)m7ca_y=ZIVdHAuw`AvB$oV{iXUAv~mfoA%h)EVrvJeW(q z01<*dKneDIgXo7(oa5DFyeYby^jIR3(L;Qf1?=H8L5C)Z=FLY?XVpv1`w-7jNTJzC z`$&=^{x~j=H+*dohJ<3VblV?LUaH&lf~>fNY(FGjvTk>?RJYj2#c`ccnog@tWv4qJ z1h@qH1E;sx!8~1)-BSl=2L$dcO4Emc7^NR4cvwG+XG7Bc839}Qb;uX0Oz&8_uJ~^F zH^|u(V2%9C(qe{q4BY^#0;3TjvQUZbb6cP@r#w}?7oH`Cv*68c{l9mz>%f7aq@GkQ zz0*9CvF)^d!GGl4T?s22Pj1^cKYfGk-p~8}%`6$XbEsQXZL`00r+rP%0fc=pCF$1- zHLPwPT32DhN?tzQV{+)g204HZ7aOzX{WRbkIFN5Qx89$A7%;!3r7fZ=F~mTBWuXi1 z(0QAtQd8ZEQi+@{F*{z=k05m$I|nJy{za|05S+up^9`h+Rrk(bgZq_MOS*D?UU|BC zqsu@6`@vzQt8L>k1Ucze3he2@bv)(14)&nAwwGer+A=`avp zIxI-rtJ2Z-&7F21R`9A7*o9!rK%b?jy?9;VX0)dfnurK6l@<%K^#e%q<3_1j$t}cP zZ)G0Nj70N*92khz%a=Y z9I;MqD$ocl^SQRCLR63hr!hh;=&Zfv+OCz1Up2jQh_1Q7WS3mIGuKZo96Dbprs`UDq1m8F~MzoZV zS1neQmMIS0ro0vd79xH|kjv?O%_BD0%Vo|+E^qFyS?@F$l>4J*{I1Yn{s%X(|ECbh zo}3eWj1PUv*l{xQJ|X_$^dUT8P?E8ukI55SA)T2_)8#z>B(1k!l0(x^=BjMBlLE6W zM4Gwk#pGv^;N4@cw>`(sKk)r{7N)ru-5MfxemjewWVmU$ul})h1*ZIpM9<#&6Ny z*QKJcqgJj&@+{hg#ebC&{5xOH|C{6yr!<;GSAnzamK|Jt-o*GmPdEgsE-_5Pzk4o7 zVmNV1tsu%anp>*^$B{xM%qwiNn>Q1AQLWL82hM8=Ss6|rrfiAWZW%~daHtt`a&>VH zaCI5jVrEEsr@X=6w3BVB?_C%-ILNX&sZ`9p79#-irDz5<0!iSei1+U1%@Z8C=|k0}Czj}GF0 ze5qRU8ADEe-`sSmiG(4MYd&$!R5x&p7&1%f4T3S0952|wiCUi5!=#~lV@_vW< zFy}9LzF@>c#<%b`YM{>2^Vj{n2B?we2|C)3?pv#6j{o)eA@X!++^%2X1xmc^+>1wV zT#P~)ikuC+-cHutW`_EMa$s%cqIXrS-{-_dBy!6OyUP>G1MIhija2dcsTXcqFG^|B z(=VLcB}MaoWa%{fg2wQTx3$wZAblPK>n)VI8V?F}%NWOlct$vaXN`fePr~i)*elHp zw?~JnUvmGC3s9z0T)c`za(shf;NI{a>oQBJ#)n65%Lp+E3&4#;gUMgV^E`+M4LW}Q zfDAdy@`TR!8j1d=REg{|;Z@q4N4IJ0G6#SB$dwe%An}sH2E0^?XCu+L)VihfuG%q| z;rQl<>FTOo-fzE4^PZ?Dd=>uN)#10>`z`h7^c`$M{^6DMKa5r9Bo}sdMq8(_6lD-G z0-_4`-WV5_>*a6Y%j7yUFNRt6P(!SmlGJ~x^~ut>&Xqro@x0_HS7CfNxNhxP_1B>5 zfWMdgD8fU@r0(<5+TTc8uIE{gLC|?jwkYUrhJVmy`9hrcV{|j(IPq>1)sEM!R<1a9 z#hkm!Q^b|Sr^=xo=MaR;h4De}&rm*2a0tMA^gtdtI5@nKm!9EJq=H7#dD;T2s+B)c z9=%|mk;)i5YaGQZhSPEGdzMJI2`o0HD|to9@^YTOuG3Gy91FNa+}&z+lC@#V@N#@) z{>!?3`N&*8Nli;WB5I*%{khu%rxNj_1xJ6nI zKA%tyIrd2o7mh0&Ju=RWrnD*HP$+3pd9a^w*)!&Tlim5-dh3ltAd@bf!<&+>0{C!Q zKc7i?YZ(cPmHYtiKSRKRVQ~h1^M?l&rTp!DUcj=h7Wga3haA_7A4A>9z0l#SZMzT+ zNHZ9g_8YmH$%0Xn>n0}=#aIE?O5)U`%_K6UCbs(AVT^4IJQq)K4#R_40`9s3Gb9*b z%kpaXrDpM^(Rk5)60a{?+z>T-WnNF+Cm~>IWh)T+)o0$E_R&|Z8 zV?M3~{*;ime9HQo0Y(gF*{?TH{r`6SZv>hKIrhnZ@WiEK?~J7zyN2Py2rK+>ETtAM6B%SkAMotJkW5QbD)U9Jl>$IwYMgDf{wW z>oLwMwkkOhjt4&HWhB28z2TtBRHYPPZ*V@5e5q1`Q}#LicKcgclUe?V@qt3{uP-82 zJXxQ{5t5R%e-FqGe*yO#KKrLzhrlj9^^q`bL0TXH@`0vCAQNtvpE$y}A-C!G9qb@? zKv>$Iy)-2=b3!qEC1(KGY&q}tfKUq5vhU8R6*z3wiLd^AZ9wb!uWpu6vBgl+ps?H` zyZh0D9;3@164vUklGF8mhp|4-bW(7Z1Q)e?*O2v4<=pwGB&|w!7-efS#=IXL<=-)^vG0*E!1`> z8<()!nZW1q-NLF|zQs`XIa?@ls1gir{AUQja|t5hP#c!I43xwR)-#FleR!ogHWap- zJ5Xj- zDU@8x>u5X+iIF;ROWMA)E-K%!NUs`iVm`92@B^pxz(1`!x@j^wlZyx2#!^i%+24548nQoz<)Rs}_i^)ub+Ma*K)f7Z03vZX+%zoX%Pli-FUzNAC zT({c()h?P@LNHok;p@e^M7xMMhIBGCuLM)lbh|eP6fygxT+FnYYD)&2GJE}nL^*bA zZkyV{7oVNZ(_vG70sJNvqmgari|rPhIVdl($mUq<{K9ZG>$vRv}vulTt^xW6dw0YcuEtf6>Zd2$k1)SX;dDIc++4&l@_~|er-yl zS>&2AOE~R$t2f~wmP=xmTs?-a3t1m2`#XY)`T10sTejeJRyp$RVjg`sfzE3RxZFH^ zL9v};Vdor2dO833;?x=jt{?HKu6iKB{|E z5Xlp*&M0EiF~5a{oQYxtFg+{D$HC=kKKH?EAEL%`KcRRae34>?Vna<)vO_~p)0q30 zrj#otYB_Rw*-iZ=LjkW^k2KZX* zGw76%**4m|o1d8qk4Wnl2X(C@y*lEtkcG*n=Gvu?YqcU6a!eE>pZFDNX_GdLZ8|PQ zmqw#GF%mkM>y1=YN~ATC!nuT#drdZ)zjyDxWZvlSen86A`UA%S!J{d>+P3Im1Uf(H zDj31Vs$jU(pEF+B2Ckk$=NP>6!TfNT>YQB#-0;y-4h%U2C3AzId>C+*4!S*WWF$N4 zXyak4jGT#a_)te>SB~1us?$*86KNZq*#V`;-KZuq7+K|r zQ&X%ZrPHKWXfDEi%aM`P{4O2+gGZlbkHezEHgTStLOPEsV@G6Lry2&T#2H#LG&;!Y z-X*&T%SVY-bo1^|)3|fRWOqG&l-r->_h)#mk1kcXJ;^%N`D5I~T(^c&if5M--OkL^ z_m60>QIIcg@l0xZpwv*!fD&nXQ#5tLcE>`BX2Dz9)9m?H6s?a*q5TG zZcs)kOVZ<00MS^zH`npxBFHPV;$WMyLF8meJ0o~1`A%CL+R4fBO#44;!9la|r{mHU z;4VTcWF#+5y=J*;MN_fy&92C^eLkA$!|jYuhs2xsl!bho<_k=tn;jpeugVWIc`~E) zw1#I%YHGgiDV>&4Mwr9V-!%a98-QDw?|_r%@(pYny!{Bi>wrP`SnzLTGD^n7@FW`d zcS3{eJ#q~5ebrDI!!=auVm-Q^m+P{k*Ku~fe#KCi-q;PD(C+s-pNtFjMFR6T?gaVY z$WPu0`C=>UQGtF9(FhOWMUvocJ@;kPH&C0*lKvo#bweGe0zp`qCoy8+=9>kas%yaD zHy6lb`}=yaBg!6Mgo$=xtF%!R5}Ibh_-{N@G4moS1fI6Ygl}|#GKm2oha5=XOuQi) z$LslNlrx;$=sbySfvZ|ty&a2a61sDad=qG|U)3QCyltG2Rw#=8)|0J7NBR>fK|~{l zCY%#0nP)`xKK>zr;SJE}NQ=m~mH!4(Ha~$zSke1N`S0yUnZuhVnR0%GWzp0cQz8&Y zF}A|j)6Q1t8u#?mrPU-r>5>4NNiQoLJaWDpLIEsk;{QT(FGgX)}#h+^-6;IT>pA02uK zk_nYprWC|59Aroe{OTfCz&>KvC;akf?jGTsdXxh{_;@JuTn{w3?MCk*vnQ@of2a>b#I)Ed|c z>0hMLe&_OubtSXd>~<$x5Ke0XlCLzwaTfa2}L`xHRD_jX$ zSk^fgk`w4TC?izM_*Ed_B1r4A^bXR04$pRcXjzm;^4 zVY3WAIFYi@C}=ZDbAW0P1L}gt7ie4DmN(ssq0vXghJ-D&9aPhOtxvHk+dywNs3+0F zuSA*{&yp31jqQHStf^cT=>W0EG~c^HXak#RcX$>`BTu4s4daFq_a}QLYF?rJLdJQx zS;h-0<;>&ZkZVjZI$velq^xvUZ1p(*!qq_LTXuYvQlFTU@ia)}rKq0~h40DncHd#N zD*|NS+Xq{!?u+@uxZ_|7adPU6j5DvE9^c%o3VWxYY|Y~KVF8wx79V8v=I5TxmxWFS zSVl7G9^~(xzeeE8ra7etvDAG z?lNw9 z_VLy;Oww8{PQ6<#W}LaLC@(*B8~ZS;;u^L0MFg7lVQfPST+s~_e{R9N|dKdwQ z7dB&GxOAQYxyqijDylgqD>iFo3H1{L&(pfp4*oby54=x~@6D#+e9psFc&q0c*@l7` zYiYQw+aS>;I%Q!S$Wg__!rK$xQ8ipiY?U$hMg#?841P@s`sLC6jD*pgzTKmt<_d_r z&rvUSlqW5`{lJ>B%zEp=!)g~XsD}OW2fzP5P!;Sx_&IR7@rEC5d9L@a(qa#ox#WddoZ2sxJ*Q5hC+Zrn>zoR;b)^S6y{xw8tWIrMZ`Mo zHcy%xOpFhb+)Gr~=_nCr-vcayP@;ImLJt+*HvZ0E6L6}ud`=E%2WZK^ccKby594V% z*oo*wSZaVD_EbSg<|NYzv)uZduqq=Xsec&GPL;_m7Xs8V;x@}pfYtd02pZ%Ax1EyM zt~&5y8RUb>c$avR4)b*{a;i2+o873ed3T`&C@U#(`D2x#cG;J~mFqF`)TZV?pI8OE zVMOr8xJ6vwVFmpe&dJ>JujKAP3Z~Fw8(?jI)Rqo6$nh11y$ypp0GNLjnUzAFl4$&p zJrI%DF+DaD5$7@0%ToHZ{r6_a69(x973Fvq89dQe36Wp$=8a3U+`^{GYd&@C-CV2jdtrnAyKKhy|~4 zB+K>RiQ~$Hm zhX>acQ1Zt2BNOJ&3F!9l3RDp#qoo5`Xc7&>FEuXq;1^MpwY&6xzeonL>ge?A@)?eb zf~!X;xtgl;X0{Hj&7-7}mEooc1R}aMcV?$<`p;^mN(%VslUH@G16j~7S1x|6Vsu<@HeevTplOF&6Zp-a$S1#6ycvnSsv) z$#s8V{$?=!VCVX=@mR@VFTj6)l1zdGtez918AO$eAwZ;x5Z09{BpSanSt`^1_d30c zaI=KL$?#*p-y+^W`xwXH-em)_@TVZu$Ek&SGx|EQ$2;Q$J^tA*uf;JI^ts%@Uck** z0qDtg@v7M}>5*~B+19<4;aBdUK*if8A(7OHLneZO|W&16Hqa zDaniKTDM~z!16xt99Z|?rCo+QLxFdvvUXl(2W;eJ@baDk2&vR47bYT`_uMOOB zv95KaHwQTh`92Lbm%s6mlBpO~f$40qi|9x&UaLqUN_OALvdt((c6#@A0{ASvCP)+N|B7uI~-u-)( z!!Cd~`>Wg9+JyP}HSs=Rt#tm(^I-T7X!3thtDXqBc1*fo`BWQf9-&x|u3WlyMH(|( zakFWeSjqyig$Zbu@A{1_ypW&x0VjjeqeZ_iq|17FhKF;;ejp6;9o(6eO9;yaTYn~R z?OP?+r!*-IyH@OVdmv$`xP1U{C9^_(mgv}60bLgTl5NJK@1{plSu@n|As~=30O)=W zunkxR4z(yibq`xJV$`Tw9x)z{!}>O`3^YsMT0#|Jz9tKX$`lLce-qwN5; z-Ipw6h!gqn3sOj0H4ADbjzk%KOZbYH4Z?f?4N6 zk`XWiSPMeR(QYa8n12|4*0ABEo6-bVdjBxCVt`8{AjDeLfkno|D4IKQl>aJ?JqTiD zA-|cYNvSmA!^J>cXC0C4dXE1)-u*=h1fwGFu)$AK>@4=}-loPms?bu9{>80L2;L0? zPxg@8SK9P{Yscu{+6m`%Ma}eI7;W%#CC<_(41jXP4TM8AzPKZF9R-09>CXDUZyI%Fol8}Ugi~< z)ROyl>HmJ_uq)s=-A+j;fW^)B^yq}Q32lmNTKeW+jTHuy>oQKUnQHKiO3w%Lp`bbC z&n{P>;FZ+uoB@s1Fvwl|IW}HCNNM+tULC0ijC(lbd^HyZM{o56T)}Q)+AOQgW}QX4 zo5aphZ!HXIG*&NbAj+q1go`pKtF&HT;%IC+y-mpqfUc{#xw+Pbi*E&Q5D|ZUcQyS7 z1XL}UP;s>htl4}>}8D4rNCm^`acGt{-HY5C=IA@ibP#LcK|J$MQ5)MCT=-dc{pm2ESIa#co$op1q8elP{fWw7L+F)+z@@nea5 zC@x|Xsc%zG?fgp$|7f`I+ZV3bjnls*H#3LhK_HC|ICZ~FWGkc*E8Rs!W;@3J-77Os zh(DC^K-WW#_QXWU)DYeC7+SL%3sp{R_N2<=*4!`+E}hpNtmODoCq&QHFjC~K6opq4 z@P_KIc?;0hRZ2M$@MxlYM7u*^iJwvUo3+yf!6?dq>xHTD=lGDknX<#^Y^7%J=nKs^ z^sb5kDTc-fYkhSfxLe$&YGzaZp%}!vBMAIWv4tGlUhwt;Wx0K8*7{V7-aD`9=jKT% z4-ANAY?S?=LDB<*qLeKBoidyd@dVXW8aR@c+_lwcilfse&~e`dLXd4?q7w}XIkL(; zHyI2!OaRYy;naxm6I>E6_uc_7L650sxd_zjt7F$X8LtmH(#Eaj>21{IfeR!#NzY*5 z%0#y<_{T4P3rxFvDL$J{>D(zr{8ohIF_(R`4bA0N(S*6sqS zg^6)8@t-D23$F*?=>L z;36~pvePUYCXo$T#VaexLe zM`+&2TlEqjov>f=_UlAhAzy)J{UYc?C+EGd`H28%k63Fh%4-c+kU-E!%TI8RMV529 zAJKMxqa_n|l3Z?hs|W*209^@Dy;T(+X()Wf8KEnn{D@4uV{dE@+#fv_k8H>`1&t_2 zO6^+Yoj<+&dY8+SfG7raS+4b~=8-s{A@Z+lF9uJ%X1A;feOND;SVPx9mDq0ddbR~J zMN$B#&c9Rn=~cpJy+^+_G9_68S*a6WajHRd_BJoKHrEUAynTxZhg}!X7f2;n-BJ6$jP>SMus@4opT-!!lI-VVZ^Uiq^zojn!w`@E9gtg;}nOr@ml)YE&^ z%}v0R;llUtOk2PuD0|w$m5Y0Yf?UuSAUH%pA|X+mnn->}3|hOW+^-UeyoczXG!vnV z0*BMA5kk`Jp5=rvHzUvSHT$ul-&VxiZ`|FqHiLs1~sELyU5Dly)w=5Vw$&hw~mGX%{MTl815B9S1fhKH@?l_~^ZOmcphvFboAOqCR`n-_|r+kB^W z?HYsfcgwH>6vXUp{#eT(rLPQV51w7Ht>=#S0y?!X;7W;)J2yzr^QkIf?yJaA&p~5X zQ}rF`$>USUU*D_wpdN3m?1@c;iiU*(PImSo6uzO1<$e0B>c6|YLj-cI{UQ%8(ud4! z)dR2xg5Hp?i_zh7!+f`lScx0oSkm(|I0QJwFnj7kbUj1CXtI9xr!Q9My+OH`H;)-@z^{0ZxOB0g<}>;6Qo>Znb_X6UOK~ z_6_k7rKyw0KbE)aKbtl9I$MKGjdh>;{6G{K?_V^vrrXKDOz6&N!L_kV%1eS5e~fJg zfqRuOf#9ymC5|L-YB8l}r4xtrF+=ki5BmL#z5Ct}x4sn3tl6Nxe7nKroaj zU%tBZ9kBJx-g(}f3~u(BCnwfSz}@aA8WaPCM|&HlmfgnB-dm|OHaPJr(Gw&cQy0WI zRjyP=u6x=W?ESr480mVJXU4-*8!{;$9rNYJMXkN7_4yXW*2FxpMSfqy_~Sw$BtqDu zt?NG*EhYw5q8ZzObbq92?(EpL^Gz5u;jfw_7M(F}x$SReOi1X_zE_@+NtlIRc=1}A zrSSbEnB*1%c~aLB*&WbJ^6cdZUG`njW(7GY?0J|Ek1qPmb?oc*_SLJgyfOJ4|JKN8 zd{@Wd-qs`&DtONDU4R0Ce8qZmZDrgzFY77DdP0sl5R5&=B}mnbJzWG z+2RO;1UZSuhAs13)|9Z^^0*QIbV^N(TcgGdSv3rrg9B~A!tQJ9y3+FdG#lzz65b_l zWQ2jyreuPC}o zVz~ekGKKW!-U|{h6&>2H&Nm6K>3DjI!$1D_mz-fEGg4#W>2sf(;hpWTezxxY#@;&$yC|Grv;OTjsC7m&UBncL7p&4MPMs$03=U0q%654yYk`=H!bxY^*Vb=m~p#4|ZRmxFuW-jdEA z(}vct696wUAl^P<>@=ON)MYpcM%7#fY|Dp!I+t#Bq3;%eqXuWpap+;V;yH0;QhK^6 zz>rBE>i%oe}(vbpZOZkHYq3RsuCV2d{0A?jY0WM@2j5Dx%l#D*&{z*cHoWDR)${He5{AS~`@mhC2*|e9%K0uN%yt6O)XR`D023zlGsOZFW&=&U5Tny2MK4bGZbtuWq_Cxs=-lvE zI%*|ao*FW&BpNbV(Uha%vLQL$64~h=o_S0dvzKAZXAaf_dUrZ_+Sz&7@+) zp0Tf}`?f3D$Jdb3J^34y>mx<9P}cF@{~~4KkA$lJi<8~+0>{Qv6g@rtS%Nos>MtM} z=hM8Dxnqi8v049S-5&GUm~J%$Qimd9YZpRz49%9Xe=pujesRIuDVrm* zTnOAtzvq8`s)mIabJHO*XP|bV5L^ZTtBGUF6s`}tHr<*Hm=SuL*5T!LE!K+;bQ5wHZ5qU1YQa08<^EF*%Ni)MItFL@N=8L*oX91;K-#b z(GDX+Xk(&|wIdLWbKXuPna}SrcMt{}UAx7=?^CRrgOY!7(fu4XhrAgl)EB|`4b%7R zaM}Sz18|WWaglvpfSotw-|YH1BNt>c8-stP7$7~iyPC;Cqh0_hKXdK*ns5?I-VFQK z-71j3maa3=js<9Czgq>gf=wEoeMRIKSVOH|OKWE7K9+UfJ^&ZnZN~ z3?zur!6OVHz>oF3F7pN3ge4_lMEDCBHLurDumktJl2zK}C?ltE{@2xD`=kXQa10LSGbkB>!=Dbg z_YekgBz3>(K0EZPsj0EY-TBu3cm6#9dk&2~vtBY*)xp95WJ0kI)HcJ*L-{|go)d|j z?4!4_-2a}T{Scg%!1ux868r82)54esIcV`9lwr!tznxP;5mv;U&o98_R35vTBmVq3 zU<8`a`||xJVo$BE_>732n?3(4258AlD2j4oa*2%9mzSqHK^~8juyivLtjNCEp3BO& zL+=6@vh~?gpcOP&giaW+D2OHAtDL7o4dgy#5SqUm)An}AO&U!%KTxHc-DKBA`?*6A zLe8IcB1|I&|8&Q@ef-m3yZQNgANqOXqmGfSwACV(O{!01>>xWGeq{QV6vlNFlasYiQ>^x#)$_RV_tEdod7lO1578hZluA$*R zLkJ5WxL*UT^tG4CUz--uI7|nvb;YuQLqHACOrB`~OXBAs$)&`j9+-UVR>5gIoyT@e z#uAFYzTi>`RM&94F!-kF-GXJrBU8$R{j>^rTH1x1@?Z#3Squh_rHivyM~#TEi-EgZ z!n@5<$3%t?)Y(yI?+*^C4hNQH0pgj)FOjp&C_1v>Zg1=~G}kEcMvqy-s3dCQ!cio? zFu#pH(QI$*>c!pZ%BRyOyNyf6KdNu7w1r1rYog84ecL|+ZE-(+SL4=Q(QZ~{xmiQTH zcY~me;I`*f{OO$!zYY3+bC8Ln%yv9&U_{R{6T8*m>7Fu_qC1{T;)vuF zh=iku3jz_Rw$#n;BZ9R5J#}6ZqU9#TrJQJ}8 z)K)fqcNwywKdoHDm$rOnRmCT-oM~er6hr-wBS$t9H|kF&174-WkVNPsrPR!@>TQ4O zg~1`d(B5ZcWbITVg?F1eHXg`V_H7{0qAAlHPt~O)cYjH3&Jer69M}gDQzIApml8ff1_=rW6($nF#pK!dRiwxy43PaE5N zU^2RW^}FXN5K6pM3Vu6rq(f!y{UJu?>^>QH|jU+2W~HEU;Ei-k@NF* zNc7oMNpiQAL!sWAo7&nFB-H=mj(seJv?bAJtxNuTeQGQBRL8#Z>NlKy-5Hkg1s*yse3ywO>(pm4--b9Q;DQ@hKI@n7ipNi>vlTo+M5QQ!S{eZSWLIm}(-F{FPhHN&}jC4*<+35yj- zJ%4dk2m-1qLHIlq)D7()xEut(P@w-{ah;Le#)KTg4#~&*iBlo7%_`<5r7t1uyl2EZ zS!){(fHm3I&K*JT{tqW;5^g8L4kshMIuM)7K{2*CxU*568xWuP_(1~|Mcqf!&2wMx zcDI5wPGiG!@pfON?}w5XCmwIh@y3ZUgpT>!@9iGByD#^~<;sU%s$PibG0bgx@<;*v z!|l*E6ov_lrjXw3RC3Y;1kcj$f2;_G%kK)+l`K%*trsuvV*mR~o;L0YsG?Xah@S-~ z2r%n2vKR^?f*b`go$4;P;+fhJlm@i^IHng@C@;kzT+cBvr@bhAgJ6Wp!4W#1%zG$_ z4a!tHqfe93l{}*L-k3vrn1?Dq6wC@dZ%%WBghm^&56wxS=l&t%VJFUF&3<%^@>@Mx zgO7Dg;Y7S{uempwcLmV}YVoa8Y@-yPoDBjozTz3R8$)blFgSFZHC&0DKgn%oF^|pd zz&@3xtjR@6L+&ap*M$4QGRYvfGkGV@OUw%ZzT7x&VG(Wv3$pw9Sl>%-1Q zm@${E@vk*Hi;;5d)4NaqRvA%&nARL#9DTfvWGpceiJLzk#Xc||r0EX1=rS+zHjC*40?K+#UlA>?q2C%l{~@Zhuq zb3x7#xI}vQi|no*(ZPJD->XA}LJblmPb2Ei2eP&K>s(hG7}Hdvnhb7?J*~y@?8R$9 z?m)GP^mbOKd{0U!66QgyLD_8OizeT1FF5WUrYX<&FVlAy`Jdj^o^53NT=)dZC$K9_ zT20xZpkp2^OOosG$G8!5TF3Ncolm#I|F-Stu00!B+uWC)+|IIpK;he*RJe}=OdjZRK2ykXAk+k)Qg)&ObH>X$TuhOwZ$Ug6` zAx>O%mO}D1ND75HvH=e~lgL5wDk4rq@|mFXW%3?pnugqSx)$zE3N$QNbx0Y~L`0OA z7-AdRXcyb-&1+6h%>v8XHxf&owGkR!nwm`x+s`p}&frS)YvYz~RwPL{cGLwH%Eh0u zY?_ngDz@1&=?C9;4Ugu@GQ4kcj3LYRZqGfv`_iIpvBOL|8y{k{|M6lcG2JK2j#4R8 z|K-Kk^zHGmb&G+W=>qZfkLQ2e@K5hhIXb5G>Mn9nV$GDnIP`utW%lW(ropa4YWk5} zY~B#0gpS_?I;0beg47&1AAQFA}s{}I0ibEqpd_5*Sh)G8SvRbQ=^3g5$@** z3PKSOhk4Figkrxi2Xc@)Cn*C6LvT<~Q18eVnSgyh31)oEuLQ7g`h|jD<_=3WcFKN< zv*YizJh)w#QU(I>w3Gr9B2 z{jxD+?5&9C53-V*YXC4*p~rrVDE}~XM*jXyStBoLwSo;8+zq;H4KVekH)jldMIJ{( z$EH}!&_FEIuBTwr|3y9OOfp>}QSb6VLD^Oe1DeC}@$`@(v3J=0;Qv}%aek>Z?wS8hN`mcmmC`Z{ zZw2SM@sgOUayg%OFXe&DdWmo;7#JJp0$r)a-f+}l0RVrG()&}9ly;^Xq0iGvxmmx` zc8MQiWk`fy8n1CBG1WvVxqT^|L081rSFXpq#ZEgrNz`+7i&8|5K7n2obM7{uMc>Qw!G!)rPHvroNH&Cfpw2cwLTi2c!;9m91O z(fzK`?)-Gchk?Xp0m&x9Gs4(>sBLqi{KVmeB6yPpk~>Mde%i{M+ad)h^`%tSP?D27 z-kWrK#Gv5ou6{5kPs3dkDfSJ6;vj47t3RO_RW}rcB^Gk!_^DWe@!qWgnG*dNkXggS z!)fq@{B~hIzw{scH&^#A0@uIe@rw8$zOc&d^}%d~ePmsMq(uVqyD8)JaI#=rY4&!& zKpV@Ei#C ziMu3U+_)4g8||HZFo^kKYwP){T;K4O>6mPmSl^rE)6P$OBLzA%7-l}az}!rbN<>#c zfUyTSsMGb3gOg9}CtTAxmx*Eisd5c5iy=O^e*sA6nhNfv40S&-X2&c%Vm}$6b!-Ue zG0N`-jhzyJ?&-wd%m7+KK4`p?gXNW3rO)q~%wYR)BUeoRUal|BPu%SZSk9DF4}!q> zJD7!bM{tgwAI8vb>V<0a+ssjgJMrW$m`dc2k|sH^ZA@*-R_<)}s|w6Y^#iH#KX7{yoQm)Sa4g%%?MUFQG@T zTbT`&PpqemTpSROAX{kXbDRK2EY-PDDU$ykAOboJJ?p=Le-1bc(gU|Gz_)MNM+N!z z{Eqk6cF_LNt)~=##wj^cVK|O!9VoTaphm|QLbxDde)Cf2&s%3%-s~6WXWdJ=K1O8$jBA{wU53`&<8r{FP^%6L|D{Se-{*NYpIkzs z!`a4IlBoizs{N_FqXfEAoW){qr`z=_@=C9513dj2WI!N#>Rlr*hfC0e!H=!Tz4B(4 z1chBQ#1+0+OaiQfQ+((Y-Wg&Da`-CEM`>z#X~&NMk{1~4%oDf^#yk*fHX$Kh0tUGx z)e#u-TnN8L9UOt>AnE@QigmNEIBsZ(8$E9A%lvbae@Ww4akr&XjX(K`2Zfl8^7~F%-761Ag3B`zz>-4g<-uf?)(Ru(Af~R0cR8e zE>@NceD!al*tN(<$S*Vaxj!m6&op8lj-J+6@8o&7?39IIGSaFuzpwUgB>VA?nSZ`S zyi{}d{jif>RHOmj3c|_`vn0(t&rUAw^tQ}W{MUyA{Or=PD2J~*Kbzn!20~)hFVslD zbK9x6U3wZV7x(JWWXk`rSr|uW#drHKZLrgJ;{f^j{@wdZPhpVk(_;~5Yb30B5&CL*jVU6T`wN0W9ItB(^J%M2BBU$4O zAeFxZK*p$7GQHK-+(43@8kicOhGJ) z=IiDs*v~ijf{RV3-%*1Jvj*p{EQewX35h;L`5Zn5h}_ts!%pZ$)XH}T5*o&SWXoS} zF$xnZoG#Or9?yN7lP&v*^Vyh|2SJF8XJZ+nY$^SjapNSyaU7G!P+By>Kepiz~d`ypxEiu9>115p<}o27Y*LNkSe#)v=_R zY-Wh~DF>{?GfJQbVcDbsoIwxcVJNN#g{Bz*#p7o;%>jO}rzgPcD}I_BGY7g*H=r8< zJS!J;5Ib`$4KU!YXOH;VA`?j@4h9qBJX7E@%LkYLiPsbevqOugqWl2ZD?8vfC!+gl z>@OM31R%xHvj*j-q*YtW{crVnQBuVy?O`vmsGIEcXUidL!CaC$&&{x|k4PlNLXfbbF*cxI{z-KL25&=)F-QfBo2Sujb*S}tq}v<-oUe>OA4 zje#G7eTp_LHUse7d_cdg8+yv>F(v?jCBOAT^uq;2JB``|0-Z zk-ad;gUSJXg%O}$VDzzN?jy&0J54E?)lQ?CnLkZc0=_dC;7Toa>Nujbrh4W=FSGbD zf8DwQcCy(?@fQ;=J8&zQaATyC+qy{aV zhfA^3LjQwjU!zj7-uMh#Vx)t|wfgPUx7gPQ)M7gZ50e8!Ey_{y3-lxS$T<=WulB)w zc?=X-o4;Pju7EPu$p8)-x(Djmo<}-`gdBjitKsHD6$1F|x&UgeqwQA49r6UU&)b8F zVG}wlS8isIXvgUeT<{8jDMH;Tn zVq#(tFqMchC>toNwEo`-A=Yv9;3Kr-eT+1=7NvJ3{{7!>D~Ic4ie{$6Za{A|0tC-Y z=C8e|*HHTkZ@l!pkDxV?#Dl&sV59dFP$1fSy=d;Xk$W4)gq=VE>muO|2bKnjTIRfUiEwKHp`Z5V+A!WTw%hwEdbzI4&%1nRYUE{+Mh zA3tAf1I%4~=La0Y68=c^f3tF5eC2Gh_poT($mZsi0Q`8bLh%**n}DL0ARY;3*T&d9arrzY5EddAwBTKkFSv@S$c0>$-B}B( z0C8CrK)9geQ~2EvGNUAc(@p8zVb~lPuCk??zUJcKx!h?`Io{~H*vHE~vx)pwzdj1S zDU@FysnMbnqy$DcUaCTXF>3~e3vXZ`Z*78X8S&>==qZ?CShrH$KT@y{C@nVMpDKXI z4dlClfKR@a7w_uxKJW?X`bL);JvL3;h2Y}VX(DTZQXHzixG4dq_Hr|Yon(G58czWwI$-F3|6y!ib;%Ah%oBuVK0Ph$eYfyLWu zIdq<_AF&b1+(}@ew42Rs9JCQ#8@1;{tuQ*6r$c> zMK~W{!`^YN{GuKO;13zV3K@4i%~MLx1oB>bHBewaZI_DXt1R}#@f&#G8ZU>LbbB-zqs^6HBK==a zDEH8w@x4ehU(5Bm<*hDDGVhhg*Xfi67__aST+Q3&H|cM0zST7yXK8M)wf;lMj)UP~ zf?+~rz|8%{cXB=0qL za6guutu|@XodapYIe9U2{@pojeob}bT zDv5omh1!4|4GdDdJPuvKs)be!<#5kYO%xOTRe$m%5OHyAC`96yC&6jJ2Lt|Vwvxz= zR9agg3hvINra{$g812$?c*%K6P8;O_I6sXY6VT7|IPNGHD7(7W6n_MIT6v6c;m@dA z$jb2JYLi5B{Lq6=4Eh!Sr_pEz7tQRre}@PSEV}R&hi;=iQ{znI3t?~CE@sgv#M+EaCjj)pC{`?xQ5UKC$9agXq$x7E7X+Qe(YKhRi#ik*7g} zLJJY#{KBHiu5hib9QcW)?*8QNxur(4AjZQLDG#U}c}h}A{|%Q{tPr{K&~U)w)dr|? z5d%0;uk~PyVB0|xJNAuEA;-GM2zcMx8F4%FJqvag(OddKfCyJI((9z+m;r2B99P>A znPM4Mo6oj~^T6%eV}~^qDZ#+#nl-h;s|ExGg0?HZ2V)@fMIyfvyQ^gc8NY-#82Y6R z0w{%O>zuo}4X@YhCeJ0dr_Og`h>90zv;2kE*z;v+rgx_j{NFsvV8?WtgJK7qBcoow z$OUWC_aJPspR`W0zYmeFQ$=-EWt&bd^aFaA_hS8{*|G}S z$JI7K@N!6Nf8!9yn+5PF(p=U}~AZ4ZI`wq=LfCvDl9u!e%1T;tU*pxDLoMGgG)Ze8yx7Y6}V);9x20!nak0iMMY=M282G zf&b33|6^a`+KrdC!yo~hHaZUgr;dULzhPG8e75zDS+|A*3=HI)PjcidiUfdwLm1_* z63iVIw3qN(j&l_aYrN(O_GaqBTn*@iP+myy1>o4!>(2xbWwFta`}J68Wq!baU-E&6#+=5j*0$QWZ^;tJTZkFTpr~8lwMD(MDT1l`! zs6B&WIab?;`2IBVcxmDOnU;S#=&CR!-g1|xQOO3GsM+sazl(Nr}^iOlEZrw2>D z$vMz&$g5|Es{%sA?p0$q&cLg^<+2e?15d^Dcj?mP^$l206_1VeqgN4Iy=^R;h~*7# z>vg_v%_D%uw)5}{w?OGh(_}u!cQw@L<#=(@I8%VDvTCNPdQ9F4Hnr#VA6Lp*pA`;w zmjT%mhrhS${Cjhm0?=O9v@f18KI?4!FtvGf*=$(3=nuI?m!^ZM3NCQMAd8;&ehh2+ zE||0@#FAl_{c$40jvMtQB+wGVDsHBjo)y5rPJ28g*+?=xoVr4XNxj6hC%jkBK^pdDpiZOHxzTL9-q1xGmwbZ zQb0ZqLtB(F2*ioh4*j9>!PvL}NI@KL&n;$g_`d^j!)fn=P_G&k=b8l4%_W3jBug?M2Q%ZC81#oaS4{%KXsCz8++{;Lo$agMcoiz$z#|UkD_c&k_ot#egPY&JqLq zAIc}pm$Y9$s5(I5N0LhmP&Cw3Ou(Z*Ej%DqSzHz)Kj5!+-AEbX;t8mnE!_@jW2Y@d z?<~2Y)HXd>(*eB2eCchwV7&R)W4!<1Ppsu;&t88=6<5t8QD?>bl408Bmn{6v=Wta7 z<%hAuW?de9X|J5)=Bhr45e}tiQ&u15eCSlDLkQOKnWJqnhiBHVV;#ibR|j^e$AZJ3!bGt)cYwyXdk#vUdrk~W5uqmRZ+~Cxiu|yF_J}%-B|JZ>eT_2k1zVG@4rXHk zk)7>pGZ+?CIu`tq&+K!m_^~ zz`}umZZ(-xdMrq=``kXlc0rySkriFlr@T5)lgge%q=uD+*hknbW((=ne{f(jvch9E zvci}CJk(GWEu^vr8^Y3115A4g(5NO~Qarv^IqWzh7|8T{+7tgDqe8)OMi0+HyWSm< zO{X!bP($f@#q?oLeWJuz!E$-m?e;#x#{4W7gGQ?U*Rk~hJJr%O3Qy~;J}H;jpCH+6 z0z+5BCw=0Ch2KsdxAvF**LGGAW;vg90XEnI1~=+SN{Z@#!?l$HP@Ugca+JUwC+`5E z@npV=q`zdRF_wOytEx62E66jQ#=asoTnoo%*#S-kjyDeD)-xSw;H0J5W4yI6W*jCdx^QZkU=(BDxw=VAf)U><+c4hKkEu*xt&A_lFPBoPJc zYE}EtA0ROX!;){&m}LRiI(ht>MK2Bj<%I<3sNcmp0;XPO?mOuvE+Z|p)2_C&QFCyw zRAy~af~7TbU}*^(>`JMpCRPZ*F&b3t$uFcwgv|?k!e7>_UcIEC`SkTpN9a}*H-EXG z<|*^p-S!bTq{*ZPUE%Tbu*$63N!y*{oaRJ<)dIYcR3hF$e471sFM~t~?y%kCy(rJk zy4?h111W{>6uu5su2iFmDD`gJM$ql?V;26Jk*iWN&h(=y)ozSQ(GTBo8u>G4LrASvu;qldFvzko5agdsy8|0XMf;nv&*j2Uh!fT=>y5qx;7!}Dde$EY%V zjxD+GY*Qh9AKr+0ULES)@J{7KLbZ-bXBf|RD!lHTYefdaMrb`@rf&MmMO-5VNH6__ zTVAxqi%$d4NB*T`r_ku2<{j^u&``@UkXYb6Z;QpE2$Fx3QY7pOPqcQ0ILUA4MIq?; zW{a);iVR~}mJ^0=8A^q{O4c!zu>r0s)GX?4C%0kH4sw3>eYG{))3f#!X$%`n;VtC5 zq!Q{}Mk;rBH&SdTx_<%too$-!+N#R@ld0! z{g~x5MKJ%@P$3kWIw_#zBDK9-pi34;|Mi6+%4)o9-Y3`ThqRV`Eh?n?y*3Kh73FJ6 z$}gUK8+L`dd~GFK|4|HT5rSd92smu!lGkI_ljT9Atdqu%TTalwrnYh1pf>uuWSGkJow)L!18|`6a5aFfHyh z+%e4DNEtvEDon`tBS8N;-9pG1kJn5W=jy`D-U&NaZFwi#j)6Lr z3JUhb@wF~Q>T-}nRg54b+c7tcx;T_B`jVPWj8zB^pQ@i@^kEm42q=h@gB!d+8bzh| zgZsEfOXo#{VJlpEka)f3FhAP>-t$gi%xGrasU7(&*iUQ61d!%WIs=cXFw5LlS67o? zA~jH~wUX*j8@bwW_&j>PTW=}y*co~CH4UAZtLKX84fPrZAZuZ$4+_)6ORf*evT$?^ z$ZT*(t;Pl^Oz-s>h4K#Ib-vRllvaF(;T2Wq$ux%sG3CZ4u|KZ;iyIo``Y-1`D$JlKhuXLX)8h-*#b!0$;0G%ryw|d zn1#=e;X-}Z2Zfi8>jRR%7l9ZjF8+*ajOcPe&kHP9{W%lH#qg+Cp!$<``nA~*nSV8H zTNN1we}ZorU}}9^xd6~3*E#Bv-AFo{1tQFs7}BxXh~ZDkPCFxhAfvBre{1%W$7mfz zXM3UBSSK$aIANHNgK(NazN6QYzG+83>oYVqxx1rbv+H&yqaMy4i=TRcv6HeSoZEc+wLdg`|z+QBW=cp;2BIA%d#^w zdJFLt^3{KQ;S$YcF}(KgF{)AA;L!c$jHX`tUReC;9qE+nw)0^A=MZ+Dzs(Nje=++D zJQDdPvRw>rZPz9cK4U&PMO&(~O9PrmmR$OirrL8!Q>s8Zg9clDxL(Dq6?swYkHYQ) z2*Rg!l>cBFA*jDuH%=D@jM#T>Ge!5K#w&=MK9jmn{O}H@IbvA{Q0FTsiSc5gVI2S~ z&iExC`Bx71D_CbO>)6z?^1PBQwS@Yv;u3#0(0#F$CpgnH#82snWMBhfM29?Dhsz&x zrckxeutNJ9`o@L3TT{Cu!op%ay3OjBP2BA@jyb?kqivetrT$ys@hgXQ`nPw+{T6st zHQNA)Cw|p7AAJr$cYWWaH|9{3f%Gr~$>!H*QWU6;)Nz06orYX>1#H)Jk*1P0aP-5p zKdx3Tg8KW(Na+GZ&6%9@140xjp(aGEL_kABW~dG70MvtIlceoSy@w!jGDYvUfB*%3 z4*f^a(0}>=o&OU`L-|gskWM8=_*6X$$EFV2Hem;|o+d5bNA$(9C@J{Nn7oPka>+(I znlLCD9=&R|vlriA`IMjkC56espLZaIGf3a(Gl%f>Z?<>%wU2n_q0HS;QdOH)(;rMI zIvQ?JYe3bNd_0rc zLTAg1f0%Fvl=@22Az#WwMIvDWi+9em)WpES z1Ug?AdzQGm3tmdUng%`!FU4tpSRtl35Uma32Z6?KtSL&{JJY z95x$hkicBxRAo|ddp2e>`eaVKv>LCU>70wD3N6B+@WhrGoje3A&nOJCl zel?Jx``h8;aE_+IO=8N?Z16kXVDk0H42SuTIILhA6U7WErC(hu74?qy$?NhyXKK7I zOWY(X6+%CG@WI?wTK0Sh(sH5SH4U9kGVr-cvPK#1Ohm#Yj89H)Yy7OkkM^>Cs;%gR zKpoFvb0{{^`R{#{V(Ke)$=q#LUG^jB;7}6jN-ed}losamXd$^1!BXf?a^DP`gh*Z} z6(Gy!CiaQvUzxtb4;md3T4AAOn7`4>82Ug^ux1)UDBw!gW;~?VBvBc3)#?iizkwm9 z`ginsE&l4yyn%r71x*95c&xGb6xbf>ZET_Xi9oUaQP|Zo95LOCyA=Wr5txrLSqBvI&eBAS0FoNW(eJ$O9j#I>!$JQ#Qui1J#~Uv8V^DWzuoI%<}#cX?DKWKVhF zituNDBwl}ypHW1903>@hPQNb0%-d8TL?Lnu_~^--xW^w^#8XDp_HA|YdTPgx$F`?= z@T$L;(nZF`NAb1VwOmJ~ zOSwBqane`We93HkiErDAU@4wkO5|1@68?o1j6v(2<=_`Wd-38$EExf{y8J8tB}T)j z@MJuQ`jYjb{7tXHNpqI}@17s`{{T>&?W){|qhOMn>U2QZrzQg*m7jyvS|2cC~+oDdu`r z%k4@5wI7r-5B&xB0Br5~@j~Ipr5=C)xFEp|akQSuk3q1LA)QhO21VCvoL|=A?cprx z5#PZwDU%Z#ErjP$!BAyT7fMKe%{d6b6p5z5d2gK@xm2Ijt%in9e&xGw3Dl!wKPKa= z^OLTuI;)bH$in?H@yn=|i)WDykqxUnuB>ZU#F+j=^jU_Ao|W14=;d$o5`h^lT?T&~ zk%h$Z$RR)!?b$#jLWiex5(JiUP~TQ^0C+^(MtB?@;RG*J6yP5x^*rgg+&>ml38SF} z6XtGO@%3})@D1a=a=ZUt{7kP%(F;&CQq2PFZ2s@Ig^t8R-~^qK-UMh)vc(Ly=>+rN zFdq0~nYsk?p93v;EcM_}nggmY!nIlh5w^Tuv$vN!@V8&Ycn74NSSW#IwLuZqNcNU6 ze}Vdy&VgA_Q`VUfc!2OM3{Xwyyq`BcUB3q`IP_tL$v_zif^)&;Vqd0_98znU~{`b!tmk3Qq>bl<562T#4dOJ>$wBTu;_{ zNfLxXII3@lnE~h|4Dvsf3Vlu(7uKmDV-l<0h`E;N+-$z}{cVVEAV@0t(4|@Mi0# zKg53lP6glGyo^9W{#z`J!p7Bgl>akHA_LmPKQ=b#rQ}^BULFFYxdfj5jCI#1$i0s z0dZPrkJrwwe%yCnx)PExB!1oI(ea# zUK+x10ybuxJ%i|NZlI#`mu=8!-)E7CS;a;k$CW?$euqWz73>!zT}!?Cu{6I-{mtTe zC_Vr@YIIX;_Cpi40639-wieJUYpb3`>W7JC(2Uq8Doi=n(r- z4YS7o+ zj~a+8k9hUXjG&UfJ5P{vZW;%J?iK>OdrowUzGg&)u7Y^1Isp8K_A;FhW~dDUF1AD< z!YW)q%1M%$Rn-OcMX3M11S|-a`OCik$E@H6>)$=sz<=p@=m&?9f1ujX&DF6@OIv7Y zsMO8HG4}#OW)^D(F-(TTo6;gvW(O+Pem$pU06zCu!QQ_jSs_79XOtU>NA0s|2A+do zrMjDXZbFU$S|{Z5J3mm$=d_pMB>qQyZMjUK5jCvX0wDDYYkGz*LdT~=OTnWaFUxJ(HAz>Z`M=MZ-gp)D(de$X*{U?TM=KuifF3w)1( zID5Rb4miobi_%d00hmW8CaDFuN9)4ERi&M=m;c;$lD(kK5KwMMjenB`w6bQG zKmv#Z4W1TCZ>Ix5h$QjWl7gao@&Iz(=sTpnikhH4o##h zDkLgskt~+g=5Cj8$&*z8hotss%}j>5wv2!dQIGys^cRI8QD~5&Z8UiKG5Yc4 zKU3NYLTGO9bBIs_uV0Gp1U8p9ZVUhtOBbui$e9yf3BdfX8ch`NmNnDLkFZgc;b<)x|^X(Sf4)1vXXZ zFwA8}7)v?QAgJ9`e$6fh<6R>^tTZCOR4GPU9XzHFlBK2MlxU7-rPvNQTIas}K&K22 z!Ntjyr*!y~_GEsW!>dlf@x8gOdY={j)Sa>rViZVK_sq zD?CMO2^=wS0fI_il=v0=&=X*F_k)!OG(o4Eu>!Z>D!?E`4aC3T1YsHLeaE!v!pD>n zd*d4dtfFXN(;I#S(7%bkOd|}s0}U$?KlM4YtI@6$Br0+y?IBH_9czH)B|DaOs)WT8NiTZRI zghKRjO!$@gMmAhKJGo8lEccSqJZ;@mtL)~1!?2Q$S1FAd?7xrS{V!kmV2jF%j}r76 zhS4M(tQ;K=$cFicg~@?AfI_H&K?r%pcPJ6Yg;GI@8UUzZTGiS3~nsc5!2CykbE_D9`A@}(}FnF+sKn;W>SB&9>ex&Xn{ zzu5;tAyyH=!S(LjDzQ0`X!IzgFkUhwyzu=t{7Yrxk(M`Z)>kAu4z_1Y`oU-p%ZU^T zJ^MZDQ}u98XLy9s_osCOtuI6bM5S84B*3gcX1wHwbzQH1dPUovR?iObZv@mu3cXLD^q1)XV03v|IjtsOk{OI3lep zYCK?4eEsub{e7v^PvS(96j-#sfdjlIcAlfO2xx%iuN^5j$ud|}X3LEN)UiRTh-Km+ z-V!wWT7Z2Ln)3nNE@vgGrAz@udJL2%IdZD^PB44cwVMR{APXyvHuyusD<3HKEOfQt zAW$d}9A5pFmV;&h(xO|twh z8C(3qcp+d&)cGE<;xm1%q=2CoheHMj8814=28j^h#*m5xNHAhTT%P61+c0DKy8M5hXgiW-8S5Nee=oU8>W(b)w z<}V0)ViLG||IO+Ii)v?8pX;?NZhS_m!Jkjs8Jgk^?hSiV-eu7o7?a-Ogh=RU?g*z( z*UyP^hqnsg+8J{EQeK8h;?h}~k|t3d^_|A~uAVTY&>s0za(Kzu@(Q56`uCCg12$vK zI|3i1DE@2UIdGVxbq2=`aNS?-&cAOfzoUhZ8$g(H zxm`j-Z}iH>^mJMFx{w6KaRxhuxy@((XoKy~dA*_uhrQOl&kn@9C?o$q&v+v4efWH^9$Zwg2 zLy>l(6A(=q2blS*_}8eo3zA1=`b zYK-l3zaUbdbQds~-#5(+LE{JycD3$ULJeJ=E>L4&(s9<*gu4y5a%^z79d8?2+F(2J zrS6vU(jIBS!lyr6sjTHFK>L*rPQ?agJio#Lk_<~la~5x~K#uINki7^?wBQ>QkicSs&rK23Mjo|BKE@C>~>ij={? z^CYN*!1NV0OWPk7OC2r?51a;Fux0Dwdtu_h;`O%*^B!r$Cl0U z-_z_dgYL190kOp<*T<`Vv(D{s?ID!jT3S3e+{D>L8HZ9F&&y+3IfTLkq-JqoZ94Ee z@Z|}EC(srYAX<+4PLt}VAYq(NFGKmId@ZISS!th{ryVFB??DZ4 zX(J&B^Bkr57zAj)H@z*XULq;fq5VShsSBXemYI;aHN;@na#&SftEtLN!TT^pP}f># z8vP+WB!z~Hst{i8PY)N~W)pP%@Td;PGfGi54`$0pmE+0X8v;hU`oJIx2iywF&|87u zu8TZ_1GYVqJFQGy8kWer$=pxq-jMQU?JVeY9a9vUeUMO3*TA~*@0Zjmx+}*<$utr{ zt%Q;rae74}7Wl&>rfv!s|46Tg&sJ3>I!`Q^7e_BB71QYzn)O*XzY4xDO!rD#aB_Kh zHvh9jF=4UBsByMAWZ>@8m*V%e636-P z(JP@}A>=WS;u~2_WNm>*eD~vrAPoG7?2|Sm`}c9Z=D0?ehB57!#;5k}hU*`QrOSWG zc3RpnkjZ4clC~_8_V>s*2C7gZAc(ynicmPtJxM?GCqFQiMeFo64k~FlA5)mBssz;1 zOC!`ESI5A?6%i@tJAZ`Wd;z)dofn&JXfG?DUWSJ$zKL@N7|#3&?7_EUTJ4>08MQsa z!L<5#6ouHhobt8cU;sW_oX&&|h~J-*AmAU(8SP2`0~Wu?YqQrJWUsfRcSmw-Z!ntQ z6+%irP9Y=p-n*suH8;;QPAZD3>3f{%Rg}(+lR*4dAK;%Ue64>iHyE+kQ_E}F$Hq3- z1A;!OFkaSWE4A=F+jQ`{TEmXIaIa z1KE{4a4yndPt5)*pxCA4{?cszJSwNC_y39pAGQ@=qvXFBLQrR|AQ^FOpBvqH=9A}9 zueng+o8h*R&MMIpH>5aG$6?Ve2#=#o7{E9={WHC9S2K0i<0w0AbGtBip{s#KN(FfE#(=kl#ew@8_(lO4SSpp!8s5Q zK!qtd&(b8uk@LDM5Z$LUNr_3S{1@&_QD75qw#F`d@vF-a_gW_$(JM^>em_c3l>fei zGtK8ta%ZF9cv}@!lQbrSH*k9#WEIYQ5t`Rm6T0=3IA~5dH zTRLn~A+1gTN%Ow7s86LF$&y;H3nC$xt|y>~2L0No2tpFy=VbM#OulyBgnhx;@CWw! zJ^3&F+{?g1cS*!toJ}72S@Yan5rKlP@t?ehOo z)qKe3M59vk!`9}2=IqThdDI7{rq z-el1-bm{8to~i1~x3eJ;BRYcvl|@9QwRd*I#TLTusF`nN6Wf+WPRsF%>d(z8{@mWt zZi;jV#)rc{&s};Kg>Sd+( z4$^1WjNwME>rC&ll|Czz8Hem|PVHVttSjIXJqo=k2ixH*+dA>F2oTWytV77`-?U|~ zeTl4N!#8}>*&Fw|7cY21d|sP23vOd8FH91-;}FT|aR^H^EXa`NRj@l8Q0-|WlOy6ec!(n9o`ABcF?ol6G;bBc3AHFxouEwB^ZVm)p7 z>^VN*x!g#^AWdeHWy9#A*3rTT3-K5!TCBcz=%q`Xp}d0O8Y+A7RcP#y$^gh$8VPWI zL|KKyNy5;`8|qs5+332wlD!cPqxAjkD;1|f>3QrokS09uFQHHSZf!wkGJXg4Ef#dy z(B?o%9-l~eNqyhpss$njGY$h2&(D?;N4Pn2?c=vwqv)DU$M4OPfHyjM#8z5S{oeM7wcPREAiY02s=?t3G4fUY|1EwSipFu{^{`A0{xngUmz};{_aY zF7SpKOOrK1yGwVP(uU*7(RCQ)MQKk6Ea6|AXX4258Zg!Ty$naYBYDvmpm)epnq%$P zhKz3aBz#fXOlflMA-d5^m~&1Y(pTP18RJpEXrUK;w6oxqH`w h>5=>Nfl23vb%G zHhK9v$e+A^fhD!>vS-%2KVf;}yZy&h=N+TdllwB4IsymGhO9?K`;Hj=jbBFXn}gE^ z@!&+7J5&;0YHK_wR#S?uveM`sA08SDT)=OaCBGwiA zc0_#sR5%@pDZw|7bxGBZQ-M$B=Asck_{Ma1;;Y(s-^}Jj7%8d{f8jDTj$SH22lzB; z$(VshlvM~%1yiR?0{2=Af|CG~kJPd@Hwjb;)G>I|G+e*o&$kDEnCbBsz`r3VLx63E z%)bITCq=henCFP5#J}MEc#Zrr>7%H}h2_l;QIv!);xN=;l`jZO%P76CGlTqRq|j`i zNB=)GU4>th@7LZKqee-L(I5>YC8fJ11OW+Yq)QrMfRvB_4}XBj{oMCC=Q>yPo=EhuP%@}E8FlJ{;C@lizRo9;L-bw5h#1qm3G?IO`qO^V zdxc?Jb!TSp(23`-*ct4zn;9P{Nf?3!JwC5Wz1a>*yQF-)AAk{n%P2Sd437`duvi*? z6%#SLC>54OuJ16pJePN{{Ai;yqSeMsShmwQ{zPIQRxl9>Kl59_ea z;$kwCfFa`0!!%4_$N>)xmav@SXAj(lBmd8H&M);ARC@P`_vofN{% zWo>EuhQ3(I`i-DD8YS~vc|jZc_3<*;%4qu|Rk-j$Fg&xhCW9a}t~B7ckG2IkZ%98Q zs0a-(9cxT~U%~3-n#jmn5*3A=xym=?E`e#hn)2EH0tKr%f;XZdl%x9VvaZJWi~y5J zZAMN$Owj`1r9B+rdII%Xi4)l^l#ttbXJmC#)O|wmYu%Rx2k~xNX?ffk2yl2W98V=Q z(3x9_b_0S{;hj+OBwZHWV91*GjeX(0P0*Of&JmmB(h}^K(K7uqYq?sVFFLWCv&`kF zfdI7rQUy3z-+;#N%N~95d}N6r{ffHMeXxBkfx$NW{>Q~{-TT}OtxBKG+O`R28{9J! zo+7CAe^&GEZcC8i8{@R-6v#ovN61=no*S^jM;P_$E65~a`_w$iB>R|gGOXcHT!&}E zkS-;Ht^R;LjW-w1KBdVM&FH_JJzQ53SgJFy?#ba@MXUss^oL0sACF9sSM|2G$b~BXGQqA?>bq@djuR|OM8M1F^FJ1if^e?r3jSFvYw7#&S zEsVA3Kzuga#8#`Sd^ZZuXW>QBYsWwln`zdgIx_?9rBE-%fhu=wwF&ImMV!*T1h&$O z5v0oXP5#Sk_HG*&ZP2z$&TX;*C{qYNKF~Vc_!JD zs1lw>cgaM@YD5Y1g5ZD z=-~o}2{wlW@nCn-Fj|{D!u5-^GN-|Z=9mlWami;=StkX!p%JdZ=JnDSdpjFJ zmsR6!`^cuLQY?CesCBx(AVl(PT1v8|KQZ!ZFy$<^>^rlO``7)85YsTvRrVDN#i*0e)d=aaLtgPD5;~UL4W$G_N5Tmr?Mhsm@ z;P1YVs(pidSbcvYSKAi-E^->YuabK{s+IX z>#bRtewq2M*VRDb=U-EM%iylO;9J#r@#SX|Ul9h+_b$U1E>q*VnF6xU2R-4)WCNvy zl$obOQyiJE=`yY!Mr*Op1gfANS2NX28l-a*#P31fk5e;@gVr?fhckN1zC>tQ z^tB`38TuCa9#FK~E#y0WLsnDPu-A`-{mDq<1VD!v%A;BmGOLt)zpVGzgryQjW68ce z{U-EL?|Yht!iYw+OuWS+-SXBfj>E+I%uf0i+ z2aOLT%0`|87rr5-XgtIIDeG9SRita|4k1d@1P+ZCo?y3*Al}hA&b@2i4 z%oIO9#rveEXT7TsgutWYd&C;L5WF3W0MG=W5zG~AdJ^>Q&kMSQSNySgw@MlORuOSG zh&pp)5;<+qLaBT5*Oe1GNXh2b=PxeO%O)1>Ez5VEcNS19@#~F)Kwb2~lgRg($o>?A z9<6?z>zjk#y|H>5Qa`Is(WZto$k;nmwiZnZ^FE)Qnc4eA&jMv1`fPFd%zJ4)djA$7 zpyKbn$E@jM&vJt;=|Uf+|JlE_2_Vpai=*M%m}nez8NB&))@Ew`y9ly&nVmI|iY zxM0@ozgM2p5@_0v%o)x*Mwa{Yz!~xfl(4c&=}jZ+AnTxR-VEsl&ZE%HV{fo%uVqrB z0$MQcq_^|cSDKys_4#KXj08yChJc0IB;uw2157m%W6n1oga%xeuff?U2jr-`WETNX zA1!6cD`}Ua(v;qv|K|eK$9+Zax*!FNj%%WNgvp#CUKsc{?yV$XdH6Tv#0P_|gHv3? zzU7k$Y8MY6#xh~8C5ukHnS8s-X05Uwh?So&I^oEmCIO-X#X3@&BaJZ17|elruCP>I zvA^z~!Ltz^x=?mLOpof{n7$Z6U|;5!I_7;<(aA!d>l!cxu?9DhN5}clwLgHrr<3Kq z3U!GW%THkpW7sUmM|Y52{jvqI%O`8Y^=TsX%G=Nz)JGE-IJ7o-i!HjUQ5r<9<9|qb zg5d(ryp7}s$zN*aMJ4z7?kC3aFHwCHlF0p4p&^kR^;J0V+-*j1cAIjg6bfZK9V7W! zl6n3H0OI?n^2E?NZg-D7gAf46A)FenK@l{RUl(W_gzWUqA8^qd9x_}wjVK?^^$-Y0 zEH*~(t$`@}5QUoN&M7n_ng)&-lQ;z*vKT9XpS$fWL(Q2G4;>JvE4~s0EmylO$vs;~*$O`y zO7Y2$!OZU8e-=XyhJ3$Co=tw0?!`WQ)Bh&CSURkhl{^|-fK4-tc^rzfSVD|vL+@wcOh2MClL*%^ZdI@{c?SdS57O+#-NEuJ*2yecv;wYUAFY~pQ zO~@@As!@0^XK3EnDsR*s2zBE7tIcmO(JTS@qnD`>3@lVybmbTpQvO5-I%r6kXJ|$8 z3Pv8-QS%5Ad{dMMN4%N?LXTSYYr)77zqWjHeY`^Ck<(ut z=su@jtUn{}eJPoPgV6n!#{H!q)h=nX9{Z;{a7s5@Wo?#9sKn|Q-MWPtaw;or4GT%Q z{mU4hVdZ-6otq+ljq~C0myp`_n@2||m%rm|DKkI*YXju($`Ktt=B_)CREMv3a3D{6 z_Hee#_aZseH@mC8R9HLvc}}~+@K4cjGxGa<1a7!dKhDjgEr}d*|^Lh-PPg+J6H(biozqzR)Ndxf_3tsXq z#T259Jqxe|B0uhtg z*;l8Byt20*xJ)Y+_|BmoL%o;>m)@#?A1=SnVTZq8sA#-7+K(@+Vs;Pl`FC%;V2#NB zj(Q-@@SPN%i`M@yFJBm=!Cfzm$H%b|0YLuZ3MWR0$-L;R>qUd8$cNemh}Ru6wI(e)%$`(DY_sqYH1q{Mq7TMioSEupCtd#oIoMe3mz=8Y0~q6w^!zR& z05PQmbhiLb;hy;bBnN}@$bRj?<#)gvzD8h@3r#TK$$wE7*s*h09AXddxVguml6xGP zZkvKto8-p$RxM#AU*otTQq-nfVklW7d8VPCNcu0Uh*@x)yM7+i--|!u7khtW@lL*d zDW6U*hQQ#+#HT%kycyo3XD`U4`K;r?IDQ4Y<4&_67qcOe(+>SH;6EBGvsBgv?s8jE zgj+42FZt)N8+$fR_7=n+V4cOuO=z)z!h5%p2~{OZzu9Qkh?y&oY5Vs^ zeE8cM2GpqF?kNmn5>J8#tMGm^l~M;CXWn|Yel1RZKp2`X9xq@2WaPcbys!KnUaFr@ zWpEgRO;=eD*uNCT?L=fV;bK02;QmV`tt*E?6*9n@{}2@#E)H|WyOFDtZerH%=z<}I zwn0A$03n}Q2bgkE)S0k356rl{SMu@oWf?k|6xLwKxMXQrlMd`_h^p)v+4eCq2vbdYr88P zZ3I3az~(CEK?GxY*pZVZYCwuhA_#?gfKF}xUTCSk#+YX>K*qWB7X{77f{D~Wrm&TE z!T?pGM}1$&P{ENtv+l~BJQ(+JgS3Q|8Dbl>v3uhvx^SOkA_@uh&C1ktJD4glGgPjk z^nV*zvtmTZ+=n~QLrG6aTJDk@LMpYbXp#cIx-wlxak-fx(e+vGl2@VXYsZhd2BiP$ z3|XtwGX9#H zBxl?+W(9-ewt8?jet zdwwU9A={IAblN))kfI2IXEl`n9v=;msRs>|A=5V~^QZ0g}0??9d9*m7iZ$h88 z1B)>DZwxZA1Z)B->#gTM%Tl3DAh(p{DIEMJEQ!-eEAh;rL()2_@Gav0l55U01>v=a;c{7W zzW3-V{yqBIf=FU=1f1YwquIm%(GQqwfC;o8nbLWN2E!H6VCh!1g63B(AZe6nqYH+r zAd^5o!BMdnkylrGXY-Ioapr6US#<)8TW<(zfN$5}+l3HF^@j6fMg4;Y9fkF~Sc{DFNq zJRgk9`{mjLh7T^5ab&2#kk?;!$A|v`SYZycT~#>Bxsl7!E9Q21YD#2r$iAudR0FfB zN-{p&{Bg1E@UAkxVrP^a9zQp*xX&%JJr+?2VZ6a0*7aQkT|b^wzAB~uwL9bb#T3Y2 zV!y+fbGKsaY%f^diAS>>F?M^KCA}~{qa5(?yC$W7IvxB;Jrp40$4XJn45^JF;X7vK0H+o5#Nxea!XlOn3E*HUdpP>hZ8fMv z9y`C_9}1}01z>>iICt;1|Cj(O4R`o%gQDh3H1{k9@HhP}0gXV*%?d?Fck{dZV6uV@ z*~>DHdKobVK!JvWpn=JRuQ1p>_I(M0Txr?Lr*rkY{T#VH#-=j7QHCH039Hk)7^qvtDhAB~dix6Th%KHY$G0KG@` zW@D?{k$MUXWi}vOe-74u>|1J-6#Y2O0ZY#*dYaHTqD2f(%#vKdg)J|z8u~5;`1hyy zb<9=p<<|+JrBO*K2Lz!%WZ=`E`SG)b9Bt1a=fJfV#6}!Sswt3tK3G14+Ne%^8^4*7 z-o?XjW6%v@+!UPN!HyUYd08dmM$FLvw+hTZB1!?u*;WU#Sj+6AEi%$e@==T%IU*sD z0Y|-pA?exaqnf+&TK-3kLNDCy05of4fBI+PgubFge|*uCcqB|d*=vdL(g)U2 zh42e&3AjB&x3iZ?9OB>ErHXx;lE*7s9d^R~jG78U zyAVG3;=J4kfK-$*eDsp~J>QT|atq|Y2iiIuDgZ;cJP_u7E8bG3{%qG_%FC7a8vMGH z`aVqAoGKqjyQ?#oBIYsNPL@;X6W2X^Ca zsq-sJUT^e&(wO6+-dACZ2`_*x0IJv9@oi+3y?C$PJ=kK5fp%KKtvWndXGZ2rm?Z+} z!;tGCm^2WTC@v27)nyx{p7|gsJ{;sjDSQo#=>O80@do+y} z1vBdufw0LV3X36clSIS31@;h-cv)ljT$W6bH_Hh9zC5WbGi?enHL%#7FMBTThPfC* ztIK_y3t;>LxJOnd9SnJXbHQOK#+gd#6VQlZZ4tY*8R*1)5C*}gl#WyGYl{4&!-(OE zdNIlV1y#@~T_K5LS;ugTI$R7Rnij(xQaC^hqhBy^96iVep6FgWGP>ANJH52h8U#Jm zW)i~J=hrP3exHQBOBf|FB7KU@3bF0Of28EqlXZ!Ef$l<}81pll!gcj(^plBIk{`Lp zEzyA1f6#5((WsboNnl8k-hveGTZO6R0Pp%a`wx{yNQx56;K9Y)6$qxz7>2x`FJ?LO zJC-w<5s{R26Gv1p+UB(2Q?1xrT3t!yqHTi|6r(4O_Qy@RiXWwOfME#ZQL>!3{rHFl z%#$#x9JjZSRSh?QrXjaRMyCNN(TXpz8gIq_6>aPHci+Ujj-DoPgsir9vLndb5MTGj zcLF!_kbWX}^H7oB5)AlJ`7uhazfdtqhN;L5zbq2~b6v>{Ijx#hc$1`&s+7AES7=_L zQ#`5^A33f5fI*qRu2U|~sI;QK@fGJ#QJ&0$&v^HLBTApU4FfNpbqKXyDbeq;-G=74 zdPV0?m1$K=;_z=eWOpA27&-3u1_;opAMdXUt$w;}sYIhNZq}+z$Nvah)d+S@6OI_NdU9uRDg@ZAPAuG5dRBul6oPH65g&{^EMNuZs zmmgU)6rzW+NVz0+9?W4Gl@@;7VCMC}R(ia4laQVWA&{VrQ|P}M2&EA)5EA!6001C} z_f7;8E}3p9q0a=H{L&wItzHHjfkke+)?NjrTQ3AvP>6msZCZ6PLp+kg}u2pn|NU!62HNc}hQD5HuH z@AJLSbfA(5j-~c)$&7&Tf2ICUos14N!non~*R1-i5KCK4|IhXR7$RbDb`LjWt>Rvb6y_jGPUB|xv`ed6!?c?JLAP1W-Z$EoFed#*2=d0WyGo5 z3DJ1You3Get48BC;)gfm$oL^#XHh<-$-V^=x?UyH^~_!ZN+3dWftM^z(34*x z+RF{J==2+HRttJsws?YKnbc@;<|88UH-T(sSexwW1ptLiXZlZloDs?qk5df~lzq`L zE5Fu5qs|iXlx)UU4qv`P$VAz8D8m8_8`TbB6qe0Y(-H0U+t8eUH6y;kLljg=$w#*s zR;HKC4Lx>OZ!i;Apj?=BGS)*e4tVY+4DqUsGqd>99T|hs z>Wsny{AykB+2tmR=LnePJV|FaIRJEp92@7eV{{E?e@PE$nP*Ip7P^0f*&r^w&T>vSKD23tY*OGE@0cclvs=v_QC{5D5fg@y#YbrGS!)E z@T|%y6O*0x6E*mLv*hcy48++gric?HmJ*;P80W+Z12N%|i8;jN{I{@qfrhC zp17&>dc8S5-m9--VrUd{@?ZWvkEE1!M{4*W=)V3kdex2QHU>h)0;<3 z{M`I^ix&Z<4jf?kM#0kLc;UuKG9$r53>t8UAzzgWe(0kQu@RxF!>k #g#?4SMj zrQRCz!{pIg62DmDv1vL_xHBCEdVA&wy&zZY>^9%Q3NqY9c*VQ6_u)qvXPwwB`}oA0)zl_bog3X{T(iTMEe%ade3U+_d)6Pv~t1(h0tq$D!e9PD;=&Nwn{7glCl z9R-hIPrsc3xa2O}8Go-lU6S|19C3e1FFxS80)2eZ_R#%s^Vcu=B|88q zgQOW+%W!eoPyu55dn4j|wYwcA4UI~mqe`w#Mbr{N{LS+G)H_TGZ8W%t!?zj)0qK=6 z)ywnuA>1VyEbwFutnT|;!966`0v1`yoGLu=#O&#LF7WWdkJ(F9UxyWbhp|V8^xh;y zax%98ZTH@YYENVU6VW>RD=ff`pJRw%_dr6XSRpPLhlW{+D?9)Po#gxa-;Q844*L3O z+Unij_mS8V4io3OenrzRtKV_-#t(zNX{l|8N%1UOn5e%kL=IlW2Vz9a+&VI_(`9jbtOZ~Zix!&$D3Jp z7`z|xHIj8M-(_1y+>n7wM)OHt(C0;xY)|}Kr8u0N9~mC9URAlQP~6M62=_*_4@sR{ zO7YW#?9p+5Vj6&)m@cl*tz*LAM(WS`=kjxJ@be?;sQJkFKAe0|7ul1st1eikQytSUljK1gYKnr8PwMoOVL6$e>zPz=6xL$psjCn+CW*5IW{@N@DP@M1d^!3 zG;I77;CIKvzo2WxvR=8ik2?Tw3$*$HY`==#kB(knQ%?go0szC9g+Ry zbtjAt=|9WKbLx@@^x0XHzOMjdnzxd@?jrAkra!A1)dr2&oNg45TzSSV0)l$AcnC8y zKOQRjp*GT^ZIvdm$8qUb`x3TzfhI|f@PK?MYgL&2{rNs)phxDk%91TV4 zHo!=wtiyE)xO;(-)iTXB%+lB9&-?&3=7e0!PJPReQKQ~K3PHU3+t-vUVEGBmZ;~gC zK%67b(TvDChu5|{+hoA*0QtgX9gbu5$ejPcj?W9#wNV%P|Lrco3D9a11S>?m3u;bRNIsWKWc}W*oQJ`bn zrm@Lz4wgawb`N7L@)#_8e`0VIFroz|1W4Bw)0~S$@#68IU0V+#pkD0b;FE6L;t>ERnKRqy zHzAnZ$igg^ckT?z$<9eOF$M>}Vp@EN+saf7IU}o(9LHu~r6M?Hl9%u@1)SGUGnn}c z9#z0*gI@%<-D+j=$GRQu*Wn%aqV9 z2~Q1rQ6+tLf747cY%*_U`>>gbyZvknGVzi5c`yAJb@C#f>yBZhHM6&F*#KUAc}JPAUfxkMVVVZWbc9zWcw7Yxiog5#h}` zq>Y#zis7YHN5qDG7^)%JW%ymFq5S0dbBEjQzT2JJVLVqOnHnMoi7&%OwSc?B3{UqB zlwtpJ>vON<*^f^=t1{`P-kIU`laWoJRjVL-q-uNDZJ@OOG5Z4p&ZkiYo+z=HfV{_0 z(*NfIFvbi3?z2yy&jG>8;v18;yVv1xk{nBT&akmyjT>W`|F|nL!29}pn(w}&y$FBN z?`m#1dgIkg)IlC8EpHL$`|Xy^(51`0#Fp(9xd9=3^6kwP8$gSaHP2u@M-!I1 zT%!|D-=J7ks#Kf=mL=?2?Og*xyeEGW85W)Pe~~Oxa(Yc`Pr4Ga^BiKHc+q>-_@t1m z1A4E;@k-}O;j8;w0(ke~QA0wSyAN(|h^%K$ojn@eom*Q1e8jPsx)D7Fz@S`jV39@-19{JJ$T6eh7t ze$a+hpY0G6{%P8I1L#4tqqq}!%==ugA9JOp?+Lpk`U@Blrau(WuSi-Gc=WW^h3)Kw zIt9)J1$U`CiLm2yH*aw*g6fCoEGyUknWgLGFMXuaqChGSCZpX15-v_p8^624~ABgTUA z9f|i@7!?xzlk45eUohhr@WdHKI8L^m&9@|*>TwJRPsZJTXPf=V+q6pZF-xy;NZ4AD zC5(&zdz88oJ>W`&Zkr9Xeb?wtK4q;}5w{SC*suJ})?8)CP`^BRC}PVarSKq5C*g5n4;?eL2p#r^W&vgUkN+O3d^aNo zQ}q7VrEh(?4Gme37hG&#FVvjCL-Z4d1px_j=~!f*UxN|N+bj-^M)?0>%-qhX4J{Y9Xa;X=C+8l zSdPnj%-n$uWVkSET0RBYUILhJXcnGf@oU*|12YOs6z&WJ!2kQvs;x!^qpAyHF2KfQ zJHaP-saIl3Ak4(NZ3Y9MqkFMSh?4wiV$6dXkb=%H7RcLfCj}ksa=lW#Slv{*dJIkr z@#%hV8VVof_+0k+6-5fulp1ZYO2G@X5U10U?=dC%tKq@&WUXc|DfBI?^Fd2!Q8!bN z0hxKD|H&p=>N`A%Xf#a^@1~bK!y2<&s>>@wO!irZWAt`k)gLP$_8K{aMO>YLF%CFC zPic&o5`7>Q+Dc@UFORzw{4BK9p2`d7P7%RJ^uST>dy_iSCk1-NpuvzxGZDAHegGkZ zvxXt~%pJ`ayt5OZmIbXQM|i}saY=?RkfFtQ`*rZ5Ril>F8Ev_zst-bOj2p3w9==Z; z$F3{<*WzCQEq)?P=0eg>PJQAvD z!TK&ue;htoR5K({((g`tU-tL*m8A}@%~5);6|1ogCVhRT)&~0~u$A+-kH44BHMs<7 z+^hf(J_*11oAM{`)oWPZ)<_fH{~kIZhL8|Z$fpN2nRH*o!a+a~Wga~9?FZw}0}1tH z`@dR-JaivaRQ=5xh&`)@g)cf1fhy~%V@)kOJWF zT^=c$(%F`ZZPrcvF8}r37)xM;)~-17c%j?34)V;as{cO{jb?1@6H!{cE`#3qq={jd zl)uSEYY#7`F$K@Xi#xC~xmVVZ92RuP!7h3cENa`yTwPZoOGn=%7)^JbxQ3tBr?x{Z zjeaMm{y%w}|8pCQkb@bs&+LSp8P!2KKE0$FPep+J$nG%pGbU2D*kqlR`IM}>P3Dgi z|I_ej7b6n^(Z16d=^i_mC^#!0@2KVb<{4GGioPovNL{}k#jbt+MB#Mf2neRf>lnOA z)B!UP^XSMb_9O)1X-6sIP)3I>?{KW*k#6BIygIy>%EUrRc2vgZex+EV^0(F7l6qRv z`;p%3X@J8ZK7)wq$1{(qf>eWDb=En$HR?YH<>B!$cU7~tefNJ3+nwwm&uWA~j`~9T zX+Vu&5qs=#DQ#VF#ANzcdOUds&KQ;1%>JBcj~d|09WKZ4PG>~M(yNi^g;~4XAhqL? zXocw(Prn7z*?TX@30iRc%arjkYuj50#^*1a zB$=nD)|rR%y}Bh1bvdUuS1obtB3BL^2D>D4s&0)ycLqB1T_o%hdaqy=~#uVw!- zKS`xGib+nj%X>LdhQIQYy!K0TH^vyqXtIBAQw{ASDJ3krQ~Se-rrjFKpe8_UUcfp1 zoZ3xyMVs{_6CGbM9o$ORoa{V;TAU$Gkzxhk>4^6f6bfXaCj(0DUs%-!jqjWvpFM}Z zxE^-b!NN!a2U%P#(YmI*x+5t#=)n^~OO6#yJOkE1r_ zxylk`6Y0Y%;zqW|SWFCvA4ZrkUu7a9@_0?{CUpPe+qI%TEjKe$moU8U;9DCi>m7XU znzr7^oIojL;_{{LgS$8nW4ft(U5=Lvf!NORrh5%{q*%mE&wo_88E)-WRDm3?*H6q% zV8fsXHjY~ACGv@5*$9`>h_ZeyQC|?0^hD5k`bD}m%Q&{meI>I(k6)%fMkiGHs#Xhk z4%>kLOM21r(e7vMdm_cwo1%+|enF6q#pQ}LVXqv4$_&aM#px6^@Tf+in&8xiF?k!Y z(wopwQBU=N_{tv3LVtwCQ;64~BFFTF{UMR_gPrD;cySEPI7xf)7^I0W?$ZRWLyBjC z7GTC089nbI-0ALm3-T~La(ij-B`5;=@M_E4cs;vQwcsy`Sl}#1UO_uKf z2DT1MELP`$L($APy_0C#XnNJ`=|)3yC(TSBj}U%#Mx)%1_}^#$JNZEmrnlCNdm~v6#Vn(X^+sZ;Rnua>$k_v!TGfgKN#0!Cx!m>J0u?$2mUT*`^*3KSudS? z;=^opMDdL;n|I?$p z!K}IYjzeV^DMzsk)Z-$1&rmEVyuB<$_`$NW^lQFg-8gnD)tkE|Za#?~h3Vcck{x6c zJpjNE_t^D}*E6pi&Y;kBP_ky!pLT$qN+LhmSjNu59MtDEM97)|Qcz#-!*v2w=l z+*t8CzpvKPpSdhqx5|BqlEiI1>Ex!Bm$KRxg{yt>?Ke258C9B9>CrCWtK0%`C432q zL~YX7d?KJoc2%7~?R3u5G4R}Pq8qgLByRS1ALyrANPg6?@4fA}-zEu#*n~^yOO4KB z7f;K)t!coKS*BSl`B}xh+grm9xlU%jUw*mUwLi)dKsIM_$6r9t?i7W~jh4%|n3T&|1hPbChW!jx5TwC|sg+($|JXXZ z4KjdMh-e{?)xh+L@oAcTEYl(9l;-WdU)o%2UViFSeIYDFN#W`fN{7~mPd2e50u35$ zy)v(+*bYaFx>h54hDit~Zrb+JI*2402x61mCXb4IrqUK>VCyeA^8y7Qn+Xqe>2sxJ zzv4F4=uB(>poP)!{y(n{_)~^0lm*~J=xHJi)-J2a`E&S<~Micvt8@n{IRGMvKxPLK_@PWE2I`>a;*z07s zRRmC>@E#969}j3oEaj=wB>~=Mzp}kE!$8EU}Dwaq!-;bj=Kf#5adn&3_L&44tF}s82SA zJ~CZjBj|J3}!~q(u1fKbJmxY&-0`P%P+Y z$f>>@d4I;HCHBqh!>~Y(8+w0}EJ1b60~$=pLW3MZuYuU#+Gpov*wglajJx3QY8hD@oYv(Mp3y)oK8VTzb3Dm6S_4_Gm$m_9 zBzViEMSzD;y{7CMupl5^Ed7!<@BFiZN<66@+;*Phje!Anoqp7VKZ%9x+CkLKQM z0(r!BD;*o#6qqAqS?+=-Z(llR+U$qYO$+Bqo(^RHlSQ z=PSOJCg;1x`gJ~37vRq{Jl)Vwmb3}Bchb$;=ILJ{;Yt3^nziJm`_4)1!n&h6Wi}94 zTX#*AtT-QD|B!di>Bgp~PYPaaOcxsm*%ikF^1Ho|K0t)O|4Cwx^hOkz3XO-OIqcnM?zqXeRohc-Yrb z>Qu%fEx8!TzjlFyDYB{I0bF?U=E+|`ANw3KN{2EI3ILBG`^X%6{R}^s1}5qQ_g?*E zm$_*wnNvG+awmf-%dgr8TP}@D{*QaTA=tqpWdp-l>|X^K*kULVFU-A8luV;Tb@d|v zgPAmA*EX+oQ;@|*j^_xE%lDuXCUF5ec5HhJVZ~vbS9&P8me~7zttIyq7{-p>HKlqF z{!b3)CsF02W70&=-`A5jM&2jM?r{vGQ!b#J`Jp`fLvTx&pAHDVbJ_r@!510#_iDaL z)l|VVeFA%fxQ**;iFFD-)oXR|ptGbt9Kz4b9h5$g>6}?f0kO|wum8-}D^A`~o|Zba z#!i5fOprK?dP%G#cG$;cGgWQ##v}wB-#xqb^wCmQoF%{0L8sELraBNiOSR7IH0L6I z*JEzi$dsY?BR=w``n-FT^rPf+^rK1c6pQ*nVLzRL!OzuC>0U02HLW-I6r3KpkP#sc z#ZNyJgq65{c7fv^il2!V;mpc_=k&;z-_($n%x9-(6`n1s7ip^!2eOd4woiMOA{KnJrW{pAw8E%RkyThhAq?3 zc~4q+2O_wf=oQJcwlUAjs57zI&$LrVd4MY-TX%AKvh``~I}vtQqu^E*Dz;UdxSBrE z18_l{pc_|*YgC(9kyf+(0E7|;b7zTm5rnCKsmM7GYFp9T7K|s~pRDs%jKro+6H(Y{ zimo_+1}KWQsvW_3s=M02abE}ajl-=Wd)Bywc*>;KVupL2BJ@GU!Ll( zF037(3h46cC688#GY<+b2wE-LLS9`BeD9@UOZ}*qD%{|c5~iL?=(H*Rn6;lYfgs5> z?IpK#=E9_m{Nj@HjyPZyMj8+lzSA-@@?XQ6eOEPdzU#R`t#y8xfnX>s15Id{*_l2R zdHIMIBwv3n z=T9b09%I?Z>%(8NzkcHqPl*Mo2y7+w`xJ$!4dOS>n70=ZeI-bN(81OH3EiCFf{g|r zI1k4kYt^|to)1+EI}a$G1DQ?Y&m8K`T<%a=t4lrpWrU)t)La3xIy?0dym+)9|4~5I z@i*H5;XFr~$N1^1a{u?kzp-zWWmT``;+5-nf^II?x*0IH2`B}+LnojxcpvbUI-PFY z67VDkQ%9e=m{-`dHpSEX+zqJt?2PgvsvMw65SfM69 zXuiKaZI!ef)F=xe&#eTYRZbkUU#JR_lMH~_Mk3{aOs8SoStTU2A8 z303{!q(nWQsI`yryRo!BvbHvHHv5v9p?H?P7fOz*C2ue{*Qp-+@FN?`<&lWj$};}7 zE=Vay#**UJru}NJ)+WZi&a_S5ud!u{2SMlIw2jMb%?PQrbnos|sS&XH!Bx@NS+?N| zo@*uMioMUGrfN2j z)nqX{{xlO);C+8Mg;@q^-Wy>z3nWrNK+;Y*ufOPS`RraR`LXKzp4wkwRx+q^G~Y&=}Tx1c!bc`@MXD&RE9*CI{y zQ+qm6GcB|%G17fDnEgZdqZdctfe$?Yw-Ey;pGng-wb)V0iUzuHN7uNg-%MAa`g^-@ zpIfv9@0~bpZ#aj-FSsG>|4*UAIKK}hFB8Q&1nL1ng}!5Vfylt6`%E;V%fNgPR9b=3 zLZwu$H7wjR0X94tA;K+c=iukv7m$H&uA>d!v_W21`~1;c+m;3VA+jI4bDGqrf;(NB zCt63Q_M{t?p7}F1o%AMo$#nt4S$mq6i7mt4kqDgn7I5aVr`FN5WAByAdPbwoo<;q| zPnj+j);|M*F#d}n7~#)}Niyo9Vul`4ml+@pyV^aQ-E)2D4dAkF%$|xz6Kf~3BeGJC zj`^BfwibGN)M*8cN6X~1d14TkqDF~kYrmB4`&Q9bbbsj9=(Zj2ZAG_boyXe@rlsPM z#|wPM6aGHz(n6jd4x{J?QfF2}VLXW+KesL^n(f6V*FSZwgje9)ZC zTZyNamKxY~nF+jeiMw!e^Jz>$YEOn(0I9(?`->g*d)*pJn$#ux4A^U5%EpSCAKaxVpaPT zvsLm*%HYlaAJMHL(ETp~pHWLP7uP=ac_D8&Lm2`;nOI(y)TOi(M$+5MB-Wp2%fGLc z%urN}j~JatSDTuKcY@?Y3l`kE2qsvlo_}zD;-)ALvgodckl0^~?~PmNgbn~xfptmn z-z%H((k3NYgMM_|7?#TIk7MZBYDN;{lUqLCMXt@x1%kw@vBnLah8Zvw*hxmttXAu% z+jjqbToE&juMj@KI7Su*WZZ#Rw-OAvvG*|y3lS&Nsw*e_(%R``a4C6$4-Orbi&_bh zWeMq_N}5^8IIsOfgdLQo`(wPn(}ho#h0a|rd^&s|{df|{E@ONks<^>2W8(j(#NJe4 zj6R)3Y$}#(au2}h4gZg=uMCT-Yulb-=$7tKx;vysTImMq?v}1W=@KL)6c8k(ySrPI z?nb&h-i_YR_v<_SkH?<1_qyV&+s5qBN~ken2#^7lfU79bz9`4QZ85}Q00MfltC(W8 zmMfE#mu`jkyF=WgRpG@Q1YFPKiFF16e;K=P|Crebj)6~`N1Yd_9P@Ygbk>XOZ*On8 z^*0jKl;VASE|s+0N+|v!B)}p0Rsbx3P9Tw4=LoV4>R2X-N~3$jJbaVZN6VeQFww2K zHocD?5H(uD2(1)*oL_);cVajdS`*-RN8zl3s z!z!$z?4byG>3n|CQ#D{8pf?`x+wgpAl_RA}+nE#Hl`~eS#TGaSg;bun zr)l}wbBeA4VRSYN#z;K0$6ALrEQpnAaMPmATx_& zXyf2!*?GJ2AI~Nh<%wrQbbHK7a7P0%Q$YeDOAgg3r18z@2U-BDSiFY^9~21cAaPq| zh9H}hi`eOmv&&)g2Kw0??*S4lY+4GI;fc`qZh$dwS^x%gvhygYUYEv=c^Uq*@5kp0 z(F;Pg-Mad+9UJ#A@&Ywz&F^nqqitOHAv5mWyzN?BqNBF0T9Q zMqBJ3dJ+W%YQ8bi1{%YZAL!h1QDtE{HDa|exm}eB%JaBz94LyXM19`OXEnDO4DJ9P z%;%^wJxKg()AQjoGR91EaT}kewPB*0L~Y3|3owOQv~`;J%_m9w!dNmcfK66nYwl*T z)4ck#*xcv_$t$IS9aD14&o$5e1@o_4{r)r9!8};Q&z_G3GNzrk+kq)h3#k>9AFAj*tqMV(Io&J-N$(BCh604uS=uYE} zcA;hfR3iJzse|&~j2`=QY+U98cu0%?BKXY2$8oM^0+ha%^E!TQ_~V^~{VKMj@p0Qn zKd5RGT-6W5)|Ox^2Ech-`8!+YbLZVvb2E#;4>+tkVD)l_=lL)1C5tsH*1@@phUN$J zg*^y2vJlBX@_WHM97**l$sVBY=v>3KAw!{FUU{=$$;~zW#-ZdEU_$%M=7Ojf=T@tD zc8K!XSTqk~p8f{1y`0yg{QWAQW`3iwgT3pL*WQevl||3uVPinM_dVKR;K`gTK)01R zMc>Q@xxt8ypw}2G5AD(Xp0W4C;rtA(OcvXhi{zAl4s;vVj-rhyZZen8u>kHg%ie3b zeA@<=;HO;G$t;8GM8qJO4&_Y%;ziLw>~FjPvDL<;u48rMQEZeXy)X~DnsPdBrzWN5 zBEUGk0LTADG*X^)THKZ_dUF4eA3(8b`84IjQ;!bfL|R^bc5Y>5luPG#JvCS<{Eq2BP>O7OBAr2dF&{EX;lNSNoI_=V zV1RJ|^w}|HJidBFo%gs4yCyw2^kUG{!YR z&bRygayR#(iqd#wpxu?HZJ0FPV87}fD5uI{^R^-29-*t|Ly##E&&**jOtbM zQw0#~DM9@E(*slj;MMobE{R}qvq$IvnO@9u=jPtt>{ifSke6RRjQVOW-aU?zrvyb3 zZ&!o{3Z>=9r-VxfL+x5u325NF^Vhz|D^?r;lxp#Mq&+}6l2BGh0k|P*U>xZPD<`6p z;KY{#ij2t(-t>Voz_Wj{Sx~2)x5jcbT~h(94kv0H39xhd?-%5f*c~kv!SO66{&UCU zt+li84CVtx9Q)8fqGpEa4hJ&Ib4q*A&M~<%ZleuX8Uu{Oz!oq6r)5v5Daf+Z;x%UB z6q+Ef57)W%oU`q(mYq7EZ(sdo7P^YP0fRdhbedOaru)&>-QqZHs6lpswUv0bZ6hop ziup7KfiXfx0du_=b{H5BT)06`FQRdgI!`U5UE5e%K0E;9!EW8BJ9tx&LiBVQJ+Z26 zCYbgPT=uJ{1_0BOy$dr*I`043N2xsd5UEGj@BdHvT?UOq3MsVeBtlg>BQJyG&o;P4 zhCg29sZ5gF<9a85RG6_?d_Dgv3l}smHuM<46KmHL_%|gIcxOxAiXOfT-GZUOU8CBc!Sca0BHVNxvlGWoDJ@bZf@MwKzR#6Ta;4EIY8$tbsFEru-9y`FZI?jJPb(qk&uw4%Iu2#H=H?7`6bhUXRp4t}ZMJn)JNa||1xH+8rX zY3KnH0&5g16Re<&NdjsCkRj|A7A2{X$j<^Seya6=au$ZS+QvT&M+$@#(#>0B{#xvb zw$T3)ti{JzYtq=?)GjL?L-erv9H*B0+7wLQfhYn!?V29Jt@%?>fbXDTM z6*H7WRwQi43_u%eN>TUm-i(Vql)ko87U5Fj`H4cM+D_wcYW#X$nhGOa53q^Au{J0m z=QVhaN;14WOa`HHLD%A%`VWQN9EpGLpkoXdBK*Y~2!7%vo{}6X=WvEi^q5I*Qm2P} zgVrlG&2j|$!4kXVzDo`ll5G(fP}=F;dc{vJT53}qo*wQhO)x;%SD!{ z^OV}ZJ7cfxiC|kna~laq-bRHjxk6Pw2jWWQb)UMj@A74)W7aaTgest@u^M4t&be)# zH;bUpe7sz!4GPz~iUad>s}Ag?SuuIN%5y*>`c4UZZbT7D#I7xLP`75+^gT1G|2G)V zgc^sg9O*#WcB-VhHzIMr#~`3D0^f3G)MP+N6zO|bAq~ns~tnyV=cf6pEg-7 zVD9~OpTHNti`)wtI0O(2sJcauQm#ZGk610TtOb@vr=}QfOkAgRYW)G9JaRH zeLk8X!4f$652=mp-=7`N3Ft(IzS1KsRCK_hgWZLH>(smC@XmB%iP=&1NHMmx11<)$ z`oN-{oU!Nw{|~N9RPm(PqrV~rU{q0mk`p^T_{S#*ZySEYJa3+<*%*#C19sQ0HCvZv zTMi;Q_O~P7c93VS7G`<5)>j_54l4yW-`+*X+2F-XV2a4I73nLb@;S1a4>Z`C4D`4O z{nI!ERXrWlyqmHi*vS(tEQ=b*%)lYTjqYQtBkTm!MP2!#mL5d^xWJ^MwzpJfpsFQ| zx|_)^^e^_mgM9{jqSI7W-L8AzfHC(Gkbh!jl7N(rf%Qp#P^!Y(3l&1P9C&l26L|a` zB;RMgB0AIpLdQoBAv)z<#7n-eKfDa>@dDE@zTXT__wK&Om}Yi>t-L2Q&tihpIa*$Q zV}i8`QEeJyC+<4yV8x?^7H1~=^xq^7To!Jd>M^P38|}+cs-qBBQ=0W5`uBX=yi0`m z5tHggDhciLq)F*6B!X-0MxC$Z=Q^*r7vU#c%PbTGyBN?3lh^6LAcaT3X>Srls3*jJ zVSa_3#Q7`Ok*UV@cKxsaf)8oqi}gjgU<4xXKyu6&TQjF=DL4`jGWdjT17S#tlfW2T+}*Wqsk0&_I{-bxNDJWF*r%I(|#=8 zvz+Di{cWpyzjx|hs4Ma=%hU0iG_TM}-&V?@X|Da>;xqDz=TZhtWt!$29%T)pJso@RQbT#lYS$W>mNG>Fvd4A4Ll($0a;Xh(-l**{!6{wFU$<3QpYu z;7dr%Ytjp%f2hUT+kcoM3y@v$XBM%d_1f=#8+Wvq7w>&w1MiQ))zX&OlZw1~#?Ww- z6SG=FE8z-?xO4aJ-~VxC#t@gz4iCTI6wvn_=04D8_`TjSbT=Pq(KD10eXM%-XIc}J zP2;V_$n|(z=VRs4==~n<97RkwryA=9CL1+`UI#dyKy8_PfjsBco9<77qBM?m-uMA3W%B z02Ou_S{Z}`?&c`wy@I~c3>)#b`c=>muGqNNf=IilfJU4{JB%8z`m;ke9qJk6lKv1~ z;_ccD71eapS-p_OmDIgk?I;kns%P>c4Bd|G;w7@)k*6q5Zb*xN8~xjdZmEYUSyZHpkz zWsyxp4evA*zmb>?$wELt1F6-XUdZUrq?iuj-ejFJ>-YfDq?g>M0X~3b#?t0N*iY7{ z)3veh@K*Lz{xB{&0HH2@8F!0(8>({VDx45SQ?mL}fmp=5s`;_uFC$~-FV8792Vh;P zEqP0Xh;plzH0?C#7p`A!xdASrw};IykVx!}9T}N#H@dh!+CRkIJy(+5Yad+qu#}rn z>!h_$74R?Oadau>Y01e!C*t98TAr(_d)*W5^*TiO`n}%5wsd1OBqYTzrf%|Sj=@uW z!VtUs2>2&FGg6G+#bUKx-2b6XNd78ujs(rPmd3;O??T z@_%`1QFXnCg1?EEm@U&8+zRr=B9}qX;i#SwmI5%Ypiy6AX+!qvP3n+aq8T9sNz}+_ z`hZS!sXRATOuofeUDP47aW|{BZz}(JKl7Pz2T$Dxb^p`3J~u-p`C}dy{Nz?JbD6k> zJ;VT9S{SS_|=q*5@2hrIJQ;QiWLm;BB94en>+zXk@$q2Wy@OK8v6TaawDC<_AoK_QSVS6286pUwEn6S39|>0vi<2I! zEN8+9l&tH6YkG22M=KX-X=vJEv%^a0*kJ54sB08G?ov+Sv2L2#fQN`<@n3{>Yp@vj z@~bTcL>FT6Z=i18YBzPQb_a0ogrVda) zMgLXQ$wB~jFrYO|SX0Ym!Yz<%H^(Ej60;Jr&lc?o=i|!bQL7lC?nx@@W56ahou5tl zFeGA^2@>HqU4a=->nJ`BF+1IYDk^46+s{UV$0#?dOA`e(lkjfp*! z=}-imQQJzyg!*{o4CM8F)jxzYC`&$RMre7V94m`7#S)&}AVv~_|kk^Lc;RqwYSLvp= zHxcI1<#USdqV=WJd`6Tj0>jw^v(JAI^eTW8(jcl3v+v$dM&M@;4$j8`2SvTOpD?emX0l*H&^>?si^Lf${HkaM24TU7{1Lg#V z9mxaYF8m(a6dc|I<7vKzzoe;?9=I7q^l;-axr*8ZCcm)oxO;s?yYs|%?d)9>SU)2xq_?|FMtmjb%#D26K zZ`xR9s4Ch*8);0(QUUud~!k4LGi4iq-a zKKGZah)5Ra$fc0fxr*$6d6%p*hd<~XjHqdC5_Ja(7OHlV`Jj?&O=r@Evm>2gv-Q;@ z{dckM6w}W-uPmajU{sE3VEvN@I7ucMV(iVap%ECEVE+*t;*341j?PMw3x&X&5+=eMd^XTS`S&pl@U6mg(D%`(>F=R+(kkTe{B zYo@-fP}I(8+B1DWDts!R0wm8`;d-u7xD*?-_}1UEuKgugt&~A);5z3vus__@3`k!8 zyd#yn@=VqtjF5%ve9OS2a7o$p?nv%dtINSX7R4pYr9yr*uhhNNEe#o45R}D*scwm}YLJd+Rm0H|Wn+?b2Lc z_*13)nZF!?qh`gH69))iPy-#{Yo!i<0WxY6c6(Il_Uw*)beI=b;%s!_23a_s2JKQx zOKEq!=UB#VW86GPCwn2fBF(5~QLo?+R|>&PWYQRbOTB|PpVdN;3MDg1M@;3j$~AA< zdSsyTjO#xJNKQ$WBQFQp5_+PDtv`8^*;O1;*x!`px$(1UM&*T;Q=*i^(R3?BqL28H zAYXq4=l&=nZz5!|heRknU^NZd>Uyr-8wcQdFx)Y)bO4g>&$u#NiC%F7qC0TIO_Il< zKlsPkn8qgS;z1n%?5^u!db6n^O&3v_|3(RCAyZfiEJxZA6%Gk002qJ0PXKV4wh=&U zbm>5$U(bhF4kc3q1Zel|&49C?GOEotOPnph@}rX@*oSApStCRy+K1?WLwi&8Uo-R_ z>q1U+p}udb-84Qt{;w-0gUn}pX<&Ds^^t;@f#iVVdjNa*q{F?)&(!W=9^&O!xwrcT z!r!#%?R8b2H~isR`>xBg4V$CyaPdb;vvHpETCQI6&hh`kGhA8*Svh=tk3NjwF0#2O zl_EuvdgOiaKK2%O^IQhgZuFtb1aoK34g8&1GGVMh{l(S*m6ZU|OC4}j=;+4iFe?&A zG~P)dO4JfG^>A`NbxSHx*DVg!bH)$bCwuPPc#TQ8P~1c75f^<}Yp?4}dip{9VxGaK z&|(*M@zi8P!eQ~**2E>cxR!_aD-AD!TZS?`=yr9 znL}I1YcXD`gDLW*!<%;!#>6Q><+cu$M7Q?Y=ReRmn8b~~^gKVKLp3(6Acpwxra3p* zk>^s7V^NV~;~x#p%fe&28JGz5#7rmbZAAmtN)83hRTx#IPWfyz$2UN&O@8J+_q27w z(?sL39+wQkqI5_Lm@)s{|AeEtAv}R*Pe~RhCxh&vi>?2I|3x^1KeOrENGSfty@+K) zlSBxqJ8I!}`}B?jwUY@EH}|b7V2`w|{X?rbmNQ$rZ%hVhc4>_KiM1hzUxhLJMyA}=q*Amq#`t*`gM zEc1g+coF-JYmfOmCPqNGalqS&l|Uqa>*W#Q-I1otMWpGM=XC*CROinKIq$nkPcb#f z*~;q>*CGag6(`FvmE+f@dV0`e5Q%i>bAIHwpP#Do%8gdK@}OQpYYzzzmMIcnr97~{ zxeRvx{QLr`q`!`lo~;Tcn0y%s6%gx_t7*OTAs5<#G;z9vpf}w_s_*Ch@so_P^qOIx z?I;PDWUNiI?D5ICWCCGr3Y%dy61TlgX8z;s8bLdJDpbbGy1xm2hl;=ksvsH;%HkA& z3n%Z*UyL|VzOwCqU>p`k{ljpE*b<#EiZ1NK6JH_CRiFMTxUU1xga8Nd>CgrU1O_BL zR@fF=wbB3D39F~0Bk2UZ?2R$;zKhFC84FxTAM;HvT@y~m_-L=<7`W-!lfH0jU*&ag z^lUr2J>-AQzlJJoJ}!CM_=wd=!RT=nr&{iU?{#0THI9jHJ*W!7K*HLi|FxKI2Tv?E zdl6@~QNdi2)Yx#I0Kt?eyXA~(UH}%TPyeos1B>88h%mR`&(ZBL-jjMFUx7Hv8J3Y= zQXy)uDIg#7N6k1aPaE_ESH;w~C!8=Gkii=RafRy84%bbz zgSE%eMID%o+dJc{WiiFLWfEi(h6A=&5faYKY~6CmRo!1#50tB*<*Nn^nC+17)OGOm zo@jTc3NHtTE#jN`XK2!f1xMpU4o1kYE!_Dp7hcSoh@hiOG!8!V_}UyQA@v1E7>C(N z9t>&#;OhQJz#~&aE{Wym0(db`Wg8wr$>`wVfXBV)VP2h~u)=jq(W^Kujr5x;7b$Za z5KmmANhKWkt?xoncboB^`jiZDp3of63v(_^ICQSdR5~(!eKaNTPKsyv+=u=BeIrFc zqlJ7T^p2b|()aLo&^-x8eeeu*WB7SQjBxe?Bp`REdMDP^o$#8U4Yh84Fph1g?Wj>R z+In|$38L{@^EUK0eeg5e*lQJe^V1%;iiUS_CbZVO2c0#GCI^3mumhb`+E!rHE<{YQ zkTNs8R1h-QsXY`8gx(fa!{pExi;^Bz4uAB638XRkSV(94gSJx*o5CkQ7u~UOY85FK z$#@7HEVkMkK)+1e;ZBMCQO2{XfN5}cVDRQri*y!M02zdO6kNX88o(^BnIZSFFPU>K ztatSdR)4MIBRz!@6NMb>Bp8a^r+L@v^`o3KgFBD{V7hn`WWCWTROb&$s-+R&K}D_p z(J8z#fryM?mG81^J(tgGqHp!1Q0PSviC9^gCaLA=e(cc10iM1YN=|(w#(_rbh28 z;l8OXAFXr-nOJl9>OelW7U@*(9H2Ulb#_YBgwl&GwjMte^n#FVf9F%Dt=>P}U7vD& zeE$EAwh2bvglakN_mcH6K=M@rdP?8n3S=eh_*DaSm=K3I?ZJyE_16xQ`2_oO%@UjV zl67UYjZP0N8jQNhZ<5$#NNe{$E3kk&UxZ?*-oH)E*ByP}F$3)O^@Hg`SN=p!F-k~F z8XyqCjE+n7&5}>+nQP7Qx6C8A;tt&?cYXz6(>{yS7&!9abD=Z1JkGV{r&Jp^Go0~G zs~6LxI>B3>Wsb}96Zp92)P}t@**S1g2-#pgzV+XGF-=xC6)RU|%h4LnfZ=#rL?uU!Mc4F->d(&z%o+HIxka8VWnyQ5SOl(9!e zS6+0TIX{&;f>63n8M|74J!sWQ4HJFq-s)OAT-P({zM+9G;DReCkg2XkWmV$Kz9>|) z1+71)rxbOXFogwyzJVg9*`bEM5<~_dR?tq*=PksQ@nktq&ok@JmBdhVM z)HI)i-pWR3{r346^g(~CQjPSFV+ewj&Wju}2;c2^F)vMZfxP5dO{D`?Zw6%`P3EQN zQKp_9Fa%oxd87@52U}Y*f-dW^8OCLR#uE4B*$(HOzG}WQH41|H-eZ_>Ij z9tSGAE^o0+V~yi8L3Bt&I=tmC1Qub&SRjSg?{mQT2gVHEpM;b|XT6r|{*-5k z-29x^QM0;AHq3XeUCiyJk0O@F?L}NyR&N{2e!Q%*dSFpGGmB#I=4$&*Kviw>=lx0g zW<+U5Nj`)Ad*>H_qsBW_z@d!bZF zFPtvfmVGsT%JTYC7aWTSE7sH&RLGq><{XQz^v zdE4&M_30K)W-wA68sLzFW<=i8ePt8#?ZeO;TLfQ-e|A6-?iTcw_$hB8S%MYXsHnO| zNbp297mrW==KFyGAVpZ$s$tpoxh#;m{)~nPYmEcdO62ayKeFuMcY)fjK}L->N+DT> zkcXmHDh7JyxqR1W4N*~1u3EOI>q1fiVNZlLOvNbQg~&aRNBv7|tw?@xPVaNP>y#+* z*{U@VK18^1BD&0KhfYT!eebWO&!hp(e0jHB{-k}IMg+-njRMVh zE{g$qOU195mFaokwKf)nYUSIo(<2$YPu>a?uaB%Tt*rf+DwV9>x<4sLQL|9nb^n^R z`D#lC2qcGAsXdh%@lW{6;5}F8STj@P@( zte~C+Py6*d5`orZB{*x2?iy);yzkOzR7dFpi6FjS0vN~VBhNva2Y^Hz|FGJLV}x@J zmk~+nD{I0E#y*teOoDr4Rf-PZ%81BdUPW3~-XQ5Zg~5WmiJXJ;s0$@}aVUE{f;7|N zaBliqAe+oG$c=WX6zbE={%dq7UUc9s&?xq&+wGq(eqm^7L-nobib2#R-3l)@&5I+P zW!IKJqJ9x7!nOTS%PdS(z06+6Yt#H}#Xf9j6cjpHNE~XhFj>;Bx4cixNZmh4*E^bq zXJphD8i>!43yO%&Tt=}2GO~Dp9Owmdy@q$;sCW!UOq%a6Wh4c*IekY2g@gv#V~pbI zm2wxGTRn@m|9qG$gDZmhF&Z6av`YsXFC7YvN0>);eO0g{VdBD}!)>j04>K6|^=6<< zeIXvYtBXwDv(&CYI{Ezr+z2s3$oAz)&S{m^A`5sHbL_+I<@(Yn$c?T3L^*V1DRQ7Q z2W}W8pcIq%x8WwL@A*y+x^;LS6Opgls-eodCs9rZvPLi)wQ??C zBB2j{W~baP15JZ!Ko8TCx~w2n{|7Q%Xf03H8%OHnl|Zu4{F10Un5RMDOPG-7H8l&7 zaW5yltT-|ojM50*1v{63pMn@Z6BU_M^ZMMRs||^V>G8Q8iXcw)HSWr5WJhGnN{l#H#LX4BoD96TDS2nDAnN&Qe#)N&D6~&1_ zISPS;$4Gb&OFW@miwTdP%ix-chVb-NAOXUc^DmTok=&uX%jC$TuRY~$rmW$E{83&% z+M%XN=W|7zZ8H*?GT+y2hZiTHxBBnhThQKVj)+vk_27?b^7Rl(9$~)!{H?#}ZXuUd z^L?ujCYeB{56;_B$#oXVgN`s?u_+N1hd!XCY``zO95u>r!=`S;e?t&^jjYnPZh5@q z`6$S&hvzj*Kd$eUXMC_>$wtJ4_n9R*K6g}Ke8Me+W|u$&hg8(p$xzc}a+4vd>(9|x z5eT@Ng3{nHvCzRbv0-HOA!i`UwKqsGi6C&m9gz~W%nXi#01un<8|YfPk zGP$Q_2x&H)OOf^?GFFGy>Q)Xizdx(LXn619fbyDBhKVd;0E|_GakdUIuyoA(Sw|%% zbqfgA$A}`E?*gCtfg54R=~qazYNB`N%ZxFD(oM)wXb1Dr`>F()XO`$TqN&fiVWtbYRL#|sdV7EC{s$TRQ?X&=CmdS&??R!*>w8om2Y}-Oeq*E8;83Ix zZ64t{kUh46O;_XKRh-I78-vk_PRNb_1N!tj4V9|NN+6L0tZUkY;&qp)PIv1XDk!)f ze1#Ci@c|#vlU@{iYBA{}!U#1HwyJ!B5|n8j@0vk0UnOWGdmH!q*;3>Zzm)c={_*Ws z?c2~t7m`BZ-~ox_!5vVex`v)-FY$z|E)8U*61g3r3l0{vd8J}p=Y1m`V1?y`%wWO1 zY~d>gDQWWsp{iuUzb#;zd&3VBz9WUI7voR;(XqAK{NBb*MKQuBOoYFOQOa2^Jx^0v z{`6?r6ZlZ)I3Q|nz&!Ig7ZrtQ;~5c@QatY2Cv@BK?C(0Z-Ijq2e6xtVqu*E-AIX(!dr#Hd6qH=^)KtZr;HewY=4fC+yV z{?;*>LZB5G9o)Wbj*L})bkxID>L2Mi3({7f&;{jQ9;$RnexJZ^!VG@1+VzUoh(4}~ zP)c!CZd4N5>2Vl~_DqV+AUs2Rl@2j684`-z8y2Sy%hJkv)XEz5s2JzUG=YjrKnGxy zFRqcCaf6(e`5hN!*`c@atFfp139f&LtgdcELRC_%$(poztLD)T>!>`s&_kLz*>y7quc8C5O(ZHv%fj z47=O|>>$HN7h&_dfHy-fU|PSE9zwvkdfGNPD0h+9TV*_U~sS!@Qi| zro2BCZYs0=yFdGRwep)n?Rt{V*8Bi7FND9}@wO_}TaW|{%ku{~e;VgI)cEe_N6L8t zDjIwWi@wo3mmvhCMGkuWmWVIG;M4b)nO>_jt{;%M zkR&)CG;(wYKtpD)u(q+8ta6haR{G$^sf&omu=%|wp}8e$j+t@qEnuxSAIl98K5(*c z99w4UrtxWb;c5gcd~r>LjBk5QZOV6%{G_L%x$po|%K5(Xd-VMG{F%jydpkRC($mu$ zPLZBxu!^U|t-@~}9I*W$-z~p9T#Ap3L|bTZljA#__(72D#ZaG=+mzQhZjcBru+vv6KNWkAS?@p`sq7_3T*Oil^R3}ihP!tW0X7)O$ffV zcSD9s1mXSo5;BVh`iKn|>9thvDpSJCVi2TBe`*NH5p0rN!8egKZ8pt!e`^%dn~7k= zEzGWgUr(eDL#1N%yjziXO8)f7{+r)(h$f3@d(d zWBfa4m_8GXU5(3fgr!wD2#CxK1X%caJ|z$&%aTk_psTD}VR) z%J{dG{rj$-p>l9UAt!pF|82j?lme|F=-`g=Tm?Cg!^K1+rH=(WEmj}XAnQ?`(TFEI z1%HnUI8tX~;Rjw(gxT|hVFBugZ>2?*56&~J+;qtjj@1fB0yrxH>z`#ZT3&3H39 zgH5ivY7)2K>E+>O^`hM%nn+}R} zQ)6F*IuOb;90Vfxu%J76ZSKjEOq^vh3W!;>{HS2D!x)-Ru!x#*hc~ZUru;^A*G;(t zf{es2XCdh8z%9};>Y=0$I8>X^h^~$L#E}t-dhfJZT$~p8?LNS2+NZQ{P&qpEV|K&{r!?QwLH>Ft8iof+u3Ydv} zC4nyy20WQ~Hna*Hf{NKOhq_V(GKMJ*tYJgt!5v|UrZx`9DTqAiACK`FK4?Lxh}#Hy z0=0#sz zUHdnQ(0qVm+&~D?Mz%tBb#=`q7joZjAt=Kh z_-Xmhe&weDX;#z&xZP;L2k)_G9>1y68;q>M;OYs}sa8Y?TV<>j@V zl&|TvM1HEiMZHy1tB$b%|6bOq|LM|=$%8fLAs8ENds@b5b^W`A8J3;e%Isz;a8TiJ zI?_;M(PNRlkTud<(22SFn1G;k3EAL&xMc=MnHQl@Fi#s*5e9Xmw%GDAFs8^O2o`}m zmX~o$ARq}@TeHwvo2`8D1TervyAzwlP(~aJKZhjDjK?b!V{%&QKw#1?%lv~T zuB4=-b0qn3<(>nGtO|NhUj}$C{Q^P<&-9o?mh|=X)<4H{czAe-=a}&U@1T=B!rnc1 za^N@9bRh%$zceXiC~H`ryR8N7MV z3_?7tTRu4fA1xzM;ek;3xnQQqyp!U>y6p`6WE%O!Oyf8y2B~8p7(Tyg-80CxI2hLx zUtBDRBGhuaJg)K^LfSy~s8u_G+*(1IDNJR)uOnVF%~ti0cr2vM)W7cFV4)F5KwJVb zMA}`*Wp>s_Kz%*GBU{=M0h3Zx{wfWG_;DAQ>z=d+Zm-{uej*cek^SgB4N&B*0BU$c zNw5}m6WVb%4WMwI`JE$2s6XZMw0R0keX4`0w>^~>Pn8~qkF4`|5#?_+43b%<1!|#4 zBlyj%peXYQ!-Wjl|=+YNpyr9?p}d_l8Fn@cB`)R{2dU9DMKE z6v*2OH6e+$INc)3)165MNz(67ONvvOL6nw&`){KSU{%br~P}TF512HLt85+0$Yg9ZuU>}}bDfcVQ`o#?l3~*lVl; zji>V3nyIa`2nRegtz3GFtT{auzB0K2#gi^FAk2_CM^+4E*(Ym5E>!{@Tx6Z%%P{fGM8b~b( z{-V;Yv`1~Hk@i6me-~5)CKKPTBA}Z=TUNiOdWKUR5uq*Qo2MYgCEB6ONS244FDF)8LmkGC-976hkJMb*YMi2F5T3`XTE7mb$%KZHvF& zPd^X+*7_(%B4Wo;{I*5%j{F8O9Zmha6^hM7%?n^%)^p6CqV+VA7eRT{fnAp|&%A^I z*S`+tX|le{15xP%nt=7k_8-{%Cr4brO=Uh(-?qe#Y z4*S;U5w!2-Pf5)CH|>zPR~e_%;Ly?c?PWYg|BfGjCtYkNgyn*06WW%RmXjMG$V=^T zv36c%-UELyY!qGc!YX^148uW+ha(Cz^{vq8#f@-Qk9tsMs;N4B zNYbRSx@+Q&oa1`d&j<1X5r~A$tbzd=aD0-wz|NM8Y1RRqU057HncEW6ZGToHCOo1q zKdPu!JA6_Cdn$7b1vPz}(>^Xiy+AeY<3}u7#V^|b%_`b~PFhq&ZDsb6AyxMuqZ7(h zncqxWsApcc2(@OU%M+yA!cp~H89t9ly|SP6$UTm?(9zF;3ppB*jyZ7E za!}jhv1T>kcgaUm$PhNjWx;X&`R#&3*l$N*qDU{|=8hv7@j+moXR`a$@=xWJ*wme& z?pF_WtE2UP(}tDZ7owvTDiH|L|-V9CQ5PpJ?!!BM_smR{^ycn>m(`#p#%8jFaupSiqi9t#{$g)l+B6{L)&5I(-)mC` zTC|N%W!MN9_Y|UKf*k1CzklAG0Iatvg6ZR@$@-r^);EX?vv^fgF9ikTYHRtwZ6{IuB6!Vc&?EqK zk@BPFf2ULJKxDNx1`bKu^#)$12%A2z)EAQ+StaL6!mRZLi=Fh--FxQkYaFbBPZKFI z8O;Q%Zm2|g~cN3wC`PTO5kFiR$c*X2#x(j(PBG~sesAhe*RyRVTECSnUGjqY5y+~(vg_3V4r+6-H-y7- zrNNh3UO#a~?z39sB#^>m|2VIET_Z+QipUq4=b%?AeinV9QMf8iAr@UmLQ-^sS@Pf~ zv_IP-rJidb591gSbW!~YAmm4}DhUIO)z&vcHTJoD!#lsmHAorik)OFA&P6ws>gNc3 zTpE{-3#h2<6Dwf#&f2WI9J9XhQWm?}9Rs7Fx3Z}xG+b;;IPmUb-{|oK5PTJKjaa3Z zg-+P`N{C^QGLPHC`=(s<9a3)$#*L_-NtWi;Ixc*FUNXaASt5M4b&U3Eq-&@E*Xn8% zLW@ViVU_Ru(0=bDK1dB`l!3i6F~#WDBd=cTZ<_LgJ6uPF`|yVWkNGOmOXoXe5nrc_ z@mwV(d?wAD7KlGO-_U|Dj(5-Q(hs!z1~burDB`0k?cK~Tdi7jwQLjnN@N-)HYvJe; z@P7H$ZUAoS2UknrQEA!L>lp4ioMbaQXbiVTGvsx7mP_tgRIQK-5%Moy^P-)E} zmqtQlMt_2wHIvxBkbd7r5svDOx(Zj!5SHe5yiw)bB0Jf`AQFyhxnZg=VD_z#<3${-680P3DI^KXX*##ORn2n{ zF|T_ky9<5nv#-18 z2Pk% zl)_~WtSlrNrceb0JP!0`L>(8K04py+eFHMtJ%fgK)^I#Q#EhS^0H2rGr#C+c?&5*i z4v&cMDz_p?_B9FC_pYUPXy+8dBoncsdP3H`O34I7xw!mSFvFz68%;K~usg%+U*VOD za4!Xsz#+C%EP0{}LJ``Xic9fz1>g+J#CC2_zV?0o`rMl&ka)*W9v+ukY z#p4+I+MC$KW*8gWM{7yZ;CuXK4{}XD6*+G!=(3sQlMSPWuCAkG7eL!P668SN%5n2T zk_^%$v@Hp>~ z3FZoN@MQhrpBNbHUz7QB6dsw&n=hf6qxVdlq91pwiPlV%vCVKd_uTA!ze7r{ui6lY zgGiYvRE}-7%q;^Yy#rFMnK*uSbI$xt%K?S98A0F#2ZZ{#SpHZC(m@dy9`)|+B*K5= z&*}ytl8@*6x>sv^n^a|dZ}Ya2yl!j;R1cj{lJ zXkLFBub3e1CT4n(wu2BN@R;WR7@fqD%KU1!>?ba5l>>{>7g{6F>v6A}8Uwfb-Z9oj zImLz@x0HvAmN(YFaz0yP9g*b1jQhtowu?NAb4HU>A|gAah+IcY>??*-F@*AcyP2qW zFh8ywHdf^bIIj+zMmj4el8@C|N7nGTO^VN0I_*MdgXl19#@hWF89#sq5YPy5LB}t? zzI2wq2%Nf%SgQFys?IVj%I^!;%+M*#kkVZuEhXLEjesC6-3&?zA|WN+rG%7piXb2z zf=Ees3DRee{{GiF=i_{UdEeQ!_ImF1tbP&BOrf`D2eV2oJ}yNKdo7yYA5--AM8{qR z_~1fh#69qyk7=!f(@D#wz&HKx@f0>JDb)Kv7N8K`w)o+2|08s{2+5t4-iNN0$MWj@ zpahGAeUoAzgN%07nKSm;0{L+ z3+Kc}MU6Ej!GFbq_>tZhP1k9exPj9HaaU2sPJASFw_?0kPwetB)d6iQA2{p z^v{Q;$h@&&5?<9L)(6gW!SLf712I(4`n7fcms$yrIhiJdN3}nzWfYpEFHRmHo>H74 za!bDjey2VNMT&w(lv3bUYjj>Ysj|l4cDIVQQJ!X9&-v!iCU7I`Uhl*KKQ@JASr5{s@|e+zB|pl5 zTU2+)uq@4PoG(GB#XWjaEEZe+)YhUmO2F(HTlC3(Cx*gR@$1i6k8X*--wPLE4)(zN zC-2#4kHbB(J=eZ4Oc;G4PJGRNATNd!J0wzA|KrL7ggQZyzQKQ|)~06XLQkG2XJ|$> zG*3GhT&(%M96Il>uMMV_fPD4lKDwLR#&A|m8=%|vzJHXNslTNcN~*1W2x_tw8}5Tk z6)v@??*As021EfG0oQ)k5zVlyyL}X*y*p_nU2kjgJ{jGC-6jOHRisYhaP;mF)wy!&xG75i{vBtfn#S)pEzS z1vd0a+Tj#Cs1fpjkin4^;Cc50a*s zd-n~S7JV3=RilYGJf3TG4#{y0EwKH{(MN0jK%Q+wXPRbDwSn@%iM6CpqnRKa(wyS+E+OOombZ`SG6gc z^dzcTk5%1HT;rW|8VRqgJ%4$|`*^RRtMJ2i&##%S3Ug4Vd6efq-VaPqDH9BG%fAdWL@-T()sw$qfuW$QS&7w4I!WefRbaqh)K*ewm)%gF*K+=sK zvWJ0v3Fohb<!d&MVH0qf(>6ExQ9<>y^|_feCKA5~0B8pGzVlcn^!M7ic$KFX{8G5f-#Ir| zqy`X$6>77EL^Mh&XNFDX2HBD;AK?&xDX_WGzGa-1h0W7vnf zBygCc>1%=QlyA!PBHkhe}YG?Nu+*vjL(O|^&7f=;-y&;ziw9J z+aFKMxAg~!6HOJvkX#pi_%#DSlXj#Y^Ph7Q+axMB!(Gj|>6%~1ZP&<<*ZoxM?KT!B z?vd*BBRyrXxk-V46~2G+RILEiA6bG8&}Ml0Y&<*1&eDFQrN`qhwT8&l8-`kv*#BtY z0_?c1gvBQpv$@9S1>E)cFJ2=Cv`5ruUlrrQv^8joL{COW_D+?u0eD;dmt&1;$NG)} z3nsk`dd^r|mL@Ngn97x{AbGmazJbqUVWe#Op0amPXKpmp`~!_#Rl`WK$hTYKUJ~i@ z?~Zsl3HP~urYCi^h%t?tkA2>?e2}VqJ=q{*AZlZ5G@_prFP=d&Ztr?1lFgHI-?OjM4Abw_$|nS$#;M)rjgG9h%UB$eeWJ z!4{`GHP=E;{yby+y?^j{V>r9mVJ$}M5d=LUfMB}7gVMOgziGCBiHyBVouMLZQdEojv|!HgRfe@c@le;H;+C3dWwT0wi_ zY+QSY6!EZFHJ3mJZTz(#bUKDAa=k%!^)c0`!tNN)!_q8Yal|tt$>- zx!-FDc)8(k!VZx=#%}`TvF*ks&cizH>J>ZT%TaxJ%cw! z->jbE;fzUQnNi`R;Pi=wD2i=V4&GQ zH18OMs#RQ}R#m|?-92tL_)P>2F^50H2ZM={vnbQy%cBWIHUfqfvmCsEOxgi}Vou4d zZHdBPc*yU0c&|o!fBz*5+ucm~Dq&K}I^7rl;rs6L`55T#KPt?dlJILNGW&|RdH8?j z<)R&Pwg=xB>n{k5T-gxO-pKhYuhb>j z)$36ky>CWq&u~-}`LMQ=coK3ryF7<}f}2IAQGjz#=cu_)#6~Y73;1tLy4Z73eVpg& z@|aXoHnn%a0h+|1fOmXy@^-K9HMtC8Ma}U(twZMo%~Ag@#m;OJ0FWO1Y?DDfK_OmK zoDPOEan3O64!-rnxk`zr`;1|$m)q0&P^DATFZY{CO}c*c=)?)V&kwnSfMSWE(7b`? zn@1BE%O6QK8)e9`8i~IhsItns-)>W1RGVAc*IAfAWoDqL&qi`epcSZ{rT)Eyd~x$# z)*H6%f@@Z=WS~J7MJLdbSqEu}p~&f-VfvP;WjSln#BBD8 z%^us78#N^b?v-A@Ye0%P#4zQATXadwm8#!-3H>4)eoT`!ry0q;I8pjsXVn8x^6mIY zRPquk&NOm$Lg_u4dbZQ*HfvQeWg2mK%$D|^!zsfix_+-it#oJEvRVFbhF0;fI)QMG zypzu^_@_@mLNZMrI^RClH8?vyP7E@9=*tJJ*eu?lK7_JW{Qfoq&_=L;vaw*O5g5pF zthSk|e*MqF+Mj54eY*?(bbY$@+oL(~Ca*Wprg4~%H}GghWX(%mrbyOz9b_mre>|kU??ND_8Z~!o}8fsnbA(X}$7ohp+YbVLb9WhE2WKN~p2< zCLgJRR;U9pZDqxp>b%nPvwhNfRzayE{t`K&{oEq`vR;>od@2I682nB!)wp5Ha@=wH z)WZII9P(;#8P+-&U!=>@Av_E$*Ku9-GBs=VxGxD%Qg7l>{9<^XH?_ksD=Bi7o-J$k zWKj?{d3Ghzqih{H4P9<|v9se|02yRU7xPP*pwb*fy%6y#H;A7~2kU%H1U+Cgzmo_D zr=XMhi1@DvP+bfMBEC_Eq~r(|Oe9L>EKja(knpH6yODV*PkT~es4PDa?jmN-%Bynh5Y5 z($PH?cz;=bS%ZReWcn6OV6$@piKisl@h*2@3W}u%8nw{TAUkbc1t}cyXb~3~VlID7 zNmS1gR>q)|D_sG3R=N81#$$hyCuyQ;#^qey{uzMjt-R=921ohd)vU`QpGSa%pK98) zHQsx|S0`x8&VpH}D_|G^iIC?HuY{}l)s_(Dt~YT~d8_+|l=EuWkAQ0eNp_SP@?11k zDEUL%lwL&d|l^S+M>^E+I5woaM%@zeL?$_BYQ@wK}BI&U5zmhfS)RdZ}HW4BiW*$EJA>_I> zf*fFDQTn37vJ~nIkH%2zqq-HVHu!LXSETqZdL>4A!1!Lzfw4ewMMenACyIKx4yGcO zVkXNdk27a+p|S_ZeA0G2%fEep57;Vaa3ee8Uyx{Jne178(Z%G{mljOy(G0&Wm~;QC zy;fLKnmQwARL2O?X?1eDwdH9pn)Se_fEmob4UQJ@g1t~e>>k4l*QjM-F#c*Z4 zvb)ZlqG0TeZ-tK~PYbV6v9w-k+df;;=&^lJNV*uU{NvH5ueC4pxl2cJ{$Oztc+VI5 zQ9?>LzSdK|^KjeXViz0kt+VPp?hjKqmX$}cB}mL2HdOPzPG3$AV~cWUOR8k6Aw86;zP2DM z4wb|cdi%w6&yxRBGxI3N_>X6P;?0Yh&zn6Q^FG=Jy^f{B|RB}JgZM-oH zK!biwnGTg$A{Y0WCI&Zt`Df!rCG=2Ye++z>LFW@)f)3hoir275N~E2kk(M3VSzA2I zL0F^yr$Z!7+`fWwWP1Ha>Cz5ptFc2Mvro!pp&-DXTnJROGqJY$Y%NB%pE|j?x>MAqKKUF?y;~!B zcXjXL?!ik5-<;xebA?wDx7PLFWpzh+={HJSi;!?KK3#ItN3MU&FNG>*Ku4rYCZ9n= zf3r4IwWOW3_#D`%D~BmFw2C!TAopxGpR~Gw3!ob-(5yu#y^o)~(6R)2!6Y#Dz2I!c zS~kPrkr7Ax53XVGW#4|V%863=`Tj3n2CE_e%MC%qx%vBV;F$-BIIJtvZ%;ck#WK}g ze(&;-?eWoEm&@FL0?EWl{WgED2)03*bZEh?OXM9E3>MMxMGOj#?oAzdXr4q?<3F&& zy8;PWre%R9I}?`}sanR%+QPzO_Q&eix0u->{;Jp%1c}}tnM)3Un5FPWP@Xpn{Q1i3 z91TXxL;Ww85s$Rgh#)E4?BR6Y*m+;~WF-WMF|gbB)@ zEg6!1y!y3ZL;EjEIHrh5)8TRP@-Is3!o@FVa)?;zvzEq#bo2S8Ludm`_xQIPVOtAfJNsd}2gcbm%u_%x}qjCki~ zXUr@tEbnK!3kdT1k>2t$LP%p-1=RLY^7P#l8d`45lPww}Wn)WxEIna0c75?^i% z>jCjDd42-q^2gF~f3SgkaOB*tDAS<~Ay=EVB}S#UT2QU5WQ59O7}~GhNf&ArM71?G+fxu}TMcaw$}&vFmZ-jy z4!S%|Fk?~AObZMQWCiBB-g)R6FTj7_RY5#so@jZh3&E5L8BdxTiw0GZ#@(8aoY%B# z#;4-oeMzl>q-*nM7A#42|G?c%VmC!g-?agfExFDwSYeUSKLyn~CF%e+lQG?Y`*&?W zL^W^qeGIy{GG9mh5BXFn;Wld?op186HSuNj_w(DrvJO7oBmh+(Z#z0VTBkAWCj}n- zl|%805cI@c?921>B5XT0uk^Yk?jZSS@`uGTdmKCnAl)!@vl0oc#$c%L4ft$nZ^+mF z?=r8+!RxjpMIq#p+1d_3H_y#cINkp-5AV0a_|YEpD31q$VF9tE9LT8!+rvk#{~!!guyY{bE`MTO zc&HWeJbyNVmXK9Kt;-H}ad8PN@AcmW-3oO-K9SSW>6Dg|5idrKmH#q1A%s9n0F}ZA zifUlw(|GN=iC6TQLU&LVOMxzddNgBK&M*?uBj>LCD?P zaCQ7?r*EJpR)d?H+jD1{Yqk!UIPu#JQ#qy{{R=6-w;^=r;27T*e_!l-5#pn}iLdtA z2e7>bEM#py5<-g@^Ese?zDCAvn)?D3TlqlR_tMYbfBTqQwz3DztqBmj7IOZrM&30v zBh1T+jEr>30D-IY81eOgrHbVoU`)#oXh(AX4tBp5c$d}9;R1Op#Op18^H?f-$m_ZE zEjB{sy+IWXxWy_}wu00_oy}K5Gj{vDoVRa@0FkDX$f)$e98oLf?(NMS5)v}&4X~}S z>sN@}0@$Io5cCW$?__PvKUo~2-)V|KM41gCFA+x{D@-U3A9WWK28JOCn2eCq?W{k} z&xW=IoEHOX1pUzw*mZP3Z<)0d3^w_x6;PFHY*va;rTt2Wvk5j!xGG;{hWDF+VvT+ZaB$SEK=uIX*5-oZV7mSrZFp-sCQ4AY3ZG{newU4GN}V37t%Y zrXuKq_=Z{+SoMks4-*V~ZBLd}sH0t=VH30Bvu_&Y%VGl2v8kzvU>)o-Ah7@^K+VVI zZ4KNK1C}gF+!oDJy~;`XKpoV{>+WTJI+P~Ay3+9Xr>}-;$%6O(D;b>?fVp!ui=F){ z2>b-266Z`cc17qgaGA}~JVZfj6b993W)l$#O8}RMWz*FVbg_cE)}JKyedBFVawg&;_?uFo=s?uF zpz-;yS)2K4&*PCaT5i>NZRZf#Iu$j;TNt&?6%8_6y{_$_LcA2!tfOlrvw8 zNwyZ?x?XP$_l1;cCag^6K7T0c!PjZhBE42l=oXH)4ul(?=h3O0M4Plh*MAadB##+D z0p{jJiH2@NpsjJsGnU>c0tW4SroND#;l1>+FN+~>Me7`XB!G5)cN?=gX z+O8%sYTn>9&I}#m_5KIQelTOsnbFr(Pi7~%`140|5T%~~l(F5Xq5Af1h!W9}VrTc4xc%|ixH}Z`2H&sab)Hl5m&(2<6c12wCW;5~ zKNtX-$ga#K_W1O2io>|ki7QCwQ)mL6(}G|t+-mH4cIyJv=X%}H^}eD0v3|0SCsQR= z8&Pk+m`&|@u!T;<9|+2pe;)qM12G1IPm*42qBir>YMqvdxoBL!n=7tu_WLC&9(=8M z_P*UPiaUKyw;y8@WN=WThGc|O!2U?>DCsBA0DhIcJpr#Un)=RakjEj!XI4s-<;IP# z0@kp{i+>ZIrSVSR>SpqITwPt=-Q8=v-<`4#feOQmtE<5Vd3JV_y-do#$vaCstT0j- zjii4XxTmHvYrvR1KJR-DD2n_-!GpA)97yWkjZwS5B1&z4l@qms<=WwQJF>OialgM_ z>hWCDU1KFwSD8<|6W=-HY*WF*PA%`?3Mcn|EckWZJALB{yu)WUj)8G~m^2&bS0Cxr1;jbvog-EPl z1VF9m*px&KrByqy+>EQ_q3+?EiF#r3okQFrH=-_O^z=wMFfUzEVKSWS_ZwEVo|=QP zBV%y9J)iOWW~B|LdD`l)m>wla09ND^OPG2FRd34_w5LEJE}fl-0msnq5+u13OG-+( zebI%5UFL<$lmW@v59+37?oa){Oe)&y`jdYdRsuwZb>^-ivDwQ>?#TLcVFV_j)|M}3 zKa;nqJE?h?zw^!ygUOpMKKeG+r^XhL!O=OTmVT|d*O;63(c zw=mWZ zBCD3cp8^;)X0f@dD6z(-vZs6gd?D6dVn(WR8tsl#Q4KB&QUUj}iUXhKWd``TmaNCN z=S>3~AdIb+Ydhb4`B~0~nQF{$W_8*UVSaDOj|lU5O8&?kREpi$bDYgHY z$ZvUAEk(DaJP2xWwc^YrH9?Ub#szE0opsd*cjvEX*y8DerF7D5Aq9_oTrdyD$4;+j zb(FcqsIf`d{Tbf+FmVfqWK?Y>DZLGWHa{kgpEqIvvkx*(3t-&A*9^69ii{ zde5MURb;76VMe!nxb`BbFl>mgyt-EV*c%Y(fk(DI-WI1AFglvPi+3gVZ)F?$f*66f zHEAul2Sg-HrgoOFlq}DA$NEnEJJ9vZE57$^??)=aI9(w0=D&pGxC#^@zHJGV_96X` zRVFsE`Zv215VPA+k4vURovLX6ReS#Z#A1wO{sW1S{MPfziH)=eTkAar&Dgn{kcd?7 z>=J(gdP z4!F%A$O$s35*0rVP!#c4%iHA^*(#s0z5H=ip620i+~M~Lvzd)ci+2sM(S;?J%lS;D z9Y~fSq1n(_g$2_uHC3y`L^W_<`>L`brZF-5u!Pm`nE140R4jQS)ilMQKa$0mW`m!R zJv=_O>V7Zr1{4kHk+PJ;_dj22OM%|E)&VItlvs@(o;vu806nF_R zA1NKZcW2SAt#=%7C>8kN;>Cc$2X^=}F8R~@JPUW5qpz@;S+Cc>IhI@05@!7tWAZ|= z3I1~!YIx3;AjyaKExkiknnCjDJF`~Q)35nWgnaiX#kJNsP{L|aaAJ2;jj`F|a>P9n z$L)qxdsUKBtoLW@)wXM%_TYVd!%o-E48hUD*!=od;dG1PthMp9`SWdC$lV*H_#DS_qoeB@w8BKM#2b0?%u_xLLszbqQL#gg#7sK$edWFF<$j~6rg3&B>3y%L zIwW;4EWr{dp4k@uTq`N?h~hI9_!+MOj#_CqhLSy!UvZ@ydI zB3lARE#?eFD53y1nj(YiV~22J7SmE@zwBcc6SBI!7(^O&Qss5wjv-GliD$BJgAX#}c zUWuA_MpQB^(B_iDVyX6@R%{?=Rxz0kcCNuR&K2e!VAnez&cEh6L|jV1EKsi=?T;sk>E4o7`U001{a$K zOMk2sR8c()Bp_WlbU1VRm0)j&i*czE9c4>?Mx$%?3+c% zg2&ol?DSn@pWkurvsB&}|D}|%8*N9WG}eT9o;@-1D2G|@cRJcd>{CpW*k6fxO=$U;4xn#~g5Fp9Z8F$651P96+n#l0ZiT`n%rpG5 zCX`)&71&k6Br>wQ3u=K%ty`3iwC{)vZ{hQui9XO!jejJ2M12T|NW8|f*1|(XBIeKb zU|Xa*m>78zu~pH+U}A8ZG;mUjda`~GC5j$RsxbMaeQ_LmXRk+w1S)R2UxyJpde9Ur zCr5*9AV^KWVo*l{MR*`%sSgRb#A#r3w})GaJ&z2eGZQrWEzB>twx*N5a+hR`G18zk zv9Yt?ZLD}~z5J>{HSFaZN&(sK_O}~BjGK@9ZBzJPv6@}Jo~&2Mq5UQ9>lRmh%a`IX zS*`+FxzlX=`4)6x6I36~k??E~Uo|k#R-)^elNzbYbLH(}N*DRP}y3yaQ%#GkX%g zSE!e(i&>#>=}6JQLn=NKF{MtxR1WJ=ppZa0!9iyoJiN|Ou7sgj5E z*ObeH>qr`pSWsv2rEy(FE7;;{C&+@#+HRWDY(zhv90XT=|{4!RC-mBaH!vNj&)x`UpVoc=N$ z)kreQ3N?=zAmU_bQX{xK`Z}p+T&lc3HfO`yNmR%Zt=2IVs_5M1=to$Ny&c+MUTslS z9|(|T(0^!}tN%e{t*!;u30`wpY6x*;_Kg0ym5byc=9Sf30h+yuse6shS9?Gw>V7bM z5HsQ^6RjnHk68Pk)4Se}_V&s}yzV;Hf6_3`^Y@1T0g1S}WW-YC(GwKd%H_4l!~Vmc z*ZF+Mja8YfpFoQe{5Ph%UAX>?(oqS&aOIFs(*-O`FUz#b7_&rzUYy;mDfyvZH-gJ4 z2}gX-HZQQTDfY_n`RctPr$wx5EH9bnas3C=MqP^dk1(tI5=aY(d6KA*6v{6)*WNd3?OXPnW9*TB=YZcuV*r8szci7`OXAAT%oMD6 z(OeB7okn0+A&mc2iPM9%)YmJ% zQiZrLRH&Ri(E7L9mo5rkUe9XWwY9JgaJNU)Zg(|8&xrAQJO4M>p6>4Sk{!7rpNka} zUVsQ$;o=0nq8%eB-i_w(KL3=l&@khq8sxA%cfWt!q!p<`h_k@23;4H`w#Rf+RH1mn zZ_*f1y%ec5uVt#7iS!a%Ua^10lnbAEnXf4CCMP&_HGz$z2Rn3F*3;MWO$F&leP0-J ziqQG{>2Ru=R}Zv=dn=?LV3N(F-%HI)8^Bfz$K$a4v(oE9E=rjhNq1UqROCqu0A5|g z;|C+}YovMHN8fGG;3$nOiQz=PrqcM?en7UWogC>pTaLS`U;E~35B@^Lq3EQwJUmb9 z+k@M}BZeX$)@}>1PF2Z<{RXgFt7PZmGmW$d{60A^zN47&nn2BPhTs5zHT^oyxI*&} zlqBPk&yHG8-!*;CI5GloTDYlU;th*j1{HsgqjBkcSj2F$Q2XVNC}8lss?slkH~TTP z3ZKnG>B_@E(374LUHj(HPgkLmwYxsVj5_|9ncq&QRiw9jN(yyeKdPb zOm-DUcD@qKfpH2mTNRKk1>?k^>q5hcg-Ebsxfr9U8bNvtKR)@|DrXG(e^XNnyTRR8 zF%}-7T%aK;schkI78Vxr6U~;yWKvQ>|Nn|2Lx>66l6@z>9Dyb;^k9mbh^e4UNhd<`y6*)qOjDnIr>gBB?j5gf?DwMBbUIM0v=EZ-2#GE0z={HCnhChTzkN3D)NyL@nO zm28ofIDp-j35)=QL_Xf)tpiUjoOZxE5D#-KkGCtb^@RX2yx;~9f@Q`RPxw+-wFxe9 z4;0qwUv1CN+_lSd&3WbmZ?!Rkgtz#X9E`Q7ys~$*4}+Pox<40BkX52%4pNIu$_&}H zvL^Bw5G!rbmK31FD1Pz)I?J~oQVb3#eMi>ui5ewpBg>~O{6>nAb4wjzuns5svq^`{HG4-2Q$H4~TnTO{+o5qQ^Z5NMCP%CYSyF z#J8#IhZ=S$?_*s#IbQ}icDHrM&ZOC}Nq8zfvByH9UU92`UmQ(JvfXm*Gd!?kx^MGu z+1SoG2slh=*IvJ(d-bGDna};oO7+BVB>ff}_v$&4UO9X8lj{vDasuGCv2MsA-SM$f zW95Wg1h*cTNm#SVD*CQ4Dlui&KW%_UY>V+fTQJtwctgbUhKgb;{bL6JvhZUTc~NnK z4myaZ8i@w_IQ5hSYb+YjB4#r^`d{!2w2=9UW(a;z5(*PqF5W|D5{{hx3uB2AC5PED znj2t{oRQFk+O@g7JHvH;o%u~tu!3xAxT9#BzHck==<*Gv5G^jUJKdA2d(`tPS8=}4 z^eQO@mLIYvO0UJh9ji4!>|7C{%oO$yzm%s#^+fJrtz*u1_)b!dfHa`OoFH zU8i-o(>FQXHOfaQhsPUlb0iXWZg%K-EV(atR+-G~6nJkiYLAf34bbgxgydrItr1bA);MtZY8yJ1+KJftpVrf z@fT2nmG8Owwp(41RFRGAfJ~|3Rd}XV5A!=L*Q=6yxPdzSytF&ojf zmJ=cqrX6B35(_fv1%Z{QtbkQo^}3)pYjb}$UOXs8dHdawy_E3p7&|PtHP@F+aisL$ zP5Bd)k6MT=lsWQHJn&A`t8hZa(X##I5{t!G#Uwp}P0B4FeD7eQjHr**dsmoWfq16W zsHOdx#A3Yz=SWnBFo!U<_*JtBN`(B`U`i*x)#=s*@HK)4l5v?wOWa;*eOO}!ZB-)X zyomj{S=5Cpdd=Z^=4w-)Nj~@8Ibx5OZp3D)6}FYp9UGdHUI-kCN`HI{s+_T_mKbV~ z2+Ng6((gEWG1gL9^zYSB3xNc0Uq+8kE#T^4a~ti4A9fYMdOfQpJL4zvurzFRvjVl@ zWK0^_VxOOZQnbIWfmqh&^$sL-EO`PaWEb(7Sy@{NiqW`;s&-I-F*#@ZpM?%y30%uk zIN*}e=yiTBt9MNon|0}L;j>#VfuO+Dal3v+JMN#OQ*q{&rAvhDj0H87D#Ppri?-;Atq_C+U8_s%U0Gs(j{V=2n^^dDbA0jq#cC3^60u4r z{+<>a=;zl(sK3y<%mJ}FA}o5g6xRdn0(hF38K5wVDXKjoS3?!*AA(E(OR{i-yceesR zN%2=S(}$8cpB}Q&33eQnWRK9K+bAawDCsN7N4a^{?PnQJGz)OppS*cF?vW5ng5e4l zM8v1=vG*ZB7I5tFs~1G1ns8-Txt%KirA+Nl_PnC-NO*T=YgyE?M5ngX<6W`x`Z1Iu z$k`0FtIWlLQTN+cJdy-0@^}AOlFf1{!1#1u2XFpN4mRVHjCa~Y5u-{37#N#mv}5_@ zPx{5UyJ%@_qf*^>$Ey;)up*+S$^5s=C)gtQ2##OBz%6(%Nxg%qxE)Kl&-R9OVoR1CCQ|wv`55*&A4F=!MqYbDR_CX zsCiq3Jq958g7@?EpXSuqGkG#hC8HTRjX^zpuny1Mb{BS>Awtjpu<%BL0{9s$TAAm3 zLx_eRN=-792oowadUvwrayTIMk#PX`t^|CJX(c5kMOc7|4#gwy4^tOi?-@dFuRQ@L zG~4hW0Pue1Ir3kuqZ_2Hi%>t-y#cp6=Mc$&(}Jej;{M2iJ{76@6_)&@{3ka}_YUlj z-jkgkpRkbox4I0{47{BY;7pX?a=f{*7_YvMJ_;^wrAC9^`Mk>YAV-uPIH}zU%(F$T zh?7B9ySp6xl-2D0GYXFoFVeylM~DpsGNuMLV~ueP-bqr<=Y)D#ZEbCAN`yPF&g#uy zy&_^^zJLEdm{jhYrgaNA<_IUT@4ARfJ)Q=j0`1i9!izO%G(b%i9-r=SW3OkEjbD@K zte<9V4`%(X3kD#{8$?K};FA#xte`E8TYVn@=eh89;QZTj1Ll0PsP`_bhs+ix!9y`P zvN=9^CqC11f(kRx-}&kwO-=Cy?|}k&3fh0qB@b9-{Qze$t5JD&7*E^wmsC}`rloX=fDI(4$NU2s zY@zY_OZSaou4Bozx5l(dO(3||_c}U1XZasS`snEp4C?!@nt-;I1Y^g}&39x(pC-Z~ z`@TeAZd*&k7(%AGx$-IVeZ{9+@kJ;}z~t=E9P1pRcmqWcKNPVGNPXU@sD?~Vd*$&tW-uBWw3ateZw z!33mxntHzhPmm-LjTL#ph{Jt zL_I6|16PgkKKQdT5VK5HTgjwL1T`-=85w7YSl-)#MX-;ZeQ_@9X(l;q}co04LRJaGK>ye_)L!U_S~s?+E6491u;+X20AW?p+_+ z7k583+YMB7q-NL3e;c10Naj!oxw{d{k_bviSo2v?_iSdqaI8Xy<kk-4S$^BL9X;sdV(u^@Ybk z3RebB!HW$HoNU^j2;2ftjX4TfIfR#4O%NbQ)=o-SqVQG2V0WOK2p?xPurdenA>)=F z>Z9i?D7fT&VfZzAz}{SXP0{zsCazNO;Zo@7KsRn7uvpZqFxFf6P#$l?7`50I@M*Ue zxPiG3(aS}Tf*q?clFVIk`RV@FL`hAK-^sdGrttGpkk&`wS>(4x>$nF(&`UXUxt^W)Z(RxSSfjBARQ^ zaF)r>{~TF2eZn}2kO0t4in+%ju`D_%u98AS>u+?;`@)LPRls9h6_bf6J-1lz5x-h03VZm_ zVUo36yC~YJ>Qc;oHA?IrAhO>&jz_2nxy+}5_B;y6XgKj3+raK(b$wkP*f$jb%R5C^ zC0}H^U3|M?F-CH`6>!oNUv$afWT&t*lEaZMpX?@c7z}t5F{{S^S|0kADWa2Y=6iqn z1CwIBR739{_Rq6{M{wLtUJIh~>LP^{c+d zst1kSJoZSl6Vd_Mpb&6iY?FV0UO-_*12pdxx>;Z6m7%Pm93?RqdC`+u?^U3K&X)=n)a-OL(K-sbF)1iKj?1osU~*Iu9j6 zXVPgV%p=bYT2pKO*-UC7);(*HAJyND-7qu?fO&biQ)prD9{E(By7#|ji9>NkLdMAA zG;6Lq_3To^=~jHM6GutciQkz7D4%pV9WAXCGA(-d!=3304yyr>a4jUmayfGD8znQ^~`bA`ES!NX__Xks=V*?gI2tIf%^a z0&vE&s^+dk*OcvtO+z~Y>R^TW0Ldx%`bYsYu+pM~d)Wc3$7h2nT!Ql-N4<*3VAA)I zETq_r?wvx3(KKcE6_E^9e?X&<8GC0tZ=vk(W$(WGz#q-aBKvzCESO2NaV24IGNf+) zD(jU%@+X<^X|28oH|xJZ<)PYicEN%@2|>z08U`sQmJ!@9edg~aAiN(nFi6m-fKK=E zt~Z+G?Uc#`?z8)cWH-N5bLrWGGmvHMLrr4=s7(TQNKjF6bzfobAZIqnj9elTlk2*h2k zFJFq7mca_ZfMYGa`n^(*mIfKA0_La_(IgzDU_mllmKrd0N=ZGoABjUA{2vPtdk+18 z&I_~PMsi`dj5;UzKy9JFH2;`oGwL~#(evBts>7xE7N07y5&~SD*uXrbJxkvX80g79 zNzlB~2C*o#{@#w!uF&Nm|5#&wF> zOqtKc;?7xj%cY}jr=yMMx-^a1A z@7YLik-{l$y6>4+)vtU>Iy_9Z2!2p|?7loMGL=-&84r)k@ag7$LFdrwwk++m&^lYa zyE;b@&xb}=F`-J7hVQ0nVf@-__xo6*fvPpkn3?o>AujH@{j6e)rm-6#EzubPy$LBU z4kijl0S4aoOqHu)r^EN+AB@+9MeJr0Tz$nA8;xgk>~DT!VmB?+4cXQJXSqC@3RkYT z*@n%GCd}e&#&xBTGhfN0+u~lTK9v|_hkoC<))0)h;9PZ%N=3NO$cRctY zkD?IBj88KGO*;s2&@NG@MrMCz+5bBqo4XIjV=nfq?TZM}F1{dPCE=mR&r;k_1CYd1 zxJQiP>Iavq9@-cIkn3wZ*a4kGx7V5&#;$M96zJ5KmczzdH-k2#DjDZYy=2&K!Oy$e ze6qmIx*jAQD?-{n;+YY+c(}lFY9sF08NWxgG`5!J_*vkW_&0BiOI&XpNVrDsmT&x#ZdbCG{L z(kcn33b~pWuyxBAzZZt$V5%F&RllK>A?-$ek-3Bx#Snp31@fE^MbPhL~%M$j2Dj0hlGhch0JrY8B#HKnWzyc*ppGYQTR!n zGA3>gmX3REeOJmY20JrNPs5m~(CJcam%leQOeXw#x*U*}o8y+znQ;EFLgg8xPuf>~ zQ#ytXfNvBpyqkxQ-{pno6;O=1$Bz&j&pTi%Fkg<28X?Ox!*_PKsEB4>O%o4dO4o_=&O9gkq%vm6#fE~}O#Va)S zZE)VhYNw~M>_#AOsPhy zW2uNu?W`seeC>HJ<{lOkTug$gap8C**gJu6W$qhspj!d}iMHjeM zoId^PznP+-sTjkNwc1U?3!04&Ns$g`jmF&xKOGb_>LcY{tp~m~m`D+I`9&=fDvF_W z%hX+>){=yy6VTL@|3lPUMpfB;U!ZgzQsU69NO|ZM0V!!|5Tv`in}gEb-5^~O(jiDU z(jk&kBB8|H{NDe)_nSBz1D_phueIh}a|YcS^l|qRtc{d}(JFt9|8cUMbhL5w$G`Znjd&RMf5$RTj-%*p%3BuR&HLwV6 z=dET!9KkxBv2K}-0;W(T5->F>DXqIgNO;~kqv`q=A3m9O71+=ncZHC9f^z8V@cZV? zf~Bsdb)=Kc)k`r_OQ+#oB1B$14^M}gi1;fy{o)Xo67T`Bn{1YD3S*XvI3foU+6d=yXP0<`8&a$w(NEw_--!TzFx#$K^{I zaenx>j?our+Q^c+q4haTNiIdv8%UCaLWNS~;z2P!rTSKV|(P^?9;!|a`EYoJ6=a&_cfSujzTAI9RHCo@!uQa zi8sxj!m;UFQa|aJOXAe1%M{gw4%vTeQ-k9(VKNen3tq+7hb5TgivYgo4aqS4@opTdZGu!R51(+;T-b!wI=sl~=qi(o0;)Zc+2Cc9T` z-ZA2SMHxtv2Fm_{mnM-WNfrvIvf%AnhfHA*cE58DatPOzim_n!xV^cXPFO3 z1%V*$qsV}tG&Kq-wgQw6hg)1-Zwiy2H2fp%C#WE(o~&1RCYrAS(XY0=>r4&kjIj7^T%SKpqQ%eG)71vS z+}o)#YE`OspW}FF_S;-{9EI81i>P5~gx)`!qT(JRx;E4G9}rSc15Z;BqEZA(K1xwq zF|>eNA5EgP68D?BXpV6el`Mp-GLVj4tsJw8YG3IMj_dRj-IO}ZPonv4M1ZXy?^**7=ApVvb+0gWBFVmRSk)yQ|7vJ!L4b; z%TgCQEtI%TN4X=k7s><)dG%QX?5g+aMqu43kR27kly>u#2`-9D0*!bI`{lps1nPR^ z{(@ML*5gL{+4)dgJ>*wNFMb`2UAl_Or<$5qG%vtAcI$Ssz%KeprkcK#v>F@xH_UYu z+Dvajk&g+n+Wh7jk>XeT9?ATk0p*A2=%3QC=T!_hU#4>PD&-NrrM2EtZi}Pk@{6?4 ziWHf#tm9?95K9bZA%_yexuU|F3Z7gowm(?f4WFIEBEvQbuN9K$!D|k76CYGy7?4s0 zXb83b5_#gjuq8?c&+n_4dd(Jxq4+cG+q(rfH%B5IEeBDjeY-eed6sR5qHT+smd4dn zYul+?9m~1Km%eu;dD6fBa!?HZvC)cSb$O#+q5EX}=>%@QzVghh8T}i{g22q@wB3_o z*b+9FZCae&BHJef*N!F=0-B*Nw^aH}t@))=^!jhD$OaWM*e?0XZec}p^!#~{BV~bC zo|2!HWCH2_8LqFyIWf5`QI(3C43TphBX&5_+g@ z!11mEpLYiY_8xr5v_wQ+&=nT@a!dNNI1@VPQzE*Jos(8oepGl&Bf&dE*+_=9<;IkP zLx%i%_m6n2hO*r<*AgS*cB>Ycko1jE$I$8oA(A`;OC<8Ok=a-${+rGsY|*aIn%6H) zviOnk$K#JXLzCNJ5QG!u&RC2Odj*O^y_da6&~tyls5o(^VZMZ~+ec*Ll zF6J%k;5!nHWj~<+QDCv0?nJ7MdS)Q|imhs|_gin=go|~LB#ZwbK1Rk<(Wwb+YLPk^ z8zP>WHU`?w?WQ<^B>k!ASAkRon54XtKYXe!F_%W9dt(#vNmZKe#IkocSShFd>*5r* z{htbl(lMDfR-f?ST5r^FCx!3zaF9m+@2DW5GRiw+^fx$_KZo6Noh)cK7?qAG#ZU=` zCP>|Gw}%r!&uJqDv3MpY2WB=jL6mivoc(ixV5Lgrh=+;-ZTl)T#9YbT9m>3NbhSV8 zRn~BmV}Kgwn(731r4-u7+i$_VotL1}dJnWEt z=QoRThVrSlNbb}uli3-XwQMLWp-L!bx1zg-WV;gv6g{Z$#k%BN{12S;Vog{saJ+%=}U<8uFrP>P&=|kv;-AEhKQOGH-*uOGgTQC zqiDVYZ>8_SV)(pkK{1w;+YiLDHT|5n((YA$a&f{^YY&FpWu9)|;m9 zn(cZe@!3*0aa2Pvj)t7y6|@5vx%!s(sKf6W@CW-F9n;jUz&Y)2S*~6QlON2hZ?k7aCVEMoAzV zyoZdB-QoiMMOWLok5=4lMym~y(BudcK}DXeLDmC_I%++q0Zb z-1ri^az@^^H_eiPpNy$f^uPVqTY{x*0po&bMwNLi6J@UZpIz2{eZ2yOjeGyS8m~NA zH-@`weRlcMgq+w2{m9AgmMfr31I7%}7guL@jhCNKItCZNdu;GuapZJ)Vs{NUsI*#F z8NP@{gNMMQd!`uB>wJfivf55bx4!b@1#miB20+LrDV8s(C9|!GE0Oxtz7;QeXa{7y zbVIt*;1X$53DBx%%V@rc<(_!kVN7PbdYk#(vvkZLxPB*~f5D4u^JBe1qk{LAY`bmk z!;96Vkqdmve|G^;q1xDt5#PSCzYPN(aY#n9jkLW> z-X!9Bb&iG~cc5>~pqz--`|Eus7t^Q-)WOy))1J%Cb7?nkalEIjUiT`gd`+4!cSmk6 zr+fkZd?XYMUR$!6abAWJS zBKdjwvpu~_#spGAjzGnJ(;uUNoCapO^R zVK^Sk)q(uAh!s~-jS863%pi+jY88JEG72GRu%|rxp6GZn)T?W}}e(!=k%akz0*kqrS}DA#mMYRANq3>r9uaE*Iv; z!J=MaenoCWtPr$mA(udYI-;w&UV!Snwf^;CYvT+XOQ;wN1(M2^5!pOOvDx*oMlVw> zf+iyDei5hoVnXYt*7q05>yL!QhYQvHYofxOUbmLMdPM>e0b1m);Y#sunQp*LG?iVd z%M7eqW$L8X;Yx|nET_K+M}w1bnfH8OS0>{`0`r0& z)|GQ%ONPE*%|7wdDYil2Ss)o={EJKR!B)_jt^=t!Bs>;}5c*U;2WcWlRBCFgIEla8 z&sHT4=KKRswcTEFG>eZwDk4=qzktvrBsj&xe*JBiL+EDVon#0|Pc3-Z|LG%A3f1DZ z=4%ARfgTj2H3TLK5hdM89MaxD9zT>yFoY{)6|YzjTk`pc&AV71g|Ln}g(_ z9ik;gK9`uLo>-pnfVr;!kdD4sXwV$#?!-=I3K(zyp-P5%JqaKa&3rn zAAvtYp+Nj<{(}JuRQiHA=`6ei2@*KIOQ&y^#v{2RC8=g-v0S1@z_1yrT!#wzy)$Cb zLWiDAoX&|2OaZX&ZhHR$O#Hu`-b019u{XHI+P>$b(e=M{HRdca;g=r|L+o7C1W~a6 zcrMucg&zE>X2B=LvADmLVH%6rxlmUKGKv<$0V2y1sPkBcJ=5=zmma-i&rKDhe^v?S zX|2-*1=0n*T|2Vs=~x1!PGZ_ohj;QG%jVJ66mhj45BZk!^&MwEddCeZ-IL$ld0|n+ zhYXdvT~z7oOv;-A7$Pt3ybxuS-b(=HhTTC?5FM-Q(Gmq!+XdIbxkI)1owxDD2XVBG ztk0g&XFfQPbYAa^Yb)~&K4xr5-J7bvcIaD!(H4!|=0ETudoyF#272$#eI&l!wsO%L z++Ke>Kd(4zV}iL#KRS};+kDmBTj{`CayuZ%>&qn_rwcfay8gLbpxx$Ocy?u$@B2OK z-pVeWKLD|iW5Lt$!2pgcrd}BVIN8gyZw(%++pol+uhF8(XT#<517J0qySo;QD4yp( zFs|a`U&aaC?yRQ%T&)M7-|#Uqvb`3(16Z7%98oQ4OjhdXKe)Ml~I{opT$+aiAA01ANO0o-!W6lTcNpmZ*F>r zvPJzqY-gkLo`RW|=Z3X7%U6_riKP>BF58l(BT3{lPSPn_#9TbuFa%Yu0?e?UkO7nJz8{%x_lb* zTk6D~s@DEDb>H;pbg$!diz?iwiYauf2{f~%k4K*q$OLizvOZ#lxi;&A+__hPWTrsB zbHVO=(RefB`$awoIN5AmpIrsC08&&G*-Y)}7M&cB zF6a?}w+SR%`~ceegNPFEk~Qii!*SuoF0WZOL2@(kLa*6YHl7|8=q5a&-|xkS0`>h# zN6r#Af0eLTs(Pg}&e_#Nu5u~#Se}JQ0S28xXm)6uJ$+wEthm>Ar$#gAhzB9|kpeWr z4s&MmYDgbZNBE2uuTc@vbMM{OujB)#>b!8&AL`QNdp1L4Vy7x1Unt%C$0Me!<4lP- zFz*W4scRLzIcw!#BXQq7VuLY$8P2$L>Hly^!(lHM8*BXc>y1mvkkk_4)RCXc`r~N6rwYncvsZ- zs~^UO5|ni~r~ll{-cT5_UFRbQ^k5{Tl=>H%!~fNpr3?FHAS!*X2nkb2ZxHfZA4Ub` zwqbSP0-~h(D$}Xed?lG?jX^YkXbS*V7;Y$G!0io?S+4KeOndYOJzozR$&I%Ot6SC*NPBZD~mF%5O zV}*WqZ<6QYe*Z|IV7Zi%pcHl=Et7_-0%mTJTq2sV`w^`2NjbxNi(37dM4LkWEQ`^! zAb{5c1e-!OjyC8_C@91#MRQe*n{9^03^)*L*PDKv;%n%9%c?8J)xfimWb+C6ms;uJ zLJdWV8Xj!vCI`jy(IAzwH)p>d>jQBOXO)aUk1WN{wdS@q3s?^$s1k+TNG2-c>FMpggBkwsT7p>Rm8z^@z?2ItqfsGvcmUOVIpxTw8NE(F%r2?CT?G=!M zf_(7ZpJpn2c-QJoWiXkgQkAw5sXCQKQhq45&4cGsQO8heS70$ z+H^6?lbSme*9JIjPW@)zNwGs3-3ui5Z04E2&F!X2kXI(RpiUEMDZh zH~3?z)a#FUS<6c{8{X@#R+yoX>tYcQ~U|^7Q?2SI=_|UHzUVyVzRK9W-CP zmNYd*@Ms#0z9t1lR`2%_{yN(;Usu~1qLF!9>7d}S=w>?|sQrrnr0icK9e-wh=s)#> zL~N}SvUE2pRQOWw2P%ZwDN0-IpgRI)I)W8AY$fL=GL05E}G!W$VtH7e|&fXWSXgOz}c- zblsV*Rdjeo_CDUFv??V`yOt$8bufDiExLQ1G!KOi#^4rG%j%fW&~) zn8g}l2uJj*B7z)M8Gn_0*%SVC6v#?H_jn3#sx%IyRXm&5CMCW#IYoTMm5^gnBEoJe z!UYIW!FT94>6S}Kz_pNkmW%OLRDlSC-4L49vy2P}N;h1uMA-vwzU=tKOyJ1iX?pI7 z2M+!Pc?oY$G7#xM1RppJy4!2T3Oxl5D ztwqfX(95^qy=D86bxkHa;zZqYmOk9nSd!kn$k!3j!tpK_m?j41B41*yR;v}iF%#L< zd8&|Rs68c5fcixdv5iiva$Qt=CZ-Zs6W1=o`fB65<~Dm103nBv)6$q)_v#6-o7F6l|HR}d!h7fuH4cGU%R3ovu|0wL*>T?zICN1HOUvofc z;%+rXmpc(uXt|m-$SB2Du-0qWsG;@r?rpuJ0i~F`KzD}PGtrN--EoQ57it=n2CcIn z2DI~SRT;{^X`t2cbv?*bvOfmYYrUTBU5E zJmP53bR8qBQf;AQ!uVkx0gKRdWOFsz8I0AmZggxwhq&ck_`FD? zp%dfj7c{u*1eKWo7bnpMSw73jZcB@`FJ6cgD!Lyh2OcwTMK&tj75gdW#?zG3 zWRjPS$3LWX9GI(C8$xqeL|lG(wuT$0j&(X1G z{GIRA&~6;&Dv~#QZAYlm7qDST78SxQ`0;^se`Yv_|K9u3#IrrNwIUu056X(ufSdG zXFhTdWv+&A^Z+^RM~}>}r6wGC8F+?ae%RAo&c=7<+8ETnlT4Yv4e8>*V`A1V9)Sio z8H^Gyev^#!ca{^oY5+Ey%TV&yk^1s478dj^#la^$4FOGSIcy)@@ZV&%irh9Q1V~~B zC(N)SUO`@qO$&~oT3p4=m=kfbL}q+lEFzY5q^NDumA7r${*WX4JN%@NuWgy+Zgzj_ zCsoXEW{2he?wILyy6fGPO@ejKka|$SbeQTF4=>#QA`SAabbfoWxFGCfWEqC)1605uGtXD^d{ z(3G5cloV*Chtvn`mbT=RnbOV9u-q2^jMM)D3QgadnmFc}VP*&QpMs1UG^r-r*W&`+ zk-DveByqnH1rm}>x5YhJTFFJqlXxJ*FL~ySxn11!cW~bqdCK)=ziZb%T<}U8 zIU0?n5$nAWlvk;Z>)K&)+gtvGJs3+Cli_xdxk_5?O(Q1^>Q|PHrtUb}xazvcZhmx% zH5&l0Gl_LGr!-Ph$k`f2ihRiUvt3D>(IMZfJNPc7V>4HQS_JfNPqBi#I}R3oY{`c5 z9>sh~L)qa~t5vZZT_n5VUfIhYMEFr^T;Qt|5c=G~zZukqsws7^kBO5A8;Yr zg4#w3I=zhgmPRs>yhzVqs#$U>rJB4f#e`t)SSpUg(4xX*^Us@WRNi z+VK>XYpDRnz$DhXu91kiZl#{J`Qd88!Xf}{ujOr2^vm!P zk7OT%Tu>QU5 z_!B>$)RJj;+J~PB&s^G81?^~Gy9`XP7ih`sCg@J#WVrZO=XA|e##a3?sai`hE9_(Q zsTcM`)6=7|2-;lHnNb({GRSF zzFq7b5UU)xWn%d_5BKKxr%T$orXTb|3W5R12Oj$#;W^F$wVM`sq$7p>V5yS z+@~ZB%PlTnKXZ|p20F4-|pa^M*Ju_Y$) z%6@czYY;~upQ?wAj=CyH8{<`L`R+vHc&pd%5+hYvPg#BmdwRk5ZDcb<*=J0xN{z1p zD1}LmfqFwO&bIA0WgMRpvvNAam8cSEhq4nhdWHeJNcn2gpHV7or+L)MsHP*2-M2wq zS<9}AeqI}jF6`>|vmsV4(Q-^-ad2T@b5zYr_l|Qm1XrrN4~1GJ4M6#d4y$c*Er=Jt zvy7-QAU9uG*|ToG(Dyf>L2gFr8@c^r($^G2vt1R_i4!4`U*L3RN$e3g{ z7?_&1`k9Wn`t))8+*X3xH;ps5pt&(B{8ca zFExShrcboE#-%dsZbH90q4OIYWd=%z{+eW=itGzk#q;fY=zUBnB({kq6a4k$ddTqc z#=|#;dx!j}xld(3$Zbng{HABVJ^yqo{Z2AiNq+?uD)j03SLJSDhfCMnQxjr^jJoav zzu&t9zo9S7YTo2{p#-eA#F!3uy(+I4%hUOE`Jw7q5OnvLH^>31wuA^5aoREuBcWr&fa43RN~$gPIb*l7QnZT`|@4Daz)*Y@O+woM-B@ zB*Rg3Lkrg;pHU&-Umi{lq@%+`947-4YCy`^Mnf%oY8V`L{1qielf>HQ5)!NBy=Hl#JYWI^wV7 z^G3YhfY_)S6voPI);n3$|JtXFE;vVCZ;;B5E`vZ5o(k0pXWW9!iUb6 zRjpDMEnM!At_FGM@^e7hC{EZ zP~NZjKB?d|AllZc3nhjzZWJcdHdt_t6Y~e8bjNMep)j7#$mv|%De;R3iysV+z0_~C z8W=voB;5DE1{`Vf6nLY(k#ME5JiT6b+(uw`AW3NBJ0pt9nn-swbCCwHsXFfiji4gw zMUfa)uN(u79Pu<8RUmfV7I;;Wn9BRkmD>=m;U`Z7r#ezooPDdgN$9Hb(i=nkxX%cy zFsgc9;LN5)g--Y(2?g_z0Ad|NLZG6BZHXCo5M%CuulrPXT1t#ax8XS(k}`GuX?lOn z>;yGnK(~3a?+!X*&A*hP+#i`Ldge>=JAK6T8N{YXJGybnl?i5=hE3fz<(3r|F7`jj z^=L$a87c#+3y zp;~NpXQF2zknC!?hci#34sV{q(ztH)H@B{TP zOwTLbx!14Tu-Xi{4BMl{NJ|75Cix)~qxfr)&z>?bKi7<470L!)+niWDU zngIGBWGC-+gJ)J#VKHa2n8;SdIif!9g)EYEuyHy(+H2oD8y<0n)gUV>I~;#b`4{@B zWHPa@BIhR>=^4`+(IDSJ>*v;llD5tdNs`+3)I!&%VNyQ>ofsw4HGInm_5DJM>t!I_ za^4|Vu6}3{WjL?lp6q+@H=E3OW}f&`uZAT_bz`~rA$ah2m=H3;;KLz_Ln#TZU|kTH zKC{%i{^7g0`lEcmZAo`J6NV6H_H*%gC`T|F2`f5P2Z$mEikX|`$t>S|6p$d2n`kLdMc*LG z1m?>qYCqkML%KAEPFKXuhlSR&K`eR{9yt^anj4G5zsnZ94QUmAK4ABDUpbz3Jk;Kt zMA;5RO4F(adqR1wFwNQDg@;g-mYFKWJ4qt;am@)=grL*#l5*D^3>C&t8=)UoH@jNsnM)w@!uuoiAePcPNy{59g;HCx~knNem?*TSuj-d-&n zhFZsmX<-6A;Pc#@uTxYTO&64+vM*1omoh1o>{E^x4e=6@nAdB%A%H7(gqd`S@#FTE zOz2l^q4?9-D(*fty77sJpAnFrZd70|$DSchEh`N#Wut$>i0W=KJupe#?kBj?x9dUlw0kGZ_hXmTA_~rSX zo)+Zu3ShIdkp(R9Ks(A<9wCaFFm}LXl(I&>QM-$0`ancLejl>Z3m9B7EDziaZwA8!Jib5F$`~5$tvIbTz+7O7 zL#GXD5&zNQA3wfUMd$A+GguJsS?6!265;@$&!??G=dr?s?3XC=TeR_U6QSU_yMjkW zLh|tqMwqo)qj~1vWhk4!>fgj#UCy5WaJWP=@jyK9u--^+t@YgMRzz0^I?huEgS=S> zhU`Hb$8(trh;!ifWn2{oSlF9g)4aU+XdC!Vn=^YPW@P*)+dWPnj&`{V&%Y~cAu+wX zdV@=aa?X*O@RgS*L>QQ`S$bgfMPT9=Zn$6Ig_yEYg0%bXH`BKVZDQh2v+A5)V#L3s z9+^G(s3Nbx2T<33;0mkNcok^0c);EvSQ04QDv1emwH^CXl>%a=ZSU7uWIcS&l%jDC zD(C2|x-cv+hv{Hud~z%i-wPBemd1XHmzqrjT~t-{Pm7ROP;LN{BEc}5{Z@UP+kdnaQo{`lPkN}=F4UrKsmE-Bl-tP z3qi7K3?$x;m!npN5CoxiW0eWg^n@mm)+=ca?9MpTqt zgKx%U9$t!nWchV^)Y|pw6GND0_!Ajd9>N@1ubM#Cp!_|S|0tLnqToMvk<*lt-X;sy znuG9dhEw??2*^^(LxP2shSUdo1^Mp3miT-=RueJ-J$InH;QFf3@~6|BgpuWR5i>p= zk$}rFm;c-2;V2u+n#p>{KPx@vwQ&ph&~er7)4V6$ahykJf5!(2lj{V#B^T!rh}bG` z{ft~~^u7)yP)ti$Ui(#X;OdY|YkuT2k3I}iVCich`u{KWW2~bDCmKzLw{`H-BkDaj za?+egYPi=d&w%Vx8u%Q>7zh>hc8y!|1-OxRgE@|69m^xn;FcIhr~=6f9uvkZ7jUi_ zMWC)a-0F`huBS?EO1JFSNi|hlt$A>x_~jEl&?;7gri)w9(^#Hh^m;u-_B{P?dtpq! z9&zSpRZmE`@@N$sab6TTFBV{0MBlHHx1zj7+cj`0t)-nGe9;XP_{6gCe*|Ul+WEX9 za(s(;f&`CBB^s6sEAsXPRTfM{J@sX_YBv#-TEr9I=jyo0%L~8)oIn_#!KeOz&DzTD z<?vDxkE-GOj5*abS*4#W)pX=CN5n72hTp!x|5MNh zYEkk*9INo6+-Hy^GeMsDUm)H(s@=6;ZN$ebFm0Be5#=ca%En9Bk3kd8+GZ?j0fJCj z^p5qv{Wq)tLo}^4uMwXSpK=)P6$!i*T_JKT9gFCPK|U{cR|(H|*8*58O~i`}JkaKD zU)XgUyVE#LddJ=lRY@iFd_1YNS?HwWTk^dyvcg5 z7wEkp>wojK2tmV<0CH#9R+8hOEF|agDf>7u`|bbaH%1K2#S`c?@*4Sg#Qte^;PX0$p1wIN_@{qNY5@k26G9dQUu{ z@o4aYNYbw*ikYME*Yc&P*d&3~Lyw6o?FA9^r9a}&7vJ{?vHKjl9P)e7d_P3X`${@= z6BL;t!U;_Cdo9xdaM9B;)d$Es42*AX)29ym(66Qd$;ffO$u<+ z*XTB3p?qA^QXfQXx3cI^CQh&0#>M;Mtu_VhqJd1e!Kc6WQiJ4k)I`%|=~x3~5b zkNs>jJRTLwVg{--{|Rr&u~p&E`Nplri!FDw^*ckvMkTkB`@J8?SV?}e8$2-@WJ4wf zvl5e!(RS~EwaO05vjN>&V**DbwE`~^Rxz3x?mp+WGoGd6mR+-V(fW&psMP`s_>aayk z8{bCvP0Ekjj=sSt%3wslHYsMq>z`v3MM{LEH(fWHAn31gOlLB0%s(EP!=3n^*22fl zbJ8$XIDVW5^U%e)B8x{&IK1p5b<(?7qcc#18ttHm^op%M%4f(8{6iSe~q~FMwsp zRq`g(SxjA`T}gDZUC)P7)OQj;CnX?6=6drtqa0_gvd3+kIVw<{4S(^rNFto0L$&!f z)*RdQ>X<5u`XvU1zg|d}!#k~75w5qTa^Y_@Yzo8^Nj^{t)~kvsPJ6=jYOHk54mAs_ zo1pNT_g#aH!~WWBmejx)s&q}hCjR<2BeQBfrLMd6#^i}!^Yo6ji`@NdLea_-PK*k}C&kv2qVGfa)MFV?w5GV%1 z94>jX?(T>Ty1eZwWj?;OKK|8CYyaii=;~>F&Lfko0&L07AUT9|sh}tCQb=t7xbnq!T&c2cF?0ef}u~_k4Z(TR#djYghI0F&gG) z7A~ZFf3Rg}og}_*gkO@Ql=?ZK!ebxqNXrxY#pi7WiTC^?G=H_x>cgWJ>)aCS5sqS9 z_qplMEOJ@%k_p6awNbB*SEWA3R5|@Rcz8q{Oveu#?)={e^(Tb=-a1GgDbwA4_T!!_ z7s+ViY`NxBt;;_W)M5XA(9Df$1KhsQlUhW9S_l5Wxa2`e&u7a1dYv82v3}~VwI7Sn z?s6|i@|QZxMlu7^^ZlD4|2PB2T^S$fnfQ(cJ}lO4L+!4P*ASoF`KngFw)&z@d%XM8 z?rgXev({w!DdcDw`T5)8o*YSw?hru>tla@859?*fcbA{i;o}|n{QkZxAYeovYH}NM z;?jstRmxds3Mv{Gzb8BrbtZY_0Ez{`XRT%^Ol+3x+7Zo8o=+}yd1wJ31?rz@k?%aG zi}xOvy6Fl zKHl(vXofAw>M+%tK%>`RLL>r4$pJYr1p;6`DbQ(==u+DkCpvXR#em2tzKaq)d>V=g zE6TF-iR!r&{W_Y&4k%gImkv9d)-o&mUcl%Sm>sAt^6Z ztY;J2_^1DXf=Yqkr>A?fzepQTR%WjKuEyr8aYGFu}~B{~u|VQSlNLH}~(%_1*ZdOx0Fj z%-QkIXPCM$K20u7L8 z$ic#sLO5P%%{tL+nZ8)wYK2%zFLmF~2$G=x4de81J(za;40Emd>6H|n|x{U~_`Xe@tVMZlv-)r5jR2x$Dc&jX0 zI;)qzpaVKBj_0qT{5xj-Bb(VuH5!JmN_s52N&Zd~nz~!~P zUiazWrcXnOyvfcQ;~{_aF3A-MatI6RbITh@ZXS-a!;FBpK&{=$*(?3|%D1?g{FT@r z!nF$~wcwe~Dojc%o>l5P%25 z^E&2a%~)TQy$Sg^A&M5MHR?}pOM9Wm4|Z=Cm6mXP{+HbT_-NS;GqR-#*ZR)mpSL4L z4mBUkd6Ma#rdMHQ*y8k0oMAqP1Ju1Qk~c!_TOUc#mwrLwi~mPy9ZLSkTIqv63ur{| z&6GbSq}+ZKBO;3Yw2@|Jlt9!wWAize{!LODVz=Wly_uBu^hyM*F_7-7dixR{Ajn6@ z+cNpV6mwBiR#FZ$LeUp^LEelY`9jw= z-8$_#%q2gJB> z4fmMw{M3m?r38rkn0A9lE~qfyi&MI3#z+fO#Fwt;# z(XekTP0l=ypGmDU=U2M%vSkPw`Xf9M?aoUCu`z5hoAI74QzscyFWFwZgXg(U-L_OE zWKoJZ(QWuyPV~lcj4o>!6F+qtP7x)2L!=1?ckoOaB3jdS^qtcuJssX;K9)>e;GV!0 z#9EiIA4{gNNNU8ABc)8@k48{L`!q*r0YaZ6zJA+iUo=# zXMv1VgEz5izJhpv1lj72i$yTHL~oDD&yB4eij9e*%!jw7vcVix)^su{JW3XpZl-x4 zKB?7>yBps|?XWCY1wT9ac?6hlJMz9EPsNgD3LHl#k3bEOg8-pweMVWnjb%9GUvD8> z&31P`*vjg0IweDs>DJ-6#zq`l^Ab1&Mf-=y2%$nU`Kv>~G?PxWaM_cvv^KSHQrHil z?D@D+h@CdZ&#?-^IvAb&0s=b^EQ(qbZTx-5CpP-RwEYXSOP&_c(^Sf7j{(jGg^Iu7 z+At5azj&8Yg(X2xp029ePeesCKbDBSTHuase(JiQMg+?QMI;@=h94;%s~|x-HsIKU zM5s_SNuJi%L@?EjvCPkwtA0e6WhfXAUXf^sv<)gOf``K0-nA6X1fsCy4e>E2g-v=b47NR#I(iv-$BEpTT zT1@U*u^tC|$iQHa%+(t5WQBfe;Q0G4|7d3>tgXFGWbJk*(sSSBb={iN1IjO~ggRf=xMeWd?ciDpAbyGQqHvG?3C(v0rY^Ww;%Oa>|}BDN?q z8$NWxMTc3Hi^EloF;1Gt>A6CSdy7CZeT4=_?nBN7nnP#pfiSkhEr}APOllw8Y)=0U zz*Pr)>lOkE=ewUB9~_X-wK()po)+(~1~B{Eug%vDr06~#I2LfnAjCTCsVaKBG)_4;ZQm0pjsaBs}F_@JK61{G`c`=IZEM=csT_$wUhr~NPS^6uo;=Co^= zL1=R%i%g=?xG}?a$qD6>O7PAe{xfg7{=NI9YSi9hy)mRf`UdvePuQmpLDGU4JM%9< zk{<5=VK7Dh=qrxg)!<4(GtBA?pb_oQ(2#dBT&JE@BTGQ<8i^ZC$Dz8$mWJ$y`@Say z8oN93+*hfx_fl_QPw4_aJFhk)Ai9>AN=QECI#cZqSkK9Z@6egNsQzC2WUAms4-)KnML3$rI>H_&(6&(DdAdWWV@Yo)H)JSbWu(`?xbqxu#tozw5&9}J+G2i^k<8LW7 zA4u$k=%u655beNfnmz+YQv-SaqI2(PX#EBi7Qf7hL^|CqC7&H0?4)&>vPbx9u^7G+ zVQIPIkmm|2tNF&UDx+gY=*uO-g+`v`)QgaSvJqFrVfqg9d`h8f`3Z)F>eYn23LfZb!7V$jgTMv ziw`vX&Ez!>wZ`NITAB%FHttxOU0=#vMs&;W3j;3aYnhLUNcxw28FZ%;Yqh!e`vg%9 zI=sVt1!uM;i8CEfHrJ66z3hyx&DLsgKFR(MOC@`J!-j)gwsa={csyFrPlIwKMAnBqi_-lX5*pZ3~Yh+=nSE`9OKy zRrYB)Bk&${{58m)^l1*0vp{Mf$L-tL;zwsNFGBQbcCg#KeO{?HL(pray6+p|6y9(G zV{g9^)u~Q_GLm=MO5QV$cWos2?JC=XRKkTK$q{95b z%z$#DNFFXXeSliC)rY_()IR-33;Q(y2UGyt*6HS2aTPL`s_5`jeU27DZWb*pLZao%GGLmNm1 z6eAt~z%35SuS{SzR1Eqrb=B%80Ot^$2n2sTZ%9Tk2@Xqv5&LdE^-OP#=MEq6_oX9I z+BZSlab3{!pb>A+`R1lW{FL>196zfxo^2u9#mm4hGn1kE%ew4BJqzt@s~Oxrb%{i7 z;G^0$I}EYuhfWo4#bRrzRH-_+AWNe+)>oeE=fB`=^k^`Ax9^n-4%8Q39BXMQtRMa9 zYR@QhF1n3OCi9$rzxtCt&}yFSEX|bw8X6Uq1AXd9DVE^#G&LVT?{PGgAOOb<%?K2k zeK3;$hpn#wt9o1BmXcILY3YzI5v032r8}j&TSDmuX#@r7?(P&2q)SS=yS}y2bN~0; z=X==C5e}Q*UTfB@S+m}mc}J_>K^)2jsTMe$Sro@JlE5Z8ZyNtBqrteG!RrQ#qmHxyL3faNJ21Nmo5J8=te2tTXu!PxQUWOllfvo?HT|A}k0?%xj`XdBC~qpz zWskSDOlf1NQzn)ak&^0s)c{j-g%97mXMJjvuQ;o!-94K0Qq3!TX{22EZSf?Cqxqsg z!=AB}I~T6SRc=Wh`--7=Aq#@83zs)h>VL}M6(K`Y7N}d;hFpJ~qzFkU>A)tZi$zfc zCx9^2*XK-564vq+g-Vm<MSE5T(hK|VA^H$F}YrX~2tc503 z>E`M)#^+y1qG>13;BLKJZ~07HS(NjVzTpbbx~~g)O&~+|iSmu${UP(F1XTPY9yRmTrMl#L(Y07<$JD)tMvL$;%SZso~J81!DVx}6Eb z1407cwbTU7dD%NyHXlu|^e#Aeb7U4Z#f3niKCZ9S_0y?zS7Px^AY%*#TTH520@=&q zEbnbUs08mj@nNE0oBNBJIL$pCmOXj7ckEVpUiUBkxUhq1(#aKI zOl@$S81x=hRW%96gt; z`r=2^U!6 z7Lc|w6~-laKgbRE%#Z_7Kfn594IOgkgc!&DLG>X@fG!ACkCRw1jSE@?1Og9Pjmw4# zgEGW)!ac%?-IB|f;g%AwwDjmaaI|S&t}T7ziGKrLnk6MRvkShr4UG6eN7Zrguj9_) z07;%HC^A$1zAY=Z%&h!|^15A;<=>y`ggOT6qgF8WaCS7MK?U-|h-?kPO4c9#>K&O= z0wde2V_>0q*skEWtxA}#hewznZ>R9?dEMUmmU`B``Yd$3C7w0+K|SO<+y0v{W~GEB z5ON7yTzl)({ltpMz}ETT_rBSfcOKM}A*GZ?c&95&f5AI;b73*h}Nc>R-{P zTrN%;IKB;z?5}^*&XTz{&W$waZe3sdjQ+Ymm}F~qIuw!@l{EgqLdE|)1OdsFoXK)D z8!j6ZqoAK8GK=!VF=*BLP87WT3_xp8sU!iL>W8BKu!|ptPx=YkX7Mig=e(Hy`CY7l z+D%)j;7y%19Bbj4r>e2$Cs6Rn@b2|)DAze5%_DQd5~d|Qk!LGCq2YDU+)3=(FBoE7 zw&tpm-Z;SNw73~o$Ut{OyHyyR__FoG&8SuiB|f2+7uqAl5;njIT9}a<06si1l506M zAtDNoTbq&f-e;g~=jzA+Lx-#^1bd-JLR*kYt9VR1x!(y$4`DD6d*s!lQYH#~i6pUw z3zN=PUT_v*)89p;b4O+wZY;OwS`fG9^btM#k|Pt3LZCU$KU`=oWI1YPr8St^Xg@C- zmQe-`x(y=#?hxw|qtpFHj5oosp(wst$hN1W3#cMWqQc}J1ahw2`q_7RsV(3TP{f{t zzB6lfNJfDE3gkYY)w=b)|ErqdA5edOuyct#epSbqF!VytsWtM>3)-Le{+ErL7;;-A z-$&eEh+EE^qy#^WyGpo5Z91hbwK*Q!@kU?*LD$~F;&8SYi9OvFD=>Lt3p`QK8<6GQ z?Re{@=-ls*P8M$svKPexGeA26K0wJuS#Rp#XjF@rML)-7K}6I*y`<1OGT#}0_#iMe zRixSmE@ib%;@dw0ltH=~&*qa&tqW22=7|DEr6T`FAiLaQ5M}Ggy|D>BZ@HUBo*Hye z{8=U2&MVKy)kQC8TSuTqfhrM?HPEo~;&PVO_**oG;BJ$FTL5u8Oou`TyuN%3p?EUQ zlYYg?*}>^ic4I=97B9v z1>(l%wYHm_H0;0i9f{UDQ0;72o>ycwx?N+v#=FnCue#GJLr^Qj>x2t?yb)ZZmTY#Go*fJ?hM8CyRnCah|v z{3Vv_!Ed`(Wa$CWF)-K}H7($v+}fn=Nl{j@G2OJ{;q}Mre1T@vX>PAs`xKyi|4J)-F;Vc+L2umm zC%S`yY}m{^9m@Ret0_&tWzc;|VQFAcJiidmWrxd;N+BC|&iFNLV#j*;_5rwQJ(*I-yDD?re>GlPb^Z;AyV?&>en- zsdP7>eE96WvW~-QDSg4+oAVaP(AEQT9^GQ}J$lfG(h}c>2BGN;zj26v2Kl|JU!ByA z-?B9viedKwe9(e?XZuK=ihNXlV|(LC{6XVR3pEsb5L7DurF40{MXy!;G%z$Cp*Cnbvqj-& z;$(?-Tg2_lcngQeVibwM*`-<%fgIl1T?zRb3QI*-+T;qN50>^p355MZzCQ9>J~%{< z3tSd1feG>o`rcX{Z-~CJqPE;@YoPyohC&=?wrBbAfag8gm+$HZRo*Gud#hHm5~*xz z?HiXh*~}{;_&a}ep)38&awf}6x+jooP!KN62diH9^8ZXcBr{0Z4=` zb3ipY>_Zjnv;-E>_5i4NsX5#XD`=L@##T@DP6a3QJIi%RbFBr4odRleD-G2D@wlqgbJPEk-o@3aMb6ERVQ1JW`mjzt zuJ{jJrI(pf*I0ngg>T03_g3k;q5>FDBZQZ3q2ect(jN)_NnjF&LRHio?Wf1#GB(e| zWybs{32jkRTc1AvR9nrj3~zFnC}@hP$5Fqa&7yz4!(W(H52sND!E@q$8QGy!WQ5s# zGjjbYo}Q}yTDgdsVv8skYMAyXP6@3>*F!;dlm*ejBv4nZyV3VPbmJc3QBdjuYA&)N z0HUURc3vpvNLzgo_|CA)A*0AJJ29wTtzGqaECTEwVN0NC|FZ_a;P zk>KqZErSIXl3W}1#+!vy~JeeFUU5tjKSaOukYPXwkab`56)A&~h z8g&hag3<`f)@Kw)F>u^FSB)^hu+SL5GNE8k=l(GYS_Qz8O>R*aeSp}tC0V2wZ|ooQ zx!_n^Ynz(-j(!&D3hE*gLV1$n{360DSe7e6B+yV1mQgo-Fo~&9C3lb(Y#I!vh`q+cS`0Uw(Q~VrLud#hj1pm$6Q%hsI%F5Yl`@$d0a2s?B z0I0!&?G!coQN4Rr7&_8y?lfMk*iIdoB%cd%t^@}9qvBxjzYxERLlqi(-!WMaJ{chJ ziHZOodysq*NC=d-hJVTks3VdcR|G2n&(Py@ zBB;=0k;DaKY%z4|Phla#ZKvsf@yG8`hPwRRr;wYI4io|;YZtdR=HfFu&T$*QsC;fT z$U9JS_PFn=`Bo#_)=%r~+v7&rnxz*a&zUOi0wXBQI2kNd)c2=;Cd<|d+01&uTDeD* z%~ZU)HIYuiIDUER>^e-64`5~Tt-h)UDN;fgYW|Z85CXjiNpp13#>Gv1`0R&wK(y~I zZK-V+77F33oIC$i?rMI&-ZCzn0+l`0F7B9li%n*1yn z#@W9M1DBUqd@}WC1@`MJ&A!8ax_VnWTJkNCM+$H7#gF-X4)~gKupOdtg4(pz>tr81 zt9@1AXScQFs(9}Q&som8qNe+qUXHFW%u&*1c5Sb$#B1vMyyZgNW>G! zvy>_ZRVsNG8oi!%zW#FNUH|EF-;?xmsW)L$_SEC_O2$)HstyBRsq$xV)jITK!P_Pj z4ff(+%8Th5>VN{dxbROp^8cmv{qKq2rnt2EW20C1%9P6w_SR4)$%Khb#A-BKm>DDT z;)3a8<4W%SL9*J}wzHF;&j0|pZaf?;#2gCyt}q9l3x0pfMkd~BJRl^*($8&OT=JOE z1vnv~w?ZonCY5qC93i*+i=E_n>I5Q~dUofls}`FDkBWlY(l4HT5<17P9_?DzGS`7xzHQOAX3^RbFQcH=I(km z|J{n$N6dRd=$E>q4E<#QZyKIhL8FeL7c;mP;si<9@9ySaW@h^YnJK}W$F9;)8s=*j zvCgnYPX&HKLT0M;X_0vHNA3Jtfi&V81RpdJ6+#3DPnRt%0Qu36_<1S(6B$P1#`Z%Y zuBC!hT%p3v(8Ln?GHVxzyQO^h{F#|)(w$b1Yo&f;B99VY z7~#}ofLm{}@NAMcLiXut3OsP6JP+F7e~)KVep8{sv&1&D*yROz{zdiS?H_(%TMly! z_YmpN#!P@^H1j7CN;(YPzRO#&_1T@`d z_W%$bAqHqURT3XOZ`jVWZ$g|dhcwmu96}vFVV&IbZz>`$oQ=>1=oU!(#O=d$)l)-mNlb!CQu|kGeIaK7KZ7<}=Inx*NkG zq1eOIg}N28USTh|x|Yv!vcampDFLQ+<8>_UgNSXp;O6ED`gdVtp&pzZ$f`3a0{seo z?`Zd`#%5l4oi&5RY39T=pICo30wC*R408=0@V6c=U5AFj%j|AgG;fPAM;zuqVU~IC zNa}l24tQ=i)t>;|=d&1!=zUwW*?48V-7N?{A3CK=Kjxn++lT$t?ZA6o z`wB+A$^a2>vIsQ0#Mi(0{lO%W_wHOb*TR7Ojt=pRkYigh)ZjlaYJ9_R27# zS1&g1E(pBf!}()PtWuK`#zE>d$fE~mY>uAd9}fC|jQpRowg^b-yb*hkh6&{G3L4t} zFkuv(KEi}~?7q8&xjGz!Arb54*YWj^)mx5VMGmTiv`fn1E~d(a*s|Am0f(a!a^DOp z=DEf_eU&SVLKOeu=3=_QB*B-f+A0Vnt(p}Tq99}64x8ISg2iK9NBCF~fZ9{hP&(r0 z5S||3%T}wkBtU}uEMp4a#=LsL=dl4rAyO8&j7)=&9pWz@m)a5IFl^o@knNjkgcg+= z3yT=zkU-_Xn(8ntLH^k&o;b6;pv9GEczAg5Y;bsIc<;t(m zD`ZU0Na-go?CY;jz9r2T2rKUUUoT=yM0q9@%>@&SSFjyP%!|>XlSI8KHqE%JW53`k z1^}Jn+V5oA7$yY_^U=y?I?a0iQ2Q>)1jLy08eJQSpN3RLixKqX2WTiQK0rB|G64GmOWM%SQJMx4 zb7LPNM*Y`I*Z{iOn@(JqtK(pJcTqYr;kQkT)ikN4M>GkJNpF&R^|#%&>U^Cd$#U~s zya5icYUpgMJ7tMqy}EK4{X^H^Pvs6OEoQUJut<^ft@;8(R556OHpEcbVN?-ZWi}Sg;Hx5<@~`*DC_<0p23fH0k4`LroZ<2u8M-wZ)oAky z?7(R*yw$pFC2=ceeZqJE0D}=>~FbHDk@K;I3^b}FgbrMImCIN77ohv_}ovvp1t!t zx+t4@9KJg;KSxceJjt4;B*IpxO+9;_76p>Ozxgt)p%&m4!VQH5+lGNGm z71C)|soQT1*&IolkU?P}&_f{wWl{8QH%TqU)9`+DDbU-D4txYJWwa?#9q^CJwK~9( ze$uOT`r-Z~Jn~$@vv0NaGb1^wkY&+)wOhbbqnOvk!Ey4MadP?e{lRkD37r!DVz;u< zRMk(@?N=5m^v;^xPbF<^7HYk#q|+|auu#8#dvyj~@RM~OYc}jnjqRa7M~nuXRh{$c zN6Q5#HN`KIE6#3vTD5K~8u^-^vn!R+bFWcwXx5}w6B}Iid;M0hJ63P_ZLMZXzZBkW zidDUK|1^U)Kb2;3fCrX^9c&KAXD=AR^oXH!Ntd=~vphdwT9N!+G9Oa3QCK0l({K`; z?hte(2CasYM(EFQ)SNE-@9Nwyu{rGSf+9@jzPSmh*PAsDYTm@g(I}CK>yU{{b`Po> z1ISxehTGGu1?wkTlHs?MS?9^Z8wI?{5)$3&J>u|`>Zt5X7;>vClzt_9m(mIxo~{8M z4o2PP@$|&+8GIhQDoN~8N$y-v@#o$)6L9i>s%=B1cr1SOH%cZO5tvHef+D~%VbvTI1xH7@14?!JgpLarOm0_w^4R}i?$0oRi85YJI#-^ z2wzQ|X_4!yy6IYlF4SL#aMmydooVb$R|!Q?4N>8=sqIlmw!k7j>kHOF;%BiwVZt5x znzGs-D;Gh?O9dEWN1n=of%%_lw*tsaY3<(AGcH0uHXH2TvAFsHwE zt1uigqeelno8Fd|%m3X_|Y*WcnNR)c!(8u=bMB)2u%=s89)GT1e%b0pC*omN-U0DpJGiS>7@k=xN;T1#Zuqc{m3; z?Z|S!x9X3T%ZQbPslalAO!54i+jC@U&8+glJMZM&bWoEZbvxsyST60B+~S(sv(@5! zTK;@ER%CMe^S++je$#nCJi+UC%GL^JICfaV&}Tp?S9>95!%v(aV%2{O|6NyNL5zb_ zLjlOt-)5GE;c=;4o$h6K@dqJ|b=F=yxm3C! zh_f*i&ANc{m&LL$1=tlFu6Id=+ErTCbG2WF**!@RF(_glQAk!>PD+Hv7JtE|$rESC zREE`zzJ7v-zIr6Zr#rGi*By?nE8@jVv)_E3F2c0K?)u(y`ddK3MDp-r4%9HZ7Ud$N zIt7JfA~Ge&gMTZr&Y)#o-x$TRH(jOuO_geo6~A*%6IJKE@^hb;z?{HA%!zN0lmyV= z*0%`qOegW_nFQqg(BO3^+B%uhcE^CTuDalJfD%?nU22J5^}7DUc=2p6tqi1zIfd?- z<52=9jQ#hlS8e`jCrk#0{Q^O-pD&g-rT) za}$v*ZGYE83W|OUDOIXo9sZ$xDXgkqe_nh4`Kf%wQQILj`hB`F=&XxN@eFtBPIwduaKVpl9m+w%|FMAtaNu zcXbDKa3|t-UY8~2{2{+B@rS0Ty8z2l4Dbr2ZbfAXOak)GK_9)OYA9SH-daXLgcrlZ zRnvE59O^`zBr@>xF)d7bAo9ldvDvE6BB6VwPi-7*^X&$up~>|=J%SVZk(U(xckj0c zx6-QY`jp{y^gRA42@xl`UIuu};tSknVjQfurccv(-R4*`+d5iezYJ+658F_#5c%9N zn8$dVQ5H~qABkScwdnbImD-6{wVj_y)1gwDSffqT!CAp*YdhntNgxk9Z?$RMirU$2{JAQhh-r|Jg{ z5dY4Zd~a$rkn1^7L*XP5(3swUwDsa=3)KrUoLHjVmd$n z>um|ELO0)`e9^;E7bBb%fjnV>0t~RhQ=Jp?j`xUAx{FUSDbdsr|Ng;y7|1?&l%^8% z;H|l)0jZXdnZW&PS@@x&;~&9w^v+aRVnhD!f*t(P-Tb{J&)=u~l^j16f-q~_LHs+5 zIQh!N#6OR`fQP(!^t&Ym5D*bMQ}xSPHV!}>>rBmbZ$Y5^d~@I)^B6YhAy~MB@Hil9Qo7vd>G8fauZdpxFjaq9XhJFzdeCz2f0 z@+szt+o|ZXOQf^J&)Q@FVxVY<_dD7FzZTBE7$uzylVkB6s@&n)1ou$JC%M5aFpfb} zK{OI4`{*=Ib(d3O|4t}i{QUGSz46&eAB*c0j`@{{MU54+$8sq4cjKug?{dpN=sJgM z_7C@mJ&JW2R-5BhH96AHHEZ-&A_7=E#rfug7H(S&7p#vXr@PL@)@*PK5{MSgB}nH#lcb?YZp_ zFGVo7mkQa!@!dlj;-4yUR}-bM=KsrF4NJrPeq*Sy41zfgq{E zM3DB;Y)MUJREqN9oX3SF6K{O~bJg8xT6j6Fm`;h9`oZrza9~;7EXI>AjwAW}F?p67 z(CzQ$a5wo@H7~P`Jt|Zh(!R%+MZY8t=e{~d65zJM+?NG zZ7X%nFF(4CQ4tWX&I-8d?bV0L_4>LuRy6r2jnD8K>`^zqO>bGnB>B7Xyo7Q9SdfEy zwixIB0Z8K*2Gr2?aK3oV0jz-}#8)}8O`-|g%T{XDt~$4iQmTb-1&t+cZ7Ors{2obM zN!U-9?)qY&->clGX%o&h6mWM%G*D>NzdPwVHqF)Bla3)(!J97L3d5rRlpEsynzrxD z6AN;e1?Y17+o!kZluzFEZe@7K5xupEz5yBXNA0xFZxsuTl8Frx3eMigEvk6z#SUhUToT{BiO>^@mhXh$x5B)~|@aef*i|Lb4;b8hfK0|{p*?%(S&h2b6( z)VbdJiQs?)wnP8vHIPYbe=>+Ekwo>O(o91)fnGb4=ZIKM{iSP{u}q?{+l6ry;G^Ek zfF64}k-fT}7EA%aA3}V!gGU}ms~>JWSF##!&t?Vs=~dn&roQne577$&xwONvKXq9Z z4c7TDw@bdhD>%|i=D3Ha)-C(kvtzG1GX7yv;(IZ{YC(yIWFq0MztMcDbv$dHHb;nF zEvU22SFZ~L0aiH>=r`=UpYP3L5w{}9$hBnL5Si7k0+igKAUX!mkK)u-Ex(b{kY<0Z zRJ=GWJbe4D)UAdei|d8USfv}Sl}?SUl@X{dU~%g{R|NM-^(ONgkouwVKFDQx`qkIf z9mbk~q4-iW{Oto7aCCW9=$c^yQ-Y1qsBC<9ehUf@OU3_65S)_-%#cfS=cS8@k|RYP zuI78I5@y&A6x>$>s#QEwY!d~!+>7H0(@vV_pc`ggrz(HtPzH^}i_7gzr8>9!x;yhj z|GKei5kvao=Zdp2$k@~*a1)n-$rZ3kuldxP0m-9yz0o1L`cYi@{Zyb{OU-3@**6zi zrZzO(7WwoK7H>;NX5%dKtbTs(k#m@R`j&C$(1|OV%}uM6et~LZW?~?QR_YtE|1xM1 zOYReKVt?H2#Nl@MB^M|>auhu3USIT&w~aI!b?-`EN8(SGNN$qWQG7dMm@la`%|5o;iL0yYl{Y&FuQiF0zNCgf|`G&HgVSSG5k>63$?w2N$3|_D7?~HVBv&yBb zIF6aiR;(EIF(vzCHByu^Nue2J6vHcI(%|Yf z1_OFtRI?l6Q&l%)@8xf4HMD+vJ;Wxm@yb#*LC_6{@X4OOnPo~fCQ1g62PFmaS`^>i zg*MtIXlfei)PSP@gMw_XH>{}m)fd?)M5PT$(6JyO&USMHc_w8z9HKnI8yoVDM}CvIDtc@*=d zNeEoOxSU5EiH@^Z+71Xq{{+_td+xtp=z}8*`JSJgVrk!>q}~Z&+GC}54pOK>Z}R2K zeRCvZW&gq`9RPT$$bPO89gcoME*VFaaO36f7z3CdH#14!obO(gb#P|e1E(w3Fi}T9 z^r?3TuFJ$bZ<=RchaB9LUl%Hgz<()ys;X~AbZ51zkH9El`BLOjv|X&}_7!h|ri@sp zc1~vvX_t!vu7O$=a6bSLPB z1cfl6=pzUsbE8(k8YRYWyO?D?F>O(yQjvGF+D(+~k7bfufW{CK=?{EKI(#JLwU=%O zk6u*%Q7x2ni_MJG{D*0rE`xTQu@u&CUraQFCv9l6?sj`bW3re{9B0>dCoQAZf^IBQ zC%;FHuNPJ@HUdyj7o{*26cQo{6xuk)*>)^BxH*UMsInXaFgWe*3;+c(#C4%T7?5-K zVD&GXI%awgMS;9AzOmzVp|8c^yyuQ4C$C$IEue|C(MRfYe=F#ILO=%~9B(FTvw|`a zw-rvzv|8uPr)(@fhmw&j&c>EFm@e$X>;Rp6lL)uX?oAcLLgHT#BXz*8J+}l4NRnX}8if zsgp3ISs7or8S~~j%2zpDMnI?&uli9Pa{ozMMLzonDteCjeholHzqy0-)HK|VhqP_S0q2>$|?QW*b@?8`f}7!u~Of>ADf- zi`84=4LS{MupFP(^i~5*NoIoScfiwJT@F zQ)|?7=I}bI-Bd8e$DKZFA3+K-L17+ld=-oB#w!n{GOW{VsKF%seEFo0Z){@?Br8Za z-&)6jcw?ufQ`?c-tWM1n<)BPi0U3)dkpa6Hn5 zpy97aY@$@YN=sJwpqUDxm{!%UW`Aw^SV{EvrOMzp2;u=c%o0WP8 zf;e*hECl%Vf5A-P`}R0+U1sVU>WBP);xV*LJsk7;m?!_l8UA^;Unb-b68>`t)d~S2 zbB((``7guD|DLRMR|UOzz^oJ=0%|=H#u9)`z*`)=m&lnjKoWf*Ahk*>ua;0UjmLrCrwUN4_p}gw{J1Dbv*9P;JvM4d`CoJR2N(T? z>v4B+o5gCQ_?E?_pS0;3^;9~G?jd|x26_8cQiO4+$3XfB*_3w znB;ZDys=)(p8d%Pl-u1+U5-Sejz-lkxr)U&qW^w|&t3GUQg`2&$nn|+^2XYt&wVuP z2Mnp?^7tI>uhvJ)!FKeQy3L-{$0l;IaK|Qn@dJsgeJf%Z>^h#*$~m>)N>a$>l4){^ z5zjoTK2jI~=ALqsW5T}ZS8}C`+Y^Q4DQtz&;2e|$ioBDqe*yCQ0kRQSsMV}&y--UD zfydEHN* zAqqP}P(^ptG4KDCu`NGj=QX%kOMMwfq)_?fcqI7YJ@5{q3a9OR1Fp}F^fIjNcYc%L zvKv>A7iupG?p3%?81H^tQ>-;Zq}DEuX*?bVO}ScmFTM9rF3HuA{srbx42F-p4J4q( z;V>K0jP5iJrZY=qi}`3)?{ZKc^2siZ)oQ)*sRnFK!p&yWI#;NdY`s-z(CDk=5@SZ? z=e-qt<;xpb86Gi3Pb$PbwgBq#ao?F-y{S=7y)H}XB z&%O);e<3y0y?ER_?Ht?!%S|UE^b&RN)=ah8uRIq=k1<}YbM2|NZHu>>LUwC%aVE)s z-_ao7FR4H1-`jS*py!9L2R9wCq`LYi==Dl;8)!IQeI5BVn-!aQvN%bVRa%CD5}HU; z(DXZ7_=7Hrpzeb{$z&;GkKne*Y5+jO~Z%aR?Xty2AP5&6HGPIBY(IgZC z4qoy3HObXPvf#6UyU*C<>L246rj3o*a9&&gRBXm&R%OuUX6!;TiuK*8bIdWZcxtVp z_bVG@6iA$x%t~xnd*vuiE(jF&K8q6de%q!Ok0&o*=Anba%Z!pzCwH7DNAYt==&!B^gvoF&1goBm}^t)~owp4qTn>(!Meo zjQT7V`A+m~?BZ}`4NxSqIPXm9@iD5E^4G1l#JQhtZ7$L%=MjU8Jev(a0*720XKs%I zU_^5o27{3R4frU0?rxrzuwLDPu2w97eG-?`F)x+ZO9OOxA_Fxrj(yeR`AP%zPTS)w7v~Wn7rCOQ`XL+{;FAHtyp8N-IvNyv1t%N#K!>Xl|>jpLa~~{?N)x({(>i` z@QY6kL5B%r*k>J1=5B+Y2&=Og+ac4z+<`%Gi>UcM4S3zC@R9>1~umZzY>vk{RkV^uqxq``)l;)`Qu?U3R zoo&;Dpy&szU(P!|w-JOSKa|1Y=YuF63m}YBFE?m9`bf7~-L$Le#Q;KLiqOk!xPU_t zAiRPeN|drkA7+i~?UysQ=BcD+I*d7$kLllnJha9eQhkjp!)_D@3 zzpc}vm}A>W^}JpLyqlV*ontN|^JH5iXa_04;BojX5F~*NSu2>pbpW=xO_3|mK~kHU zy0fv`aH_U-`h`e(6l_OSG3qE2Hp`n8i|2-exeA{}-Bg%>>VL&r2koQG%>~5ib`XQ! zmgrzsB4;->^o=GRz9;@A%QbH$CO(61kR?G99yt3d#FqnbCOcu>5oThz{j{2YIUN_ATI6e%!lx4R z<|y$B&EfdY0?PUU$m_B&jTL;SX}?TLk(0^U!sL+fsA7F~sK)B}aemP-vSoJTMGzGu zZ;mE=iPTwGU#@LgO!-BR)0IsGY{#>nh~COR!&A2aklZ)1O|)$!hvw9!=PH237^Mw( zWXK{X>cUqj3#{hfT|20KDVbrN{PopI)19iM!@U36_PY6541-rU)2pvO`wWoF?3%)i zO8q(EbCc6@QVaxSaA0Dtfj%t~fP=L%6N<6q;!wAt7$1>z9JGUk)j_GTS^P;z52TgY z766ajJmY!2TQj5igp{b0N{Bp9x1|~DQ5k=o^X?~B^D$u$%C*5{rBEHfr#em;wEyjx zNH+CNR+oS)hk*d6)7CgKVbDQR$1hy#&DZb7qimWlMek?T>w<0@oOj1`oLr$q+x_Wv z8eQ#|TA`e(1*LcGY%dP<`#!xcK*41ZwqNU~KobT1^BCcfo{#8Q9FV^+;=4HrV1Nll zbERIY2Rf_hfx~IRw-vB4-y2OT4$H4B2gAQxC!XGf|_eWJjR6+mPQA6ZZJt;lC%+^=dt}pD zYqzp>`0*M_&2YHApiaEb0QD_tlbxUj=!UXQU=eWKeOo< zs~yv8*H?CM=<_5p1?h9`wIniVk2ySccus^`$b&)ttq^585+9dP%Qbc-5Qi06*;zz7Gv;0(}A`hKNqlsn130pP1TU z|8_pWpNneghCjq{a-Ua)C{cHxm;)5(f(VlUTLC|L9xCowHzTltH6 zj&mi?aC)7+OUjspSEy8u)}qNA+P>?lctV(o09)}+=%D%Rr=wQ6S$d`Qf_R3@hYAv} zA%S+yU6Z$hOlQlN^Nh!?Vu_%5ZjgRru26! zsnPA#=~cH*u@*-YReLt3;IsFFfK;P^n8~0`A0fz9pbME+=RMew1=>B~^nFv3@3G&x zzA%u|@A`;YReCb4e=Re9B9vG?uT+Fu*6}%8nVC;TF&XRR|v-%!l#C2 zaGia46b3i&5tFuZ*EPQf+bbj#4Uxnj$3Ls$Oo#~{c`}CLMwyt`K%TkmIOxI|g@%=H<(#=7A$P;ydMAhf>xR zT~rH?qZz~e_Qmv*GW1)o?Vt3wB#+MFL$Z=A&~8Xx7({=p3#o%$es&C1z3ly?SeuL9 z)euF9yX#F)`;0qE0CxA|D>#2LSZJ{qFA#%%I=t9*F^a9I#=Cv*0U8JuT^jImq&)lS zfOw1&>NR%_`k@z!xP^SyGeU5wP2}8SM4*Z&4xYb2gVOKBOfZ2J@-So&`S|?GJG6Sq zJA@hGupezIj2R~D0(klp=QE%^@w*b^xdP^%)Oka@C+mE|QQ&~I$buyzIT*Ab9}dT7 zpYf_*GE8i`CXCpz?ZjJ|NY*nO1Qd9^s@(XyJlij(0}l0hbOyOi%bZ@2;-#b4?ytD{ zq57bS6NF14fZ@X(&nV!UEMgDN@mXec46jq|jk-E#mozwTX7?cPC8CWmEigSDkqzVG z)@>VC;Pg1NOq#FJL&muHtTR=k`QiJL#eQ?3NB-waeH+4+G^CXm`$oXk8w|yyO-O&~ z`sLT(dF6k*?|71Rr2hZM0eke4H{^#0n_0qT4uGe1i2 z$Zky*gi2pnzo)x3{~S?|vfs14<=GgEZKFQCUhxu#?VF~|&mtWXCFS{$kN=Oew}6VW z4Yxp*l9T}{K^g=JLFq2(lJ4#jkQ%xNlt!gPP(iv&8Wg0v8>G9X?>qkKf6lpU-Mbcx z#SGtk^S%AV-utml4KL`;z{kXKKvIf%L#z0Ro2}$U;KQdcxA5GO?&sP#n9q0IYyWZ7 zSM}rjLLl$!!#~pUV+vHW3X*E6@4E0usFsuDJ()xd>-1Q<==_V}NF^jYrd!3ITU&6^ z!UXFQOa`KuOQFr*G`ww(n*&CnIPIBOWa@iTt;U3+ctQ7QLh-9-!wtcL5xY9DO^LWO zfHg}8AxU{>GsBJ=uUTv?5+cq{V5b?{;)%`j4W_qODm(#^r*JlO3}&H)O1I0hJwszk zVX_d{bSL7q7TWq6fNYG)9~MoKW#nk+O+fjKXYT?S+ss*FthdEN#YO`%KD-b!@aH0U zAO$g_kN$$`Q|BK7rdcFgH_u3_4|o`h@nsywnVX^8TN0u`te5bL8&i@ z{2x)FhnYevj2cAZ2LUYM=Fd1pY6xr-{cCgHwUUs%B#af=W zR6GzPZz(C|{bS3cn>3Kc)`gQUe-#&r614yZiQ31+Ar2^^oW3ubS$~1j%kSbW@Jzrf zrMdl{hGr5D=5_?nG$O?a!iWr{s^b^5Zr}c{M83qN9xgv! z^u!>>f&8lrvXrK)F6wUKgz`_YJppLD%f6X^^E7JB`JDq1AujI-5)HY~yeQUQ9 z0eL#>oqf!fE9{hJf<86LCEU{&n>7L0EPo&MQBTcR=?@kV31{WQEh5NJZxnxqB0V9n zYr7+CVZj4i_QqJkKNUYB#hq2$yY_dt+HF|2^%?Iq@#_Ct{q+tXY8Nze@jf!PMCfJ$ z3kciQTyyP^|1=D`Ko<0wzi)>M>$NR6@AiG;$8s;!G9V*c6QnkPF}B=NanT%^(m@)n zU8sL8u8`80K|NJzUD$h9_y0_I<|Bl?)wnHzkT)EiQ)aL$_>w~;lrfeojG`K~@*!bo zsx-0JsGLN2qUoc~G{aETmes!07^nDMsTAyMzC+T!!n%pU&K{Dnt+WBlQNahRstu+- zBG2YYtv7c;@W!mS`_WUIYi#90WBjsjP?~fcB@d8{ECs@%q-f{W8?tp4P`(AZu0e4p z8@hC?sgq6ANjVzGeGtZFAINKS6^7oU!e>yG@=b*~z~Y}nISikm?h-R4Eo=t{F>68Z z2lt~Ya{YLMi^LBlNW{S`fizWUb`zn6@eD8L>uzQhXq8EXJp|dLgr;~GCVk5236u^$ zdgT2(EF*iFVl5hMx>3m7m8-&d-(1NA>V8J=1>EgpwP}Wg>6fF4 zM#mVE6N%10VI(r%_ZJi^6&zxv0so?3x)cdzttLoA>xyF@y283xFuJpVf>h_w40EjW#I zr)=^jIF0U-c!?#!56?@AG!hF;Vk)eaH-3zjmooog4ke|mfRO+hcs&+ch;x8#@d2go zcV9RdWt8wIi1eYO?dM191JVy8NX%Y6_qrT6B2}u|p*Q!G3kR zFgvnvJ4!OYc7wwq?lm@fI5N6`29}-N7n( zW0xH5&O0}iX_D#2?C>+!&~Rcdd3OTNxb}@DIU`!z>*Fz%iH6f^FT9&$ZESMe-V|O+ zrFS7*z0pS!9w%EY9Z8(8K>kFxw{=MA7@3NT1TB-SS4%FMHO7mGE3I9w=?Nh?Sz}Z> zYaL^F6-y0`#*FVmyCDGhZv@c(8ED_l32*IP`>`55TL`Z9|0alZtM#yX?|JKqDRc`g zP^E`;*5OXx^N;*k<{&e_4pOhHrbSc?V%xrNi}=kl&mR+XO0>9g*J-vo;by+a$swF_ znosn9>Oe{`xyK$jmPrXeNh?)NC{YGlxyc8?43GCH$0zfbXlc2Fx&P8$owYnNcI&la zC^CBG18SoM|FVcZE~epyCqds(D!YvL4MW+#hs~9IX1#_5b0T4tBV${7Ew>&?qyAjQtSzIAOe-<0aeI6O8+xhmCxT5c2hA4_uQ1J}xCldMhdVPboCCH6@7I>kpGBZkoC+ zu1s%ZK>Czu7vhmJfnM}Lj5SEusP6?6bYVHrH<~iqAUoT5xk_9vKBgBK& zRtWh+R*i6Myj~=+Jr1e>zGUA>B(Y7NNaRxL7zv@Boaaq zLZv4nH?-U~TC?0Tw&nXmW`ekyNqjiNB+C|%QU4_5g6SFQhsJrH2q#U-&&_2cL~M|F zqcWTnG@ZTud{%yNh`Rh}9uFe2@luoY6?P8#x$`*{IK@9H%yt{@Jo$!WbHq4l2zC2l zXZeAWi1;eXGl*J;a%J3el&AEL$u}Yv$UNMr6(=RHb@07qkz#dcf0R3Ubhe&2AmdoK z*=bn+ejzH%e21K9*L;OOh%2;aqRe8<;&>s=zf5p{t4Wduy4>v9YwJ*2TxY*f6M2Dg zPJ~vuI2(0};d#nzafsMwx9N^)1VNkKguJG_8*uwN65C)N7NxhR+vXlKe%l`#!rj?= zuB&XpiQ+D`FI2U^ZTlA%K&mO^4~R$JWX*?J_pZN5IHVsD0;am%Wj}d+%8i?4qoNgK z5BdzF#yZ)V%@Ftt=Hh%;R2c#jhZ5ws9U;Fqz*6 zapsaI6Vmo@+od0Ojc9sYi=B$5{8pg3fA5QIK~R639p9q?71N1W#zk-@>4pHHu#7+d=0>wjo4Fosa|L|M3E#c+=9VFU=HnXc0#^^-GS7}6m$D?hcfew zV&I!N28mMyk=AK0@uno30`q0kUV=5K7{Q(#S}5|?zyEbv0tE%Jj%NfLX2~Ax^j2l9 zHr*6`M`ZwI@2fx!Y+R)0OAo|R10c4=du{Rj4&O3wFOm@y8wPGqj^ko9-?a;FCp||b zi_!etasfdL!%d;Ju*C}M$56sP&Xk{j{lu7&sHN<#j+)&E8l4-iHo{7x4+>1t3j)FW zW~i{@R_+ks?z*an7HG;X-cU-3K-$zbhp}1iA8|ZWklZS{#YRm;g&OHnTYxNP;f?VG zZ3z{FJ6r(jA^f?`)nqfMbU;Y+R;w)9)NnJ7ofG@6C@yC6gDVuA?-2HsiPymelteAb z9ceQVc~*;EZ2`0r43`Ca?hBl>H}r^MhM`rcNhY3+CHR;TPi$+sT{&;U zgSmEO+ccYQbov~-*(5o6tQiT$h(aLeDSGxjgt`xU(4YeFl@257tF|!qS)2_C7FdZr zz7LCRd%UA`QrLcV*Qp6epR^3>HA7~*5}YhCkmzk+g=7;VaX|4%Oi(g;g6vT5SKk<7 zw(5|c@>zI?A3kYDIYsEUm?or{T}a#hwc1gin}F5sKZRq1n#mn^d$yu_&P0FVz6m2y z=FRrR>#`FEvg~?`RBF#XoMw-@1oz$m%8h0L($kmWc2J*1#Gnt3R={e~srm4%T8N-Ap*B)kbGC}YdPyrBn}&#Qyu`l* zyLNk~%7Mj&UC4IzNt#Z=y`P_hN+X=;_wNSrHlgdh-A@S$MI9ho(npzG52$0L( zy}IO+H8xFdu;Pk#+U)jytbmaI@ z;=)Jasi4*9;v3zC)m%I`k8@y_cejvWo7MN-!M7vsmvNvDPEp&~=B*@PMaTTIqCLTh z3~drVYMS7Z()2Ri4 zP8C~<>Y@I;)yE>n`c=yja@(N+^%;Gr2884}A-^I;-C|?Ow|n{@ArDIYB<@F!ixp!^ zvj*)2Bj^6LitTy3v5t5On=5(4Z%+kr8ii3$hWIo$E+j77&hmg959(6B3=^b;n;l8a zq7rTsSa5w+fI5n^gl!JCvLg3!nN`WIE)^cOAW@`@=M`? zC3|httZfL_cFaUA`e5~LP(xLWF9d^LSd0NrIdTOl$RJ$Oq>BbgEHni&F~5(pfa=s9 zs(g2!;8aY~WNhFVLf7=*@P3E7r9&Hh1)s`=BOmefO1GvUa6vJqBJYRGqW)Mj38!^{ z{aosP>?J4S>FC>hMVd*l!_zytzBPe>%>q1G$$TXO+h8cNqNIuK#63)~Vpk*cPUguB ze?^=e=a4+T-Zq6$q2@u!40T1Gm%0_TNj?R>>gShHKu9pY8tsapGm`zw}kmp0sY z>t_=iDN}#r&!4Z{Es&~P>u&{6@XPO)V4s>mo3t^2Gt0h@-oZpOfA1GDwxI52{{DBo zN+gFuilDDzbS&-##wqEjMIC5ED>5#8vp)W2VQb7Y6`L@55Le`Qi~L5I8(_~We}aLDK?S9v^IWT0G4$*5#L63zy;l4XK#2JamgW8#L=BV9Tw2)`GNzL%1W(oE9q zF+X9Rf=sM*{`l$CdeqX>r>AsN0Fk~&4l?=xien-;KP_q7L&j&7rIE{p5JmABtI}r5 zqpwwr&24lTPANj6-Iu{Ge(p;F;!ETniFTMVeq6|6tzjS*&964^^18rDj%L0H{;d?a zPrr&hpu1(S1?8e@Df;kz^O~2lrEKQ<>Enf**E3j=xOIjL;(b6z0OAfuV+l1wL`2}M z%k^fYea4UTs#zFLu{gU_zc?if_%;%0AZTW;rI|aM7%*;z_WJrzPh^{_I2t z;D>*6Sr=pgkQYY@7l#e52=LDjMJXHr<`ZD#h`;_5P(ZRm2Im*%q=!}_g*Fl%(+7of zyX~{#FHhK>&j(^JZ!PngmnHX(12_HGuM1v42;Bj zeoaAxg?U#*C?y&+5#ZKX5Y6}hi#CDiBVDSoVzSJR9;fj-%H6s3Bsmtu1p%hUkh6B` zj7-pr0sylkzHH?ebE)~|KHxD(zuM|>-rg`{zLg|T?nR^lxjm`Up}`H!6<`WM;)fFr zvtO0+{}&##hXeAU-XEzgQQ*L@XRL4-k!Hw%?tiail?6A@Qtp=gg~Brgx1(%F{1;a2 z7Y-Xh(!s~A+Do;50cOm=t9s0YZ~tH*{i@LFRPmo3yV5eH19+V%;9e3@)<#JD;$Bt* zJ|)qPo-pD+{r|^UH1Ppb%_D?S77mE>{|;wmn(i7^M*VA`z=cira6H^pp+)O2KBg-8 z3=Ex|1x};gT9?{)qEE4(iK-9KIM2VmXr6b>^Yo7!VKi<%>sIeh3sYm&t@SbNjI#~$ng zuKv9%|AzCy|7eaj`Lkc(!U8iHZ8pC>JB8>y=%@TB+zcJzr5>-PxOb{P#!j%tm;Jtz zI`t>MI?ZrwEKf_C(@v8b@c-YMcBqUCwC;ftgijr(>9uOSa;EDX<@Fo9Xr%?E9|FzT zwiX0_oMAcg+873K5|fSIHAJ`ev71@o!d-RKCuyXdy`u`GF)$45C^{0=gL z3eo+_s}*_ipB&PdUXMtYy7VczpU#|4SGI2jH(q(jo*!RoSK3Wb0P)8dyhkcss|J-y zH|a8fC;u2O4v|`W5(7}uK&hpkw!KeJBW3okGXFUrg}1VM{`uM08WP;i8Mhww-Iomj zZ1+9-cKwgFg}{ThWP8g(JOQUMS z%`|xGWC0|=KP&?ZB&~YB+p+E%n?rTE?Wizt(=%UUzpA9 zX6i&XR2k`Z>j`yw^=cUH>-J&GRRh#8dNKjCKO`4MiY?JMe+q$Z{{i~{*n6bWe&!iM z0phXaEpG;#K%q|`Q!KVh7R#Y?*WKYJ4RdQqK9W>`W+|&XE~#Qu$K(3{FJ`b)oc3w& zKbXNRqza_R5xK#K7P7T*@;}1jwm;oO+Xw1m;M^5ah^3K#=oytV6p(7y{{{|@?j-1< z2HLIhNiG|*vzNh0zEfYU>hle1l{?ixGnF+Oti;NXChBn5eEyaOq;D89isP=W0Dx#x z%e|}3C6-Z9P^-cy{`!IwRd}S!hO;bxBVVl|e`~r@>yEVu U+SR9TU5t&ov4CAK z?Jp`mLR8HH=k<#+Y`w@vn%$|tWBtTt^ho-t(WGvUKHFzV)nBYUn{ic%$kauSvc43- zM?m2O$aZAPESWRY$WLNw`{}US1Eu(Qr7+l^$}#9)#{_C!k;;}2ScJNO63_9^DYv7# zuiH$gY?@<-{VI(2dR)>N5TuU^BZTE^&RG?gJT*s2Y)2TXt4 z&%oZsDh3CPUdRx2M^iOOuzU9!=V;b^K^_B|UbGe~c-qt4&IhsA7sRx9oazBa`^si; zDC=9p!@0PtKZ&OALiF9%M{WFi)1RmzY$Ln;f;k=w`Og1|ax6zx1BHm#^h`Sr|BZ5F z>;At`j(HYe3cXDcVUtP*HO|V=<=|`JBQvPB}_|$;kR~>z&mj+ZEjoJ2$k}bC! zU@{|0i>f&!cs?6-gQh9)r99s1Ot*cz%*9f*WWdU5P*d5Kw`Mf2F^V0M{Y&@9PV|>15QP4)LYnS`cn&Kl3{&d`XMQaUyQajtGPy@Igkt-=bbBD_1 zsvh4Tuz@_zg_Wz-07HQUzCFAYfK~Wbj*DC-3u-c&9(S4zR*Gp@U8oUWO_f>n(Z~;C z(^~A*HJ^W-+BQC;0+KT5zwP_rOrVIx-E#x}uNq;IP&C(^7n>9|p$5V?tL0a2fV)~@ z#`YI?l>)<8llqr<6rqlGi5|Y_G*HbxwjWPJxBmvph|6x2uM2Q`V6rse+f*@PH{bB@ zA#@SMfeoy4K_&i}K*f^`Rw+>j*Z*mj*q8-8+;p~?obey|I3NW|2c~j#QNzw7J&z-d zSeMo>YJ=}x&48~@dGhvgtSlM*?squZ_w^?XY31dSD)S*ScUikDtgs`k8S7HlWArnl z<%f?nt2Lt;E{@h{-VC4E*-%z1-*=e(P|uCEfT2@D`NKNutDaWP= zR>wJ~rRK-ied@axkQTi_-ggyas~^`71MO-~;})_NQ==D=ORb^?(nsr0=-F|DCdxY& za|`xaDhxy2HM1hV>|9Lvy-jIR9B zjV2t%NhTRE`mm!9cZ0b-<3pP&cjD z-ryIe&Cj38trRlvqXoKG+sL5W?|{XD$dRyionhfYoJ~G*^gn>PGUh)4b0GzF6(d?N zEw@+jk<;i?a=0$@X?Mm3hTCc zGJ`6WUPSoAORZS=Vj{78k$nt$Jc%WZg zXey{A?2sL+c`w<&zJl=a3hhd^BLQ`t0VUC5cMHbYjt$Ew0M&FR*oUl@u?|6>Ct$O2 zLz8mEeC3Q0_muv^N;85al9u)O-R{oewU5vuS^x>k4d|+Fr5u26h3g^BoqE zreJPILDV?%Rb z_pod|IV)YXJtKgVxo}^jLKKbJ*k>TO9(V6RcI$M>GK!fR^13#FGKd4!_5?wZXjOdD zgNS&$NVy^5u7}b`=%cXt^}8f)g@5KQzrARDtRW)S@LWU;pt~026FBsgdmvQQ*NxJF zNgMgC6)zVr<=ue@lUp~d3s%sA?fqEkbIe4uso8m|(=mgJw-ZBjQ}~$iOi9^&C|@U% zxw8j7lIwCh#bT^FMAc3SBYqsRXm`CgG6{I6N}(Zv|7GhoJB;^5B*C=Q;~YPNGpCPLn?{x?I;c39X+9@~ZXq!fHh=}l1k$+! zi+L{P=DI@QBwL?u5Qj8Fe0S$+^A3hd9v>3ie4KjA<3g3AT(2I@2I(2yl@T=QUJRFp zPE9;CnX22q596LIep!>r`;xQL(~~Wrto|fldq0rfPP5BMIDyIP-ewsU7Pc5PY0+x{ zAvlbo**7QBJkn9nsjEc^OLPiE$i%3+;17&(U2Sb{bWsoUgA-&!cLvVSf4 zBf%|L{=*xflz;TZsoP_?Xt1VmyM8>{o|xEi)o4}e8*PP5zs5(6e#`K@^L53PD$=Ug zB&@(Ql0oU@Ue$QDhZ0Z}(EhGhZd-s?fhKAK-O}u&_;gfOXc@HE_^*m%J}^lmYoK6<3kQv!k&Vn2|&1yTp=A@2c+DM z{LX0xR%r)&eUp@yhad#jn9Pw|&_}2Hsm_;@Q%91iNUNrt;I2;j4h5D_fwh|g%!TBt zLJ;WCOdi^D{k}yAf24!6gn6NVv4joCd8-u}-ZD|-41Rnw!;s53xPoQ#36wzBRt@-U zPMR@}8fo;59wrPo%Y5*q#MhqAFpn-VtRF zST&0C+k%UQFzX6q<~`4S|3GOr2$Fg5*)H#iaT^|VSOitX8}iiw_P(|Q@}+p2*k8|; zocG>GdVt4lIV=05*Yz+~8!dx*%2hct`+F%ZhH5goHMY2IBXd4N`TTTs=`x}oXMsO% z87KV{jH$2^al(MP$q^yx%b(<%QeQ^{7Tl;qI^X-ue9~y7wDw#di~E9dx|i=TT337e%X_%MQ;*87WFEVf{H zUT_0+UoaNbu;@%=%Xa1%wIBjiodBRkVSA= zJozT8l!*|8CY)~*l>MRT^!HvLE&PlMtR15UgkZC`ucs#!#iN6N-oef*Uw4>zJj0NVrjJ3Q zS1L8DRnShslox#;;&&wN^47%0v4?&r%@EaI6l&9>?EmD2e&a*(N0ddPhHC566;aQ; zsdIr8ik3UV&H&Xg;4$lQ?gEXcgC4)xQaFnl?-z?%Lv$p2uufbDpPuHGI8bTO0rfa& zOjelAx=f;+zq#0C+Uv39=q3Wp_k22hx2z_YcPcky`dE>-nneV=@9gZ2FpiakA}Eiy&Bz zksm>>xY;zNqS2=B+B*NVUkkGt;*EWKddTYh?f#@7G)xqgDKpdKl>D+_I9FLBo!V;K zDD+Fj_aEaP_TCbdmHpY$=NXp(#~^Enr#RJl(EVFL=U-zJL=DC!jQ7ki9q zh>MSE)4~s_#9BSp-V46mT*11}X7ptfrP@6h5UJA)p-O0N-1l&2UyfQx5~~G=)Jx3Y zpL$Pco{U|>Dc&+(y1RD9$|r_fdEdfj5|Dzo%^UWp0TcIfyv+Q+9^)PZIKYsP)QunR z;-CVgPoEUhj<8?6;wINgS_UUAA1>y?h*qt&Rt1M^mF=9ToN|@|$&b#xQm*oV1(-`7 zk{JaqRP!OwNRyr_b5UYFVp9A=IPTw@h9Ka#8vR6rMUe}{`Wjr@cra09Isso#Zq<#8 zIsj@YTQLz-hCb(gDiAUu2G4*xEL>`NOu2zeNJp2f(m-~#(uSPxr4&%^`P`SiHDD3V zYf)mu>eR28;!Epp7Gn+TOy0GMeHAqgFqeZ%kD~s;aaV?Sl53|0SeV$;b44rY`yUJ z_^5csoRmb8mr?f;dUjmlsyN?~@q=1yJq`=1Xn+E?d6_43deMRN@O-E_%Onmq!gIyH zumDQ!urZX>bV9l2{=Pf6l6UXkKE+0I&F0kqr9ky}kMF=$@gDQ&{|fj1N2TuXU?k)f zh`3^Y=>4Q9Lga7G0X}Rb4n|2c#$4d<8~ynQ(7^-I)F%$=zit=?!)7~5Y#=YMAL zEwpjm(8~ZL)sY|ZTYs{JvEcz)qxVdazlAM9|9Axp{~*Nl4rbqm2W0)f!@v5+hGHe` zzZWuruYSq;$G7}1RPCQ6x3_+__6j`&H$jEpBxvI?u`E2y4WDxvea^`LgZ+KG4|h+a zdGGqlGnP`^t0T3_FJHHj`q}3^^-BtQlF`_c)GxAC`iP?4yFHix|7f^Y;7F*%Pgy_W6DNxh1GN5Hzt6VXlK(!J{pP?( zOEvfF1f~aMRDCbi#ofaKQDyHB4lWEf77C2Gy6$PJ6cx#)jx( zpQ;gCO%%R?^M_leVt%@SGz4J0MsJN*O7Bcx%g?&g#hLb`sU&$1NXWb^Fs!)-=T0o; zaywkhZhgc)6mxAzexypC?CLCpMkYlS=zmjzgbmhU;~xRoa}a=?1p(Nm!r{SuaUHM? zk7w{I?t_?d>?0S^9OZ&IcI)#`&O80ea3tu-13_wOA?e59_<1|Q_OJ^W0Y6%5$_^I4 zIi0b-;D4lD_ttrP!T|T7%wlEgNiQoV5X>g~%tl)@<4$br1=m(FEIPI~6mY*J;_=?7 z2D0rMi+~Ym+KEfStnC)vA};IU6O?##*jJ5b%} z_#@L)aC8jc^WMIii)Xq$v8+go>ofX8wnOKA^yT$l2Ij_?o&uQ=!@aEBbL;xT-HEcs zkDAxE2VI}S4y>;FkXjx-s}P^-i}^`T_Z(r_yb7@xPU!t8^FZ=-96j@DUs}vdd`4M7 zQ~m^Sc`{xX&%d}@Qv+4neiwE1Oyi?9d${hn=}x}YfzsvAQtvsmU!n0*wm)|6k4C8s zNgUO}-|McXiVm*o5??M&s=<|W@ffup#`dZM`o9-^9?xxHYyZB#fYn6?Kd~ro8bO7OX z8lW2UHe}vJI)=5fm(68V6fIwSC>CCvUb#kB=`T&+>x)0-!e#Jmn1Ci&*^l6H4GIes z=GYpNl8NHwf~whApFjzzAr@_&&KscW`cY{nck<8?$pwX6V8gMfB?jfm}l zB$3l9zgw?dR3^T_5(m@dn}>!^!~SzP$Gm1`q4iGeV=aFFs-<(gi{m*VAV@S?s81ptMGMO^!j|~`rEDYX9eT{9*0>klK zEufMOZNO#Del$?(NR#@`mH_P;CfF6IC4>fK{(Jg6B*J;3C1&Hcudh$0aQRLyT+2+l z905t576{Upn%s04y4wb`PBC`?LAAK^3Is8Bv%TUclYxDE8(q;)%4}zxn7+HT+23cg zc*k5DxiSjV&)Bp#}ahcwaeJX@Bhg8ClE*TV@k|zMk8?g-EOZW#XmB zA&lSmnqTVb&*0P_<71(a9-X@!)&*ROx3^r>O-pdiJ_=`KdR#aIb3k+p+Z>!2dk=uo zl4jBo``_KODI2b9%IdSlC3lzy(Udpu)>~BlM~*G+U$p6?L}+EeLX;3wEKBn6$m%Vh ziPCzp}8ep~zc9;RLeSZtKS)5=sUO7jF|k|aI`ixgZ|cwU4>^=|0>*Nfn;A!6#Mhl+pxndcve#sEu~8qkSn1KK=6{x~ z3jkZp11J2LtKBJ7kl8v)B84Exnr1Em4GflUGN05eRiFPiqh`>CHI z?l0Uw1#!RvUx{&ty9+F%KqILDV!mkv-CS|$h@(vW8gUx)fX|b8{1|Y@$C?#D_2FE3 zS2fnJt`@eQ`hbRx_gMR>R9UUph>W>>`Vai(;^f!S{9@u#X@VB7fQ%-yRQ;ZHklTlf zkc>Q6K&NyvS9rvI?*Ihnfl%g+do-1@b7|Dvh)x7JBsR)7;TmyT@2W#L`z~Kjsk8>c zm87|WP)&5}{}L1arSD!as^q&rN2mDU4RAS-c;-M-dBmpIW@>w%F?V+shGS3&F>K;ZE2G65rAh%Y%t%fdMMo97MOfcc@F~iM* zJR!?}tK9rbD?`KmfLJVQS}f2cZ07O7Cg+cSiO+x$5IJ3Ql_yA!-Po5Bnf(jwEJU^lyQs zyRxD*c+4`=T4hBOr+RqOe6dur$)Y)cImJIhY>`uYMrx??qkhl1H@ zV~5_oJdHp!gAYIM0-HFicjkh-uiYhh0XW0Q^WNW%r-~$1v-QQ^)i!3LQQQm%)Uc_2 z>GsyPWgzebMQE*V1O=RZr9a6fD$jVFY5*>DY8gg6v;O;%rR*H(589n+)Y&MQWQDmS zHjil7X%yz}s~B>dY|yxXoNBg%^c-PGf?M_=*u{_c>$JWQkQKHzK5!^veekq6YL-+$ z=2Pcel~hR*dcdZC$S+VRj!7FfrjgCd>C(M2uLF^$i0xE^yt-pRj-Xk;< z6Or+FNqq`ic5SJ?%@WbybS+S^G^FUf(Bi(#@>~jJTvX~|QMHl+Sxx=d2l0VIn>{hD za!nNy?bnxjk5oP>zl!~o!gj03SFq4OBX7GI@!Ya2>-dYQI`c}0j_@|Gvr@w)vf63P zogVb2w1*U)9KCFZ=5xj*Qy{1Kys)qhLMiaa_pz_cgctbqFX}>&!%n;U5f8_G@CL4@p&^{--njgjrD`MCYgU z1~o6m0ZSyzh0bT-*^A|Gl7UH4;H%EeX|NWf5o|xi05-R4EXOm*e&nY~*3DQl4AX<6rT&DQ2#cd=ndGH)#5<$E0w=c!O z3!%1GMewKo=T?hM!iGc^Psx7Wn-x5n9OA$J3p!UA85I-J*>Ifz%&&PfFx^-Xhxq@R zYri@wS`&Qi6>Xm81^$PLNHBl4xFaO+KPjo( z2(3ZGD|-K)y?(+7=n$fZ6r4q(;PVJlU`YH>-W2|8euM8E!vOt3{;Ls-)ZqEaInsV_ z`K2&u>|vm4j;`ZXv0GInS>wmzV%EOK`8k3cu%+MwVF+y1&mV)kxS-nt?BSq;zrx3{ z?w@Cd|MhDe4-u1}`!D3Yp&PDLW5Z`w7ex%I+t~S@q}Jtpe)LG-1j^Ru7D)hF>+cJC zDiQtn#`uB8c=#CJV_>Zti0ArzRjiyX{Q*>&f;Kpn|L^141nN!B}lTX=AddIaz2(}aF?FRN_n|QLs*f2LbtEdihMo4B>|xo2<2F}+%aJX zQp($Nr-6lfwYjzvPM;-uBu7432$}V!&R{Ixf$T*NnVRmx?+Q9yxs+AnGrw z6@=QC&t5p>l6ht(_NMaXd2leSw|jdY{}}4~EH`l{CA~nmQVLj;N~sg3-=>v^3AOz!ljI((0&sqe3`9smcSX$=j zdz(eiLhU|FG;pXhr`c_eVqjyB2?RUwGNRihBv6UVVEMZH%@T9S?JA~Zz@j)_(QIp{ za+%C3s}<;Xo#_oXIn}oIF@N)U}4s&eR`cTzH zWK!|dh}s^YWtBVR)Mwc=kFzmep}}u~69o<=RxsgFmOc+z{CgKcMZaBy1jB*#wiD)( z{&a8LX{>tBpzfgw6w6$qj^pGvN2>LYrSkSW@%k8R#i3m%_8)p)*`?bm^W9q%7%NFe zX?)7i*0gsvs%Qg>xg>G;){qsdQ!A4+-kjvg5PXqE#=sv~@ttDPp-T6;IR1P>&SQko zg|~BIw^!wIh%)0N$%+3+n}5_l!>$S6qk(5djKgNObH@CQL`4c`Q6v zm7kvl*oXy|q!@o&VSasRP+Ha_W0q~s>2duI`SF#>6_Oz~mt2kE!qlnb9&AbHsco%P zoiA?ICY9F;!-FF_s+GF#7HaxCw(Hl2?_4%G*r#Gwc}~Ukj5I$PKk~lW9y@<|Dl(IJ zRcL9qT+8_3af(pUhjx~Z7dXAi)PXy_Z#1SFr`?85C4lvBA88ewadj5c8lqbHOutO6 zCSN^&YNg!svdDx%i8aJ}#P0pRiusKNdChIGc&hdNnxfDCb%KG-4e7IABQj711F9%e z&jfT>Hv&~2MmqIgkZ>N@RlJxIiDxkYX5_@%<;tn!9G<>D{le#u^Rz~|&S%iLyxd@N ziPOm9nJBR3ok#Bj@AwSP2DZO_Vv=QPhsP2<TKZx=SCfrWf0=8o!CYk0emxvn?w z#NUoTU~gR$5P5hIX>-`;12rn%Z^B#FwV%QW6AD@z*CK7*z8JX737j2w`KMR-Y{oNa z=YPHN75$8c*O$iTOKzM?nEmpG-`a3I!w#b-SwL@Sg-QLG*oDevVK2i#H493H&#bS! zDKxQs+1s$Y$8zU*Bu%W8kwh=PV26JoA6?FhftJhW+BT(^wcKtz;IV7P(kEHM8!a`c zFPe&_*=N9gShZ506uae50RaX>fJhcNMgEx`kQ9VwG9rMu)MQTP91b08x7-V>S1a@q z@6j)&8Z;$(;{1O0!P#r;k(?r+X3ZcSdoxEcQ|sy3leizVlGyUdtaEmkpOAx9w`wwf z%d@VKLBsp&BQIRsgByG!l;ho;)AqXikE%)jG-tOb-A1ApifS9bjVK_hZLzADqeIclvVI(g!?Z5g$q>*3-fH!+5#Zu#O~3c z;^yXNn*n#^Hag#RJ+03+j4@bC(5LgS|j;cQ&{(GYoZbF2QhjxpPIb-R} zM)G5C6bqY|=qh?V8)kWgQTGLuK>~tnDi}M#AcWq&;nHL4RrYYDw*{?i-1L>yFh1;r z(3NlRBlg@-_xhU(-#PumQ=Bh+Ze$|`HwnD1+h&#Q*^x(`_k796NQ&w+LEVP+(>WhC zAZeubNn8HdcOBpD({h43(WFF{{QaT@7HkLf&v*>Vs-R9@_^@l<#CV`hqf;>>wgR3HuxCPdqml)-)8|rYg0O6 zNH@U-)~346R9u91wPB=+7p=8Xe3Qoe5MZ`ifmN#*Hc0l{x}B#6W~<;+i2fy}j^0@g z9T~?eMV89aLq)6p{+K6eLu=m@-&-L;P=$e&dh3Dem!Q8rEco)#gl`15;Wrfa0!PNu zhc>o*atSuSKw>O$z4^~*BbOGB>i0QOschf$Dme7P!)1-Z3o@#wIwjD)}mC# zaMvR0P;MjP$^t9D+Iv*B6nZh(PF=d)M%I=)WBtm~cIX{l#+C9lU(u{n$8 zLUY;>9s=smOkh2-M553AK1fiw8-N&!HXOu)3RO6 zV;k6sy)b_NZV}Ks*v1l83@w-5p?8u`KQ--z^$DqLTjR4^uGt{L$R3y^i8iIfN6xDJ zr}}S$MR6CQ`2i6uB*dokt78&}cj?LY40WybW2d+&)fyR>V{gaMoo*iu8tK!kq3$c8 zEu{^1E7fwSw9Dp%!D)OE(fTZ+(DvA8jS#rc&Fj7K@#RWq!DJMtYWw5*w-4ebDkfX9H!`!k7lQex?oU?-W2t$ZY|Xe zV>6fa3B_P^LKmS%hilskn-RI9`m?k`{rcQ02`rUP)tvIBJn~deg-dT;llHnCAd|kn z79)m^9o4T_v!i|mi^|KhVibST0cmhU+2cu!GXET=?)Sg%_^VW%3IBZ36U$<_WvQ4+g%gY{_P>U8bJg}rL6HF7X5 zmdYD*W*3cK-E-r13vJtg>WiJC_h+)B^jf7qdh1WRg-8h0^OSTdHik7UEpfM}OXSNe zygoiysTm=uWb}rG_tpb<0z?4S;!g@xi=QiT*j+8V^2EDA5 z!%Gll9?7&46BsBD=FHdmM9^2MW`1wF;>DPfMxm}!Pe|8#t$pL@lA@p;LjRrAbUV#j znLKqSCHX@;6>}zs$+Pn=7Ivp|Q@U}R^P{p{lYoByvjccsfj>&K%|jLWQM+ZEK$lxT(3eV%qd zwAoypBgyW6c1;&D24Wxnluo~G%MjG({)SkX+vv4%J;WQ`>nhsC&h;%VEz{KeriKRf zd>$WX9~@>Rao8_kdJVxUJTgVF1Sa2?2qv%(k!q6iT!sO2Ke}|*F~rs9qD)j&RP{9G z^<;%ph`QZ$#v<*GW7SmN=Ha>J;GL|Q{j3>_3Q+h{K)(@oZ#u%u#`fcVPWQ`;jiC>L zyb1WP5JSQpe1N&Z?{W|%gWqE(TJEL&#UsoU`F;HuEN+DHof-&Sl^b7W_a3^wn;Vkf zNHk=xIh(KmMpw{9s^=*vz%Ia>G+z>`@4Yl5HK&|s?LL&gJ$bz>IFm|ObjU{{b+R)m zI2rfjGb1KEP_RnEX4ad}Jk{tDl3p31$Z6ki5~c1WI!v3#$+z7w+!(L5{1b*w_$cdG zr!gE46KFN5>Gb5by67}KFWJ;ZJR+C>671Ipq7~ zk?Q#`$cjmBoGHvu&&)Nt5k`=6N&IQzE^;lnqx;_?DBgV0dau|Q35FKh^Plis5Z+!@ zQ$OrQNj*rGWE`!tP4Aru`P|4a&5{%V?#^1(2g&K%iJShLVvlRJcR^@$eX~9!mAOK> zn^s=ENSA?RSYRZxVivj@nCxR6(Yc%=ylbuj3r{?1Z8qs;RzhqAkhD~KtA^58FBP^>6->JJ@5R{99qH&zxwU(-ifcWcBRH%#4?ApCBX@)^8D~4k zo&HbRWcjMguw4eV6+sKeVn$XkP(ZK#sPntjsc(aKGVy56#!;hQNTGSMgZt`zo#hEN zR9ZoQqf-UD?v1anlGyFiRE}sj%)*K_%d{}mxv!jq1BT3#)q*&vi>PQ=!;gnoC6I8R zfzwqL4JJE8TLoi!AxX_hhM466lzE ztE+Yw#!)KMOaD)GR~`=K*ZxbUtbGY3B!r4YWXl@KPO^-pu_a?y*_Xj6R4O7_vda<~ zYsPM(5@AHhzAxD)Sq8)JjJ}oW{l35J`u*|#uIu%O>v`sS&Uwzc&wcK5f9}tHo^v@m z*RU^Ni%Hb3Pw)Ckjf$_CokB{Nt9xGS+Be7gb|txariB2FR@}dG4leNcHs68X@P!)G zb4W0%vHrM5;<%nt_11LjdqyAd4P6{1&4KSC{4~vcEgl0&4i9qAhppV#mebL;HxO`X zF+XF1l12{u({j})V?u~Nn2pdHBgwLkiQK_?*$b#e$69394ecb76=K=Dm2oZv~!ud zC*CoEZ~0Wd65V|`{@p8YR~S&qvZ4%0xIoWzW8`+Oxi8{`PEw7Lx#5pUrbjW;Q{cyl zDZ!{N@ShuHU-2dX13y>g8gY!vb1{rQUapnco6!8(?QQpD- zc@|gB=Q6l2L#5#Y5pCehWONIBV{5_ZPhY!Kr{qS=8cVKyY6{b@b8vHqp_q^*T!pz0 zD{r)Wi=v>gvfGoNKss=|z$es4r*_1azqXYAy`-7eX8f&UzJ^S#xSPV!XH83!d8~s> zzY34{VUKU(PwIQ+KV|pL%Fftis2A-949PuLTHVT8e0;Oi+?w&8 z=}Xti>Mr5C_6RC*m;xsdXF1AAI^L@gV4(j`3=eGmyIp(X{lm|x8q?JVPx{D?fRDGF zhfnAcfVaxfSXTQ+ux9O=JN43Q`>xN0`cgMOCc@0-`%-v9C#0}vg(0#LyqeP*kLMG5 zE->9&070PKo?@sm!>c*r)t>1Fj~Hj;k_mZACe`ZMmw z5|-HIx+^b+$rv}kTygMspG=VaJXFB@fQ7lo*;QYy1>WP=!+59Rsbmp2%O$sAw4TrC z+gOXc)rKjV;^6iw#Oxks8Hlgx0EzGbZ2*KHJ@%$x)P_OD1FVx`n0KZfpdu=~(<5!*7Xg^OMfNFfHVFJUpq*oC(hG zkzB~t%}eoKKK7!OJ4I_8Zo-^yKAdV?^wlM^IT4oFUcY25`NpPw0((Kp)DoN&yBvi#ttNU<)2c=P)iG_Sn5r@f!_Bk&`6 z4uEj^kEIDjB=~d2BLhI)G;5q0cR-;4DAB#HRZII>K>$64xWB>^A_hOC4XihA)=LD` zK7<7WyCv=IE4AxYfP-K_QbW01Cltsp|ES=tDu-huUAhL#p-lMJ%mkfoVZ!$1bwM6K z65vSTX*85dNu$lc>}?b~K_pBt3@UK4I!3?!?y zOxaczw|uAMoZvwza2Z=#lE?2wW5#pZ8kSb%_0Rt3v!!78Ik&6`-unbXL0Ke5NKCEo z&TfejThsWOB0-}5zK*GNh8HNsF+?t$aqt|H6VAN957Wl^OL)Xrar9XQ`6pNeaf-b8 zNS2a;$cT-8V#|)a%k&{aOfMy|nfe`7-Q8n~1HmLO>AQjf{*lBOk;?*gh>?k%Dh4!% z;6H>T=(LdxleKQ+#?r?p&JkaYOlHW3AL$XHkwMTidmBGp`8k$5JqJWVd>L~Jb+nNs zvvzfW7l?iNL2+c=%kn{L#-+ZBnD3#F!AMU+uJTgr^f0myggMAY0v74|c)LJP8lQBM z)P`#`USd}tH!lxWQc`2%TEqE0$yes_ru@+Y23?7Sz64p|ZTFPeWu(4Svl$A9-Z^k5 zkt;wx9?}+*FBC;d`|sL!t(qkza*~o}v|%zjtV(Q_=MiF(_So87v6-LTaiFR9`OVQM zdL0`Qt3k+JK+Wf;HttAJUK+xsVc_{ttpWFW30og`K0Ezbk`oBRV~0m`=vDNPbVd1# zVuFm)1qob28lO|f$4QG@Am(WxDZyEM4{9ej5|o&Dt_aI8a)=a!V4z-CR`>#GCl8PaG(Dqj7;KLO} zuWa{=)d66Se79m-;w5u6VvDjA-Zf5JmM9(JyLP?>F$^?Fg>A1hlQgH0Mm%mTmqc_J zT1X4*K{$coOjoxE{HeI|{-{$%YDdn-Lnr4E`uR8M9fgOx_<6a{7-roo?2m;(n#@?w zdn@>FBd!U4pH8g{IcPUGk-%p#!X7exm-3LktZ&Uh!fko5B~dSSgS{0*rv zQBSshX0?Lmmr|E{vCKzok}kH(!EaN3Y8f4HxCKVC}x?0*(agArR1Z9VK_fP$s#1?}R)DhX5Qt8*^RZ zjZU^c8p*4jw6Ik|y{fRHME$b)$jR(Xg_^(JdU!arTcc!n_CG|9tK|X8Vj!O^QrpTRtE3NP}5P3 z#N3XT)s$3n067y}D#}sHlkU@mTJ`Bq@PMVIEkwE9=Ei~q(x@I))xQejOF1A1aou&s z+G8WhVIaAlJvRenAKJ~{wSAJ@E8D9Vs_~`7b@_0V0CeE)Bl~4f0*f8a!DI(i`mY%t*s8;NwF022>5G#?x?|3fis*(%8$AGWa_O+aoj@K({wl8<~ z?nm=?`m^L!FVc}waK8#bw+I$jfdJu`f-y%@#nXfY&ao*%&0`uIX8K)*uqtBM?FCzb z7^!w61Qfk>eSQ#8GRM%7w;XO<;*{An;EBb1-4B$sLW^(TTog=KeJ*xYYH70R%7$2T zN4BO9?eXQu4lxGhhU^K_c(nWW_X;VAqQR@@oyCCPrI_SbP;Z;2zR^jH(8-#X40I3p z5^g{*Jrjf(Dm{4C8rPguZ*N^MD#W(ZV*~ejJ#%5P-LKy)JGtnP%hHPT3B(;*B}WN6 zv_Y@_eE_M?sW4EBJ9R zX~cAmGF~_;LNNA0L$z@)-_pN6Izt9=u$`_sfh5T(YsNA}bT~7L63s)=r;n;y3 zSZ-jqSYM+9>(&+U1%5qbd~6iI2m9RGbiK_2zBB%aVRQVEwIM})QD>aphhl{24@5(E=hXxVQho_&@!1~bKPyw^$)k`dxaMviBZ`PH^!U2I zv@cC|jEaWH!q|%`nWj%t(LkO1h8g8=5do5!CNk0|bnNOd*SqGDzPwaKm$uwi^0ylg zB;ZQ|X6R;ol?*!1vOD!ji0^d`1g?MYN%JBoWU0?@X*1@pj8p0py_WMuM$=3A zl(Qo)??i>-#e51}T2f|i1LE8F9Z1l)w0<`WX_1G*&ZMaxj}iDRvuvKuC%)Nt^~QYY zQtU(AS1BwA{cl3rGHGBtqP#XEW{s32N9#_?bmdGs{mfCy>DN z7sU$|zI64Y)5vE|edNd#sFy9-<31BfsToeHr7l z2=}?Zd6e($dO9todYt8HTFuvEY03w`_U6@mMrX*YP`ON`&h!-8R$;@L$-vv!wb5j&;<5@4&QYFss=|l`ZT|kVL2v_ZY2cqo<8@Ilb<_3};)m z!&&V^fbfjgbD!s;&goB_A3bu{1`DDna4E{Av`sVH3SnU23)5$o9JF$34N?M`$A`wxtoW6+#fM`dA2co*4Qq3_6&Z^};-D$$JfZrYw z#?3SS1*nBC^0pTgI@wl$PurJavCIDjCi*yephZ-Q+{1l?#M~_Ik^rM?S!ZmkeB4uV z!W>k!W+WUU^zr9^nKZK4z0FBynbG1%SzI2D3I9rL z(Qh_n4Y??zGUbS{rNUIK>(G}W=0Rgid?-FBn#M}8x6h)Koru|U()3wrKR z778#BqvdJ#Aq65Pbfr7?`{uJ@0lIIeh`2GD?CaIwQ%Y^*8q|*tAydq>m}FUg&S4_R z4AdDK!&AVj)ohp_Ue`{dm*TyO=&`WTw;=ChlBkoB;=k$`MnWyD^@$e6p1;c63KPxWdx6@p^a#F z1e>ADgMr_}3WkObxB@1Tf;ys-_b$hyK=sMg+}bRu-%m4$pWzmw`EGQ1`)Acek#ZzM zX1#*l?Qcs^)9&+*|H=je03q^Oxewxb^;YukBMNGT3X}s@cQ3tr$j}_-Sdq=%yTMk$ z=ztyR0B-F|xR7G@TN(7CHyH?wCDK)rvd5+R$dA@0-&BiaVu}2*JVp*89LIH1m7(B+ zs-7sB;&!~Uujp4O-)Rqkq!3j_w-OqYxLzi&ZIe;P8UIV zfL5DtP2!IkvIH)v{d?$u=37`(iY`de$d4{!q{vQ32A$G;KvzT9 zZU!MH5kVU!k}`|7NPh#?;O8B|vV>S)psO51P%_nKI|VSCk3*SE|I##{g0?>nQ~EL0 z{w^!cZypLZ$})4hpZ4jD>I6z(O5QYoy(qPHyM?dv(_D~ zrD~kiw6VFPXu!6=71PE9M!PhC_JE^GOyg!jRQSF*E+Lv?`gA#xmtq8{z6`Yn2a8E_ zOH?Xpume9h;E>9pb?qxL!nWr7gHUfksVrOdKeCvxRM*bE({b?h{F>d3YVx~*9cg0$ zISoMpu!}LZ&tglR&VnRu8qz8AOQF$#xQ--dKoV`uAOApN_CAvS|5_~Q zU;#|QO;mpt_)-2QG0*(yA9ekG8-NLyB#FWPuKyFn(Bi|Ze`p4==zqSMf)tlx#1t!A z&uZ=pBo8?P{?VDbUG{Gy<#~~#ulVS6kh|@n-O~E^f*JyO=~lwKm#SYf4EWcSfnS|Z zrOvMnHv+j^zs2+W3M3dQ@{(p#{uHS=BSm$f4|(wB=+9q%7u&h|U&{XLZi!!Ak>-AJn(-2Fs9B0 literal 0 HcmV?d00001 diff --git a/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png b/motion_primitives_forward_controller/doc/ros2_control_motion_primitives_ur_whiteBackground.drawio.png deleted file mode 100644 index 6b731fbcff7acafd0a24c722fa919ebf7fc253a7..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 441153 zcmeFZ$*%Lzwl1^<0--D27ofkTOXFmsh}xI>!;kA!#z`aAjC=?hWd}x^>^R2{gvQwg8m!!-@y?jOFlhZ<$~cDY&h(at0~KS_?rB4*6*#iY?`aS z`yJhd`rGAiINbK~S3>$L#=)1+MhJg~41aV{oBf__!KnWUu8SU^N`Lol&sU23BF|`T zR3FoO45|P4Z?E?EYqp0nMML@M)2x9@q{r_i7?S+GX8Qfz@lOo#yQ7%?ew#mcMLS;A z`DZ-8&$M1JboMQ)it_JwhV}V>!O{JD(Me*eAv&#r%5v)@_%`&>_b54Zb=CH=?4e?O@`gseeJ@%L%|a~}|x|L5QR z=gFG>S+xJ(T(15nuGwq%I-W7*Es^IZdjC)O^^at1QM3M;eG>#a`gw|IO3G@16<((d z9%}06%YTG5U#1>C<3GVq+b>A;VNIs0t(Iy7vAJM*Kkd+v)dHMcb2$t-C3FphDZD4_r2G4NgPbTzDKf#`^?_j_@Sc>M~ z?24MIKF}G67=Xh=o0Mv5uXeR5U4Hx&k}@_6&PV|S(K zIrwM1+){E2`1D49N|L~Z=!5c7?mv5YCFLDg;y7Kg1bE(~x=oDlG; zA3WgGjQ-Z8UES#wSc0> zdg{8B)+FcSs9gIBd0xX_PxT{kL-o{}${8< z6Wc}v*+%tOnyyNruvJ+o?SABM3F%xp-tOJI%+o!wHrBa~>Qhwci60&j%hH;Ql-hx7;~dfyaXj z1RgKEICvDe(Vbi2fb{#^j?2G%bO8QTgmnb5@~A}n8)yWB-1BBKf>{q?Lu1g7iRNd zm^596FP(&xOcQbO%a{I)O7~vwpl3N>Rd+$n>aY2Br2B-2dTlBNrfeJ|Vv_CO`Df9u zLK%iXdeREHy>D>2qb8UH$65GjdHX8wPreWYH<;GuMdm^zzI-?o?w?o2U8i+FGmW}I z+{;@$ZrJWQT-l1b@wP2;)$`FwDx7^&!@de9DKz-r5V^N_NtnqMh1@mp<2VSptXUaJ z@Pp*dftE4K(;3o(Z^Csodz87lGHqH8OF5cKuu5eEKa1R#!c&`#W=>ylF7v6J5)I^5 z!~g2~`*m)S)bh4lH`qryIKg|i+Hkm1ggj~MeDrk2>_}HUO8D>XE$SMaS69>Vf2LZyq#(J4B8Hl;@)J+ft|hbgI@!+b~Flw z``^n%Fztq4_EP)I;%OPt;$KtDoN-F&%v6W#d-AEgPbX1C#&R47d$`ZYV+Nn+6EF{w zJh`N>2bnLb@JzB*m>fk0+|?}i2i4gW$k%PcDY*F!^D7B_Ki^5i=MrCUcQUbPCbM@# zd@1pXWvl}j9pI9H? z+sEqS@4h}HFmyiHvy1=r17|%i;ek_ZSaHlz- z*=&7&O?!Wc5B~F*2{QB6OZ<>KaPIQw(t7A zb&M`C>12&Hip}c&ZahcBe)6_RtJwPt%~a74EmM z^WtuBN)4L!(3*!#5Gy&WG);fSG5QS17^%E{FS5sVDU{-U&9eL1)UT@|JiD96YdlR) zpBp^1Ok)FiGv1TD5>Brcg@F4tz7cfu`M&QE%gQwT97j2$8#-2ZBDK5uBd$F7TEZgZ zc7bF=en!0AIm5yAp1|$Czy%}QaXy$OnDDLnNU)AM4DezFQ-ds}oCY2ai+qGz(Bo!3 z)6{+)zhttZd>xjPxW#dt9Tu@QjhFAI57v+Wd~wV>@4b8r>e@-FmLbfRQ{L1ik1opu zQpZnp*AYzi_3hWs)i4Nlc&3yYQh4M=;#GTg6U#$-@ZIh6g?LFS+QbTGA4&b{?dI)~ z9lN9l0nbTZM|uz)L;>&4lU&T@C&@DVnZppbdvMJ?%6%2Cs`gcZln6<|!>c4eI@`C` zAS;ad-%#2 z$y;wo-q+K@9+=Vw)}{FtZ$doDnXswA#&a*Z-X5`Gps9Yu1Ti7EQYYj|64;xyG+tN9 zK)t3}?>;|oMN%6nv7FwG94C72aBg0H1y$f&VU|H`g$@5MvtIbYq4_Kx&9B=dFKMtG z6`Cc40 zV#_C%+-_Z6aL&2!+=DADf<}WkNs^?+bHM0pE?+}k4lh=M_vgW%cSWo0b`GXX#JiW& znX}b)sQh3-t%+L@1UV0L0Xdee5d_iATfWue4ZCjuOI`S51?Tq}emo-l31gOI|sQ`MDnd zdYYYB@FVL}y*7V%53*gb-=K!*ZYZFq2rfAYN+@QZh>bcl0Tp4yxs@a z)Iw2Eu~dE@-7p$zZKp}u0%*Y3Bh~613XmAOTeBw^H9jrDPqvMDj<%n68p5^EjoRiS zHc5pdr&R1yYx4&OQzksp?7QsX4;)Ve$8!>}geHuZ7wMyN8SakEpHx0keVf0UVbL;X0I*Lf_W4-=680QSJ@1_;fUr3kVty z!Bc~u-_)s%R(*Tro$xP(IfOpg5hc#EtXh@wn*78ywfjDg6w`To702($5fDS6h!eJ? zZj#nJ#r&aVfly)%th&TiAD7z|$sQY9x0vg>UcSX8HY%1Q6 z*mvHsFUt_&w5#)+szQ+Ycz@T_sZ8hVh*28Jc4#?MF47kHd5u_dzM{$9TlWlS|8WCz zDPjftd@KAJ=jTK zw!c(Ru+4mc9YXOhjqH&xdXouRYeu7hW}B|_H8JCd5;|h|gb6@aF>}r=dcN-d>-2s5 ztDv7e&XKPHD-&shIRFF!fr-GWSZ0Pd?JGeX&30NI6uu6LB?zqobMd;vO^`M*(h=!H zG*ayC5Q8m*Kzu@C2}2;%x2Vnjw16gi5Uv8G$CE^6J3@TW)3(iJ%Vo8i-X{Y~yVzW- z@_SQLSRJteUrAU3BQ$dPh-omCpS{Hn&oRf_e7%NoJacKvej)hNo_NCUH#PC@cCCK@)HMphkJa{kR@W{(4Ena;*MhY1N<*EbSZMmq0B(-OrStVNZX>#|%pOhLXo z%qY3I27H6t^;q7%N6_vY=er+>8hy+!+&4odd+vZivMA#=vOgirA%oN7d1Pr%ecK(2 z!M@~@#zLJn;gO|d} zW50$*t-dN-k{SS}Ic~6t?U~f%<6Bc%Gjw8e4&#usaYi-s&MHSbo zugWTHwaV+G;5GV!H*WGzF2{|sQj^)_MLJRl*jV}6NY{RNuaF>|HYMqb+$;dl%D8sGnkLz&}QAXWYY2P5tbCfuTGYw+{AsWwIj^ z3l(O98+1)m?uTOPhY7!Z`E$8$7J0SupGbh}=yiN&HA0SNh-)Y6Z9Ktdbfd&BUQwRd zTX}xM-E_Kl^MJvp+wFtm_4SP&rFcWsis3w5AFQG|z*uibrbJCkfoWMG(}5s9xx*;* z#8A$-7=~pX`$rV>y3s#I;oOfr8R=KjgVPdWI3cdGItie$ln&g%NDq`vPHQ2`s?IyMUAH z)*E044+)}Wn%7e4u`i4#IG%DR4!F=zo4iM2=#s&cfRN@^?+_#BatLlJfG@%JM>%B3 zKS;GNI-$B+)6jF+r?ypf3l5hb2F_!mw!e?wYrH0GjPg`#qmTMDv|0h^np0u*LmLFP z4ZN?4E$ghCFBr-1MvCg7Tw`9v5`b{-;Qb6mM|N)WyqWPNH~Q*pvAT|)e*jNFc~e$j zj6UMZTU{PJfPn%eixNUjP&OR`GN?ZI;$ey~KX9ETTdm`#yv+*t)avl~?(O|rjq_MM zN-r5_8P6x}t>)u-dETEkxoL7lNSvaO1lX0rzY-bM<_7(PgRo?5wBI4?wWz1-53+vU zHHc^(n+7Y;KQGxdX;Qx3KJpg-K4NvR8GtE*HeR}v@Nn;T?ZUU^DjyxESw<@!y4W?> zyQ)c_D>4f(k0^r5Yy3i|>+R<`WEsMyTap8g1@VA{A}1eEjuE1#7_z!zRiA>2*6j`U z1ub5RE^)vRkbR@jQVI|`j+ZbK5OAX34f)b@$9cP^5Y;f}F)dRXLk?IPa<5w^eFto0 zQlDJv2h~-3C@#dJHXQH7#EJ&GlWgkta6V*}(JS4DaLw1jNx5}*ItHz8p05Rj1N>+8 zbJPEl^BlyzYoQslR*iyH5L1{uCb?Ae5!-fbDe@2jI1RWj#G_mPF};-3nYnlQ#)VcwmUbMZoFc+(NV zmy|k&l2CDH|IFKFzdDTisCQw!YIkbnWX%$ z=$CKBj;LUzKieV{lmN$zI(~#uFBrY%fTKC(FB77QS^T1f8 z_;ZQ{W*9GwvosXQ!1lDhW`0%_;OgJP4RtT_^KNvv%=wNYK96jcTQ~X9Z_R5F*>P|- zZAY-2Crq-gT&$b3Do70IZ*vr(BJp`}FkGk{vxuZ0ig2cen@8B#w&!2R&kzc9bAlk@ zk%BKrtTkWyS2g9Jzuq{C`5hNcW9EjR^2)j%Z^v>tP)N#q>GSde+-}P*`!;u)g%IkL z7|S^K*~T8CDVQiCCqwyxV_Dwa$w2ecm{6suYKACikzg8E%c#iYlBTV_8AVZn(ZCgs zw6s!-d>Ns6{nx1dTXzmbxCW2zm}4arqd1JMcVh}=uMCN2E0PRoI1I7n-{3V%8qlnt zb+(ZqU^p|e0P{+xmAywKZ9Nz;P*i6Q`4GYEGhptR z!tY6J)lp&S>sQgH;jPGzi<{x(YrXCGEjZSj=i#gjes;Ocnwhn;QtXmn?JoLJ3Q8Kh zxwud8sGco-ZX6AalZ!yW8Oq3Xv520IKD?Ywl3Vi%PR~ zG|TW?k3+Dw09)1=WR^$Jse|yqIGEVJ`7m=81*EK&inPNxdtCZ_u1v7H+YPm%o*jau49CBQv!dNWR5CjCAJnW?7^=tr{}t>e(#Xl zfX#!S(A+Qc8Z5N=l~7*sg=+=^vj#dsHbXs+Rrm8M`v}m!O>RxDi+#w}3b0PxBZ4`X z?dkqVJqZ)IBa=X7r38vV%MFIaLj1v#aEeuaf8;b=e$ZYC^1$F}1u_rw=+`2Yi+eqV zG6j;0O|byiIHXs{A$uPPWS|==R{^j*^?)CNuYd|ZdmK;3IKdQW+0V6M*o&E~L#_wU z$d@#KLU{QwjBd(qG0Mdjif+j3)pkEp-%`M3LB=3ZNcYWiE(%ubOMYVJ;?)l*wac0c zwKY)(4SHX~4@C1}(K7gt`I~TG_eME@m`aYepu;t34t^r)%Df@lXrhSd%7XVfOZ4Ei z4Us|=cClv;S0kIQX*7B7{#y{$So8(x>#2F&UFXAB0>vgsiwa{{ka%ndnm^O-EJg-Q z?xLjG=HnhwlV@cPxqWG=ONl_Iv;TqM?kGTp?RtQX6^3kHnU%G{T=H#kC2utku>>psza8zHJ=6^y_KkGDE=b1py@M zp9uuX)t$lK{8Z2URGX*e0)Bm zd&DT;ce0=_SzAH+J}CI|Tw^^ZT|EG*sP>S9BA%h*-=Z9v2|nkqjNdhv|d zXx^dD6Un~eUm+fn_V(dONAY$i52svgSs;;@?|uSn?kuogGXNSHUZ~$1A6ZDKao=YH zY=yKh2I$`_cRDRjnq4mwOtV~I*+@bVAzS(kvqrjrki|aUAU$m-Z^VUvs9^cJETCG~ zEtv38Ip^aM)lsxkEcZaUbx&W|Tebz$o}em(^#W-@*MV(CK}j&Yq0q4&}|K zbFmTfoQhKlrKp@hQfi@$Cwzp5`xM^@gG1kcqS-3!pZh)Qo5fttbui=?=0NJDTIDrU z007AJ;AP@|aUm{O9I&MD06UgIV6OaR=ef8)kftnzJqN@Gr4KT1q-j#Hw*g!OhKE-oH6P^ch#{5W4ft>bPJ%6Xr{p*7 z)JNB(eyuW!Zp{FUpt>KN^8m}xOHj=##G>L0D!n%Xp|SFgEc5TySq~??q)^aXS>^)# z2Z5>&KA!I9MJqyxoFi|Xy%@$Kvj)PL)?t+lQ_AjO#+WOOrTWY5ydT|hTI)$$9rsoc zB3E2ZkpUD=MB13czmx~5hly<6pE%i{AjY?OS56PGYDRAuF_VWV*w>#umUnNNefr@i z;hB#Gzyclu&{mazn9G^7XCS6)3gV#xcCYfgiKcMF)e_1OgQcAU$GVTmb;ca3lgkzY zASLO`g${M#RuMC6HZ6)Cu36i4*Vq6!=lc=jVw?xgR3SG52nZrkO6TOyRD30Xwfct` zUdlGh^XEHiK!z<_n!bN%@-Y zlnixFDE+)eizFLLKco&}O4$0rP?U-4vW#_}CuM~C{k|a-Sx$)*59ij_)@h}uv%Fjc z&=im)-d(`_oo@GZN96Bim%ny>p3_(|HlbPwG9*(COh`@vQ@Y%^Ju!D>zj(CAVNijvcnVu$|47IHT>{tu zXpk_gEDOv!`QA*qWo`5Pl$C@%N!}PXnOgkmlF^Ji@^qjuT$Z(n9?OSwaQON&t(UYu zzhA+CI)f_56M^F+XbX>B_Djf^ikMb=Xj^orJvs;W>%ilBT=TrgL_qfnvm2riOcVG6 zj-&y{v>BHh)p$x`WDuD9wGra!Z3mQZKfRGmD!|~Vpjn2`3jW2W zY8Q$_J;K%bXaGM_2t7pYsGx$d_trC-*16l?q|p#+&DSs#RrI2d2dlLCK*kY~?S(qz z=Dm8)gRCw{Bc~m{NonNMk%1d0Zu|8ieWk)9QNCV6%=PZ7B(KwSYxMe+Woth;5^3I- z<|Yxc$GQU2v2q$tf2=&x!X?wglbc{)-Y_}7FaT!ZInki6KZTj_tIX-~x_d8$XY!7< zzTRj(jR!tcwTU#_{#Foo8bb{8FBC2$g8;vQ9I)AEljmXcu1mVoiSV|x)R5Ch;Z2hl z>J{S)_NZ_Ox%v@1v@$;!H#y~ILKBQ^<(umKpt*n^bR$K1tdkNU0r}T#vg~o5n7`e9 zLIG|7d|RFEz@{WS-=eeocJC)?9G>mk^=d*`;uJ{t=Ix6aZv2W$+#e305&*pl>T8H4 z1F=Q4R7V214S?D+ecuP^@fo(z6T%eYU&9+84wA}xf;8EVwn%Cf0#M+yolm$Mae>%) zJnyDDza12RU!cb!PRP4$uTD|Df)$LlB%{=YfA7jh~L- zlN=tgbRL;C3=p;Q3UbFAJH4TN?|rXhaaWOWL+xHc2@yJ&`A9oHP;j+Ym#BDg9o?Z?V?s6D`3j?4gKMHY zm%3duxg^&*6m-bNlirQV*>D#!U5WSNK%~R^VII>2?kyG*_NWxY6SQ~z4E7cfRrN}C z%egG3Z~`%mq5#L)M9O~aOm}Zy+Y?En=ZQ9Wa=>PFz*wL7mY;^ujX__634Qi63toEu zQVN>ok6U2FGy7(_(FQ2SV_6p?+OIx*%4J>ex3PVeFJi>Imw>&hOl%sQ^;u|e5wwYR zZ+*^O%}EE6ZxbZoA0-vC3K+6CwALDuXV~7WsZ(Rum~aws=W^I|zBkLM4H-VYfa{Up z9R0ozp_U=GyzKDpEd8MEP<8WUGp2yfMFe2!`2e@baiG3e3TEqo(xW!47nr7IfXpno zPIB{wT#d(tF9f(U(83^+iv)?za`glIVITZ2KPPv4pqT6Yn%?*AQupOePAI4m) z$^bTR32-HFlHKQbr(k?{lUbT32&EnrPOl-t0&=4_#+T1&fpE(Piq_?yz*)vKe|nBj zy#uR>ZU|chc_;jGGiC9(&-jYc^aK@*+a_%VLglumO^Hw`&+FZL?zde!?0^2&j9gH`p!Y}i2I2cpp%MorIT>PU2 z?+92NgGKc3sN`Vk*?b)58aON?SnYKg?{i)!h(GALxbah+fxNDj2ldm(s8kTw6>z3b zfvu;W@a-*xLC;Gw17b-!Cru8T#-5_NehdEP?98WOX1q*2H+EUxS^yB+f2xkrTdCAoz`!ZdLDBggb4BZwM}XrrR+e5{4r`TdiJ<5Yfgm;7#_FDyDG{{GCt- zt7gezal0kS9zV7FXKXMOEFoY58SLBdZ+@F76`)PTVSbR*YusbKdePr|Q0a%Kb;vcsYyfJ@6 z!72rje>lsJJ*VrDE9!;1wb^vGOUy*(grlj*AQ~-5Gff5Np}8lid%VMCbL`*A$=ns}Z&Bn5+K z1Vjl@tv}r@8E2W<@8!t$jWCb^T${PoE))I5&hzoE`>tPc{d1|Bal`PvfY{l-i*`2z z=@=D*2vEO~v$+rG7?9kzsV^Ca@kPC<2=KU`r(pRz)+6fG2%wISpDGuf^sRjl-0ATF z1}@6-P^8jA#y~-YJsQENxGxVyl7P1=5CI`U1ZrUDJfJ5b6z}hG25sf@trMa-n%mCQSnpjDGCe*UoJrzBg~ z#mI0>fC#a8Hn$#s2b2nD7O6&n57>z`!Pc~`WQWI^#{-ha#GEd z$KZRA7Yv*WJwp;$l*jj70=q-`?U>Mup)n}ncmj*!(=iCMLTrJa{+$hIS$aIdR{=jN z0`UtVq>6YHwLhA-K7=F90#eJ_8OngiZl)hp~Ar$Brp!X>*`8~ z0%A^tADibI%nW7ORyQ4xF$20pUNjNXKU^u=T%PwG7$@EKZ1IoTKV)HI6B?Mv-ycL^ z@s`!qO}j=R)<;DQ=ja$enlcS#fyKY|)#y9qcwidrdcKRVajQQ9Fc3mnh>=T?p>r%? z7T`}=!1+~{$p-ceeH($LbXQTN+4j`(iTmsB+^vx!$#P0k_-FV@Zd<_v>DjFe9i&2! zKup4W3sNM@jgxGWQj|a=7NhX})nzViugj$c=GoF-$xqY!z@Vu<__!mcH_ECRi{CM( zpBmKzzQLuOD0VAn$#;X^x``Es{4H$E{FR`Z2CT|FM%+eOLP7(Zx}ho?MDpWs*WxKx z*C1YgQ1}$YscA3H_l7Fns80a##}Ow|g70ze6BwVm1#+rIm7_82L*#9i_Gg)VvN6EL z=(e|4Yu<(2QsUT4L5R4I^YnBu0g#apcT zidCTywSfz3z+K%3RD1bOS_4eD9U?oAI8s1@Xx+Gl?T7i{IvytIgnYs}$YzwMVp1}9 z#_!4`wPi`)G{W?*BgCl#&>b%yj&@LQgtC)~AupU%!gGA?)p`$?PI$`C80csYyTX&M z%PKtpRR5^V4a#ynwbDy>dz~&=4LN`;iOGL3ls<;y#p>(H19GCT2=zj?u?gk0eUhoJ zGVZQCLZRjHk_S*10x;&vQW~7TGS4|n=_;EU^FUEXMPaqs64pr{P z9uIeL4S`n*7dmkgrv~VO&Fk>7booX!pSOFx2>((iCEwqR0r1O+T1!!n1G2q4rSq$!_IdDLqAwq0RB;}CdqWVX}UZP8cGqc=o zV*$MfZwTXp+qNu$drVgm+yGNQuXJIcwI%CRr&sBFy#tC&gH4a0Pk%j4R*{FuANc$5 zu5Z=VFOsBdzCd|699g+y5t8l3|u%?s9k z!6TeKZd2Oc_UTLIpw6$R81 zhX$R6VW)lP`w3UW{Eu6Gz@ zXVHTYK9bF-03F<|83L(HWT+g9m?z1QWp*n<)KSx(={9x!0km8kwMtN91WCXbd9RsH97rFy^;xchIxaj?(j4jVuq-6@%YE_>K62?=cLgN_Hp$ zUr7V?@Blr=p*9_zVIGWlT49lAcu`>*cjUN#HaU-D)JcM9Sj7XXRPqul1mt5C_{S1D z3Aj7I|8UhR@es8ToD%2TnfNs!P7$-#$2Vwq4CxKBduR}YYkFf?ihc_XL@-|_TDLcC zynfhWGxYTK40toX`&L_wrHDzlT3y@jiaY2}jhgzWtS&OjF}-yxbPl*I(bugJ|2vN= zj9IP-y?f6ReftWV1j#H^#-aWw#9m~**5-%R1vkj!8epYuB34Y)?BLTP?Sf4~SjX>H zP5SmJhXr^$h>3hne{!qZ<~;FIhi4R1xSol&EnIY?6M_67LC>fyM9!YnssKw+KAKOl zSi@6cH~o05nzFo6zY*#?LbP1q@3(r)iN(VzcLRVX_V&Vh4XO+z#Np$&xX!Y~AX7*~ z-8Np1@Ar%0!YlSK+gi}3Nwh)ZyT{*W+0k>uO5Mvlgz9C(8Ch7{C+FvSLM+9ZF63-1SzM z`JoMcl5Qw+A>u!Tz(YeE2$W~3XD)@cbeV8%k?zo!_QgU`(Xf<%QrnZftOpK1SaN)U z9rKk!QM$i0D^9+Aa{2aPi5CFG8Xv;X%l!vVHBMo>8@GkZYA9~clbOcKJH#&@7e2GH z1KO$X@nSBPkY6z@2Mp>bUt4ETtC5siKpb-+)#9Pfj*XHn0WoUFG0~00lw=_H`ar@I zL08zu$8E6SM-~FQNF)v;J;uj3s@IRD<&l07O+lc;v9DJL9t#D47+EC zcH;toF1!TP;e@KSBdU3r;P=}p>bwXvMltG7qT{Xoa8#x%nD-0%hiBG;j&VsHq<3zk z`x%Bl7?87xC{BGW5=^5wj1e>yo>wLW`wl0m5XM4xFdRYMob0V0MwZIbJkk^p|v;Da+1Uk-qJ-!p&!-t8Xa0X~YrV=q8_-9P}xA*qKK|2WeH+ALfK~ z2zptM$$;+mFEDh$cCf-}@UlyiM6S3?{vyp-yX73)tvi<*v?vR)q$< zD&-EbJ6uS(2HgDZc@kNjtdv-kNBvaE;ny0o1JqGpPGr2kQuGwOi9J?>dhp+Ca=Y7R z`Fvk}aLh$s8@L zGa>y`V$A+-(4CrPY58&a8v%W@`T1>VRszgSxDSEQ*52gb1XhO5@?yr@@d8CLs6iZ2 zgA$)t1;mn@h*R<%d5Lm}UY+i)8I?khki6vpJ+nVPwrS*`z$f6Q0Jl5P<@0s{P`?uQ zP=NJq(yW>Z#>iw!PKDmc@%s&&ySzl{xUsK86}H{@1uZg7xzk4NPDuM(X!r*zPOy&TxZ zER*K*8T^0*mj%mv z$Js*%{4Jxw2b2%Js79`*>1MuHH1;B(%l<-qKFoG=Qyi#|a#ZW`VGuNV@CA2OQGcHZ z1n2o#Gx>4W+qMJ66K|i^%nOij8tMj&vBM^#4q|E!c{-F$adU(N=@L07ONGvx`6f%V zT!ZHc<*UV!yu?FB3KJt=R<;u!TF%{Yo`P2*tOn$nq600Z7wOWXHxSg&SQp?=J<7QME z#!tRUuuv1@d30&$ti3l54kXb2I>Gl3c}SW_yn7=Ljqf@z7Ao$!BOiy?0pYsf=W^&A z`RPH}9szMVdK7IBKub5NU47^J4o@cSSJt%hVo&22a8;(T0syTXaw%PPTV(D}I(g^; zC_KRG5+eumRC~Ftu?y67;ngS*OSKTFe?iuz@~3-cM4cQYcCpjF0efLSVE}kNWk4Z} z2H+6xROi5i^9n$yB`R_jfMpcD3sNmh?n8t@$q+0-7r{vbIwt?{How7IM;OP4cixRG zIy>j*4b7o-qPXSAV%F!|p3dpuT_0iZCDerd5cr=5_Z!~>Yi2y6#U8lSeV2oN#Lm$` z%7h#{&0e72!#LLs-Y261&Z=i0L_p+C02;v=#egKvQ~#;_?+YpT&#HCzYq^AL1p0G4E`yohVG z<&Bm}$I?nQcGX{mf}5MO@=m%}S9TdDH7albupqDFO+ge-?s(Wxo2}<w zJCOPjBh!I*oBVdm%OdpHKNP8M<7&5M$g>Jmt-*{fHZMl$QJaUxmRZm>$#!mD0~HCb zNn8n(gYw850Rs#Nmh~vsBavUOKy3&<@OGFamJaTT`U+8`^X6ifnk67-pJ>G;|=cmoC{Q~rlQRmz^kwkN>0T;?Qe zV0bvq1dmJEr7L77;rCIC;$5SOEAm# z0vP`8#3M)zdV17sz_b1D*eqQA8ZYp?|8X9owRz}@vh`%@Y(T!8>0^Ip;Wm&6|?w4y6 z%<&TMZ@@)xZSd4kc{cnDn{~fg05yS<`D~{nBpw@NPr#G-%8Nb%&k;!aEW9dZlOX0x zT1O*p(9hKP#n|8AO);sUdO{`HRYN(RyR~E2E;zd$Z^*}>Yw-CfzjFp=kGG(j4E2&Z zT^AJLiXthscg1^AFFY1yQUfwZ7IQL`4pDELpL3o0_MmCIUK7B)jsq}3Re@?Elqt3p zKs-K2oiq?*$dG8uEGkLB_S3zyg$eZVQ*W55$9mHaco`3Rk5-ic=B5C(mV?$tZ!|LT zG#~RU@;hB1jVd2_%fb7mzGm=^RqKU=St}2ck}Ub7)JvWp5;M`;OoH@77Y5JE6%z#l zu7c$7rVDUL=$E|!?*u5|l_r?PWsS!w@FtYQa`1E*WDh0Qon<%&v<<)CO86dGgvbGN zwk&bW9Prjj;hheuK7fvKcVTrfQ8pauTWm2j(|r1Egw6tZyB*ixA)|2`C;04z%R4f3 z3lP8OQ1*PwR@a&&~KV09jhS4pn00g1X^d%n@}+x|K~9TO+Yl%y;zkC zS-<{1d1WN-tj&unj^vxqGb z^?mcCm~fil8YAyFIRiWL+bw8|Cs;7dk}05`zGSj?k)g1LM_|#ANm3=Y|*W&*XAU8IP&O4XwO~arQBZm9g&C2Sb*ERMg1l z0l07!T>lhU$G?dt*11(i`<(1eEzRMKC|~*V!j@zU`uA~57i_Fhu;TAQSy57v04C>s0&tcs`K%L+{H4 z=kxobw@O_D8cJn}tdu!vO<+wxQSA;KX~`rm!{06^!Db(%J1KH|>_akHX#RctAv@{M zO6C_Z?RQ|xBs!j)k$!BDjK2PBk)qo~rk4G=H=4Z(j9;78=_tjxTz!5nP>ogmjh=qZ;8-N#p5G zlWsRuo2N9$*XjEbx*X-yr`bl%S#Y4nSDx9EK-?bcwu4OPcvckn2%hS0cfCKzR};@Y zG-kf0&i4!DL4o_T-s@4?^sKbR)cb_))Ge;|5q2F!;d?N0;HnuksCkZmGZa*CA1b;= z;@x?Q`ukfxWOc_&d-S8oBJyza9k06a6g$!|Y*!wdpgi8Jd@8jju098g`YLZ#wxdm& zeNGkO9|_{FPFUzOiM3y=DD<5kU=ot<#4=t?I9VeZts7U6K4;Ro2-(uBW}=UH4mmCw z@W%e#Qy$?)eAG+h>D4sz)Y@CXdx_71BBL`;Uh#T3{M{?Ye)`4f0M+i@Q)O89O!HcX zFSFB$+tTM1Q(eTKDem3Zv0HlWqo6U)fulZzi|qa|G<|+q9F}I-k?}|X;l{zPEbe}G0*^_u+Kf?-(J zg7<91YlDL4c{X6ZgD%nK@AX@S?}QbKBH@uy!}UU5t~8@E^GSv@b(p*VtKo*+X&b&tPy|f zP=sEZ{&cJ7{Ojh46gX416C(Tg%j{I9GMI^JuRdup%d! zPo48Px6px8^_SXl@^ImCVur5-r5T=c-TNhs@#t-=(E9B`W}rloh7I)lv5O~eW1=Int@ooOuR1f6Nx~m^uEkQfgK^c^ zNX_;;T&KCYu53(RVSH>)Lmu;l-LXrWxi+NK#YY>fXA*Q8?Q7gEAeY!NC4Tuo$*Xj0 z-`je%;88Yk^1A1niFaN)fF)`{_ zQ#K|+wt{1`!(E{f>8f7$pmpdiaT?(SqkOz{L+MG|Yc$Y(xcg+FQoyC2hBU=v>maWQ zDKR}F7K%w;a43sij9f3I&t70gL24&rStjR)T>q!xfl}``Cxl67K0m|Zy5Ynw8c+~m zbo@R*0Eu~__&ke;q$2C}Ns+NZ>+0)*yF$*=Xa)ezoJ9V#|1ICY8iwdP82lyOi`8l$ z&p*zV%r<+g!Is$kh`1GmsN-Z-e)JYj{UZ4#L{c-ohSlyJyW_SeL|Egm(({k_NsE$a!SMzp9Jl-HcwS;2zM!Op z@aGGWmgli}xt}m#?Gxus->2n+YiWSKp3au|Ja8U)BHYG!)9ypFTpC?RvIOFztb9dE zA8tx$OP}l%9gl0yS*I7L!xGtg)wjmi5^gOn+b^k>4Y^H|G+V)1v-k`%PvzxYD1jJ5 zRmfo5k?sU>kEX<(Ka-Ot4~JJ0FUm9Ao7KlCF0GIwNyPQ0YZ!{njX@%Dh$370!m z7H>@&#oqDJ6tT09C7P{!Ffj-`1;P2_Gi|j#Yu^Ev=W$Fw0EY=49vto5`U7*B5AWp+ zMl?|&5%1^wNZh?RZI>sOpYYNLSWjhAYn+K@7v#75))8k@E)^)y!XF>Xj6(?1fZch7 za$DqbK9j3S1lA>q&#kPHrWZZ}-=2S*$zL7q%Lysve^MJBaCJvB|>s zP3G@0s2cAl)&ZG#6NO^lHb%XGvJj=W861i$s!dR22ovHTJBDZ|l5ad-|J0RaI-1sy z%%te1{7xx@x>3e#Y$LOelqsIXla5)$hx91wiQFydd1C7O{8&Js=)+>CUuLJ`cDvPu zDf#H=KWtb2e4`=0$RG@I`;T|eJ*L6+`E`9?FBu^Pk$WbB(QDmcM(sW4?Y?cZ*1=Wc9++abw8{uK z!z*9@Ymb&pkRB_XGe3v-fORJuKmB;>4x79G;KKQ0xVD^y&--{|(*!E{HwF$ERYO7L`~W}(QVk-^SPl%ya1%WQvVOa`a|5F!({6KJpoh<_L~+u#2`8}3z{7mBJROMOY! zKZvaH&p_}Nf4DXL`QL~B_-`Y||9t^htrRY{lHOH?@tGDI0un)9=)}c z`zraLu&lo9$$&vW)o97x6eXa2hqm8jAn>;|7N7S&%crC^JdH z{~SUb|4G#_Z3|hpg=Lz8&R*f6P6IJk0}fWXKf(m3CRjvGC7%R>C-2u>T6NU$$-?qsa4x>dh ziifTJOwVc}dKH}1V8%HM@9nl=9b}va(yvTFAO@ zlpM$KF_A+7K1R_o-$_Q)pYE&4;b~8u)81-VaCPGxUCf6MVT_Lb(Iw7XXqSq5xSM2E zX6@;WD%fJr_uoZ?u*Zy!D3Q?V)Xl=7Xc~-^8`Q(|!#d!Au#^+c|9KqeFTUEl-xWz; zd5ba>a-utn7p2X;0%PZykSEDh50h-!a>#0VYk03O^HbdpJ8(!b}W<8IeK zYp)_?MD}pW5`FC-Z5*s!03hT%lhLonClLbtWq*23d%>eb`MgKZU^}OQwHm$n_4?Xr zJZ>vXMr=?9K(h&+^ASqp)OwX_+`bROOejf~F)W(IIQ*Ia>fyY`FElss=pN8&Nw4U* zggH&xj4cLC`qMZ^>yY(T!D_Mp#-9MYQ`+bsA9C~R#~2<}{n%|rvULqu<8SPx5ti;p ze9+`cC3+nYJ^$M88#JdPY#2G73rT(0t6pc!&4Ws6)^pe}eihSI;1JH{;}akceeC5v z&2OHcX~|3F<-e0jmSX4lB&WQo!-#MACnao|pBLfs5- zdAT2s>Evzj$S01IU2#{g2mz-QK)`kraCu=pk zb}^C9+i9!)=oPk{2B(f!Z2+5X%dBn|s9E>D>{>gwJeK2uwUylecL!pk@x`-EAuX{=MXvo8M3cy_gm>@lI}HNg@dg{S^g!{;B?6?I|PM zw)*E75|Sl8oYC)*%$qpgTn=x_74JEVjvGtnPT9Y`_A|(t!dF*UrNl>p3#xwZ$W&xc zlNB2uLiLvnaQUIfcb=Y~nbut_>(OzH$%`aRk1i*lmt6@(Oj{xs3@yMB4_Ehc$O6;f z-6*#gDB~05_Pu&+r}9s0mOc(Yt8oTM?bO#5>azUw`0y;SO-zv=k*QRL5?nkW%b;Jf zIg^e#*^-3i+Z46zhW0v`{TL*{IO-Yc!?kf5a!Kz<3@|6*~(EEx&L1j_m!Z3dBYEz{#;(zK_IET%9u2 zGIwsI8cHAN(dW1`{Q0}zI9kT)eFlvg994kjiKe)Fg~8iGZskpS{8^%8^w@aS(MRbm zC4a0|9zY*xxqsar+O-VK%`~hGXCSmYDa)M~X=Ly%^WDlnz98~#G67BzA4wm- z9U6J$NmX?vA1@zT8fLH!{0t%neAU~;TdI(?pFG?fVW{aIYs)k6UgmkH58=rKxuZ`m zekPpBq)j;A|1>AmMoYIN=?~1!0))wMyPI>?#ut1}d(2LU>JU&#WFRUg|D<|jablx9 z52B@ya93?c@5L$~mf*NN#}^W0XEtKR{#)JCmt>=BGV-SfET_MR3tr{{b(m}4pfzKS zbe%StoEBy|*#P}qUeJZ{_hlHOBllX#(Ged!)Tn=f82G(-_u!NgzEmA>jH+HR!08|( z+20?({V%UDrDL@1hL=NMIgF!;CYy4xAYYM#=URpVs9`)wlJJ9uOiaJ(p9eX`u3mko zZ~Cy;%e%P1j|lyL>3%tXAKv*LarWUm{-L{m@BF0G(*~zAVQ7LwW<$?~N9JMr=aGqa z2+acNF4yp)>&*kMrIh0%5EdE?|H+i)a=>VuT**Q*B|lTcWljQG@M}ewmnl?Sq!Z(H ze80mVA~|D69dYJEQVHmTQqB|Yk=lXwFAcszA6;cYIE43UhF4484={gF$v$^vdBSbJJH#fLZCQxO|fG z>2Hkyo-_J9`s-d|dO@T6e5rwrhT3HBHVa--_y7q%O@O@X{CRb2P{J}8bi^1g7q6>u zg4g}e*$lAg%bSKLdBi4R+FT*U|Ee)Presy?Kel6qxpM8`Ve{L-h@g-~N8U9#z#9s*Ectz9kaHDg*c{|rt(FK+i52n0r3hRRK|evZd$`Ln4`d&KdgWh<<`Yr)QHt z_GsX~;UamU`>p(B)e9y7YvZpod!XHuGMTVxo;b{ozg&NPwcKi3v>_*)&P#YS|2=~8 zjbkHvx#)y|)qA)Ok%8`&W01`Q`BC`Q{I6yq=^T9jJ<&Ag`v=SnF51Tkz-Vq#9 zJvYrH+gFQFnJCcKt|FZ7f2vRqF+;I#Tyk$|Fm6rM8)iMWHc5eU4ipJ4IRj)>{o(Ln zO)wbhtJFZo6~2OOP-NezIFTqZex&&Ie|2a)Vu4Rk3L?*jB;!0jsD|d&& zBl}x7)}vP^GO9oeZ9k|w0KG3#MB@FXG=#hlN)kn_uSfrHy2lClssb5YXre&0OY}i* zM|T6XRKVH9O`>l&JngL8$9OAH0jdK;I^R61x#EpGE^3HheM?_%j{%&H%5lM9`4XuU zXiE3*5su0#u?b{ zv0&&}h_MB}N-A_61@@AwCx-&b!uoyCN>>-nPBA`WBmU==VZ)FKJmv{S*k3RGY2JID zH%z~M&yBl1e?uYsmdV+B%jH{0T16{sf>$WxEdXESSmNTs@9-c-V^Is`>4+2BrY(=a zLGQvRklqoB(0l6x{&OrwQ(A|ep4-%DykEr^TJEQHxzB|u-+iGXod%-8csm1|z4yC@ zSrQdy%N3coj>(LKv3)(wD;UY{Ml*Qe82&XTlRV-I9xCug@mSh}mPS@kZ?9ffwn3EE z@bn}GudRSD096_?9S8CHCQT2t<4uff$pQ1Z-CgWhqy?jEXh0KkIays=g#8eQ3T7Kw z+Q}RI6d-?jIwE!PnIM|5(2l`b5+V`ySZ?esJXSHJwNO0!8pgSE1=8%2hk8>8%+uau z+o?WOt4D7mZjn)x%qx=ov_1bYvs9o=VtuLFzI4$PpvfIpl;!0*==F85UDd7)Q0^)^w*#FYo-up&k%AwjgOW*ZPh( zfz$;(*WIItEm_A2%$siVCDnvshs#SLFY_stI2)cJU|ArfetrwF!YnGm7aDMe92O$$ z^p*dPg80)FXe@|~O_h9a69%`0D`65WYzq_(!h`wRF&fI~ONi8_y({7N+pvL#WGyBX zD5SbdA@yv(a=nAt}z9f6@9+$?SXx>E&)y{LOWa zX$!jtEL7sDY|ursty6&Y9yvk^pQL| zGp&H+TT|zmiJyhceaC{sr6Z%A4GQF`LfkzPSg+gC&|=$A4Sn#w?f}Y=@-8n;MqU9i zn^;nE;bZZrsHQ^Eg)CQ2yDr(;O1aWCWn4xiJeEzn+N z8x@hm&ifLYgt&*4;lC2Gya%)2xb~jR!2e_Yu=jCAgbIGX{`6ZTY)_^BqMOlgJ}7{0 zmkQIt;&ZpTq3f-8cAQS>#5I+5)WAq6aymiY1&#)~$Q5M8B`Qmj#y1+%)&6Z5unL4y zP`%Dua7gjOBW4psT9S0N-Vs04)C9h)o-<6t+X7ZYSphHVcENW%T{o-CKHY_sxMX_Q zZ;vaSTaLhz_;c^8hr1@+8phT^358<<(j63E zyl8ZIJU91oolzWUH}`{D7rCNm2u9Nx>4ZJlhTDg}3?I2Ah8~N>ScZc_z#dJm@@JaBz=in@j2OFCaP-|% z;F|;foxGYjI|VOCEKB@g8gA{CMVN{EdPDT0Uc)KkCW;|DA1O1RM^eJ5SMs^LD|u&+ zq~Y1Uu7*PqqkK0nYG@y8|3*h#Szr+N>FZ}f&vbYMl?Ei(`Ro>ohVT|8&1wHl=y+otE3X@tq#0bnERrB2ntY+Znj{ z9-QN`ypu=JK7Y?C7-!n1z~x7sX2>x>m46!PJtAy`Vb$0pj>tDjZ1*r2Gd3`KfJ=~A z;l2CY{jnzTjquS7Fa`!^=ka`Its++F08zF7+38?H`f$Vr6iYId7^Y>axt3|}+ncvf z&TQK39Aq-#72aq(>h#0KL9<WoC8ZRv<(%3g(&biufBPWQG05kTT#iJ{A1v;4vsvF{> zQ})yCZ|+Fu|0I3S2aW7~#Ifp1ll>f-U?jB{uajz>v^M=6PUrb#Rh{QN8Zzx-|JWpd zs-o>3?L~$7WXMrZulkUEV03XbTjAXy)s9zc%qE`S8`dd;ofvG^GD~;VlY<`KJ>6CsSG_af5k98DtGkmN~;B7E`xx(>v}K2`=4%e>2O&0o6DJ;OC>vq(`ESo0$64qbH*WFQGRnzf>bI8|3*A_@HhfgQi! z4m{1gtg*ua3vkt|hxnCnBKBN_$L(X<2OHb1IUidR!b7hwa(TueJo#5By+ri?qUjw& zfKBMWXRt07X!s$c!}t`8c|mLir9Y55#zBf#`%$@n+kjq^Q@BcUNxCV_CZrFO{dT`A z*lb_y#=B_jNrUuWlsK|sUMDZiX-**3LrxaSB|X?OdxRjb8u6YsHYp=r7k2>NX6Jp# zC#Tdmd^MJj7`p<~$2I$6Yh`Kop!&69M|q;iQvvaKD4n% ztGTeywLC`she|m0E?#@5J)L1l*Gz%$$bB(?kTA**_XPP)n7C`i-^+lRO`h=>?#$(! zw(F2%j(CedXd@kYxKnp+fy3bN_RaQ(``ll%3kK@+S=wU=HEW?|F)!-c6jc~x(CV?H zy<3~#L^`(m0!xjdQ0%Sa3s8qX<+Z3rt@0-Lhw*&2@-Imii{wuEUA-q60mN6)h0_7^ zTlcX%rDFfC_rqKgeCwT;nd8ZX;I*rH)h_UTIa-qsxZ2)9Pb4l1(m2c;7_d zGEH)^m&!g{_Hz9Kx``ZbNP`j+=7NCCH=RR0;=w!#11xO$mG4X5qqR`v5=62N%+$BZv5#NWN5@w$k5@=`Zji!g-urtyO!{;15RPVI6FYvRTarY5(!NeEK&0 z;6y`i?$dxy#L{w=8jJ+!O`L`C4hQMoBPjxbsv{<_jEnv=}WckdEyyM{+> z!kE31vmJFSuQhoGEdGXv2if6Q?nI)U?@fQ--L6ACz|xiF_do!50iQyg$5__mDoKI> z@)6VZrT4uMT5}7^Er0Jn7gw~?80hs62Bfwkonk?L*+=Vg>vgQ^@HCnd(Y%u9zOM5F zsT7Lw+iTFC$?xtBQ(9Dv+JJN((y{u~yjN`P`-jJ;QzzQo2pj+UoWAaDndf=uBzrES zoaHp`g7v?QX`0qO=Xb^Rf#&k=rgCKOu|+a<{&N@;dK(yhYbt!Z@U5ffLa6+RUstAh z6i`QJx%EL7o|G>9H+YRezm)p%&RZUt)Hu+@(e5p#&e<*lq?!K3qih5*vO~9uhIbhu z7X@R>HR#EZ$D&B=pj~r&N9FazKK)Nj>fa%A6^#g?{wZbNl;d^AdO6rTr2~sYi4F4PCxax%* z=tO7(6@;W-6ofbQKrHpxMei7RbQ{ON;%^ia)xwKzD-^#o6w_^S+}+{x082~$FtCCu zQjXTs;|KjgnxnN1llu|oK;o@^i=?}ng`Ze(k(pMLdw(QPw3@&WMvGg)c&sgEkF$m^3yUlnJO&CQ;~Cu_(RSi=nBd{ zDqj97A4zF8GMHMh?2(UlNq)J}watA&)IqL;26!cy5uT0L4MO|6O4{ z{$UKbmzv9;dZe9a@27KkT{mY;(CW9QcA3brDaSKz6K zy!d{R6%{N&Yq~&V(O_Kl(K+%WojDy{s`d);JNlX6fzmgz`XQ!3bh&)9)}mjfz(qwa zg0yd=;`(>3{+}Z5_vdN>=TYfD>nYuxUe9JAw!+6N9iuaw;;cq zm*oF=RQt1sZpF^o_&BEOgbo2Owh4JfB)V}7yAzC(t37jLnUG*fY*l2i=OuC`LI|P- zuEd)a61D6)kK;Is$-^Np1W73U^E8mgD2XsaW!6yeJQ=f1d{+)u3%NPokw|cbycsy}&Bd9yrk^%>$rFD-x8O%=*r4IZr+wMZrhf_dN`0YNK&Os_oG#=*fRj{yd5k8) zBMtmSL`nt3ZF9VGA+`l7&#>#8VBfaxmgnUC*943=i$ z`jvh6Jh&uzj;u@}+`#yb(RZ4n>n56YCvgw{K;Faq#!t7J8|#S!G={ee_mbS|QWFx4P&q4p?XZM*akwIP1$e7u=(o`I_;-;>|Z z+_(bMWaKbP$Y1T3dtIbx=-yMHc%##kQRLB)9~xoKkc8{#y(ATU;Scgy&nWHB9~Bto z@pa6vyx7r0zd#s(r`(pnj1w(muDfU5dRj4>pT`AsJTe&0@fmo+<3?{b0?LVEkxbV( zulvE-SO3*a=_Mik36ceMfU+NK5_hZ?b?ef1{W<)|eZmvhPtfo`N7DS5g+~b z?MZ_5#=6imS9uuBF7M}d%2dsUTgz!K0h}Skv-kN6oc8{(&BEk}e9iO7A9$Kbf-!h$ zZf>{z&U>2+Y6hZSA|3ia@+CQ|6J{rkPAM(m+C_JZQril&jP3P_xFa46t^wR}QL=yS zm7csFo($IrWC9q{{n4q<*so?#YqH0)+O1Blp^FJ2Jh{_*1^lGvXKx;_v5|k0J#Hqv z$0NGtM^(v6)U#<~T#ci=VwRFV$otk)I0+tXZ}G?gl>9v6`~!U=sYitw6+Z>%EY{BE zc`pB|?eDlpuo;>-1KW_(_~i4u^|!Z---%*)nRR6a$;wa$TZ@cfrO+QROW~gZx2O9z zCv%}ZBcs*9(57u~2%KIZ_6U{qjOH=DOBHgWm{Rx;xfF>RcZ1f zimi6{?sy+6G?6n;GEVTI17w2e0{ua1O71Is&bhm__8;e4B+rXvp=`(?s)EbO>b{KS z7P5&zlh{LnU~4;2G}%&eSZ<$I<5l0kzA#W7Y$s&43x)QF@p>x__)Q9oirNJM&lo*G zxp2Lfk!OI8uQrD5&F30wplltpppV3z(HPdqz<2QGWgk#5;Fup->E^g;!yx$UH zh=-~!z_hqmh$8y$w10apq)o)~%x*VAYbM-ge4FWv^t*P%SLDkPBTKklo?Y$JCtOz1 zHt@e!BXKbxUJvg*0wu@z1+;mKCRsp zh$jDdVR#oF%Vi0vR+~^i-=T&RPDefXK}T>+bnkgsrRIT_R5yZD@Mf+75^gt)jJP2_ zottgp(Gg`3kb6~7VDGX;)4|YX?57L;?t4d%jewJIROex%SYGoj*W$%td`#I<2$bsi zVr9UXlS`8EnJZpa7#-w-Vlg2Gu;hpt^qT{|CS-m`trHr69j@8l(nE>*8^xRuL*jrp$V8+@5-D$JE6@#o*Z!b(6y#;nn&g_ z>gMx7JnelbjadA%&n7g9pdqNyeZD`;9D2B*y9J2@9Ry*m5M>!-T=rz1Q$TtUqkqTe zhX9A^>!ak0qq`!J*(Dn$`U5!4dIFl|=mU4(@&*%Bd&n*bI_qSskHbw(*f-fy&2Rz1 zb6;$~-afW%s-0h7MA+WHMtSBvVCKLoe8UHx^ILZ2660%(JF&B93;l23jYX z+!M}zQ3%uW&u0bG)wJKeS>Z{N7ypq(-RXDVyyO&>%`@zgk$8fv2(c;e3bk&n167nC ze)Q#%bN<+6=MD*F7r0YXQW$&?Wa48Auwcn?^nMg{kX`Va2FJ^Kkxi6lZ|w&H4(iX>Qq+okXoFB$-Wo~4xm=)8f~Jo0mum*N_q-Z@A(#(LR51G*$;1A+ z_=U4fOGkD9?E@A%;QIU|%=zY$n;Uj67_qz|MjH;HC&Z3(^t(hfGo>kZzZRj?w6{Timy&%f-ZvKW@<;p=ww{ zcA^*ZCU23otJ?|1GKGzIv8(L<3#916RXJY*jBrkFK2>AOH0p+b31>>)wf1 zdCxy6JcO^Icfq@TRU?2WfvjlE^&Vny{70Crej&L7uq)yUARiMu;v49D2Z?T!=FrE; z^hJ_3x>NSMV5vSjMD34%d{kJ>F@wjQ#oRSLJw7q>lCPPa61L3!4(LmbwBM%-9d{3K zAAR2+c84ab#cu3A%#hkqe)7#@ab6$C2(#~?IzV~gzonh^l3%DVO>UAhy{ZtQlhnmy zaPbbmqj!x-#o3S)DD-N_@RyCC^JPz29{ad?QFkx356mN5U<174boo81haIj{1jmzp z--KO_Eu`UeUVaG6yM{P4QTGbp0W?N|wJQdw2(AhJNb+rM81zRARm9)^f&VzKA98%i zmF3a+<$wPrM~hBEfing8BSKk?{JZ}ZF&GjO?G|6BdfVp-atT!X<{zQep>oxD?Xc9F z_L;nMl+YNuv0VZFGeqiOlEb*~kH{XxZ`x5?#A7!I0U8V2CtB|Z5$6z)chF5eTFy~d ze%YfeJ%lZT=1H7CM+Rfai0!{r&~_a%0?1Pbu~Gcc@1-^vrTVHZaZQf91!BNQB3#vu zd*ZYQW&<}GAKG|s5ZjdthYN%(4;%;5&Jl=nI(YEK8wz z`tetC&JmArqf-OEmpo`0`e>n|9nJGe(karRmn2J*IxwG4btp^o!}Bhuzg&*p;p^0` zHFS^ss#TR{sAH?;%YBb$vQtdZQ|hsA7lN`r1t2La$Erpq*?O(%;Z{Sq_LJohpLi{G6^AE;^8wEequ6=bCN&46y#OdK3hl)=xIEhWB$)R(*&@Z)#bd(n;gaWwS) zr|$`l`1v={<8Va?(v@W{YVIE`*o}^d{SVG;|F@Nn#gCa0%J+e0V7HhtgHiUZs7&|LVX9vs~fWI*>m&5>NT=OfCc9)%7IM)|4wX9kXjOK`( zx(8tJ$FIIWiKMM969t9_ZwP}tQo{@k!;jBF9Hre(J-1Sh?DkB}@D8*-;s-#s!;{#G zmyG1Ix+U!m!BWv*Cu}i&M;0$8M)HH%)40mEQ!Qm$zW=-|IKxenQ3Ou#j2tgeELu_I zJCCJ5q^VM$$qR`u2Q$vL3{7d3v3j@NwjG9$ch+Osu}EP_uFgW1uo!R3OML2QFmek8 zITR!{>~ESNMGvlo8eT%wo;KWd{T`okoZhfaUnKZ&AEZwyT&rR}t!jhb$EZM6S;c67 z^w}1_4#-l>nxAJ{=w$2qAO*B~^qjv-<1EpV$0>YpHWV+L;#5H)BMIVDQhfP^6OWbYLF(gK7*qnqsV&v8 zkfN)rPcmLJ9F^9VV~_j5v_E!0WeyJv~R+KHrw3f&WwC9?c? zE*i6M52IsWQEU5Yg%^G9T8-87X z&$0^o|L_WrBQhqCdC|wM-M+`S78Me0pSd;@K^i}X#7~8!d3YRl-xYq34L8rex^1fEF+TJC4mhqX|U!ntmxN&=O7?T=xTUU+j2!y&RebkjM(oX<;k zfIn!?V1~kHM@Li>Zp8K4!Wj~F<-_hFsr8|)(cv6K9+{@}K(0nGw!SU>i;$%y9SH4( zsH{W|iLp5C{lQuAN%#oBW^^bWH^SzS(@iC5rh7kn=f(nKYeJ*JR(Bc7k0#wT|0nP? z9<&U5!1p32$X1?IvO^{-6}C@kWh+6_UPeLGJ3h=fO2BoVh(r8uu&K#Ymv$0MWW$r4 z5+9-_)^7J(O0Nq(I>cW%1L-dK*@zITN|agJ=F?xSdQubfM{9kM5#W={RW zyhZ{YbSKC=BnzVGQgR0ggO^r$_AI9IiJR>Ku2Znl!VufY5U!w82N4Z6#xOA}Uc;GP z@b`Oa*Bp@7aDpUom?9qug?D>*CzEqb0}u9YtKkAfP$C`-+}Ze5Yz^jcw63isNm+L| z98^K(|I7kTc zbwpdpC5Q}6l^Ed*;j9zXdU%mA zH-4ZKBQrOEFuUWsYyq~5gLluU>$&_n^_zh(3|^X*BXiakIC;f*?sN=||4x?<;_4sn zkVC5m!p0RDznT>Wo7=oWfkvnA@<~*WTukIpi-~1a|E2I*srAPzpiPi}*jFCzH8QJ) zE8uiHcM9qX>d+UZ_4!4TR`r-n>~KE&4_bTn=x9ptpOWY$Vt z4y1m%bJeGYNQthMheA2K8H}nidKJZr5Cisu*R`inRszRyK5=WqBMXMqxKcaFjdqg< z@g%WsyrOymiytdzTqzyTb*I;&Im=In=mt9K$)u?5J8zc|N&@p7rXFpV=8e?<5uUMp z2&dfv_`IEvUf+Tm_f&q;P(Cny6$1Qr9GMr+7=@J|q}E46ha7K7?bg&6&IhCc{#Wm{ zh?mg8qmZI%To{8kVQXnwf5;ks1_B~x`Mg9wqTq8J-x`g{sEhZ$A*-+e8gyrVzqgXS zX!e2$4MX#P4{S?v;Tc%_E0B=$4+``{^SutGhFPf{U{5HOeLL?)d>J85$Pq@GuQOP1 zdNt^TJLYE|6ls9$Bgwpn^i(7L036n(AEK0PQk=l3@H)*gD5v1kvh2{6BvB53Ko7^b zv)oIvyTw)&ME0K!13Lxzz5J3fW>Xn(G{`-S54OUQJur2&+GpW{5b$t@@d5ECXuWx+ zqmqZGVk%tfPu{<}odtdPcBUm{3@Qiq-QW<|CcPInNBD_rNE+%R|AQ5t z0=U~=VQd?!;H2>o2ta*w0Mi#TaLy(>7d}QL&f!pqnZenJkGq?`@Bp98y5>7gduv9T z^B%#Q*O6L{x@%kH4;)8J7&{8T&9D);$zgfs2bmd35Fo=Oh&{9v-12_?=^+(>^z#lWssU5G+ z&npTSXF8miZ=;3HnzzLpK4`9J`a3kp+T0e_tR1AJdcap@NyM4zo=%)FLVfVXtQ9}< zYoDE&Iat1RJVG0C$Iv$(GiRW9btD%V%?$9|c51v2vK_-=#;qKnWCuHJz7dx=_@`eL zW?-^J+{s}VA7wH70X(GBt*Up(W(*sI1nq>oJUGa`EG}f~6(FPQ;&qu_g&Tg3uH2z; zd9?K-95~;;f(m^MQAo%#l{0U6)!LNyED#wE;6V!ZOkKZxQ>Vd)%y?gGC(`V4ZD*{U_q@?oR=4&HZSEq$2Z_Y*N7Z!sivB^Lb0osgkBnYH}`FkS4Y zn>1iA9Lv86)Zy0)MjxON9koTUf3j+qs zkTYnWe*+rZ4L`oVH)lw=*4= z4X6-xnhVi2B1(Shf=6?Dv2FN+9&4GT+9KyehJ{-UB7@n~?{62q3*|CTW>eF;Ejl;D zX8h&=OdsI=OgkB)_0TV%f`J^mQ=iZ4owQRPT(h=)&iFt41fKs(I>ZCQhiW5HK=AOI zFBL4Eav@x)+aah%NRU9atNKTH546WIQ6I+>Qu{7*nT{vv;7OqCu>AAPE1_XM8W1_! zgbZfzJy+Ii&p7L}G5`&;UP4)}U9Z?Bk%@j{QT&k~OpXb7Fs^r?O z*$3fkjLYGKD2;WSubhe=5mJ@Nxs*B4%+0**5`6uR|LZHy6%;PB6~`SGm}iiADg8PhkG|6+&dmMOu?Y_U_ro%>G=-3XsOS-0`$&ouXlgf z6v2dl%ceMgS@S2c8ZHEBl4Ous28sNf58Tt;!ABBEjAzl88o90P+b(4iqJZxa48Asj zy@w0!OQ$RO+b1s|VLAX!-Nf#)WB)0s8zgwSZ$q3)T1ie99CQa@4e(hr0{#++Zb;oI zvnI~=vudWke!u~p-kiX>y?)$P=J9X#io8AKR`)QFLg8#{CAei80!Yl{B0K(a{tWmg z8^oUIM=HqjX3#h!?+aR-998Xo?#*eq%*cL8@Nt`YtHsSvqrV4Fa+K=h41Xb$O(z2RuKBU3KI?3GT6eZ`NP8%dSSKb;Z& zmwk|*)! zd8bfsJRkJFH|Aq=c?Zrh7Cz>iqx)~|++p{sA|5@*{zddu5src3IQZ}IjcoLzzg!~a zaLqIf{thV~AUw~Z;#z|j#iHG?bM^{UoEHV#khv4QXahV{3RWe&n+}RN{0Gkx*3nqF z5oWsXum389=U|fx!G*k^X0ERPK`$?Pfw9wqQqC4LGVPFMiFIUm(6eX@2lF9( zKYCTpKglEul=d3Fmu|jF25gM1%ZFW{1w)jA(TcylmJ2YKn1(!svMDp>nJT3D<0=?9 z4_l^&xBth}d2K7IbzAtAR3vywPLhMdod^OVSp|Ih)90%FpVr*Fs+KMT!VF{d{&l=f zrL{1Q3iW65i02MD44QOIKvTd+ydjBNB?ZQ=pu9nj?q>b=K^h?g3rP{_M`+OCco2~o ztwK?iVBn6~i&y`UzJXHca?maYi^eJGIMH{Myw4LUQ9$u>`%CFTzl&(;1xH0)2qXsl z6$L%A2*C}#+F0TzirtfC>u(@~)e-h<>Q+g>DF_aTC;F64&sD$|^^qny2s<%5HRBhd=19vR2kyK6b06OE4}~a$XsU)AtzV5-?%i}_HXf}|9!>7U zv4^jC4XWCYfcs9qm>CUM;YI^&bDKMNhhrss-McE!a`TKCsB7@LZ^s*iRo;1*Uwem? z_w*4$`8Gn!hBb|nfta+Z-~I8Aqm3UVf~j`P1<@{Wq?`19wgbtyp<7?k!y81dTR2AT zsoC&1=MkH{FDxcmtet{Sd)s-eH=IeVHcZ2Q`<{$#yEy0Y)NIYRS)4XlypV16fzQNna@v&OLS zo3Q(Qw^EkR4Pt?-eE&fr=2f9>-#9eqjsvWi!=tpS^9@lE9Lym|{pi2EzTCbQHeh+o zQ)5w8A<|GtEClQRHbg+DMXJAzXLo;slO)oA1QqOA$rJ%@EMl&_`TNyHg0?rw*)T=J zL8OpjlpT&Aq$CveI|Bk3M`Go8QsDSPt3SQQ6CYA{mm%}Mm;NzLRKl#!exbgn5O4GT zh^l&^%kJ4kJI9ko^aYxgOVzvPKEBDXB^4RSZq(2D-|iMR^`BLU8_0WjvE@8GDTdl> zQx-gZPh>odl2-tH>khhyP1XgRIx47uFw4}lzi?NK(;rX03#k~7AW03;rj+~Jt$Ci0 zJTE9K+#CpZoyxd>V^!-n^7ip}g{DLtH~%Gkn*pc^XRqGuJ<_cAsBd8B1cx`MUHFh1 zQf|4Y+EZ|Ep)z{I+~EV>lcG!pNM3RGx=JdK}ISVYV&od5=zjnX=c3Sa^b<~D`+NHV(y zsdYSQPb5C~A$)r(S}b30cfua;RGcyHVA11pCOQKkrNNn&G#5pONa8IaQn&0bikY*x zlK11ha3p1y?3a**vx?a-xslKKC7de3!M>iW;KaXnKnomo^}Tt%=xrAm2(C}lnxFKi z&AA7K-@pxD-lyF!Q&8QpsJS40ZWf~A2impYR&JqlwA+7KmJ%;BnJ>^F6|b?A;-UTh(-k1hOkVZ1Uh3w$dOq6;-tlSDdO!| zT&~w0>Fl3f`e2zui*mr!GOugK-%4S`b3v-0-=T&>L@9C-k<(M~>XFC$ZP5#+otov; zym&cJ{tg`pYFPuQf;m9ZFzN0;`}&hgTt!XDFzK9zYw!DZU$1Z4y1ai9Qb!V>L?*tB zRxhF}8pY~nK{bOSg>rsz_p=DOczypSn3wRWS6Y`&t8?j^pe&nLcDcKpyTMa zr7e!og!XQ3xuq>J)w`YPm;clEs(x_3T)4U5CY~`=#5DAH6jdWW4)`BnnxG<~Ud82`b}2XP zxOp$@nxad>seP4K{3+ufiQgZcW%{li{9e&1G3~LZ38XU=f$tSclgY zWpvYM$`p!&jix2E1IZDW_aLf*d6Em8eJO zA$rg}h98Ah&;T=`k4GLjGB7)*XReBX6oT)z%8xfNKKP212|^rjz(cJ55)|nC(TL&x zi#4B9j=iGlXYaS$-1Fs*PbEqiy^WL*T>AZC<* zClz6ansoOwx z8T@)knel;-(o<+@PQIdwdjJeEqY5p*tl$y2NZM3LM_Mm!^_P`v_5P-ao+bU_=)`VG zG>-`~NUC%ETo>j)MK2jb-P2o$8~cuU1DU>>MDq*P3j+^%*#uZl>EGv(aJ!K>g8qt# z^_KpOF*?M-3q8j5$URnuT)L;AL*x_oQ3@?Vk1}xWd8Vq`m1x{qA$YRax@P&?Z=d<$ zT;Z%#le09OaW#OrVLm!kUWQW=Bl}i9MNmIrv)(7>mLD$bJ*Dlt9$Pz*wZwd&s=I)W zpq{?SLQ02sM!Dr z5GxfpWD|0^RiNZR#&3b!0yFZ#UJz=_+K9~qQ-D3fDxM%HUC)eE)r0MOHmL{!B8j?aQhL`700E+^10LR=K$$r9ruuj50(d=cQ z>&a~Fn$U=T{9pjWb3k0&eEa_9?~v95O-=(H-{;)#ZZ7hl{g-qAVdxTA#(UiJ+k|a> zQ0zDBMtP$HbgKv5it6ci=!}oID!7j9u_#O*&&zCW@$<=E1Qq!$Nngjyht3E8MH066 zO#x*eDD06A!kmsHjCC)E?v-RPmfSj|9zzsG#33;^mm3~){$gZ)^&(mOkd;t)Xix(^ zT%x@dK~?Sx&%b6qsnfI4G@Y)5`t^^#Sz=x8V`pXt-)a{QvfLboSRZ18@c7K2wndli zHJkd=mg9hZk#GW_JrMeUuioC5@A^NkQzJIPj^Zovj#%%jPA)Ip{@8!ZhNNV~ET8fx z*>x2zwcpdN8^CTTiKX&Hj|Bm2!14rVsP{lvFuIY8Uv>)NBA%mm^3T)&v>V>;%Bny0 zRLtElMTRw0ut@E-yh?`hqUQ;rVgkk}K5ES=C`p-drCGsA+TZ;|%c)D7+t_gBt^mjytwf>k~mwDk6k> zFz`N=wbCTlmVHqpCDuBzq1UE~rakT06AW$FGN~_OWzmK?-!UV2HPKD|P*B0QEX;6R zL#xuNh6cVgbVP?qs8_FVnqAl4%J#}k%lVmFm>4#pAO1zk{=or3_%m{-NnD8^0zGerzoOfxi^A9Hjo+)DW z>p%@LSX`gS`KC=@lYdQitF~NS6Gf+TeeL(w?tO7r@Zo719Z8;a4ZdWYHU{1vkyCq+ z_F|3L@Uw#}Hbl1yd4}z;!1w~Y&87ZrvK*Zz82b=s2K4uAdsVO>RTSe@It%Xhh1A30 zkNmFeuxD6d+@pdbs;C)}s>q<&71 z?*k8~SbK+$*CG7~H62j1UiCU$NDT%ZCUWdH@~Gp#^`{X2`vPG*>Hn!jsNK*ON&&j*Q~iPm#=D{9g&{rvt$V+33~%@;g~|W+{`YOYX|$-E z&&mHD^Zq9WY&huC%g1|r*Qa=ynUFD1R9jRVA5=iAN^Q7q45?rl&Zw9cVYUQu;&Gpq zT8;@>q1a>yC$IfL@*sO?gAl|7Xy6k3OhfMtozWn0kNJIC#^iC&o!#e%3ih`6O@ed+x}16 zfo8$mbXd7Y`G$|JQ3d)fJlvKXM_!;Gz`whfG5WM#(8REV=cV;-;eWwtHldfJ4!)^A zy&W2W7?g7p&l-Dow|Le%IuSooU*d@`k!05avj6-bKjN*6#DYE}<5@w%N(o6j*ta(_ z17xZ}4sKV(w#@OQvsI7-@|Qubra$V}&N$LM1OVLO1K{utn$y?i!DQctEE|*U#yyer zAWT0_08ip!c${xXeRLhWKR4KRHvu~2eY7QlREM?gCC-w)a2J&fqVR80?*s9Fh689g z;EIrQ5i5U^|ItAhq6!fhHuikCw{~I z5BQ_Au=fR~G{_ zbwl99Gxrh3(FI+w-s#8JcT!UP`m=r?7;?cq!6A9+VRqv|8iX={3?AJ%zkmWv-#?JB z!-)qBGdhCg9^AgWyi1+p{iz2gZ+fKN+>B&J0(S^akEVE|6b&a?c$<85aV6x{38}mJ zzxH9HsZ1XlpctWheOnnh#7z8)D+YGJ`*XWh2!JaNk=T)?{BvL;tkz@?eDph5r_}CQ zR3kj&Zx%J>Df+=)#!}bzvvkhkcEE4!4}Np2=5l#skwCvTJte&EhkKc>90d7a?=_TG z`=B3)qmS_Tk{j-ZiGUL^gQUSVC!iG1Ii`xk{_R6#oa~S7p8un*;hj>HMIr%4Al}Gi zi>$>*_ROHl`)`ea{%&OKH-AP77>DW$sgK(vr2wl|M6^Jvsl(kmx9`h+Nwy1f@Ks2W zOw3g(Wc~Gb5g8SdNA>DHUMfWW&ApjlWVUoE3UdltkxgF;B2)s?{jsz!4@3fqhY;d+ ztzi@~BJ*Pd1@@fnuBfbePklpZ&hSokuQ}$s4bMa!jwpq8>0fd`ez;DeTcMvTc5gfQ4qp@)56zJ5hZnY8q)+xFS9K1s3vMOeWdx_{d!Eu>VvDNLdP; zd-$Qb`fFs?Cv)C}5n)n*uL|H=+yJ8=HQ?YPm0WGsue~)`fAm1Ccf(_Y(ET z&{p)|%!RWX=rcqv(Xo#JchQ1CL_7^%;9oss5*& zUD)?RlboLP*}o9~*9hP7#8L-zUK_7>JoSL9d;{-9og=_VHt7%g%pMNlPiK3WAiI17Y9hz;$B#gR!IW;@OXzkJ2`oHX+X78+5D$$|Zm} zezt@yj6ir^HyGmccW*OU5Pc6ux49_Sc&&+l@Sf?_p_6Dy_Lz)=;;InTQHZ;L3d|>9GsjH#v9NqF`T_;n!4|=#7 z(A~TvnbjQXIx5)nI<5FSAkZBz7}t4BF~xnt-@U*3$uC;xl3(^aba|J{{_|DTlZ6WB zarw)BU;X^?waQ;KZA*QrBzyd*h8$OxQ&rZdg_z6xe9h&NRTaR>0fJL3{-yOVzY5SV zDlbDaZ?oflWktH>(1#i?OiAFRl@|K)0S6HZq0dY_TZ~pfzAI&itW^U}u&_s|uj(on zZrC+|gp2X_{g*Jj@Th;6DHi4&n~|aEy3RfGf=d{3PqUI0epFiR6kYK)vPk*M46LQ#E_pw9&*!@}`P>bvq*xT2B!GS&^fG{nJ ziJSwgcx$e~ysx9Cz?Z6QS^TjfEv2X44d70a;Ey_crJ5bB(om$r;Grz{8lS$ajke>z zB_x5mhz4W&m`pJ=qy#Q6-AG?&ujiZRtK+}>daKIF4Z9*e?v2)2aUrYM7h$$Qi3TPJ z53-twZ>M_4856I@_;`RQgHJ7Y$d9i{Ld!6o$YB8O25c~%oK*wz4SblR1&zbUco(?W ze=@LQxaNFB41Hh8$0l7m;SeC0lVf|=Z}kj<6B*?uU@yw!J3XK-%AU95M?5xrar)i_ z9#-^S?+$xHUY%Jy^Go#rG4Ft?k>UL89DxE%zIpNod%gi8vbGk;64wvf*~a0CMeH`< zon#;cuXb}b1L&U+#-t0R2PtUK^Q3f1$^0ZKSw1B5<!aYLmP~;@HA-eV=S=NA4BS{f0K4DOsJDoXT?# zW$h%8q(AUdZrmPkj=oOSnKN||Y#<^rM+H>Tbdetg}Gw{NbD>NY`wowDriT=~s z7AQ*SQl7Q>{);)QhKB#wrT3HWZZERJCMTi;nc${la5l(wp-c+^J1;NXIdrrSiaRL! z!xL-N#VMU!!7}}eju;KZaz)kaR+uLkRYtzvW#H5w+R1<nMBLG(S%->EIJOy@iZ|D{AKL08s|1u#1RAo|eR%1mj zN09z@>Fye`5-K(L4U4-_)$il4p*XNE5^P`5KTg7zT^>vCTcurOFOQLT@-IPq1SQyR zhPKf%P~E$9=^_6M+a3N0P}u?Uj?0V?aT+sjve8Cx0>%oF3el6to}waY%?|bW_%Qob zNYfHZXgbEbPcDOxM842?yz#al1Pw)Y7^Lqk%os#}cKV}^9i18ha594pv5%boYR3l5TX@kgXiofg@kN~1A9I_< z@zUR4XFqDhd({eAKy^Dz%?r*3FFLeGDlh0W z{ezQX(jM19KAaAJwB{4)B-wo-MHEDyZuDNXKohu`rN}M`!E`OYZ5g=4&2|yY-b^;{WelB_I|hD?+qf#holdk zHhx?@rn~IUJ#u#AM9h}-$8Jav{i6kaKZoeGuCZ@AwHMkGf6qgz<~1ny{UgNWitO8F z80%8dW1nKGeQu)n81haxEa<_-O5^t)lK$F4d zAE6{`&+o`VAi%~+$d`dYO;m$`k-m_;018Nbi{I6)Jn?n5Lf8Pr-FN?&&BrZ1o}1(U zc-7?0^_laPTvN}3xG1o=ODBIsZGDtVlo(X#gEMZy*s4H#p00sj)=wzq7q!`KT9TQ0 zIj5^;H?vbKkM@0ja97|6FRv2OGmw5wX8t>DKQ&@H7@I_NptvAIOL^a&+myi$=rG$m z@4&+Z6li2NH7v5Yqvs`kKgs$Yx9>Dzv-Jv|w*CNoU-KWcu>QA=i{xQ z_U5`*18>`KdHZ5dZ${Hu{nhNK^W_anc(Xmv&&kgnf$U+5_cvky*IkVzx26mB1VjYCzZ93(d)ModD^hoIq2NYm zR9Ds^dz|IxkGe}Af zJ(}ZZ5F^L}aHT6_((#4uWQSfL`>gEe^#d>W5=j71oMle@PRtB3j$x_XpY!C-W=DR0M&i4HhFssikkmR9wXnvzgy?d=Q>#^Az8s*u&BBa zqw6Z0;4D(oX9@iP4%%ADzE?Moj zoRh4p@%;FJTq|&dJh2>U=i|TTl%SKVb|C`-ZXCvX1o>W`a&vxM@%MaVBjY#2c~g-| z4Y!T_sfMK3wNSv#OJFyY4rrx-b1EP8Xx126DRDOd8ddPzF^4ADd}y5iH23f+EIcZ3 z40P!?mrP<3hZi9qy#j-l?Dk-%_fbHcx81EUD@Zhm?E!0Mlg{!SD}o#}VhHgs`c9p% zI*FE6CPdY^Ibe=?4$gLLa}=&}Y&US1mtX}@9UFuh+6-#)M@MX1JWe2(4xc~Xn(~YuH+rHdgq~j6t)Wk4 zhTq|Aw3pAHk*OiZ@R1CRSCICHuRc7odhPwQzN!miKW(Y8;_JcSWO1zqNnQCzC&}=Q z?hzM;aL$ZX!GyTcnQ9NWqEp9SbeB{wS6r0y8RznyLTOG*J{RVc2n(%;jnk&9cgExN zt+)@la@u4@3M9aTah_90&Nnz3lYH#V2Zl27Ug6;;rz-NIoZsQL>RN8yj2dukJ7L@> zxCeI?@O!;m?%^(H!kqX-1jSn9kj%O%GEeabZsRmjCHhkiihChOLq_WCGD;If?yiK} zOHOkLOKMuvK5h_G`l*7A+GD^HDF(zA{H5RQ@E}x_g{tAgV^Md4#U7^QeeVg;Kv?{@ zOimKf9I)3G+#lT91q6@_Sr*`SB6Y}TO=_#SfhqlXh;XXl?PDvC~`I@D(|JW)$_ zpAEWZvsaj8%MoU(}5jnh{k>}ZEl&5ox+Rb z8Sx22?m{lYE5?<7^QGW~EOHNQNV6Mqc@bZ4E%g!{SS@EzTTdoDGAhycx1_gOi1_lE z>|k+wlC>mm1x&BH>OPYlp?-h{2Pi6e?{LbP2-#APeW1$$;uHmhDezNeQt4}JfRK~! z_zY0|BB^9Kv{6J@z9!9eWhkS9&;$bTnyjjshK@`yCYY%^L7>wrysU4SW&>KE^}8J zgxWXAbT7K(FklI^HX|o@uaQue#gq$z2QZPe4pZ&pL6kykb4j4GXQ3sA>-A{-DhMg? zB7757%ZyUoYqew&nvOF@*`n)1a#9-Zc`z6?ZM`sINHOP7zwbO{n62B}nNZjJ?f(GY z;%>g|D-?LHwmqzz=$8kLta)nYNkDUd7t${~oWA6;a~zku6P=1uNlNm9Tn)p~?PVau z1V6(ANc^!;CW#V*jFe4fv8r)F+N={JHG3 z*L5v>=lH%i6*j4N-m<^9oqhMa?AsOj^G?YDb-==Empwb|JSFHxj!uq%zU-)n*FTT1 z%FoIp{!5UZ!fH&`LLiy;A%B-DQFhDP)fcGR-EYf^vqRvOs4r^|GB^vbM(VDpNC@${ z_}DImE)asI;eRCG4{TtqL%W`r&2S@p6LjlEOoj?YaBOhq6JVjD!Q*kjpdaAxADvv( zM72jQrIB1_IOPfz32V|#i}zz+AsN>w~j)7e>wy3{_a-6X+FCO@yjTV8aER*|;@FF5`ut?rr*A>j z$Q+?sv9py7Cf9R&_0#n?mfj7mExSBAZW%vS|A|fiXJD!C;^O30q+=kdsMPKk@e3X4 z0gY`Ta{iW&+RyxLP^9(Ekl>17E$ggQKO}d^>~Pk`rK$bdFlaeTFcXm>zo3^FQ+N1E z1gz*G6Se+={Kz-KQ8@B*DV%StAMczxK6WJ?qXBWWWiffZdW91)6>j12W*xY6I@g@LsEzLU5l7`u5n4*dCL~x1KuJ=#9_Hs+llOLCCt+s0xpG zmaoWw1;ASbf%B(nS843-LEP|j@61ThiL^B8u2FgGCRk6x9w`~!yiUJV^v%#qqpp@T zJJ@S_1#>`5zC+v!FZ^oLJ}7_kq%s!wRpjJG4`#VM7l;062%!X&$s-5GvSjXveIX0i5Sh zK9WDNN%t34eei;0>Z7|9eCm%@jHmMcLo-dvb7)gq9n%L;CExd_G zF}e`UnowON; z!h@Ck(f2#a;Ll{+{P&G_m%f2D1T&^C5-n1$z|$*%sh3CYKJ`knNO_oBGgvV=fqSjU zPjp%9US~H)cD?30y(Ka5srOwNC`D40>gRp<$nvy(VXLW7*5ss@+HXemy7cG(yB|Y8 zlF8><1Qc{Eo%we@uD9*rPh^ei*^Tx6mXxe}H@*~oZ`tVm54|&Hly~g`DEXrLQ^Di0 zWqnC+TF9VT5scb{mNHXy>_OEbXFMWs^;6=fx1P7kezk@W8aXaH$5Htlw5E^3wJp3UWI-5 zuo6PgL3|3I-=!UWVnKj`Z+Df=s3;+4#xa~%`uah{x8vW3Z}BDGMCF|7-f?Nh>TL^y zc%fMxrQTBuu=APIq~}71mD7odBlKXf8bjuLWfLOuXPxL85SwNc@-3KeI1`%Xoa1K3dMl) zlYX$q0ktnslpr%dl7UrXRU|AUJL4x3=?8`l#gxMIt)7Z58~T=L9%gLh!AI4R_;w^Z zeLpzkf>IP@Y9;C_CuiQr6iWuOs%5DJ;$V%Fs1U*~nO8*DBlkc^^`nLC&bg6v)!_>P z-&i8m$7_<$8r(VLz2Ki``nqTymN!DeH6L5NCbi6+sqgcO3@%_iUYoQ6N@ zRt{M+-hL-?f*o^S!Y5gx*Ymx4R@t!pF$muLd=@wT<$s`x$4dHZp!fF!yIegjhKh~`~`&wX2&Kp?m%1Z?GVISLu!BwTiTl^~gz^p(VUHqwW9esA;+24(ULdTIG zV$FEO3#vL?Nly+Lgcw#YUZdCNcuP7xsDkel+hnm1zoaS)es5 zIV7)BqX-~27)%@>E9Te1I4M~+58h+IjqhmTKO&FpFPUK{s%aWC_YpKKkyFYKwUvd- zO=o048)?AmPL~h*FR-H`jbV?MRr2?spgN#L!x zPQU>*Tgc-}5Q6OcOi!fN6|&&@Jf<l)g74ppk3K%ExH^9Y6Q>Caz|o(_x$LtCc;<93!h{L_zJp z0Mj$|h(kU2f*;4Cams-@RC&!Um?_j+Z+~TP=ZJh2EJjO#3>5Ma49_?Sp8Fv7x?CI% zWDA0xoPClidrk2#p~`(7)QQa3+WE8n8+S6L{?HOVhL#yZY+U zLVr@bJ^$?*U@}GH-R@Ll(GZBe+3Jp*RacnSo}t~2l}$a6DsZq(<7BdX{`S%9`yDNN zkX-5_6;5?RpTkRqlnBPiMi8-GU`Jl_7N&IHZl7p-PX)y%0VFv%1PIZDW#ch&I6STG zWzjQ3&A&be7w&=cSlLSI_hqfi8SVSep_0!G>Fy^v@;uQFU!kk0sT==8kGfet`7H%3 zXVbfGj)ZXE_F@JhjCk!10L-M-7FFi47sK3&oMKyk`Az9d z0O&{kaCq@-_mm&qfLaMuHs?EP-_U=>ZpfC%;1c=sn13CAW3FVuwjR}TJ4VO{STc(L zAdu#;mSVzdN1@kWt5gTGhb9(T2`)9l{v`K}zbaY&AlDk|PDlwk^t%DnI2a=RnmI8e z4sw|4;bFSjB!iLEs`Ke%Ul1)@rt8w7o0m$S3K64*vu}$-*J!>r45fvV95^HsqsqaY z-zu^eYk2dyHB=MZ#OAg8uJ>5+@v;wxf`p?^`Pnt)M$Li(i^!) zT|OPVhr+2h`{z?mUwai-hXOqF;m%YecCW#LNc7L~>m?}}-|ZI$B!ORxfjVld`r9Gq z7l#)DFA~}(8W6xf1zSUSTV*EuB%L%%UoPR<5`6!q0Kq*` zSpkY1_ZIR~)hl1X#^<~|j_v%Lxab@$Ii|@$fK6rsg$Hb1-){)XRVI=A-P6CLDn-kw zK9!UB_3Pf-5294c(P3ZhfuM=5G}g|~AV>gnL>qHUZmJL}emLbG-~s-xN4%L(Q~^0= zA^?C;eHzcwMt+yxh1g7Bj=@_HXk@nE)7|TH4$k$<%1d0h_>J9@GNKq18=(4rLhyz^ zvWd3H&p!2*eBU7io6h;L`Ubv!C^cXEQezjg6Xm=eZRQU$DqvDnJaX=^AodpfcVD=t znSZ|Lv*aL&RYe0SXG?=|{m-bj<4{paZme>q58Gqtunk8ZQDy9N0S=Jrf;tqkqkB6Z z%cqRf>KET+7vOGBYu`6%DEGiM#c;YGE~jv}o5(cn-N9wu*SuOFRX~T#hRnexXT3n; zCUbS1q(cP`7};6vVXED*Hug6ELh{{vq$bUNKFq#KFTTu0U@i8b!}iz^@kW*N z4=gc-P-5jB+62yk{1W`T=Ps)OKF)Gkk$qi%z|d?RjGd1wZ(b->wXktX04030Tu;kd z2!avBkjR0{bGN>;Nwypmo$SVC-HGK*i6)PC z?)lw5DtBS3blC`O?mGq^D_4it0qdvd-8kY1M!fm*G z;U2H#8^Qb}fPK;j5VWa*G-#BxR~){P{7p*Mcc8Wt?`n=M>Nr~!p5*~_>YSnxI7_6< zYsjDtb37PV^=RpqpIpDMr4|vuVm8+90B6Cjfe#e6QJi9<*lv=po%-Hk2T03w`T+BcxZ7_$yX4+Wl*Y7rt76}SvGwv#rd|({hr{3(b!mKF zPg#PvZ00o)1i^c7IOGz?l#(NZxbAL0Fni9wAzzS#WW$4yK!#>$R zX_Qu-W{2xoD4E4t)=HM0-Y6enx^Y>qmP}zmPhr?cGoxkE-g8!!2?u zaau>v*9+Hee;H+7pvz0;yZE-TpC?gDg5s~8a${K8r7}_9V5+^REqXl&QS2P+%z$$u z_IkW)XN{cDYi&Oy0YzMpOnxeejg;ERBVfXic8Na;Dp9NYQ7BluzG<_JrZJ8>Q4Wt4 z6(T~9f0S;~tHev+>kG(Ws}rd}v`g#5M;bSMxtw^lS={bhgM&-|j>y`fhFl=l4B_~9 zo`R8kNp||1Q6b&llkEtH|8UoluH zZqADA0Jp;%XA2e)v!x32AGr!drU-e}a#GUN<#Ta<;q!i1%D&KyWr_qZ zM#ud|U6`Jp@5wpfc}Tzqvt2XHlMGh#v6qS(vnGrBd@U3(+FuV*w^Mp&MNpOU)Gb{~ zw&TN}SQ~JDsAgZ^;1}dJ>TuV`(Oy=Ae94*rZ~?%-yT2zVBn+-}iAqkDG8b#1-V-0( zbKZj-yRc_9x!>FUZ@3dSJkB}jy=Nzo$zsN^gNQQ5+aZ1lHx@0U_)-*o>myBOxgHH-lo*dc>-Kb`IV$K0(P#(BaOM=E{UO?t2N`s#C3_CNnmgGX)##8sCTS>;@8SaTvNhChe1_iQJwRn+$?+X;%-^2PcbCH^hk zf{0w)&|>%uDJd-oC*^Y<`@pID+#!}yJRdqSPqwP3$|qO9I-qSjF4xf2ZzvZk?#r7V z*p%MH@71ICJK!e)ClT|O7hFTUoNgC*&Nq~uk!M-DMI6#hu)@6fNrRZsTohE+{?>qx zZJ6I!tB8@0!RDIOIF-Bx%|F%Ckb(BrzSr%D|j;n(^++5%Q`)fLv&;2uW;mE(?=*j&V zy-dk_-uyhGq+EWMUtBROS*1?we0Ln2H%dri>$F`0MTd|>S4);XfV;tT4xoUKf+Uw~ zxMl^(;a?bW>WLpwP*H0NQ?q4}?=CyfF8Om6ty|JUs1n1Ppjfh?83Ypj}v6fR<+;Bi!UNxxA>+<_or9hOFPB# z`E73k$A+kuZU{$Qwdoh=YnaU^#ca^r6-EdCf)=-zh6g*z#eeltqshxWUKoB_)7 zlj03F*ZW7Y zQ=#gofRa^e@4P%%Y7EZk3oKTK>ha^}S<^Q+@qB;1@aA5cUI%ibp%s6^@-uECiAk&l z42l6MZ%+w;#2=`Rx9W1qeK$%qI*qH_ZQrXe`zDN1-<5jV0n1e}(#|z8wZ(|6%rNgM z*Eh~BL}70Jh;v%`ib&8^1NHE!j)lgNsS$DCT#&ELxvm2efLG!z&Qowfb^H~{1L|KN zM_23%=daV%&R@p4US@)pK^|kavc5XK5rm58!BN}5>q-vgxVOd%t2&T$BYrROZkj1K z#37xTKDUSd^q6q2<)hep0B2U$IsBcqs*oC(Gc@qstaJn01aCz5+%LR0?`~9SWclv*-`&qs&UYKWlaRjid{}T97`rB#YLocUFH}bML(d;Bl(pXn9>|vH2r?lgYGWvj`9}Zj6T(Y^dY$R2_aeKRF3b{*yn& z>GPr=sN@3DdvtIVnB|uA(BbFLIe{*)oas zdH+}`{)i^g4(;Jx%N^F?6l4^F;vUF17b2zW#pn7xg3-)9!pAYZK5!UCI_K7INuF1- z((I1KIJPx)*o@Pic3tQycj7S;V_aI}IEu={TN}X*3?$^1DpvRJEO!yVV~ZOSBhU!} z9h=P4D!q@9tj;3qg#SHGCuB<=Bc8grR)&z^Nkh>Zul7N@1;g-U5(~y4+XJ#U8D%N5 z4u0~jmZD*PJqF$l@M&bspEIr6nAZ3Kbe7xY;de9Fo8e(B#I77c!i|2~Z8g9J#dk8- zyNoj1q=Ykk(nK*Dx2_qxH`9cZja7b?>FW1Drho8zv?<< zR1Qr*fvv3Mw-^)WB_3)=HUDD6>-!Gf08Vs^sZgmG@-Cug_5AVqO|dov7XMgWIsaHR z*Zh(*Wixy%}9$ClZZl4Usk?s>UC5#EuVg+x*AUofm+hPn@ zssZYOB&DMqHqTa{ZR)eI;OH4C_~IS2R?*#y%x{GK2A%=-o8(GsZ&){ke>GX!52Fyp zfpd+BABNT6Ay*5(w;ilmrmV?@2Q{Ia?usEIqb7yxU;xjdL_W&l%9wJ?&Yn~4fOK9< z*!if(HhTLHT5@7rE@ZW!V|WB;fXc|L{Fp&lshffR_NHkID6*J+a(!r zt%0TjP1Fs;#ylMhe?+xG_#ui`%&rCs+n0I`KDe%FwFtXrW)A4=Oz{jHGk$gUcwP?? zV!CJFzIDZ@`~GZ`P!f6b(MN*nUJj=Hb--J(pbYdGZ@f{DdAv;W%a@PNhdG+}*>(ps zhIg^U^X*KvujIOab8#c-2aIxLUU}3{cAN~XR}>eDRFGud!LlFkyouHal3NY8@x0F5 z_Lm9C7*}>^DMKyW7guBMgXeC{;5J106T1~KbGqm@Maj;^7MW@$VP^s&dsX~YQ`;Kh z!SUvy774aB6w_p(ByqoA^6vM=wB3)%$GfatekAhh1Qk^e2dJRUzZRUac`xG>KwBKW z)Od5@#k4ebQzt z#E;xENTg?9sJ`vn|6}jXx*fH$bkSdvW1Rbt9`wzlKth0MBqSQ~at9y~ec%83JJ*iA z!(pe>c2>FSWSw)v+Y#D}RxsCGv;98nNu1^#|{V#Me^*4I(Ki zbWJxktP0dj^+kPpC4D{}EHNSnm!i$c#=r#Sya3~`k10qE%<~vj2`E6dEVf8hcYn~s z1}D$uzyu;O7CsKtHD}J~(*&SZefEZ@hQ7c|!e3}Ihg(lZ9mGTv3DtZ8AI1YGZRm@Z z#Kt=011cav^P-m)Ca7ZNY}rOC$UuE{t~Q%)to6dM&4dpRV5TXGm5SozpaC9*cMm+c z86nZK9AdF=T^9g#_R=Ihbfx1oUfH8l65ejtdzK`cK$^*y(mxx51!R&^Xr1MTZ_wwGtj)2jb z){;~LU638gDQhOcfMd#)(_u86dBe5po!sHVIPs2J5Us;W&cMqpBCdiG_-- zH}*QZO+`fjFW$f91^6jPLX$6rpT1>qtr@6zzPfGb-tG7i5N-RE;S@M=W&jN@w+zaK zx{gN;nHeD@T)D_LcApZIvW41)BvFnzMVJv7GLUW9&shnu?{^267`=HoXM1{Snxaj5 zt%{H?h1I=V2qVCt0A#SR{hmTsQ5R%8C4KfNa6g!6hD2=}Y=ZpQ^$N21&Q27NrT{Ii-QQ5Wx zfb3@zz`mCg`!Eh0s>_AEc!JjBS4QN(cKSZPX0pj2iv$pXKokd<y613J%ybC9x~4&HL~W4 z2xY!d8upSNE)GH`flmSD+@dNsGgUpZb9d#{JpjE1p5*$%xzqCo{EX`eZ`;QX$!ttq z+RUZhDlLC~*UAjlMiOv?m#6a0qkb=lSEi7tk?54w$Pt=RLbmj62a5?nHF%NZ9)e8; z$8bfe129k8`*+^d-17rVW2iE$UqHVH_1ZP?eG)IQtfX_Lxzh2lU2&i^vLPp@bgM8d zp&5YD7WgfZ4>h1Q0N#z6Z7=fW-9GAJptZVh24aV`N_-zZqTJ$asA?9vnhpa+L+y!x zN|PGk``+L?2+&d7KA{N93Boq$pP?1V_a1aOxU?Sh#ARnFEz)zIsVszXDljO71OH~% zgiXAonZDTN@cP1?_U+p}Sxrc|Z-^qGf_6k#u5&za#$fhFYmM(caS?&{D5E1BD+( zRF&-=46n5QR(lOSWg5 zieJPFE+WKMrr^XKQ1jr5oeoX$k+Rkno6tpi5-P0AGUWiZ0Iis*)(-m^O9Jtc2WZG( zh*B3<>jmOtXXTkH05WULn+lTB3MQ#Jhv`B^Eoz7mqLQDn7 zvP|@FLu!s?EuQ6iw~miT3sC~#Rshgo4dCng7uy&|M60SznRo>NaZowf3T>f7@PUJT zRA1wC@w);Vuej*XPB==~iM$bI}ekJs9ZC0`#vyKa$A}d~xNKfkG}ax$mAOu0DF?Q{7CVyo23# zV-BXeYYO+^tXZv3`K)QTB9=7o1)+j^07}sLl~QHhGYv1Gpdyw&0CN&$#19wo4gu(VI{p<69jq@I zOI>311o(9(u$9QSC%gj$FGM;e!1sXH2VIo~GY$Z!Ps+u(24w|k5B~bJ_-R;+DF(zr zX9xpAeKSzs7-&;Ns)nVB#dCuW{T*;D#hdRM`2h(Xy}R&tEWPx3000^QIGe%ox$g|G zJs@@|5~Qo)5Lr9K&M}}g02H+DmhV;GL#|@ zJ+2T|pM`WLAGgpuKX{4PfUK;C{Q}Pbkfm;bj7x@NSw$COQ)vu7KB42|*;@e^H~jG` z_!3%%49i)F&jrD)xITk< z1ZQxvmLJJiMQ_jm9T;s7#P`t2l#f6a)|B!sRjmuynTtVrW(oasRdrxtota_r>kTTU4{xTHdi?a+cF0sdjg}B9PkB{D%`v00ofLf&qKEevcGdH zi7Dt+5W5FZ(sZ!cAma#rSQc73{3;&g#PFdSR~4UGYPP(7Kt?VXFh>>&u^)UqG2D|0 z;!r4R!|W>llo>hV+8ke%4jiE6Ya*A|>p(ysX1wk#4bKapko@@$<$7(hdW*x*IV=tk z+hr!m5L#yo&_vXQBohdCp^|e6h;CwFmz=i?fD#>4&yrjjsH*^j*{qDscO}ffL5${j zqO`|>&>knsIi40XS0I6Blb8Ll0bRh-moMY?h7*VmW;rPaxayeyXvdJSTE8w1dVW|< z5nGH5TTSV{@iWHv@W#xRFuDw$G?$qm!RV?Sb*Ys zL?Z-&e;bJ=1 z3QmItmJFy@z6R-^Nbq&ga0(gL^y`+s_6>$_JHEeP1MP}l{O{i#sz#Km6?lBgKiuB=+u-juJsegy zHQbw!H1+s-n;3+L#g}6>-+8Zj0pPB zdxkIajz8t`xA&w#<)b~37<@b9$5i@#$^15%el>6UxD3W@{_!jX_U|P7pU-3t%IWha z|6wxxEb8b5ENM2zcX%mi_oWY782dr2hctM7hzQ#EPs<&Edm=&l@!b;N}LX-3dDPhos6A;HQ;rf*FS1_dC=j$)U?{5UjVdy_N@}J7r zU#Ue&613>IDv{s6n}}9sixA2&^u2pT8$XAQ&wYnXC%X zr276UHKd!a&5(^5KnZ|qX~wasV26JqJn*uhs}=tIaE>o=7?JK3f}xEgG{2KdA zxa8q$6usron>eQ9*up{tiy<;NmSy<~XnLXZGHu$QUZ`&dyqXMIB;O8zoO|EACOA1* z1Pnr?l`6=|N>dF}ydQ${?|p*~|NGScos9n;h4lZ6|CG0HxZ<}5^c#BXuaqkuqklq3 zJ?LHho?zkhr?CAfSlFrRUj{Rwp&{(4H|u(Ev&{yRN+a0dQiN;4mp0J0ZAz@kqp;%@{4 zab090z|_P({`@$^ywN7xx@Qnk`*s4DG2hPdZQHjC{a}5ejbGaPBt^L1E z_pj04S0q1ZnD48}KP)dltYghImRSuJ%7?6gGWqqg0yidp{DB+$<#O_~&GhbrR|ad> z*O&QRioS-A(9;=xs=XSSkl#=BWdNZ?@Jn%4D;(FRKh^QLG<`Ar)JCxNmy7c+R^M;W z^+%QSPpqAgul;4-Lv{>NR0kAM!^0YmVkpPRz(!Ii)N@(%tNfe-{fZ-JoTO@4i*F}V2G zZNsMzJLzu({SiSxE4>co&`^0ugJp_F`vx^yfBp6q+oC_BTQCe-m?qH4;cxU8I5dB- zFU;W2eZQiH|Dn@-T2d{_t!*4Yq&W^eG2F z#%1BDf((8?35Ia+zb*k`+pi4-{)1qAhH1ZV{KdAPRR2ab)z*+Sy-=`scg<7Wesf@L%nc{vG=X z$3NGXKOKVnGafLKBY0Mj9Jr#V1;2c)7fq535LNw9*x=y(L2&--JSc+lbDrV%@8G{6 z^iO|2qaW-nBv$u78Tv<3^PdU*!{L9{5<~l4<359g42p#Q9P;-*Y%ydX{b?KK2UF_P z*!np*kG|56`VGSF=u7@(L3p$RqKW(`te($E$^SO1=l7-Yn*@K!F_@+SDBSO};Zv8u zSN-#6`8wCnbL-1o0 zn?ES^F9Y+N-uzcmSU(z+Kbw<38k1-pCr=Fe4@Bb6n;$Q#*{I{33&sfn9()Mj8{UB8T zB=PVsKJmXWAMtZIjQI@2qc?&urGBLYkXA=SzjzB@35$QHIsa)a{N7uDLXfN-P)6|& zru9Fh1%Ig&ei1tV<*ffXukjD_p1}ehXMdRYWt^aV$FH4^Z>b72#lLa^aMJI2Ofdh) z0J05VhTR`d{co@Dk3;*+ml*#A^ZbX2{9E$#HTG{LK3}WY?}<+j1O?#)Uf&;y&tD-e zV76f~N?d=f694B)%cm~-%J2LS6rNAD`Fq0izeD4^I1B^ey8nx0=&Ru6f1nJ(B8%49 z-;<%S2cY}+M-kH>h|^!8ftUcpK1yf)lm>eJMuPf(^cwc5l~9=UPnbmij!W8S!0PuT z>MJ=teiU5&cdTmx1SAMl#`+~y-%BihZ3lfX*!w?0j6Ndg|3l>n@)PLJe{g618v~#J zN(%ZvnyCHPgPgzNPyg8f&mR{bGoSA8AICirq8WNM|0Cj_zY$5~=%09!;8|!DV6jhi z_2rpz9Ptx}5fsDYBn=-v-IFh$;oHOc%q*a1@UI3R|9iu*|Ir{R`d+_GqI|_rejVt= zIr9ICFzi?0^3N=5Uo}_%;Lm>*^}d2JfE51slHD2_)WysZOl!d|=QrR<91ehMmY!_X ziUU{{hr>}34^Q}499?LLf)C6CD^E8EQ2Nb{KZXD!>D4nxBZ*Zl7u#!o2RKLQe^R2; zh4-#(6rY3QV!JwkXqIz#lniqBYVi&9L^F;WrJTD~_7~KX?%!Jt0F63gehQaXK3rJR(_Z_ksyKBDWYqi#FCS7U!5k}H`TtUm`4VO=X}q4ohb zCPB=Qcz<;V{;^-(X{3eX4V4YTOIn?yT`PGdQOo^o3(x#`IqC(#cmPm@)G%sbxAGk~ z10!%BuVTyezA$mXh%+H1}bFit!!SMtD9 z0Nk$18Ql=2RywJdpEk3h8sIY>Z6>(pH?=+tI-W$k1t}ZpzFs4-SaM=Qy?|$h@n%U2 zNPGyM{(8KgmF7kstVry(PLduov$_E=23_9JdHS}-^QfqtH%Wxu&^oX|Xj&wiNgLtq za)=McRx!}G7H#RuZ#`<&2il-kHT~dj9d;4ITY}D2l~BjGM!LtQ?KdhAFq#&b%}qB* z=lc$9r9u~&E+F1b&$ANxfNyq)@~cR>m&cowGGUf7ToIM|5L3q^Kwkox)oml|>#{OZ z^d9}pYQ|LcQwtL)=kdM|`V(+lZ077Nk{&eRb10I*u=Z|1OB;in(0+fAS2;+s>YP* z&<(C(pP2E`6{m-_FlnSlN_|qX_ED`Jx;B8NF^L}pVsgl9&+BhRaJp-PcI#B2gV;#l znr>-o(a=9FjGbTsf|)e}t%AIQyd2eG;}tAI_>j_RLXFnY5ARSh@ty$j0*!wAnMYC@ z^t&7TDPorZeA{Q?Q!&gGNqk=Q92)9mS;NlOLwqsrcFO`8rmb|n!@gwXx#CDmu7T;~ zJLQlHfN`n3PRHA31gdzSST+`G6L2Z6u(}C`3bS9j!v7<>0b%YUR+@P{INmIep499d zR+sM17YHFk<8n9_hfkxi%oF|(=gNIQ#da~$$56((2!u5E; z8sL;6FYKH-m4wxIgqYDiQx1JW0Pqt|n0s9?<7(f?*N&u4zTa@_7#aN|gWo^^r39co zw%uD8VNVvu;!-YqnPyXWND@589#z`B1Xm}qn*DAdMPL9k6C4bmf)Qxst#Rv~zQ~Q? zt_Tzqu}J-xU#sGBw?HTWEWC;mz^t?v;KzoI@I!e7JMhUn1ziYmI49be4?!X`)eX%E zqOf%`x^3Hd<*V^wsPvAm3Ye)nmhH1~eH=wlqySnV3BcGhC>QkVQuS=-HE90h0(kE* z0L1bXoGoDUg(pt0zG%72bM4mr5^UbkVWM#nbR+E{3PbCvEu#W;eR= z+um*_RbIRkAi`K4AjJx0{79Bl&Iiy^-uZ=SL0%CqSOhy@v2E2(@~#z3&vDdJXv*J6 zk2*7!5I724&Or))B_Ya(XpV_JFM}tJ`ZD=gxL$iT`uDp{K0(Bap*X=cmho{vQ(!x*5wg>(2{x7RomK9z8qDB6l9C-FrcLtJd0B;2K@H1Dil!tU-V00o>at=NwI^VgQ{3m=qNc07&cTk#WxT`7M}e zqSfbhSONZIshM;D6T;S;%CUT&kWqPrZBCLQxT7#J*@P5K@ z@8A zB6I6nYS9&*=_Wx7UbsBU2roE0e@RzgyirOXv)7h&2L%pBq8oFjiOc}`2j+Yjz0nz{KlTQyLtoCU7F%1e3ba%Ri<%>kx*~J(%w!Bww76Z5b}+7B zd!E1&*0tz%!|s(4C@yzQV9}8#Yku@SeWfv?JI2ixB%a^cx0o}GD zAMs##6m}x9kE)k@S`O*F;@E|bwbMEP`D3Ey)Z(zarhf><16{%h~){8u31&d1*}yvfW-F$112L*(_`kW=^R>Nn!WBF1C9zX zs9|NbV0PM7=t|mhHHGUonjtK)%nL0`j{+a`&S55lVyiBf6a5U3%3wSRVMDoeMFO?l zgIn~A5o*+pv30gj@^}4S6>ki)_tk5uN6u-P^9Cs5mo^EGa1ehTAvk$I=v2$I8@C~azA@lTwAN7D^u}j;2Xz45PW8B&O z!!YrXnE@VxkW7b+k|U{lruh;1ghkQ-kwepX*3$qkXuxn=72r-EU`d`lxq{?$JVcPA zCeL^I!Luiq!DaFVP8vY#r(0EP6>Cfv+?)A{0>EmmGsTl~-m`}(PB;77FZ|X-0NeDS zxBldYQU>f!Lqey3`>9fOCMFk*9%>aIn3MDJae3-Q3~oz|2g?b#!Z^2tM;=RlB|E>B zr<(^$J)L0=nu<>nm#-u3$+qLt9h=e(4~I@#ugO(LKlB#-Sb$RZY5>wK5^)4lR9J$2 z$(}A%561(*Q%x+C2J7hZ1jw7v*koX_0^p?10URGdo~}IZ-UAXS)%F7q81L<7DeS8Z z1y4BF5qkEjxdR@r8xdDnMBv2}m+Bmrb9QOFNVK`d4$n7E2!*gV=A+&|DZogL0JHrv zg*^Z%_JA$Dxeufz0iE6rpQn>Gm-Hbxy_}PaVcQUcBkJ@Qj*@dxf0_*4_Qsi?{ixrJt$e1ZZ3M!U zz_i{a6A`D3jUMg*+*b~uE{|@f!=#>MyvuHQ@YMSN5Vt+dz$E(^JOC$Mx83(+NC@>} zY|<@z!MZhv{S!FD`;%?=b{D{cDuuu!g|2=n9wk2me04!k?qs=?%UVQ^t3~QwCuE)A z$9t#3zc3TQ^5=@>79z1nI{YFTel zvC;KR>f1c}Se^{V zhoRI>q;$5`oN2eo7qs#C_MQr3h8+R47&CR*;JU2;HYW{S13_RKrrlrF^BOg`!dF|s z2dmEUm#M_v@>;Kfgy@*fZS2HfnGFE2GP+M(}0V6U=N^R*YurAW}7 z2^|W)7(~NKJ=ho?`wpgy%lf52RQ%&`2MFnSJYyFNKuDQOnQju}xxT4YE7+C_{z&rjeekS|S)?nEgnLtyDsizH~slm0hix|XL`U?D>QxU27 zlS6OO@ND``fY?Zn6)<^C3OM11P4HYP(1~&B!?MnEu?Frz{>YQY-Sx%uwV^*E3$LXJ z)Dn>PljZ^%tKwsSH62{$-o52I9zfJ~n%WTnk6#mb_nMCOJOQ^9Oxt8G_jgve)^5VG zUiP#L1JnU);K9;55f4*7lJj7{j>(O!S{DKuRKCkIg3%Jdh>%``(k0vZ(#!(EU;_aR zCNNXPxiS`gwBlfQV)OVy&V9HbdDz!7H{piBpn9PO5J@-f;Pl4RHJEo1Rf{tUepHo`)%L^r<}}mlKpQO!D;6-|3in(fm3(Qz%k# z41tCFwU;AO%%mZEp{M_1*Q{NVK-x!PzyYqSK%zC?U4>T1*0lj!Er)?8+^-L3Cb#j) zKFo{rZuyps2L62(-VmG8CQXw4c@*j`Ct<(-T3)xdrX($STYc|6%CmhP_YtjpPBKoj z=XNU*0F&GsVESGi4Bw7TXJQY4vO$=SPqw^*2W9gwlBBjp2D-hDVJTgS=?E72Q^;qa$2zTVeVoBoBa~b) z9pcR8!7V}x%2nk0cF(vS;)?2&o*iw`<+vcCd((@|F*k2vWjLOhDjnz0SOL)AaNoPw z=i>7z&2OGLY-J!-;8GN{UlzLdG+_s6;;mT7<(h2WBrs)sQO2O`d~4T%eh!F%Isz_! zdJPqRG({DtN$GI`#zaoSB^2LrAx`mpwue3BbVl1RRa_vw`@ZdGKr110K^l*h7XoM@ z-o(foxsbQ+n&rpvPMl)`lhW`)wogW2WKpXRXb%GXatydX$H}ZMM!0}2DS$RJ@jGo% zH+2JKq1JgC5>u#*7ubgEti{Z|-Llg+<w(F~X zQv1oLRFjOKNBaf^x7(S+`Imx8WoBIwChYR1Y`9o-g31oSBzn;;}$Q0{>c%@=-C!DC6ykuE+3! zA~tFiEer6+tTEy*6O?CY@>Wru_q2Km2cv#Gc1Cp9Ht2@=aXZSx+z{4@1V7x5y+J*> zNt@Fp!FX-~RO0~f&m1W)kxdU+L>5*E;1b?sg-eaY*@1?VepM3_>1L*8m!u)z-I5!} z?hH($MrJnldbdvdVYQG|Z>QL%_?;Eq96o}hrzSRG3BIQL^GRW#XYvT|YZIdPVH}f< z;pgF?V+9Ds*-|geaqNLRj~js64m^?IG(Ri*)M93bmo{fT?jlB{#&%Xm}^b-i#-tTfr{7N|Ps z5zmC+`!p$f^C&5re$p}yoC~SvZ&j}Bp(C-U-b8Y3AG@JqY&t0CB0MbvcPg&{bguQn zWaAYaBF0oI@+`?j^E^qG=wk^3ydrm>KEBUIJXiSqNUu?qAb)zn6Orf4@M6|?R&?`X z(Wa|poY!+;g~xH(j`?--mQ&OL&ZayQSJRUF6GX6TI@~jgd7fw;D8(?x4)0Uw-n>Y{ z_LY)&Vj50yfb?U`!2`+stOTF>7W667A>f>-xOKoPJ-)h19E4Zk61e6~`kX!g-Q5Q2 zC~ugo6Mg+=GapD41hWcX;dJP$1&;$D9e_u%A=UhN17pJh%y6_`#pF$vUBGo!HQ%Q# zrBdtkREbrd$;Vc!Fr0jz1*h0Yjvatv97cxbKR*BMBA}+;qspI{9)kZz3?vl>D6sZp%wN!~J-& zGsp}~3L#S|qkaRxKb2e}3p@@=HFzxOS;kD`{z&iY$ylG0VcqWRy4AUw-a@eP-Ti%{ z#}@;kr0f24!E1YsG`EZgNpdXwOdcR+{D}JUvavGY8hR; z0W8#m#`TBhwFt@0e{Twr%`3$A#QfS_?u%RAhMV_}8DgePP`?Q}cKLP{H3>GAd zjd|lf0|VaMWKGsaDLUb(7zSu;r|8115csa85CHsh^)+7-QlJCNh;{nrB=ofpm;*`b z*=4G79y8pmoq{{ORl#t#_H>VSZ9P*$osne%sHHJmzXxQfNrCE#Y?aSen?felHfEr9 zRe{@kdcWt}65Er@16@%~@ja=?JAmzikszQP2?~fED7IICaL|)hdbWT!UNqI#rB-VQ z^g~4*A2R)-^p)wJ*f7U$GHLNgonKGfWO~DS_fP5b1wN)QMAxf@+?Lrp>^!=!kV=43 z267iFF`jmu$wvcSPg`Du0SxaYTwU0`)TBHt^Uf~?0*E?I1VA$>UwNy0&_?te9KwaT zwj==R4eaitFkHOm)svMBs^QKVe@#Qc_#e;xNzqUuLs)Hh$WaLBEP?STl-kL=wj55c zHwvwTpq?b;SEW7X`?<~d$;V1wS)c*Y*?}+%MJF3+Q&_fcz&KxokKA8DO^yNE8IHAiO>1_A7A!2ZbadYmqbw^dOD8P{c`Nm=Ny7fp;hK*F=(JY&d(i&O(CYAr->j!;wrSx!#q zau=OF=T?+>SwY9a_KbjC@w#_$gpUyGfO|AwZv;drEnRRi(NV(7Q($t#kj$>|JtS}U zM>=(ASdO{;+||@x_8P;8p9LN(as&Yfh{?2(KeY?PD$p&_8RpF zyyo!K1mak<%xTbo8+_kw&|un-gb-7ht>2Yo5HHUkW_91j#Au_-1> zs(~>j@f@ttl0>f@7q(-r^~&{eJ3z`dfg)RXcC z#RpGUxd4$ZR8w@odbqqNL*%qJ#aQ*cd7M89ahb4W6# zl)EN3795L!Q-n4opp-zS5-DpyhkWxqn>zIip#hvMNSTyFjTIoL=hOww9{$0*C}nb- zjnjhW+vIzkLXmU6b{o62I}SH_*?P^^2@afL?&c|>K2VB(leS|9fc-@@U;$}Pp>5LI zxI_HY;9iNb&|!TC%xC3ET(rr)xa#4xwGMd`vqKH&>}Z~15QgpDP2pC{f#e-reLnDL z#vetJ#N!D{8)gT%SdCsMD9bv@SkcQ*D8@YJ{8j)}~ zuuv_wwrxk(63eJP1NtxfhU4K{K$#Bi@3y(I85OT9c)F+7tItIj?<`aWZ2r66XgzOr8Y!zO#5})exmRFRlA%JKiLKyjryGTo8qT$b5U!VZ}l-Wy5f6zvJ~0 ztdGRK*za*`@%Xf$RUmR}-P{lilf>B^&DTyr*^HT-Uljo41NjNu@KuJ26PPC}2flU= zcEi)wB1E|T}48qA?g?_(70;{=kcYjl-~&s ziSze@U+MX&ta1*Eui|#8tR3-3t9q}OI4>&vdV-T#T)XG8V>Ae+MSuhJlSqOMwrytb zet3y5WK2l&EVT2rz%_9GAgGxG_u-Dc>C4-Tp^)Pv1f((<($tWbtWD$0^Nd%+udlQR zVi%cs*d`v1m=*@@OW~7!OGilVSfuB{d;5m--CNE@b&ogrl2UVigUkz(kcI}nJ|5x) z@)Az}3XZ2E#-dE{^?XxkYuQg`$T`;?IJUiXGC2X?{KtlU4M>CGcc zL?A#hf8Jgv%$Cpg=?pQt5+ZHaQhB;;v{=)^ zD8xQ)``aZp{c^Fj2#iMXD&_-tH4@~n7$~T?BQ?@H%*~&vR~iqdzsyCH9gg#G>h)8P zdQT;mfE8V+sIy@!@N5cGo}Kf{_G+KPFrcry6R_q<9u)Gqu?7SYS7qJ+^9RNl~D?d+lyREQ;KhWR!~h`mq?lj=MK*$6|Kin06!cEye`$&v?h;% zp#{skATL_nns21tLwVhoa>G@cc$q3oChilMbiv)esLQAbjvB}#@eG9o^Y1hj*Z8@4 z^U>&t!l>^+Y8?|BMJF~1e5Yi+UM%S;liu_G1c$k}DA5x#<+^w+?(3Zg_sLk~?q(Q% z22{S{Ss?q{Ch^VVvTVRkKwO2lz0#4BJ$2ycEHXp7l9hcflaFFEAkX#j+2%dmdqkqN zs784}X*9|$cRbe@1u9#(e0c~e3Dre>SVO9a8Lm5q)?n@y8j_d^(V4e);V1!5k8<6J z)HV$3Xd-j#$am7ce)HTpf2?Lfq=qB%Pw~DgFTXm`786}CZaz68Cjh5jMKoh#Y(RP` znQ}jhZ%_40CllT%L}bmz;ZzK0F3ElVqQWs=T;~-oJS6=gvNbnpf+f1?CCVVB0Q?BCzULH2lvNG% zKZSmPdIC2DWPYRn#!Jd38oTC)e2Ky$(Wcr z_!VnJe6)#Pc)I>nMR~u!8pwh8MWLfKYJXSHp!VR9X6D@Tbl0`klCH zcRR;3wtHPV*saCuMLz<42`?Dl#i=#tghKBj56?~_=4%~|e#&bnpj@Eh#wQsxjvc|0 z@HFQlI0jTC49S_PUt#@XUSxU|Zjq}^zRHH9h;$EC#cP$G*6aCt%AHij^1F61FenYl z6UjJ*Dl$!;^W`PXM9y$s&VZM7n2^Zb?knUIdan>#Z!N&m5q8TAX>)b~%#<_FlLs_8 z>U*yZ7Qa`eiVY<@!>dQa1UtVwl2e3>&upNczn|Nd^7vwi-4+!xR+=jZw^Dx!NNsZP$c@sxVzKy8qTDbwTsN*(WPD` zUJkZa%{1_7JNz4*iIM`=6bBO*{B1K#6TUp)-hqpsjM-SW+j`y2C&$H<#^H=F)AGt848ZxM-!Nk;luk)!OWO9;shrDInNY`R^g#Yp;C86d>j=LBKSbb zmcj3ga?e)MinWf1KuT>-$f~D)>t{albvUGvG{d|zMj5&i>0Ev!g2%(nq z3Y9)A)K+8>-$Bz7y7GY^DpV&cK|uvO7;?G0`o^$NnvLZQgkHy|Z zg``j`e$qOL+dP$uchQ-Ex_P72q4syEZtBkm&sww9_QTnpcoqu!IX_JNI(+*jek6O~ ztv7{m9oI`&rIxWH@n;}K6?%DeT$hNf>19`yDA6k$E(QUbwmU;mkllD5%po9UytGO6 zf@mgeWx!zP?jvc-E(9vP^nGYZ2^hr)Z!BD25HFV@cGgd5W*rKd1c8#oppygzs*$SG6Ga1!2UM>M5_i)t$h#p= zL@PK4PDw6ow9;K;!Qe<6Es)sxFAh&k(ejQml(WpN^pF4ytIh0>=Q+*M$OHR|(*WsI zNJIL~QCa@OOYxF!cPq~$bwhq$8c39#j6zB@lv+5>{b@()hGJBn&xZmYx3pL5i&m@GlfHM+ z16~NJK0q@gl@yM5xLBQPih5U>=t?)`O_+2ohbJvqqDd;F{kr3jUhVnWJsaeDrh!6G zjn4jQVnfX$+fH$U>vX?Ud1{6EB8tJo$~-*LMo6+g#YlNO#N+)uznOgR=aP6F408(I;G2$GG7%-lnA^WpZvTTD{_42`%n}a}G?C z;>Agx<($$2%o4k)ngE&sp0A#h<62rd#;0&bKdZ~))y3Vv$!|Q8x7!_hKN3}gv;w`s zwGFs6_(9VEe(LcIyjN`E7{0dcS2_0{Fj{i6oA|LRo11b+Zh(}4EJ~u;MOau9@3vX! zj~qCasq~6oj94PcwH|%22a^7nxIDd-V|0T-H`R*UrbXVkak_7c`9=1z4=Ve^^pKWQ zy*l=Ir+2?`Y-WDez_(513&)DUYuua(ceo^2o1W{N203Yv09N0D_E%VGrbH%BG)EZY z9P<%Z^)64{yRM8(ha9JmAL*7LMS(0;VIPoc=DY+JZ6G5u%rM?aB!f+`)yTE1p@a(I zl}e$IvM=D^3$%PWLh02K_e2%IyrGFFcaAOz4a8e;66y@!Kl4kLmosICq7UDRog!w~ zK!KvwC&e9mTrO)yFG>RiMFc#z6+%2#%bl9lHcx4&8KK6%t*n}7oTEwg8~!GN0E9mutDhO0zze@9WyCva#(`b4bUrhA_#Um?-K!L_GYAa{3ABvxR|cL& zdVaaLUNAU@laHk%4p+Pz2P&wy34`byYrmMOdB>IB`J|yJ*Y>K%6v(-h-}*!8-v%Rm zc8UQd!VEW*E>ypq-d>-ccx}T_P;du{4vt8G?wJ}0*7f+BUZqzj4hGe}V{71NyKMF7 zjnC7Gg{0|23Olf5u;BC{yBEh2@^O3Aro)F9{8UT?6TI7<7=TP&p3oy8$C7^MN9%oa zz1y3BHw8Dx;_ur7i}!O3k$lt6^bv2oJ5-0pEB#irl2xO3++yDR0*~$ykpZy^ymPt9 zk&`R89qSHwKCXGHPkfnpQkTaN!<)c|yMS=SRSO>etI5Fgz9yu;N~~B*2D)zlEKNSY zvO?`x7lkeGlI5;Ay#Fg9w<4>^3dJ~3})p;pnwS&Vvf>&+XlCr z1!grt;l+?i!UM_Q63z!2wTwIAR#><|4%#!;*e}pA#*O&J0#4D0Ua{zyr5$PA9meq_ z*$D0}tG|IVjl9&Wgqhg8b^HdOA)Q?47IYZKDa1v^F4nSbY|f@X%)1QE>oJ5dg8wom z_4V+35oVdRzx@*)tmi({TM>slzuKlmt|~TpKpm&fMRoy7`^uD32#wh0xv3yn z06bvBN*_u_x1D2ZkS8sNT(Of$8QImoHqQ_~mZXqTh9U-YQ+hD&l=TJBi1wgPg?b0R zWQSSvFqffZD6Bjh&rV3)TpG-QNUo z4Nh+1>l2m}CUzX`MZk-c*MSq+S)MK?*oHv7IRsL>KH&V&-N3$Qt9Pp_6=?S(efns2 zxy#wJrMNhiqiV2Nio&S%ZuS$S;r#|?C-erPg7emF2laj+T&q5*S|ucZOV*Tyg8{7L}+@OWYfkI}Rf#Bs87j(I8PF4Oo zoIM;iQ8p*cKJ*}%s|Uo&h0>UInuh+~@5oZZg-T6%=nzXL5!?pJn3=PhKI(-#LRwJT z-Ypclkt9#?**S);qJmb%%NsIS_TCF_VTW_dQD+bQ%oAIzd!n7_!B9!)GI?BxQh@IY!q8tSR%9ljA4%3-eXOvX?(HOG(_$bxyg!pY6&^4#dXtkkDW8`^3 zI*-qSj0hi!W%d>HhTIl$zQ7Jq>@4c>e!G%94-@0q&M7dl-Yo0oj|9{s^QAuUuT$uV zWDzBsCC|WlJC4RGh{UzuQR5(8yc1+;q|<8e-1-2u@J?LY*N$fm6ENp0@Kmyf4oo&o z8AhP%JGGF~8ImNpOHMx3&tSP8sK~xr)|y~N6Hk zN!vaVUie3Ox-b?|0vV^7oRYqQ2BMm7a8W-5+n|?kHbSF=;FbPofp=vR@ znzW}jOO9mi+_xq1iA*Tafa z>SNoa;EnH44x)yZht+dKaSU@b6qzLLo7*tifyn)keJ-j?-_SZiXwPW7Q#5iOs5+#5 zsu-Z7`H&QNK;xvkooaU8^(bNA3k1<~<~UtWV&c6S*Xx)EbjeQOM+yi0Ahq|x{r}jz z4#1}BCaxeuX4&{5d$01c6PcN9nlw$@v`xY&SxwUHJ<6VC$&{f8g5m<%GGt4E0;DiXVN0QPP=}90(dEAsJ zyGR4sBp&scS@AKp6qY?!1EdH}5|X4)@?$&_$O0iLE|_!4Rgp{_ zjulFbDNrIqk5cJG9t%&yQK!m*5eW^$Q;AF;&&-4%Hwk9s3coi38jv9heOP66<= zzzR^rR)s7!)|P5@!rV`ifd^%27J-$`l1I?_Uadnck3m6~-+~GI$oY`vL`8~8@~fihb~?DT9J)BxXK<(}@F|&Y zrX*6pj-Yx)TsPUSVMGbhT}u;-sAMi#>ET4{{BcnPnwM*iuzDO+ae|h@aK{Ph2+uDx zd)!ejmDL-|Kw_MF0zK8@5^?Q9C^Uq;2SlG^VD7QY6GurDvY=d04F&%+j{rQs7&6PK zS8D93UZ08Ou(A}4q$mz#uvk$ZpCG_)MHqGp)5_o_K?$iMNvst>Q4Gzj(JNy}!0=bY zxMGWo=Zp|*sa~fDB{i`44qp`4>Wmdz{Cu^L7sZX|Lv>(eyfVQj7kVNgDuXb{P(~d| z)AA`P@(8|4B_#-*R(V8#^%@VzndO}&MBGC{Z#Wj+(B9C4~(^+J~ z02YNjj87ixgQ%sMr2|aL(-93kb(BS5x4Gp!yHOFtib+akCXo!O0GTKntI@#*dPQR>oIEt2>MiQC~pv@uDHC@Dt^pH5F#l2l%mUJ)ga;?QlZB)iZqjpoN1 zoGhZ5O;M_uahfGVN@TZW@TTz;aI>57d?5yN*S zt5P*Wk;p+138VciUy6iBN{MIMBcnAcOC*b+NPsc%Nd zGje!NPoh0u&5;1Nm7sQ|B)EhYkxk9F)3g9+cm{Gb#{kK7g+?9;aD^pT8F)fUe2glA zuGjfhB9b8v2>0kdhejD8Ylegi`l4y1+5%j6Ts+1;Z zp?v_bgc9u*zg(-dCDM~z5E^jB+aZrFW{9FwsBVjj>tadBQl%qB$PqFGbdp2wktn?k zsM)f~BH(`V9JFZow253FJ%W=8f~V#2lOpL72(eg`q;UqnRtBVIpa~`U6c(91%FmBC zLrRuRh=akc5Jph4#gtgSl?PnO#3Z5&P_i+`1FsXt$;2T2ESuaThXP9i08FjUVoO!a z?a@?Qq?!vUlNdjui-F80FbXUZ7IZ)Wa-AkYrjNBN9jrvP6O4hJL+2#MrTVPk@(Q5D z%)pbGR3wD1LXoD`Y2>mTF%p>N3r3g`!%0OHsUjIwq((8YoEW1MI^)gIEJSZhVaxS; zrw$brqrglNB~TOMX>bzTOc78cRjElv8A(ox)u?20KQs%GxUFhqY^>SKb~9~6vMf;>xKT7Z!OS;Wgf6ux z$stw?4MYjl9B8a!6+e~lbBf~8eV3%A%S3!3pAWExL?o$%FtDBCaGN|bF_14(wM@29 zs6o*5lZpjJ5*!t{Ef6Z=5u9?c^M0*U5)W&v;xcV^pBZS0=!W8m4FXL>swE|f%akQX zNQ8Pqq5yGFMLH^EUyQL_t3wIAdV2yt*5@K5NPz+5pfCcWqvNNl{UWPTBjXzpR}{(4 zi_m)&%4mdYjU-0XBCSTb#}e;R$41IMG&*pwtPv?OaulE>@(?J+ppqF(SAv@0iPzX@ zWWSRL$#w|}@jXh3jt(QzHBz~mpm({!c$y7Hc?zmRj2a>0^%|JKQHC>P7)FDJ5kt{M zLVZgjo#9pkrPHM+u$5}6o4^)P#Z*ePm15$7nHR_s>?B1J(dADCZfz>vVgSifxhX=q zK&;bi2~xc#4tV2iw?rvQa?7Kkm`8$MLTNBsB7`vtF~e!K#m6Q&Z2^$wNfZ&-Vq1#S zhS-c=iQM5!(D<}AYou5ub=$y`W)YbP1J!bLvzeoS%8EE@Y_um*8c$UkxKx%NaJEqZ z6CA|x5)M&ei*N(Rk)j|-%1_ZzI2NesQ|stjL=nRWR-sH|0R{!1%hg25AWbc2GZIu* zmr3N3=$saj)#iv{DG)-eBEslT6@#nIQp;lH=+)ttMgeUAh3^Wn!c0h%#Ofn~?t-Z4 zrqoof61wQ{5@I-%SUvig5wn!TG}?#`JJI2l*bJ&zEn+5XNIFttN@@%zk{L-P0G(Qt zYDyKkv_`)o+C)-OeR{eXf;L2tRpWD*%}El1%>8k83~D|NJ$Kkr;HM#O{{Up^Wy{cj7dZ>5XBOW1S{08GW2L)2eE)-GlRzRIs67w zYJy&o0RA$(8T3>_h(5NDVz*jUk#Y-z$~Q!4X;P2bXf{!(TtX}fRo_&Fi7wTPwPuL_ z%3KC&5*lsx5xoq$OJH>q=pvp~U_#Z8%xM&mS=6|MBs$G!_b3TAF|_amkA(`nSt-da zlh{%TOeaO5Q28QRQju4wPIAQQbZmlJD2ue&1$I=R)fSXKmq3%+X-Z?H8B!n8Xn~t= zRwV?ee15heC0dbUW|;kaPGSPVlFC$2U7i>;(g;z18c*+ww8ayZ+!&sn!1c$|lT?AY zcnVbWxC}CrLlu`41K}nfU8%4OrFsj`s+GFf&11T{!hV7xq<83yjg~sKIxF%Mt2uet7a1PJyaWdkfsjf&G8)ywF zQ7L??SK)Ffzz)N1;>GFx4nBz}BeB>?iC%G{MSx~pOmsgJ^a77b())-8xja%JRL8|J zP$kNe5xfdXgab<5v{q$Qsu&nwGBqD{K7G+-kw9T*8J!#@LkRqTlg5%nB_=Rzz|-PD4syC74-`cm|(Hg;Et&f+baLj`I81evURpW>7{bsTPeoPOXoZsgvaKVkJRo zV%m-1%*QyRq{`GdFM(&#NSsi(sbEq$@gklB614EG$PrGDS!I-yB7kcsG|Dv!9o#(@ z_)%839uY%9Wg>!*IZzf%jG;y#5`_+GCw+*L>9P7{>PVNvM6~)emN;X)g6`wmfGL2A zv_=Tca)|LNvOkpz#({ulJXt=cg6FgaNb^32RAE;j@zE(vuOyPJrSlUJuT1GdlPJPy zGATk#q{Ttmy;PWF^(1oRO;(s(<_3nml}qz^CD04SDj_=POm3V_DTGQ)9$%FtNR3z0 zI4pZ)Txw)ogdA{z&=*CMh)q70J%R;c9tf_K)Ho9#-h>tz4LXO#mg?AKMS`9Wp#XwQWC5xr!!7f2oou_= zk{AV-gGxS_xk~fNya8IRiIYMzMOhUb)DEY}*%CX7D~vX~hG?ZYxk`e@A<-aoR0;CE zI)TfKhNOAX@NGGqcsnK51FQ~sK`epIWsuZVo5*eCr$(wZW^01N!Su$Y!fHWr9>W|N zOZRdpR;nS|Z;VHP#vmlPpPEyi~n4CW234vdBy^Q>ZrirD(jE>jZi-OabRh<#9BT zpKFmhp=8!=aZw0niHIl>DH7dA61v(kBqV6rW7km< zM9@7(F6G(d0?9K&44npJLU)uQ#X%DinK61R zpH1gTUGWSCg#fOImI4*Y0-ByeQt_1{fzx9oxa@4DP@V)K+QVfQo2&OY*`{r7eNke?YP(^wUQ@cNDL_gI=oRtfc6wm(tiA6%+F3WNoyS1w%Q$8qN6%X1CEW>k!i385RUMcZk)fFq?r~{(_ByuFl`luz3|(t}Nz`|1I4U z+g^dOMqs=*nV4g%QQl;Tu_n-P2@X-TIkOEy)hq#@Cs>-yHMXZhWGh}{hjs|>gbJo2 z!ie4gu6iXx1s-Uq7%@oLfwxhN@GTG`M$jfRFyR|c=Z`Lj7_u#llW1QNM0G>ETdDbiAOd;`9~ zsrWksSl&E(gd2~6$=8J+F|Q?nDKY361hneH5N7U3YxG_{4;19xALv-MLIghFmUyoG z7Y!A0AXGF|#AW!6LB-<4267_=*vyuk@Bjg(z~nOzbTT767lJ^@CwL$6O&Yv;|6uk@ z!BI45jDi8<^6;O0ABX`i=Ln&fr)C-#mC~ z@Dqf1zNjDz6-sDcO=9Vsz@{K^(2ZIAc!pgAA5Wo#G+WS-wW8)Z5H^BZQ3@LP3NdX& z^u5u?ct9h>4?qoIh`}pl!x!A)h5K_kT0Q@G)e;=)iv`?}a3Tf29A*+bV#{pT7@@0? z8;ez8h6dkOp#ilQ3u16HKX*%aBw%qd{OZ_4{6dzL6o&?63l+SgolN{PaHh%o26qZ1 zee&%Tp2ZI1#6hePU|i~*kdA;~|MjS^kWElrt5=dy-l};T8uM$xzuZ zj!?b|RZK2a5#stMHvq^5^@tsX{G!XOhE^Xz4Vin6&|w(@y94x@^=)>0oRS4MCu#4w& zG~Q02f}yPtseCn70<##oK0TO{oRm=EvseRGCXhNpv1-sIf2l-LaV1PmIo}_9N<~=|C~9%?ofz1z@xA6PK6WbQwX3Ug<7R>I5qYHkScd8 zpi5jjl0|tVOGNlwA?|4*k=KBJe9b{sB7(ABQN8P#Ev7tp9UZmulvmAv~FkY6&IeR^(x0KR1XqbeSpmk>$b&7AmR}hh>!rrIS=rA9iK&L|-CofQkUJ~?h;FRY) zo$mv^y%BjlcUhu}q)=AZe;kY#4YA+$O^ohu6tQ6%gNTsx+08ewZOO!N8UpP}p{|ht z?H#a~7OqF$;%$q;l#<-G&%u|Nvl`+flrC?$aMvHrN&)-~JeiAJ^3X{0xzRbH>2L(0 zqAvxQBSYbFIDuRQ27)ui8oS=4L0!OLpdq*w3h|ms(kZ85Qc!YcpMc~u`}9|7_6ukX z%4^UVknGQgHlXe*FTj6`^#X=l-sy$l)<<(qA4**M`?5kKAbqxQPWTZSl z(TPZa5*=(m6(bjuZ|9W)q7zQ%4G|a=7{y~m%Ulu@H}~j&oapp=V(Iw={vVh+blexJ z6N-+p;Zf~>4vk+4VFbzr6lg6E4sSX@Ktz= z!vWa+EX0O~kjhGe%;tfLJ{4LwYjQxMILB zIvCF@mN_n*i;v4!0W19~2yO@?AIA)X2(Lt471+-m^X^~l+W0clQ4^dt9yDl2|zQQ1lE8A+Jab6-4ot^p}+}(C8X>B=8i7;_$&d)qy!>? zLV;x^l8MB;763vubQmN_h2^He!sBU(kbNGo&S2!pR1$>-bJ{UY5W3Iv8gL9Mm7;x) z7g)V$Ni{~J-s*r35=B)^7N~5?r}t?Dh6biwp`~%pgKouu2!)GHj%=2IA;`bPz^@~d z$dHOhsmK8YUtoy~o>H0?8AFz@XOUBA@LwT|3`#!u6L>DP=TgoyAQ+`W0MJMtEOY@N zfMp_arH|qS6q*w$BpPTCDt4Pg#0TC1P#+aKG7-pB0+otKu0rMKdFPZS0m97Liv;MU zA!3Q4fmh+=(V$rnH~@6i6M$wFSPTpo02=V|2~eH}L#qJnkG?ccOC*fTRygWQ_Qepy-&oUIlBPfPqcohNwBn>))MyF6I1OV!Iup>tRXw+~L zl}?AA$uv3{2l}DwPX!G?16&BGkp>!q@;n1ls-1kuaRel?#Fjr~F^TjNau8p|>eCqE zuu61{V}P1(fXItAP+=w&;=x*{yYGE?2F{= zUj`^&u;2s&1)Mh;QqY(G+Zewz2I=tN{}7aa%Z>Mk@r7(}>}rn;VY{m!{>$K6Q!h?huCzD7FPMcBN*wlS#0AL`c2Ss3Dm( zT(Q%L2%34LG6E4d2DKoZCy>JFR5AgwbD+E-c~@A@7Mwl`kw{|zX%hWAsK!du;uj+t z7xcygc(6FO_7&t-7zi~ShPZ+|M2DmqBVSc0fkuWrD$I$(f3VvevQuF#X%Jtfz&?gn zaA+bnxDs!hX2w+1i?(XX!SbRrECsD{;RzKym{k(EEdQ!PER_cO8x#NsSdKJN-I>O1NJ7;A?rnf^a!;8Qlp^e z0fE3d$VX5xLexaD>~yL3!7%*sBGq3C3^g4xkSIG1sB8!wCj{g`Dhjx|V8g*t4!FxN zw^RgjI2q75B+!C?V|$`BZPV8pJu5*ojmuccMnnVq50oz?u3`KYfbD`-`Z=eRrZp`_ zQ0px-(j~asn30A?t3>dFfXfIpWD<>z*LY(J03u}s289Zu0Q@#8@Ldb2>cATy6e10w zLg_fMuxQzHPANsAf;Y!3T2S%UMoa;j)Tp2KTvLJnD>IV4Q%a_1?$33Y}>rmU_HSkN}mjU;*w70r|;oJCMjvJ3YXbM{XOm?1nfgDpL# zh&tv>nhu4DP$7YNVxf{uq+puAG)ZzXqBbvYjPi!^VVHs1;=y_)oXhR?lF87(fDBv%y0 z_XTnmqFlgD6j<%4hyObB?^dLFENSBxG!( z1!Rhfmx*A~hR?kU(PfZjA{Q16!}MDzQe}A7eZETNutJyxh0lt9!E`7b z0;1!f^J>|=+BB$D0@{?s<)Htesp4c^~E z-0Tw6m}tRjKp@{%jfux!FdYd!`!EH7@340|GM|owJUcCAQJ`;Q` zY_4}9p`2n9KZ*m-3NMp~*}a&-!=)B@H+V26#I1SW6!v^}zZ4WXQ7|nKV!(6VUDTuf z2TlvxjXq!mp;4GDU;`nhj@rOtG!6?7PP#ztBlgmw8sops9SsZX=b!)BKL7%F0anqj z6COu-OMw6xZ`g%zPsrt!kWqO)+NUD=b6 zFnFvcA0q}8=F&J!;>C*Sx%<6OB}1-e=~r^yJ9P*jo|#zTR}OR%G0wV`?#(V#4* zf32wCHu|j-m0}Q{iV%@74-pi_g^>aCL>%*wt(r8v zAq6xj4upktg!D##8V>J`U@lT}|H5#!JUjUSnFV(1m%0IrqFtwHF65UmOEKZ7W8$2vFNY zZEYyAU14|PwBgXC7YzBaJ9#hz0dq%+$1cV_&Cm6A_xvkU zDcIh|uM4AL@?P|9h+`JI*9VOV%QLC3juz|h<*yCJ|DVoGUZ|hr}f5;)$qTeC# zKvpc1kKUM)PYO*tRV}O^~1K z&iHp~0%{>~ea6296A-X3@=g^5t@%rM^8pl)-?r!IhY;O>dqlY^B@_?^t?J8^*AyQO zV1cs|)B*Tt3fxR0|4tnM<0SLv_HrU&IP7_A(E#2YG9;cFZBgq}^co->AdqNx=q+aW z%>wy1l*^!VI<1iQgI{^@N2_=0T*`1@D8K`|#nBNf`EbBP?ALHO9B#2|;Rrb9z+8ay zV5*fFJ)pLz(8rpf>x;fftygI63KRM(ypEWRzlqwe@aQeUZ4#ocoEk4$n-Y?5EPenM zF01z|lxUhE;FMU=slf2nI4voxmJ|-Wt-|HB1X&z`RA$~fW2`tiw16Hv^xVx{fVNN^ zfc%^i5J-vUh2qeFHFzK-I7`K|M4|a+Jcx^nZm8pqz6Y=6i$4|?wqgT)pvW^#-oR-@ zL=O!Po*&r2>*PX&u)tE|LoV{x$@~H;sw^(o;a%d@;!pY>^ z0&5JHm!@SYMy@3{dxBcHBGPqv(*MPF8UjUDg>JsQvViuj2;Gjr98fDX^b{4km7y(w z8APz?yo?2?406Ck&rKmwqV!4*9_Xsv*LJwrGd3oMaN(1DHxLtnV|N67m-C zD<-0)NzAY>_9AogUnRf2HfaMkf1aP06}H0Uu{6mVCjKvywf_iN?zM>)iI`8eu<+Ku zPmvW?1(nZU76G~bW%Rn&CSx$oB#-*S+wlHv87t-b3uiODNPqp8`FO8Q;2^b?N8n!8 zUgmj|QV7oQ8ov;M6GN0G*hMy&tiv?lXv0)G5JFN6dpBxv3TJ9Swh6)Er}oF;4DNu_%V<}cxO&ZOgQk? zqanh9XCO+ubtxFdj&~}YP`vg|J_^wsATckaJP7!t*AM}rV-e`mEg(4@&k*f_*Hs5P z-644L0FGh>+yShS^9YUys<)%DSqP!k+c`Dc&uf}j?03gMlNA;%7ZBxqB53a35x>!B zq85siObW=*L3#`^DePLkxnrP|7JUw}20QxUPbe);C!}x#3ErINloq=hEnz`l5Ykjx z<+9s>^`NpCE%soSdb?KHhKSPR(3bU~zqAeZTE;&jew*+wffPurKg z3tVDL*dPo*HVD>(#_5B4rQ9n2;Mc+{`f~&+c-smb2C>L{3=R}>OCa<9PELG*q(9s+ zObh}7_ZG;B4NBK@ivPCVX;M*!boSRn+2 z*dUAcPCVX;N8#e}GLrEhSG`2U2BC+Sxp6?kdB=3aeIYOdPsWdQRSP`rsdM7CF1m!t`VzRh3$xglL9mnz=;CgAm z1vo4i7<`wL%9SDqFw2wi*<~fAfkWJ@T#Q&^Ec&9~{ht;O1qWCCCkj!aUpF;hA1opv zUw134^-oB72%)g*G8zP(19ds2r^g2rH3UCWo&u44;*r}=25(@bGFn{F^{l9#Sh)?f z&~{UKI%J`WCbai`-X2)bYffKC8!UoSLC~Pb@k*AWYGu(Y<4y2G$E^kLLujAM*H-P^ zkpT7ax!uy}bm%!A5EQ(-5e2LB3Xw1(AsinpjhDutP3Uk@Ekz=RcbqPsh`sinA0hQW zs5ns7BqFqjM5|!nAz49ZAS$%hrwH--r=$Gr7O2}p+fkA@XeTt({-C??jff)>j*y|n z8vX-y_*fGfyw;jX4rd^_%^1jq_o!iDLK`ZcXcI2{cqtN53O+Y6ccdiOt5LaveixJ) zy{oA#wAwa!@HsV=Bp`g@?OWKKg7634FB>d-etd#~zM3Zqb=)EGma z&*>Oagzm~YuaKUTd5tBi5_r%=^-XFg0<>brQA?;jEJSPwrBH65Pz6=&dE_SOR{Xt! zTs*j3s;L}!5h8rp0RIFnPKOW$!bc~_rNCTOh>;^HcC^JZk`UJsBpPHH|7Oog3p~e5 zg~NFqsC*a}YqwLx-Yf1#$%i3J#kL4Ez{mxW`5z zVnlh|v2Hy-#i@#iw%D?c1zQ{hKVfc3G_mwLD0#u91|cX>EQNtf0)wtnk&6K?a};zw zxyu<9{RY7z_%8HN--Ur-js0-n1)6`6DL9sdf8P#QrchBV*y1-%qfkTA97#bN1|Vh) zB)mgABowZM3Tf$Hl+*g32(_Sg9XeLvKP2pS=LixED0bTr(*bR2A;*9D0Y(qwY;c$bx z3(_mK8(l7ANI9;Ab2-{S`K0^VTFA z$s5es^)iOEntVuoy=}VYP?xr4R*&0w{dnTZez&6;=cmMXN$>Q_rDndY?X4XRuJ_}2 z@ATJ$Gh;eU{ce_jNBdI^ENh$ge{^S5&x8H%9f|lh`il#_S9)(Le~|y2dOWStj&j|f zWiRVB;Nf|qFH6mjiJ7)(Xoa2gruC7Fmrh&sFr7n;Y2Gnu;mif{pW7whj;r6O(f)3g zqn?rdcXXEz{`3XeeEe_&cHOpd-yj?1O|n+O8m>M!NpSA=p6=5IK6{enzx&tuyW>+w zHJ|WX=T`f^yL01Ia-#tc{_O4VGNDZ?|2q8Eg$?U5r`f=!X=^+;!k20HR9mp`$-QGS z^&cFB+ax~t%cKoQ_&2T{Te-7Q+SNY~Xts>5)AiS;i>_uiA3w#i{^8cNkB7a#eqP;b zgFhmrWd5}BWV^6%xUG{P-Mu2Xa`30~Q+t{xj;PvTgy5U7-k(idKdD|u-vO+~^LN#& zZEv~q*7h-I?Z1-d`9;0ieD!$y|=M!^~^!tIH;5ZCaZ_`k~6_Uo;w+ZS&pS zRN?%Cv*V|=p5<+JM7{Kc=cMoAcDOII@5&A>?5)}VeQaBPnn%#$vvZccX_sdYd^)jw z)&FH4{Hf>pZH)&`N&HEE&5Rg)buifKNHw@|2nWNvqE~4`R5i&eu!J) z-+k?q&e=CNpTDwb!@WjB$G3ghpqi~VNjP16IilyNnk~=49n7k0bGO_nNZwvqiFCix zD)EbFe~xUtbpQH@hOQ|yeHUgtoN=I6np-?@`i=_gv$J+)ou8KM=M(weFMTz1?I~E2 zl+{-ju33AkX_9!8Y|Wn|8mRZp<(`}!wpp`d3STqT-m&A>>Yuewy7zmhgdeA@g{5Bl z?CE2{wWB{fuFV+U_RrpfvpZJoZ)G+acw^oDKC7QTx-w7nZO`cKZ z>Aho?-{-I^ScKl+`K^7XPwE_8AR}3x4w}>E+TkT%-<%;oQ}Kg!s+uuv@1>3E-6N*^ zljR@#FU^q+8K<5#=YEd5So2Al;UluUKFhwn&RV^GizY*_em%b1C-VpJ#@288?D45* z>Jz`XPHNj!v21v9kCilVP5XxpB(YIX>xS1mxl}VIVp7lHy{Cou&S;l@5;p6Cdpi>) zM{g}u`WUe%zubPR_m<>Jc7}4|hH{KkOR}h*>&F+I=y4~e!-XHN_2{wvRL0slUybPB z<8I~4Yn+$kEbm|3+Q1@Q(0BI%-$PO5FZgwzrR@5=Wpck;!>csz*6ZM+N0PCgR8=Goy!a#lKtfJ zceA@B#PN6|D%3B#k!m`6?!6mBt9P5wsH@*QyH>mRhK#yd-B|V!EaTce-5;K-#khA^ zwd}g)D{DrL2=BmU^IU)J|Ka2fV^bEB;Jzw-c=u59JmZn2b`bHMKOgFI#gyzBH+^$P zqpg|EM}I%Ekw0?xCs#VGKKp6swR^r3&S*BYeAP+($*s0$KfJx}PG*BcVc*r~wwM}~ zMY~G!nWq!2Cl)IDqOv{q)AcvN0b%I7Zm^adX3=g?E47eDA2ClYZaa;r;F&NXi2F_U}j>`{3(E z8=m@qv)^pl&368?B>$nI*xBVmS%s;n~ zDu1o+{^zh-8Iu;A-8!yTrgR7I$&d|{R$^hb54E@MpBg9t5n8wDc0y9`mZoDXb`5SY zCvoFAq`q)$#Z8;2saabxb{_0%`s3ty<%oN#arK7{Q*RPKtNC?jS>>}MVWC?5I04?{ z)a{=A1}&ZY@s>`eV`u$GKe;=WDc^ACcR`>2vF29$AJjco{Z{o3vlel_8+jw_>uR6X ze0Hr&-7$%tQ~g)o|2Vs5_txXrrQN^x*QuY^HW|37{IgBpZ{F4@?YAqQP1h%|tJSFe z73{p*{l?wUrPXOCxp_tiit0;7?Kz5_^%m{g7JqQgC#|a?_2-H;D=R*s)QWJAUUgwb zokv42|M6W~{{|Xn%N>czqmf-)2Is&*8;(2wh$arm_WlqzZ}f7@sgpg&I?tZndb{$Y z78?%V=%Aa_ZA81OagKAD6NfCVvq3ZF{_2afuB_YEWI!v?%uDMgUowoc2?i>6Sp?yG z&h_SXRo!7MuRg16wS9`l;yQ5);r96|vE3K;CdoI~YtxzcAbk#dq<_QN%~OVE?|b&u z#&S0d3s<*_=vrg;v~IJg!iLNTJ@(!_`K@K>)zO+eF%OU@9eBxH+41|4&H8_!&+sR+ zx;X#Zzdfz)wajat%e170y)O6PmUavD{ha}=>k_VI9&CT3Qri0W|6)AqbyWP5{O7f{ zigel1p=rOaPj14$sqZ)0)A&hsRh`&RfO!zgUVK$Fn`hdqqp04IN5nuH`>)zV{SFlE5~mCaL&fZ zvk4Vd<+hHeewy~%2;=&Ui%;sBXfzeL_WcSdW9mi6f3b ze){-^qsxe}4}^YE*Sq@{+&Dg}N!eBnBErfH+TQ5{(&P@UG6(SF6Q)Uj%sj=JwcT;{ zv%#B?3T4*a-rae<=F;)i%Ob8a_x_^ko3$z9%j?>(Js*cT1$rKq9MZconIb9xH* zy($|9Ww+e@v2VoUany<{$9I2vxOq9%jL!A9-Duj5U!7HE_QvU74f!Hr`j}K_7=N-G|rv9=iE5zV5Vg8SA)6R_B&h0toUh5hp~I6je5{@CHwUKt4Bx;-ap%F z%rnAAKikrK$5kuy>F|-|D%U-iIVxdV#_c+^u8}=jiKqikYiIYrVCuQ0v21yz(VA*= zD#dl$VUC|>{~EuY4rH)rD58R6SKA$ZZFBK^T_|m zy(aR~)bUTR9Y{*9^Qf)C+;i{(l>#~XedE8{PF?-v{cBa`?q6X_YdrbT_->CP3r-Wj(va`m7!88P%@;C|mYz#Coaypha2j$d!5v%dw`f-`43ur^Edp zUH-1mYAd>`SA;JRWTREwa*5)xTj-_l)$Gn>sdmu%N1?_K55Q-RRz#b@z9l=NEpozwwgO zQC%OK23~Bq>-wrD%We%myY7!w-6z_n3GNUM4kv%QqH?FT$d#MhH&*$)Q`kq+gz(DI ziTi7Co)W)pwrG0i@>yxTy=%68`uNx7OE}vS!ym3$_QV%vR$Mu8a!=SOqoy`0MwzWhd|2vpl^v<$syacE{`<)1k$au`K3ORu_UIqsd^C zQMw`Sc9u455CQSsKjB%|@zR1`s>j#YSQ5K*dg@-eg3#1*a;=YAr`oXALu*w;(iN?? zZW&YWzNkw?|6!|ZF^y}ScT0fZk$)@QKy4?Pa1YXC5YFn>4njCGqES8ovvsLux z-aQ#j>WiIXv*7gabC?~ZWoF*^X-K`bO+EA)jqHbNem$Z4_lgQZ0XE{B*-OP(UsvYqw>y>Gz>9FXt4G+rR-K`$IrSTW7v&ziL z^t4%X^CN?BZ|r1tMl1Pxsi|9fFWa#e*G8`xGMmlnS&o#^Y)9<;UiM>^9)6qrZKEGZ zNlO|n|084Sf&SFl`^N8Gd9zR7q(Lor>#I-g`{~7cip=C$<+g9$UAN!%mNWIYAJll# zU`*Ak>P<~zubmO@&FFIQp1gb3G^_CRxYd94dE`U--Ws(c;#AoWqmrW^{?Pi7(S3J9 z#N+TDKaKlk{Eb^}YhS2;ciXS+Qn`__$EJ-Ob^FqY{_pklypQbbHe_u^+QmN>n!0D2 z%O0hqMr^Hh&^vob!!ZLNw7Aja3f3r#;e7G)I7r!=n z!T7HxsT5@sh?Ud^__)`G)@nVlx5m?M>l9g?3)#Oa%ii5qzszjjpN4Vw#_w4=NHB2s z{Ry9UC~s?cf9a~oWDS4WS04G?v*FXSTXrA2sYVi#XsvfJtm3LQo3eLY8c=?F)g$BP z4axplzedrx$+g%ks#{0vA8z@{3j6j`UtZhu14?k%+5#~`*h~&S~q$h zyRmA`i8JG9n)iAeQLD%zM_%#Mc9fNRlo1~TPGvu zgt>m7Zt?LS)E+!!)O#(g6C+1Nd{D1r&524babVpR?Q5Uw)M7}>`ZHP_?RbAc4^|K2 z>5XE6oHb-{crDS`<vf z4adSho_ajJ)xa6wA2Tg(Q~$`0Pgh5cRc9uzDHm3zPP09YPM#gnXtBEcDH8Hsqv?I) z54q>JKi6b()3JNYht-stCvJF9Yjo|uPBq$UKcboDYo{4Ic*T~A#0Jk4%J)Aib0oFS z-~mr>RNKm+S6@3rEW5kx@yD4>1z$~=+O^GyQzx$NI7rK+-Bl+v4*Rx)wePUS*6Jfh z?{09uZ`}JI4rNl0-K;d=e8oo{YIOgm;~$>A>o?7~XZh^H1m%P3t+}f2YaQWTpJW#f zxM`WcP?a?_rtfk~(hm(rWS{T$sA}yaQwMS0-HlSou2%9gOnEi=V9TeaZ1; z@Wrz+2d6JM#;xC=?$(yQF0GMPS;p&P+rNCdDZND+@_ll{auYXfzfVQ* z;}s8PHQZBf-5)hS@=W|z@RV4-$^J3@x9y8rHhmCt^s#;)e75gNm+sq7c~z?xtL97Y zT^umIrToUi9>1Pg%^k=+CA!r9uTL4}pP1I(N~xbkTM(1ce4uaJ(&j@5-TE);x|}?= z(`Cx&9?Tva+xb`iZ_=U18?JSCS(uqKFEAm}HHr5g#k%BKdf&{x1NOuWzZo6@tFpGf zQ_gKztIw}UUpH|p=Z}Te*nhDG)cEDSrSGYhj$rNkyz?#Pd%t~C)zNy$t;mk$qrXo- zBG;ZBGqL>WPii|s?!R6~I!QYF*`}^-PmCL5oV_`t=J|?4S*=!^KT5A~*?ePoj}^8{ zO_)vCi#gkqGdc6cOh(;?bIWq)w!D|weR9tRD(dIX(`gOdUqjGgNX^^w7T+??q3P40czebDNrZI7=|);rbV z`gIQJlYac=dwx0Bsj~R{S=WX%J;b_H!(L|DHw&(42Mnk&B70o7y&qOF>gx9UV?}h* z41uo78d9r-bDhq!?phN1t!*t6x~|Mx5xHTkcXR`uH0 zr;{H`4_7uY&sm85KiD(&{%%jbCLM2?juAEL3Khu8F)ChGlu68>-K6}?S!o0h+k|yr-ZoB8}w};j8 z+?SNCjIqsi5$P?m>x!~Z>PLOLM!f5nbBh|L9qYGPtUfzoa%=bg;XfniI-QMcaB?(p zYvnJtEZf{>;FF_LqN=^8%F<;|RyQ_}I@q~?rQ5Z}dcw{!4G)&|KCC+Qet&L=1aEJB zcju}D*MF>dMd1Ik*@ROSjigB@tM(+SmyN3S@YF5d!!KL*UylN*nq^v!{(RZ?(GlNp z_GQO@P_I%JZQ|nU8RAse_TVk2YcA`VaeUPGUHfhMlC$MU$CR{tO^Bep`_>wg zN$ECJ${Vh)kho9(-RIfS=VqL1nfTH1`qq87x;#Nfb44wq%oS=d_w86Mbq#Mu;Yv)3|+dhN`*QHDUG8TbDLhT|M&s&I87bU%KmX%O4(`tXgk~ z^25&v!^-|ybFS)#N##>z>Hnkc{_YDJE3rqPV>iPleB7b#s&l>8`WK&S{nyB0=}V*! zzwCEiG}ZLmrb|Ot^_ti1;hGnuMjlH%QEuPyW&ZU-3(R2dX@E5oIUg_Ghr_wv=>x^jg*H!m`>py4I z9ZIgyCBi>RG z%TFxRbnLuI+0l1qbm^Y>(P4R&?IVxScP!~e?v$Av+1k2A>5Jyv{B`!#sgWD936~d-toNvY<1u^B_~(!9JGb1!zAFbDU4Hy# z8>+eeDdu8kvvD6YesA7p?yeK5dpr-CeDFWb@QQN=Y&_BK@fpR9`~Bw*NY6SlV&2W> z17nki*5h?BOGd2bKjlrH*JT=ibk~n}jn8&H?$%(yR|r_ffK+w+m`lD8@szc3-v)(w z)u+ds42=E#NLa0dBW1=R&Mj9vx1BY+4mE4qV)C#7UtO=bGvl7^r0b6U`rrv+SE(Zy zJ)K|Io82L0*au51C8am5HcEMGXxi7+MJ-#kTw_(PD?23fl=@M{tom2_>vs-XI_c>o zBC(ZXEwj-_G;z26o5Id7H`Kl}>{^q9gz|sxWR>y$9l4z#H~r>0Z8*iag(6pyDy22+>9^n)-np*!ykFTmz44r_ooB2cwSs?abRY3oUC(^C zWOtWH=kYD|ceEVHZ=CF|+O(YS&xalEamMq9?D%5#xkbqh1S!VP>YcM3_G??0dop=k zt>5PAyNscotipae;_fI=cb%)sbVBm5$hG#r?vL*AV~xY=il^>=K_U;Z{5bf)o!Wz0 z>F;G&+Oo^AKe))Hr-P42$A5oKJa1yF zzk1aEtbSQlS`(3UxNgCyCX*B9w;9?m+wcc>(u&zoC?>R!5K zHoroYs{9ROr(Kn^ru}q+dQexNLd+Q4^+DA$hr(Nl%UA2fE;ritzcnYqVTWjj#Iz}I zFt0zpxbDJ7+bm}W&0fmwB#-@E*SM|)*`2Yo(aoWs@7_B89HUJ)@!ln_F1lvCw87sG zqHD%1Z8;?N!B>m7rcaC3Rop+jeyX4@B`I@ zN03&d?vx9wIqXQ2R!H}2(>L}Xk?apz!^$gUth)WHAT|218jp~nt z)s}Lfj9gt|>pqLD!_XZyZag_N;(Yqa8fQk>M+LMIzYpk2RCM(?&W z8qOcP{$Tj$Su}6+iW@7=DX(vASqtk>^-3*puP*ezGjHFmKQ}*`(&xL1=cr{GjQf4s z&1!yKPjmC1F1If;y!!i*eJl1&KYhH#;L7D53hu6+%&XXL#UZ9xswy+Q*;aGf-O3MQ zx)9P%*J{_G!H`W|HTBEvY?M-WovY%~-x}>0el+vP2vzh4C#DZK4qUmUacpna+9T}! zar~#P9tn}Lv>D|b`+uK4znyL6VD@t6gY$JC_MF2i*K|OKt>4VmdYLcJ6q}H2kL$>c-+K`hkn}9U~JFd2dDjX^uV`g8$IA1k#SCM=(?&RcXrpC z6Vi@*?F%dI>e{!`Z%t4AnsK!9AJMJPjLbMReC)C%{(+CLt?aP$i&0g5BYxXB{cw*} z8O_gw)mpeHLr}eD<u=zT32H z*Rd`S?;J}sEm?MJ^NF%Y=T`5hDx>$f&y{~D=#&0uYQ4{OE0@1tH}Ph}YHj8x%unpq zy?vW=ohmFKOkA<`@gG~yXEeSn_-XaX(MRsLA0zvIi0RaCtPIH5t?fBiHR<;CK^uQf z-%>p`rm^O6xAbL^fKd}76v@reW!p56OYww@`{J;h7l!xJ2B-(xnEqwgf++Yaq_yno~FkVcUW`1NjwYI}LeqaM{R{(Rxndbc`W--6l7 z+r6@;-DIvkbTjR@hV8@TI~v*ROL+HhgWBRWxmHazw(fMD2jS#%ooYp9l0EHf zPS#bFtcY5AVB7y{wU%s{%CXHq(RJ^jJx6{V?cbM>O1P}H44{+oVRIH)j|JH5lsM-|zeA*um^UzuXeWN|fY ztf+47`WZFgu0`^Ib@@$s;YRgSic?sI11h6xS7?|ik{hm}8`Qmf{vc3Ha0VJoJLS+S{U z;+7S9ZVj+pvhEXO7(qT_ZQRZHb^i3e>&betjYiH`&T5TLqfVnGeSh98wnAS zk_HiJMQPZiTe?$1K#`V)At4PC(lBClj~Ih7?$hh~em>XzJFee-?2q%G9ox=x?^i#b zFOdEi{;UhR;pxdr{wUS4@;KYx9l5A?-bDLxzG@kSWj4FBshlh(j4D`sv}WsR2T>2j zg{{@#Lm&T`Cyk4lT7;yG2ZjF~sSUHpIiLbo`ZiV-n`rMDF;lNAwJkpDVI3P! zAebFQ^x59nnBxn0XF@R;--p=qRD6>9@JSj|0esUff|J(x*;LI1L0Ok{-@()4UFrXh z<_D3e_Bx+@63@W2QRf9$$)`Wg7=ArW&E^oqjgFyTVKLUW3ZzD+c`^OE>JYZ-)yJyI zlM50hbXrH8o=pKJK1V>n`iv21?Ye7kZ^F;Twaiw*=SMp2%8St#w`>=Na7g5R2x>ms z(0%BWe^*!iZ|BL}Gw%3cGsnJn_7tzqrzK0kkYV2o@V1gmQZ55$XZiMAT3FEI`c-t3 z4i@zCkdS;UZo6yShygq{x~xUp0?g3i(gZmFMtS2y?(w(tEY~(11VLfPl5J{~8u)=9 zy3VMUZueCFZR_&lM6xLeE{}6_;4oxs3IInv^mQkR!>fKZdA9UyCC#Q4mWADgpR{@6 zjn$48e$01PfpN1PW!uVd-PzfW-J(L+C8OUAmZhqs(kT`qDK!!K!C;;fUp2aK22gNf% z)S!W@bF25`l8HH>!T#J9zKBStzQR~(mK@zVW@~Y_o~lljzdrbY$niuGaTnEioKPrQ z1PzY(VXbf>Cz%XGWch{=z9sDp#>4-X9J@(}egd>2dR-VIvSL;RXwic|Dr~Z0$EL}} z71av(l%bh|bH?e4KCgF)JVevy_J2WKW){D%%=Zn4R|7+#E5cmL!vKeql>_5d@g>E0 zt@Ga+OV;U&4%Ub7pD;FPFFVnR8!vn@J8c0H#PPQV0j`;;{+qS`)vk$5f|W7pyq7kgv{>!W#fv?w)*a6*E3jret< zXrDZBx8Mkk!fqt26Pd8SDQXPgkgN z-p4ueGpXZKLb{Lc<1DMTl|s%4Fd9FvYJKf8{~>EMX1%@Iw%6A~M^>3>9G|`64Sa0i zH&E=9foTcQqqiZY!`qU)EiLPhaxD=&XyQ+Zw00J}#{qXtr~9EY$m!Vkg9VJzo*1&K zqS4RfY~~T>msB=36P4=Vx0E{s#S8&5A+&c*Jolb8oJtCA_0$?8D);p}&neAVHv;-S zgd?Mo3yYssNgfcji-&QFRT0!vj^6L7mRR!JGv*W|i>5e@o0N>E z3^B6a3&NRxS$?d`@wZ)HY+1rA9#*tisK8SmlQrt?G7GV!0LGwy2f+=%HR(;;dvap! zm^JUX@$lN{F!AT;uCVeC-qG5!|D@q?lYl=g~Uv4NB$@U zD#HBp#X5sXI9L84%5;fIPFomu!Nlj{*>o*o?=xhMK9|e1@ z&!#QKAMj*n4-`oVsj}G-zP-hS`?iMQCm%Yi=IieeV7?E0M+9>N(5L;~K#_LTLuW}6 z&}LEkce<&G-M|~TBmr;Uk$w&2$yWZJ82LK6R>J`2N4Ykx@((XV}M!f+M*kh_bIvqOzn$nt=$OwlTq z9U`?nJU49_z-MIPo;#E$$#Zo3$L?ejyK-Jq*QZDP+uDMr%_^A^6)S#FfJ!O0UIV!! z#(D<~rWdTpmKMdgH$&QvJFXdh1FjMBo4;Duqad3DjFoL%@Ec^qq|H~6!5%sJhAHk<8`yo5ed2%?g7e^dDK z-YaAp@_c9Rr}Qn?3+ck*F40~doIs0jga|1dRUMLLB+;*1hDgcLZ%R z6QQJmKeEJLt)*)BfZ6xvSQpGThI08-Q4t#RH~ZYNar_L%MGR|_1Ko5}0}qq%`Ijr( z^Abg*ocb*%YfIl0x}29YxU1!{SoB2-;G2OZ7u=01lrUGx{W$lpB;69uvL730YDF7< zUk?_wvTA$XaJomcey#!k~L2xlYy_5yh ze3g4k40GK}!{K?5J?7BgXE~u{bun@O${PWui(@|doV`@i!sPv%9l0`7Nv$b=kM1e~ zR;D2-Inju|#3F~N zOznpa+y7#%51nV&{z9($2jxx`%{%-Klcfn}?)}`IQ$%C~R(?3)1TV^s$NXsD4Lo#R zNdM4Gw3v?QfkSWF%zU?tk!x}CpbVvpdDoWxhdwKzbci%d$gv2r7C@l}>KrBz)x9i( z$7cZBDU91Czh5`edf5D7n}aDcng0r4*Fvd3x;3uggZlx-)C?eixx-nSZB4aLYn>NI zGsM*`AZWWL0LN)n=6Wi%PJ`ZWfKv^;1h_W4p>)ylDr@X7vAg;QA$L=?=q#bvXYM;? zB?ABz#Ck~t!(M&^JdqszXyX9@8>UimKX2${+V46>TEW1U?XAnUc7v&;ep>Ao_VZNN zJ3k3n1vhj3Tt8v5-*ysNn4fNqaf(!K=0PFL*9$7px4#(d2?P9%Ye&BuRa&Hif4gpX z0n{|Ms{g`bb5p#V4`E&n0Ek5sPrqb8kr!ljjXCghp~WoK7He%D(00GLCvR{~u$B}J zZZ`({Tl!$9x=87RMoxoSl9Z>e=cZ+ESRtVr23cfy@fQDjpKb-V#kcJOQ^i@0RT*>v zS7+W*p9jaNME%_w6z>%&E!uoO<|OGRn68NbK#gb9T{=n?b(<*+lOyi*rOstmh2N-* zAEtZ5^P&B@hqXlljJFasV;h(J>MB>-HCdgd)yTEYsp_=FSwVArQU!4E3iUMUpsp7awRXlLedh%2X0443<0jRUY5aYiHq-}1w<1S>iJJNkZN7Bc`a;6`?}P~-sKMmB#!&w z-l&oqit3{uqt!0k09iR=fb{ANAzI?lf+v(g#5gwuPvJyC4h z;3@_Xp;Bl>l77OUXATHMSWj2*oO+G-EKYHOPB@M_`1wEbfmODuIi{of9;xN;x|M5o z3!8bGgL1{|A1xwT%g^WicJ0P@cZ;sadizW{dqaN7lc1%~sS7dti{>xuWS+?}paKl% zU>OvopKF%$W9lE z3Gc&z^Q6H`%iVz7a#{bIMfXGVhQ5zZZmEHi3#raxzIhz+n}i{-oz)Ho~iLlr! zHvo2xo;H^;r^{MyP6C) zw=R0G#V(!c%AO?~#TEG=64ZUaI=?N(30lgOAKdwb}bu(JU~_)Z!9&&bvfhfC(qv<)gP7X7ee>a6?MA@m>j zI-c=-7YEB?!@Qf9gNS9|fyoVb!I*A|9om>6>fqxtGGr9gv zz*fzmaP+np1=DbrBx;VU@oaB)LO&D^;Lt3d247z!7+LtJvUo4w-UiT2qqJmF95}dA z7|kdE=j|w?i#U>8@>X^QQ2tS)XZ?ul3rI z3}fzhy3=M`9lKf^O$R5>VriOsi(;%5UDNg~$-hs9f)_&-FKz^6ZARJRJZc~Gqm((&~Iq_v6 z^tvKh8eev+`1(Ana=;)h+wGU)_IQm4qd5E<7Yu_bd~0Q%RUh8hQYb$f)g!$>Dqp14 z>-oC9^=amVMfJ>swn{qXi_tQeA1n@y^mAkR)Py*!glQ+Tf*_m?iyvYqOHE9L8!y~v z-EQt6es|4XCBpP?(mC4vSa^~nKQKx-@I$Yq{z%tV_{L_6tp-<*SH06eluE?_Z4^qe zSwze0{pRuWWlsyN{M9MvVWuQ$83@@(g6A&6e>D0tlj5R{Su>y?)eYgoGN(8kV4s z6mi1_&p3CGF! zQMs!jPU(KuSBrq{?S*o&eFsSMU!2P9$n?4z)rF@a>Hh72gvDYhBmZ+{Cjf>zCF9LBbb2Vk0Hd z+-}-CKko*eRJ0rne9ruk0;4GT^VQ%)z9L>O z7He9zZ8l$a8qunc#@z%nHBZ|}S!8Aes8RZKshDD>Bp%(7FPP$7HpQbjz)>!?u-pIy zu@a3wz6R-lRX=YuWw(6NOAT+NT3Zq-fm0pdhWv>(q!Is28l5W-ZCBrVP9C2`q2C&@ z=q~;)yaQjo(-ilQ5Q5QTv^%HuL~>i55y4w@vo%&|_cI8OCFAy3C=CCHbi|{oYe4KK zvr58|{y3kc0vI~oT_v=^TNUK3q&R!HcgKaB7f#VTi30RzYeG8;_=?UGQ^u`7Tl4;{ZX_Z!CM=lJBli+^LNs z5sp-8HsC|f0vf8`ZciWP0IIq`tck4@LA(c{3={NiMexK?v_5 z;bp)QU3^Xaq9TL{y<2~8&g0qr3(%wAMjvI_rAwXW_@XmTMNbK=FXOgQZ_6KQvJST- zHNVylg8jBs3R`tUgt{lvEmd0Ge+9*&?Q_pe5qNi?xms9bja!y52=QLfT)3t5YwgfH zaZoU3J*O8(Za>6}|B#1v#n>1j-6HZ+x=(m(8KvkmIs30lGTxL>CERaW>S4JOP<|pp z!uh$cw@~s)*l$6+h#f1%@x~26^sI2|aIs+(FxP zj@Fc9v;bb}IhpHNcUCwl)V_}0PrQqrD)lQIZQs{h2p^<9$iK0p>vICjgS#wP`FcGL za?fH;Mt3+_TT!3V)WU5)q2#>!E&V=Q&Jf72yN!;h_j|$pxlwW#joAT9Jtm_*r=PD7 z2lH<6pK=}#I=RInw~it$STF6Sd#dOGgB5T*htS&Bg<_49PoM#+=dBuC~lwxrc{xc!P@Ffj?o;3!7` zGfz^a2WV+|7(p3q6)qE|5qt0aHq}Qbb`{Y+y~(s9f^FhzVj?=4`Ea7w^Yt#ZlLowY zd42~{aSI^$1pzLOTF#0(aN>6Gpw@|+a?e}~W#ZJaYH7E}32{2^cT-2>Tg4ue?9{t1 zHV4k6@#+7{qEPnEf7nCrV{N)lk9!Z7)}e9z^(vXve1R(Qp^u_RG?d~zs8v~;fB~zq zbSzF%K*&K+Fj={nAdCQe40huE>Li_By&3}`8>fhTW1rCFdIb2c1kAtiYvJ(fVSH_A zm4iNg2*r+4-x~}o>rb}rjs$x6#eGzbM$ob3wAz)33c*D?kQy#|RL@yb04DGbNuSI! zKw0_8W>I&(`XX`K_-|?u?-#$}sfP!Bt#}&=PpnF%Ip39xpk(rfLHueI{2}j-tFL{@Z@4)LQ@r395`fK-q?zGUajd< z-BfMEx@iXsg^h!sd(p2^|6;8JsvZHus|eR#!KZ6!g6%aL9e&APGy^uYns30HIbOLa z>1%>+nQJ^^lh#5ZAOVXL{&m^%Z+BG_cPjnP(!;FaB{N3!2&4O0Q^}LyuJd?KVJ)m+ zTqTPoXD!G%kta7m_32(t(;6rj0Q(OgHwMmm?Di*slDp3&7x~r&UgeISoc?BaA0)kl zcuB1pSVdYPBxy}Y<~*e^kU>El;@a_4x+$yV3-d{jiY~V^Y05qZ{eIZLESFA~UMm&D zjjP(*W$JhQDbkP0CFhf~KoS(qC!ig|4b{r>L03*}_(eH5IT=lt6$wDn8J|q+CyD>|0a~m5NSX1Ry_Dp9Ha_Y?)XrUq_B>v+)PNmdREb_8XugVG zkV}D0|EZ~Kh3zWYarb8RcrT1SwvW!yt3FEk`HawBQRrQ&Rv_F~I8|fFkaTcG((upp zg@OUrCzKhV8Y#9Y}rOuo>$;TH}`5eO1e`8lNP znaqSCrqA-|M>`8~I2&@>Wvv<+VtJJ!;hgcNix%$v*Tj~4l_FyMoromolDMr+e8_hs z2~DU!$j`SN6JQv}c?DB}L9BdU;b`dFI`-#VN!tWlN#=P!3AU$QBFJgYy^R!};r|g` z?;btse-mvmlJ7;Fxbi0H9~NL6edZ^qf@iG*&sD{KiPpwg7nBs$S+hD{*P62NRz_}w zLuM|CuOWc75xXOjdQ6Z*IHo{;({@ffX{7w6*#!@09!yI3im?DM1?+jT67F|MPOHPt zrpI$4M?L{nz=pXLUPO{Q;I{9{R2>h^>it}mFs_cLqM2B@d}?uK+SND6VokQQ053rD6*$VN>SHni=j75}`Dd4E4V$j_v(JR%PpgsXg+I3m z{^{K++@<(<8j6Xnx6ku`;o5w_KiiOOCd@_XmiW!zdt z4soDhMWv+WO03)`$(VN}$Z)FMhb&Mcuf5=X<FynN}*Y!C*HS zu?B7*^lak}OTmz?Df$jq#3*c2QLe!9?r9>^h-ki2(!jJyp6!b|yi0+_YnN(?MDRy2 z_A!0as2R{xQphhNRmLWQ93>eE$nnUdXb2~PxYj|f78EI*q_4!Lpz`(^qO)Aa3lH-p)%~D&jEh z$<9O=A}*3Ml@L8B8{*NCu0ll|KgwqQ3@Q4Ki|aPEqE_QOA-K3=U7lj5!c#q3jrT8H zwOE#GuPdb1-wJHRtm)=8avED`pCp_#X=c2GvxpvqM+||P>-5)a)^r4By z;92hO{u8n;>+)reeOez!dB``u^tb&%6cNxMq^PtaPb=RiG7oPafV07S8s0C!2lpn^ zrRF&=XM3#Y{fq?xY#kz}E>EmzzZ=a=+AS2$r25V^AS@II=}i8GYl!IZ?l;WYiATjx zN%kohrUyHBa56%Z^WE{=OpVP>cTsG=f~vk)@C7e=D9-X0azkCNC)9D*@7atTn$sn- z`uAKCzj6c&%38s=5z&S_vbPi%(NMi`ed*X|+3@{{ zs22*rudep-s$z?HNo(LV6Krx)17B@>dZWZ_i%4nDI}Wvk-TM}BwB$K2$_4&aL8SqW zun<{(Pb>N}HdM=#hQcx<=ZPSQQn){MjaeXW*5dhP_`d;*1J|%zD{cR^sO(%jc1KI9 z+El%4sl4$+bCdtL?$zmm0dh212)WV1I+(yL=C$#w_EjIeoyQ{q{OePK<(CnOYHx8b zbff3WY`}V(7d(+j9&^xh(Iao&qf|^Dp3!jqRQim`x9Yt zJM==e5UX>t0woqg z4|XR+-d17L)JTi@_{Pd6?q%|K@`rMQNp3CN)MtX-0^O|CDFBakm-|3D1;=Ly!FZ4I z>rdltHR=1f^sm^G1VFRS;VOE+4tYt*HF|xWdBf!t>Xgl8MZY6W$={ zdIVN(nboA7F2Ih#osW*R`^a9zUZinD`@>^RwHcn3DrYN`98tSdy61%w=f?TQHiuP_ zb>{Ye0D|qETZ`^3K+)P9O5Yuq9<%1hTgBF{H`}5%H%a~qe@9U%@FS-kv7;9dFhxq1 z*iHqd?g>=J)1+cl?Y7d~2u0=u@yl-UT>)BFpRcbYv~qjwyEWCuwC_{gr#NP!r~l3r z1A=}hSEpvKp3CFb+e#}3A5FNd)z#+9;HBIvz?BcFi}ip-gBx*w5P5Pox)1>v`Iph6 zfN_-K`0vz(beLkh7VEl~{57*n$2nf4RfZsXumWd}$u3ZvYme}*cAs7{cFNxPmURNo z^C&C<>uWlqYxDBQul1;$w}{`2o)S}3pU(bQE=V!IR0+4O<{)(Hb5Vll`;KuGJr) z87F_Stl*E6-XE5v*y zyZ}t<$U3&4j-qu5!c!Wrf0xB@=a{6*Mllb?6(T}>OE6i)^L;0M)Y3op3|oTkcCK_2{?$K#YzXQBL0>>V#=wd@ANNHXNyijzf^@!PFib5B?TY?p;Lx8{D2SsVKJhKFZGt}mU zf;K%SLBWxNNrK6c(grp&HZ#2~1y=xjaOuO-VC$0xjc6OPk=Yb8?te`64tZ32*9@eh z?b}B;zzEW1qM?=D=JI4wp`->8>Jmy%J}|Qf?tYyd2v?R!MPCGQVxs$;@}k)~82zds z`uXe+V5Z???>_3Vi3#skTqH*K<0cSsC&^DLSOp=kexwOmU^~TAp+V_~rzU@v zYYcmoS!5e~h>mGhLQo8*xGUDpihT}KPQZ=CkGx-m34O!qrv1@}Hr)JkA8>Eg2J9bz z>S>2EiXwqRU4|GQs|H-NRL5NPv_4>-uUS$x{F1?j@_Q+2JH~0h_gR8 zu8Z)1{yl#nw&P><79nONUFZEy8g70rHWvbqZ$Qg~JlJ1y3laemDUr1uE7B7bOyY)a ziy!0dWH%Pn@x5J>rP>$2;EraV6m7>Hq423j_H@#(7ehZo!}E(qBMnB34{4LrAlDWY zQ$?y4>>PS*rf?)D^cp$f$1{fcP0)y?+K|*ZiIw(mUL%zrteE;~(=``!YNO15QB--o#wQK-m zi?;XS+@QUDU)!MqUvO4A281~;=87YN1D<}n-s$heJJA_}i-FGFHhh#KXZGA4_Ft$^Ynh6!-o>T=&DH5xpVgaZUYfO5V4cjIcaxd(1tkOo#~K~9p80a7 z^MTV)aM85YFL)=L{ef4K@d4*9AWMk!tQL<6(rW;bx1N6Pf{5Uh?wdb^W)@;{q?!1W zAeR;(EGBKzZAPOX{+p$M?%;qh|5Eij`tHmRB~|RfK}w@^GAq?BZsQM_wHL|Ee<=Co zlN+4*)T#$kEhWR=^XC>i@ZyBx1ujVWr8BxgX@OL-h7z4?dm^v-FTi` zaPd<;FLh${F?e^5hsE!iE6gFEDIi9wV?Sr;&cX|{>CDT74M};*BmEnGbXJ~3!RSb! zf@>noaFO6RI*3H#(R|V$n!v?-f1iUhynT_=muNO9iuuoRJiBsh4viz;oxsH&uwH!a zE^ptnlG+y4ze1t^?7BeG1{&;6#O_F*i|h5BKf-FnwU!515lMZ8nmiF$h5k;=damXh z7USm~J9KSb%k)7*8oj)BY(h{G#%Cvn0B^UST?&lf)SL{vQA!=<2Nx^#Xd)-b;r)p{ z(M9|0;r-IAF~f6b_R3;aCvk_4Q(uLmu_nCKupBGTssr{zsLa#MhBxbW({Y%^63D&U zd8DP(dfiR`irVb_T1Zk)9Oilr#W&t!&tuZ=T=ro8=9a@`V;M&3%nR)__o6VOf}2wv zdQb)t<%V{7hg%d9zT$Y+-3Jvo$Y_&)jx=g3RA4{)yS;{|@IA8Szj4=p>X`p&_8Act zF}iy;=^?_Zfzvy%LLhN60xo^lP+AA8DNp{c_uyy>O6Qhz99N!jueRQY{WA!26h8UY zoM))8rs4@u{|8#~=q82}z=h%~z8QT_Zi{`4Y8+Wa6lh)f*;6(?^c)IDBG$&dfxO-l<)Zij`;?=zM5@QyA^Pj-Htlrt1H8V z0T5#5x4lKexw^-~{;@FcEfSw)76xGWx*^iCJ8bRg#hv{fEFae=0FKlXR*wNkI4`hm zP{=3z(h)1tl1!)_9Tgea+3RmViix0<$@+btNM3k1%mEq|gBG!|kqSr6BJ#d?(SmT# zd0+ciAwIo*0IZMtGB?r6|NmlED%h&VnNI74ekr;^$jxhgQ_Lin#e7gX)3xnS#c`J1 ze?$-LpaD%%H%0x_Zc)4Y=$*LCJGuf0O{~Nif?|dNiK>|AK+beg*7}(gnU0cBw<`^O zKC&UhebBw9PAR&JW5eOn7ooRpf?FkJZ*hN8BZ<*U&44jeOeMQQ_eFTp|YzuM|8oUjS*2c~<)lI8uYp;<=?M^tvxRM{@9T+t+Vf(6S*_lfJOAvT|IY%IvkI)M`m38KtAbi(u~>@94~v>r3H+iJmd zT>3Ma?=G)Ysvv%(ae`<<^*FNLa!NQwet0a`6;j_vaW9vS1U9&D*7%t<88hrsClT-; z67K)LAQ=MxZo~stXT92^TSH`3@DCC-(qY_4&K$mxK z+t2s4_A-8~Sa-Gu&tY6lU#Pu$$opHP7nWg>ob8|sMSO&w_4%U6>;48SNctlV5c z>^Ljpw1tf$OEOaC#{CPN<-OU)C^pTG3dSsL*LQ5LGESn4nIPwIBa74c{+I!|oyM@C z(B>`m=a5($M^(GcXhHma0rPJdiLnh5p92&SM%Z53zH_RdKv5%=XhI|H75X7E|LV=IZecJ$a#MLtoNXK zr(%;Hs2kbdy*!K{LQy8{NN7idPly$Di88n=X!XDA$cmn;qT>)d`l|5>&@PkbiU@O% zlk21fpyuE8ZrZ9omF3fUx|3v0M!c|6Gm%>LOJ5Px1V(DeZX@Is?lXX$e@k z>>MQ%>t%IgO|b^ibOUh9xRkct$@tAYf0=_b-$0J4Z){Z_Eq!0lG)U{ zj_TD}qxy(PBg%~v7&J>%h!U>P>7-f%!cJvGIT;fMQGovLLwiH!ThiAPVS<*R@n(}u zueS@Ox}FzhtY|+~*aM$6iG&2!FMi>pP4({z`#yi4XvM@_YhKIh$@9fbA2zA0Xx@w4 z`-G@u8GS*|Y75QFcwxQ%!L&~&Nd_|r>K4tYqPH8v}FW{BM_l|-)HDNF_#LiFRv(l~+* zNymZi*;H8y5YTz8O=n{NqOF4R3bi(Bn*_`Gq@C0c>#i7dUsuIu79tK0mX9AERPsZ; z!sn*M{+Gk;a1B+6o^mOA*GpY=zBHW3k80qwNZt7HEi*Vg4CDa=Ce1V;+$ooVBQk&e zd09#gJTzl$_N=!x;c~>n2Xht3)t?ZXN8HLR(8m+KfTU(ZhcL1l6rwV(EQUC(RdM_? zas&vAv5X1&zN)Rka6ovpPd3E$i4_Vm=QkjEG&$k#|AOEQwfJ*B`W_{p?eSu-9Vy@1ze@e`rFeGJdOn6!_*uN==qM?2IyJOw_S`8Q)Dsms zWR_l5f5r)g=5dU#96bP=b*F>JYkNp?Wwj8?sScm};7`?6Um-_9WXB;Sv#_Si4-oVV zMIYBp_Dg~NVuYJw8Ts(P4WNI|FfWdDY{$lMRsCIH)%;iKbMLaC98X?vHicXogL{Ewu#w)vI) z9lWs1g8N#Fx1V?OieC4@#}3sI3*wyr?b@+>Mf-zbHAJRB7az2;l?(8G_Y+zU zhT~7bBTulxmMjUHDakZT4kdglM7(Iz2!5^Fum9_`M=8kQhLJJzgIgul=JI^o4~rS* z>jzRZU<2nK-&&JGq6{mzdv*!J!@SX#Cw6`D;zer1QGszwH9p^z$tuNQHv)sHveL$^0p@X$)bu%pdGkSbRh{)V*kY z0#v@_wLKQ(xFa0b_e1iv#!X;`iXb~jvqzLhudS+upI^BANG?Od#Fa|xGqS6LG^)hTR*7=wU8U2-s{3c-yG6>0BZ$|1D?J$lE8I&r5@A)wPFM?0 zAO&|_HK|CtFY%Q@$vfPAhC6(hUiBR%!rd`SL6|Mx^-E*VcRQ0^5+IEwL zW~v}Jr&?^vlndF?cJ|HXAeYp6U$8dQ%ww@_)U4=)^mi{w^j=b&_QJHayL;Y*vb^7) zfqOMx*Zl7OX)MU`BQIrm+EAz)87nBw(*KhT=AzbphhdW|NoC*w$f3=vm5RLLA~0A} zm2-a1@$E+ma~|T_aDEm(X{=TP-U;XPk_vix4HU%263YEceY`cjeba*X%gtc?$fC*| zYc?pvyRn1U)08>gnh+i#bM;E)z>nAbpjl{G@Jr-^>?7q*4|a*p7+-6QjyNC}B{>3g zN8>?$(c2~BMK3)PuxYA)(~akqiecIBAz^zzj8q_4J`T55&=QLElTO;#KhN>=KrcEd zd5tu?w9z=79l(9R#If!uWgM5Dt=9c!`K*oU|a50@Oh4Of1B)u?I5 z?6q9^cC7aJO$P5Y{H@Z3HkY^EQ+Mwl>`$i{fQ#VEIwiyJX0{Pg{Lf3Cx)k1bWh32@ zL?(BovQ=2Z+9TskWPXu8<-0pwnG~>Nl=6Yv&1z?;hbT0cmk@F2S<4xi zbIZYSpt&|bv{Bv!nO4-`Od0p$`Y1R8BPGERCXXt2mP%+t^~bM0j?VTpd}?s?$Ec{k z&#RS`ejF7u^o+dJ->umKQNqfR=qd+yyCG?E|H$qq9TD^3?iynyslh#O;1s2Mm*v@QzqeID4pgmu9)BXoOK8a{ZeQ$>3ek!CMz) zlIb*GCJiIW6NSf0S`Xg*Rv<4PY?u?cAYXDM^EI_2^Pe}#y6mOdez%aI*59sHbYQ|E z6ds|?z$>max;?^7mh!ElNw1=1`%?(AU7YTa1l=M&`p54c zKuBAGxuGXGuLJ&78vS39#V1%nwD9A;4XZ)nNi;(jv>j z?cWDCfnm9bL7(D(qQc>ib0xVKkCO%6y~i|lg<8GG_)Y4abLbp#){h46Z7hEm^J7?l z`~9ZRD!D5IQNjPG3?a*ppj z5hWF>RY(#RQ#64myQ{^@UnW%+y_*O~6yBgkroPF{}C!6r~omsUMn<5Bc=V zG(VZS9K-BR$?d&1Lu^dEL*{(RgHD z_U0-4^6j4FYbQuy5#{58eJpaiu1su0i~91j!TB>PfM`j&zHcZVE?A-a2yutuITGdD zw36DASiuN93f>69WMM!}qgYNiobqbt_nciphE55sxaogOCE z7&vM6%MSM8*9JgWCiCoiFtcK-`wfWS%GaX9!Gb%S?v#PUYUmcwll8;arrP4&>hLVQ zP*o0txO)yxL9j3PhBM|#s5?AX%Q&>;Qob5|8{Dd<9$K+HOXC02g@OyAmOP@(+Hdx%WKo$gl11((*tEMozK~K@|xn&+fJNI5OYWtrq%?`%OUiVg_q89%92dFGn?f+ zuZIJw{>fW^$@@$dy+3VPR2s?HZdrQ=F;qL6w$^e!r1z;O8Y}A4I@?{5^QN;_F!egC zAzpa#sYrO1d8Ws{AE=FZR7zsEqoJM0GXX5em?ZRl(-LBO|AC{RI`f>;C-Ly#q$g4# z2N#9p3H>k(7fd_HiA-EP&?QNP^eP_rjjz^c#STtriB1-6WA~pr2Yq-a2H5@Fp0|6J zQN=5l@o2A3emUcHNz5t(FNM;rRoG9` zG5!tGH{iB9n+Xz?7kVPQ>a`Mt=D0W9snC)Tb`ksT$f{Y2VUO|s+tnzy;@98j#4aa@ zo)^B}4;jmlbqZrzs40tlXRZsmba`EWRSDa0_gTsKjGWO2KRIl-e-+?$+*C5ya@guh zcKH?boy=LlX}I&3uDriJnZP`U7a6bt8+PG-ILC%W{i8ebOX1`EKF{P##yNk`vuO@< z%`x+LfHv(PT-D~DMN5V5O(wPYvWoz%Lc4*N>Yy7;VYq&rMceu|U6|iz`+|OWoH~pL z4mnAYIqBvc$G%avVx6C5dNyUUBl(7FpKQTsV>C+uI%2WPoNw95*X;`^fu_~qDq;1z$8@?|Y2hw%`1#mI_)Je14U4v>jX9QY6ES02P% zOTEi>PM5N9Z96NSR#pHGh7%#Ngj5qYra8FlVP^)7s9($wHK0yjjKSH z{Z*9S5#;d!fmFWTZaMhnzR_rixCsYz$czh68J)J0k&da_TeP3p7t($LL7RkmH^7?qG@}%~vbqmM zQ*LU*@!{O4#Q-O=8fi+wCc}QX3gyHuF*VL?AN*G=<7QtAf3z5Tzreck2RvSE6l|CJ zYs`}Xlw+je{>}6J$(u^wI@l1d(v{mjtm_m$XHnPI2&rj72L})cptCNIN%>gjDssvN z+S5M7e8!TVAmYLn*cukcRlmOI=SuLDxI#wriLI{rxG#iGhw;y4+G)KSvh^D1M4u>` zSJK@h!=>Ve8UaQBVw@9L{7V+|nBDn3DGX&#NfnK-;ncQiW^E%U2f4IBv;eq?}yopy^;^4sxuzb>z ztTe-)sBYd`@oKC}L*V2$?10bVmJtv&q=MU;K zQrk$;#Db#IEiBV1`qZ#H9p6L@ayATr661N`$EPy-fdyawjj3Fp6b9fweIJ|GYi{{D zx}nFMYb$C-KfAw0G4nU6I69u%dTAW8=peQVQM!nFC6E2$G#N0#2iUW(k_(gvBDPl# zXCJ?>dF4FIm2me@v3G3P?7(Tiez4t<(6m;Xa9FGUJU4|#GNuiI5ns<~&~~=m+d3q< z-Riaas9b#I{x4>}8kd~x$$5$r&gcb;_=PN+SXBE z^!R@md&{V(`>qXCz>$)Y5Rj5k8YHDbq(MOG?hr}o8X5s9>2B#xsi8qSL>h)}7w z3_wW?ehxKKyQu^FuBxAkVY87bu3&w&Jg$pF&=lCfH6Kq~W61~JO~W+R5a8WpnNXRs z+<)@8r6&K66Rz5)%|3=Mmg^3z+=SGo*BiC5&Z`*cP|pC(N!o9rBa;p4#MVCIw#7Pa ztpeF4=|mhyU%#opD<&z6n5kS~M0?WCrhj|w zCJke!hns(5y6(RsrP1Sa%Ji0HQ=hQ5_caEcZ;c67APpfrWRR5UGgJ0*w|=!nbHF0E6-K@m9^ZR&nVi_Vg(hi+ z><*x>_-ay;SV;-;2{-~@fL2u@MC?Tyu#yCu&4YWKgfl8nhSFyZtf_3hn!|BiUWYW` zqzXMYuR7sDd=2Ym7YLYFqupbhA;qq53n()g$iVuec1Gk6ctbAP9T2XMZj({FY_Ft} zUO+6Zb#LHVW_vHirE9>ze-I1miNf0uGuydI2B(hY`T~uN=2OU5j#HCIVy8XWPJ`Ad zFR9Dwt(Rs0R_d~dDQBz)D>y`UFN#v|e)LQqUx?TS`oCown;?BZn;@fZ%mOH!tC$K+ z4Sg@e(w$5!cU_zeJx+gVZpKB6#&F+e(pYAA3HvgGyqn2#f=i6#AMaWY#pH}J zC?bE5=1?cHYahf8`3xI>eV(F1(ztRbUW0G3RJd{cL9z&w$mp@~soQ*=brrV!D`IH) zWEm4GP4fK8jmRw$v=s4 zK9?2jG8D^yiacwn4=jGK)Q*V?S>$}X74W+J5>2sn|3wmOEHgt6cZ`1nw$?k8Z_-;M z&7`MVLh95cpU@^;@8BEPZJF^#tr@pTQ~pT%RjIeG@4b%vPjh$qE}R$q@;Xa*4CUSl zWycW8lbW*hle|UuJ4&a&+H-OZh)RzU39bir?X=9}tEIw>DQ*&j0!f$}Zw~r=s#b@! zC^P)~AuXXY?~hgGku`Z2G7;B+KgBI{>9SncTbXgq)GUO3fR-DoS)s)a9@YZTO2Sy; z;+e7-JO9(xcg@bn49dx~U5Sq}#q28tXeuIsBE!Lm7kZ_x`i4LSEu3TcYt+fw4K7e; zp^DVJm^3uP)e-8&uL??q!)opGFZ^xWNV|iwl5OTiu{Hob^SolI!8R@3O@sQ{{oL#H z`%617QgsK`O?${tWuor!BEgSdl7SFkE1cO%mDfI&)m!@tkkF>^Kcj+3 zQKAvNy4u30nh%0H79Y?;g5=<4V)6fSLnFpQsd2$qOM(bOF^myIz8_Xt+(!;7o@kiZ|_yu&4xpfB7=OZV&BPcadaAw z%NhxEHaHBAr}F45#t>9tarD!9;JdrKYRhd`;g1Bp87)_R&{c_S*ZzhP=9|X$a6aFl z+>*+=-O2TAd2x>uguqgw$!Mj5%YNuM^!PVnzenlY5wzJ6pecH1WZTH zy&em+_#nXuB@^*JqF99q5KFid0A=^xX<^T3+2}%vDSU<0X_pKF5}%z@ZP|>v&vw@8xWA958V{Yz3tkUuTOnul?avf#zE-fLERf`r%f888Y+@}W`jo}6WWwkA zfO_S9bmTn- zX$W5-hubV2R|xds(onv{a*qMlDq>Y_R`h?@`aTbJ83RoBfannA|?_o1m^8Q&r={k8!Ft^dt+_2l630Y?Sq~u+kVHZQMCM_AE3XQWB42u zph$9J$?H>;=)JS*bMC^*^(#X+nhyu@TGb{ABKiuH{2Cnzu%xNQS{wA`azixbEKvyr z922&`Cgzf*$27_U+gSl8)c0ba?@WG>8es2?rw0GErPou>eSvJBQTaqQxYcQB-uV4T zFk6vMcla-ed{1TRWn^JpUbo=|sHn0vIy(F|k@n%Wi$DD+&Ms^^ZZf3y??M;l{eji& zub-TqeJyqL7&3Z{oQM42wixaRFf7bnDa1j;^Mpg+P>K15nEfW)b$yn^v7)+MU|DU` z&$OB3NoL=kf&t9odbiYkoNdtNdFl3wcj+UFX1C!7r<(Ii4A-I3KlU@eXH{7mravrxnCE$0Q?lG@OskgKJ`OS$(`d zC-dreZ|Q4zU$LEw-Yr+}t!rHsl9WXcYx^yQqTb9ledxaW#7i-Yhq%RyVI)w=XN1X7 zmo{6U2r@3$Q6&p%f659=l_$k88?uuc;?rm?)N1XuUt^bsmPWQ)h<_skYO7rD+uK=XPZYh&k ztH}mcj9dij8y%Eiu8*F$c5SgiMAN~&)38Pz59|+FsNp2&P8)T(naz#))*6WOJWvD)Dm72z zTB)2yk)OrEd_@k>xPB}PWy%u0f zliTNNETuD=LFX7N-RK-^^V33mj(1v&$(u~%%;J;cAUm#ss{Q;%mCD}7Jod|a#~p^j zg_OeX`1>>EeR2KKoX&8@e!;|fyBt4l*bLjN*MU_EC`sKbSmaR@lWIXMoSu3rL>zg> zXBM?Ps#S#?ptekoP|zM7ee(8kq7t)wQzmFcSNo0YI|umnR5ba`#pL*}7UIBA^j7}! zPn$0g<*2oD{=8|33k-w2AoE*JlcEq{7N@t!oFN0<(-MepIcjwzn-wCHI1YkmmF4ji z8?F_@#arcC3u&$E8X}Xc^JH>K4G5kiCW%6gO4O78K#s?2!`v5EcKkl^PPx~bH z3c0n?xH(fmHGVeK6t`)VDuGNhoGR3B-Qd z)=`t;=y=~rcfnXYQac=lBl%e-4sbs{SP>Z*U#2KX{#M7?sKr&`(R)6q{aCw(xhWwLW}}SsL&vD z7k`%2oG9lFfA*arcw)RhFdT7cDYfF?xgd7Y7~jufxv+L)B zuKy)*R*CKER?CNhHf8kQT@!4NqOs~9M)%x@4%*d;2>UVuUeg!T`~h;|lYut6xViRz zSO3?Ao?#8RRh`Yxea-JM^isoW83ksY#;{t`mQkENeS!BVqM@&Ij^%z;49v3DTb*qZ zJIfe%EHL<74Vh+-UiT^QIE{JGmUu9c?ZvOr%^gO-joHU59Jx}ag22l9Y6LYe)5S{e z#F*jn;RxPbOUXb8FSCxrjuHIh#NFC4cIWDGJaw7Xd4&(`su$a6D|(OnNHap-3{&{y zM1Mo@GNkk`dY#yNDH3oYZG@!F$|b2Zzopz+bF||?%B+qU=_Scy$aKP{R56!$@1REh z7}Qm_mkymCHba-B^n~&gv5`{^!1B|{L{a?6o{&lde2+eTJ`df0fF}*s+af=DeHRr@ z^ipgD@R7FXcD&pRWUP!=+AA+M`AW6r<)|Uui?m>5gCr_plL`D5R-0$qg9TjXy59VU z=-Wa`ba_%J{*VdU7G0OmBnT0=k^6cx^UJOkE-5s>gT|FxI;m4A<^pQ(Cl1Y$XN#A{ zqo_97mQ|`8WdkdCE7MgP41p}FgW-6(;++~Ufh?Id?r<583%)<+J@!u!yw3(Fl4dIn zW~o{gza)tjf{NosdU}2v&nToSUSsYf+fmvfikFu|>5tOTrTJ=!SaNa$Ayr+Pk&@wO zSUa$*jo)!MpW$%$+m#;_Ou&+Vve3Y0E}jhq7w+>Wko+&upt&K&hwsmlA1pND0j+kr z`z}fy*EX!<2eL>DobCf_t_^dt<-fd#tb7|B&0`L1t3ljVd3brh*;Alb0$K;sP7doY zKZozLvk>^KJIKIw^L~U#qVtq3e3n9@61*1X{z82a43UX`q&}z}!w-OihE8h7^(VXb z9VWVPA-lSeYJhOTL=J|&J*ejb;J#!CxE}`=J!)H z{J(fg2w1C4p~`(FA21#gA#95;dbdLsz7Tuxxx4rzpKcW#m9NyENVspZ2vG};| z%iOb666v1Ib^QT?S4_YT(i@8uX}bkMLSN{82Jf?b%gDpGhy?lY zI$Z|ac~32=k;5nKB{CTb8&BHdq;DNn84Pcjs3y&agQ*M0r2SC`Io^dYFhdy;8Q1G- z!wBQ>p{=Q0CGU|jF7XlU<{e~Lva!gjvYg}qW`i`vz;-$1X%Fbj?i6pvp5JKbCNfBSO zu{q@Kmgiu0JNgT=z|sx@c{^2U@kX+S;{6=?!7k>!3_?)3yUSdIh|OX;&r1e(it}rf zn0#oJVio|+$0f-7z>>OH{t#FDVSM5?RAhxgn@%WXuBLd~G2cA_Rod*Kbr=X)l0XdK zS6|S5MTgatg^Cbi=#)EZWapy&2eqfGJnVLEo5~p3>ksEoT$O9r4jmTBM-9>WN*^nx z-OKw?${5f}-l!F658?GHXmlK7`}Ul4FL3@`|4O6*Ti^W(-Cr>=zH!0<#(a{nVDu-_ z%i9QHf%~J#Lmcx$TfTf3xy5}4Q4XD(UQQT#zM95Ss_)`-dIPBXSwDqM#cHVx}mQ;9S? z{$iTevsJi)4oDA)M?39KWJMaC0o!}rXKfZJXWIUpT#$0x#=)uh0v{awJt9&yGL=qyO*kviZ@jl`B<@5tZ>> zPH%1LIuc8_k5-Vst>Ci~6o4hd|RYu`F4@S*@T&ZrObs}fa^6@7Yc}X5DNrr3C zZTyiApA`_10Q|4+L|#%ro4TKv?+nbE8anrtxc9c4_=5bg-x6;rulH4X2;E-oNs6Zy zZAi|#6;Y``9WRi)WcwigAMS}d~rGeeUBnU1YMWB2iyIQn*S*E zpJSleVx*DN9MQM&hg|M^-2zJKXgt;7UTep+kodkJ^WcFI#TTJW($IV4b15I}Ts!pDw}x+LaBWj88YzA(*1NkS`a zF5>?hXaWGjT=T!=)kI#$>E_Ty)ExqmYx&4vxwOOZ_IZho8IP z)#D{D=xUm=zkp7Pf3w~>|6FWxL=$PL?^*Rpi{TjhdeEGVIW6QHQs`z!^C9597Pk%7 zjoWbmK!&}YYNc3z_ps9{ig>nr8)2q{s5y_gEPsbAg?{kZVKtl072g3|z1tkuX3as4 zSnFe?=ha^l`2N!VK5lIswz8WRh%E3wM4Pyxns|HQh`tMOB)eWa<1gbmG*K5IKK|~G z{vRpV)}qaARNK8hZpo|i{{Cf4Qz^95C-T}xqmRm4or_d}Z=aavGpQ24uu$v~5nX3x z&;k7Di*`gb^6t6)tB+K#4D@zxGq_Eigne!vzaCrZ(&b4_pv7_zd!VPxUbeZA1D`JD zOO^&eup?^ol8)ftkW>2se*W5LgUyKgL_8k}O}$pmmJ~@?v~p!#gjaHruxXpFbmIQ` ze1k-9DrOL0+>XXS-u%SL{Pt^sr`B!v+eL`ijDKQ&2^m(;WBBb%tR&p?0E6OgpYv#? z1$|yxt#UUsO5clCqfE=c#+NVqb$b>U&_I8wd$Jc|Jp5d8HI4<(_x9f7 zu%;LK37jRaVGh@6{sIy)ru6w{I~2J;^XEiTEucoEDZ3`TU?@iQx{psHbTo^`@dv#H zt9kzXmpfI$GOcEeDa(5-h-W12bRq>SR?|b2uw>0^###vg2Ti`*m*i|FwD@<ydF z%^qmI^6_1{oBQggMR+Q7)zJsEYd2MX zcVewA&P~1jiOdjE_62>r?^(DX6K`<4!sW5oF%;`-)RN1W&ycQkTSaJZ45VO#%VzPl zW~TRdzj#5Ar`*l1R$;X5z12>4Q5bh^8HX}agrHm<04}SRH=S=kka?6p6qto_{Pf%f zU#3$0Ll8Z%!cF2R*SN0!-&T2E!uY*?vc$kqtSOU5YH7Dc8c(fw1=+DQcLF91qxj8@ zqbLLdCJVw>e@`V1B(u>~7`8?76n`|?j-r%}dlkv#BcFH40u6)l=gu99x?`o(T1>6l z{C+2}dVC!1ft|!M`ywX$=y%-foj*r(WjgJolG5KL3M<;qXK>(YTEz8;7%L(b%*1`bdYpEfT7MYDGq3Ix_-9Bp%eV0U}(?Q;c1@C z(>{PPR)I`-CG(jYyr23ud3Emr#~0vc(2Q9OC-_Wt_{Tf{8|relUx%T+mJ~;3V8;qH zVravxP&rE)Se7uCM4phHx^gS5wUi2HgPJK)h#;Z|pj ztnd|HsAhZIVIIEK2_#H8>`gAsl+mVZi6&8To%I**tgz5vn&!|-ss7Ys=mC1lRz(j^ zf9`6u!c4kkiVQ=wV9D-Y0b0lHVXk<4dk-ItZ5}Fg@h2(lY2aWXaM~$Q!TJypk&~`7 zpc|)3*1}E3S74`PK|6CAnhXiC|K2J5+6QZOc>{DQqXfj$uJAV;u}Yn@pWD{+?qis& z=4uL<(zcQew~QBI4O)DAOm@p?pD&d24;a|j${Uxt3dF4cID&);kdw7;Q={DkA0D0n z{JN03%5$Bah&{J!Q8M1`b7KEd#)9L~yd=FM+=2#?QES9hGF?Wfm6qA5K6Jg7mw3o& z2V{R;Dr7-V41J^i9t!S~;JqA5pPO>Q{)V#vR3f#b5{$lNW+C+qp0*78XkO)fkyu3W zE&2V#xZ18#kq)p(7^t%(Xb91N3`LGqbDhfUmk zVP14|y$>Bo1MTpw3qqz<}iI7cWzq3L0Su7zV z;kY5zy`qr%V18os9vKqU%aS1Sz7&r+AjV~73O_WLGM1x?!RA8$df**^_QCO?V>M_cWlM#GW_&W(As%#&ikP-($bOIcm1-U7Y-E_e zz>m2uB+~8wNjz(p%<&xl%P4wyC^6C()JldVk1ey|JCx|`YOf5_hqy8vEVhFH?;yEG zFNeB%oH|nCo0ENWdv)~gu*7^^Ug|80ihsA>6=*drcE>9k%xAJAu6T2!P_~?%8>t>3 zpv;7J_|KvI#4tYrB6N*JxGEuzM#nrYu*cani< z_&AVlMOdLjCx~Hk(T_0+O~!Jj;1@|* z6ZMiqMqwM@2Nj?6=i9RehWM@`a#I}4$_EP^*5ImoO(&I@cfXJ`5HW4TGhrBV0%}CGfFnk>x*Zq&M0eiqSPuTW=BsA5Q50vrNlg~UN5`%bM z^~!E{U!;pU;ct&-NT%{wE6$-@tQ3c}+Lz00KdFQb-OSE18h&8a9dSgkp8V3x{K}4%?CH-dNYeu$FpfF1W^XA=Aruei-kjM_JFq$1H-n3m z_Y!^l!%%|xQnQQIg|Wz&+e^$$2rwi9OxSWoDGBuN)1Qm1+oXNC!5?X**Dep{Kinxv zPOLG+vU*@0EYuS6+w0AUxIJgrk7#mS-}@Yb4z^!v_4gcnwYHe@3HCby{ny!6e*yNk zqtQK8zFeAt#8e#)u(48JEQ*;n31AAMClW@SVR{_6%RM z5Dd5R*i-KG>+T6VEPwYHI2$(gd`;m>_%HZ=3$=AfzWW z*JCyYFw>u)m7%sZj1(0eD~v?C&CfvZ{bgCIysw?waKywQvW*NltrdP9D>OM}04cz#v#7KjF8-@2Y-P%T12^*l~ zmj~P)8c*Q%97A_h2Y(p=mVdXwennKRQX8B4X&T0UV4Ce})E_30eKxaIPS+>E3ZB_kujx0D4&#jYdJHi3MX3tiyFvpsX?T^Rjz0LQ7`@))b*~Ww{ zfaoH1FiZ6^OcVDbv{IA3^hy!%WLIScEu%ez9Ks-E^S)g;(h;zbNZuHN2V;MS<-X=t zbypjKOa+W+rNrIMMYZXbf!W}31UC4v|0{7De6RPD+GTzA{q0x`FB@!!3AXeM+v1Mw zx$Qz-r=J8}3{SD?L|CK!iiRpA<)r`H>wy#$EAAsU9y?wVTQ#qbi<&5wtM*v*;!gC= zo+fT5q;9as|B@{NOHmZ09v};EF*3lue_HNuOF%zOa^-hFWL9|_4JsIX6rt&9&{N3* zwb$58J^OG6g=%Rtt`C~y?9UX9{goNK`N_q3?*>j_9JjMB$i)V*$o{)G1xz#l@Uf}# z5uL=a9&Ba6PDFG+5ElnHfHQ#6gM?3nX5-F@;V-=FtuCs}he!?@&ox}(Z}sbHoio==s;!9%g)zrH!mdu9=o!E)BdtS!TbE* zzuXeFM4@y)-{|S=ex38?>4yhyj}_rE9RviK@^ae?DO}dVAvk*xM{PHzP-v_xzcZ3T zrKSo5@DOjVG{?f=ysvh!;JUTAoHhnKP+gzluF7W6Aj;zvrN&$d)3K?6qY-EyF>r(@ zYXjqtfHh$cYjpf`sHtr%!i_%ukjxfWE+Q4i^UB^+;_VHhx+?j4#&vlghLH9hI;zva4teeKk%r zEB8Ko)s^?8vxWRG(-7&x4*~3|+ZeGyqFU%Gn$Z#oi(vhfT7Zbr!DDdim9O|=+-n|1 zibCUCKIpPOO%4`~rpHPAVUYUVpT{VZEpGAA4t&^qe?!CZuli&B$#D;`cWRA{S)`-U zCkq8XeADU8{5dpEJQ5I@uvh#F% z$}brVU_w;(DvBmQAfBYz*f9xy6^;nzF?zx zxuGfTY2&|UAJ45P7I4yWyiE-GC1&&1P1F~#)_y6c3-&6p%O(0KX5ezgp$n%LGuED1VPd+g_SLnx9#3|3NHF9^v3m2B>X8^{7EHI;{y-Bz!AHP=KKWd zq+&cLs#co4TG>s$Z2ibvjN84=reKo%1BGU6v(4SAF00jNH}%I3)|-+@1ewEzJ(&Ij zs<7|VO*tx~_}hhN;P^^XHApJzuncZ#{tukMt2dS!k7AC5#={Nnxx>wTp{dCk> zn>;~q(_k_ABwin;f8PU-F}oRjU91bwJG($Aw>v7mQY46=rGp9?Um zm&7m6mFqT+L+tqhJpNd}<)W)<^->B?+Bbjlo!LY9r416fcjty4$4Zj>8urOTX*OIn zq%NPqNSLt7bncr$@5U;aQQaFtc5BhTym$&vQ@oDNdQ08v+uuM=az~;zqZO<##Pg@L zAV=y2OP{y7C}Jd2Qi_t_Q)G3a_iXRXsXpYja(srAjLX@VIxW%nGbyw%{$`+Y)Zv3o z?J#WNlYd%D591GEYeJg>j^9t~qxwH&CC9_j*pR@1xh~zqDcmP>*}k%|JD4}TULk{0 ze%pI*j&cvzOs-3m{9!XYj{ASh8FlIy*ZMX4ARmR_0oR18TJb0DBrDuYOT;QmPzj$@ zzn;SC+8;C`T4&O=G1GZa_nZ6)i{T0~uxt?g76Z98g7;;Xgd&q%wS{E{6iu@Xd0wPH z9e|grdooRbwrcN={YhbN+xrh{(MJ*Z+dgpd?nFmJfs2q$5FhbRJ5&xkJ!s`~jtYK7 zrH5tN&-PaU+<~Dc%bv&~CgLKqK0f82@CaY~0g`HTLi@$ME}zD|@(GNk3&|1J0BHN0Y?sssp#Xu~d9jqem^g2@>opCq%W zbh5=N2(ERrV~B0|(JSpcR(R9OJWu)a-lBqA+-i)FdeG1;giAztmHYw;39IhY;oA{% z3@84IsqwnlkW?2x?X!TuT_6*R28zS7*65@iajJm3yrBH`PIZW5Qh^C4C>Qu9b0l`< z0RDpx(KX=Nwdv=5aR797#m~|Eve3$Ywv?w@{~XyA5g_74)mHpgu_5sX0eIcCL4HqG$qjEy@bK2oD>p^jpILZ`Yw6@$a^!X8dvg<}8aDWY&gIXoSYkb?9{YOe240Gi2} z7oqNbos1Z04zYfs(y?$5VKV z_ix%d>*dFvd=X@ksjbK5lO7|jxmd`LRpbdg6oT2t*W_R#76SU!$bIrb63v(o`q`AC zyFhq}p9~u*16m%Nvgi)y-X7yp9Ysg!=h$gHj@&(Ez@c0~^>VY>nVSjs&3d9Q5c2%m zrVdDl06~zb&PR6YhePU?&KaB!7+SG_`h1+)0N8As{r5@`;8S`#c`*Vo>&@iIzKx5k zhF{o-iw5F^Yk+Gj_j~P&?ll>Xfw;(@{!uO62qY}6eBO*$9au$s2#V6&C{@LyUp}v3 zy8imJyF88G;bu~V{=<)rdTHf5A5<~LJ83BcyB-(f20-4U$XCchA!gQ;9O9#lVX$$X zdD;`96DAM$g5!^8M}ewMP;BRQW0ly@SNGGkQRK#dBCMnWrBSl~91Iv{u-I_8Gu8`yhB+s;}VY2U+o+u)h!)L1lNtUSKrBpw}=W?iARA ze^*=)0(miWSNzO)8aMs#@GnSSgP~875;rScp)`zaMY*qP>}K`)%o2;eZ*rBJkR(&g z?TL35P1A8l&d%Rj$WY%p4vrK9qQIa~8D(ACX0}?XTLdIa`1*-=g!V)Mx=M{RK20PR zeCPy!63MCFJwM%XeMbK0QsR_I<&sFldwemRTw+1M;n$%*q)ZrG5ptBlQ~$hNt8tp# z>cuL~ZQrLYKwEVF)XDWg+78+>;u%PTw+2WnFS}o?4LqEw#5O;Og>(~xNFOnU7PAX_p=Gg-&9O~QH#Sy>;i});aA(L|ei>)~Vp#S+|GZdh&oPHNb;yq+m zx*Z=;!b%NrPhyCup{!e-=wlA(*d*oedYPy7b3aMH>fHrHST>svXkpWBgGm|F2vlbK@XGVm~!4JF9H?hh$XcdLIND6n?n{})WOIQ#zr z6OXEKxv<7mfG^mnohLY3Wyc#1sL;JM6dhIvU5^rGOXKBX^&<=cK~KQ@e;K1iS{h6b zf{Lw{OMIH{#z{;D`PawK0~3?q0v!;6-HHSr)j4tei3|o<8>KwJawhIsx#Tvd{QD|P)wum0Zu{vp@a>$K;M8l(0j zN7yT!wPxgfl6z2AjP(8e5B0S8ESq1l`&7@62EV*9+plYOR9n%b4ga+HcC+A7i;5qy zG7)erzj*7iTXBRo?4-jGp2lfMbXl~snZ{p1r_}6Rq*Y7~klPy<1YH2WX=5uu;nxt4 zMyLZlqSEXD0QBOR{rOY25-5lAqnS+um(HGUtF^u9(k9nK@=2g)g7aR4mi(~VgY~mr z;1hO-J$i`AO4N#Ji7tUIGqWvj96-@d^t)gzDJ`*FEa91Z#Mzibse188(8)Twd*Yn# zpAn^Wfv-||)=O6Kqqy=>XJa@C+N9*wjVh3V`?Z48Jlv=*M zoHs$yEY;IKQDRKJYA0S+xTN`?a5GFya1zHgrEMx?U*(noYqKZ#%(B{d-*^CI zOG#qqdVh4x)a%Af#-sD%xVMgoBIMQd3pY9-HjJhCbxXw#oAH^EmL~CdfD8tb)}8M` zfDuo93rgYxgt-DI&o8D&kHE)EE$9K$z!VwX#+TKF4;9!=?kBWZ&)E_4BN4#Z8N3#^ zW85zxhqd%dsYE0ZQui&Dm6hQizF8`3`n$|hkEH?VYM)<;R+rCyx$K8IA_AyWFWDfo zf8QXGM9l%4+590N_#fa|26#~s*IhH{L^hCfetcbPsWQm_+(dh&L#8PRE=%w>Zrj~Y zTQ)+|J-j~cDi=uQjZHO|g$w)Q`#SwNsD zrc!$;K=4RpO|Cf}09}0Z=JV}?`sZYcXAjIL{ zYGRV%v`EyQsG4M0Dv{9mi%?D~-u*w_WgZc<3<&^f5OMXw{ z6?U*s1SsnG@5qZL?`v8vi{bB$pQI5%M)|KuBGG~5QR$Nco2dum-`q1PVFth<78pO* zZNF}GB=B^O76mROkGV31JpzI-328t5RJ@^1jA_6F`WAHp^BGZBAdc%HRMly`HX2KI ztMHR`BQI${1&c-+Xfg1>Ta3G(_^_G}#&?DhzCPbEjtZ5-7Z|l1%iN9aw4ThDsL=a$ zj+CtRdFypqW^lhdRVe#|9@A-iG_rBoQ-L}h0)f~OcD`U6%Mz2xeIIsy6~~|u0?g`z zW`U8I6i#zB<`)ASz`(p+Q=|8sw}rM(M9z2X`$Yd%8df%Tzj0iY3Mc9Wq;H^R3LBUk zC;^V{P0r%JBfjX)SsnWKRsVbI<+{KWLjVv}m?;EzKM*|@##vA@w!E_pik7)M@S~@ zFjpR)IDHgkAN}W8J!_Z=UwJM$Ll}$=Wcz8AmK)Y$P5u1PQ*o$!E{>5ntX-QUwI4mv zZtB((MY*v1rsdWjfX+U_X5O)?;-QeeH7#X$pDcs&L(o2@FDx2eT-iSL9TX*m@sMT2suZ zYae2MJ3Y$m8a&UNXFJbIsDxZuISDe@5at=c-t2QGWws$sDQM*kYk?v?7SXq-h&Hb) zT&x?jj?$z`*vrwE1gM$u*yV_bh~$U^zg}vu=yZvjr^Yil_VX`SIrjfnd?dfUI_!hn z|6J`RvF%nrj9ASwS%Xg$RnmGFjvzMcn-OeYI~@iG%fE2W)ZfE`zgkYTX@Z|p2yn(USVnrHSnXf5}+oq-akR&QZM4gy^fOn5bRsJwv7?29SzVOwG#*38p(iKhOr;2 z@sbC?>QLW5WqQw;mOq3g?7PxP_KkO*#!8|?HQUlXX%89rzK9hqD8sJKwk4kw*#tI@ zms>)N^dDe{)S0E!k??huWB<#-zI{w|z<&p+|9B%<3dFFM332PW?@`=ZV5yARDn}>V%U8w>ISdLw zeOLoV9U~{!%U5i8q;m=b@d`k#1A3#B&2_l32C5N(xCQyL@nU-e&u;=wYO0kV7o+0H{JrF={MYm zohxky!qSU`zikQt2Y%cgil_3{?bUeKzE7}o9IZ@HmvD#mu%x)}H=vShM*}A+aU9S} zI1gSwdo34UZKy19*nEM;MhSSE?}mVAV4QU^%|`jen-5jQ6A$B{**gsJ)@P4Cv10kV z$>9DB<3hui_j%3gsza5czNxn@d6E~&H-NXdC^pOfz=)r>%8}PY`kUn0qt@%Kw1E`v z!pyq<6cc(ruH2<`Yr2g$7IkD3O<(d5dLTNwJ?@R$qo-gGw?9o*FTb0Z8Jc0yJ;MZJ zf=NBd=GOL3q+ErMJiQfzAm>N=wHA@>^sRH^7_D|of+AQ68la$+aRQNqhp^!oBc$pOaCqZ!B^z!}UK^Kg*T+FW<= zJ;)ocBfl#EOvXEaH>mt|`wsYVBflTT1g$L5r4V|^`NRhIM^Z&q=Y_mvAo?ThX!cAV&=5cxG#$CsWy-2^_Werf^UR6*}TV5O5uo-BkAHo_64h9G`=s7!b5M#j$5Na~H%ozAyqwHdy3U5Q zO}dg=x}YuRJ2Wq^i3PEl#M~xLR^I>4N^+J+`_Tb&HSQF{!|XXkDCB{=9F-wEn&MVU6;8p?qp$-56pX; z0-jOrb!A5x&RvsykIS~I3%swd{JF)~R|7htRXF~T3bqfmHtbms)|Fs^3=hptLtPH(WlTCE<0o#SgIRPk@Mv3iZiGwdRImOj2c5I^ zl##A{5_`EMeHY_9h9l~CUR_+$v4-v5WPs#8MTfu$C$*NfQnc!QHhJlv9obLFa}x5n zlL+Nm^y}F*x+9=KV%nJeiUoyOLen_ow$`?^Y(pw>oxY z-tkGhl4n*Z*7cqRtFY#073U~vnerf1J#Za`(_i0@4&0V$*FJe=1RQhvYd& z7&V4bvC)TLGvIC&XgT!QbamFH665`EYH`pkYV>ueR1}tNx8ojDSXwpU)hR>UG4X;z zgrC#d+;&{P6*C2s-TIx?)#pQfH`@!MT05m|aeRI~r>OTa5;|}Af9U$}c&h*Z4IGci zp4qz;vbSv6t5CK$WM`8-juqKSqU;sfnVH8Z%ATFnqC68tK=J1?BKS?$IY?(N7H!sqNFYT5 z*Ci0={XXdiF#bL^YjNSTBCjw8DZ(v*p)2i6l0BS1-{8Nv`ny7Vj&d%OH*Rgew7=}a zBr*rH1ltL)|H|!J8uLqQ#{&2F%CEtE%;ZG28rq&emlXuvvRZ9Xb$^4dFch=+%DuEc z+h6&e-^-qbT~T@_AvDb*WO%RUv}q&en4@B$Ti**F!|||e=lXKFu>C2DS7Sz>dH#IR zm_e`tWd7Kc#0~w5WZEU&#@k+9_RTZ~9NM&?ClH@F;a|p$LB{L$NcEoHvb)W;`fNTR z`9WuK;zV5xGNzr@}BxnsxYeTF@ni!giRH?T|Ej!?Sy57 zb*4*nn$d~qyLJed=&)#7Jcej8yy&Ld2p{XqskquiTWiBSH*c=wm#^b%d`NF_d~OWo z2oSrbZt7OY`uyv6X^i5-58^U%w^Wx`M+=7K3m5jPky423SH5!u*Rw^<-{hyPavK(h zC6X8SMQcsHq=eIbnC*ddK4K>95#5tw>ks{U%IK?=`CWm~%FHy@m#j;xLxnl-^Ts(_ z0d4;`xGBTdhy<|~>r-Ie9m&zo zJ;lj$r?y04zTY(?KgXaLcoF2Q^-GrPb47wvFTfR(8FFA9iQ8qkTf8B(TwlO9%7|GG zWU=zXM<;F0AH6$k`3Nix*$n_2b=M{B&mwH{lo4G81wF=-HPe3>p>`~yWU(<vi ziIf}M-Ge0wO8abdu8Y@bOy=wkw4uH^n=8^2Pu5SWE$8FJH+}$6u}K6;iUg&X1p2OK zNo*0-`#w!=Wqn*$OwL%GQU=E~9Bz`rR4k9XOf4VAcwirHjw`Foqs)z4Sj%=Pfe_lh zNpnEaO?7D($)Qdg6Ac5(F=G*oMbt!@ggc3A4{xCDgI%L)Q*D2Xipivo`+*F5C6hVI%=fO zP0a!h!QwRz)eQwcyBYS9A!;_+okIf#0H zre1@c;OyENA4&JkGY)tqmce}A{AAX!#Lvag?!^fT5Gq8s;JGJ+ROpO^&I&cTCGjVR0B&~Ba=VJVEkckA3hHJ~!m zyZv8UyjU1cJG=;`Fss8cs-RDvD(*`$i|-?wD>AAuPJOOHPKQ5lhNH2(Kg3>I2(1wm z%zC_!iAt~8rp#!hzak4{OA;r+cneI8hKe88TaOAN1`muIT$#fWbbMKxDHayOzg;R? zf8uc^PEtbF!M|{#(wGjSXA2Kpb44lh%rD(UWo#?*wJ|N$#)IUHJEk_&7+x97} zDp)u0z`GP~@;KP#)ia{~Clf3cEU&4oOoNAw>;P)E7LvS6dNtSDEq`FTT>~+Hj zRIP5@A#)?Y!EbLE97D?ZBHS%}d`w}EFrk;ZXq>Hxtp%R+O!m>@lrX{rV82dy=>?w> z&b!=T*}&Mp5I+;bX~Th%g_3Hz45jTNvk{!7azYGOgFbOg^{jt-6!ALM8|nqn>n%e* z=`Xdu2IM|5>80zUo1dGFj>d-)U6N(tsC)Z7B%>T^B8(!6Y-s|>i%YI`GF)Zf4D#LBVJ zWroJzeaU-<;|*6RiP&%ckR;kKmDinll<|k6VLKsbkL*bdCJW#EHv8=7bItJTiL{oa zheLPUaCp-8^pb_yv;_OuZ(A2()L^v7g3NPMVZGiR2-={?54lxo^{GHjjO;%~IF8%d z4%4-;il4Q-gGA|`1~z4(!THUp3PrRolIAveSrlyfHnTKj`yC$N#$n=99!_ef*-CDT zpo{O$Lh_@ig0=nh7wo>K_;l;(+qeSP`vT0uGeu zDN(g4A>wp*u2jWQT{b2Wn|j&s72&%*C=@_9CW(JM=>bI=U!K0oW038}K>2KL7km)e zt94~3{9>xyq=g(5VI2QfX?rIVQ=5zAV~ta8F-&k*leCSh$+io^HM8=Ns`m&!I;ywd7Y>_>l`=I2{LAPc zaujCDJrJ&=XX2s{ST-~m1~=D1B3D$C#4LSd?RQJ}C~;4)1xm+BSKtd*G)xZa27lXx z7u||CIe!zKC{lRp_CUCQ#E;Q(=qP1;o$CBe+oUw7t%wQEYW9Y-?L3c2vxc+ff9#*G z94y3Xq=M7dM+%=M0=6gV$C%>z)M(L~XCJEKhHBPfeF z7+Jq-bf0UsG9uyE>RF;vb$`4nBm2ny=IdS?JIb*4~;Z7Zg*yp2o7r zcS&cc4XV`pDgRV5Q;;lL;+nfDVyaeyBcN2Wi4L!z8`66kF`nBXB7BNhWC-d3n~dX{ z46a=!dj!f))laEE%+4w>gpT=VrhdY!!mH+w*}Z;7wM*F(1&h|f%ZVO|o?t0;qw)HF z6pK`B7h!6mIA(H)7PKkH$vpR;Rj92g13THP`KG@tOkJFL7PQ<0(_U>vg5;A^KQQcb zGy#-xcd+r+uk}D%6wMQoJ?2GE>s!JbGG5v0YxS2QRo^uWpG1K2*p?JNv$#|KK0Rlu z?Tcis3%dWYaM-{asi*8sR5*eh0xkw0PA`&V#&}oS$D4VouL~_fr`We>MMV%EagUAp zEm>J6fJYa1IT>~wzxjjJWWthA zf$wQ1C$PKuojB0o(?+1}LA|>@5V|ht27rFoFw_{z`LUpgl;2GHl6TN|d2R>T6ET(y z!gu1(_6>A42F7`YVS8hd$3f@q{7s{ig=vr`*0dC!;6AW{&dShd*jjTECC?j&2U35 z#pFr)5>sH9h<19ww;iuXu)*J7Ml62aqdp(xaSnUr<>3<&os3RgA>;DrM~8^I(xX~j zLYn3lqka0lG{m_SlDag#Ihpd7=+UGi7zRHfsz%QJe|;lLT4Ll!$pmh$oMhtA+jFs9 zOW%2U`up#Iz3nTWCJ(JPz=0;v*CAE{5lAg)@uQn~P`6#C#POHWu#l^SWhSm3fkyH)igaLZENt^$aDF?`Z2Q(^e3Y8mZ}M;L9C*mWn-3;0T+6~f$K6b~qE1TX8{ z(&+br0`uf85u7_V@2PHS)_z?j%yM&MFT8!2VQam1ubb9}$ENroAlMEe6u}}do1}5F zu%)_|gk$x^^GfF(|EC%ikj5{LC*D{$_Y%YtOT;TtS63DVHq83FZNO0krhe+Jk~C;~ z$e<*M&xkG^r=%Wm+Awc3{JageR+8{`OCIT_j;7=Y+4reJ{2Zs!Z59uIoLww?z40l!fjfTgGaJ!f?{&hH0_Cm$te;kF(!?k zexaLswLLsat|1R?sg}!g^6Eay`RgY&3Q_i6e1*7RRQT5J)&0!HaW&ot{zb$gAWe4e zV{;EA2y>`TG|Jh_7M;h9mV(Dz#)5z~4h4-P_46b6;e~Ap662Fz@~{4`=9_&h8HsK8 zv^}7yg@8=p)MdR&VmJo&r;ZMAu4zY+8&^I`5FmN zcWY}Ez}2s=qH5gvb6Qj<-xKt1vraExLzuIdC=pcgrIoF9Uymv#9+SPlGqHdW%2P!I zKGJ+h;jkFK5<)l<7?p^a|Jf!Zx(!-lAt#B^9t~m351AI%mTxlh<8{s3;&q}GY?u8B zJ)R@m5~Ut6+~fa8T8${f;>5P!<|>5BbYA&IJ{R7+ohNBfg9$FcrNHE!F8tWrTRhhY z)kA)?(SIJW=ma_e?{ali<9QHdpb38xW0W}0G86+F%y4p=e5xXyuI#)#5&p`e_q5vz zHE7E)ec5~w2-P)Hq~xLh?)+fp(3l^^NjUqntay10hitpaJQb$&RTy3y3hMJM@@pd+ z{Z2qrfy7poUQ9-~kVo5}(Z^}k`k1|-hRVKA=9ugEcH$ccy!xV-o=Z8LP}Uqh)06A+ zHq-t}(|?S7^_>0r@dBem+HsU$+1>f;)Bkx^mdif^mWYxH7b+4BG@v#1;zkWRLDU^? z>K{3T?=G$LQ3%i>yV&EC_fHWRyU8k=8^T;R3;6h!sb=hl#(60B*H&(%LGHiG^ zm8Qig{jc{l_b9qEx~sig6E(=3ESIOU=u~?q_a^9Hh||&L@h9e8V63?8K4^FO@s2kwp1v;5@=)^j2L%n406}w(!G_IjEUgEB3q6G zT2!O=)wprPHcAHF;iK_H5BElgAV3lN=bc}Xpd}!yguzHUl#8hj$Lu*C5IWQHE= z*kOd!bp|&ks{%D58(t4QDo-Dw@zW?t9=r;m`%#!@Hj32wXnAATh%h{mB|^ABWSbgO zC+P7=_;${!b;FZ@P&GVgl3ku0H)H6q0#PO7t&vhDQj|{kaF$hdQ**7qP;{ju3G|$8 zS3STdZb|GZpYn@8c0;in!Z@wV=ew>j@9cl+;s_7$_KefYiZMtjaMLlkILdy{RloYR_-@XFqJ#36V-<){R+bPfcy!jn%ec0!6rMznb*%7cm z-15X1rZhYF)mEQZ0I(G!!}|7G@~-!6vQlF940Nv}96%>Vs$m-Eu@}ulPumA5HX~kQX`OvDW?X%OJ!|PY^-{q!FY= zNK%+psnpvz0?}t_skwORA-eO-+An$`j^Z!4Q95(P>KPM1BTmU}XwBEh*cUW)e`uOV z?hj{4ZA(%Cp)k^D7+$&h?FZ%>W3n?y6q)m-QUyy76)`IKVoJ+(sg6hp(xLiI+bFe{+kc2=?x7>A87fO6Yk;JvJs_#aY3XKv zxO|(qJu`9plco5$CslvqdN^>vvdXmvJ|P2OI9~l50e?C9`W^+yw>CSPkoh>eeE(0t z;m;3EGJ;d*Ohx*jx)xfOt5ja!E>qAfe<)Q#5_=a3fB8)NNwo>bMU%E?}^ zF^qdJ6)V-VCN6&4E^sw+yvT-D9qB$(ch~f`_Rn>fkd&~k==SLH#LeM6Mc5(@r%9kn zoOMQS186&N5^<+|E)`m|yTu_{xa*wM)u9xio2irUdZ(&B=VsBN%XE1O_YJ#Z(SGM& z#;T9B;4G}*@EWO`JaG)FyLs&<;St4#GAm&i?97-)3$FL|m@Ws}kIx;Hfk#$G5A^G2*b>OMHeStIm z5Nbb1EMb3eCv)!+2o=`^iu@TLJkJtNM7+~arz1^Hj%Z1>oEf;!dn>{Mj`-2G3Q!2|2%0xRw{QT%r16VOP(P3~E$=}%Ton%(EnTMQ3> zSvyegsCTg3b~0s)!qF>V*TDVy`1L8Jp=lYf{h&$D{L;JSBq^4`^E!tU?*=zaHOA24 zr>pd9F%veq;0x8exU$IrhIiZRO>w4#2bFe)(abkj;=DfFYf5&9aRB?{5xb*mI@%OLt0&QOz4gyTp-Ml$=exwwNnh5QCDZqU9I=I<`MA)L8 zUQl1zOe8+ZA4MMLG^JlUS+UrTyYa1CRSbme&2Doa|9aYqS1q5rP=K6W@KOu`3L<2~ z&u-g6sAd!xe4dGmJ-D}>2f$alZ{Gn~D5X&d;N3jso^7J67BkNh&V>eaE3qco6(v$T z6gP5nvnRbt)0e?Au2ZnmE`ftUZA8wkWPQ^B@FHaWri3faKjQ%g={S@<#`u*P7}py~ ztMj)jtJa#*klOC+bcIzfNn#JJ+*jxTK~wc%#1-d!^k~!WQm60Dl7!#gliVprg*7e6 z3OEna4MUCz{7tdB)RqvxqnqRwoP3WmTNMiZ+qqC?St72mb#(87f@!Z|jPVJVYQgPJ z)7GGbNw+VnSk#1qiZ+YZ%VqfFF~AiUk<`kJzB*fi`a;Yi zRn(^@Ml;5n@n8)+Hpl!4K?AA;Wew&W0mT#o%bZ1e^^T+N^k{o(sa%2|Z|+WZxV*Q1 zGu{gd*}0v!LGPJpDU&kk@9*ry&rG?nTs-I}63%y9!y^*HA?a>KlH@G+uPxf$M*ePX zNyzXbl^eDnz=p55AO~p$;mrroT+3~m@IK~2kfH&0|GtdhR$KvRe~irLa@3{m;n&Xq z?-;765@grS-2Eq~Uo52h8j{b{_cGSlO?Fn|yabAl@e{}@R0CDL-xc=?*d|*-efXaW z)2DS_675S~YSwUqpf3;z7&cxNzlp^rvnuq0A4x3$RDLP54$k_%w5=PGd^J<=C^KJD zbuB`$;1;Jg!NH~|3@iGB_+7qV?uD`P$TzYMn9`Uh-owb_cU$_fT>~RMcYG{ zvHoHGK(|k;ioL>>EP5y#WFoxw)x5dHP{s)5O9EwAuC)e%jbE% zCq>6aXbd2%f=93EOYF+vjJ57^WiKYFF*k)c^06@u2OegsRw088!j(la4{$wE?p~YV>tKGO+#_ zuPyyGLzQ)!8Q<4qIzCjJW;aBmlHvDg&da?VbIvF4Dp8?ZGIoG8sXYEcqCARh+nAt2 zD)iK2K(w#`Gdm+zD(pVxiS}LN5VUL$xBKyg1A>X%oT@U(_dqt^>_Z&g>bCLOKFtw% zz9S`kJ1Hf%^W&Rr{5+4dM{dHX!Xp}DY8rq zQ<6+l-T;D867~C%G#*1>CUlTG*IX@D`t|bv9(~eo?|b}I`l`tUAys{NNme2JCu1Cz ztcp=Eu!7kqtoKgyWlZfiO1*WgWiRJjLU_~i67)>JzN!M^6tYbo-Dgj@3YFKNml=0R zmj5hE;y0_e9sKCadv8J3I$Y_;#QId4@27OKU-ml-9V!$IDBEv0X!s16Vk!3eb1mmY zUg)zIKg__{mGx7x!hiMNaD)nVi8|n%`eaVWo&5Kuxbx(_zldi6Kp@#~_g8u44{F5d z!?x5(ZhxBUFeMX!YJBRwB}|NM83q}e=%F02K5m1PXlck$>S7MSYpz@nyPU$8J(HwY z098^@?%%LQjB=^Kdw>K)@9U7lX>~A1v0a7#{YwyisW^x_xAF09>QnWn) z^+I~{F?rUF+A{qv4n?T7fhcdT%QL5H)6a#fn4o^+RI^vOK#g-|sau2$qrFyR z;p)N|9m`9}h?-N1u!5#H>=IjT{#ba-$KY!4x4HB_2{fsRT_GeKwD&%3E}Z--$7D;h zB31EqR?if=;7gc%YEc5YVOl!$-8K7>WUhybq>^^#58j>*CtV~h_BJpc;Vvcc17j}7 z)qANsWA|cfoV(WY_o=nGXI=9fPMxNm)9)J-G9X^%EfxRmfQ?@3@l%)au#~7B!g^Zl zW+onh)JMf=-)V9h3DaZ3RLo zRCb}`{|n&!Av}zEbG(#hsO_Dv*#~H{nwkXqk$bS^nasoC`}T?l;+Ywqszggx?E%Ro z8%Ey0flSEW4kP+tPDn=BPXaA}bw*@Zp|49YV&pRQ;I6%jLAxE}+7A;B^C(gv8PS%o zeqRskp1CU@ld=_cEitsC48(owh2(}aLGwb)@FZDsI1+YidZsf}7698yVNdgwaO?(X zyb7uI^-UeHx}nvET|4{M00;843gH&F8x=UKJvd&ZWY`5!Cs^vzu_w1t3tAvDjS@?R z@nu{U1g{#Gn{(=Z-dvq4wjx`2ayAyH6Vy?Q*w2w|7SW#(sI>ZQh%@8(id9xp)L|eJ zjZb3xqYz?A4wZiQg!q~sixlzp&&sb+1ZO7)B0rvX#OxO?brl5gnN4vsfqNvsk$cP} zfz4!@a!TmAv8KG((>rs4I5TwF`AmtWj0XwF`TWdu8dQY=xSXO1#68^j%ikUV+#|A& z+2gBli9NPo1FA+t7;+#76>mh`0YEPQi}(OPFb73{9a(6OU z2p=Mi?Qi*#?MAh{s_Bn==U9xqt5;NwykM03b$*Y^($)B!tR=9_gQ|eWRHHaI@|{%2tI1hV3sdC=sHSaF(sE6jUIz2ha7Ke|{mC zthB7UL{7Z9)o=*ZrOM1l=t~CP_OGPl{0IiHFxe(I^(dM2@lO^Wr03{C>xa^-=WTyC zrHe-?k5w6#-Q$#{effy4V@7h%l6ZC>8RI%bBmv?GE_9I*BOTGTAu-?&PvX-JV zQbTx{YFkV(V+UAwA*-onu__KQ>QaE@ zp8~2<12#UAJIBX-D6MK>ktfc?hi33?URFfH5{p@-9ajGSlBGcLlnchQzy2_$#Z%y~ z86LeDtPyWn$x}uc8DDr?QVE}iMy)&YS#M;SslE(R2lp`tk$m(bk$U+ScboasjVM*$j4o8i7zYTfR zX8l&vfnN6gHMU$EYic)sJnT?t)ETan_<^{YLWZ|(rg%RmQDxlVCoF>iPphaapejWjHp9^}&2AGQ_ z8U01wR4>X1S_vsA;AVG$w)W5WEr2#6CLw74fZwd{tE74Yoq#U;1h-$p zgYnHUd1n!pG_5G8L#-xMgjt{(ltM!(LGKJw$a$t|k9+bDC@r)PBdCl-uEQvm#SLW^4PM9USV|**p#k|Pn4pEfM+0{m$@J4cE6BN$m zqd`cXe^%xHXEn&rISCALE3n&rahdD0|D&b8Cr4RHXRdW(tkBjVfe zagOtliNH!zx=)JCe-||Zkjwq^omA=_hmnGBHS!e@aogACb|b!r7lspISKxu+)`Tzk z;^C)~E(m;Az++DfQ6p88+wytxDB~R|J_+5F*-bR#2SsSuRq4|f?+ZO8rSN+XSQJ7S zu&o8g{zeygQ>hhZ-yA7&7Dpe<9 zoZjHZ^lL>mgx8l>BAR35uJw&2boI1L%t|Vb%9v@y)62eW7+jrnat8Gcc5fHvXk`mKE=(&AXX3q z8eQd09>_^<-lH*jIlstq@|buOa)Ittv`HLLw@N6|Aiu@)1@HMi6dH9?WxV`haEfcB zV~pHK(K^Nc*u0RJvX}GwsSI}d23`EX)_y3dJl>`TUwnLPfT+=FN{9Ocdgpe=SOXCQ z{!->{8}x5j4!$lS3kyr7V0*&0tF;3Tz>L!YcF6c&KVRD$#1J>TA~L*Pj!m+s0Bu8~ zU&F2agcuoG!BQ9vg1k&X=7k*5fSM`D`sy8NJVAG$_vH5@0VBU{CcN9+>P2#qsZWm( z_p4WEcQoD{Y9*B|QTotTX~W|a;16?*=v+&yxFjd|HbNr^)TCX6-)d zke@hnM;COV{1u0P>OcL!gU|s7<)mc#xVr@$n3ghJXsBnJqYcngsOR{Qm;J13$$g>K z29SjFS$lt0S)A|%xV|(pAdCEUTP=RG&~<3yE}?^id(d=YJ@3M|1bQl3+LC24=K2Ue zz-^!2Ta){Da4glNBfa10&^XQU<9?oNwsv28K2@>w{cfl>cVReS zv7=nl(_i18Fa$A>E2#lO9c<`8wWc1sN*YE3llWw3;Tf|Vnylt8e+PKnx09zTU&FOH@jCY*D~(5A0~6UO18&fsfq>S zwgvJp#liL>A@~lXxmDatMH&=ORFOAOb1goOfT`E__S~Z7NoQQ$i>=2IFk`DbiU|T0 zNcihG{7KV00{+$WPUEdrg2i0J!8DnQ{*r88+N3~TBiRFr?hVGx&{V@ApdCY+STZ=H zTz`fsUV>hCO3+cmA{1MR`SZb=dq#)urPyfS6~6x2Y29T*?;5ELlt z82Pa`R!1mB56=<1vbX=YvSJeG^-9vq*sotzS>yur^~9kVbUwGx63Q7~ozn#M)L6|N zx{xomO0{!Y>g*Vi`|sF%3ZH>R;bYAGAwZgXZx-cZhYP*(U5}{w7#g_|OFnTT^vs|A z!T7UpS0<$ITSl?rh-1c2DK0J~Tj#eJ zfUNuy{qEkAzTKJTOqjJOX9!Tp8qHTDMhN>zaF^#6+yW0-|E+qtlQx65y zxyC&3~@V z?Pq@Jg6x}edn8X_x2b{Zf7=v<%rK@%O--HMix^A)wulvn%fXqiwNaT{+alR%9oSBG z87S1?*X^fcV-vLMO4i}lh{v@8H|oEo2?qGS|1C{u@cL4g@C{oqcYQ&N7IsPY4+*XaUX7yG1^ZIyG+vmw@mV=!I|+>o8A~Q znWJWa`zzPJe3(xl^mkM}n2_$3%lwzmF}-`wkN=iX2;17YOcWDozvWr3Ubbh!-hg~u z2YO3D)$RT^Z08gK`)SDxP0~fwc+`ZLzlXK>Y&>wu|Qh~f$GFPpB3%EC;PdY4#b zfu-9>64oN_JU?Zl16)M-4y!x%`23eTE^Uf&q6QhM_kLEIJ#j?OO3eyVc8RL|x_Rxi z=OxMPhsbvn4Pn9`S{24A+DMglnJezpV`pLb-$Rfgo7EENE|N&0F6fS4f;Ya~KTn!J z4TcDmgFQ(QOpLw@tdpRD5=hJclx{qht(OLA&J4}iN-36b>~bLRCl%=E1gZMfFo=tx zvKH@b;$Zn7NJqhLVX-J6cE5cpJvaA=5`FkEHaz^=R1IXQYUaCp-WO6H@Wvl`tbI{~ z1n%m$9zDUU4JZZkQ`Gk6TLjojqBn%F&L$)MU0^&e<`ej3{yz1udEeLtiGW$vn=LSu z0sVydU3(RKT8#GxZ0P;I8yF+R_Ln|KH1vy5C z2!16wG*s99eKHRM+f6$8vz~^)lFM&mjXK@u29PR&8x<54#B(38(Ww_nVus1l59Q^9 zkb)LXx)u+{2)<~h-gY-aj1{Q-Y7eZxF$%D-O-Z3>louX8ev1ShBUUQA{Rz13i!JWd zjXVe<@XkTXzKl=6_vcH%v-sZ=ShdpvKLA{3gI5UpP6SM$vuh?Zmv339KKv#%^$YRi z`Q2ZiIe`pwTGD2=VtVfDhRA$+VdekH@T*x14Co)H~h$5*&v*!P5)yT7mG zc`X1w%Rxs$+6;UaKeptSAoLm*%Z-FD`G*fFVqYET1dhw3XQ{aO4j4Pf#NX$DKZozY zp`orm8$V$L7@@@YKbj+X5bMO5me`yw!-J9tLgQHk)@6aGi4=Pv+`*xQ7#XV3hg298 z#mrs*z8C%&DbPl2ei;Iev=w`4QQOCn?_0-aA9Jm-r?mTjS7#DTL5ipRvIpiM0LocC zQ3Ifii6uf4nI69xn)3)r_|c zX^>jrIWE@f28scr1o4;H2~{DOD2|rc?iti=1R?#W>Wxc~m7hx>PY8!P55!dzuVd)= zj7ia)4?*^ZSma>XovAOqS6Is%`r?K7;qT!Du7@9f5%<0qHI>N$tVPmePC*cqC`7`z z!Hp`y@db7I1;+S9?6c2+LdH@z*tixY?^Y9@F6MIY8Q8Xx*-ILT!EX5@l9IN5n zFz==x;0p;e>n%2irGO6rhLaa$dwnSSEf;aIaX6;kp$mcw2NAZ@uL0viRU)!*`GuX1 zxC+Bhkz-@}da-v_v7n=<|9P1xl3THWJbDf69~buSLX1HyB2-gNF$7d0jFgQT(MUs%Fro27Y(n)YlV9Aj&j-49@Dir*uRE*ecKtKDKVvH@SlX zH>zuanDWb^UIZ@w@fbg8v-2buxZ~`grRL**U*_if_eh}mr)AK_At^}*QsqNUU3dBi zH)!zN4gYf%Clg7xY!YzUu2HMh!yZGV4%6f%R3p&_CSlm`24 z-(15U6?Oa}!B$?RiC+$Qs{2?Qr;+|<6}-~LjEx}dhc+WU775de5m{31vi-LIEbYO< zn?}yz&VwOyL+^LkQb)FoFEOan+_)voyzJrWS*sD{XnY9ltgpfSCV)pP0AvTYB&{3R znNOqG{=Zo3AQ-47g>}BnCJ&!sA%Pm$PYXPA2H+pCeNxpQRz*la4wi0*k?Hhb(*$