From 98cd2e3a4dfd9523c8137b4920c7384eb171d359 Mon Sep 17 00:00:00 2001 From: mathias31415 Date: Tue, 8 Apr 2025 14:35:27 +0200 Subject: [PATCH 01/33] 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 02/33] 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 03/33] 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 04/33] 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 05/33] =?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 06/33] 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 07/33] 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 08/33] 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 09/33] 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 10/33] 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 11/33] 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 12/33] 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 13/33] 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 14/33] 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 15/33] 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 16/33] 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 17/33] 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 18/33] 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 19/33] 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 20/33] 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 21/33] 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 22/33] 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 23/33] 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 24/33] 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 25/33] 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 26/33] 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 27/33] 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 28/33] 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 29/33] 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 30/33] 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 31/33] 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 32/33] 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 33/33] 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_)