From cd7da9a289261db480554d66e0ae4b2abc9ea52d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 8 Sep 2022 22:01:38 +0900 Subject: [PATCH 001/433] [complex_recovery] add complex_recovery package --- .../complex_recovery/CMakeLists.txt | 63 +++++++++++++++++++ .../complex_recovery_plugins.xml | 18 ++++++ .../concurrent_complex_recovery.h | 29 +++++++++ .../sequential_complex_recovery.h | 29 +++++++++ jsk_robot_common/complex_recovery/package.xml | 28 +++++++++ .../src/concurrent_complex_recovery.cpp | 43 +++++++++++++ .../src/sequential_complex_recovery.cpp | 43 +++++++++++++ 7 files changed, 253 insertions(+) create mode 100644 jsk_robot_common/complex_recovery/CMakeLists.txt create mode 100644 jsk_robot_common/complex_recovery/complex_recovery_plugins.xml create mode 100644 jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h create mode 100644 jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h create mode 100644 jsk_robot_common/complex_recovery/package.xml create mode 100644 jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp create mode 100644 jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt new file mode 100644 index 0000000000..e6f2eac773 --- /dev/null +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -0,0 +1,63 @@ +cmake_minimum_required(VERSION 3.0.2) +project(complex_recovery) + +add_compile_options(-std=c++11) + +find_package(catkin REQUIRED + COMPONENTS + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES complex_recovery + CATKIN_DEPENDS + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros +) + +# Abort if indigo or kinetic +if ( $ENV{ROS_DISTRO} STREQUAL "indigo" OR $ENV{ROS_DISTRO} STREQUAL "kinetic" ) + return() +endif() + +include_directories( + include + ${catkin_INCLUDE_DIRS} +) + +add_library(complex_recovery + src/sequential_complex_recovery.cpp + src/concurrent_complex_recovery.cpp +) +add_dependencies(complex_recovery + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(complex_recovery + ${catkin_LIBRARIES} +) + +install(TARGETS complex_recovery + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} + ) + +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" +) + +install(FILES complex_recovery_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml new file mode 100644 index 0000000000..7e703cd18b --- /dev/null +++ b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml @@ -0,0 +1,18 @@ + + + + A recovery behavior that runs other recovery behaviors sequentially. + + + + + A recovery behavior that runs other recovery behaviors concurrently. + + + diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h new file mode 100644 index 0000000000..03da70dced --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h @@ -0,0 +1,29 @@ +#ifndef COMPLEX_RECOVERY_H +#define COMPLEX_RECOVERY_H + +#include +#include +#include +#include + +namespace complex_recovery +{ + +class ConcurrentComplexRecovery : public nav_core::RecoveryBehavior +{ +public: + ConcurrentComplexRecovery(); + void initialize( + std::string name, + tf2_ros::Buffer*, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + void runBehavior(); + ~ConcurrentComplexRecovery(); + +private: + bool initialized_; +}; +}; + +#endif diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h new file mode 100644 index 0000000000..83ba5babc1 --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h @@ -0,0 +1,29 @@ +#ifndef COMPLEX_RECOVERY_H +#define COMPLEX_RECOVERY_H + +#include +#include +#include +#include + +namespace complex_recovery +{ + +class SequentialComplexRecovery : public nav_core::RecoveryBehavior +{ +public: + SequentialComplexRecovery(); + void initialize( + std::string name, + tf2_ros::Buffer*, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap); + void runBehavior(); + ~SequentialComplexRecovery(); + +private: + bool initialized_; +}; +}; + +#endif diff --git a/jsk_robot_common/complex_recovery/package.xml b/jsk_robot_common/complex_recovery/package.xml new file mode 100644 index 0000000000..126698a626 --- /dev/null +++ b/jsk_robot_common/complex_recovery/package.xml @@ -0,0 +1,28 @@ + + + complex_recovery + 1.1.0 + The complex_recovery package + + Koki Shinjo + Kei Okada + Koki Shinjo + + BSD + + + catkin + + costmap_2d + nav_core + pluginlib + roscpp + tf2 + tf2_ros + + rostest + + + + + diff --git a/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp new file mode 100644 index 0000000000..ba947e42d9 --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp @@ -0,0 +1,43 @@ +#include +#include + +PLUGINLIB_EXPORT_CLASS(complex_recovery::ConcurrentComplexRecovery, nav_core::RecoveryBehavior) + +namespace complex_recovery +{ + +ConcurrentComplexRecovery::ConcurrentComplexRecovery(): initialized_(false) +{ +} + +void ConcurrentComplexRecovery::initialize( + std::string name, + tf2_ros::Buffer*, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) +{ + if (not initialized_) { + ros::NodeHandle private_nh("~/" + name); + // DO SOMETHING + initialized_ = true; + } else { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +ConcurrentComplexRecovery::~ConcurrentComplexRecovery() +{ +} + +void ConcurrentComplexRecovery::runBehavior() +{ + if (not initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + // DO SOMETHING +} + +}; diff --git a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp new file mode 100644 index 0000000000..db675d0a0f --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp @@ -0,0 +1,43 @@ +#include +#include + +PLUGINLIB_EXPORT_CLASS(complex_recovery::SequentialComplexRecovery, nav_core::RecoveryBehavior) + +namespace complex_recovery +{ + +SequentialComplexRecovery::SequentialComplexRecovery(): initialized_(false) +{ +} + +void SequentialComplexRecovery::initialize( + std::string name, + tf2_ros::Buffer*, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) +{ + if (not initialized_) { + ros::NodeHandle private_nh("~/" + name); + // DO SOMETHING + initialized_ = true; + } else { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +SequentialComplexRecovery::~SequentialComplexRecovery() +{ +} + +void SequentialComplexRecovery::runBehavior() +{ + if (not initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + // DO SOMETHING +} + +}; From f57ce86ce4cf085e799ff5aa8258c0f2fda9649a Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 9 Sep 2022 09:56:43 +0900 Subject: [PATCH 002/433] [complex_recovery] implement sequential_complex_recovery --- .../complex_recovery/CMakeLists.txt | 1 + .../sequential_complex_recovery.h | 5 +- .../include/complex_recovery/utils.h | 21 ++++ .../src/sequential_complex_recovery.cpp | 23 +++- .../complex_recovery/src/utils.cpp | 108 ++++++++++++++++++ 5 files changed, 155 insertions(+), 3 deletions(-) create mode 100644 jsk_robot_common/complex_recovery/include/complex_recovery/utils.h create mode 100644 jsk_robot_common/complex_recovery/src/utils.cpp diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt index e6f2eac773..320874eb9d 100644 --- a/jsk_robot_common/complex_recovery/CMakeLists.txt +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -38,6 +38,7 @@ include_directories( add_library(complex_recovery src/sequential_complex_recovery.cpp src/concurrent_complex_recovery.cpp + src/utils.cpp ) add_dependencies(complex_recovery ${${PROJECT_NAME}_EXPORTED_TARGETS} diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h index 83ba5babc1..507e0ea0ab 100644 --- a/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/sequential_complex_recovery.h @@ -4,7 +4,7 @@ #include #include #include -#include +#include namespace complex_recovery { @@ -23,6 +23,9 @@ class SequentialComplexRecovery : public nav_core::RecoveryBehavior private: bool initialized_; + std::vector > recovery_behaviors_; + std::vector recovery_behavior_names_; + pluginlib::ClassLoader recovery_loader_; }; }; diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h new file mode 100644 index 0000000000..1bc3eda805 --- /dev/null +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h @@ -0,0 +1,21 @@ +#include +#include +#include +#include +#include + +namespace complex_recovery +{ + + +bool loadRecoveryBehaviors( + std::string parent_name, + ros::NodeHandle& node, + pluginlib::ClassLoader& recovery_loader, + std::vector > recovery_behaviors, + std::vector recovery_behavior_names, + tf2_ros::Buffer* ptr_tf_buffer, + costmap_2d::Costmap2DROS* ptr_global_costmap, + costmap_2d::Costmap2DROS* ptr_local_costmap + ); +}; diff --git a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp index db675d0a0f..1fb51c2375 100644 --- a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp +++ b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp @@ -1,4 +1,5 @@ #include +#include #include PLUGINLIB_EXPORT_CLASS(complex_recovery::SequentialComplexRecovery, nav_core::RecoveryBehavior) @@ -6,19 +7,32 @@ PLUGINLIB_EXPORT_CLASS(complex_recovery::SequentialComplexRecovery, nav_core::Re namespace complex_recovery { -SequentialComplexRecovery::SequentialComplexRecovery(): initialized_(false) +SequentialComplexRecovery::SequentialComplexRecovery(): + initialized_(false), + recovery_loader_("nav_core", "nav_core::RecoveryBehavior") { } void SequentialComplexRecovery::initialize( std::string name, - tf2_ros::Buffer*, + tf2_ros::Buffer* tf_buffer, costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap) { if (not initialized_) { ros::NodeHandle private_nh("~/" + name); // DO SOMETHING + bool success = loadRecoveryBehaviors( + name, + private_nh, + recovery_loader_, + recovery_behaviors_, + recovery_behavior_names_, + tf_buffer, + global_costmap, + local_costmap + ); + initialized_ = true; } else { ROS_ERROR("You should not call initialize twice on this object, doing nothing"); @@ -37,6 +51,11 @@ void SequentialComplexRecovery::runBehavior() return; } + for (auto index = 0; index < recovery_behaviors_.size(); index++) { + ROS_INFO("executing behavior %s", recovery_behavior_names_[index].c_str()); + recovery_behaviors_[index]->runBehavior(); + } + // DO SOMETHING } diff --git a/jsk_robot_common/complex_recovery/src/utils.cpp b/jsk_robot_common/complex_recovery/src/utils.cpp new file mode 100644 index 0000000000..745832b8df --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/utils.cpp @@ -0,0 +1,108 @@ +#include + +namespace complex_recovery +{ + +/** + * + * Almost copied from https://github.com/ros-planning/navigation/blob/47c9c629fc93e6c6bbcd3109eb2d5b55efce400d/move_base/src/move_base.cpp#L1019-L1102 + */ +bool loadRecoveryBehaviors( + std::string parent_name, + ros::NodeHandle& node, + pluginlib::ClassLoader& recovery_loader, + std::vector > recovery_behaviors, + std::vector recovery_behavior_names, + tf2_ros::Buffer* ptr_tf_buffer, + costmap_2d::Costmap2DROS* ptr_global_costmap, + costmap_2d::Costmap2DROS* ptr_local_costmap + ) +{ + XmlRpc::XmlRpcValue behavior_list; + if(node.getParam("recovery_behaviors", behavior_list)){ + if(behavior_list.getType() == XmlRpc::XmlRpcValue::TypeArray){ + for(int i = 0; i < behavior_list.size(); ++i){ + if(behavior_list[i].getType() == XmlRpc::XmlRpcValue::TypeStruct){ + if(behavior_list[i].hasMember("name") && behavior_list[i].hasMember("type")){ + //check for recovery behaviors with the same name + for(int j = i + 1; j < behavior_list.size(); j++){ + if(behavior_list[j].getType() == XmlRpc::XmlRpcValue::TypeStruct){ + if(behavior_list[j].hasMember("name") && behavior_list[j].hasMember("type")){ + std::string name_i = behavior_list[i]["name"]; + std::string name_j = behavior_list[j]["name"]; + if(name_i == name_j){ + ROS_ERROR("A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.", + name_i.c_str()); + return false; + } + } + } + } + } + else{ + ROS_ERROR("Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead."); + return false; + } + } + else{ + ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list[i].getType()); + return false; + } + } + + //if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors + for(int i = 0; i < behavior_list.size(); ++i){ + try{ + //check if a non fully qualified name has potentially been passed in + if(!recovery_loader.isClassAvailable(behavior_list[i]["type"])){ + std::vector classes = recovery_loader.getDeclaredClasses(); + for(unsigned int i = 0; i < classes.size(); ++i){ + if(behavior_list[i]["type"] == recovery_loader.getName(classes[i])){ + //if we've found a match... we'll get the fully qualified name and break out of the loop + ROS_WARN("Recovery behavior specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.", + std::string(behavior_list[i]["type"]).c_str(), classes[i].c_str()); + behavior_list[i]["type"] = classes[i]; + break; + } + } + } + + boost::shared_ptr behavior(recovery_loader.createInstance(behavior_list[i]["type"])); + + //shouldn't be possible, but it won't hurt to check + if(behavior.get() == NULL){ + ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. This should not happen"); + return false; + } + + //initialize the recovery behavior with its name + std::string base_name = behavior_list[i]["name"]; + behavior->initialize( + parent_name + "/" + base_name, + ptr_tf_buffer, ptr_global_costmap, ptr_local_costmap); + recovery_behavior_names.push_back(behavior_list[i]["name"]); + recovery_behaviors.push_back(behavior); + } + catch(pluginlib::PluginlibException& ex){ + ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what()); + return false; + } + } + } + else{ + ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.", + behavior_list.getType()); + return false; + } + } + else{ + //if no recovery_behaviors are specified, we'll just load the defaults + return false; + } + + //if we've made it here... we've constructed a recovery behavior list successfully + return true; +} + +}; From da0a7198ba5767022608d51592142bb90fc1fea5 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 9 Sep 2022 10:23:26 +0900 Subject: [PATCH 003/433] [complex_recovery] fix bugs --- .../complex_recovery/complex_recovery_plugins.xml | 8 ++++---- .../include/complex_recovery/utils.h | 4 ++-- .../src/sequential_complex_recovery.cpp | 12 ++++++++++-- jsk_robot_common/complex_recovery/src/utils.cpp | 4 ++-- 4 files changed, 18 insertions(+), 10 deletions(-) diff --git a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml index 7e703cd18b..6d7364a039 100644 --- a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml +++ b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml @@ -1,15 +1,15 @@ A recovery behavior that runs other recovery behaviors sequentially. A recovery behavior that runs other recovery behaviors concurrently. diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h index 1bc3eda805..a02ee51eec 100644 --- a/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/utils.h @@ -12,8 +12,8 @@ bool loadRecoveryBehaviors( std::string parent_name, ros::NodeHandle& node, pluginlib::ClassLoader& recovery_loader, - std::vector > recovery_behaviors, - std::vector recovery_behavior_names, + std::vector >& recovery_behaviors, + std::vector& recovery_behavior_names, tf2_ros::Buffer* ptr_tf_buffer, costmap_2d::Costmap2DROS* ptr_global_costmap, costmap_2d::Costmap2DROS* ptr_local_costmap diff --git a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp index 1fb51c2375..4000ba463d 100644 --- a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp +++ b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp @@ -32,6 +32,14 @@ void SequentialComplexRecovery::initialize( global_costmap, local_costmap ); + if ( not success ) { + ROS_ERROR("Failed to load behaviors."); + } else { + ROS_INFO("Behaviors are loaded."); + for (auto behavior_name = recovery_behavior_names_.begin(); behavior_name != recovery_behavior_names_.end(); behavior_name++) { + ROS_INFO("behavior: %s", behavior_name->c_str()); + } + } initialized_ = true; } else { @@ -41,6 +49,7 @@ void SequentialComplexRecovery::initialize( SequentialComplexRecovery::~SequentialComplexRecovery() { + recovery_behaviors_.clear(); } void SequentialComplexRecovery::runBehavior() @@ -51,12 +60,11 @@ void SequentialComplexRecovery::runBehavior() return; } + ROS_INFO("Start executing behaviors sequentially."); for (auto index = 0; index < recovery_behaviors_.size(); index++) { ROS_INFO("executing behavior %s", recovery_behavior_names_[index].c_str()); recovery_behaviors_[index]->runBehavior(); } - - // DO SOMETHING } }; diff --git a/jsk_robot_common/complex_recovery/src/utils.cpp b/jsk_robot_common/complex_recovery/src/utils.cpp index 745832b8df..660d91007f 100644 --- a/jsk_robot_common/complex_recovery/src/utils.cpp +++ b/jsk_robot_common/complex_recovery/src/utils.cpp @@ -11,8 +11,8 @@ bool loadRecoveryBehaviors( std::string parent_name, ros::NodeHandle& node, pluginlib::ClassLoader& recovery_loader, - std::vector > recovery_behaviors, - std::vector recovery_behavior_names, + std::vector >& recovery_behaviors, + std::vector& recovery_behavior_names, tf2_ros::Buffer* ptr_tf_buffer, costmap_2d::Costmap2DROS* ptr_global_costmap, costmap_2d::Costmap2DROS* ptr_local_costmap From b4f16b98e1b03767f5c41a621c206d6943d31e05 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 13 Sep 2022 13:50:42 +0900 Subject: [PATCH 004/433] [complex_recovery] rename concurrent to parallel --- .../complex_recovery/CMakeLists.txt | 2 +- .../complex_recovery_plugins.xml | 6 +- ...recovery.h => parallel_complex_recovery.h} | 11 ++-- .../src/concurrent_complex_recovery.cpp | 43 ------------ .../src/parallel_complex_recovery.cpp | 66 +++++++++++++++++++ 5 files changed, 77 insertions(+), 51 deletions(-) rename jsk_robot_common/complex_recovery/include/complex_recovery/{concurrent_complex_recovery.h => parallel_complex_recovery.h} (55%) delete mode 100644 jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp create mode 100644 jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt index 320874eb9d..a30e1f94dc 100644 --- a/jsk_robot_common/complex_recovery/CMakeLists.txt +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -37,7 +37,7 @@ include_directories( add_library(complex_recovery src/sequential_complex_recovery.cpp - src/concurrent_complex_recovery.cpp + src/parallel_complex_recovery.cpp src/utils.cpp ) add_dependencies(complex_recovery diff --git a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml index 6d7364a039..52d7a4b4d5 100644 --- a/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml +++ b/jsk_robot_common/complex_recovery/complex_recovery_plugins.xml @@ -8,11 +8,11 @@ - A recovery behavior that runs other recovery behaviors concurrently. + A recovery behavior that runs other recovery behaviors in parallel. diff --git a/jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h b/jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h similarity index 55% rename from jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h rename to jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h index 03da70dced..fc56d9c217 100644 --- a/jsk_robot_common/complex_recovery/include/complex_recovery/concurrent_complex_recovery.h +++ b/jsk_robot_common/complex_recovery/include/complex_recovery/parallel_complex_recovery.h @@ -9,20 +9,23 @@ namespace complex_recovery { -class ConcurrentComplexRecovery : public nav_core::RecoveryBehavior +class ParallelComplexRecovery : public nav_core::RecoveryBehavior { public: - ConcurrentComplexRecovery(); + ParallelComplexRecovery(); void initialize( std::string name, - tf2_ros::Buffer*, + tf2_ros::Buffer* tf_buffer, costmap_2d::Costmap2DROS* global_costmap, costmap_2d::Costmap2DROS* local_costmap); void runBehavior(); - ~ConcurrentComplexRecovery(); + ~ParallelComplexRecovery(); private: bool initialized_; + std::vector > recovery_behaviors_; + std::vector recovery_behavior_names_; + pluginlib::ClassLoader recovery_loader_; }; }; diff --git a/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp deleted file mode 100644 index ba947e42d9..0000000000 --- a/jsk_robot_common/complex_recovery/src/concurrent_complex_recovery.cpp +++ /dev/null @@ -1,43 +0,0 @@ -#include -#include - -PLUGINLIB_EXPORT_CLASS(complex_recovery::ConcurrentComplexRecovery, nav_core::RecoveryBehavior) - -namespace complex_recovery -{ - -ConcurrentComplexRecovery::ConcurrentComplexRecovery(): initialized_(false) -{ -} - -void ConcurrentComplexRecovery::initialize( - std::string name, - tf2_ros::Buffer*, - costmap_2d::Costmap2DROS* global_costmap, - costmap_2d::Costmap2DROS* local_costmap) -{ - if (not initialized_) { - ros::NodeHandle private_nh("~/" + name); - // DO SOMETHING - initialized_ = true; - } else { - ROS_ERROR("You should not call initialize twice on this object, doing nothing"); - } -} - -ConcurrentComplexRecovery::~ConcurrentComplexRecovery() -{ -} - -void ConcurrentComplexRecovery::runBehavior() -{ - if (not initialized_) - { - ROS_ERROR("This object must be initialized before runBehavior is called"); - return; - } - - // DO SOMETHING -} - -}; diff --git a/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp new file mode 100644 index 0000000000..bda15414d3 --- /dev/null +++ b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp @@ -0,0 +1,66 @@ +#include +#include +#include + +PLUGINLIB_EXPORT_CLASS(complex_recovery::ParallelComplexRecovery, nav_core::RecoveryBehavior) + +namespace complex_recovery +{ + +ParallelComplexRecovery::ParallelComplexRecovery(): + initialized_(false), + recovery_loader_("nav_core", "nav_core::RecoveryBehavior") +{ +} + +void ParallelComplexRecovery::initialize( + std::string name, + tf2_ros::Buffer* tf_buffer, + costmap_2d::Costmap2DROS* global_costmap, + costmap_2d::Costmap2DROS* local_costmap) +{ + if (not initialized_) { + ros::NodeHandle private_nh("~/" + name); + // DO SOMETHING + bool success = loadRecoveryBehaviors( + name, + private_nh, + recovery_loader_, + recovery_behaviors_, + recovery_behavior_names_, + tf_buffer, + global_costmap, + local_costmap + ); + if ( not success ) { + ROS_ERROR("Failed to load behaviors."); + } else { + ROS_INFO("Behaviors are loaded."); + for (auto behavior_name = recovery_behavior_names_.begin(); behavior_name != recovery_behavior_names_.end(); behavior_name++) { + ROS_INFO("behavior: %s", behavior_name->c_str()); + } + } + + initialized_ = true; + } else { + ROS_ERROR("You should not call initialize twice on this object, doing nothing"); + } +} + +ParallelComplexRecovery::~ParallelComplexRecovery() +{ + recovery_behaviors_.clear(); +} + +void ParallelComplexRecovery::runBehavior() +{ + if (not initialized_) + { + ROS_ERROR("This object must be initialized before runBehavior is called"); + return; + } + + // DO SOMETHING +} + +}; From 95113c999255f29adf3dd809e2c7f22f3ea96661 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 13 Sep 2022 14:03:01 +0900 Subject: [PATCH 005/433] [complex_recovery] implement ParallelComplexRecovery --- .../src/parallel_complex_recovery.cpp | 22 +++++++++++++++++-- .../src/sequential_complex_recovery.cpp | 3 ++- 2 files changed, 22 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp index bda15414d3..80425e0f1b 100644 --- a/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp +++ b/jsk_robot_common/complex_recovery/src/parallel_complex_recovery.cpp @@ -1,6 +1,7 @@ #include #include #include +#include PLUGINLIB_EXPORT_CLASS(complex_recovery::ParallelComplexRecovery, nav_core::RecoveryBehavior) @@ -21,7 +22,6 @@ void ParallelComplexRecovery::initialize( { if (not initialized_) { ros::NodeHandle private_nh("~/" + name); - // DO SOMETHING bool success = loadRecoveryBehaviors( name, private_nh, @@ -60,7 +60,25 @@ void ParallelComplexRecovery::runBehavior() return; } - // DO SOMETHING + std::vector> threads; + + ROS_INFO("Start executing behaviors in parallel."); + for (auto index = 0; index < recovery_behaviors_.size(); index++) { + ROS_INFO("start executing behavior %s", recovery_behavior_names_[index].c_str()); + threads.push_back( + std::shared_ptr( + new std::thread( + &nav_core::RecoveryBehavior::runBehavior, + recovery_behaviors_[index] + ))); + } + + ROS_INFO("Waiting for behaviors to finish."); + for (auto thread = threads.begin(); thread != threads.end(); thread++) { + (*thread)->join(); + } + + ROS_INFO("All behaviors have finished."); } }; diff --git a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp index 4000ba463d..4a71196ea1 100644 --- a/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp +++ b/jsk_robot_common/complex_recovery/src/sequential_complex_recovery.cpp @@ -21,7 +21,6 @@ void SequentialComplexRecovery::initialize( { if (not initialized_) { ros::NodeHandle private_nh("~/" + name); - // DO SOMETHING bool success = loadRecoveryBehaviors( name, private_nh, @@ -65,6 +64,8 @@ void SequentialComplexRecovery::runBehavior() ROS_INFO("executing behavior %s", recovery_behavior_names_[index].c_str()); recovery_behaviors_[index]->runBehavior(); } + + ROS_INFO("All behaviors have finished."); } }; From 6e6c94fc49bdc4a539bd44f29a02d076d725541c Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 13 Sep 2022 14:17:43 +0900 Subject: [PATCH 006/433] [complex_recovery] update README.md --- jsk_robot_common/complex_recovery/README.md | 15 +++++++++++++++ 1 file changed, 15 insertions(+) create mode 100644 jsk_robot_common/complex_recovery/README.md diff --git a/jsk_robot_common/complex_recovery/README.md b/jsk_robot_common/complex_recovery/README.md new file mode 100644 index 0000000000..00e334c646 --- /dev/null +++ b/jsk_robot_common/complex_recovery/README.md @@ -0,0 +1,15 @@ +# complex_recovery + +This package provides recovery behavior plugins which combines multi recoveries to one recovery behavior. +This is useful for assuring a set of recovery behavior to run at one time. + +There are two types of recoveries. One is to run multi recoveries sequentially and another is to run them in parallel. + +## complex_recovery/SequentialComplexRecovery + +TODO + +## complex_recovery/ParallelComplexRecovery + +TODO + From c36c770ccc10c728a16fa54fec8db64fa09a20d6 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 13 Sep 2022 14:20:40 +0900 Subject: [PATCH 007/433] [complex_recovery] Update README.md --- jsk_robot_common/complex_recovery/README.md | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/complex_recovery/README.md b/jsk_robot_common/complex_recovery/README.md index 00e334c646..d49032f88c 100644 --- a/jsk_robot_common/complex_recovery/README.md +++ b/jsk_robot_common/complex_recovery/README.md @@ -5,11 +5,12 @@ This is useful for assuring a set of recovery behavior to run at one time. There are two types of recoveries. One is to run multi recoveries sequentially and another is to run them in parallel. +![complex_recovery_diagrams](https://user-images.githubusercontent.com/9410362/189815175-a3265d23-01d4-4ae9-831c-b01aacad2872.png) + ## complex_recovery/SequentialComplexRecovery -TODO +* `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) ## complex_recovery/ParallelComplexRecovery -TODO - +* `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) From c5d74bf819455a8647124e9d3343b4d865263e31 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 16:33:26 +0900 Subject: [PATCH 008/433] [complex_recovery] update README.md --- jsk_robot_common/complex_recovery/README.md | 51 +++++++++++++++++++++ 1 file changed, 51 insertions(+) diff --git a/jsk_robot_common/complex_recovery/README.md b/jsk_robot_common/complex_recovery/README.md index d49032f88c..fc65f10920 100644 --- a/jsk_robot_common/complex_recovery/README.md +++ b/jsk_robot_common/complex_recovery/README.md @@ -11,6 +11,57 @@ There are two types of recoveries. One is to run multi recoveries sequentially a * `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) +Example configuration of `move_base` is like + +```yaml +recovery_behavior_enabled: true +recovery_behaviors: + - name: "speak_then_clear_costmap0" + type: "complex_recovery/SequentialComplexRecovery" +speak_then_clear_costmap0: + recovery_behaviors: + - name: "speak_and_wait0" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "clear_costmap0" + type: "clear_costmap_recovery/ClearCostmapRecovery" + speak_and_wait0: + speak_text: "I'm clearing costmap." + duration_wait: 5.0 + duration_timeout: 1.0 + sound_action: /sound_play + clear_costmap0: + reset_distance: 1.0 +``` + +In this case, `speak_and_clear_costmap0` recovery runs `speak_and_wait0` recovery first, then runs `clear_costmap0`. +So a robot speaks first and then clear its costmap. + ## complex_recovery/ParallelComplexRecovery * `~recovery_behaviors` (list of dictionaries which has `name` and `type` entries, default: None) + +Example configuration of `move_base` is like + +```yaml +recovery_behavior_enabled: true +recovery_behaviors: + - name: "speak_and_rotate_costmap0" + type: "complex_recovery/SequentialComplexRecovery" +speak_and_rotate_costmap0: + recovery_behaviors: + - name: "speak_and_wait0" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "rotate0" + type: "rotate_recovery/RotateRecovery" + speak_and_wait0: + speak_text: "I'm rotating." + duration_wait: 5.0 + duration_timeout: 1.0 + sound_action: /sound_play + rotate0: + sim_granularity: 0.017 + frequency: 20.0 +``` + +In this case, `speak_and_rotate_costmap0` recovery runs `speak_and_wait0` and `rotate0` simultaneously. +So a robot speaks during its rotation. From 6412229a556894a31ea277afcca93114f7a12e2e Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 16:33:51 +0900 Subject: [PATCH 009/433] [complex_recovery] update dependencies --- jsk_robot_common/complex_recovery/package.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_robot_common/complex_recovery/package.xml b/jsk_robot_common/complex_recovery/package.xml index 126698a626..0789a9e792 100644 --- a/jsk_robot_common/complex_recovery/package.xml +++ b/jsk_robot_common/complex_recovery/package.xml @@ -20,6 +20,10 @@ tf2 tf2_ros + speak_and_wait_recovery + clear_costmap_recovery + rotate_recovery + rostest From 4d98783ba6470f851a6b01ca0aa34c9bfc803454 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 18:42:14 +0900 Subject: [PATCH 010/433] [complex_recovery] add a test for SequentialComplexRecovery --- .../complex_recovery/CMakeLists.txt | 16 ++++++ .../tests/sequential_complex_recovery.test | 34 ++++++++++++ .../sequential_complex_recovery_test_node.cpp | 21 +++++++ .../tests/test_sequential_complex_recovery.py | 55 +++++++++++++++++++ 4 files changed, 126 insertions(+) create mode 100644 jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test create mode 100644 jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp create mode 100755 jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt index a30e1f94dc..43488cbd96 100644 --- a/jsk_robot_common/complex_recovery/CMakeLists.txt +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -62,3 +62,19 @@ install(DIRECTORY include/${PROJECT_NAME}/ install(FILES complex_recovery_plugins.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) + +# +# Testing +# +if (CATKIN_ENABLE_TESTING) + find_package(rostest REQUIRED) + + catkin_add_executable_with_gtest(sequential_complex_recovery_test_node + tests/sequential_complex_recovery_test_node.cpp + ) + target_link_libraries(sequential_complex_recovery_test_node + ${catkin_LIBRARIES} + ${PROJECT_NAME} + ) + add_rostest(tests/sequential_complex_recovery.test) +endif() diff --git a/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test new file mode 100644 index 0000000000..78bfd748f2 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery.test @@ -0,0 +1,34 @@ + + + + recovery: + recovery_behaviors: + - name: 'speak_and_wait0' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait1' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + speak_and_wait0: + speak_text: 'test0' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait1: + speak_text: 'test1' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + + + + + diff --git a/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp new file mode 100644 index 0000000000..618ff5656c --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/sequential_complex_recovery_test_node.cpp @@ -0,0 +1,21 @@ +#include +#include "complex_recovery/sequential_complex_recovery.h" + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "complex_recovery_simple_node"); + ros::NodeHandle nh; + + complex_recovery::SequentialComplexRecovery recovery; + recovery.initialize(std::string("recovery"),NULL,NULL,NULL); + + ros::Rate rate(10); + while (ros::ok()) { + ROS_WARN("Spoken a test"); + recovery.runBehavior(); + ros::spinOnce(); + rate.sleep(); + } + + return 0; +} diff --git a/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py b/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py new file mode 100755 index 0000000000..4dce3752b1 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/test_sequential_complex_recovery.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python + +from sound_play.msg import SoundRequestResult +from sound_play.msg import SoundRequestAction +import rospy +import actionlib +import threading +import sys +import unittest +import rostest + +PKG = 'complex_recovery' +NAME = 'sequential_complex_recovery_test' + + +class TestSequentialComplexRecovery(unittest.TestCase): + + def __init__(self, *args): + super(self.__class__, self).__init__(*args) + rospy.init_node(NAME) + + self.lock_for_msg = threading.Lock() + self.speech_text_list = [] + + self.action_server = \ + actionlib.SimpleActionServer( + '/sound_play', SoundRequestAction, execute_cb=self.handler, auto_start=False) + self.action_server.start() + + def handler(self, goal): + + with self.lock_for_msg: + self.speech_text_list.append(goal.sound_request.arg) + rospy.logwarn('Receive a message') + self.action_server.set_succeeded( + SoundRequestResult(playing=True, stamp=rospy.Time.now())) + + def test_sequential_complex_recovery(self): + + rate = rospy.Rate(1) + while not rospy.is_shutdown(): + with self.lock_for_msg: + if 'test0' in self.speech_text_list and 'test1' in self.speech_text_list: + break + else: + rospy.logwarn('waiting') + rate.sleep() + + with self.lock_for_msg: + rospy.logwarn('speech_text_list: {}'.format(self.speech_text_list)) + self.assertTrue('test0' in self.speech_text_list and 'test1' in self.speech_text_list) + + +if __name__ == '__main__': + rostest.rosrun(PKG, NAME, TestSequentialComplexRecovery, sys.argv) From e4897be534730656b185cc2ef0038d401970c35d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 18:47:30 +0900 Subject: [PATCH 011/433] [complex_recovery] add test for ParallelComplexRecovery --- .../complex_recovery/CMakeLists.txt | 9 +++ .../tests/parallel_complex_recovery.test | 34 ++++++++++++ .../parallel_complex_recovery_test_node.cpp | 21 +++++++ .../tests/test_parallel_complex_recovery.py | 55 +++++++++++++++++++ 4 files changed, 119 insertions(+) create mode 100644 jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test create mode 100644 jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp create mode 100755 jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt index 43488cbd96..daaf33657c 100644 --- a/jsk_robot_common/complex_recovery/CMakeLists.txt +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -77,4 +77,13 @@ if (CATKIN_ENABLE_TESTING) ${PROJECT_NAME} ) add_rostest(tests/sequential_complex_recovery.test) + + catkin_add_executable_with_gtest(parallel_complex_recovery_test_node + tests/parallel_complex_recovery_test_node.cpp + ) + target_link_libraries(parallel_complex_recovery_test_node + ${catkin_LIBRARIES} + ${PROJECT_NAME} + ) + add_rostest(tests/parallel_complex_recovery.test) endif() diff --git a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test new file mode 100644 index 0000000000..e302365713 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test @@ -0,0 +1,34 @@ + + + + recovery: + recovery_behaviors: + - name: 'speak_and_wait0' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait1' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + speak_and_wait0: + speak_text: 'test0' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait1: + speak_text: 'test1' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + + + + + diff --git a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp new file mode 100644 index 0000000000..3d54f9cad7 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery_test_node.cpp @@ -0,0 +1,21 @@ +#include +#include "complex_recovery/parallel_complex_recovery.h" + +int main(int argc, char **argv) +{ + ros::init(argc, argv, "complex_recovery_simple_node"); + ros::NodeHandle nh; + + complex_recovery::ParallelComplexRecovery recovery; + recovery.initialize(std::string("recovery"),NULL,NULL,NULL); + + ros::Rate rate(10); + while (ros::ok()) { + ROS_WARN("Spoken a test"); + recovery.runBehavior(); + ros::spinOnce(); + rate.sleep(); + } + + return 0; +} diff --git a/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py b/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py new file mode 100755 index 0000000000..8d7fea0de8 --- /dev/null +++ b/jsk_robot_common/complex_recovery/tests/test_parallel_complex_recovery.py @@ -0,0 +1,55 @@ +#!/usr/bin/env python + +from sound_play.msg import SoundRequestResult +from sound_play.msg import SoundRequestAction +import rospy +import actionlib +import threading +import sys +import unittest +import rostest + +PKG = 'complex_recovery' +NAME = 'parallel_complex_recovery_test' + + +class TestParallelComplexRecovery(unittest.TestCase): + + def __init__(self, *args): + super(self.__class__, self).__init__(*args) + rospy.init_node(NAME) + + self.lock_for_msg = threading.Lock() + self.speech_text_list = [] + + self.action_server = \ + actionlib.SimpleActionServer( + '/sound_play', SoundRequestAction, execute_cb=self.handler, auto_start=False) + self.action_server.start() + + def handler(self, goal): + + with self.lock_for_msg: + self.speech_text_list.append(goal.sound_request.arg) + rospy.logwarn('Receive a message') + self.action_server.set_succeeded( + SoundRequestResult(playing=True, stamp=rospy.Time.now())) + + def test_parallel_complex_recovery(self): + + rate = rospy.Rate(1) + while not rospy.is_shutdown(): + with self.lock_for_msg: + if 'test0' in self.speech_text_list and 'test1' in self.speech_text_list: + break + else: + rospy.logwarn('waiting') + rate.sleep() + + with self.lock_for_msg: + rospy.logwarn('speech_text_list: {}'.format(self.speech_text_list)) + self.assertTrue('test0' in self.speech_text_list and 'test1' in self.speech_text_list) + + +if __name__ == '__main__': + rostest.rosrun(PKG, NAME, TestParallelComplexRecovery, sys.argv) From c34290e8191936273609dfab6bb6a76710bfb263 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 18:47:47 +0900 Subject: [PATCH 012/433] [complex_recovery] update dependencies --- jsk_robot_common/complex_recovery/package.xml | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/jsk_robot_common/complex_recovery/package.xml b/jsk_robot_common/complex_recovery/package.xml index 0789a9e792..1892a9fc61 100644 --- a/jsk_robot_common/complex_recovery/package.xml +++ b/jsk_robot_common/complex_recovery/package.xml @@ -20,11 +20,9 @@ tf2 tf2_ros - speak_and_wait_recovery - clear_costmap_recovery - rotate_recovery - rostest + speak_and_wait_recovery + sound_play From eba9d2e2c01ba10e9ed7cb18c598d5831d07d7aa Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 14 Sep 2022 18:54:49 +0900 Subject: [PATCH 013/433] [complex_recovery] fix parallel test --- .../tests/parallel_complex_recovery.test | 50 +++++++++++++------ 1 file changed, 36 insertions(+), 14 deletions(-) diff --git a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test index e302365713..17dc02c20c 100644 --- a/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test +++ b/jsk_robot_common/complex_recovery/tests/parallel_complex_recovery.test @@ -7,20 +7,42 @@ recovery: recovery_behaviors: - - name: 'speak_and_wait0' - type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' - - name: 'speak_and_wait1' - type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' - speak_and_wait0: - speak_text: 'test0' - duration_wait: 2.0 - duration_timeout: 2.0 - result_timeout: 1.0 - speak_and_wait1: - speak_text: 'test1' - duration_wait: 2.0 - duration_timeout: 2.0 - result_timeout: 1.0 + - name: 'wait_and_speak_complex0' + type: 'complex_recovery/SequentialComplexRecovery' + - name: 'wait_and_speak_complex1' + type: 'complex_recovery/SequentialComplexRecovery' + wait_and_speak_complex0: + recovery_behaviors: + - name: 'wait_3_secs' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait0' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + wait_3_secs: + speak_text: '' + duration_wait: 3.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait0: + speak_text: 'test0' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 + wait_and_speak_complex1: + recovery_behaviors: + - name: 'wait_5_secs' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + - name: 'speak_and_wait1' + type: 'speak_and_wait_recovery/SpeakAndWaitRecovery' + wait_5_secs: + speak_text: '' + duration_wait: 5.0 + duration_timeout: 2.0 + result_timeout: 1.0 + speak_and_wait1: + speak_text: 'test1' + duration_wait: 2.0 + duration_timeout: 2.0 + result_timeout: 1.0 From ea9785b1569777b70ff02bed68ea59fe53700e20 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 15 Sep 2022 11:13:11 +0900 Subject: [PATCH 014/433] [complex_recovery] update minimum cmake version --- jsk_robot_common/complex_recovery/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/complex_recovery/CMakeLists.txt b/jsk_robot_common/complex_recovery/CMakeLists.txt index daaf33657c..7dd42684f9 100644 --- a/jsk_robot_common/complex_recovery/CMakeLists.txt +++ b/jsk_robot_common/complex_recovery/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.0.2) +cmake_minimum_required(VERSION 2.8.3) project(complex_recovery) add_compile_options(-std=c++11) From 6ed42303902d97e331494ed2fe99b74f354b74c3 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sat, 19 Oct 2019 02:37:48 +0900 Subject: [PATCH 015/433] add mux candidates for fetch coral images --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch index d8faf71fb8..198a504b64 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_tweet.launch @@ -1,11 +1,10 @@ - - + From 9294ac214e2759c82038dec9fdb4ba4c00cc9ce2 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sun, 20 Oct 2019 00:40:32 +0900 Subject: [PATCH 016/433] add video recorder --- .../apps/go_to_kitchen/go_to_kitchen.xml | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 81c75095b2..6fbbecf3c1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -1,5 +1,5 @@ - @@ -14,4 +14,12 @@ + + + + filename: /tmp/go_to_kitchen.avi + stamped_filename: false + fps: 15 + + From 873c3ad114d011b474c8b3f5f7f3671898f44444 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sun, 20 Oct 2019 05:55:44 +0900 Subject: [PATCH 017/433] save video file in xvid --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 6fbbecf3c1..06db9875b7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -18,6 +18,7 @@ filename: /tmp/go_to_kitchen.avi + codec: XVID stamped_filename: false fps: 15 From 71daff6498983fded9b61cfffa48191378987189 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 21 Oct 2019 23:25:24 +0900 Subject: [PATCH 018/433] save videos for go_to_kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.xml | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 06db9875b7..ff42dfbefc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -20,7 +20,16 @@ filename: /tmp/go_to_kitchen.avi codec: XVID stamped_filename: false - fps: 15 + fps: 5 + + + + + + filename: /tmp/go_to_kitchen_object_detection.avi + codec: XVID + stamped_filename: false + fps: 5 From 3dfe46de1d87de05ac3c75770e8f12e71f92b507 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Oct 2019 10:57:34 +0900 Subject: [PATCH 019/433] update fps --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index ff42dfbefc..0556f2c003 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -20,7 +20,7 @@ filename: /tmp/go_to_kitchen.avi codec: XVID stamped_filename: false - fps: 5 + fps: 30 @@ -29,7 +29,7 @@ filename: /tmp/go_to_kitchen_object_detection.avi codec: XVID stamped_filename: false - fps: 5 + fps: 7.5 From 9dc01dddfa69e556770127a452a0117313158db0 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Oct 2019 11:09:49 +0900 Subject: [PATCH 020/433] add ros-info and ros-error for logging --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 0556f2c003..493a0c80a9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -1,5 +1,5 @@ - From 6dfb98b920822ac8b2774fbc9bbb480c27899303 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 24 Oct 2019 17:07:08 +0900 Subject: [PATCH 021/433] record video throttled --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 493a0c80a9..4fc81b1cac 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -15,12 +15,12 @@ - + filename: /tmp/go_to_kitchen.avi codec: XVID stamped_filename: false - fps: 30 + fps: 5.0 From e2dd862b6813873614d0dcd35b63344024fecca5 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 1 Nov 2019 03:15:34 +0900 Subject: [PATCH 022/433] add mail notification in fetch go_to_kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.xml | 27 ++++++++++++++----- 1 file changed, 21 insertions(+), 6 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 4fc81b1cac..104880e930 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -1,6 +1,21 @@ + + + + + args="$(find jsk_fetch_startup)/euslisp/go-to-kitchen.l"> + + mail_notification: true + file_paths: + - $(arg video_path)/$(arg head_camera_video_title) + - $(arg video_path)/$(arg object_detection_video_title) + file_titles: + - $(arg head_camera_video_title) + - $(arg object_detection_video_title) + + + @@ -14,10 +29,10 @@ - + - - filename: /tmp/go_to_kitchen.avi + + filename: $(arg video_path)/$(arg head_camera_video_title) codec: XVID stamped_filename: false fps: 5.0 @@ -25,8 +40,8 @@ - - filename: /tmp/go_to_kitchen_object_detection.avi + + filename: $(arg video_path)/$(arg object_detection_video_title) codec: XVID stamped_filename: false fps: 7.5 From 9e6f054908e540412ea5acaa8192c7d6616efbb9 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 13 Feb 2020 13:38:03 +0100 Subject: [PATCH 023/433] add rosbag record for go_to_kitchen demo --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 104880e930..dbc949969b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -2,6 +2,7 @@ + @@ -10,9 +11,11 @@ file_paths: - $(arg video_path)/$(arg head_camera_video_title) - $(arg video_path)/$(arg object_detection_video_title) + - $(arg video_path)/$(arg rosbag_title) file_titles: - $(arg head_camera_video_title) - $(arg object_detection_video_title) + - $(arg rosbag_title) @@ -47,4 +50,8 @@ fps: 7.5 + + From 6cfca4b434706e4e7485b0d59306f130ed361388 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 28 Apr 2020 21:20:46 +0900 Subject: [PATCH 024/433] update fps --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index dbc949969b..47fef4971d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -47,7 +47,7 @@ filename: $(arg video_path)/$(arg object_detection_video_title) codec: XVID stamped_filename: false - fps: 7.5 + fps: 15.0 From 8f6d6e939b9988b95f65870b0f947307b34e00da Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 29 Apr 2020 01:29:28 +0900 Subject: [PATCH 025/433] use app_manager_plugin for mail and video recorder --- .../apps/go_to_kitchen/go_to_kitchen.xml | 42 +------------------ 1 file changed, 1 insertion(+), 41 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 47fef4971d..af52dd4e51 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -1,24 +1,6 @@ - - - - - - - mail_notification: true - file_paths: - - $(arg video_path)/$(arg head_camera_video_title) - - $(arg video_path)/$(arg object_detection_video_title) - - $(arg video_path)/$(arg rosbag_title) - file_titles: - - $(arg head_camera_video_title) - - $(arg object_detection_video_title) - - $(arg rosbag_title) - - - + args="$(find jsk_fetch_startup)/euslisp/go-to-kitchen.l" /> @@ -32,26 +14,4 @@ - - - - filename: $(arg video_path)/$(arg head_camera_video_title) - codec: XVID - stamped_filename: false - fps: 5.0 - - - - - - filename: $(arg video_path)/$(arg object_detection_video_title) - codec: XVID - stamped_filename: false - fps: 15.0 - - - - From 59cff4498419cba03cedc149ec58692e457375ed Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 21 May 2020 13:28:31 +0900 Subject: [PATCH 026/433] update rviz config --- jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz | 5 ----- 1 file changed, 5 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz index 6cb1fffa48..ab198412bf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz @@ -65,11 +65,6 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - base_camera_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false From 03b3d422f4549c8d525f553d9ff27f409a5445ca Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 24 Jun 2020 21:26:28 +0900 Subject: [PATCH 027/433] add rwt_image_view launch for fetch --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 996ee01797..f36426a191 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -110,6 +110,12 @@ + + + + + + From 3501336ec7285c2a46f5065eee7bd132a0c966b5 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 17 Sep 2020 16:12:16 +0900 Subject: [PATCH 028/433] re-enable object detection video with throttled rgb images --- .../apps/go_to_kitchen/go_to_kitchen.xml | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index af52dd4e51..b90f67e2e8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -14,4 +14,15 @@ + + + + + + approximate_sync: true + queue_size: 100 + use_classification_result: true + + From a64e509c80985660998d93339c86dff7b67506a7 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 15 Oct 2020 17:35:46 +0900 Subject: [PATCH 029/433] update jsk_fetch.rosinstall --- jsk_fetch_robot/jsk_fetch.rosinstall.indigo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.indigo b/jsk_fetch_robot/jsk_fetch.rosinstall.indigo index 189d65d616..3fc61d6285 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.indigo +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.indigo @@ -4,7 +4,7 @@ - git: local-name: PR2/app_manager uri: https://github.com/PR2/app_manager.git - version: kinetic-devel + version: knorth55/fetch15 - git: local-name: RobotWebTools/rosbridge_suite uri: https://github.com/RobotWebTools/rosbridge_suite.git From 0f8a63c38d1d00b8bfeffaa6c96691a07ca35ad7 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 23 Oct 2020 10:49:38 +0900 Subject: [PATCH 030/433] reduce resolution factor in go_to_kitchen classification result --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index b90f67e2e8..1e625bcc70 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -23,6 +23,7 @@ approximate_sync: true queue_size: 100 use_classification_result: true + resolution_factor: 1.0 From 37855e68a7e73ef23d3d880ef4865ab36eb3fc97 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Oct 2020 02:39:40 +0900 Subject: [PATCH 031/433] update jsk_fetch.rosinstall --- jsk_fetch_robot/jsk_fetch.rosinstall.indigo | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.indigo b/jsk_fetch_robot/jsk_fetch.rosinstall.indigo index 3fc61d6285..189d65d616 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.indigo +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.indigo @@ -4,7 +4,7 @@ - git: local-name: PR2/app_manager uri: https://github.com/PR2/app_manager.git - version: knorth55/fetch15 + version: kinetic-devel - git: local-name: RobotWebTools/rosbridge_suite uri: https://github.com/RobotWebTools/rosbridge_suite.git From c920b065ed51171292bb966e4a58239bb505fd43 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 1 Dec 2020 23:48:57 +0900 Subject: [PATCH 032/433] add warning args in user_speech_notifier plugin --- .../jsk_fetch_startup/apps/speak_battery/speak_battery.app | 1 + jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app | 1 + 2 files changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app index 0a48645098..cb4d371e00 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app @@ -8,6 +8,7 @@ plugins: type: app_notifier/user_speech_notifier_plugin plugin_args: client_name: /sound_play + warning: true plugin_order: start_plugin_order: - user_speech_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app index da0197d1b9..e95306664e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app @@ -8,6 +8,7 @@ plugins: type: app_notifier/user_speech_notifier_plugin plugin_args: client_name: /sound_play + warning: true plugin_order: start_plugin_order: - user_speech_notifier_plugin From c841a4aaf2a38ce79df8698ce73d4ac63095c151 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 9 Dec 2020 23:46:46 +0900 Subject: [PATCH 033/433] disable image logging in fetch because of cpu load --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index f685bdd841..7d630a5d66 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -20,8 +20,8 @@ - - + + From 5367d2a5d2aa90ebde996d9d66a01a3331023578 Mon Sep 17 00:00:00 2001 From: obinata Date: Wed, 2 Dec 2020 15:55:39 +0900 Subject: [PATCH 034/433] add arg for what to launch --- .../launch/fetch_bringup.launch | 40 ++++++++++++------- 1 file changed, 25 insertions(+), 15 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index f36426a191..fb73b4c552 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -13,6 +13,15 @@ + + + + + + + + + @@ -20,7 +29,7 @@ + respawn="true" output="screen" if="$(arg battery_warning)"> duration: 180 charge_level_threshold: 80.0 @@ -30,7 +39,7 @@ - + lang: japanese volume: 0.5 @@ -73,7 +82,7 @@ - + @@ -86,7 +95,7 @@ + args="--diag-hostname=my_machine" if="$(arg cpu_monitor)"> @@ -95,7 +104,7 @@ - + @@ -103,7 +112,7 @@ - + @@ -111,7 +120,7 @@ - + @@ -124,13 +133,14 @@ - + + - + - + interface_name: wlan0 @@ -138,15 +148,15 @@ + args="0 0 0.1 0 0 0 head_pan_link respeaker_base 100" if="$(use_speech_recognition)"/> - + - + @@ -156,7 +166,7 @@ - + tts_action_names: - sound_play @@ -168,7 +178,7 @@ + args="/network/connected 'm.data==False' /speech_to_text_julius" if="$(use_speech_recognition)"> default_select: speech_to_text_google From 9ea676d8914a885383683b541f695e676f773ce2 Mon Sep 17 00:00:00 2001 From: obinata Date: Wed, 2 Dec 2020 16:26:17 +0900 Subject: [PATCH 035/433] add more if elements --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index fb73b4c552..210c30504c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -15,9 +15,10 @@ - - + + + @@ -95,7 +96,7 @@ + args="--diag-hostname=my_machine" > @@ -112,7 +113,7 @@ - + @@ -120,13 +121,13 @@ - + - + From 6a29fcbddb1b7243e3781092686e357c5ee6cbe5 Mon Sep 17 00:00:00 2001 From: obinata Date: Wed, 2 Dec 2020 16:30:23 +0900 Subject: [PATCH 036/433] missing arg --- .../launch/fetch_bringup.launch | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 210c30504c..ff6b78922e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -83,7 +83,7 @@ - + @@ -139,9 +139,9 @@ - + - + interface_name: wlan0 @@ -149,15 +149,15 @@ + args="0 0 0.1 0 0 0 head_pan_link respeaker_base 100" if="$(arg use_speech_recognition)"/> - + - + @@ -167,7 +167,7 @@ - + tts_action_names: - sound_play @@ -179,7 +179,7 @@ + args="/network/connected 'm.data==False' /speech_to_text_julius" if="$(arg use_speech_recognition)"> default_select: speech_to_text_google From 5f6f17e372dee17592ebbfce4cb2362150c3eeeb Mon Sep 17 00:00:00 2001 From: jsk-fetchuser Date: Wed, 2 Dec 2020 19:00:38 +0900 Subject: [PATCH 037/433] add missing args --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index ff6b78922e..d7b506ff42 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -5,6 +5,7 @@ + @@ -23,6 +24,9 @@ + + + From 5e3456645b337f931a274537c2d54a9f366cab1d Mon Sep 17 00:00:00 2001 From: obinata Date: Thu, 10 Dec 2020 16:27:21 +0900 Subject: [PATCH 038/433] remove if tag some necessary nodes --- .../launch/fetch_bringup.launch | 81 +++++++++---------- 1 file changed, 40 insertions(+), 41 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index d7b506ff42..5fd2e74b38 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -17,15 +17,12 @@ - - - @@ -117,7 +114,7 @@ - + @@ -152,44 +149,46 @@ - - - - - - - - - - - - - - - - - - - - - tts_action_names: - - sound_play - - robotsound_jp - + + + + + + + + + + + + + + + + + + + + + + tts_action_names: + - sound_play + - robotsound_jp + + + + + + + + + default_select: speech_to_text_google + patient: 6 + + - - - - - - - default_select: speech_to_text_google - patient: 6 - - From b95d210092738685aebd3963c1e15a1763e38701 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 15 Dec 2020 00:20:14 +0900 Subject: [PATCH 039/433] move robot_localization in fetch.launch --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 1 - 1 file changed, 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 0bccd16208..72826157ec 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -31,7 +31,6 @@ - From 591a9a5f5c85b6741be73a9d2631904f3d8946da Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 9 Feb 2021 16:56:04 +0900 Subject: [PATCH 040/433] add timeout in go_to_kitchen --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index e81df30945..bf21da8e4a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -3,6 +3,7 @@ platform: fetch launch: jsk_fetch_startup/go_to_kitchen.xml interface: jsk_fetch_startup/go_to_kitchen.interface icon: jsk_fetch_startup/go_to_kitchen.png +timeout: 1200 plugins: - name: service_notification_saver_plugin type: app_notification_saver/service_notification_saver From 607d86d5ea89c68331ed94a8fb4de60c00f7eaac Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 8 Apr 2021 19:04:43 +0900 Subject: [PATCH 041/433] add jsk-object-detector and jsk-human-pose-estimator supervisor conf --- .../supervisor_scripts/jsk-human-pose-estimator.conf | 12 ++++++++++++ .../supervisor_scripts/jsk-object-detector.conf | 12 ++++++++++++ 2 files changed, 24 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf new file mode 100644 index 0000000000..fc8e36b63f --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -0,0 +1,12 @@ +[program:jsk-human-pose-estimator] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" + +stopsignal=TERM +directory=/home/fetch/ros/coral_ws +autostart=true +autorestart=false +stdout_logfile=/var/log/ros/jsk-human-pose-estimator.log +stderr_logfile=/var/log/ros/jsk-human-pose-estimator.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 +priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf new file mode 100644 index 0000000000..91625c3b04 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -0,0 +1,12 @@ +[program:jsk-object-detector] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" + +stopsignal=TERM +directory=/home/fetch/ros/coral_ws +autostart=true +autorestart=false +stdout_logfile=/var/log/ros/jsk-object-detector.log +stderr_logfile=/var/log/ros/jsk-object-detector.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 +priority=200 From f76a7aa3a2ed27962e56940bfc3648a877f1c54a Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 8 Apr 2021 19:05:32 +0900 Subject: [PATCH 042/433] update tmuxinator log yaml --- jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 5f2e1d51bf..0e0b53ad62 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -37,7 +37,9 @@ windows: - jsk-network-monitor: tail -f -n 1000 /var/log/ros/jsk-network-monitor.log - jsk-log-wifi: tail -f -n 1000 /var/log/ros/jsk-log-wifi.log - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log - - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log + # - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log + - jsk-object-detector: tail -f -n 1000 /var/log/ros/jsk-object-detector.log + - jsk-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-human-pose-estimator.log - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log From 346f2a1040bc99a248739b2df803166633a98347 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 21 Apr 2021 16:53:09 +0900 Subject: [PATCH 043/433] Add cron install scripts --- .../jsk_fetch_startup/config/install_cron.sh | 15 +++++++++++++++ .../cron_scripts/cron_fetch.conf | 1 + .../jsk_fetch_startup/cron_scripts/cron_root.conf | 1 + 3 files changed, 17 insertions(+) create mode 100755 jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh create mode 100644 jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf create mode 100644 jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh new file mode 100755 index 0000000000..186b8dc4cc --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_cron.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +jsk_fetch_startup=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`"/.. > /dev/null && pwd) + +IFS=':' read -r -a prefix_paths <<< "$CMAKE_PREFIX_PATH" +current_prefix_path="${prefix_paths[0]}" + +set -x + +cd $jsk_fetch_startup/cron_scripts +sudo -u fetch crontab cron_fetch.conf +echo "Set cron jobs for fetch user" +sudo -u root crontab cron_root.conf +echo "Set cron jobs for root user" +set +x diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf new file mode 100644 index 0000000000..2013454792 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf @@ -0,0 +1 @@ +0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh > /home/fetch/ros/melodic/update_workspace.log" diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf new file mode 100644 index 0000000000..da33972f7e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_root.conf @@ -0,0 +1 @@ +0 4 * * * /sbin/shutdown -r now From 38ae1d72fcbc492eeda24e0409bc3d18d221cc3d Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 21 Apr 2021 17:03:13 +0900 Subject: [PATCH 044/433] Redirect both standard output and standard error --- jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf index 2013454792..839bc9e138 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf @@ -1 +1 @@ -0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh > /home/fetch/ros/melodic/update_workspace.log" +0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh &> /home/fetch/ros/melodic/update_workspace.log" From bac2726f176b1e9ee2f06d4f7464ebfae16ef130 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 30 Apr 2021 01:09:45 +0900 Subject: [PATCH 045/433] Log dstat output --- .../supervisor_scripts/jsk-dstat.conf | 11 +++++++++++ 1 file changed, 11 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf new file mode 100644 index 0000000000..7ad426da83 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -0,0 +1,11 @@ +; Install dstat +; sudo apt install dstat +[program:jsk-dstat] +command=/bin/bash -c "dstat -tcdgilmnprsTy" +stopsignal=TERM +autostart=true +autorestart=false +stdout_logfile=/var/log/ros/jsk-dstat.log +stderr_logfile=/var/log/ros/jsk-dstat.log +user=root +priority=1 From 933714b6e4536e606c2c26da6b3e02c153f8834f Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 5 May 2021 11:23:43 +0900 Subject: [PATCH 046/433] Remove duplicated supervisor job --- .../supervisor_scripts/jsk-coral.conf | 11 ----------- 1 file changed, 11 deletions(-) delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf deleted file mode 100644 index d7cf1778cf..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-coral.conf +++ /dev/null @@ -1,11 +0,0 @@ -[program:jsk-coral] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt --screen --wait" -stopsignal=TERM -directory=/home/fetch/ros/coral_ws -autostart=true -autorestart=false -stdout_logfile=/var/log/ros/jsk-coral.log -stderr_logfile=/var/log/ros/jsk-coral.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 From 8e182d2ba8820fb11c9a1200b43f5ee6f9a69052 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 6 May 2021 22:25:05 +0900 Subject: [PATCH 047/433] Show more CPU info in dstat output --- .../jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf index 7ad426da83..b6e61e99c7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -1,7 +1,7 @@ ; Install dstat ; sudo apt install dstat [program:jsk-dstat] -command=/bin/bash -c "dstat -tcdgilmnprsTy" +command=/bin/bash -c "dstat -tl --cpufreq -c -C all --top-cpu-adv -dgimnprsTy" stopsignal=TERM autostart=true autorestart=false From 318631182ba96259260b2cc71e77f449d9ad7aa1 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 12 May 2021 19:17:49 +0900 Subject: [PATCH 048/433] Check if voice_text is installed or not --- .../jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 5292717154..b0553995f0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true use_voice_text:=false --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From e9bc2ab5a22b414d080673a903326ad8c13a4a53 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 13 May 2021 14:29:22 +0900 Subject: [PATCH 049/433] Throttle insta360 image to reduce dual_fisheye_to_panorama CPU load --- .../jsk_fetch_startup/launch/fetch_insta360_melodic.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch index c94523f778..c8af2a9b22 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch @@ -8,6 +8,7 @@ + From 4705fd06341735ce5a254bbd8088585a530488ae Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 18 May 2021 21:31:31 +0900 Subject: [PATCH 050/433] add tweet_image_server for non-euslisp users --- .../jsk_robot_startup/lifelog/tweet.launch | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch b/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch index b22b0d066c..827bef6832 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet.launch @@ -27,12 +27,21 @@ output="$(arg output)" respawn="true" > + + + account_info: $(arg account_info) + + + + + Date: Tue, 18 May 2021 22:31:33 +0900 Subject: [PATCH 051/433] add tweet notifier in go_to_kitchen and time_signal --- .../apps/go_to_kitchen/go_to_kitchen.app | 8 ++++++++ .../jsk_fetch_startup/apps/time_signal/time_signal.app | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index bf21da8e4a..d1fe0dbd9d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -105,6 +105,12 @@ plugins: - go_to_kitchen_rosbag.bag upload_parents_path: fetch_go_to_kitchen upload_server_name: /gdrive_server + - name: tweet_notifier_plugin + type: app_notifier/tweet_notifier_plugin + plugin_args: + client_name: /tweet_image_server/tweet + image: true + image_topic_name: /edgetpu_object_detector/output/image - name: speech_notifier_plugin type: app_notifier/speech_notifier_plugin plugin_args: @@ -144,6 +150,7 @@ plugin_order: - rosbag_recorder_plugin - result_recorder_plugin - gdrive_uploader_plugin + - tweet_notifier_plugin - speech_notifier_plugin - mail_notifier_plugin - shutdown_plugin @@ -158,6 +165,7 @@ plugin_order: - rosbag_recorder_plugin - result_recorder_plugin - gdrive_uploader_plugin + - tweet_notifier_plugin - speech_notifier_plugin - mail_notifier_plugin - shutdown_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index d1c5e17227..d30b535da4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -5,6 +5,12 @@ interface: jsk_fetch_startup/time_signal.interface icon: jsk_fetch_startup/time_signal.png timeout: 10 plugins: + - name: tweet_notifier_plugin + type: app_notifier/tweet_notifier_plugin + plugin_args: + client_name: /tweet_image_server/tweet + image: true + image_topic_name: /edgetpu_object_detector/output/image - name: user_speech_notifier_plugin type: app_notifier/user_speech_notifier_plugin plugin_args: @@ -12,6 +18,8 @@ plugins: warning: false plugin_order: start_plugin_order: + - tweet_notifier_plugin - user_speech_notifier_plugin stop_plugin_order: + - tweet_notifier_plugin - user_speech_notifier_plugin From c89289090462c772178e59b2b3d5871ff0404113 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 18 May 2021 23:07:08 +0900 Subject: [PATCH 052/433] set warning param for tweet notifier plugin --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 1 + .../jsk_fetch_startup/apps/time_signal/time_signal.app | 1 + 2 files changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index d1fe0dbd9d..0ce091344e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -111,6 +111,7 @@ plugins: client_name: /tweet_image_server/tweet image: true image_topic_name: /edgetpu_object_detector/output/image + warning: false - name: speech_notifier_plugin type: app_notifier/speech_notifier_plugin plugin_args: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index d30b535da4..23b6e46481 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -11,6 +11,7 @@ plugins: client_name: /tweet_image_server/tweet image: true image_topic_name: /edgetpu_object_detector/output/image + warning: false - name: user_speech_notifier_plugin type: app_notifier/user_speech_notifier_plugin plugin_args: From f72217a55653744698806c6ba632f53d5f66148f Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 20 May 2021 22:39:15 +0900 Subject: [PATCH 053/433] Save dstat output in csv format --- .../jsk_fetch_startup/config/install_supervisor.sh | 3 +++ .../jsk_fetch_startup/scripts/dstat.bash | 14 ++++++++++++++ .../supervisor_scripts/jsk-dstat.conf | 2 +- 3 files changed, 18 insertions(+), 1 deletion(-) create mode 100755 jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index d07fbfb529..6d12834900 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -20,4 +20,7 @@ if [ ! -e /var/lib/robot/config.bash ]; then sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash fi +# Enable jsk_dstat job to save the csv log under /var/log +ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk_dstat.csv + set +x diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash b/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash new file mode 100755 index 0000000000..440237145e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/dstat.bash @@ -0,0 +1,14 @@ +#!/usr/bin/env bash + +# Keep only the last 1000 lines of csv log before executing dstat +CSV_FILE=/home/fetch/Documents/jsk_dstat.csv + +if [ -e $CSV_FILE ]; then + cp -f $CSV_FILE $CSV_FILE.bk + tail -n 1000 $CSV_FILE.bk > $CSV_FILE + rm -f $CSV_FILE.bk +else + touch $CSV_FILE +fi + +dstat -tl --cpufreq -c -C all --top-cpu-adv -dgimnprsTy --output $CSV_FILE diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf index b6e61e99c7..4fcf56a3e3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -1,7 +1,7 @@ ; Install dstat ; sudo apt install dstat [program:jsk-dstat] -command=/bin/bash -c "dstat -tl --cpufreq -c -C all --top-cpu-adv -dgimnprsTy" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup dstat.bash" stopsignal=TERM autostart=true autorestart=false From b0372851bc9695e40059f9cef1d3928bbdc738e9 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sun, 23 May 2021 23:35:15 +0900 Subject: [PATCH 054/433] update jsk-gdrive.conf --- .../jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index a79cc1deb3..dc30c03ea9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,5 +1,5 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch gdrive_ros gdrive_server.launch --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 1f48c3fafdfd7eefea04623a6c145991d806ea54 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 25 May 2021 21:56:45 +0900 Subject: [PATCH 055/433] Show jsk_dstat.log in 'tmuxinator log' --- jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 0e0b53ad62..3a6121e041 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -44,3 +44,4 @@ windows: - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log + - jsk-dstat: tail -f -n 1000 /var/log/ros/jsk-dstat.log From a107604d90a5d244a7a89ff064e9effd16b0e7f9 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 2 Jun 2021 20:49:28 +0900 Subject: [PATCH 056/433] Fix typo --- jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index 6d12834900..60878b5a97 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -21,6 +21,6 @@ if [ ! -e /var/lib/robot/config.bash ]; then fi # Enable jsk_dstat job to save the csv log under /var/log -ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk_dstat.csv +ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv set +x From e6ed4ac583499d439add09dcb24c7f05fa1745d5 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 3 Jun 2021 18:54:13 +0900 Subject: [PATCH 057/433] enable dialogflow webhook on fetch default --- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 581d4d8f87..8e8aa85903 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch dialogflow_task_executive dialogflow_task_executive.launch run_app_manager:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch dialogflow_task_executive dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From aad0d95e01dff183c81cf6341d383e194a885123 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 12:59:24 +0900 Subject: [PATCH 058/433] Add supervisor job for edgetpu-panorama recognition --- .../jsk-human-pose-estimator.conf | 1 + .../supervisor_scripts/jsk-object-detector.conf | 1 + .../jsk-panorama-human-pose-estimator.conf | 13 +++++++++++++ .../jsk-panorama-object-detector.conf | 13 +++++++++++++ 4 files changed, 28 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index fc8e36b63f..8021ee6ce4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -3,6 +3,7 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/cor stopsignal=TERM directory=/home/fetch/ros/coral_ws +; You can set "autostart=true" if "autostart=false" in jsk-panorama-human-pose-estimator.conf autostart=true autorestart=false stdout_logfile=/var/log/ros/jsk-human-pose-estimator.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index 91625c3b04..2e8e147a9e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -3,6 +3,7 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/cor stopsignal=TERM directory=/home/fetch/ros/coral_ws +; You can set "autostart=true" if "autostart=false" in jsk-panorama-object-detector.conf autostart=true autorestart=false stdout_logfile=/var/log/ros/jsk-object-detector.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf new file mode 100644 index 0000000000..48b3abb4c5 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -0,0 +1,13 @@ +[program:jsk-panorama-human-pose-estimator] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch namespace:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/output device_id:=0 --screen --wait" + +stopsignal=TERM +directory=/home/fetch/ros/coral_ws +; You can set "autostart=true" if "autostart=false" in jsk-human-pose-estimator.conf +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-panorama-human-pose-estimator.log +stderr_logfile=/var/log/ros/jsk-panorama-human-pose-estimator.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 +priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf new file mode 100644 index 0000000000..5c68ad54a8 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -0,0 +1,13 @@ +[program:jsk-panorama-object-detector] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch namespace:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" + +stopsignal=TERM +directory=/home/fetch/ros/coral_ws +; You can set "autostart=true" if "autostart=false" in jsk-object-detector.conf +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-panorama-object-detector.log +stderr_logfile=/var/log/ros/jsk-panorama-object-detector.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 +priority=200 From afa5c3b472e045ccc8b26c21e420da84ff9f47bb Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 14:00:44 +0900 Subject: [PATCH 059/433] Add tmuxinator config for edgetpu_panorama jobs --- jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 3a6121e041..7b4cc539a8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -39,7 +39,9 @@ windows: - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log # - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log - jsk-object-detector: tail -f -n 1000 /var/log/ros/jsk-object-detector.log + - jsk-panorama-object-detector: tail -f -n 1000 /var/log/ros/jsk-panorama-object-detector.log - jsk-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-human-pose-estimator.log + - jsk-panorama-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-panorama-human-pose-estimator.log - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log From e3e045037c37728e51133ecbe0551c698f85526a Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 14:27:48 +0900 Subject: [PATCH 060/433] Input quater panorama images to edgetpu node --- .../supervisor_scripts/jsk-panorama-human-pose-estimator.conf | 2 +- .../supervisor_scripts/jsk-panorama-object-detector.conf | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index 48b3abb4c5..a8a897c9ae 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,5 +1,5 @@ [program:jsk-panorama-human-pose-estimator] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch namespace:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch namespace:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index 5c68ad54a8..01209aefbf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,5 +1,5 @@ [program:jsk-panorama-object-detector] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch namespace:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch namespace:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM directory=/home/fetch/ros/coral_ws From 097810dc008e685c0c9082fa0c624936fef269ea Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 14:31:03 +0900 Subject: [PATCH 061/433] Record edgetpu panorama image visualized by coral_usb_ros instead of jsk_perception --- .../apps/go_to_kitchen/go_to_kitchen.app | 2 +- .../apps/go_to_kitchen/go_to_kitchen.xml | 12 ------------ 2 files changed, 1 insertion(+), 13 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 0ce091344e..65327b063f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -29,7 +29,7 @@ plugins: launch_args: video_path: /tmp video_title: go_to_kitchen_object_detection.avi - video_topic_name: /edgetpu_object_detector_visualization/output + video_topic_name: /edgetpu_object_detector/output/image video_fps: 5.0 - name: panorama_video_recorder_plugin type: app_recorder/video_recorder_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 1e625bcc70..af52dd4e51 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -14,16 +14,4 @@ - - - - - - approximate_sync: true - queue_size: 100 - use_classification_result: true - resolution_factor: 1.0 - - From f149849cdaf4c2cc64ecc4a4cc5d7d0c62aad9ab Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 14:50:00 +0900 Subject: [PATCH 062/433] Change object detector score threshold in go-to-kitchen --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index af52dd4e51..fff5a42682 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -14,4 +14,8 @@ + + + From 60cf8410d5c848881827f68773913e97927e1f3a Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 19:58:25 +0900 Subject: [PATCH 063/433] Fix launch arg name based on coral_usb_ros update --- .../supervisor_scripts/jsk-panorama-human-pose-estimator.conf | 2 +- .../supervisor_scripts/jsk-panorama-object-detector.conf | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index a8a897c9ae..48b5fc4dc3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,5 +1,5 @@ [program:jsk-panorama-human-pose-estimator] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch namespace:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index 01209aefbf..434ab2fe48 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,5 +1,5 @@ [program:jsk-panorama-object-detector] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch namespace:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM directory=/home/fetch/ros/coral_ws From 4f2df3a548d541390b371d930b9edf221e36c8b9 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 20:48:22 +0900 Subject: [PATCH 064/433] Use audio_video_recorder_plugin to record edgetpu_object_detector output --- .../apps/go_to_kitchen/go_to_kitchen.app | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 65327b063f..a7aacf6f3a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -25,12 +25,20 @@ plugins: video_framerate: 30 video_encoding: RGB - name: object_detection_video_recorder_plugin - type: app_recorder/video_recorder_plugin + type: app_recorder/audio_video_recorder_plugin launch_args: video_path: /tmp video_title: go_to_kitchen_object_detection.avi + audio_topic_name: /audio + audio_channels: 1 + audio_sample_rate: 16000 + audio_format: wave + audio_sample_format: S16LE video_topic_name: /edgetpu_object_detector/output/image - video_fps: 5.0 + video_height: 480 + video_width: 640 + video_framerate: 10 + video_encoding: RGB - name: panorama_video_recorder_plugin type: app_recorder/video_recorder_plugin launch_args: From d505ba7ae92ca05d14614c3fe6fbc15656fb7650 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 3 Jun 2021 22:49:34 +0900 Subject: [PATCH 065/433] Update go-to-kitchen demo --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index fff5a42682..75d3b9832d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -16,6 +16,6 @@ - + From 1993b7086eae1d5cd870cc2f186fe76e5340a052 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 11 Jun 2021 12:08:15 +0900 Subject: [PATCH 066/433] set longer timeout for time signal --- .../jsk_fetch_startup/apps/time_signal/time_signal.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index 23b6e46481..07c42622d4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -3,7 +3,7 @@ platform: fetch launch: jsk_fetch_startup/time_signal.xml interface: jsk_fetch_startup/time_signal.interface icon: jsk_fetch_startup/time_signal.png -timeout: 10 +timeout: 120 plugins: - name: tweet_notifier_plugin type: app_notifier/tweet_notifier_plugin From bc5d2e3d977edd10bc244b2f63a77cbc034bcc7b Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 17 Jun 2021 19:04:00 +0900 Subject: [PATCH 067/433] Turn on/off switchbots from switchbot_ros API --- jsk_fetch_robot/jsk_fetch_startup/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index a89d0c4dea..7b40053990 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -29,6 +29,7 @@ pr2_computer_monitor robot_pose_publisher rviz + switchbot_ros tf touchegg sound_play From a20df81399b00221c9bc9f238ed95f795d9d8c5d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sat, 19 Jun 2021 19:57:38 +0900 Subject: [PATCH 068/433] record rviz video in kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.app | 11 +++++++++++ .../apps/go_to_kitchen/go_to_kitchen.xml | 7 +++++++ 2 files changed, 18 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index a7aacf6f3a..f2d6f083bd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -46,6 +46,13 @@ plugins: video_title: go_to_kitchen_panorama.avi video_topic_name: /dual_fisheye_to_panorama/output video_fps: 1.0 + - name: rviz_video_recorder_plugin + type: app_recorder/video_recorder_plugin + launch_args: + video_path: /tmp + video_title: go_to_kitchen_rviz.avi + video_topic_name: /rviz/image + video_fps: 30.0 - name: respeaker_audio_recorder_plugin type: app_recorder/audio_recorder_plugin launch_args: @@ -102,6 +109,7 @@ plugins: - /tmp/go_to_kitchen_head_camera.avi - /tmp/go_to_kitchen_object_detection.avi - /tmp/go_to_kitchen_panorama.avi + - /tmp/go_to_kitchen_rviz.avi - /tmp/go_to_kitchen_audio.wav - /tmp/go_to_kitchen_rosbag.bag upload_file_titles: @@ -109,6 +117,7 @@ plugins: - go_to_kitchen_head_camera.avi - go_to_kitchen_object_detection.avi - go_to_kitchen_panorama.avi + - go_to_kitchen_rviz.avi - go_to_kitchen_audio.wav - go_to_kitchen_rosbag.bag upload_parents_path: fetch_go_to_kitchen @@ -155,6 +164,7 @@ plugin_order: - head_camera_video_recorder_plugin - object_detection_video_recorder_plugin - panorama_video_recorder_plugin + - rviz_video_recorder_plugin - respeaker_audio_recorder_plugin - rosbag_recorder_plugin - result_recorder_plugin @@ -170,6 +180,7 @@ plugin_order: - head_camera_video_recorder_plugin - object_detection_video_recorder_plugin - panorama_video_recorder_plugin + - rviz_video_recorder_plugin - respeaker_audio_recorder_plugin - rosbag_recorder_plugin - result_recorder_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 75d3b9832d..60d62199ec 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -18,4 +18,11 @@ args="set_from_parameters edgetpu_object_detector"> + + + + + + From 50bda1542ec7d8850c73fde36701c574c4f2b989 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 15 Jul 2021 19:08:04 +0900 Subject: [PATCH 069/433] Seperate fetch15 move_base param and fetch1075 move_base param --- .../jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index b0553995f0..8d5fe6f077 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 96e74239ba3d334d4a221654b68f4a8b5d979c27 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 29 Jul 2021 14:47:04 +0900 Subject: [PATCH 070/433] record smach data in rosbag --- jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch index 43b5a923ce..12dd846fd3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_record.launch @@ -35,6 +35,9 @@ /head_camera/depth_registered/throttled/camera_info /head_camera/rgb/throttled/image_rect_color/compressed /head_camera/depth_registered/throttled/image_rect/compressedDepth + /server_name/smach/container_init + /server_name/smach/container_status + /server_name/smach/container_structure /audio $(arg other_topics) $(arg regex_flag) From ae8347aea7e222cf3ae052fcb7defbde87de4ab8 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 4 Oct 2022 00:29:21 +0900 Subject: [PATCH 071/433] [jsk_fetch_startup] add config/config.bash and use it in robot.conf and install_supervisor.sh --- .../jsk_fetch_startup/config/install_supervisor.sh | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index 60878b5a97..63f1be57ac 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -23,4 +23,9 @@ fi # Enable jsk_dstat job to save the csv log under /var/log ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv +# copy config.bash to /var/lib/robo if not exists +if [ ! -e /var/lib/robot/config.bash ]; then + sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash +fi + set +x From 9f3f03d97e0daf76afbf04c6b28c391248ffd3ba Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 3 Aug 2021 17:49:11 +0900 Subject: [PATCH 072/433] Add app to upload notification json --- jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed index e47207b282..79f90d51b6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed @@ -29,3 +29,5 @@ apps: display: light on - app: jsk_fetch_startup/light_off display: light off + - app: jsk_fetch_startup/upload_notification + display: Upload notification From 6762aee48401fd2162d9ddcdea40e2adf1ba42f1 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 13 Aug 2021 14:34:17 +0900 Subject: [PATCH 073/433] [jsk_fetch_startup] add rotate_in_place to dock func --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 13bdcee901..0290cf1ec1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -117,7 +117,7 @@ (simple-dock)) -(defun undock () +(defun undock (&key (rotate_in_place nil)) (unless *undock-action* (setq *undock-action* (instance ros::simple-action-client :init @@ -126,7 +126,8 @@ (ros::ros-error "/undock action server is not started") (return-from undock nil)) (send *undock-action* :send-goal - (instance fetch_auto_dock_msgs::UndockActionGoal :init)) + (instance fetch_auto_dock_msgs::UndockActionGoal :init + :goal (instance fetch_auto_dock_msgs::UndockGoal :rotate_in_place rotate_in_place))) (unless (send *undock-action* :wait-for-result :timeout 60) (ros::ros-error "No result returned from /undock action server") (return-from undock nil)) @@ -169,10 +170,7 @@ Args: (return-from go-to-spot-undock t)) (if (equal battery-charging-state :charging) (progn - (setq undock-success (auto-undock :n-trial 3)) - ;; rotate after undock - (if (and undock-success undock-rotate) - (send *ri* :go-pos-unsafe 0 0 180))) + (setq undock-success (auto-undock :n-trial 3 :rotate_in_place undock-rotate))) (return-from go-to-spot-undock t)) (if (not undock-success) (progn @@ -202,14 +200,14 @@ Args: success)) -(defun auto-undock (&key (n-trial 1)) +(defun auto-undock (&key (n-trial 1) (rotate_in_place nil)) (let ((success nil)) (unless (boundp '*ri*) (require :fetch-interface "package://fetcheus/fetch-interface.l") (fetch-init)) (dotimes (i n-trial) (ros::ros-info "trying to do undock.") - (setq success (undock)) + (setq success (undock :rotate_in_place rotate_in_place)) (when success (return-from auto-undock success))) (if (not success) (let ((enable-request (instance power_msgs::BreakerCommandRequest :init :enable t)) From ae265463347ff7976a3c5ee45d5e6efef17c0023 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 16 Aug 2021 18:53:20 +0900 Subject: [PATCH 074/433] [jsk_fetch_startup] rename arg name rotate_in_place to rotate-in-place --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 0290cf1ec1..df0f96174d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -117,7 +117,7 @@ (simple-dock)) -(defun undock (&key (rotate_in_place nil)) +(defun undock (&key (rotate-in-place nil)) (unless *undock-action* (setq *undock-action* (instance ros::simple-action-client :init @@ -127,7 +127,7 @@ (return-from undock nil)) (send *undock-action* :send-goal (instance fetch_auto_dock_msgs::UndockActionGoal :init - :goal (instance fetch_auto_dock_msgs::UndockGoal :rotate_in_place rotate_in_place))) + :goal (instance fetch_auto_dock_msgs::UndockGoal :rotate_in_place rotate-in-place))) (unless (send *undock-action* :wait-for-result :timeout 60) (ros::ros-error "No result returned from /undock action server") (return-from undock nil)) @@ -170,7 +170,7 @@ Args: (return-from go-to-spot-undock t)) (if (equal battery-charging-state :charging) (progn - (setq undock-success (auto-undock :n-trial 3 :rotate_in_place undock-rotate))) + (setq undock-success (auto-undock :n-trial 3 :rotate-in-place undock-rotate))) (return-from go-to-spot-undock t)) (if (not undock-success) (progn @@ -200,14 +200,14 @@ Args: success)) -(defun auto-undock (&key (n-trial 1) (rotate_in_place nil)) +(defun auto-undock (&key (n-trial 1) (rotate-in-place nil)) (let ((success nil)) (unless (boundp '*ri*) (require :fetch-interface "package://fetcheus/fetch-interface.l") (fetch-init)) (dotimes (i n-trial) (ros::ros-info "trying to do undock.") - (setq success (undock :rotate_in_place rotate_in_place)) + (setq success (undock :rotate-in-place rotate-in-place)) (when success (return-from auto-undock success))) (if (not success) (let ((enable-request (instance power_msgs::BreakerCommandRequest :init :enable t)) From c68a15b997ec5b18bbe779217a51dcbc772fa8c1 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 16 Aug 2021 22:40:33 +0900 Subject: [PATCH 075/433] [jsk_fetch_startup] add jsk_fetch_spot_power_plug demo apps --- .../apps/fetch_apps.installed | 4 + .../plug_spot_power_connector.app | 74 +++++++++++++++++++ .../plug_spot_power_connector.interface | 2 + .../plug_spot_power_connector.xml | 3 + .../unplug_spot_power_connector.app | 74 +++++++++++++++++++ .../unplug_spot_power_connector.interface | 2 + .../unplug_spot_power_connector.xml | 3 + 7 files changed, 162 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed index 79f90d51b6..c1bad9ee46 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/fetch_apps.installed @@ -31,3 +31,7 @@ apps: display: light off - app: jsk_fetch_startup/upload_notification display: Upload notification + - app: jsk_fetch_startup/plug_spot_power_connector + display: Plug Spot Power Connector + - app: jsk_fetch_startup/unplug_spot_power_connector + display: Unplug Spot Power Connector diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app new file mode 100644 index 0000000000..bb7fee363a --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app @@ -0,0 +1,74 @@ +display: Plug Spot Power Connector +platform: fetch +launch: jsk_fetch_startup/plug_spot_power_connector.xml +interface: jsk_fetch_startup/plug_spot_power_connector.interface +plugins: + - name: service_notification_saver_plugin + type: app_notification_saver/service_notification_saver + - name: head_camera_video_recorder_plugin + type: app_recorder/audio_video_recorder_plugin + launch_args: + video_path: /tmp + video_title: plug_spot_power_connector.avi + audio_topic_name: /audio + audio_channels: 1 + audio_sample_rate: 16000 + audio_format: wave + audio_sample_format: S16LE + video_topic_name: /head_camera/rgb/image_rect_color + video_height: 480 + video_width: 640 + video_framerate: 30 + video_encoding: RGB + - name: panorama_video_recorder_plugin + type: app_recorder/video_recorder_plugin + launch_args: + video_path: /tmp + video_title: plug_spot_power_connector_panorama.avi + video_topic_name: /dual_fisheye_to_panorama/output + video_fps: 1.0 + - name: result_recorder_plugin + type: app_recorder/result_recorder_plugin + plugin_args: + result_path: /tmp + result_title: plug_spot_power_connector_result.yaml + - name: gdrive_uploader_plugin + type: app_uploader/gdrive_uploader_plugin + plugin_args: + upload_file_paths: + - /tmp/plug_spot_power_connector_result.yaml + - /tmp/plug_spot_power_connector_head_camera.avi + - /tmp/plug_spot_power_connector_panorama.avi + upload_file_titles: + - plug_spot_power_connector_result.yaml + - plug_spot_power_connector_head_camera.avi + - plug_spot_power_connector_panorama.avi + upload_parents_path: fetch_plug_spot_power_connector + upload_server_name: /gdrive_server + - name: speech_notifier_plugin + type: app_notifier/speech_notifier_plugin + plugin_args: + client_name: /sound_play + - name: mail_notifier_plugin + type: app_notifier/mail_notifier_plugin + plugin_args: + mail_title: Fetch Plug Spot Power Connector Demo + use_timestamp_title: true + plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml +plugin_order: + start_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin + stop_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml new file mode 100644 index 0000000000..ad05e91977 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.xml @@ -0,0 +1,3 @@ + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app new file mode 100644 index 0000000000..7419a0ecea --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app @@ -0,0 +1,74 @@ +display: Unplug Spot Power Connector +platform: fetch +launch: jsk_fetch_startup/unplug_spot_power_connector.xml +interface: jsk_fetch_startup/unplug_spot_power_connector.interface +plugins: + - name: service_notification_saver_plugin + type: app_notification_saver/service_notification_saver + - name: head_camera_video_recorder_plugin + type: app_recorder/audio_video_recorder_plugin + launch_args: + video_path: /tmp + video_title: unplug_spot_power_connector.avi + audio_topic_name: /audio + audio_channels: 1 + audio_sample_rate: 16000 + audio_format: wave + audio_sample_format: S16LE + video_topic_name: /head_camera/rgb/image_rect_color + video_height: 480 + video_width: 640 + video_framerate: 30 + video_encoding: RGB + - name: panorama_video_recorder_plugin + type: app_recorder/video_recorder_plugin + launch_args: + video_path: /tmp + video_title: unplug_spot_power_connector_panorama.avi + video_topic_name: /dual_fisheye_to_panorama/output + video_fps: 1.0 + - name: result_recorder_plugin + type: app_recorder/result_recorder_plugin + plugin_args: + result_path: /tmp + result_title: unplug_spot_power_connector_result.yaml + - name: gdrive_uploader_plugin + type: app_uploader/gdrive_uploader_plugin + plugin_args: + upload_file_paths: + - /tmp/unplug_spot_power_connector_result.yaml + - /tmp/unplug_spot_power_connector_head_camera.avi + - /tmp/unplug_spot_power_connector_panorama.avi + upload_file_titles: + - unplug_spot_power_connector_result.yaml + - unplug_spot_power_connector_head_camera.avi + - unplug_spot_power_connector_panorama.avi + upload_parents_path: fetch_unplug_spot_power_connector + upload_server_name: /gdrive_server + - name: speech_notifier_plugin + type: app_notifier/speech_notifier_plugin + plugin_args: + client_name: /sound_play + - name: mail_notifier_plugin + type: app_notifier/mail_notifier_plugin + plugin_args: + mail_title: Fetch Plug Spot Power Connector Demo + use_timestamp_title: true + plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml +plugin_order: + start_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin + stop_plugin_order: + - service_notification_saver_plugin + - head_camera_video_recorder_plugin + - panorama_video_recorder_plugin + - result_recorder_plugin + - gdrive_uploader_plugin + - speech_notifier_plugin + - mail_notifier_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml new file mode 100644 index 0000000000..d61fc63f62 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.xml @@ -0,0 +1,3 @@ + + + From dba948499e8beb7a658db344b9c0909ef4996468 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 17 Aug 2021 09:51:48 +0900 Subject: [PATCH 076/433] [jsk_fetch_startup] fix app plugin --- .../plug_spot_power_connector.app | 8 ++++---- .../unplug_spot_power_connector.app | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app index bb7fee363a..ba7af32b8a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app @@ -9,15 +9,15 @@ plugins: type: app_recorder/audio_video_recorder_plugin launch_args: video_path: /tmp - video_title: plug_spot_power_connector.avi + video_title: plug_spot_power_connector_head_camera.avi audio_topic_name: /audio audio_channels: 1 audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /head_camera/rgb/image_rect_color - video_height: 480 - video_width: 640 + video_topic_name: /tag_detections_image + video_height: 1080 + video_width: 1920 video_framerate: 30 video_encoding: RGB - name: panorama_video_recorder_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app index 7419a0ecea..ff90fb0eb9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app @@ -9,15 +9,15 @@ plugins: type: app_recorder/audio_video_recorder_plugin launch_args: video_path: /tmp - video_title: unplug_spot_power_connector.avi + video_title: unplug_spot_power_connector_head_camera.avi audio_topic_name: /audio audio_channels: 1 audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /head_camera/rgb/image_rect_color - video_height: 480 - video_width: 640 + video_topic_name: /tag_detections_image + video_height: 1080 + video_width: 1920 video_framerate: 30 video_encoding: RGB - name: panorama_video_recorder_plugin From 3f40b67712e719b7427f20672418b0fd38e7c927 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 17 Aug 2021 09:54:52 +0900 Subject: [PATCH 077/433] [jsk_fetch_startup] fix mail title for Unplug demo --- .../unplug_spot_power_connector/unplug_spot_power_connector.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app index ff90fb0eb9..c41c6f6d88 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app @@ -52,7 +52,7 @@ plugins: - name: mail_notifier_plugin type: app_notifier/mail_notifier_plugin plugin_args: - mail_title: Fetch Plug Spot Power Connector Demo + mail_title: Fetch Unplug Spot Power Connector Demo use_timestamp_title: true plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml plugin_order: From 9c4b8082cbf1f8fb3a557c8fc507a87e2ff3d612 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 17 Aug 2021 10:06:26 +0900 Subject: [PATCH 078/433] [jsk_fetch_startup] fix video topic for plug and unplug demo --- .../plug_spot_power_connector/plug_spot_power_connector.app | 2 +- .../unplug_spot_power_connector/unplug_spot_power_connector.app | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app index ba7af32b8a..0d74b1ad21 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app @@ -15,7 +15,7 @@ plugins: audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /tag_detections_image + video_topic_name: /l515_head/color/image_raw video_height: 1080 video_width: 1920 video_framerate: 30 diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app index c41c6f6d88..1786eebb33 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.app @@ -15,7 +15,7 @@ plugins: audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /tag_detections_image + video_topic_name: /l515_head/color/image_raw video_height: 1080 video_width: 1920 video_framerate: 30 From 9c66d16d1f653d695bfb624996794fb15e41ebd2 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Oct 2021 13:15:39 +0900 Subject: [PATCH 079/433] [jsk_fetch_startup] add icons to plug and unplug app --- .../plug_spot_power_connector.app | 1 + .../plug_spot_power_connector.png | Bin 0 -> 1017109 bytes .../unplug_spot_power_connector.app | 1 + .../unplug_spot_power_connector.png | Bin 0 -> 1017627 bytes 4 files changed, 2 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png create mode 100644 jsk_fetch_robot/jsk_fetch_startup/apps/unplug_spot_power_connector/unplug_spot_power_connector.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app index 0d74b1ad21..10982ad16c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.app @@ -2,6 +2,7 @@ display: Plug Spot Power Connector platform: fetch launch: jsk_fetch_startup/plug_spot_power_connector.xml interface: jsk_fetch_startup/plug_spot_power_connector.interface +icon: jsk_fetch_startup/plug_spot_power_connector.png plugins: - name: service_notification_saver_plugin type: app_notification_saver/service_notification_saver diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png b/jsk_fetch_robot/jsk_fetch_startup/apps/plug_spot_power_connector/plug_spot_power_connector.png new file mode 100644 index 0000000000000000000000000000000000000000..d1b1329d2fb8c9539a34bf003836451586ef87fb GIT binary patch literal 1017109 zcmYhjN3Qfp&@I-|K+t=@+koZ`NQ1vYZ!|0VqW5m{Kv(qMa|42wr3GkDN`Czd5^(P= zUNT80gPA8HPMoa&)6~WP_Fw;(|N7TofBm;{Z0n{(j8sUtQ$?9z!4m z{tp=X514i#>~Hh~!|xyL9|$Jmf7>TzG5qI+@P8n1f&Vpp8!=!@t%v;rpBF{^cLMw0 zz}9D)x*{l2rQZHV1RN#*L5cSiMRGOuZ-fQgUELPoLoBj(d{4=jpBA;60=W#B|+vn25EM2R~XC&CSW zn-u&3KiiJO-Td!1K{1=8?%QzSX!MMRh2uLoLabXjrC=xsI=GZ11SWbA6mbP=5xBQs(&sO=-$rgy09BfcepL zxxJ5KnbzHG?`_|!!vao2XmL=FdQhO*+X)o>7Qgp=BCj2e1`jNBCpf4nHeS=b?{<-$ z%MO`%@Q3wjC;R=Y}N+{f&ZQKmo`=O*xL%@!cVAg z1^#Vo;wquk6?%e50+V7CJET~TWE-{jnvd_69~Po0Hj11ia2VI$h8s+NMh@Ctu==}x zx=Qu8^@n5=Vysd(q1@Y%)zf>9i`l*UN$&t$(Bc#N!mK~__kCfs+w*+cT#|ZSX}5=X z58YWDA|{DD+#uJK>8(Av~w3M?H{uxC22*5VXX%(K{B{^nCcNftl0l6(O{?j=&>wGmN!n4fxDxD1iJZj#`%7-SE zLJrki<+~A$wHP{N7iDA{?QSACqWm$Ht@~1^g(v+MeDF{hp8BEuj5xMFfs@@)g*|A% zl~qyjSt!kZd{R}pk-t+wE{N|{R1`+a>v)nSn~vUr)9nw;ZpKM}m`=JrXg7`$nIapV z38#=LBup`3{etNRse--Lek$F9Gm}X&3xZ!1W**{@q)d`v?BDi4B>uSg?j5LuO6QzT znv?8&tgg~;;;xRA3h*){cXedXV9N8io$J%6>y{-WexWSNzL{Ho9nE~yNa4_91x*0% zFsiATY;Q?Syt!dLgneFEBxDZ@~-JZ36IvC=z_wXA052zl>%9xBXfvlQ0kg+iRwo%0jq zG}SPo8_CJ$2XxmqYBO#jU)O7r*n2s0o)pyLw=ty!{&vAumeQh|FAUx+#+H#l6p#?R z7ZRYhKhj^Fl)|eMad$mr`*SMXbY;FX{qXz>JC|jXjCW&6R5%IwB*mBEipF61>WNh8 z{6xPD^1dr@8v-)5D%)Xnn=SKipV<0EYiYG#P}dk15l=xvfi(pTI{>;a)v#0iZsxVC zJVr>9wGN9FaAm^y%tkrcytBDusFID!uln*`P)hrC;u)$qypoEFH_zzRE!u{chv97( zfp;!^>DkSnF&|lO-&$i_J zQJM_)-PR1IIn(){E)|>_+J6M=-(lQ5xlkT<{rfRSUW}quRk!pVcE_C9|yM z3;G0_uA((FnikCp{@DU!GV^uP+^&FU9S0?-Do;|WBp8p~paaw?7+qhjeUNh{@8_r) z{=9k@)!*TW^`mmZdKukc==KQ1{+Wg~0?Wvvn?UkeSHHRZ_`T&cJSQvf^x)ut{{>42 z5C?N?c63Pw{o|;`ldd){X{(q>T6<5``C)+#1yN;Ga)g1SjIreCck$b$(hzV33e>)dHYWRYb= zewBI`GCldnLHxP1QENxmtVHOiaq`E>Z#u6iEj)~=8y#=$^Bb;9_H@%n|& zPyWdDrEt}<96uCtYxp~x+Wn=DQuv)yd44~WZZK2XqZR1JWZv9aTLLWpu;Hr}2n+x? z1z{m0&vLA!`{~urYU!qPmwkKiMnO6W`R!X*|mQ8gpVujSp8S;S?PM${m9mxWuYzWhWK>3*|lSFAg2x zg>>Q1ydT}zym|Vr457Q_jB0+QE_LX)b4BUH{cN&=(gCZMZ+4ZpBHk_cW3G~^tX|_v zcWBty&L9+)ZrY>?iMb_(|5y~J`HhJ0mC==V^ZgiNj3*V-8Nb`wNIzG~lTrz0)AU+v zZtBZ8qNv$~E?WFRqy)y}N^*|;s0b^rq(Sfj!GSQ0aujpltK@H$xHndyJJ{w>aqI;r zdylh>fzHs8p4(hX{=4f!kYNdju#JfpA1Eb|MPH{rxne#^MDZA3K7^1>zM{ijIAP#O z1dcc{B;+h;OC5D_8w+~ta4WZwzWsStc1P9nam!_>^nF*B@uhZ5E4Bw&VwA}dd_%Ep z^l-mq%P+IO z;8ULtlzqeDwA|hxuvNvWt{FKUjPAAFWPQ`bis2qMXtAqg4gg6e!h&>{g|fKT&wImg zU@a(&B}QrS6FMZC#E&vkKb=N>p0zh(Kf0NlkxE4ysykAnS|v}zj%DHN2VsEQZ_wZ& zXLDXq>D^~tviOPf(Gi>;LYZ;r$y9S1ob!cFdGe(ki?{DLiewLjx^wXaV1fv#!&6EJ z(`Ulz>=Efb9$0zCKej()Ejj1uPuy0lc3ko+Obm`miMTfGlYwCzFXu^VtJ|_}1(kC* zit=|Tom}T+E;l5O=?8^v-#i#;emz#QUoC1~T~K4$;*c3|pvR{FJ9XKCAV1(CN;E^%by* zs3lG^;sjjxRi$T@T*pW2E~5f%J;FpWPfwP;aDQ(iEA;OT!KcShoOtLc(IWCEf%BXsTvflc zq7yVl&}wZ4jY?Yc%qQNRhcd1ejg!bHz;0W3E&p^JxgI100{`e8YD>GZF0ExCdOz{= zyoyD78yA!ICJrOm{GQyUjI}_?*I6l*0kfLQQS?66SahHYr@3D>YWE_nOJy~b>6&w#%*>lM9>e<{V0NX8u9-{*YFr#WDw3)Cum zfeCVGKbfnw2Qikkm117UM-(lnF(vp7|3r^G-5za>mDSkUKtaUsd@-`dvn=)O;0j|? z@72JW0{wMPsCm;7Rnhy(W;+@XX^wP?ExC%4E^=!?zxw%UZ+Rsbl$5GbI_l>a&KdN}Dd=^ycQs2%v{vT_QB6y_7i|%#pYcnR4_pU!i@G#8<2(6Wx-IIVxxr>TJdeV1t=tJ+Z2 z$WdrPVu*Re+iwhV`^O>-d{p@bkG>dk6fOI9Qrqmo3ZeL0(UzuZKag3>gV%heT-c z+LG02i^eO{dcgSTUkAm?FLtdm-`eGr*|!3{k#Xo`gYh;`0h{@%;3@4S0q-Z>^}-O?4jSGT>X%^RF{&$V@bNy{cd^Fa zWQ6CZhy#oF^3j(eG2(6k*KE$b0arV0EzDG!+ZKZoFT>+9{*M}l*B`_IB)wMpY#({h zqfK>%JYV%k_V!36?+4+Wo^KXW0vX1+qc<1H%59CQcVAEB%8wTDDUx~1uxhqzzobj#fJ{?px2Lq|C+zupFju>lESDoBbTSUt;oa@}eDhQj zM?7Pn3gVu=Fd&utif2{SimkKH8^UlFyKnUL45X!V99|m9uOPStE>NuFz10fNx#z5H zbq0c6GjgpGJ(%Sm15T~J!tJyvQ^)9%G6=$zdN{LvANSL;9_%a)^NZ>zY4N_q*T-s4 zg`KG@2Vz2I>C<#`d571=p3oj|>;oIN&PaV$Ik)I#XE+*du;DtI`+IiPwkohv6CYb{ zsnWm-nYDYZw`YOTm>^`bP$@7C&@%kpLf_gu@$W`)TzokBT5hfiU}f38(L6f$80xuI0$ZZMvomuvlnp&d z`J66^UrMCn8;EGa3|t$?k1ZrFx~^rTFxm$us3&kg`bnSxnUr_*Suz-KLZrBKU5qPE z9hSeE0S{Ar>^<7A4iJCQdw?%Oh9c6$8#@O-C_q5LO_855ICF6!!d)f988`BJwZpD0L>&-Z1Lh)b>C3||)HZ^ti|stE?9P=ks(X4)m| z!4cx&fFIBX$UtyyH_5V(S#%3JJ;u+gVIDbAAcsy@tc~4+AYot zLT&WOcDx-9h#RSRVc!dZ+uRYhvvB* z!iMM(y09awqph! z0EnZ(1tXxm^)emK5Jb)Q=VfQ?)ww3F;0sx7Tgh1yrMe2Fmu(Kv)J#oBqFSJ{L}Mn5 zNv(8nk#5?k%bLoMwlK(IGfY0ZcaR@^Q6GZ&zC;kRyT)Y@jq$o+9m7{FU0R3op5CVY zNz+$tLfBc&IC_rrHOj!SXL1SWJ3AOgzx4&h1C=VU^PEv|7u&Xyo+$wQV2xM3p5(Qm zwa=^wP>ETrc}y_5SwaT?Jvh`T`VM&IKHcVh@j!!e@+bJ$e&uWYGi4=h#vM2Weh?hQ zTmJ`AK6P+$Vm&0Ejv0`vg+2qWc}x~+rR_yf8SG#y>u4k zMnLd4S7g4%<%S9p1v3bcV*5*jJT-F@>T|H(@jBEGRO)=iHZ4NvZ+rjXcGrjP7$NlF?|nwkm533k*)M~- zlbGz+-+Zm2wf5!K(T5j2*uJ{KhjM@XW&Kz+v$qm{S+$iLIN&Ro0a_zjWzS=~PPKWe z%KqiBMSzIdR2ztFN$((aMF|8z32vK`x<{#MRJ>T2sv1TAEpEHh-}K)FnV5Tf!l$#% z+yT(=QT^}hgnwL}?9$9mYK)B5b?H@0y)&Bua4cMc=aqoX0h=Djd}c+V=Zq~{T_S%u zO3pLG`Y*sc=rsM1&{a9s{7AobFQ?#oqeI`1E)qls4AoA{r!3#($65^8jbfr>_bl-E zn7UEVI=Bp1wk%Djn_zM5yxa}4K*{YT+$8pJ0}*BQlN__wf%Pi{*Ac9iMV}*PJqx`{ z95_F{0WVX46-8DexH6H4yZ9wAs)d8BcLOc8(t z;k8vZHIgFcx72g>szt4qfXRA>xuF zO1T&+r6D>7MqunuP~Ob@x(g#c6MFnkL8yryfN_S{zw5{ZRmlQ4WaI_hp0Tb1LxW_( zu;uIx2-Fqo8eKzmiFQb|L^)?oG^H7MJ&ssY2rauXZ3u6}5x#9^F=SO@Q8OXruUYhM zas*9UZ!0hXVfhB=7j~15^({heeqBYBuZif9T-#8y&p0v^Gh;)oA9L(Lj-+YRs==99Q2u z&v?xBDm6PkfVY%GaE0of-`E7eNqm|!JumV$AKuM@X>av_B3E6f-TCZjbo9tSQm8c!2RSDfAhmZ_*Up@*}^m_;EoS3byjrz{cMyC_X0TqyIW!JSsPy#oYm$n$Zi02?IPlCFNOC zuKT$RXmRec;q1*Q|A@Hpp`xd{08>t7p#_9ZD10WxdeQiqS(|+Q{Df~!UODEs!az~h zC%{&4@9H~Khj)VHjoEp5Kyg_!IRx{g^{$bsz>p0q@9rJ+z7Oa<`wQ`AhVPv&NM^L% zzO>>bN!zbS`yib-4mFL&DGvFtSD!ZyhZ4Zos7U4snp17!l+3j(IKsJ^jKqJ%5EfX;Ltp^T) ztKA(Q#AG||H>f5~!s}=5vL;$xo*iDE27$h)JAjGG7g*Z{`G`_Ibl)3lVFakYCS*}M z5LTk?i$0NJ$k=@qaY;I|`P_DLev$@|={|5O0Ge2R?sq8=-B`?ltIXEo>IOXDKtI&)(_K*3hx_3p2tFSEB?GQ?dmO zLvGT0lJSM8ufhzVNDoRg@Q@~RZiAO7n=1EdF5vyqMl zQ7_@}dp(%UlzF86m=&GLK2&(il>`QTLhLGvzSj#*elNdK1jag#y*s2^Ex3c?&_|4u z&!V1Uaiq^xPdq5Jcfa0SE^J*!{Pk7@;93b<4itM*SDqWJl4-IQZsZlj#nJgnBe?M@ z9c+OYK@BW|00aW-2UCO>@r&UwUN@Ua8pK5fBA>MoPm>K`eSrrFSLt?dIIm8IH$@N5 z-;s5@@;pGJ?C`r> zK|sO4XdjIpsCc}6fWYix;_$HfV#Deb2zy8ho>Gt++%NSecrGkh_Y5RVAOF;BZQaE_ zhP`>$?mN5&9e;1WJhpsb-8cQR!S<`9PC*;}z~o#DaddRYjl@?qo>EV5_2RZn4yLrt zkIW95K0RL4#jQi)nKSnLG8X6g3~`hbA0S-eN<8kd*JB9pjcy+Nk+Vo^y2%ILFj8Na zG>16(^y5&E>nPw!(O}voLf+xKz^EiYen#nXNUWv^&ktCjfq3{ItQ4y)N$!e!YV^%x zaS})O+B9xsAOnP=Ov1qYrn2+d?O#5f6Yb+C(FA$QWM~*^x4#$X^NspcHxNwdMZgND zdz=;dAsVG803B)GzS%P&XqM=O(m&sE?#?V;O|IEo%>U`2bnnHf6#t4uLp*uxNm3wf zA_ifq4x5#a0$H1wo^1G;ukql97YO^AfEg`A@OvoRyR!DW!1ziQXOIRlmJot>2+~!` zvndknm|i5#q-$>-Q6;!9QU}>q#UYMpR`1zsm2cUufzp`2d8qORN{&fBRD@mgSSj=E zJ@?3hCtz%@F#Y9pS}b&$AVHVF);>X3y?#yxst0)qHw${wyknSyVspAUT(~q{LXXPt zTfAj}U6R%kkXqhR`}9=D+0BoHM8}zBpm-C9UX% z?S$Zok-73fxh>MYhyhG9bs;7O`_vsDk{#vFcE^C$wnyl=`*deYU>N~VQIko#TTMup z&1KbYzg#T2r2pH!(C^?)r>9fXIat?yvNxd~+uYKT3y<}$`CHx&kBVje+?r9rYv@=e zso3?*>pdA3J$K=T6^q7-1ILIiVGk;Yifek% zaPkmN`sBIiWLxce!mvU48nK4FLI9v2L%;y`wdvAhicuH#8r1PQ8ph+|QV~P3#Vt8y zuzNI#=K7VBpDBZ1XX=eX(R02Xnr8sQFObzME|<|!DG=0mZ`c6dr7#3QB+#*YhZEDj zT&NIKiWp8=8yo?r0Fr|nxiL%yxDLS-FT3wzhM3MvfuMW?#iMOi#IQUADJla3ZDtIT z0nKMutZ(Y|NYdDx-EX({{_Y(Sy&UJDqev0R4-o9!6l<{i8+cl@aSQMX=8aIS0B@OI zUmPzrR-X|OY8P{MZo^;##ju>fgX&j3AKPPzehps+tHfh0nKJ!iDrO!!m^EN8DRk=;RTB8je#T0H_~1lodRJ=fDGX9TLOPO%pfny@ts2G zP8s ziZts$>w^N6BVL!LpK>RHB$tUb39vAq1}0#Ity`U!?STL~LUMt_!K1cY>48rHV^+8} zdF`5XN|?iq@jBge_ESpwaPy%c>FSk0Td0MWeEC(xBLVWR2Y54H$Bb8i6nqf>u<%22#BNAaHU$e;;3<*^!1u}v*B&j8B9+6P z8sw@CIhtiN)K{p|fJo4tkc>T>U}inVbeWCtQpYW37JiLG{8@{%wXZP@B_z~iq~}Tv5WuK|74#yLAh{j zgS2i44_`P8oq7b|E5(rQp-mUhRkeQ4Ap5%1A_ZCbJ5WE4P;3nAEtNQV3J4> zv5uhP3hLzGNkAutm5WR^T!>B#m^dAV`yI6NKyR)YvJPa$Nw?g17P+gUpfFcCA+o<7 zl<*|LjD!$RR1oz^yC2e7Ug}Y zTqHal(dgts2@5VfH>;kU5TNg_DQ`rPuuvG7d5a1B8@e!tk3MfyEL7e|ig=Lhm>Ka6 zP>VYn(vXeAlzd?UfM9x4{%SxaaK)?(%X<@`H1oy!J!v|*-n%5Ub{kY_b(YrnY{T$9 zmeTe-gj0X?{?S2n-^ElPO?g!|35^#zQExVh9@13S@CWT63;`56R}o0%{i#gqH+V&Q zT_$w>tEFh=yr&hRGGm=*qGwmQX{0LnrhYLmjHaT|?*7L1SUj1BK75FiKSH;4eP*ai zyXX~t1uOyB9b7~rbO9H8J+9wT<{w>=Qrl0F;9K%r@v&l>{HVg1w)+}SmvynHt5*+4 z@#k!|8w_{aL^I;~Kqo7PK86Gbu5uh#M0-ZPBknk6=QOUZ?YuQ_zS5mZvGoV5rNPib2A3M)D8?DZMc22Q~gf8(dZ4FkWu34Ce=u3)PI*#OC3mlTJY zSP4(@-S^OsBP;PeT^!=g-_5L|w`q8ezVQ?;zr%M* zBnx1svxSm9#{iT8ApR~3ye2_@z(Md6b2Q<~aVU5vm;ypRwgB&h58wy?EvxwpJjeh(4rmdn2^dq}DeidxMN6+*d z7$q~)qg@vR#oHOLGsiTfM%^?x;sa!0EKQ$c!?MEBOFK@>`21V=I~bSP z)ABE1*BqT6lBMXzlWOtz^Ezvs6#*A#ilxQow9A0#ynWS zY)p~H&vIXpUE%g`RnL$7d!Ifz;ql#Ibc3(zi4}1iXxF$mtOM@-=B-pIj^wrU2eeXn z^dY~@T!nP7%g}RE1R~`KCB~o_8~whH%B}<|txo_*7$5@u!rNDpBa<^->6~yqE@l+f zc=&Z@A6ef?*XkNbb?+-g)Q+8^;EWMKzbrb}sd>()<&mFgmtGhSL573?mJ^&A-yOPY z`=?ahZlH;-0BFMG6z~<0*bhqN{21GZFB;y4j4_nXbpYie&`nvUJd=VqgFmaT=3jv$ zLQtLGtHI0^09}CHvnOY?GSUvhXZl?}oKvv2kAp3iTF#t8q%L?`0E+eSuO#-)g*Z}> zHrwa`#5(w=p(wO>@x~cwuAH#hVL;{X%EeNr2i|zcDXjTQKI&=9orY$(R9q4K*2BaqL8U1k*?$ zBq9K7xB#<83K|4JQ@9sEet=Z+ny+t+q_o}&Puv(6I%D++?a$m_#b=sn8PINXd4ITd zJKaVWV>_jN&}qR2)CR+eb|ZeM0y)1}F< zN(-df?_8-|;A6gBtO+#~ZFsk5hbPE%nZfyt2VRKZNTz_wQG+Cp1_UXFt67gb{~4I7 z0rp)6R4eVgAVhfdqh39;CvS>_fNPU%cDIS$Tn$|H6zT;`k{&-K-?Zo0rsI%idT0-> z?XUIzrBk!Kb8lQM!p*+n)dB2a#Kn^x%}E*#K|N<^z^O^LKWMfi4ImE$DzEI z69b_)*v~B_3z@Er*q}5J^(a4-S|jAwq)*uaLBcqJ?0Mf*z*tp25o$_foEHcDk0bdb z$l0`WtRHXaJsAA$U=oxBhy0O$!z2MpEF4QB*j8i)(}?+XA87)g{;!HWiVMH6YlFwQ zUvq#@jd`Ir3u!MYp~J=vO%SEvo6Ai*hm@HbQ;KIO20>n=4up2pQROOuGK#*|OA5hoML>%Gc?ICd8Npc&cr3Gl6 zUJTP{lqH30Y~ed+G&Ng(=V(4pLX8Hh{M0I895e^QG8cQ_RF;!7kiX`usz7V4#2b_W zEy%|Qspkmjohl^lmA^Ycx1mbgaj!=L>C-m>>v8OB4*dN%$)I?|iwlO+{ee{DoqIjV zW(6>{fO2Q$kRYWpw~4_E75L1vpDxbL0?5NTt2z<{I=aX=iz`-RNsCbTg4vJrsqluT z9X(OwYcOz;J`2+GnRnWO9@zFRX}?&d2cQ;52r~ZR?ZVpgRFNK8>i# zY5`*;;DmTs!0n+quGWGdA|&eN1=5G0p+|P>r2P3rz{?pQK!cV2<#U8N)sJ;-<78{U zi2~=Q>^n7Vrne*4;{{B}-?&BW0}TkYj|6g_LG{|9BK??@`XSMzk~j?0{dIz5^AHRM ziy&V|mD-FZg4F6ndQ}XisPO{6XnG5X!$Fp~+}js8ulH?DcY3sc^~o^B`{*E%Cc-i+od`W{zARYPn37orh~o1a zU}(}Hh#(Qnat9b_kz20#U>F9jmSna*)4W&aX-WLKJlN@Z3*W7!@p-m))e^H}K=*hO z9tV}jV9+>gO!)pl(kWNwqA)$3AL%0T&!g!DT3q_A1Mba~(j8n&^N@P5&{b4I6%=;o zQ0jr)*4_zHHG{VM4N*kXU$_B2Mwn&aa@|lPfDpm~t0Fz*Il+35AdYkqmdVY)?%InQ zdC=T@yyTI54wd+It@_dxR;%AXkXioZmc%J|paj5V2??b8il#h|y#TTPZB^Qq-b4lg zc`d|CQtC#UqCP-c10J(at6r$yVS4@&Fi%*@T$WI(Z%^Bs*@J)V)s&gz_ZZ{C1uzyv zrWKME9pF{WE}$h)Fx-)~jz}LI(=GNL$@Xgm@?sA9s^UlvH*OdmEG*wmSf+$_e{EKs(7XdA>or*Qr5N!kL+ANoGLIc}-cOM1>x&mfS5xq&rL(M%W8-(Z zKbv#MlSA@SfAWAuk(n%hU<@o}SR^AYtKD&*O?^QFw>yJH5mwWL3ye@k>97H+z{Uk~ zR>LsoX?JYEnboS{?ft5j6ca7C(fu~%F?Vckjbf^e?n9reeyWOfIZ+Ih@9G*ZWiGbg z^R=QYjfhqKAch40%}{1w&=M+R@vE41y;NFheFvbU(xsC+=MjiZRf}1011Chull&+e zzo4jNfs^Cx5|=J^a4lXsL~7v+rZP--CgWQlZa+ED`mtT0hTXl12q549o4JWGQ~%UR z%7Ar>^~CKQ66SBfr_OJ%3w|~QZ$DVGYgNr+sqGi%@vERdztu1_Vv*Pkey=*Jq6WBw<>@*sRYA*H<(rBqr%efQZ&|A456zMP-i z0U_WrX(y7{f65%<7v*2GFVVb#GnO|-wQ=7HUH^KP<=>a197Jr1JM(STOikV`A7bDno zYPf9L>iP%wj0t@m1Utk52i{5d;sR;e#+z{bq*>L#NE3oQ+%HO^gaK5Pvi6sTNC%R~ zw-K}LCm+E90t}vlED7qvdk(MDPo*0V!mzS$R7Y|7$K_$on~dpyGC+doaB}a z+Cgw)bSpAg<`pP^W_^FmS4l1O^7H8yDVu!2LJcB`^nAE3nG04&7k4Z{cl!|K0rLpV zeYT#&EIaMw-!JsJZ(u)lH9`faed$*3Q{e2!A&JNho3Be~tIcG71~4#Vv|*Z0zyNxy z)bSV42m-c&g+vc=0t94Sz-Wsz_+Ejh4sVUMHV6h;zi>FLN|Z}W{;m(k!mrh zqgq%pK=BPqEb%+*{V(J_Qi!j-moxaJqSEJ3-T^mVJGHj`M*xmKIP9yY02hVcGA{Bw zl&04gX}Y#F5%pS!ZwQt-61-+hpa|?PSs>;jh)fg_19Om3-};QAjUm%FbeAs6Fo^(+ zg?TNqv@7W>D!e$?!7AGZZ{BP+0bjA;cAp}a&o5Y}0%`AK{^C-+`o~?tnH&7uJ7q{E z{Y4$Hn1ZFcctdPwUICq@kZbf?mhDXniew~1UZosBxrTn4f?Gcd0@hZ8RapY~5(+6@ z@5-4WSO@4Xh}B2D&If62lON0h0}HZH3h$j#M2GHU08UJ7=XMeuAZKJ4$CF*Kgbwtl zX`_hKvx;@gcvBY{-x>s!z;!-!Y6D#Q0fl!2neUYMNt>A!z-? z!1~YxxI3l^)r`uWWCHsB_%c?KMl_GXF6LwmjNf;9HTX=g^>-@9D6L+5q98UX@THro zmrKlCw|avl1Rvuikyed|jNie6mH1+Wzo?6)R%vyVUC8vIX>baWg})x_rh)|k@9+m% zR*O@90ed%KU1?WF6Yz~7gyFx@Rug*($gaE|qnb*M^fxDAP?V_%b||nW6EpiE=9E&A zTLk$aID>H1St`BgTmHZ@W7%K|`A^TC>lcOYapcJR(%-iQYy;9+8Vc&0pG0k7!52+f z0y8w@t!~iOZ5ea&IhkW{KqUi?@wjU#y|1;##kND+sA&!zTgLH%-XN2S1M(A$ke-w zc=7gvye7D@WaG%4an$o#J%|ztc*yoCNk(@#894^!1t%siIO%OVm%LSF_K^F>b2yc}7a;Vt^JX^o{-KOaY`YM?kAT z$MA|pcpn`Dda#C@LDs`4BU-;*k7M1U!I!Uq!N*UNwsdGKr6+a&61VR)R{7>xb~ zoa~eu1pA&PLqEa1MX=}rTODKQ93a>X7UJhCG328sYHUE>rA=PS6xva5iH`|ur)w_@ z?f=L^LC~&&6|1^m-%&)jn_Qm`yLfm~qrUlS?B7@XR;@`blQwEdn8FRrt&QL(+9^ zDavf&S0W>qWCT=@%pEyN&OH5Wde-W5{vHF`TD5D3FPtH>YG>w~&8BvwUx!^lyOR|ft&2=WuP&HTwX6F^ zmR8)MWwG9KeX02I>{jEPzXt#%vI{}7wlAETzYix9M{Kd0^Qu(n*%v=9s)~2ktXkGZ z)r(*LT5X7LsV$#f$!6n==@?Ui!Z)u`#Q0aI+LuyuWfHNO<;mWHmI7nHfo1B=c_`lp zB~tMRRaUw@LNJt0rcbm>SC%<#p@RBuTwvTaydJwl4#gjERo{=#K9XswLz2>1lJk=2EsY2 z_=e_K&RIn++v@2x3 z@Hw5rS~v|s)+XB4pONF59?#WRka((Tf$j`<4gSHyfU3q}^GjB`@PNZR{ue6<3%D3; zxX&x;N>vy70ArlUTjsx$aw=SUK6Y3yTn^*qJIQJYdaX2yFDfrwJzI}?r9HeRMRf8= zbDL?ajX*W0NYXs>0iRI-(1V;F5fpWfVC8(ldYz{FadjVmCM`oaLGNF)kM?dmDX~wx z+Woep?N@*`cN;?X&i6xAJD;Es+{N!Bwz}KotC(QA1h^TR`vi~`?IYSgaepfXK)axO zT&)Oh%Bchu6KA;Fbycgzl1a)9!s+mE=#`TeSsKi9g3_#suc3xe8BY$5h$*xZ?JRE%*GsAqDgoDV__PsMo z5A-llZGab-{%9J1MV~YmcOK@D%cm?=u_N3QQ*l7A*&;^TWox&e?L=;cifXdnZ)U9p zXMNXMX0zkAQTC5&0)PcjRnWmp^!y)sG#Bkt4xXNf6~SFMLB*F>4>-hVvOb+Ep#+15 zn;+Vy0>(Ejso}YDG(zsrs0ys<8Gq_*;EN>Vsu`dmd0xaw``zIcq`8ue>wQkgb1TAY zKd>c_ibyAmXQ+uk90%&LbhIxoN-}ES0H%vEO0Epxb9-J-LL^ikA{V0m8k4 z0buRl2>_P%YTY63*Wq#oDe|2I;26=QEBvy3E&Q=<`Bvpx31fXhZI#lX{m(!tLP*^a zim!S=)?>n*9dJ}8zOR1B` zKvA7cYBl7)<5#c!=0~H#@io1WfS7&2-uT8(7ogjS`*;+i&Yd2m9=ayW^H~pCI{O3? z7YKwEjxjXBBdMH}zLXq{>?Cx%G61~Iw4!QWjc4b7L0hcX5-zN|0aE(3!eFwAzPgKH z;Vk4D_#e{iPgSQPg3Cv8gt)aTM@TcEpD*52i}3C zz4mW)DhuGl?vi8a9xy9HX=;MbSsD;2E8dxW75@qDRSo}K>6<@$5L&{h0OL`@jGmF2 zQZo2xqyU5PU3n*~KV63Wj^W2Ly6|SpO30nub?*d19H(cGHujo<;u>e02q^ElgPGzU zrLnZsa#rx*LBRw#r0BQIpK*wQE!%vB_IXJ6k;*+EX+NsKUQCdL>V^fk*HKhKXl7Q-b3!>CrUp^lNU7TnT!0^PN=Se4zvyX}=ui`9mQY_1jZQ5{X%j z51&sFrxCWq9b>&eN|={3oG+cbCy7iC*b}&Ip}Y0frEfiJmyZV;clc0dj$<*QELs!l z%_TlpLkzIn^#_>2=sG|+3l0ovq&be0#N#`i&itnpf%Gb%Ae_q=mgKEp*1qRcy@A@| zea<|d9lgX>h(qs)`3)Kq#!x*RgA;gyGi<>t+k!e#@4S|1tYWA@?MJ{+pq`vKfF#sU z3FMpFNWb>)TzxvbqaGl^uZGw{zj=xbdqnBmU~3H3P?{sRT?!?7n-FD*fjne9af2)^ z22!5msXj)z3{p3*dWqMF>C*>FzDv6%KW?lIK-4dqbwCE_s7mLIEad=&Ji?6WU8*h8 z{D2A|_c_mxhJT;;s%pRem)}fB#>=0}&~UPo-m~lPlyjU&^_k1F>vqHa1;S2#)hIxD zd+4_p&{=}RkLjf8E!W30nn!I`uE=as%lXp`pl4k|OV4mKU>y0&sVh9t9$!Dhn4fCe zR(C8YP&vtW&>_j`uwCvmtPB4Fwm{ASOP)KXOas@-cjc-F6T`*w<>u&v#;`s$es8<` z%fSLuz4!GU5JN~6CA^xaE7}p5f1R#8q?m(R$Jxxv6!V{C>SX}Bo9~g|*k$gC;=N)X z62oSp4Um)Y03Hl4R|`4Tn0%zc;RTm$7PxJFmalI~TRXtpvlJ~k>{ncBAa{=eSBR|a zpUG>ff^^i7YcHAqBRDo(#7Mgzo_kTL^6Uv1Z&QE)a1wCe23eBwlfKJdtyJJNnW*m!^G z*PS2UTfZspHi+~C+@_U4%L3D&SA(Kz09rXQTa?HXs)v0&FtmSsID$PG=Lg}(O`=BOa772`B0NBS>nM3B9Tr=3^UMH6Sp6P{7|Qd&eV zHEIPphs`nHJE%;RDas2Zwk4lo9{v(Imzn8TB!SvpEFmx22AVZ06t4#04>+!`9}FKq261+h(gd&mQ#Dce#@7HxV0yH? zO$&O!$L^z&{lOjeJGkBD)K)Wm=)AkXOq&=lxTp>g#(u%%84*V@!Qo~-%7yH7pjtBE$fi+b6%qnXBcPaZWfdEs1L#oaQC02@zK~8989SnQEcvFSQ9B%9fGd3@50zU3WyUY z2aV(6)!khz&K5DuAanyT9SA&ksA6PTz2pZ4LT}f~7~Q<{YFkG`kDntzaJ@@?E5~*X z?dmx2@C83lhsay1(BWU0YXyuiU|Wc)l}b7F$2@oY7&Wk@WwvJ1g5OGQ!t51PsU#_UaG*wc6-Y&lM zvFxCbb@flXo^2-- zm~m_Xz@fIBD3u0e+`c(SkUmKuSMC~TTb2?@pn0UcnSus!-vx1(2^4~46F$~s0NuH( zpoLf6lY%J{yLI z5FQb9HmS1z0AQw^LF3Y<2m6Iev;1~5+659rVkP_nLw`2ReJ6frD4vDS;g2ddJyo2H ziTd~ba692k!ISx175DkH%mSNN0{PAW-Nql?r3U7tTZRVOBiPkvYxer@&aA%Q=ri7b zWWO+E*NI5^6s$G1 zjRUhSNcSavBX+TDM{6cOyCOZBjxxejlK_QqvXpvk>igu3}Jv!+Xf3XDb3%>_->R+tdTHN3)P17)FJ_a@D_Fo8sEK=5zvEr|sx zGdVqZ)+6445{dC}L`f)XeduGL{MqzX`?>AO^Ew12n5s)pp_=7;%Ou3~z43P$GH3cm zPF-b%uHTHB0vFiDqX5YId}W8{HJCC2C{p8crw~9sWfI$;l5KTf-v@sUim}NkwskR8 zOOcSVLR@Tylethj%W!vUSsw5}>Ih*F8|oJ(yprcvRroN@!(^QzakAgW$29L&Th^N+I1r>0B{|32+v ze?^4f>CNWS(qYePxqF%J?=!GMeFL8#6Y~a5Ldw>+hgsA~b#?s6EUBD~}p013J z6r6>~br^gFZ$)y6r->U7L=qVSjrAP0{kLF#Smjghf+NWe)1*eyEp>4*X$ z@Nl4nQZbw}UL2>iZc6uu>3zwPX&8Cw_u->Z!(BogGkA1a}in!opdwOd4Qz3AGYOU;&elA&@p9j;oJH z6lP%!mDPDU=^(x8+pQ1`Yuk!%#QzE&h$l|)NkxUuaj3rF}E`!zzWP9lB z+ESSUjv8*QPNF+dj~PV~wCU?w*@Y*=g>)&IpEFk@8_7qmf|AOYabL<{v;t z3PN}xX_I_|^Fs|51@{u@yMQ#_`G|UyAE`f9b;l39FgGplNB&^t=nZsO`1fayM_0p2 zXMX10Vh)~B&Nh^k9IE=B{+vbH1OYKPfa&do)H~;iWL*+TcVPepj0jImP+>&Y4z(P` zIX4jWK?s?2#XN8s9jZB%@Kx($BXs_`U^ion*_G&fm~}MSIu_6*Q~fZ`g{_e84hLTl z0XFHO;ja&0TcE@Px4G<0p_zx?fG)|!=O1V!kH(B{PF8)b`@P<$HI9Y1JqKr+BY+J+ zl_>!!$`OuQF6mqdL2wC85y*s4kc3akzj={$za?7zm-P=j| zf|kia8dT_kvUDx|GWPrM6FT#S6RWUp2C1L$!3gQnKLdUI#5f4#^`lX*9AUh=6Pcw) zEN+mX-py6wL70Gwp|Gs8=O{Gvqc1Si9Nz0a%y3!uw8_(#zHP6=)Si2hD;y5-?9Ax# zLaMfbkF5@^D^DQN0~sd@9vjr;sb+ z^)(qFX{CQ#Nh|f6vnZYOFF2RopxcqENpfpc+X_#F#;cORx zb2p%n&}V;0W{#PmZ9DUGx*Az(+jNWg^C#Of z8JaSDz>95yF97q78{J=vn19ft$kyob49}8<#t>0LUTm(Q~t*gMSUFfbWP& z6boqNX-cu-#0Z!>yne|F#lS^Ppf0+PK7XdeY+tLL{FzWk+@-uJR{ zMKloMFw{*I{eqI}a>tY;(gik$>=S;6A1XUuKnk%zHO2ctHY@3OumNcFCcl98q90$i zPwl8aSmWn@A(NA4)r8o{y&EffnW!x1HdcIJV4DKL9C$IC2Z~5@h*|E}@b5JQKf@zK zeq+_mhuDDfdjVWQ;Fy^@6X7aXMpT>`6Yb)$$N2fz)+`jRUq%w7Je(W*0VbdCD!1GL zKs=Yx#qsCc@OQ`Tdnch3?{taxv_U>T7F638M(E>6{<*(q4|QG-s3#%Sxc!LWJcs`~ z>&kkow@rrh9Zq)2t>=B9KM(JKX3YrSs(LSC)};5AP?1px{X2mj^?lW4Hu{Q1sVeOp z@?vYN+Cuy}4iU-d0VBf|NISq=p0twbgED4mXGOzj8WN2|TR6$$F=vvVb_X&Ra{3%y z)B+NgrNNBoJIBt)OgX;+wQ>y$4 zXo*>8N6-cO@XvM-Ik5XU&2~J$mIgqkMeOgjKebjrQ=4Ulp&EoqP@q7o0N^Q+JCp~Zp+eQ$JT1x3qo@?TM_#5fS;RFT zAq!ShlZGQNN^SE{yn9MKI=r8Kf%B>dn}#F2NuH}s-hOR|0>NI2Aku*t23t2NH=PPa z`M|Gmpl*JEtN^a2UK=&(P=?;r$205|P`pM+$LL%0?-> z-&nWa6>Rg1KZ83XUVPAX4l9>iA>`?}0K{KAip zG&mb*ejC~`*^5zlztHOqN`auRbBDs;A99}|0^VkUF|h`00WNiZ=7 z=lHBgPF{>eVGj+FtNGa2S)n1KMlB$4Z8ey z#00u}C&=&(`1?~95K0tXm{lR2BSA)G_5Bi@cc83OH2QrsH61_i4jGOwR8uf5x+{s_ zG9KqEqpUL9ejcy)&j=ViaEE#*`~5|l!E<(6n|R>c9dUpTP)S7E=Icdle8rH+?`V<& z#w#;RY4DaDd!GRIuh`3)dR_Rlz7err@XQ8au7a?#dvr=-sO6~tYQX_=w=@w2!lyUvD>|Z}!1h0Tw7VnA>3EreYlQ{9O(f3Ys8a4K zVjRzh`V*G@k>PgB0s)k!ieB`f%G^%x(oz(B&4wSUDYJr$*tC1XwoJiSUd)G+-n^>=>Jb5EPzhn$bcN}NHQfg1yyqp5%GWYc{LZ-O@jKkxi{fv7Fc zQn0iW zZ%#pDJbgZ1&{H6H3?2(V=bh9pvH$>M`|H5lm+X6~z|S2-IXj~iFhlTy@H+Y%Wdr62 z<4`$jVxG4i_v^A6DFt;!c<>5}zK$S?6t|%S2#d0aHN8{N@cGnbfps~whyWcUjIs-` zwRa{Xa5ZW2Ew+NrS^xKad318csDzF@x!Uuf;KDVIkL|a zZ5f8YE;o8>X1rn!pzoq@qmW3AmmnYpF^>j7CrycKXJBfwKR%d2You1+egpnN^wWI2 zh@>~S8bNv!NK2Uts}NXG9v*j<{pEj~a#?tg`}Oc00HOfoMK^UyYT6VU8MDEm4g|re znt(qK7$Da7GEVSOy>nZtydJ%ZqOaMXQ!*Dj_rA3lrXbG^AwEvyYp}zAHrUPB;;LWd zL6?8nZLYx#tO)@r04gWO-1P8J4i+yBPC~i>NL8rQiOOKWT8v}cW7EPwC!;e$rZgLt z-QW5LMTuUZF6(Cvw zX5gm(&e!L=*Ry`$P5k~VEds_rd%Vbt8>36UbrkkwD*=XB)8%HZlLDAC8sMycUOf)Z zMNE*jvOXjua3uMb?wYCy0h(~Be`TEM%0GK1q@)cb_w#(+tCC&T!&M&N`)mZdb%edx z`!t2_HDGVw6J}E97=!H(G7N$R?k`t`4)+fD2F$0a#wq|^$(@7^1SwYdD?p<0hT}_r z5=Gn?T_Lu3a7=TK^h&^AY>fA3QG)ZFwKR0B9S-i#d;=_waFN(o`K8U~Kw6{!K~tw~ zsBzE_O_K*j{Wa%vv|k~E2O@19ysWMXJMlG`{Zu(Xu9hY=d*c(s{MfxP$1bHlEK(-m z?wy~A0oY$S;sF*ir};QyQb@sOb}aVCyE7}FF7ZLIK{{hs!G~kRZ-Z2*sD~+$-dmsy5vCq(bGL62VXx+ zzB8>_glxtpoDIiR{|U4&R8p}Z3sOk*;v}Fl|K#u~0qry@&W*%N`@ozBFMj4^*7POP zk>9Y;j{8s3IF`Oqgwpaf{IA)V@cjcWa#TcmH6aa>{!jwEGw}Qh79ds)<_H%`6-^F( zRHACBV{|^C_;fNH8^cq3Vr)x@Eub~mAM{%V<&t~9B_Z~N04`m$`vl2_I|0k@!fR)N z5PTnl-)|isqV|cm9ge82|9z-x*5&g9;a^f?kTdT&tb=a!9qr}XVkVY@vYfj!svVcb z(PbSKypr3gi;F#J8?5ZV-38C)@EAO>0MuO*pj97Ym?p7g%1+DJlrWDnO+9^JxcbqJ zn`y{pAY%sbO`s_*)V^+p4AoGYv`7uK-4BwL;F7o{+4Am#Zre#TmNMjELPvK9vL1W) z3$@_@U`+ku==NtCoqKeL4oByGR?1EVHW(ojPnUACx$UV@eg}%u;3IiL7$nGB+u*lE zHeWUrIrF{ue&Eyku)gtlm8L7?AHb911{?zeAYfs?=+ajwu}`+dz*-}Cqfc1QQa}yJ zaYeDKLfYbAHjpwuxWF}62}j^=+B(vo)y$!fU}9s|cCt}q@|uhelmUVQxr+S^8p_WE z6d!nr#I(tRvex|Ev_HuJUGehCfV+-L%M(-15vBknB=;f(Bou<6EUfAYye=~WdMNj? zRqCz*B<;IMdPTVG7nJou1AV_J)SUKTMXF<2PLJR6k$ReyF{nF@2^(!Qn-lO(SpW=V z17qnU)n#qIMKduKG$7k;JV^+78Az45jRh7np$Ps?hUqUEl0BvXQVc1Dpc2BMG%|nS zq8!kr+j}x>lhhZ_u9~U~XT= zga30c+gbp*w^E+pudy0*DM%W|gY@eidjb4Y&t*;o2BsSQyD0#qKK_LmIxjqL#Z~`E z{jhV}1E48tW>9CO#h5b=$IiL07tkDRJTJ$;#hrneGkQm3X#hDc*~=q5@YBf89`#Fo zYmI@)6ul>KzaO2!mOd^!?_x+=hm>ocS>zmkQ%*mCTgRiF(%(JGVV*T*X&CqOEwCb8 zM{#f4`XL<`I)Kph238nwJN9a8k9z!uQ+>VTOWPw+W)3i3c+t(@ysw?1s~};A0w$Yq z0csLCqhz3pB%!#Fpz}ilpdA%J&OSJYUkP>G&u3fFqN(rQQVPMZf^>6?A3#(rEi}cW z_^3a~f~D^c7>j_}>4uogAfT`br1c|%wlR$9fSjy{^2-&fTMv-Su?+ycGC*h&OuLJ- zScLpUs@k!c>1lFA@6O4>H3hp5MRsgB20lIv3seGND}D`I{*lS!L_tkbgZuQZZWm>d z>vnfUUTmAecM7TPfZE5le^^@Qp^YvjZ`6w2%KSVi?#ECrsmS^Hnz3?*FBAAc@zosT z8ILoS(e;f#Y~8EexPj(ePA7GD+c_!5h>t_S8AK>5NaeXD_@2Q#-J&Nl(4NYpN%a%e&w-Y zM?0CANLW-0BkDVuhXjV>!*{MgwpB+=onU{UdTwf;{Qe7*H7rc8Vu z_-Zr(RM6WijRU0myTfSuccpK@>@8V?qPPxZz!uJo)!K8v{9zBF% zFq(V|uZ3nH2uN>7xbj~@+nm_uwCzoVR}zjz zO%oVUv+=Iqh8r5^-89;oq+7I4lQ02ITUb+k4k5ZL^#Vx77VZ#cpE6xrFzmEx*p+t z`3723h*b6S1>$ah{VWw}rn%M@NaNH}2Q=GEF+3KC5j4X?OQ^}u>`>AZ|D{uKY$Pla z&_|x`G?gg?QXCTi>^I0O?*5#HU^ohlMtGw=a8^P0h`7t7n87qt1!bI&O{hn_J3|58 zDuxvduri2}B}tI!ef%O+#cppw$;#zk63~z+q4~|}QlSKHlD(ka`tYILxmZTIRpPi+ zb#mHuO2T+#D-gVxVC5}PI)}dceI}~lHQ-5aqmWAw^vIGjcl=9;xjvw&`+%8Eu$F@S zPinwz6{N0!!~&8~zI3E*7C$~+-`yE{7lBci8t`)cGUz`ww)?5`p8zcv0a$)$MA-$z zmh`SZ-_=D8fC(p{h=UE38_fv}A76psRTzC&E$9g<*4TM&Ct-mDfWAH(u9BsW9ymt^ zLuv6Wk@PW5?X{U3{nC-`aQv6|FUuAiEHxb|41LLjyIW``wp&;>WhWWfd4!A|Th>j9zyf)~DDWw}`EX&__u! zC_TM7kZ}G9)*ZpT`h=D#*H945rIzPBXlN6F8tTg*#w3Q&89|aO<|Pi3h-8{=y7)be z1#n{>y38{IFC{B3K5zR@73dIet@Vw)A?kQd?;c7(WL*433`C{Iy<>E6lkh7VhM ztZ@gtFL;nP1vn_W=EY-*_U7(3tigjaq1=|R`=nxM!m$o1y;UX3kNF)Km&|!81KUW- zU4U{XRu6*AU8V@C`y=@*`0Hd;RdlT8T^~sLenE|~S4Q)oVY@zwPl>!O zfGa`Y?>F|6J!k|Bec@RGG@QkdIaYlMe-W6X$jp=crnUA8#ay3+4`V#!Q!bA&t1Pzm zgL)k&RaN5Z>Iv7f0)N3o(cBmt(yH=#bke~UOHh$YSsgl>a|yL z=WnYz0YcPE@k=IH@1QKiA)W;$mu zVsBmNdP7-(%!>(-t*0ryfv9B=2bgg|kYN~Fz1Pzk=g)+z&8Grs6%4p#@;-c>7gz{? zis8y53G~U~9$8;>Ggfu^fuBsWJV@ptfL0GN$FcxQVp-R^tNMo9GM9eN&^F2v_%bD# z%JALrCMEltxhA;5=2nZxQf0W_UlKSa0sx|<$NP7S7NT0gVO#HmD+y9x{a=Zk$3pfx! za*S-{k8{697z`H3M2i(I$ly`;`t#|F?vyyLUryxvZ;~3xpEL&Gr)Q7yaR>8U@aZ;z zUBV@Z1l)j0v=N^9JG3CT<)eu};T0vic}{}zYNoP?5Lp6^W=M4<=nIBTRxD`%*+gHf z6b1f%Hb%hJP-&sAY+@$#qZoh>yi2Do{A@Xh6@ulb%)8GH@Nrq@9Ex;6MhXq=wZ03o z$)>yQ5dk6*%+WLdPN~y?G2N=FLhWq(pu}GwusW^iD^TnKp3$h)_QH9&nbl?l)>Cct zj*-1E)Uu?vS)U?+Yv3pn$Gcu+^@|_+!sw6+_S-8Yz>*YjIKl#+pWEnHi+*oNS3eBivS{AD{D#b1pfiCQgHF(JAX0@ z`lE7PsjoW{c_1O}b>M6LK~USO@MG;KlM(_LXqcTi;2{YwtJ zD>D!C_wviE1O^0nigo54>sTVwjMoe^XUMDC2=W5%%cIX>na1@Ekr*^MjyKLzIKb0> zSnXNu2T134;vZKOL{!Ol2QUtTgI!|pQv8JS&M7TGuYv7wX`5hI`vZj=ki4&%q#1HI zp|a}Url1jGa%2!Y&3;ZNp%Gb6A}%WZ9F5KL^#l@l3jHszxvJS?f=b;Y!`|A7)plid zp&!Q@#_4DvwpO1Myd823NnQJhVZE2KxYz<kRMxPG#gbZU>5(n3$3^a*9pd#hnhouxXE`%E? z>%zuHVP=5fJK-Ix*F7PK!5s~(T8?|3ni$Q~ZkFFyBx%jL&&gMzN;_Rw2MELu2$+3NX7!3S9R-T*J8r>!1Ffdnzfd31+=a zev5Z;gghB zfqME94>H>441%4Y&G%t+3kI>+`|R+S{--{fD*;7CP|*Oni>^SH=fU1ROLw^&ozel! z8W~ks0pKd33V3B&Fjd&I(i^<3>JDCx!-M!2q#jOg2inF{hvbV-HuxiblnCgx=P6n7 z^(NAN&4*jHa4gY6#%#IJo%Fnev{pPs)+_A_Jsg?mwTLpw+|KzU96^YmYHss;lJ-#VL+ zyir3M>Qa@TCLq9~;OtyRcXZu3<{OT#i`RYov%9tW0UA~ARNKywF+5q+xS`Z`}JLc5d@RN}j4c5%}Naz}!9^avx6W<&NXB!Jh@`o7&Qd6j{K&N)57n)q4+XsF%V%G^;f ze<=V$UA9V=R11iX3tIgO7Xn0)swXk5_AP=NHHuxjy zEtBnEX zR}K2F0MQN*dlduV>BG!ef2`|-f+@%kp)vfybeIWhK>TbMFpr1E|LR7)F|#wy&qj^F zcxDjxO>^bAS?Rbj4xj-$zXI9N#Aqj3@~ktw0wIeq1&j$esixO)FCX}k z>WQEwIN-v>F`%&t>M$Z(uFgD}XY3<$Qw?^~&;S^gvCinzfsaZu znxaB8s%OU67aXd_;+52yPe;#yQbKlKdQUHMt)Ai4s8{1|;>=XdU-*Dq%qt~0^I7`Z zWl}I0c%$tn$(?<^w-Q^`Lb!oORCWuLv(R09mVg%j{sjF>3m{-_lrqAp!R5@b-q66< zxoa?Ssl4YHdiIL8+`XsZr|Irq*8>hMx}tKim=p~$Wp285&4Il=V`9Jpr$ zGrANoySbN6PlRJGEnzT`$Td#!UH?(e!O{I){cphXi#|PU(etc2;t9Hgd-2x%MFXVe z1d@ox$!b!ngt$eXgo%)w0Y7DyQZt^gD`P|ZXialnHbFR@6PTA z{7bW`mt%wlSo>IDH$^mCHD=q{|OdfbTOri6rclD zfK`t}eeg9-9%6OM2R?^Q$6G$$uRjcp z&1>}bLgWW^NG+p_P-C<`ePF0+88CjHB-G+OQ4Ku@iW@+nq{0){{6CVeYFkk-jJ^^` zUrLD}ptRnJfFL1A^YpVhv(~IRB})A9#SZmFneE$^4v(rF;nfo9>){s8?>z>WP@!xf z=AhjO{w05*VibL<_(nY)2=|70!+QzBynZ9H6w^b5ZytlCkS{H2Wk70QlShp0;qFh97Rj?w|6%R(0PR8}1%RK%I#n&El_h(^As$pcHv( zIvZYCCofmsh#*Bk*qim)X+x`ru*$)%iZr`__EU%WUUK*qRUSC|skPc4smE%y1njk` z8>5ULLe$GnkfH>RKt6HQi+C`9=(9qXZKm2<6{6wPo9&?g${$|XKaUlc0(4(cLG{_5 zcWgMSx*e^eWuD0IC$az;T5hJKkGdH@g^UFplJnsw8KDm7@ex=XuQZaE^b~crbeo-}; zd-N)#(L>!=V0*cU$$J_VO9-=K{=oZzDOJSn@Ulkz9J~EK|K4ar0w(mm>pVuEbkb_a zJqj=;J2D~+Raj#o_bn=oynU!~%Yy&c{lH=d zp`qR`6C4VTaPpSsy#~QJi=Q~-#ElF1-=914v-U;vlpnNL55ZMQ@^2gjk8=Iq<=K6@ z-wwr)T{<;ur;NVb&KZRp-U&+<{8CTfkGnB9UaZh~(+?71JXnT2UY;M%vdQja-7@y7zY!Rpx9EWR4rLP%ix>y1 zdbcwf)PRZl>z{AbY>h~_3*%QDORvz|k2sts8pPp8!FAuMmR3-~XcD0FZX04tsv#{yS6SJ^~*tknr1-3Kw zn*_oujbAtc3`c$I)|{`_LqeFY;{QOZp|*JXQE%tmRx4X+ycA@HLAIGL;NwJ7qklCi zeU}r2Wl`hYZ*aWT@AL}tU7CO|^4mw0=Xa7JaSJss>vx3*#P2FwC)AGu{u4Yvvbr=LBY_|ohhKAcZlR#s?D}+uXl3J?&pp;_s5u)1BN^DoWS(^Xd>u_2xo1zHDeAY4zy5^Ggq(pq7)QIj?Y ze-o=G5*Br}w8pkNH~KKsAAMrNwC%KvV0cc5X|ugphu_eic`JP^?og#g^$H=Q09!%H z8K4bv`@OkV$ojfYlUF=WN69%rl)1&@Qe(+H;0}}lE7s*E`^{eTy%G=zWxlVU$-LwD zrN-5CWqp3M3KWAl{YhmIGAA`JTm@177`UI$>& zP^8zW4!_-(!QGuD-S^26%xfAU*%Qeh#6K}H$w2v--}5yHOeQntW1gLsmypP9QUQBP z)1yiZw?P5R?mgBKg8yd2R089HxiZT;@>w#hZ~X{{M~>`{DhHQ}>67)KRq_lON8e?gRE2qnntV&+5Lea?82?IRPrHIDQdNkfN0Tm@;we?>hk4@at5Nxjwq0 z{eeUbI4#h0iwHzfJ}pWj2@(&Sk15X4Z-_I^=ab`D6*2{Z9kvsf1HzvhOU4ateauMt z+XE-|*pqI1bJTZO&!c~M^ABW1iJ0g=@mz6V*E?4Hh!X<;a0|cb12oAW%ged452>4f zVa#Td8iF$*IlF-$^amM?8`O|aEvOHN%MiU_-1{&yNW$Wf?>9#CO-!8}6VcP;Vh!&Z zkkmL0x-?+O`0&S2^@(pc#VC@ZY!Di*M(&>mi>4#mUFG4-b}!Ou-oXp(i{mNSV3NJ6 z4^L)_8nqqM`&etde;Bq=)^fDw5xLRowK29X)jKr=Lfj8DxUd&KwbKa!LvWfC?#Un$ zHk7rsQTbZ3fl1C+quW*}w%5(Q-+s_8(f+EiY^T{&mE9?99Tbz39`WAtx_*#~o_80r zR`koWV@jKCq`M@+StNA;k;ZU6LO^9`KVEeKJr5^1@1Ym|VHFYyNwPoSS=6StjfaO* zX~9OhrmsBD+^4FaZrN=>51kCgc+@mU?V*vSx{nSQ1*jEd3gj{8ZxGkixBaOqrQcnM z)4(W5p|-3nHw(D!;AcXl|6X8+*!Lay8(aQ%tmzem*ZOQg%6fjVslAooRwXAkx?X?u z4FPicly=^bX<%a!elz_ruGdJ192k|8Y#F0{#tETaM09s0#q&*j%ZszVddx6Ui!kgC zDNG?Az!$lwnBAXE3zeUO4OaX;OuLVRs}T2$O-Rn4Fn)h*S#H{kur5vT<`V{r)vuAP zyifB)o&=*J%JzmTAy*iGT*v?nN8>yBMaJkMHt(o9PMv)xiCg~HX*(BwZ`#{qA2fQ7J<5Q9w|up2_>>N5fOn=c8aQYxTK{z<@M@{ogr6ddd9`a4w=xyEmQqJ9C%wn6%`(oQc$XwpG{>&B^UW zp!z>CBsEppKZGj3$D(Dvg!O4X8}+d;m9rSd%jc1;7b1Qs{8G+G0xw!~&30eZRsqd_ z2I&x4j=IeQrNb1N546o7yzc4^^p}>N|ZIEV~Hy25x6xH|tRJVL9ioXNni4kICk9fOMWb&Ah6`pRgQ|J~CTV0> zYKROL3taIRuemf=6+`Sr*<*SKwAk-jfFjBhLny%n3E#u@2mjZOKT~<1=O+Jb4q6s1 z&$&h@))Nk}ZNHJbghwYm29)@!pXgm4kGf=n=q^CTH>xVa&62Hsg{tQX?B~iIOJhC- z7R%JA&+v2Jzd8C?MwUZdPJmip$Rj%E{5G2yB5MDIoc#mIiK?sgZK#3&t~MvrrINMc zdsG3hU7|cA_VIx9=JFVB#%f;p>z=buNBDBuJ%2PdqSrrr;P0guI@qa<`wft*JN~EV zydi|A{+rkD@XL;(d@Ig-8TBn)FQ1{WpLt~8Y_IZwJ*9l9?f%$RB5dC%J0(~A&>!^lsUY>~32P62!+Cf^ z(O+O*zSY`KVK>TBWq~e8iIqXJk+(P;3{MnP>iK|NlsgHpex6k?aL#W`J*bqM3{PjH zmhI_DE^)&tza7?l2yB7$eZxbsadW9)3)O6R?t3l=q>OQaN=wzPm%DI15HOr7*|C0; z{yY5EUiiqvJ+n`xvHdP$)_90h$&XCOAc4oVe-KW92pKn^`C8|xT#f!{?BbChR{oP)k|z5l@ejLYxv zjrC*wp}((~UEjr_BN>S3U37`pfAot~s@Lt7^Y2SvGRdCXLDNAD7{B(1pbqMrG_ zOvXyG^3wqgM+blvIWjHB^m<)uWz-vFSO&_s*0_F>`{FpAY=(U7o& zz6Ep)cMVEPE|=`#-9L~vRwEm)IM!7yN!SR#BN2U{c809g3+pvK)xSlni%n}5TNV#oZ$_(1-g;7jmWI)HqMD-HgUYJ!Ph{*fE9N)|GUgzPs& zo8Z!uUx(Q|ER~RdGR+MYQ@W(9<^raZ|v$?M-k#X`_SX_N! zr~D`(0-@hd$4AmhVH_f#74tO%j*EJR;QE`x*~PCGFMFax_OjVO1opfo!T~W>@Op@h zpk4O0X{aG&wQqw#gbKB&iXkgd)*Ay_mHsR`5TmQFWnU|*-s(@M7O#>oV&>T&)c`_U zQ)up-KC&kP%ff9gK{XWPFFY~g2UJP(i-mJjJw2&hY^G{+f0824ln&(g@{Q&JMvg+D z{WKGB{#t;445cgSavNU9_I`fQ%2m8qB}3lFDMhN|NlcjUVd(TT4r6+FqNOdd>;YEG zfOfFbRd?&dtGJqLTSpnNG?@~tl=8J!DT3d}H4u4^=#ku$0|bYuUeLlqtv?Az-HpRW z)Ky91BvJR->^8mg^^vXfJ3*4!&&L9VqKkU=`>U_6I0c1h74GSWZnB(x7~@W@@|!Pc z!<_Llyp6bU5bR-qw#hlto}Kt~(x>lUW2`m81ThBKO3}nSsg-(#&ISF1enFZ=S9Xje z>0lh$zN)T==d~Fj$c&eTEbXfImg$;@Y~;tB8$FuSUI$qmhOqyJ`XoBrqQM__F{Y(G zPH*ekA=U_VJLdtk2J5bG#I`5 zOWP1|sLgenlb9Nk%eMlgRRbB4-FOyi2sa945AB#Az|}8K=kbQ-sLu)#-Fx8NZ;`h7pHCEICNZW%xb7 zl5Ic`hv$7eo#{v9aAp-QvFf3t($JJrX#14HEg>Ig1FM)1mQfwGZ5S&A1!+ePcY)5j=oYyQeU83_yXniF;D6fZ^5#Cw=_pYhVVV!E-7c5c#uAXJ*`!s}cGY8XmCjNs!fmm6 z5zoqOStm7ZMzc31Aj199Aq-6qunA@2t0v@}ZmRiI1-ifJY#2;7E~9=(7_H2Lehg)bPPa z?Y_ORRPnxus`)vB_&_eabb{VYuWqP5$uCv1s~AJOso5JAreVXl4d2XRnvmz-uPSQhKG$gDec-5PL)jt8K z5pNP8nMW&7;Z;Jr{_UlV<$Jm972bSi@+Eg1Gkv|yG~9#5M%QGh92@yT4)+d<`=SW| z8GqWJ$1FMr3hcDt(0c$SqH1Icu%<}1)nPw5yxe&{K1sg(ZLFruT*@;Kb>13LjHliO_hj+FEdPN4m>wj^5rveQP0ICDVEu0$`)|5CE3)B4 zv659Wa?!hZ1g;XFP|P9?)b~5UWmrTFz}522{#3p-#VVUzjmr6%5d8ZPFBL4XF-|!% zx>Z{Txa@+UR`gDvleR|iD0AIc&XW96t35!)Zt$UNrW(JPNyEDFXU~?q7QsGr#(%GOr7Zi{!gBbc zb~0d>sA~kUbeFQCkFO|B1I$i-jNTK8_C2=w=V4Cv<3!V4I0>%JcAN?1BiFLM z-M^mP248}BLh(cNh_%&a*q(uwf@;46_kiosv5|*``{V_*FoKJ4^Ra+yIW50Z{?P0I z8~BkvK4CEa9wC8R9d@|>Z)A`&3S&A$M^Sdb^-@|c2r&s%uwT>% z(VxoP*CYE%_1{rD?8{aD{lQ}mf8a)qTdVnKLZ60oAcU(?_0zg1$HOArAAK1fP2(0u zj1rguJ^a8oqh^Q}fs?Ut(h{!v?Y0i&1OC8!=({g%$?wS;LdRcTK$9`ApOCT}k-QoK zZs09H6h2Hh&nIjR5DT}Nj0J=c-(St8eYm&3T9(Kb@B84SSthO(mdd zpreXiAgxPNP?zta9&Yv6yb3kzy~?m1-2tDOK!tgCyAxfu+PAOE0O{B_`EIdFn^2}2 zKMz}J2j`WX9RJC;#e>MCm4fI^cIS62mv~U3*rXySaiP>~$!iwfPX)80Jw4CSNTNgj zj&CPzr$IsnynID-Y0-9Y_;H~_Ucr@#xn}M)Fy)4}P<(&*{Fd}hquZj9y|nj-SIEC|N-RJc4p#tb z6Ig#OE0z6XC2Q8_5-=ctDcF(VU`2_P;u+j)AEgk@}ulw19AmJ%E7VjMi zDF;o6E^Glnx*wbG_M)Od>X0|sx1Bwuu0Qv%s=mlYmQ`}Ngh4G+43viZBtW@(kdCz3 z%X*>Fnn?hesVaZs&dMM0N-nX)i5G<=-R|bTr`EoFc{uVI?Dm)}J54SB^ig{R#UJP<;w=6UhWKi5^ev^o&z~+H?dKc_W%g`f+~eV(S^wDBIYrH2 zNOBgud@LYfh=-?En-&QgJL*78jXK9{9p+j)fHYIJMSH_Mbu5{+v56 zGgEpV5pGuOs<#jU|A1$R*Wm*2ztXIZbR?a^70whD?+ZDQq@?zBV0CzNB7islw3I>m zM_Qoqmf7_^Kkgs2uQlaW5fbNmSO*w;z>)>J=7BJ+u5b@Niq4#aY6xA#XZuH;?stB< z&a}M8GjTwEf5Co#`^t{MR|tPuyHB=C{IO`f@4%}rdz83q?8C)4wzwUsxfhncx^Z7ts<(}VOYc|gU3JF`DrJjAPava{kx_qVei zG{@vm4lUFB)gZ23M_i!6ATJvLP4g5_RiCo^IT7ROJ!a`$lp9c@IaM4=oOliPs(+&Q z5EAaJ*J9t{1=goZSIHZXndqyVUU|dWd@&}i8%Zwl3X-mH;rDZC?8pz0ZI<7PfJYjB zGkw=j=jHZMu#f%kH4G$svUD!|t0b=%0NlHtxNtD5U50k|6%_O7rxJvAh>z4eFg0Fg ztxFPp>?>1aeHGKc#fc{Pzi7 z+0fnJ<4@tH?hjieQm9y1dZl6mC#0<3#t51QTU76@MH%W^H?h4IKqpWoKE9^1AOj`-b zMeWJL(-BYSd6O-GG&|z8U#?-_ik2RiOIL%tl(784AF|&*mF%-PKdBdV=$~@%)1@~M z=-C=UoB}4%P6OewdhT?%lc2_{P{KT1%(%bsH&=^$Pare&KdBDy)35{r#mY0Mxpu8R z&+@{LLd(LOL!&;mx~x_QJ-BS+ zul$?s=#fKWak~q;cAa3^sZ`!@Jbbr+c26M#G#^aq_rZR~;;Z(_{hGe$i{q{b%SwJ^ z2eE62xAM#T5T#;ihKow8kG@yPcXzxG`y#1R-*LuQ<}+Vl`FNVBFdyKH?B_3jpdOI& z%)#l#G9$8|_-*cChVy(T+b#Ud%Pm$!ZfvP|+_J6M|sLc09W23@vhT%jy?5fil_kuj{2f zSaVL^dKA#8Jy!)%$h$xl_05j>5c38~cyOmV7dDe8y%!D?=^|RFds%;B&fDcncz)>0 zdUq<6lpZ&8QjU5ntn{Uko?2RL(-VCp?fk8O+jb^PJ37hDYYGFZb*C!8M}!9p)Q51* zC1_GY=T@#A3l!dC7IRuY~vGw*Q+OYQa5pU5z-dR1~IA!9M; z=81mBX_y%0kTul(sT#fL{w-ix`Gzy-<+)F&VB79`acpH(qrri392`9xDHz=6 zD)MC-=wj(Q6);{6pYw|Ws}RPW&EOqh)Wh9_oD`LrJJ&GN>GdEsJAcf>QGg)gN%NEU zQasxFN#~Cb+&RD}Tw+NcR$I5F35uOd_7sq6sG8K1^T=f|=~gg>#G(Imk!Rocn>?p7 z`v5ny;LSLEK}-v#>Y{C&wAQw=vu8N0{65w6>j{5hWEZ->qY!~(;k*QceEhEn z`uywMbTZlBr||*}5anvROYg)BT&JD}o;Lh+aK4zM5Sc$3 z>3an(1aY@H$rOnb za^nSZO~CgbA`_W}U(5C5@#N@p*Y)-`Vx@rudFkJmcSw)0Bp(!{cV9V?c|aZiP9lDpV+kL-@k7Rq?lpBALB?~@)C6tD}>isOf>U&-LnLn6ZPkEQpN zz(tMD-xNjL)46mPeiShtM0@8GhStl`|I3jn7RPh`yfAm3o(9@{dhfQm{& zVU7V@>IajpXwULC=Qc+0%GvkqCxg{@_ZtwqD?Q)ZE$^y4i8}@|ID7)14Xgq@8jlSM zM*Q8l%zCR`5|+x%{Vo(4b3nfkXd;?ZKqrQIvmW$}{D3V)W8vX+%~>_B#CN0z9oXi% z@`Cd(4$RWCZ(>3X_2nDCT|4D$TC^U&eXMft<2%qPFxB*!bGwen!8mHL^E{w08dOA7A5{id$`YUQ+Lg=(TmwrfMk1Zh2S76s3w&8k!Jtt=NGAo6P%w~d5{E)w18*>U)$Xv!Xj9?J?}8YZ*w zR+JfGCaa~aLR9+vwx&00J=g|hfykmDM!{80g{6>B_cEsg>3o3S zX_oQ_#oc=SJPk)!%Q{zRI28Bi_s+JCV!VX9S60P;yiclt4mBj`fg*z^L^X?=992MQ zvELM)PRfTk-&bjYp2<6>sL>^VNkSwy_7S(CMiw`z8pY@a!DJQnU)9LE8P8sonvLZ4 z^%D->->SMXs~_XnL+vp+w*jpQLN$KIKTG}^+(ZIt%x{?qO=h}$Vex(yiJ8P+b`;2= z6;lSUbdOncB8mOdqqoLnI}Gv-yB}jxMLo>xO?iIH4xl}z)j}Tw!cOu9#sxL3+NyCME!MCWC=%`4 zER;5{J)|(+HAlj^dLJ5@8|&aR)FlV~pT8*f{5d%i$oSI9uCwS>vE3E#Qoga+s*p|= z@CD79@A7mYSP?^+|7`n@54EIG0UYHZPtUwRkn{0rRaJKsDSGu*J+X48uX$0W4*N-| zYZL|@h!c}VbltZ$U%7uM`j0Ed%aXqr7AoV+?N-yvu?}rjFT21$Z0w&<5#03G*bND6HM-g zG8jJP(E4xZPh1fWGfCAT`I8)nc}^#WA`pbN#v`B6#pVpiR42fPY}qMH2f^myHO~WC zVoZ|;E2~%1%mLz`ZXl{*(N3Eu72Y~yKH$UNw=Tlm8@26CrR)7jZnvzT?}l?f5s;F7 z`ws#sBmhu9NLbXNaD*eE`Fx9w#KTMGwEd!^q%?8cp68~P2CjaKsruVyEUN|xNO=rB z+vG;yJboFHCf4^AP}WxW4Pi<^z3vwzfaiH$^ZR(Nzj^TPgvKD!4YwJ>DewJmPaB?% zT71?6`#kD#a>V%2LF7DtJ1*@1qC$l}Hs{}}LI&~YCrzDVe2Q=~5~%r!V=sSVUGS`R zJ{G0?K$)mJlEDU>XPdU-U;O+D|tAZMMJLLr0e; zzMSkr;y+?+JTzMAyhDSY@`p{7i~X~v6F+z#;kA* z7mv6LqEGZn^(nRwk1j!M<5LNBL}t4<`~_JP zHJPzC6U7|stAQD%inAX5Nu2LRI{cjZymF!RC-rf}nD@B_IWsgrXj`7Yf`@|l(YZ9h zpkQ+B;-RXxo@4`b#5u8_r)m9g{f}03vAJK1J9spP`vY^K^fn(fUJIE<8bm_m(ssP( zW>XF`CdhaU*CMp4PDT(ud$0UTnSEzEk@svU@n$hn!uD3tyaRU2$hee#&GUO{<5H92f9>yYKll zy2QS-;$K@7PsneP&U`5T=~gOObpJ$la-_bfTN5JZGxHqC}h_N!cbEAw4Lx z&gD?w@Gvx^GK0qnVktb;Sa(RC{O;@i0Sh-zXy-h|%XB&TLbd=*in}1zm*DU|E8f2U z`KCN4PghLKib_ZF9;3|=XFx)azabsz$9>)hYt>w4dfypF@f7{Sz2tq(0fqPKo7-&J zn5OB%CF~hO9H=;g#cF3^q8m6=9rl1@k0c$(-m-7b81+N$r?kC)*hrB1@B`*zonH`s3_~)$-f>nH-J@o!|R?6y#?rObK%b9&v43rkOtW9=RF} z7T5}`u5lk)H#lU_aGQaw3HKTB3&fxM5RBw0wRC0PcPeSx_j#^Hfn$Fl0YgIwX^+AYkhIFhOe%Q8b(8`EVyeafa=y zb6>3S;3X>^;VDC$=6P9S)?*6f9*f}twynNNM@Bu=r7IY8@CXP1fV}KB9)$@$w^ZqDJk~`43v1^* z_a_e(MfcLernCfuJ6;(L8CiLb4*KCbR&?VNKlmaP@)2Mo^_jVD0Q3zG;{+cevjck5 z#{>Kye`J5B_ebb*`uuGd`F>GhjSSO@+Xdbwr2HJeKR1Jw<#;@v?0qPmUhAWHh|=AU z*BS44_44Oseg&6$UzJ-M+QUKg1lSotHhz&ou5JGVnpSBKp6x)^j-{j^A3O7*CtM)} z!#7QtI`<#(C__5_noul6LEU4@r_G5d@AYQF_pJ!2{%xZ7vdgZD7(wFc^eFZb1Hi9L z5@#2Ub+|iEmu)H^XKj=yfS1xPB96C5Q~=yh1VVj?=_T}#*xfAF@!1~2&bG^c_s8_9 zGWAyXK?wJvx_N`FB*P2NCt<}G`>P9fWjnE0KOmuE6xpXSu2L7X?6%Q;%3S4o>2OYh zer-|v#H-%UDRWpZq8=}B;(keQ-falegc?m2)NP?f{~o#LIE^D5W;}lk+HjBg4Vs^o zXJ_(T-r|=$AM*VHniq5fE3Qq1gw*;kGeaueZj+JtKwR+qBnq2<#^z&dp!g*N;wEfw z29YV!QFWg|ocFkLLMH->uj~*sNDUWeK~H70uJJV9VPTF}Wyvm7Ct`tn`Oo~4+?tNW zv=W09VC>)8&_6ts8`O7ZcOTtzb$#o17iKf3C4%b0F%VzpEQt5`siRQqhau0~{TL&N ztz+y+We&><{0%KK9DSTWLKOwPSbjdFU;5dhK^6P=O@nw}9For8dKIntvreu1ntgYx z3!1!lFf7@;l6AgopBebObRQCaPTfguFA9j(&pO}lQsvq&+f=}Lv9oFPcuS?L<7UNu z!~R;T^3vuPA-)r89HTh3h~I*gz)jt}!SZ zfhK)Ic|RTlb+5SFY&fJOgKJ<%Td+%B}FhvYB zh*I0+3mFh3;6GS*yN9#T(nD&Cv}tuuc77LEu$Vcs<(5KZAFbK-^AeK`O!$c}GYmHM zR{f+keBRpYAi$U-3%XV6nQedU_-CN&kV8j2$S6w`4~Gf*_#Mg&A99~GVYVIC{guIy z{_|ocEa7z9nwSik#Z8ZgCiUfppPdZYZ|lVw8$2qk$9dhJc+R1p!U(4~h!D1(uj$IY zQF)x?plZ;Me|qDgJP><+0^$JEcs?41bX%N{_NX&6x#wp6G#>-q+K`CEq2LTDtUs&) zWBg!;mcdvJZ49hGM*gplNrl{2`tB6BluQq6@H#V54_lN&I=1`B*qw zO)`1B(+)9ehUB#{(HcSvFG-eYMsR4x)MME;d;{qRjkhU;DUgk zwoSO`fQ>c6pN4Ch@WNze$G4BvwIcRs6#RZI44xObC;qCc&LGjWM|V%JQoNahFHt2V z^hu_&$69F5Tw0`%FnA&Qe)->nJhAHiaz_%a&yzTI?~TZP`pWqUtvjwH}<_mwiP zJi&D}C2;nYDU+VZeGPT2mvKD=SeT1q)OZm3{2f)OlHU!6LD9n1l1D)utA9U1guESR zEmj8iljNwQrb`1i$v;nz$+ssMwgQ{GFxrIULEu8TA-a5+^6$ydjPyox;rbb|=PTat?R?S_Y;FAj5sB-MJh=wdJfJ={V24=D zFDMWRt%R`^ofIfDf1y~J%m%k8m}Orc;PP2hiBI(?FH#Im>%SXF+II#zWRy}OKe-+{As-$OF-^x?27uWTP zXUbz3Q5%F#Wr2Uh=3lx0<<6R^XjIaRP~MI+yQg%(3Ci2PtmD!d&lY&Qr-!VgX!Z_a z*9ru_BO0(ktr+75G%Z?&g+HHOOqmcRq=gGse50g%d6uoMIG`^m&BYoHe8F*@ea&P7 zO8h5wu$rFD?}z9M^$hQlQ36};!CRdPQ4jg^A$IFYgnl4Igwtz3?5qB7Z-=XQ(<{TA zgC&u%ls#KFKC8SxrQh78r;|})M~l1$QM*Ei7J(Y}r=NAAp?spCR_sQZA`G80&-?SG zXBp#ALU8gfDU+?x;gLA7lrrlN>S`gYRGGN+$m=y+r0tJIet?rG%mVKX@2Hpa@$xxQ z?`L&F!`OFNget0ks6r$VH{U*b3dl?WA#7Z|J|!FSzvEf6nE^|qIL>9EjtE%IhxK(l_o$V>oJkY(|hUr2kb35^Q_}wx|hnG8*|CaIhfD$+P z7w=#83BW@H1;kuqx*6x`d(`2o$DNnYV94#vGv7zGBt#9Q`@Cj9Sh_893!1@eC~wz; z97k9hU{i@5Mf79qYI8<*xEEi&fr$UZ{$RTQE@#M}gxuBii>r9e>LujTP`?L>_W^m{ zcc~>Ql6oh!h)TJ~+=a7Gx>M2=H>;lNp@Zbj;SQD`ev80vT<_aQe~Wsg-XoM2e8|k( zCltjd#AcA#FBXS}YP%hBz6Tyf;0vD8 zFC1d}peo~hQ@G@6&-Ax9D0lIc%3xoUkzQ02x-mbd)XVE{y%oRDsV8Y)ww@58sG!P6|@*)e3uD(Hie^ZDFd`-!Ff7pP)&4$m(D_JnEOG%dZLZ^P)wEEzvA1 zDP7~B{rZW-`_8Txje9$Z^3@E)*$UFpqdhuh{D;kajl*l z!{>2N>Lzm=OZs7-I<*+9-fJ31=OaVT^lZMLueBV%*5!6L?)&bXXzx8Q*)y8g#eE$@ z_z-^0QzfrU9$P8>A!3iuf60_P*~y84!l!$|k;)ggn+LajB8%^< zpaoV<4V&mmF*-jy8#Z$cw0dYFlH`X9W^uG-hfJW}7>2SOW{qlRm#Cda94Fq%)Oxn% zYCKyM$1x>Cpm$~F-<6QL6ljo@;b&>!i=dR(3s_@c<_Yc_d7)z-C z;k@3zhFS0Lm1Nb`ljO<$lb*}DlMCaOK7fFLn%&yq=+VIjwU1u?4SU=LV$TeVK!5B* zgYD#gTc@+e1si05!RlvojnUq>IK)g5 z)4(oo5Sg<5i&!IN(j_}HPvJr+au4kE16Y-8FNTd2{Nlx&|0_O-F#)tNjt-;#b%Gc) zw|aLOz?L!e;do6i$z44e7YAB6M$VLYNUXTN&TbB1`X&;fMvTEuDFA8`@(YW$OdeZ1 zQDLp2h7LhF6nmA1caHby0}%E1eFi&t^U|?PA8&#^x#T^ye+l(TVv>)t0|g9`WX}PH z*p*^zgOO2Tp!X6GTsH3G3w>Pd{?kJAxA!b`8F^!k>t)#Qlc2*xGsFw~IeqS{vfDrR zIuDGe{5M!*JKuJ9Qww+z?^3M>7XfB51{d4!~Q|=G@ zyqpfznL!%mLndq^gur>7AKY|s_c!ZmEF!~$e6u~1x`ek^1Ea|HfjoMjB709g?+}<1 zmmmnY;cnA|usyWb%q1|HBC>#bVSBHqy{z&6)tB?lmxj%d1$HbRrwqEfgg^xQg}L(0 zga!MDXeL0ljWSnjHm1yqZAsr!pjr2-zb!lx6SAg#f-oBz-x7;Hj6WsnSi!XXo z&l(wrcdLalI4tpg;KksrKR5atzIxDFG%6T9&Hodws+aHW_Gb<7r&fd4!CEp+C-b72 z$8epDlvXk`Rtxslr8jwUOmC3hu7>k`z)b9dF-%u*1kr`3Rty_uiQ*?IjDzv7?PoKXwM%2XK56c zt|dTP$0=L(wRe)vU3?R@0N<0DPZ0@~wM2Q=Zsq%`HP^#8IE=&!EJ8sa2^vbLl zQz)bv;HtMO6%YO$bUYFO+i&oN?b-+N+L@Xf`f)WlKU9gUT>Ux{mw@0;v>LyB!k(cT z>fldz;;^5w7wmyyq;O|yTTe`)p&F87rB{JM;IpehlMBrhy&eLK+M;}jy3 z@OO_4)w!lKMJmqoA5GV_t*8=2e~BC(MFc^TB!M?22na|P{rbB(v+i1FX3m&E=&r7= z+TmyH7e{)+H!*Eh=#td;)=4AanB178+~+j7!8h?BsI<>y^<4OTPu@dr`dv>4UQbYc zb%EwQZ7c7)zX1vFkNf7bfCXs{C{W*8j6GM!0s zQREt#zyf!LHAHzsa%zv-*A2I1tO(Lmys>XdPMqACtQH*oi&C$Fb|0S<>R~Kl&Vp?O z-$}7TSjj-mwoF*o$#wUsZlsJ_=e>=Za$QE*>zU)smVo@gTe9Y05W#*x7_jeVdOsg2 zXjf=G?1*kAdSJEN{PaiUoQMxLabCqj?O=pF(FgcKEn;l3UJcG`eZZC1&F$R4aBSTjATF1 zt?BUl>p^+X{^pT@Q{2d_k!ty#*ZEAN4zc~!i^!Ns|9%<^luST8JOU$FKr`u>&D_c{ z*YRpR315$Nz(Mi8>s<|GHIH@e{w#Sy&7o3=qnzP*kzEqQJRF2)dNO&aZZG@rq6+1c z)1CeoO7<;D;1j3nHtud>k_ZQc9`3lNFcfGDfBeHa4BmyaUai!GDdQJ2!840#?ik-i z<6n0|avTcrdUh|3omB_z3fEs_#G=4rKc)2TQGSxj6KgA=`4BR}zwHcvRHsSUB+B1) z1I)s$`aQH^&x$wL1HP zw|7*X>oUp&o&~KsVQj-RvxwV2QoF7Kvi9?yt8}CFl{H(v4t%vny>^G>)(cgPyN4&& z=xIFnn+00nT@b%t#<{+MN`U?qi^cnJlZcjoN9c>ts*c{TTp~|Y9uH$k7_Amb`FHrD z>GdqxCCZE2OOl_~^?b-YF$^7f`<}eJy@j9trIo}7;vAxTQic%_p~T#@Sbp8;`}6|S ze@>@X-d92NQfcPG!U!aje*MpE+0!%df}tcA^OzkV^=eVC;yECBkkqT{u;<0z@;5Rl zdiaH;X><=LK(qev+oM$AwQX4>3!IqZF?28@KbszWY&!G{#t*M z^<4;`i3Oipm-32_!xhVo+i|Pz8vgh3zTE(DQM+&G`7uyw@5@`Kgdy{@cz!*ePElBT za&_||BeARbjm762GRX1ZrzJy$d^Tusqy_Fh>VPYs1=lT&A#`(D`l)|xV3D7QIwEeD za_eqTD*-GoCCKl29U-IhoS-<>e#t6dc{}bevZr}-;(PrYR3@~|PGCr6oV(>_7md`X zfywhZhNzL;eaeR%sd}#3_DuoEWy@SwKd7tYHSQ5;S*{g=mlA?=21PukY&QttP9!`YaR5nHe9Ry?bLTjJdg=4a zxr;wo&?Tc>zJ8QjsgUZ=j%UBwY>Ie4T$p&kqYlZaPx`)W^&Ttb3}py|j(rC{P4JTU zZ6)bPppwG*t-{LU_)FjgkME)qUmz^0V0i~Xy>nuh59=H1K*37Q6IY3syKr?Ax4k#M zX83qRA`Q@PmonLv%p5$YQs?CyI7B=ZXDWPN*hsnCSuc5aK+yRsbZ1l;>MopFL>GSy zlg#rQHRkN^?Xu}^n2(we#U+>yU;b9qw-c`bOPrpoA4|=vcVAj|g)AKZ`vt5AM@2L# zFOTr$lo#H+4Vwt&)w4+E82q0-9zR6?{S#0NX5L>i;val|=iN)$@=FMXTsJn)*@H=U zn`dbgAO32j?5-Ijsj`jA@CO1TmcJOwEIdF=Jw2YAOuT!lI>)Nexaw$hbv^Q8{eg)n zXyMZP@*Ut+bNHx3Vcd$?AujFXNoB$N+6ziCc#VS_pnUp`WS6U%-Q%Ne*-{*tzt7=K zC?C$52}p}a+vd}B(x=6WjbwER;PR31{A`OPNO98|AD@dex-N`tmrB>BQnkJWSc7lB z?}z?m1FzbOOpT`2r7WLnp`h$U8NXD?g72Hw@|>}6EgUkKkF=)mPPTt0Ru#p*bDar- zp}t3Sbb#|P?Kqy2q2NQwmy=Xt)#1)?A^Bt>n!1N;9juF6?Rk86qdxxP?jmMV;`2PO zd=4%fSZ*6Y=i)Zp%82hOV6-78vwUvybaF_C1($H}}$) z!M^GWTn937ah}8~U%x-?yD9{Y2b *dD{|V%je?8fj!c1$McCxcGcNB z??;$~tQM1X{AR)kYCb$am3B1u6uqd?qi>ATSpICaE!kW z-$OcaDukzTVO-cx+m8sa{V3pLcO&Aw-r6Y*HgE;y=GPphv%1HgQRRDvP_J`L&c8O{ zg(DZ^{nWmn6sn2%Yu{9{1c)66K` zrZaRL@_h^tYq*j47e8}gXECc@o+n6Yp3XpI0;*C#(AW{?v|Hg1G1Eox+V(R*A^U1c zOK^RXg_+CBDiZYUHJqU)Snj>!M?0Oa<@vM-V?V%B4QHTF&#WuDz0&fytmwKYzQqG4 zy2nwb_(F7^Y_}*#nhL;XGZCDn>>O1ydjtZU6{6Yf_Ln_v|l_^a#!IKQxEUwFx++CPUR>r%m88WJ->f#?S;&s>LIyQ zKuzp(LSuA8YichYp7S5|C=yTb??ukO!ZYE(Nj>cHFT9>-VbVxvLPm7`%`FpM-cc&P zP5Jl&>AZ3AcKh8bVhR;IL?Y>xGnfR5N)!GDJ=*=)K~LrIZ!FnFOCnl$Bp};Bj>`N_ z8JYk33*m8il@?Fm#YUWgvF~|sQAB$1e`uLe&*3~D9e9XUi_h}>?u`%mNpP%2FE|AV zM7rn}Vu*rNqCa0VC1GQQ5A<&a3=pAMyvBn(b0Dh+b}_KVP8bJ!^PBM8T~jb z0%lD4C2Y8%{I7#F0QGkH_xj3{{`V#6byd5hC(lvgvn|%bl~yjNlBdF3-B77v9Uz@< z#gVWla2*C$!Og$qIpBlCH~r+lKvJJC+O_A65VgnG47UmNnCs%*u6lv@Oz{^=hL<1x zK2#q#CMD;_Mc|TBNIYiisxg%j{^n`>miI3gXAB6SLj+93@y;0QsXzU0k2g>{eDf@P z|2LXco>+9+j}J4V*T^M zP@TGlNBZbLI;eGQfZ*b&c;P<#lUX%{Xc3QQcK!Gk7zqH%<8ikCdDHuzCRTz;+EeL6 z8URjVLyT!dq}ullM^5F34I}sazLD?lg(z`0GgNkF1=JkGEL3V&m(U|k%^fH^`fSlFaNW0edds`AUFE+z+M5M{gX>-fH$omlbM zvYzoWxO7`zdqC34Hpg_7F7^U$9;7)&D3oL%vfWVgIHp=w=+XVF&znV%R0v&n@#pBp zDT3hvB$3X!C47wc6_9aq``-Ig)e*7kc>s@wpTh+L{@i6~!6FEsjCtEV0F*D*?0ugq zfv|O-&mRw}G#AWEW!I#`QxhxP*mO8~{9XdkYbZ2Kx$>)gQ&5>2^xL_;N)SZnycpIe z0<}m`JZ2TL7fxzWeYwX8*2k|V@gLcb-=|ey&5X)AH^QCG+Q!Dg<$x+xTKj0veU`^W zxc<(iAO9dO{q3>uk`8OUo#&{Sf4-fvMWo-eX}Y(hF*Scen$4kk*?Iwt!&Ak*k!~Lf zA7~T|?Y-w6UJIu~z&}OJ|B3uSQlFy>(k|?dGDG?BTK0v$&0Ht)k$+T#vFe^5fNAgk zkIONhcNd8O_{Jj*=u}Rk>VVkGra7B_dFYv!)<~T7S)@idQq*w|FEU*tAMqoa23$XA z%tjZSkO*tPed)c-SXv?9UWbX0{ie`1jLVw?n)9DFsQB6J{ zU}FEYI}piM22uiji)#JQY=BW$j3*xCJ7lrq6aDL`yg%@b)F(N`h_W*}2a0mw1i8w9 zgh{BWv`tAd5dZATFCZ=obB4nEnOyqH!x_Difh&N%kNUE2!k!8(jn=bQ?eOSPUkz#- z?+|3tW8Z-?fqYihKV$C&64TznTKf`QxmUtjqG!}oSQG1NRg!9?%H+XJ2!KGspyU31 zM~PVERx6s`hewa%?d9u2Zq(Rk6$Y!zfA89GIGl99Ha<-CWPpH3%EdvUiY@7@Td%H!-3w)}8~la<6oKAcwFV-rOjw})+#{mUWP&px78cogi$83}D< ziW9FzMi`b~joEAG(W+zf+&SLqN@>L7R~$_96m0n(IQr?b=UDiGBdYYZJ~{_Ej-t?6veHKXvkLy22*(5{EHbV_5vUiAK%{(Th-IT zF4bc7AzTlVsdx89j%`X9y%EI|l7j)Rk!0(yPwYj>oK)(c;&T56qydDuJxm@Qu{ zxtWgfFe|SOKoPC{@4yPL- zpI^Pd6*Do!!tC|H*L2Ti^==+Zt24Eyf@r=Atz-Fb1l)_{GKQ7ITas?CkPvR}oTe)| z59n%$VWoIy;+%(zL)XWRA!Z!JrS=_60wGx$mUPwqo=$RNbzF@(-Ig?zIbDMuL)2XYLywQQrJmr>sSh9rv8#Zl*1N=87EhpQU2n+-rDE=nT7WtsP5Cy;#36U@rg(a zQHcKO4zD!n@VFq5ex7r#ywl4~>YwfT)PN(QZDK>+9D?D#l;2-Zx zzjPq*9;}{&;4_R5w33>hv#BD7Ji#4`KXUp$neHM_CN`8*(xRvi503DTCtN#)1N$;L z?PeoW(nPnO-qugK(ffs-?aOi5)MUO4b`ah>qfw-y{oa1o;dbj&j~GVg5|9ENmaKm& zoLkiXYWK(z`dulQph!{Q=@E`40RjI**t6{EfS z=+oGP%dscDDwxLeAgmZl9{+$%R{9!pu}U0=9Msa)rs2{=8~X0*{I=+B;RWFu4y8{= zd`3-r$5Y7}&bF3C?w5JJ4Diu;*mQ4 zVlD?ZFnJ5)9~M)3M{lQzsL9e!bpl=OT-Cm+p^iGRj8t}fq3Y0lWqj^{tDl3=lVPgu z`-TCaf8iF!{`*E7e^HgNepZfzQodgo>~wHo-4}+RpNZxjmh{iK-qSri{G&NX#ED7C zgIr0alTJ!J?hEK2E3yKZ=ZQe9+#avqxX$;IOImH5K2Nz%;0r0F*=yPl=m+s!*#xvZ zs$i{uaOJyK(QiNQ{bB{YP}UC!hf*h>%t5B8pt7#^O@l3jLj;$e8cT*Y*ayVpxdx0V zoX$R_Sd@jC3zekr5`evss7_hN62$idmlE-t8+&43`bK-(f7zBFWa!v*0z?sJ3*+oHIELAQCd6Z-2ev`1;uG z-@v;`@#)P5(28Msh!f)(JZe7~`QC}sa_)?Y)Z5X#i=H);^s(K2dH~=f=Y2K^a33QIsEa z+qW0*jYMIux2^K;#J+@aI>0gjE<{6ApY;nvKX2)^bYA84_k4v64R2efPt|?AKDY_M z!(ZC9)>(Qvkogu4qw4K#N2#fgclye|jPflIe~u2{OAG@Mn9jqWsfXN{)MV|zk8+zi z_q|BDi~XBV>XShqvqZToW{BN$jTpA50^aKyUOfow6cK9LF*I*Iz8}w1bkvQDfE-j1$~b!(P%%z z2Bq;AcRqKgz{D0oV6C7rs0~h($$p=%{gmIY!@-8@=Znd>&WLR#wJp3|jNooLmAWMY zoa~^qh;}4AIeKvDey0JM*C&(rC0U+g1v$s9vWgE8aLx(k5a}VmfAb9gVb;lf|3xLD ztUQk@ao7?Ij)}J0g;Jy3o#Uf5YG@-I5wmopT3*EaY*za9Zxe4 z?Lf5c{E6~xb*N)9G5ji>^ele@#BYCKYu&D9@rK~r^?TL~?`)O#rx@zLAHWRH6q4M& zCVbvcvpHTV)G1J`!1m6Hwu`f zO1(~S`1Q|by18d`(sr{J2@+=h#(C=)VJoAI&vOl3@dry^>0ih2h%2o2xqlfz9R5&Tn<(v51BuwDWHZK)1d4=!Lt=hmNss+f(pCAdgg* zZ>=>q^6L|qBmXr)-D=l(O>~lca9BbVNXzQ^?{R>|-FTE?lg)?~j!3`pT=4@+i3D2v zcSk}CaSR8cVvhjGX|@mNfpc?mU4-Md-rw`M;BRng*z-ZZluY+3P#E>|x9u5l8wp#} z7|fsebtH8}-}A_SlaZq+nmBgXYf5s4G4)KD^KNjX%l=#fhOoY_9zODu3o$&&_ffM5 z`PuF&wuja?o{^xjK+@-?EW^JrU&(hWKq_C0tozA= zLi;B}REJ?nMa!&0EQXGthXAghP3gWGr>ol@myQKk<*H?{hmKlexcHx%w9WL~k$Ws; zr(o>hxrSfc!)sQk!_AcpP26PJa;z-fn?91<#&ND?(37fy?4pvc=={3BB!b^N8C!)Wy*NqQJK{&XX zqGhVCV?~g*Y~yd8Sf+qMLk;`<%zLf)aWjYn(*d5N6Pu!Zq?``TjkT_m=NdLsU3fg? zrMrx$bbJtXuJ-&p&fjl3%}O!y6?wmo>1dZQf zeM!mp=Gc^PdJnwk_$BW9V%N9!%iDK2l9HP@WYEf^EXF1=;?FU-)yJ>=j*_pevZZ>< zP-i;?NqZ0mpP{CCKv^oCy}fgw7 zxTvUH>!-5zltt-L@~}0(0L=!A+XvV^jAn=tiR7y)47h(>x8no!%*&nEgC}rta%10r zeq+C}3{n1tlyA4!BL~HDiBwLm!+IeuYOzEEa%1S=?h1-hO=}SWDVvjcMeanw;>RY> zvnOr9?V6#@Yhw3>D%-WV?9&>W9D6W2dN*}D{*}YoPfa0(V>zbyY#U)nwmDJ0?F{zW z*Gkkpshp@hw~iK93=W>^UhA-Un2OF8yQ#id%kR0KFjUgdL`C5ThOGnpJ_XhIq z1)r%@X(P{qUd4cg@TeZSA{_a4PMzfY;)O%=@DeB*8@jaR_lrf7NQ6^#;4Yt$K=bS0PR zXL7MGogXz~(-Du{#BuC}UVaphYJUXV+hu9q?EWzH3O5>vHTDPuQF6Z(d)!UFn za7C;{@Z8YPofYxvJa3Km)zbss;(w#*2DF!%3~S06jqT;?(L(yFh$gO$(hJ|={lSNx zH_GxX^x)2Q1vjq?ZQR9Tk4;cKk3!thqxlBY+&FX8Vw(XN(GGgyDj?xE}O6Ai_;R$-f9{igTQ;~|d=-$cD``qbuaOjK;m3iaC_v6M8v8;B z|HMP*q-Y**_fI-y?*kFGz^ytbnG3?fAC5V-SCA|Dqh3DR+TrUo)5Ax{8{+9}GeLEi z_~i0loUT&*Ma@j`MfoP-jXBvp)1+%Fjl@eK1^0Es$=Fg-%(G!XvayD_7z3{ zJylU3_uunAs_>(;-*hm?8Y$WdYVg|bt9&B4vjs12auoMPHo9BeK0K~(veo>(Wh8y# z$%lC_K2hV5GML?blB&I(^9+tp*E==$IH5l*=>Q?Ow!mJ3JxJa{b zzlu(zC~>^kLC9@=pRyapj6kDYuQcrZ%<6I0>=&7wD$C~hL(2TYUw)Bi{=!AGspKQ5 zBwv|nExiYhO_`%+e66rrwx10(ZwNhM>A6%AXCJbQ2N0LZ60d9@!7Wkq#bHl&JV;Sb zNJZgI$pA@rzCNYhJ4gvk>3shBv_FTnH8kfYf4x5+$sU5IX)qo5BPJSDv`V8;Mq797 z9S-tmrce`3DNdfLuUTasW>+{tT_$H&>r1=xAqdQ`!5wl-fk7$3^F;~t?S2=B?;a<| z>nJc(&B~&CJW|*1Z>uM=wbgHTI!@gtTXN=K>O*0|xxj{XcRwt(h%)!zq$Oo z)C{pF(${14^BY>%8FLq5Vh^~H1I3)O8CTd6b)0n0vyuDIp5ne<@bN+5f*?3$I2CbM zd-Ou?MDX2*WPh|H{d(pj?BP47QbK4?g6KY)GLXCpWe|V#<=nZkN_ekGcId30EY`4 z1$5kur#d=_5=xG8U%bIzqeh%t`KjsFxi6?|fSGU29(4V{zEO z+gTtfwe}3uW3Qb!;}Iiurb)%Z1qN=Fwo7nVZMqD5Fuwixy}{$F0+ysd?u72I zw~4YvJw83Ft9WTNf1f49^_ecwR-5g+B@kehJ>>kkIR*B`sr@;E$d!MJfUKZhwe z>K#igeol1Q0Rz&EYPgC7H)zUlIAIma#Snj*j{>%Tw6= zR5+ih`7s*vg(5y8i&b2j%esb%_TW8<;P!ySBAk}JiAYQAW3~svrQ}dGg*;oZP}N5a z(}Vms-w4}fy(&2$7p@Za#BrNa2u0x+2~#k{ZIWKaVM89|uaE!k}7V!nbyNT-buo!Zx=FBfZd5_G|i6g+~=`sI(q=N{87 z42Rfqu=qB3TTZAmuuixLcQZbmTIN+`+*uwf}U-B_@I$l&y4t;s4YZ(bIdA2ujcsT%|)+IdLTT!R({VD}c=SvpXGf z(&yi3WW7Y@^vZIbfe1-RJidf-ggw^H?X}kxA{OR{jrmtbKZNRP-fBzxeuA8&tBOCL zM^-_YBZz-hto4tgB|0Q2Uq=q*usN9fT{G?3&^^JiW%k^CL zTI=W=q!)&YU4fwWI0J)2<0+E0C)m})@xs|ROTG6jv~Fal^~GXu)8(urSDQ#N-{30N zB9xy`R5N`wS$!(^I0nh#{kcluJXCd6wdLr4U^h_SUL@Ssek(87@&eb`HM4y^&9SeQ zu&yfb9Or9JG%@9aLc;^DZDspHhnXT#-1l)Wt`AQg=~p`!Gu8p+aR6TsUtlM@=0t^V0miVYw` z`^8rjXe|nBzpC;hHoOBIJ{q|DXi%oXv-==5z)##~a4Hg32*~7I_IqVz+!HfC+h^_P z0tl-*rr*qq&&!UdQ#@@93i;197T_GvORq;TC{M0Bs7WDv>`9J*q_{R}s=T@9Sou2y za}IGv5(yP_{YZXpS2BCEi+h~dQxPpM=@l`7Lh$=*_DC?J*QE4=01=DQhdAmTDtenk zx`{{JeA`4~4{?CE6E-IgJUGX~0oPQ%s4 z!og>+yy{+G=g{8ej9*ZdKs+%&nO&Ry`;*uT`4*&!0I$Wz;Rnc=1MH$_<&F~9ZGBwg zVc7BuoSPGpj@g1SUPb}z zCv({#|FY~f$H${MUHu#c^E5NhIN#Vb@4a2Xq)$IClwb$M4b3i`O0WRZLXSf!yW1Cb zZLk&z6v#qZ?(6V+>P8>_u;uSh{t2#Dj}jJTIu|(P#ow19(EzWA{GtJbnv6(V=l&@4 z2d>xy;IlA(BcNrk#~ill@jFlt!MJxz0}M5?qgTPf`RF!iY6fm#7kyM^`3qXra3Jh~ zJ8CuUnrHM}>=Ua2f1MaRuSOB*dQy|~r<5C1la;8nJ2G=3+)k)p_If3cgH-J;DAK5x zK-s>`AEHEce{$CpFWo(s>znpP2MQ=%)kkgz)fg^xGX6E$`&?m{8A%CrSl`+EHO`Is z_>Hv#xZ~9#S2=nx(S5QX19x+<#Sn^YLZ$`ia!kOA>1ot5h=CBIgGl6=UD3SSmZE(T zO!+$MJmDrzyN@0mrf0J2*1u0ZeO`V98U5X=5}V0kjw)AC|vj5=as zdJ<;hQM~9<-1iM5%rb+xFz;Ij3I0klKGP)ruIS83><95sYCgD2(tSKWgi$ZgrKk~} z;o_aOOKTuUP^0}}gZ@Ih;X$vZiceSA$J;iFRw5VxP#_PVf|EN8&A7&kxO}O3+!!kU z?K^iW)}1Vu!n^egM<4D3(SGvUWvL4fdMNvm8(oJn=_3AARXaaug;Ptp3-h2uC0Q@9 z#;0rZMPjm7$|e$jeNVARNbheW@cD|ZCHsXS`0xW|GWwGVu?GW<5-;RXVpmc>CPBDf zEEb+2@e-f^^rs_hNV3PpNTbuo`Hv^J@_O8^=NecAJZe-g8a|i!trS?B)v=-}fpC=EihL zW+ZskME&EjL~9BxC~Mx21YSDR>?~L~TdAcdC~-5n;r+FYAM#5Dlg59&_r>eG2Uoc| zU)enmk701b1%(AdM+~)1$9U#CvQx0{WLPj2kjzhRlNrT-8TR)F$2xtSv?HhkwJ*XH zX4sP}`BiCjCTjHo(j*7Pa*J;+S?#?)%9nUy1*3A|mVk4VDmi~pn~ySHbm{%zq{p;= z>0gKK6K3ui4PxgUst6IvSt(A>A5(>)9IyBO3wF%;#Hy^wHo#>}u!{9gQ|yfU^O)HV>Wnt(?3rqeSg~0+GDRWAe^#( z>-j#?5Cw`z->2EaCKKL_uBxmb^%Qg^B;%X2+&D0~n+ACDklj8}tVV@srG<^*o-Jt1 z3|78bjVdO)DrDNNlhCG?G7Eb70fk&vsih@8W^JAJuaZFgI{bo8oR?b>@ZJhd5YJSd2V84LBE}Y(IdH~U_9aeLW_mtib~MG)2?it zX9qA)Y5$KcjT&e>8pUR9Np~#;I8~IfR#z_Ld3?B;{s{LWhzF4euXZ%}D+bQC17Z|f zT)uZ^K(UW->%xcsqtHBVUyT>pb)XidP6N$?A=f?#p~gOouoJ+qg$W*vbGY?+y-JV@ zDN3Bw@5XAHIlqt7kEqRs$n*L0N9^f)Ky^sW@37`ij}T*?+8RAG`P2p6&z(rf-zc*g z2|X)4;yq5l7S-dF8#V-#DnoiZfz~m{(N}r-BPcBcMF1j&s=xz9m}G# zOg|oo%aG!`OTuvL$g4l`NCM6KKNB#HgvPzMyM-!2RlkJJzQ8INl`bVhnXhr5^u74h z5YyX>UtI;Osr2T64f85gxItL&^EQvr?%?fKx3zMnk+}wt#F$ohPuB^5fsaK7I*g|0 z!lT!&vjY_Tu^2YTG-hBMbDX{+%KdyRuG)rCCdr(t?F)Bs>bj}zS&*jEsJuUneBb#` z(G}f&eF%zUlqy}tPmGNY0+<}E^kY`o1caxMw4fGjv6cc5;$KFF&yyZ%bZBF<>Sgb$ zos7@xdUN9=Ghze*4+iF8O4CtuydCWF!40R!Nx&1=N7n$6-1QIt)55P$uJ_KOGM@~l z6%I$}fI(mM+GDpPT?(wQnFc-6fhO4^SA^owJXz=m=g(9EH}_IQD<>o(qkVd-3?JpM zxrVPj0ov~{^&H=mjDW0QyugEdzXh$%k<4+72F!Ws3VZkCvPzlp5{fswF@Srk@e|Kf zi(!{~on67J^N5tTZQ9p+etNHQh;8iqb|@Ubvrg$_2hanItHOXeUp6M~Rq6Pg!h3%K zAkA2$28ur8cC{1KNDpy7u)o8PphJh{d;Xgylrf%s)~bZg!{+p0KF_ByR*y?{L6!c; zJC94y_}OsJ$Twwahk>I5e+ptymvLBVQ#@Q%>qEt)%_N$uz!n z`J01Sv1P-_ivSivDAv3%&gDmQ3x8kVhazJS>WjkH9zfKZYH~@SxYxq>#MXd2`1#Kj zt=T1@Zf5=aG`y_*j`s-n5<2h5)T>W+zI?X$J5uBFX{3)!zE1Zin@yU2eeRdPrrFA( z8#h}~+AR+8I|#3`m_ULoDY)_1O-uN^hR52=>Eo7i=jW<^-h;8QD2}d&&xQtsHn;>@ zExg`g6QaDhZh#OXezOKvO**W=cDKbpfts{b{ciXwztcVqEMzE>@|xSBs|SWCJi&&B z%pn-S`_5(_iqtFA>tXs_Bn40`k+Tb-0=TiKf4={L6fl$%w(t4F@?YA9*YIj{dwQOo z-7|8(!*jQ_Tt{NM3r7GEZx5O@@U&VniN5Q?N|}UCCM03?yc9F-_tAH~UkNiv0+*TQ zPJ4Dz2m417ljA9Hffu$|b|R6c@k~yD^G+yr26r)vTY}8ok1akx ze9+Rad@UWB2qwSK?g_X3G{Ad(rsp6A}NbEo~~(E)=~8pB($Zf_l3FhR^vC?;MP zWzjwhtOg$yE}tYj#L#DWQz{ppVUA)mT&T7=ZJ*>a>h7X;GZfbN9`=|FmO>Ec^F4Ds zT*gs;Q_lO*a!T{2Ivv3CYEf8~5{@C8!z*;f%We(R+#kIyBrl;21yEi+Q$9ttc%e_# zD4aWRd4HRwyORKg6^@3w=WU@g{)fV`-~?4-Jv*_LE)eyK*}A4hoM_IHj~XZSF2yU0 zZQv&j*zEC9sd&0yiQBHIBHf2bJm9v~I0x#QavgUoe*`K-+xs4xr1^86{Sk0R4Z1NG zY_rbLVVVx~!~}LiYbxx-reA!1)k+ zj>O*gIBp!8q%MaPn{-HIyzWxZa=gzF&aE#tl02*coPcwH5;`?)ntM;t|at`us-M2fhc!Q6o)W9~~ zoM%R8c)>3(4KKR%Rp>V88P`dYsI?01e@7K&`XnCh5*tYLs^Mn}=-clsq?sqvS zKac|X%(y~xK0lwDT~~>D0t<1!NYZ1*0fo8M54`>Swj}6t_|NL}R+w zQ~z^n7~WLTQrEX%J1t{bC|^`z1>no-))-=zKlyIE$oZZH;ZW_#{>8g^9>xY2c?miJ z%lG$z zH(n96lM6#-ZoEIc#66yjLl)dWMJKXp?d?kTift(24zyst*hqgGO8$t6(1_vpYL`D{ z3f_A}X8i25SRP$ccBEl@h==~rBcIP6H*b$c*{-_!Hl@v`W5dSgzx7Gj^MR_~xwT*O z0K$?|U)K}y^+lR(ZX+BAZpp?lD(4W(tjPQ2XuB1r0_&G29fuXI`uBPz&)Y!fe(|Ep z*sVVL`PU+7NO$NtxF6ykptk4J#<%7y2N6m^FN8Bc@0SRZ_c_7?50{2R&5ffBUJVUi z-!MCOClMGrw9m`+40@f>Z-^PnOA5;IJYIa2^8e;Qh`%M0WpbzYssmQ}SS(;LVrr4} zG`yAHpC(p2%iE~_TKa}1TEaRiO=iDgsD*}>z%UfLa+?3yN^n-}Tw$-H()uZTY{n^Q z*uC+stgf#tC+%J8X;j~hw_SS>1TeCFErKU%pj^pMM)rh3E+Gp44IYMyyN7@JIZ4Be zRBZdqp3*x;J@YMYu1G@#^&UGKy4L3rm^snb$HI)Bci~<@vM{oat9_R#n@FK=JV&Xl z%dcET7Ma>P9E>Tp1!4JVb`PhAS#PF})Kmy&BzG$(JZzx*CEmU6nF4K#_dyGjx?(4EZ?E5U zqw@#?C_iaD=0}3P6@aKSpksX94}_TC7L>A{Cha*H!5u%|dD9r5B-7?^A^E*y?Q)7G zP;QN;GOQ8&v|9O)L!%q(_031i0`RK2ipmkPsFV7ne7G-iB~C&~rz0Vl6qv4A&k2%^ zeFww|?0sD9Yy6^bEl8o<$o`n=nCj7~tizcv}zS?yd zY)iz?z-=5KllVOU>O*k;)EcQfv#Ra`9zPednGdW8Cjx&uq;3X{z)SZWgezsV7V}w= zpaN^KQQQ^$Q$m_lR@vld_}zyn>5FeBqgqmVgtA;gtU&)|%RR1OELPv;wxoXZ%ZJ)( z`T~6qdx^^$Cm-`LU0We5mNx(Wym2%;(Z_cjpEkJD5wUJ?)!qYEyGU#+n1PYgr7H7K zH`9}!te8vHdAgNgV?*j#q^i%-m z<~)PAe0p~S{EzTBKM(3v86n2@**X?GG{rX+t5>etxx21vv!|KZ#FZ(1z5}o%t(?Jp z@mP4J4PmKnPJwC%`qc0!WdYp6`;Gdx>HCzc)dINyNTMu83AlSYU`+xxadZBm2BgxrZ_q%<({q6^@88zN7d>p*cc+ehI zJTVVamFnPO?cAVB{ZxkZTpu>SEhvv3HPOM_S~kJ%snE$8*|>7L?Q;P?(0W^m_xCA8 zfCYTVqi-So|I^RiGf-tsEjGvjC_DGlJ~O6}S=;9RYhwlV(+Y0b2V-gH*a zhr#JK;7}Ys1&;fqw-6LUVFe7}$}t#QGVa19aRTh`AOnk=q&TO1P8@Gb_MG0ih}O3d zz<&DzXvA9S6cMOs1$r4AtgG0O6T!E;{GFjzzQ;lQRIksq6|c_cNFQ2at{v|y3|LBG6OxxP%n=ZluV(LF zk|ys2i)wk{Ml6F=aAkTrvh==DfV1%LuXg@0QnDa#p~qLeeZ_7|T8iMj5DWX=z^0&v zcbY&Y4Xo;0Gth+lp3jd%`X27oYK9izsL>ynqAArfqNn<|G&6^Nm1)846hhz2^=d87 z>CHp9``V*pC-e^)Aoej$1l`5actY1>e&$23{(z3WW7-w?1-`%7P^=|H^MhA(=&yM6 zeeiv5jvB}SFnaYLNoTgEsImp&R|1(YK|nAR9uA#J7;LmFd4_=F**dU)||499`Nd#)|vVfdNpF)no#2pc=MoDgk{cp zbM^UNpYr}55l_XOzKV$TU0P3nzO{WV%gld1VG<3icD)aZ8Bl-TanRU7O9zTzntodV&+73AzQG-BIJGtmi1#3Zd%So5H3HH20#?`Vo}G98yyW(Q(F5I~ zy;ayf+TnG+H6KG!iAK;^r({~DrV#d3f*fr8&Bisdld{A2ie#Mi`POLVPgAF$gVLuyw zdZKhhJlC;lj@(|HxJ*UnY3=6c@O>nPp7D=c{`)Z;l+(*l?(44;bCt>OLtK#T%+5#m zhHF4l4uP7ALZaeJRWsorwio)nIH(LMP(k0raQsU_RySigvBKc;ghU|24UN{Zkf<#w zai~sXW!M^5O2K-92+yKiXNpSiWmhn1tjd0pydXmu@pr3vJoMD{F~dBVO@IdP8W!n1 z!9+5?mtOmb#K4o`J31DJE*2s^u0Fn#fxm4~u_e|&jN4LSt!Io_DmKvO{Lg;%JEyAd zT^`EH8m07tr2V&Y)h+sa^PZxp*c74UV73hoqXIeHl9zHFj^6}RE}n2s>^q0QMe@ae zPFLVdr35L2f9y;wbX7Zlgi9bH>2R@rH<%LtStI!KFKJW%j|dy(njNA=ca5bw=rk zJoiVA2xr{#QqG9EJ=)w571M%lrxe!y4Gc*%k+ZHFL)bsMy(AGe{-qiFGhrwq8qvJdXA>EOUFw7YP><37k$8Jc!ZY z*UWC$^|5gnFQhyyLky03U1eIXlkjkX2l>&--sH1X&tS zm7I)~pN904x^Hx=EcJV!VslBl9?%yGJjT#ffkYUqb8C?UBAc*&+OL{Rg_9Y9NbTqC zT{6r`CE|lq#h9D=MBXFf`vXHO!(GJVy;5#As9^`j(JDXxZ5h!W1G+i0AR18+rXCx@ zg`s0ZpSHwD-4kLUdW6mUFzFX!t$5CPQ~T7kARjnnA^~+q$+)+tykFG*^@Q+gm&wZ8 zEz?FjzvPN&9gZ2SG>hAaQP(C*!WZbU(D1c52m)+2y0_+MG=iwXc;W1Ad@m%AVL!I^ zwR$s=%$CUzdG9L%6&2f|q{n^QPJ*7YxnfKgRn7zBsl4bo^3CW?!kmT-VCPp~t9S~( zQg}V)!o}#?Vn19!3L`|uB0^j{`rGJU_WkMM_fr~Wa)-+yAU<*fFxL)`I^Tz9M zUl|`6^wzvv@dK1;puq1l=)v=U{=M!5Qb_hw7Dbr!#GD8J2`TpL>3llle3C@Lk@6N9 zS6w}Q;zpE-do*|F>9uARG!$t}L&-*b+ekQ(WzKpNk-XtTg?nf&C&)-L?Zg+qx0v4nB@h5f65^|0FLiqKYedGFprO; z@1yj}9=GkGlW!Gv=IgFY#4pn+v1=jjotr@qeGoq!o-_Id>9mqnr=Kd=Pb)L{*}5Xw(IY6|6{qbS$m=t6_oYHh(Bjf%eP5uOd_+GB(rzP3c zGv`G-$8@C;Dd-}NU|Bp#>t0XAv@2*w($WroauuSZ@dUlE;TCfrezf%NuR(ZH#>Wa< z4%FldHjM_EZg00;B zQS4>c^Tn&``>jnAdGm<~D&y-fN0edqT!gr0_NfqWZ2oj`+qH-2*X$FjaN$^D|HA1b z8+r34s4}~sfe3=)t0l!rJ?|6w^K}T#&f<~gPAU}-erTSiO%Ef70JRu)H)Hf#oNa#4 z2nXvw`h1++Lx$;ppA(q<8C<^eJwhLlgQs?Oh7`fm`#pi;`@Imqo~uP9KxcK*W1&@Q&ayXqd9U?NvYwKyI)U{zLXoiSQsVNJ^Z$lf{vinl%qAdYsusG#n{x ziDUZ2BR=nZHO^LsP?`(XlxUMP#fEE5O}z7&7?~EFSbOSAA)gGcDyagatlErm#tV%H z*4^!vaLZO#(|mj)q4$~u=@XqN&F#7*J$xVjRFRT>y!qYj7d^0lILqz}tZDquPjuG>yaI!C;RCiEVo^J)U*n!XsU|Dnc+1)1;+wCs+lNld{|a9h zS?#{?w2od-!lQv-KV!e@A9ojq14&r7-3TdtXj0E4*E?dk8*n~V5^TzWlr(J!>U zSo~FT{MV`2Ue7URXKVz_op{_w;KYUY2-@Rk6}yzB4giBG`$_FdFO7Ttt$q~^!5JTk zV?lCHS*>|({$np{rYHQCv=sVSECGs+$XA(zZ3~qcV{2m(x=*@Vv_p4Ik$!sKzrg|j zy~M8{Cw*DW$<72&%Pd0EZL&Q2Ngh{+14Pr^>zP_xX9OwilTrWh_=|yeC6UDfxt9?{ zs^bcGUDDZoFly6p%+KVR3x1+*>A^S#w1-XZ(rEWdck(_PR*z$kzV8iLrcsOFId9P+ zmAM(V5uSfsiCI@Qt$k>K0fmB4YI``xFk#%KG(>O2?@ybfj3iZ9o9<3#0=h$_wfh4! z{sYH-t`n`t5}^)yYnIV(K{_)+6-b{qoB=X`!~nwtYx&qvK|w9;29d3Zrxp}rDg7px zIVB0DwBB2$gdM4{yn~f9r}?3-pdaZA=krJWm@VX7zNhI#xy^8>ufZaiaa5DW1n0q* zr&;lWS^b)6@A5%_%veW^=T~?7N`v-f|3>-bNm3d<&%Z*fKj$~K&vy(Q&P6|QyfA$T zD22nCK~nuSc${&gM;=@B`E#lY;x@9kea08mQ{>$1?EK8iN)_IFJBEE>8SJpiZR`Bv zNvX|sn%74yukITGiN!6MaVI3dSW-;x2U`*&X*v(|%|x@@l&Nz+^*{f475s=bZu@Wx z9d!=S*6$l;l=VkNFo%tS`A?(89-$J{^S4qkjcneBzv3AmFx#p+P-Om7vT}TZ2;c=9 z7F+JmVVDC)I24xs0;Vezu;0xS+6Dc^E3)jfN9Feug#9{6gon=XDC@D$j$AE< zwFs!J>pKvvxY|$qe8_#ikU1blL9+-`h)lyO2RL|E`US`dahR-g^4SMX{OONYCtaX~ z`*!kOgt_4Qz%{zhFa2+8FCFvf>Eh|q+Fl3o$hYJZ8vr-UzNg&)uNHpGfhi9-EU+oB zx42EnoE;EI$`^?-)kt}KiVG#{NUk~|#TGfr`Xhb1=TA^t($6vzLwxj2X|)yq;Wf^` z^RLK5v8pbS;ET|KQ`ZY>49gslQD98OH`vF8_G=@(mq_m3;>^f~QddWd66_j$AKROF z1l`KZ_vesSbFzQV<_)&EC^5Pj7#2ixH=;Fu1~QTO`-D#*W$z!^Q=kRcfcY|B{E-=R znmhR#smB19gvw;^cwfFf-+TKby|absBR?Vbk>PRNsD6e48Im1JwWQf6Y^LkVyB6Qi zE`O~L5z8aC;wRBM_I!Wrd*X#o64&5jT=GETn99B&Uy*;C9n$o6`w0_VbYsJ`=UlJCH;zf88S553b#` z+vyw%j>&?UrWDKcy7TYHNXP8Cho(1kJ5$f)iBmy=8zB7U2K`?wSun zierG95M0Ash6w8OPm7#OS#*14J_HD8>y%MI(uM^RAmUK<${imFCju4%p+vuLeiiyZ zwNVZBvBBIfK_B+Dzs%QFQXkX$_VwH8^Yb8A_M_oJ)~%a(YrwY!rq8z@McU7$E6vME zY`ou>Bjctu_W@^tg8vY(=QLn-f1+tAj&cww!k zDvB&DYn;5ybT0I#*)ly^5&MYA7*vJ;T=fYPg_`iq)2guh&dsebke_8$y1;%kP&XXE zt1pH7o3TZ`khTr~7|H zI`*n9i694J!uG$>r~47rg&RBp27pJo-@%yR$r=JZaRaF9!-?~LLh;%}HgY?TbcVmi zul|QjucaXY4{v>kV;|tds)h|x)vG({iusEUFP$i4fbS9Pn>>I%`%7n&#t%o@^0|Fo zB0@h?t7Xq09H+@1$JFH!th;fssil-H%2jq6c0hpY?||dAG-zz{09NYGRVghtVl@8&P~h zL`FnLok#&Nl7T!s1ZstgjC&T2q%lA4teqa_vgs*0 z-TiSL%Ae#TE0C~7n4~M`EV`c8-3|mEn6Bg%Go1upAT#BkUbZ}j-VU=|{yd5^#2Ok* z2(L0)9%aby`1Ea%+#B*VSMS{Sb*wzKn;%GeeMf;-?QezZZXkcX4Ad8r=X59fN|N~T zp*RT%wivX2xRdh-9`;Dv%X;F+`hrh^Bk(yFN}xZ#--P|Bzi{0mHVK;P(cvQ9KV%tL zFeE2&KMwWuK6NfbJ_5)_%{IBM!yFy!X%?ek{QQhSf63VvL+!)D;V@X6FgZXKzP<9R26PE*H#KHIFQB-_Do{bhNp?xmy`QgKLKl+O|@|VBlbUF5Z zuoWa9@X#JbhxE9ul_>nRQ`1DO_Pd^;JcZWBm7sHnYDYTmZ}9iI?UO$1w|u-lZ?(i6 zxxjl&^L}K^C+2JSSN2CNpFv!nv+rGNGrH{vhyN9~=s>5pgJV8|z|Y}=d+`djm(FZ6 zfsCbuLKAkj&EJm6$e)(wPdA$su#}wDNpFwG4O=!=IL{S*d+4|xq!;mw0=@=@rNj_9 zVnws717m1nQsVAK4YAm7+R?CKh*!Zol)zUr_fmQ$xeKtI=!+N)-sA?<@xJwWh$e2r zMGBz*1!Jo;1VqTbazf?4IkC4Q5=L~TtH>aS4>$9__J>SzO#2e11IZf#iPjYNRptHD z3#lWi(A4M5d_|i3{h7BZf#mD3+x>JZC+VF)EDq1_AW5JVE%JGll!d@JB;WTc(-Y6Y zm~NoNo%RYgD*9~j`92REl{m)%132<#y(l*-9qytns5evy=iU|-AWP@k90gK+|HN#B zp!0}13wGi7au?ldIW1AcgPy(JDXtg+M8S&h1x2B&HZ!?*GM?PCi|^{?{ZTY^d4h!czVlTe)%j1APGa||CmHFGcUH5F%BYs6NGDnqB1L9kzxxWKi0!CfTki~}WZE^<&} zh&JBEK7;nn*0Ph0oB2aA>%LZd+$G81j#+35i96T;B5A_1ijZHjA8UwM^jKztqDv|a5Yp{Bh6f((%!{te?w{*=XpG7rxIEyy@THBr zxkNRgM#K>v-9#_#R-*xmEuZk;$ z?ixTCWCVWLrk` zNULp8AmBpONi*IqRf?dU=W;lXLCLlGQ@QLTdkKk?%1~0%&;SEBf|#C888S$C>kIRj zGbRR{Js+m#CockO%;il>qkHjNRi+A{#UfaWFEg1^l>Fh{lOOSh`U$ZvT@Y8@<#9pR z=xsB}B7`4&T~hEy6+4vJ8-B8OLx#aU6xw0^CCN~+H*rZ!J#1HZOXZ;7vXSLXA~Tz! zkBa>EBcQe4j|bK6Uk~(F`cK-?#C*S>!&mZ7JhY615_64=^0GqJiI~p?M?jeT)ZqitZc{%hqohoF?R&O9LV@9UYG)ZVL6{mkV|ddXo>$!+e3=d;hZDhD3I6 zT3i=-yP~){r)@~IX=!9^Cmf@0U%E*H;%blOwa|O-$s}mo^~G{zF=|bbfQt2H1lU8Y z09(GFW3|O+SKsuOJ;+4PA#OYz`ZUDv?jO2^IR()L0&{zXUnSa%oM#Pk)h}!Op7d9d z?#29#>*lrwqD|ARvQ5Xt2eT)MYfg_p9GdaPNt86;5G^>~ZDT9Yx?#5is~uJZ*#Hr8 z>qM^;v5!HHjE$w1disUAS;uz*D+CZYg*)dq^tg|K_affB_N2Q{bEz7wT#EZ%eMF+)F$g?1j4mZVPmQJ$daP!t#0;obi5~x{Ife`)JSfjfbM9Ef-!Kp3B2JLg$1E zZFcur7235$bAC56JW+_>ZdNoKX9tLK_B97oLIuV6i*^Ty8s7u!W*5G7h>oEJChVW& z(dugHlre}vzDgc{I1Y#NNrG7MOQzLV^BKue8u2@JEZ%J-fVE$0?%-3LVEc_GM)H2} zL0WouFK|StO|TC0puC|yJCCQN=Vb|D&dHo(pRax3e+pdb$iKzj<98p>j#k7=cI^Zq zT|{>lxPeo>umMr&$r}ojJ|g-3B3SeMK(wB)acJ z=AZ~c7LYIm%W})1_bOK?5K~5(ZbxkAVB-m|xj-F{=e!1Qg+w9njeWGZkM3Cv5JG^f z@tRRvxUt@`c*HNyr@Vb+#-+3$feHqAM%qVL-2&N;cGD=XmF%ELft{rUaoD_Ksq2Hr z1h;JZs>fbLFc=HpA$cAi8o6lqeT%}8Iw@m>Cj%tdLhq#tuntFQ9bIQ>@LALgrgHuU zD13Rwt4rnKa9$Wn8Ic{HhS3e1DfHoVk_y^9M;9vpf>s-Ewy%Gu^dvIWe2{@=IX5Hi zAz#fzLr_A%;XC8B6+qU&bMl-T-#EN22n8M>`(KMaPVy>7NQUFyb?)j|obh?C%KrP;s1I662_ao8MTCdHNj=>E0ga zN$j^$zvB1GFT*wZZG>A*RfPn_YhV2qSQ4ivHQ%=E4xjb0f;gMOmf{ccA;mVE@d}R9 z@H&}4IXM@-up@iWcShZbr&d0aMsrhd-yHo@%$Mczz&8cp=<)d5D>JV10>+HyaZ5v= zPSW^-HYmQT0PDb;iAIU|W*w_U~nt=$8l5 zp?u)>U(0M;tgr2t+SE5Y9Z8Nz0k^!^pnNTr7T8s}d%r4Sf{v}F9s<&R3bK+!LTEZDZu0h{Lq>ME)BRdYf$eo!@WV^*C{K`? zdHERD;b*Uz_IZo$$maaEd~YuCp7|fmfeE_bfL3Zq1F2hitS-*G_XbWU?v{nZ*@;?c zb{uB7tWDX5qj0M90)Y#7R53+J<2=&_vOqIDjT9XL;h#%?AVBY-Ugc%F_$pBjp^kn! zh(M%M{)oCheM=X>FXd=24M;YlmVYqg3Ch74^MW54k?}x~PSaEalV#Lmvp9b6O;%)QAK3T%+BAt# zAd1`ql7q+u1T&o|gb(E|6jT770XqJ~5^6*GHT1HdeT*)))yT|AbN|TumR&E#V&{-@ zeM$OyKHm?ISJ*(6y^q+>U68CU&+{N6Us6Vh$obDo;sptK(PnG`8$~CxHpBw)98AQZ z(#yhg`EniKWKM#gu@@yl9w^I;t*lgQ1EMqfnZGKwZ$5F2OP$4Ck?*3*_O)S-Fe)}o z^puD$7q~DclnkFuF0^=kX{f8!wm#D*oz|eddX5QcD)F-6;#yBF=UPt@;A2V69EteWUdCj)kVBM-ph}FZ{i?p^%foq`axC>2_(;j zPD~^qpI5@h=se8(n0d8tl}o`a;yGYb8=ho0aAecvexSlrOWiNUu`FSi^sn1H83@;2 zzg(F*XHZr^?{szLN;v(C_BeLQHT$?=Z#lPr;!R6H0LEuTQgXo*3t(XQIS+6QgD>Wa z(GCtee=l@SovrIf5Q}m`zUP*mle78M- z@P|iW&_)jBD}{cy=-B-`FLdh*x-P`^n6#u$J*lVey8PalA1WEHFcGV2lt(#W|b#l=FE3rFW<|;Qe+a6&h`^EJt`td>i4uUbT~SnOZGkk zj=E%?O%AC_Navy8#&z(U>r-s~z`*XNLav`qL1e4Bu_oui795TP>$lCW# z_FNqm&A@ejmRnQ-=010dyD}4Pjl=M0-Ph5k(>Iz6~QIAm%IRU+Kzr}wno$R_FWp)3CZe4lA>;Z)b*TpIdG4;2>$xH)f zSL@C*N$$T9aB}>9pLwh?a@TC12P7NJ0#Mhe)~iA0ei10hk9p`H(o9{79#PU?fQ5o5 z%%on$&B}KFtWtB2Nzg4$UYrD$V5`NkGOv)fFQ;T^j^BA`6u9AYis^-ec5&gZOXG-| zuAk<6K4;%w`njXlQln%q7!_9+73$zdl_Lw;Ll~rniamgfoXj;GQP{&Br1$r5AM`ta z3J=cdilA({zFmI$0t9mQ*{dVTA)a676Yzh6h*NGd-$O*l_p4I9UBD)Z!NX$vKw|4m zU&<$P95^Jr%CgGgjd=9Fbfj0kUZOy*dN4kl+k50W-SS&k-GC~y)Pd>-}3y5SH_FFz}GBZaYegnH?vQa_48odg0r_uAVzoc>Ukzf8X%;qgmI$R%5Y zAw%LSak6|sQ_`%m>XChLtCP;EdaPnix6%WIBN{DJ z-`;4I>VYk(0x4mFZxA`!ciTvRhWnB1PFcF?(}I^g3>k*IbBn?S0e`mzAZVx{KTZtz zpgIAW!)atq-?eld{9H|tYra;;Ub+*$Az4On$OUbTGbY@+sch;*Vi``8re&F}B*y-f2pN{Q)p zd8j$eaqsU*K7$J03$*$O@O;9J`cRY1V&LA7BA+A=U8c~w@B(&2yRCc$+1Zq#YQxj9 zN7%V3?Q1M$OIM&uefP3XhF#;THXaM9$)Pr)lHCfgR4n6Zev0hGM;byDt*d4Cu$r${ z<~>8CyjfG$A05=;^?iuV3At>9$7{OU#XceRn)La$bc$uV&!z{w!PDXv=||O@9S+(< zz_=R6cyrpmhKR?!&ehU!dgcfK=H+XKf{+Lqy&uQAc|8&EQk=@SXCbD=kF5p-D zIYB>tQ;gpl_T8n;UC4Umc$WG{4aqk<4$AeZy9aB(M$VVBKWuMWR^0w+9zKMqRL}EkzzS)9I6Y=|=`l{;(3P`)VFTncNzsFH0WKbhp|7;|z6fD%xRS?)7BZ*! z+Xy8J|8b5E+onPAD(M%EKraH`;|f(o@DZupBT$KSUv(D=p3WcdOA0=%3o5aO=%F8=j_ zJGf2ULkn0{=M?At(z{4Fztwy4?!^7#!f(og9-jecfw-?U3YT{6DTaj@Ks82mmxfBUb-7ttWjpaIQ)WSfvxVosDU8JoaNg!}@nV2(prxvT)zU z!qRZ^**XhDnC|@Vyw&?^Na=+Sa{IagR@Ei;F3x01tU?6IEJGi$Kd8K2&T`i?y+xcO zw7NF=pixG{oX^WcAl5ulH-Lyq!~sZ;l^t*vO2VN;j~Kl3PaVttgH+MBfQhP?8+teQ zNapadseL#nKK}OhC$ja&E&DdiH%4|JeOkkj*)s^Nh*H#CTP}#_&b#V53OBLzSWM%Q z+yMd|A7PugY8Aw%)>Tb7w=(NvmuoV@!AuicjF=kIH+XE<0&*Fk-YIO@M_xbKR|-3h z`_7+J7~6FHrhey4qX(W%OhI*Wwb=56y-wxr#g992HM^)*F1{7bzw63FU9&#M zdyyrgboP2b`lfpoDIaQ44-Z#ckq0_a(hY4IEWhX>Hjm`7TM}GInbB5$(@!}S)Zfk7 zubYn4NPD|-*~)f4(Dhl+-opaCuc*AM>MO;GB7*;2cc_sKGNlYI~_(R$U9&x4`YcD5MiH0)7j;{9Wt$61`+gU*xCuL`Z#0SNvVyt^!-?nIY?`3TAytXro^t`LBPP>WaRg8Bw| z?T;{s3a?LP-f<%8t!MZ!{T__t!Mz=Owb|I$gBKsH;`-)q6$%dt;n@8A(`uG(5Ck7U z<4Ydth@#yv{UQESW}%cj6Qf4ynUtt+1!3lfq}_cax)=iUQG`BuMCgKEPtQsyR`H}J0l#}r!Ju7F4|Xj5c+UY zBNE2k5)uNGWc+uZ0PeQ6#CKrg^S?|w;&$^{J?Q9Yk%uEy@J>c)GEjkh=UaOaAn_VH?&=tfQ1f46jjps$bM%jUNS%vHJ3%Ejo-)f~PAu)E2@loXXT%LHm zv{aerQWm7CT~v1;6X-a_`JxIb4AP$>=)XSFq#Xh#Zq)+-Wp6p)=3zu2IpMpm9rvra z?<*8~X$pw0XP`tzd%3Z>s5@r}+hqp(Fki#g8r}bG_ z{WeIGa7+)HY;&UdT`RU8pqlissZi`Qdhj*o&bSyffce$kIvR+kmkaE?(eLo}wx!mi zG4#pz;nCIlF#{_ol8+fSiQ$E?@%Z0$FK!;+?Mnd+x-f;qCX5a|Erqv_(9N7}zb%be zOAE;aZwYR47c`*#fw)=nq%=tu{-GG^r8sZi>-;0W_LsPEXm&o0zjl=^pC~|Mp8)(8 zFa~=ZF!+rSc~#uJ<{t11SZi_zs;by;o_{jU^DttIVI$-6@M~r4K6%B3J=TDBwy(+L zgCIBdDu6%<6)45SJt4ArMp!WyOI_9+CfPA5+HCjMj+8D{Iit^u`}2r+{&2K&TjyfA zdJR8zU%>RpWt3GTV5u-Wt4atiAE;~}SD|x13i2oT*Z#Ay-fEN?RFnjVS5!Ro42lP} zdtYC7k~`e83miNh6<0TRc*q;SU^zHeZM+W_!J5^af@&j;dNucULoT*4s>1{3(*u1H zkE2DR=Kx*b0|}x`?(GWfd~L`B=~f#F=p2Vzc|Za6zI29SKRXS9*ew`do=;6UWYHqn zc_O4!#z)HI+!sWiBTgYV?rZw|9kLa9*4@f6KhIoFLU+?J=HT=&mCsuC%+3=q2etn-1CWnji<7;?9$qt!8N#Ik|Ef1R9hd$Tpgh4kI5 zj>h>xM)Bzn9<(!a!2#VT%5tkp@AHc)U{=xrxN|ITq0YjMD2gAqrG~%Y_qc(_T!dsRSFFb{faw+f4K8iJ^ zJnUoR&B}8z@UgsAAHI|w1}f4=>ID8{HNUSdbZhrCF7u+X)%89ef9RNkDk$V%;%v~C zHleJd5T$rCv-pu`e+}2PSj?yh&zooRy zr^B=O%Z>)p6(Pe7r7_xwrjUc=PiuG<$qCt_Bzy9|onxCmzE3cKUFt6flw>W$IP4?q z^|+pxn`efezbdoC?)59}E&J@4+t|!{?U{pz-EOQB0A5h+r~)-|3@Sw6X6k_vyYCub zRL~?pABdf}8?R#x_Z5`t7(6YRmvfb;^Zrsf33Wb>okb26~3^Y?Wc z-UVsv?V&%U34gTV2~W-0te+VgQSu|fmSCad;zStdwNOBAkQY0~0Aajb{?ZPzGd;dB z>BYo_=+osa8zTmhTDZ%^Zm?IG2+~De#1>HSV*2mN2U8VqraL)ssbc3#N^G6{%ZkID zS9Xzfh|e<<>88kCxsyX1i%&W~O!vnj0&Mf>Noy*|0Dp=@RbRF60RwUU3wbV=>BqVVfbz3ObfT=@?&1X zCL`QxKba+;e+7sBSA)pbOTh>`vxNv0HDBiFF^cnku01N*Nfoj+M-iMMhdN$dC2OzM zRc93&w~No9_Rw`U1?nm)CLIMeE9cG<)~^}eExgLpI{0NuyoQi`Bbo@Qc3JitKA-PX zP9Rf0*I$A~V#t9LpBh!f2%A|s_I%oBbt%sFR`Pj?ZvHI+GRPotQpr7&rrj4~|*Zp?C_sw%65!F$s+8FD?Lb`mCL6^FKDfARa1)#fe zS>UXa9&V{`JiN{ecZOy!dToZRkd0Plk_e|NaxwF z(ej_lxIpctT*F}1dA#kzPs~rK;j(?z(PfyRZsZyHU*`$er{d%8v_e|42+YhYR4-__3;L zW`9d-V`P60R{z>_))7G=mV4AQD4yd4tJ}konxh!^3r>%X?A)^eL;EvhPq!tw@osjS z*kD;-(-Roe_H8p~)^GotDI+U%qJK!D(tp*H71Rk{A? zuEmp?#e6mN-HTw; zl?|&$pki^K5s9{IGnOM&f>43LM=vB9^PWFW7)aD;Mc4_kKbLn!r`9SD>~SW2ej9&x zDmiR<_WG^cm2t%1nsiIQ!rFAB`>5w0sgNFoTWNuBfK4LB0ANA6v}A_OLnn>*r{ws) zOm)-hZ*gFRTs@H0^XHtegn&0^98Z73bGOUxMV&(+abV2su|QT z%BBQkXmHc4vxm&%xc#)j#fFY0etE<&DG|cW_O(dAy===eumk*IBLbN%0sYC+nxHZ!wKR$l8&kL`Mfo0*byq~dc|M5gJWz(D`1Fx8o+BsB$`VedsBT~Ci$XoIz|25Bh z5t@GkO~m&M&_Kut!Tzy9NXP&0(=n!nDXZBN8GXWhNKTg~{4Lx4=)DJbEl!*e*yoLZ zdFp^F`STD{7^+v}FX_kp~GJfDoX_*B=3L#umpxAQfM-#6%a&mE>a(`QH zL||9rOABlX8kfk4Q`={vG^XTVk}@*0g4dO?HxEqcJXN^f>OvjR$Fp&7R)E_JEIAj9 z8IXap*UOC@zY_O%P~RrngER_iwPcc80}<7s`<*0Ny;%7#f9SP286%**@MR~~y*GZ> zpZICci-{(yo88*|iasSo++PcC+@=4i$sz#lg!^OTE>0;v#8~h5D3>2K=kx`ig`cm*EjR- zV6_IXoPRul$ZYJx%K>`#7d~9hJ{_p@HMp1{tLrj!q3BOo1!N zuj`lfxm7hs1b%tv&l_JycXR<%^Zdwd&(AZQ!e7yKAt9}0k@Q3(soUrz0 z9R5hylFTRZ*DtaR`wIJfHOzvqR<&1ySi4q%S7k;s5y8W*sD3+cBSL?D!}E)kfTiX+{3a2iW5HAnaO_x|vOx5tqu^tPUF z#z=l1rm;^=&r{=Nc!j7Xh;O9_&lCCjOwU6B#LsXMA_JYllD9Tk!a$-#JB33WA&h57 zv;n*lR?mokT@5vpVHqe_87!TI+ng?N4XYLz-nmWCAKJd z*e|;8=j6f8Beq*79Sn+m+Hf3P;AQ`Z@kn%9R(F-<#mtLcGFSVUxP1@URsWg_Rc(7i zsB7yfIU}F9h#2H%n>xm+_I+5bP~lk?iaqwe(0@VSUR(n7cM}xQ#->u_`s?-bJm4ul z2Z(l0?gKww&@%ftWA;G0HIzt?sJrV&-(bB~ca#l=rm?-kjm{VE6~jG&AwdNkX=oQ( z+84)$kvB-RxLh9T*Cb143RU&yKHPK5?t9#}pfC%AOG;gwuFg9xBWC19+(9`oaqdZg zcfx&WVo45}l{VQrlWJ0OC^dq-cSNC{{=*`IRbLX7t6A&j!TXbrU-X&t+oFqFC}I;DsS3^b!Z6=rf{ z|J=Gh6;E~znRcGVzlonMG#)9T5P|`dGU(>fp~}l(0D9(QO=G@3C$qZ+$7|@mA)!Q! zL^9rUv)QMZCb$4Cu%D-;LQ8zQD#Unl9O-s$?olabKrqq<^nc$fXN2FWD3bb|P38%o zcRKyW1Uma`aw}t%`t+uOb7N`uBL8Vyv4ssEVg05Swfa$#zRBxef(K%rJNfYfR}|)W z%FO4z+GKzGLGaBk3FvM&_^H%zPegI2eSz4dg*T!wy8PAFimhhLH zvFDy+r@ZSiFg|j=lnG+um^0b5=k{a8s;AP*JE0+i(+U0uvS^x;2no8SvSa1afjL6R z*n{_X>A0JFnNaP=h<*6sN%#M5n)Q~o_J9^vTpa{RYEd4l?C^Vnz}HDo+>m#Z=4_J{ z$}3$cq4MRyCCjX7za9|^L}!R|xvHwN_vE59GGRln%NO>ssxg5UT2)E~yQ`;8Y}ptc zfKnp2ock@ok6pJWiQuEH-dg{Y$&Ce4P;jdk3MZB9bs6r;uNI)9k(Qv|ZQJT;R?h4Lh}kV> z(Tm%w11Q3p^|-0IOxNFK&p!>IpZyj-mr0Bjr4rIFqJ5BK*QtN8O(%p`wL;n@Sh{_x z`?fV)RE0{-Z2R;NpGJo)Q3h z^n?XHA$G$r(#>~o^4;CQuN3!-4JonC{r58KiyZL3ab%EKE!)~~pA*VAoBK>@?I5XhYnDw_IJ)Ta;b)jC%=0pHpFnxBZ*mCsFiH`2+Tg<6!uzo>Hz# zi>z6jI>>hbAeraYF`;iQixHzmRXQ=wte)sS8A)7b`0F|qHmZLG7AnzBc5{xUrTIBu^EgP)&mle!v?@yo1 zzTI4DiXn}o%AwOs7Qx6$k{moYozFInjbH4K1<2GGrIYC0;}{@B&o9J@|5)t!Edz8x zejQ%$j~&<_O&xTWq-=U&PFWade&=GWThqtqQEwYaJ+$}}18QU316WipYlq&|uTe3$ zcn)vOU#5Kw?9#98u$Frtq6&6lhdd#+Y&_8Pr=kJCs84dXS-G(&3(Lz7ex#0beXwCri8LvK zPXDnNHs^HCX78*a^@#l1RSzmwFZWCnA7PfHT$Pa*jPlUALtlK<`%Q5@{Ii%GK$-y@ zF8soZ_DhNPh5PsPzNyCBcn_`06n!@>iggR`eZm{?ew~Yjohhaj&IVwf6xHyDOPm3% z3TU$PfXzG;)9dt}r^jDcI|fyn4L%$TT&EH_w^vpCJW&$dCeg~QM~1}%gQI+&SLb{i zmme*@pZAC5N2Rq!wn2^c#c;Q~HQ~)c;rf0P=#S0nACVjOcI?&A;u5nGc;cFJ`A~0` zAjjGgb#AiiXa=djklSv|4r6hJh^2x>?8W9+7760)N^xIS45Z&}i>^d{XS7N~i9<4$ z`4)%o*kkm(mX}lVys<>io!y!Sv}GD(L%M%X$7rA5GPxa3*-JdsV|^dy)Xp*>Sp6ZO z6b>$UyzA@lxlhI~Lf=|Nv0`$cZg(56G+GCN&6fKFkW2Tby=^NvG?T_usyWBh^!v5ayXKu9%t7UGN8;(g{TD_oY zy-bfkQRZ6xD%w7CBdJT-Fmzwe@ggAv91rV@+Iwp87LEp#UHwyj+Bf)uZZ`$$!uu*j zCzz3t#B!rgm=q-gDok?^X;bf-hCyC+%DH`HJBnY@s^2y&B4i-tUmEU_-YlH}!08`L z*VV2l5=8$JLDC~ZL~@XzZ$tq_5D?H`zlS^ftvfUKs)*2CU0rp;eF|s(G@TpqGKl$p zfo~__u-dlsN)0=7-P$Gopu4{WVhu+4#k7}xG1TqNW=^m`R;MoV;aF01naLgdbN?l! z3kk6HvueD6_1~tjj`Fkraq<1)jcJaON z7HhH{)Sq*G50;w0RM`dEql zdvN#d*hvx$kM8A%%524ZGR*bm56)ft*ak}J0I|ty^M-w)Yn+6VKTB{H1zK<*ep$&W zKR}{V-_R?>v+8llt@plU`9~;x&M~485E zPnO(}{+0!7@|_@Rc#lgMFUXWn#n@QS#zN0(7=0vif-P=-9ytns3ZU`ywx zGMqHF;%qzJ1T;sdf*2IQemZh57qvalw!+zaw zNVL?{(6CbB^e zXI=_kS3m62X%g4z>9B8;)TO5c+uJK2{L`D!So)Z%x(u0Eoc`1k%S`-y zsD09}j}M8u&M8>UZMmAC0G818@UXaq!gY{bWN0@S9d%rLq%F2Gv2A?9#=9MO&&p1@ zk}T+K)XHl07?l#JSLmmT&=%s%EpA@`e9%lrfd4>NPEF17iU8qbM5`K{ z7FLZtPOLE6f`cTES2NOl91^bRk!-5U>(TjC4VyTTpG7sh?OT`VO2lZoch{j8?(ZoV z`qK#tRIr#~uGyh)4?NF9Uo8LKzMmVns7srq+fCi)5+M4_D>_awR6>Y7Nn`N807mlH z0H&G&=ZR&x)uGCp$6U@jU5v+fUD4t`Q5|J2-vEl?9Ro!DjkN)(7P9Ax13UJXbWCo# zE;L>5mmiPdF?lv^X!j>$8_%XVKb5jpLax4%1WFWNsDJfJTIW+Eug~p6pZ;p8RSYj( zy%_+vK1m^2O_5eVZ4)$^{#qvj=QfGF`nr%F9(tA}8$7|vmfe`(;1S?m?zZI~aR9LEhxtcdVGuUh)Rmn-CQ9*YrT*Xt zar^ehFlgt(NRO*im)%F^C(VXM5}_Rq8HWnjamit(DtCnGi6khV+7Zc7kD9`py!UWg zN|vX-VA@I@_an*kgAbzxfo*4h02l2N+IPP54>PbS&3Wsc_9)n9Pgp@XNk8}JIA70? z%(R&fuG&Hu1YbC7Xum(9n9sQHWFodFgAD;xwTAeybTfc#$J#{$+iSxIQuzGJLlE%! zD$|RXgB;K4`}`U+XU3!hU3A@pT6W`C#VorjpO|cT-#PA-(r@{&t(mvEI;(;Zd$AM) zy0d%b`6`(LnBC=x%oBL%l)LIVbmGvyKD#muUi0xn8eX!7X**ZV@Bzq1P0GzkmdWfd zJaZoTi?;8mgy0=I;V4a2!NDLH%+#QHmRIBWgDda;LD==XE%4=+;|ccLyx(c*5k?ny*e`avyy;+YEcsIH-9U+(qm|`~@M^I3O@&W{i=1?S0w3Xx zzawgj%=_mLkiZ{4#jklz)^t4s43;D=*9aIlFhTF)Z*Y6X<+nK3->cu=7yb84_z*RF z;i)?^16AY|2RuxOlj=wJ(9z^D4$oUVo)4xA);L9yfShV`WONPROin*Dd-!KhrHj9$ zyJ$_@4C4zWQj9-Ik$AsY*uUo`Bi~CP)=?!|%Z)ueDqHNuPl+DP9={X!H0>+H=^U{8 z+Ij#k09S8a!2bH!6v_!e=NGmCFzVJ(7;k$ispRyIhKFnSZ-kfA_*&{P3@ceNN-^UvK z{*&q7eVg<4DIIq&b5bu1SSQ25#?@xgZ+HB#!Rkq>7iEFujoZQnA$1j)F*yvJfu7rd z5(xRa7oE%PS271VcW}$SNm$&f=UFahoVHpYhfmZpns_m@0d-yObkAd=`>U&Kb-D+y z`DSYBb>ZTX`y~&h&{%tB0_q(H-4L5Th&zFDlyu7GS-@(jGqmyU5y0TP2OCtNtTWMl z*#)*RPu?(^H$t2QL)DIuxUy*9j#udylB@jcOh(3Vcc4u=j$EPb+o8%h9m-#KONUig z%&18kXePPd@jeF6{1psW@PmZa1h&lg<#H%=>Xa2 z-D*IEan;#I-i{}O4}nUeBl@NEr*iEbZ;|O7ZZGW5n1scPQ!sjdzlP(ApME%hX};?d zjSUROrww=65F=D#D#QCLL}wWlvb=!N%Ao}C4J@FRS(=K5Xw7kmWp3+d_8j zQzd|{l<-`CZtqZ;9c*0L%Yo7X({3n&UT!%*B%2^klx#bnG2HHid6B_gZr-bm)b7Of z^$S392mk6bp^CfkPF7H|HwYiF6#=f3=9Tp>&uMf-2#8 zeVpO4rYYX#)@90(*AFmF5O5?Fz7oR_TY(Rc!ru%FH*#4ndIb2*e$9Fw-6^>Y_MMKC z`Aqef({sqUji&wMs=-YpHulzk(A`LOcw$5#an`Cxn~099-TV8<6~ zEo`~(`@pl=V(g~zodOAGo&t8**o@|W+!K&eQj@k?eKL_5m8|i_TfqZ zi(lfsjK^R~-ntuq7$i=nOhjFgZ=eo6k3k}Qs_SIaRmB4HR$q3RK=_Lm1$P7h_qZg@ z9+K=x8RlbXw&q936}E_8;12GCeDY}$LRunO+Xh(}5cw-XB!?8Hdll8#j5VI9ACL^8 zcLN%@Te1>b>4pukQbZo*w}Nw(dU#%_;ahq$xfgXeevjSvZjU5d{<5H9nO&Z5sCdoW zSiDaHl`3v;L_br)YNvKmG;9!0CBL<(&a$(mT~T(48go_^yl!5m!VB$D5uQ0Sn1Se;yo|Z zWi?*0;&md=-ynX;7zNLG;+_DJpr_NBoaNthq;^=bWvb$$s)YUMQDU>_qrN%`H&=SSAQdA(;> ze0Ko{*%=^79c2_6vIg;SIOF;CzRsV8;INC;KLNOiyuI=A$4c@Sd82P)xPHWd+B4Zn zgO8L@3<^9COuD&+ql$XXT4NAO`t?d!O?HhasF_S{JMdszkAlU_B|s^o zKwMfO`#zRl(7jxVgBcq!^|G!XyIjigt)D?)-}jU)Ny#F-SF+w$-j#ZuUZmTwd(A+E zSj5f!QO{fLDsm5vXC0(+GSx`ETyCmS9=dhb2IyL>JxH)tH(x)Z{<^?Ns~6f66fkkZ zDupAR0)S=7r!&jESvTu}n1UpKJr^e?_fh3PZn#Y5({0|z{s})#)63`;@+gyHNh@HOpWz1$RRuHMsmjAcSt(i&$T577{DU@9^|b zz#5)Q_GG_pVQ(tPobI;#)i4h*Nf?eu?A2#7fi@XJ@gASLr+*&lvBtr?W&u?<)eYZP zW%lNbx&fGWRdF5Fuks{daX>?rauDx~bcSrhA4rBclMlXh%->m+IxkK|D!@CTsAyFk z-PDRY$Y2UJmuxC;)$c@|g|X50%FHkYZ*`=dkJcdn*%yCPiVC2*@f<*GXUgh5>jted zpn~*U0qrtBJ1|+lb;*HMWNrP5bRx};-Qq`GKNLbsX!DX%r z`h!>5n{Fx@1juQ&hIcR1Ua%KXX|>gRXN9QajdM5K(w$@Eakm@ptTg;!aAX0x`CarP zP>h2+y`QT7+5^)*8d?!k?An4mxA0~6dY^#^8^SIa7==9Foyzo_0uZbJnxtP5y5U8cQgbN|-UFek#8UA<^M zzrNabwi~N}vTUfN0nqWzo(*iiKQx0M?DOD4zEO|a|^SrvWX z*SL5m5v2F&+X?xaWSp!gi^E|rqTAOTdV?IRsFlVmS_E~p2`r#&U9tDqPxsa4_7rdD z7N{Z{FY7V^d|Cl*+K30bTczP!xz={o)>C0@&>p2t`B^`sLwLK)fNgLDgTlu?=)Qtk zO~lz1&f9irYzQ?$poCcEua06fb~yo0wtFBblX?3dTx!1~T=_VNrWUPSan;}hL;lL3ExD$udRw)6V+dlmhLPt@=iv8K0;W$wj!DL zqJg@$`a3;e9}=LOr3 zjk(;@Xl+9R1{R*d^In5OYaV88*gx;@h%K)_4{+733DN0l?hk`OX_x|?e$U|Qz%zw6 zQecRF(n(-w@R%t*JOT3klKHbaK-ZC( zCYti&C1tdH!}~cqkM!0c(_n6fpR9(w=c#x?74j6~cM;L-Kj4K#(FRtn$Y!rLgH4$Jsad_e2l6N`;=DRKSnAn>EUi0?hafPS6b`!MwLb5s)LQ^tSBJSc zQkDot9ACAJ1LW&v3B=b`b&Ay@j-h*rM>6hU=YWdiEuN3TeHHiB(_cmJ&fcLk1C&>O zOW2Wl51VWaH-c~kxFV7JomK#Ah7U}(k5~Mds&{QrQhbL5V4S0Nllw}*h9x>eMu(~z zPdS!sx?xd2l;_``Pf*FAG0C742^w3olGWBA#Vkbw;ggmhn3=jCe*5 z+MqHELs*)&%OPBRe+%XQ@W?*ioAf1z7GLVaKKtT+s&^{YTq!uD&-FApP$EXT6z&Zt zS?ZvoPADO}T_*%3;%4WvuwMkhOm-HpWGr&wY4S(0pzfS6iFrS}sY5Lqp3{dKsIv2q z##Vijz4(NiIC2UH+whMg!{u+pN7u*4(LS0A|JAVD;~vw<^&D-#VAEVD#2*02Vtd%t zQu`{UeEkzdp0y|_E~r=tOXm+KYP%JEm+Kr&e`%Oy1EXT1-Art#Y3ljtIFj7L-MLVJ zT*y~2oN%DmL3ha`uImpC%n0;e;yb{_8_ysma>7R8t?QxG2Mp5@c0hG=abP9!)8u4) zpci;DVfQ63?LPmf<&&W&5)cc4>a7HDiP3QTmfm08GARBenEM)ld%yAxqNje`6I$R7 z{eU@J`!J#lEa4+(TU$%tTU=82KE9p)Eb7Tz;qmPWmI-V>=Bj1SOpqu-WZy83Nd!Y^!GqJye! z6z`U6s?%e&JV)uV*rz#hJFO3~mKphs=dN#e&m^2Xpt+t4sadVMo`UuSblPebX1v{$ zu})v@?BscZ@h$C4Q7L~_!%MjxJ}^S82A7BF1k}s~syl3#m$nNb>{WhM7BUA?Q_?R< z_XI8O*H4JF@1&D7I)rm=vyZs?5j8|S=9S}SCw*q0(*As|_Upvp%SrB0@J=Uw|DNxZ z-7sO)*XwiJ&q3ch3Z$Lj&EN+-7Qhf9f*H-<8{$nU>8n=1v2xPFRKA&zU$??R?-GuB4JYI45%S$=j(SNXjXy1p1 z+<*%F1Xjs=?O*i@ZJR3v_e(gRk>qfFu?89btlxa$q?LHS{px~OiIBvoTz5+v=e_Ux z_gPO~_xt(KWf)w>j9ye4nYka6hd~v6BByV`Y+g$(yXV^(;-`>R-nEH+K)u$6zL+$j$q-OLdA@zo zwVKQE!h#A18@Y<)!b?sk(&_XF!QA>BzRl%OU0T}b&KfcFi;=}jRZpqIfkB;t2MwD- zg^swD-zKQfKgjGGK{NN6g{z1CtX4NiPE<&fz3F<#5bwLhx1bnS>t67<5^|oGMcT$M z9&(b4GnlIfee+pZa@Gzo?$lxSO1NE`46McdU1XB!#_!|xa?5pGn0S1JAKjHdL#xQo zZA3s1!Dh~)_Id|F>nXnsIQ!k297b(*nC~@QKNo%gk}fuL8-Llp8l-vazw2(ElXyBc zfpY*VOU?mcMzgynuO;~N(y6Fds`P)vl}X-YSz^K0AfxbMi;WZe&7VT)mz^EHJVNN#i=$wakezKO4)pi;9!jm5#1W%Telb|#AN$_eYR&j? zi0@6*Igb^*($W09IC;D%PD_VS$J}>Acw7Vgfuk1tohr}YvgWjz(INdxmCE4dItz}G z>HTpPit|Ws-X5!LGb)22ZtlJQ3L(Ibd9JG4@7~^cIM|n@n$R`wu22tB|4iij$UY{h z9)c8``cs>Fp>bYHnfb%AH&{xgL_L z4Bnsh7@G=1%K~Rw4a4QB@E7cF1W!@Qg(3=BxZaCksYx~a`;Lz|J9|)sa$JPz{jPji zCUty}FrLoklda0}46VTgLVbApP~Sf(eLV{=>fTP1Y1lJVr?MD=gD-yn?qBYHBeE!; zR`USZ(=E@p>ZN!3svb=}IyRoGbR=S?RD(!<5$Mz5aZ1z=zh9(#(pDV)euIAL!YI!< z<}LdXAYylg+#SWakAyabTXrh1T8#_{B$q3D;=539%e2PuQN#Tlaq#}}@=+)c)KG3m z$Z*l{El9XyBwo8dwK-i7Qq-mps?=PB_364+?cy^)V)r3LVNRs=vMi5r>@jA#6vwNs z>3iC5g#s@_{FRBV19U*kx^?ML#O)y$bVIP2{sU>v3O~H8_W7wIV2RKYDSOoq?7|G% z%krhb-Rfr2ny|d4;Nsw5ME$vj?4Q4Pz~%?AhUgS6s#|$TsOvqaF80`8WEG&BQhP?> zcfDnm(ET+4;R<%CLWR(%P)0v0j;)6rKA2RGtmw~R^)ENCL?K$fjd_RuHK#Pp^@x7L z6ENGG^_BcNt2vWgG~UzC!XJ%M*!)Ze5ZVO>wXge{hI-iLr|{uUiAmxpJiSzn##^G*k`&eHH`3BRgm|K@!d~r-bh! z;_7wjL;gLZ_Xa(f7wPQz<417%7e59Z#9+o9hOK&8*1>4oqM&cn1n{RSX-Rq0)jZC$ z1*^vQdtYTi{?$watVv~Gd4lCqy$L}AYj~t9o$46qk>7u~^Ag{k5htpB4_@@}$3fmA zU8g~u?z0W$a(L$w$%{9>t8dNFfmJ4DSYz|gAEm6GO>aQu-10m03SS_>`Ayyi#g4E zO3xoMzGgsaOV#-;&@Aa^bP#qWj*Nua1@WdBL273zt2cGXdssw$8vop?C<8uYoYB`j)Cb^+DG&U}gJ zy}NWI--_rVr#j%E4+9JXYvE~2_=N1Va_JJhY=$QyYthy{MPyz#NGyOuzUNJI0#nM( z_J$+%I6SuIdaZ@=N%#jmM<)jv?ou9j_}~~`;+K|V05IkV^Z5v({7>``JO+1kV}D## zvwjb4%;`XR`+a4b7=Pj+-bq@oTM<&dIswD{tJu=S3 zNEFto5)q}PT94Lo`W-pp;|NoKT+l`t zB-7OtG;5>QHM}JIhRZfjLJp~*y&#bGFg`OJZith&3aUZ{>m|r`+>TS#LB~G4@az-o z7$^q0Q)Kb@7|@Av-v{CMhz=J2R)Wu78sp;ODG)P?Eqcr;#BrasjgcJ8ukA-X456!@ z52~O08`Fyj-L5YVS&o{ktlSdC(z`53n3g~)|#CE?UaEuC~DL^)BG*I z$?0{!56A9#rTINI{M~OfODpt%bhi?t=MzeH7Juv?diai4NeP5Nq-CP66yN(n{Wl84 zw(hVAimmNFGIQVN#urU_lH#rpvqCg@oBX7x@X(FN{Sl1533mVF-P2H_Oi!d5D`KLh+6OX{sz(O*eo%W z1-okB+q?veQ;MRSKG~kp>^E|$(2{@0e!#-QH5qF2NKSzUp}{dp)YomJr#oHsh2w%( z20*>=V}N?$^0fsje=i~BSY ze>lF4j=v%tcHi-W`UEg~uJE^>JWf{{6@PVAw-U_y%X=4$Va~OG<&;S;DbVPArE zKs@w2X5p-lIidM(1J8=x+eX@soWK6^eS)!*Ii9Y|F90N8DNqDUpcoms%Kf}&h#?si zdnD5@=S>o8{aidg$Ex&uM|6~B<0u@#voL(5u0cXAe)oSaiQyoo+Ve-h>+7s6%oc=& z!8vPQjWl;T!?`qP|Lm8KE190S(-d*jldeTG@Xa2cn-LbK<(4uYyN?fpN()r3PiOwb z{G^cC$ZLQ;%XWg5w(?_XmN=C*$;x*?JdUvKmPI}gzO;8CA&cQj?AI0GNcuKc$vnL4 zX4m+WmRg9SMth+IXh7;3Q&V-FQ#Ld{a28YiroW|?eYm0)%A+1%IiNr?kh3qzKq}vM z>8`Ml-s1yO_UiM4w${rF<*LZTZ<*LjaumH)OMp8-|vixH6fMYsn~SnE-a zk@*^P&Hv?>imsgYRnA~V;6*@)BCg;M7d{ISbv1=pj>MARr}?n$xfz4v#5h48pC}lw z1`a0$TlD9cprzVh5xN(P>sZf0|02DM}z_L2;67zVeXW`C9PGOb~mFr5=_sxi>@FpFSCX8Eh1W`<(Q`h z4e8A*UJ%Wg|FFp??=b7_XTM=(Y@Ej;v2W%3p|i)5W1C~6WY}3PIFk5_3-Y+I1L0Ks?Z7)#FH-m3)yFNYR=pN#>26?bO2ier^lUdWsZFZ z&?@9jz5C#}y8I7X%3|_*iMKmEHDU}asiN-%{9y1&yC$3jJIl-B|Ilkz=L^tw#X%;v zNLrTjy%5<4)Yhw0sJ`Bzw_Lo0r1tO+ZE1xnB=(A~vGy^bXDKe%_2=qkI8H!001_+^ z&AG8o_qmE6JvBWb+iJp>#@q6`RG61=?;*|k!Y1=<61ia} z7TRVC{bEO%+HyE|p}iiyn5T<^!f%a#P*UVl4^2xb#%-$@x&6cDU};aVv28IQpl3 z3Efm!*uJB1K&kBJw`7-Nv(gy4*%)?@UMe!g==`QTcYT1dg;Iaw{}+1L1nC z9bu4;Eg2A81!RH1Uc!}!7^#SWjyD1Rtj|Z#6kj)4yj|4T3y(*-ypx@D+ULY|n*v=+ z%Y+^!v|8{E+*N7n8YdFh?;Xx_rkv|HCry=V4-DBM=9XL-ne*N8}e&$n=(tcA9Ink z!(0Tfxi#A{ws`5p8_BsmI|(aRhGI z>v(zRI%9%D4)_Ukih?pu8^tTAh z>yz%YN4H!V$Aen`J${e1D88qLDmMfi6(%jAg++_`fC9f65APPQudRXoU@E^GE;7>- zb<0P*nfd1L>%Ji%d`xlG&<`%?UzQUcVi>Bk>BDMtBR~?O!dqVTO|) zN6}ur(d}>!fA9Dd%{sN-?cakjkLu4$gbCUr`&?5q=GZ-0$?iD+9p^OrI0!Rcp+oek z6!IfN6yW)B3&rGB%7bM4SwDr?z(FEHfKt1yOaslhu*-d8lQK>u_x|dt`a~l)6Ll7X zut`n@CooEYl`I`M7GqpeU#R>^f0pA7r)!vjL5!hpe+Q+dY+{g*V<(Z;odI! zl8Y1+=x%7*PRp-G+RyGW@HUSvnJC|SDN>4IunVR-ggMDQoF9;i5QoZ)3SEBGs?hSq zc1=L>`oMYdv+l?P75>OlIL>y~Q?qlwEoldLYNAm&$MuUd8*BS~9mXD>aDuO}cZGPi zAKPwNsMgVf@wzh_Mf{SJJ8!Ua_N)Tnwa48PVjc#br+pxP`0?8-k?WK|%I|sWVznh7 zk;F-v?$+$1+a_IpeMdvu**t3u|5{;M5yUPBAI@75X7VHh_X%IgD-`F@PJ`d{0f4Z2 zaJcL=0aLnP1{yZxCuoF!Z1B8PO^9uWg)alYwGbUpMJH5#E8(y0f?%$`J(UI$q!;`A zI6>5!^X^?OB(_(zC+mC6HrfC9em0<{bHU502?l!xQ;GFcMu6C}hBVp-1|Hd0?62|Y z1-9DcDn-lP;EZd(>ZJbL+Hkz4OdndBEohkT+e=62dwK)JdscuB_U z96x69V@!+@{z?@f+V3O(fN<(>S|AYHm5){dveRiU^b7nU8xLD>=sl_q<8Smws8NsU9WBx2Bm%jR!K>0ks4;TEC zF=8{@`yhzzSpptkuM8XyL2Qo`zXWVL`7UVvb2=Xf(HVM3GCt-LeAwV2F~l89thK}y z4E2uU=Ux31U45PT=E+7$AuzYUgG#7JcPaeZuG$NNgZq*3d-`z1KVGOSETJ57OLjiM zIMC00{E!N{7ywh8$uy=&X-O||3J@$uzl-;?61syhatXJ*UM(20Q_{xOI&$52N+yDb z1_x0;xtCc&Aj2Gln-VV}&bu0~rROP)2aN+M3j<*bQcrp4M>;Dg7=z&@4_3X?!5zi~ zW}fZe*O8i~Kz~E3$T*dfCv=S2K$!d#W>HauTI>1(=%2s6a_M(5_LVK=&5pF1@oy`r zYj>(7?${U8ny~H5*6n8#+j)vp*P{W*Heb6m8ywJxh&YLPh!FifnKklB*qqTUP8*ti zewo9PRL~dY@Mi?+n(7a!m-KT($ac1tW5uVe_;Wyc{Z@9(5@g)cpSbIgHe>Z!0BhGk zn}!sx$(<~?D{9$xuk$RQOm99TLFX6pwOX!^qrMlTZm1@EYCk|S%5|Md8%F2qQ*DoM zne=#rfFZaQmmEXLKk2>Y%~iiaAQHyv(Q+QzE_t1QGu$K>cd!dGGYvwaO1M8HBx-rL zBNr@(`>N~51+8RBbz9?oenMQ*?lbIE>S7MZ~&K!z{9Ld2o{QBN}$JQ|->7a{s4 zC9avI62kpVK^9###Ic~c2fI(+{Ckx?xspx$fI_RrgVdU}5B&*VIc!?~S*3k{ftTd0 z>KsI0hHp)jH5N?P_sUIyXrsP=?-lK>vJGpf8NE&xOqVv&feth8041q1V6sf?pJ8-+ z|F+5@!*-;4Dx$x_!RgqtDildN`x~KmGyzs7_G||?!+jg!na!X%vNATYLRYPO?Rkk>(WXT@8sTttKDAiwXWo|0QdqDc)Q!sU93*!8>5YI1lwN1IE4 zb@{n)D(~t>KIHbke7#8FK9!VQ=+3=@_c(sF4;y^O_9cK4cmOc#po}zKGd*{Ibj(2D z4#VSS3n^g$()5syv;R`JP0@`9o5vyYwBxq$T^3n!|9B@rI^uv3TbpJz;*>=OWvag4 ziYLS;Ca7woU0WQga=7BsO3FwbUk>Fb%&i8BH(}pBE!?)?F)-(YnE39a2JC|2ulYqf zm>qZW{r7ZPZGQineh9xZ`e0-*;n-u?(lt++e@K!EJZcWq+tybDMgAbm@UgA%wBK^# z=cL!Xf|h$n?ji2Qo>jM*>@Q^pH$yNEr0BM4DPC@~0w6i(e2Mt?{yhoKIq!iEd(H(M z4S^uUw3DQX9SF$@bH$1BhVY^TUV=w>?a=&C2Gu5XxhcuhO-WDoaH(pjrqK!A^NC@^ zR=gUu&m7Az7SN6!Gkj3F_4Z{836u4#OSbFHfsihmmtGD_p<3QI$R@aq35x`JtIqcX z$$+Y7at=&7UP?-wD|GM%Z#vGh@}`7si_e9MOio!YetRtj3_6cR%#2y~bpL&fV5=kjS4gT=kfhqs0;*{@R zU?n`A%^H#d03_W`=bMDPh5ktTLQeb!*VIqGF2LS52~6qRDf(Kns$pg-;2vXxoTThB zOUrL2;ja1)srU>=?lCz=++qdLl-+rb`mP30Y>0Pf55=EZZsEXcF3 z@K~V%yl&H@)h&_J75auONR?WO_sREtN*}!S*eJ6I#;wOz#1ObAM-Ql~Y}5CzYsYV# z1S_F{izn`jWw`j&b-`ou?Xw&^Q3ij_@o)jDE`}$kGJOG>n&7l9A5TY+yNW;lvwbhX zt>5!u<&I6;KD~|zxXm_@N%Owg&hma-1?)THQ~Nx`4qjN80pI}HZFc5g*9;EJ)Gx@p ze|T;I+Xg-d#ar%QZVQM^GBfCRfzWuIfkhLcVED9Pb5ye+nz^yT8>d_F%- z-^n6UTy8Hb9U)md-Z|)FjbQ1b&268??9J=bni3C^QM0U{bng`C@eMhk>N_G&ebtKa zBl!5ZPV;xO*z4LLgv@|4d^Phs#pYK$Y)=b86tV}CsSnRRp2d!9s6ORhc*)p6iSf~6 zGpdOh@3cieq4%7T6L6!`$X6*ug0ssNd70{%^X5RKQRcS&>vB10M%GDV*{J}y#1kFJ zE?f`9;?-u|{w{cnBm~SIqui?*je1g@*IhPbb)A6gI0l^*)SM zxf^sNK7wB!Pp_Ba`(7w4^a*=6r4C|>I(qJ54NP<3a~ieX2ajpU$#sOMS4~4@H?&g^QpS%#0I&*Dg0SO2N;g%(sf;5<8qKMT zmpC|^W6krSAWw^OJe=3tekC-hVAE2pa6m>CK^Tv)fj@X9R85|wpDf&JhV+YB*nOSF z<&>m+|NKLQKdPCN-li3QEB^~DGH|?|Ixt^*v*FUP>^rK*HGj~Wui-7Qm^kkD>`+G% zHFTnQBT~K56*upleKp+|!F_RkZb2{if39R=LEn-i^s=Vv`BcB0B<`yZ9+a#kHnoGx z)b&vj^2|Pf))TQ)8m~QbWXKixhcr9{m8DQmy$jAo2>mi-Uqv0}++c?#}ydzLR z$&+xtYrI9=G08rehpJljwo@s7<=WZClOvJCRphr1l5UPo7c~^fYnIz1!*9m@&ax`o zK6FMN7q`A;OX<${*ZF)SK7w6>XFy};xd&xFtc*Qnfo$2?=bjpP2s&4H<>4CMm@|bW zoV#Y%4`5@%Y55jm%6-0>EpG$ytVmmWD=*c=4sB~~uI*fWy7YiGqUj{L_EV}Ni$DoC zlz>)$h1w0zTW%;qT3g_J>>1L7s7rTv$JXWZ00naWbql;h&YzJ_l!v@s`_uraXR7rJ zUz$OPlDSnJ$#&=Qs^tnvpb!cuD*P0>+djd5f0miKJ_ynAOkQZ<6o|uqW54FM0@C_P zm_%$;U-($CG`Zi7O82-G*%OMbudDyZNAtAZaa4O}w3#p53;60EEEkxJ{iRYmbtF7p zL9$mlPQUc?1AKu8nz$ok4d|{_>7=yUaO6y@y=zyt?ev z6^!q}GG4DuB%e^|Q#{L^ehA-2?u*+HjQt+P)N^-PK9%_S-P$7c*qFT?RLk3S9l^cd z7Rv^o&#a!BOl6Bxsjayl*b7+J)&t42`i_4YdcydZ?i{B{@rQoL(CNeMoiHsohlV+;E!JMetcR`o|jZK%FAtc9lG#rs|TalU=vsLUpDzi($dhI}h$(iGp` zrujQ%LvkyF>m!yc?<;<4Z~BjNj*5RZXo_V%1<&OZH|4jl>lyUS>nWk9LYeOgfP<@q z@;lAi?Y2c!&fT*kXu9Gv7L6km$_Vg7#U{;6)?IRtUh0a>?#5aGey(Zr?y;7GJ@zzhg@nM}F^DT4PN}B8ePxd_zb#=edv*!HS zPlC=t=S}2{-9ypuNUIw)jR)*;BsiRv9R$NS#P0skLZ2X*b7QD3hnFl#u725@Ebfw( z@iQFzk9lSa-nbM3=!WJ@%>3_Kr+sqz_N%UTF8k0_tg$?~|nutDh)MR5A@ zYfS%JaqZ0olGBn)&w-AE&2D(GA)kX z=0g2yD#|WZ6Ke6(M~UJnCPz&E&-SwKz2jd;3~%XiK9M|m%y{$7z96_FhkK9F<7{WH z<$@){;lK);t--}y@|#lYGfuvB$8^iCy7efbaaoSyUoCh3~WT?z#~H-2&-3 z-q18tIa4=|5_);xnBNen|FpMcy^EmsQD5Mw9$6WbiRDj^KcrMpM~CCFq@6D|+I>Hi z(UKC4GP9IDIN(8Gr12Yh)h)}C#aj)F1b z*b$H%w9i#OeBY-fc#?OEJWRI?3#c6JQ{YuP^vIlb7{@JF@)R>4W>PAvEeQP5p#{r> z2&J`tSo;bpv)aBkhG7liyNL6Cj?0X@IJ}p4J$!kbPsCR!+^Spqx@b{174{l9k^ek4 zXZ=K6mZYKCu1Fe`P_)tL)kc40uzz{zEzWhkzgP;MqC5~8w(=TMcx1k!*X_KF?JG4P zW?Ch}<4@}V-%T53(s&@eE(_fE8R(CQAAb+W!peb)1@7cxbGH^+_VJOp4VzdY8^ zy4nI;U}&AKA5uab-utNx3Xhp>C^xjyP(F6#%SnE+xy zECM|%WwIHgH7*Lwfj!!VOJb3-NFmy#osOkJ!;=8SM>goTR-y{kI_F7-);FG+__S>* zlA+K0952s}n;pkruIz0hZxSTXiGu-g>D&EYopEuw^6C6po=?|MKdosRh-g`gRs3lC zqb{V|{Q893%_?bgSSn;hBYS)w?~48|Zq2^*60pC_8w%Njr_$He9Zt`sulzz&PkY!A z^dxUU^YfPm?*r59+u_P%0Tr9_oTgRi7ayh5-f%wQ&(O~*odIS`My$e>Hk0~kdf%_VdixH=zQFscFGh(46Fz;+krpx!-yGK$ z5kMJ7#C`_4>7Mm{YeA8zJNfLF{Df4h?7x<>7(@|HY4ScE11fOgpNH$75cX~`<1BAQ zlP1h!LSF~rKt!6?`0igFkC_b$v|=KNo<<_7WzsbLVHYzM&n(A49>!_^Y@WQY(KJtg z79av&>9u$bq!+r#a~+$fo+c!F`SkKdt4L{kWdOWn(fd6dV_g!KKCfpsE#gJ(<+-qV zT8JJKHrk)%KcQU(tE$6qN4(u?xZ~l%@HR~a@I5z2EzqFUvjsgX>{#G|3-kzx;u&qy zlro=@CXCwf09&Kzw&?j`g7x-->7ghp7vFHOYsuls{k;7LFy-0LDIt;6GRpviAN=Zd zXkFkYoa+jS1Bp&zFL)7f9kxe8f~|K*(nZp7Md`}V)A8O3D^ZZJ**&JJcXWyM54RVO zebXpkQ(Zm=Y_%upIo#51STE+`wx;AW56YZwq37P5)58Or(zveI4`i=_f~Q~lJNHcY zxmd6JT+H4kLc4tosf2leGG|>Z#9)pHQ$W5AQt~cM_vKfmHbB9TafO3sT^Of0&c>5g zkQWo~U&`ogv6dbEvG|>R8dr>_<+QTifp{#r9)GXcTX24;32D$YIVSm=KYY%`S==|i z0cO(}WlPL=x8(cz(A`kSHNHPFIXu%EbwgQf)}v`{2f%j*e3C~<*8L8{Gt7d!wSD_X_x&H4Zr%#XrhWKlqH?zH6|TBYsF>X zOq3w(x+O==O&1i_jPl3*s>IcVf@X=lPgY0aMd}_h}Svtf=0SfiX1BbRf@PfrYmDQDs z5NA=BkNQld(^Rfg9-PI96Ny*qG-tbC#sa98TR6I4E>veGwFJ|iDPp<^)=dTi+SY~SfP~dru$bY zQs>S3QGm(81&<@r=&weqEEcnmW=O^79+kgfer?YWj0Ud5A~ABpyy`~L-ll?nNqe3a zA9w+HQRr^Xar~=N&2Kg}bnGj!=e_>m1!#Kg^RXI8;=!st0g8@j_waKs(+xS%u|YvX zIC}xK75ge_V05bSyY`QGWe)Sb%zo1<=oT5^m1h6M`!Yso(;@3vX4Vqy-$B6RqiY*) z3e5T`CI_I$_+_@x56eBihRw~swI52vC&z}GiD#D&7bom5&KVNV`v^YffTEaXY}` z9nPs%3A8NIU=kNV1}h`{P2t!5dzHp{H-=z2P9VZBgt>Y6VIK&UzDJ``rtfr*R)FMC z*_eE`XGPwS9&&|7FkY!t+8+Jk=XOH-E!UuZJ%He*$0bTv?z8?F_@)5tO7|RwK_Kp) zpWN!)zvSX76jL?H|M8lc_93-qH6}@wpyP zA!RIQqOY&FgP_?nUfsr~z6Eb3QeZ#{Q`+@wGtzc9&kE|A>fsA-SN~<5S#hwbp^TyfvD_)sYd6f zV-$H4vigVnHJ+WAV)`3cca5O^fP;=oILAUJjQRvOgMG+uVnw?CLx_mS{y<*L@40mk za**Er{*=wDu;I*AavgWzl z&&)~)?oFp`UnXygl#%kFxZl3<_StI}g39kXuh}e2@7bB~m~h(+pnVw?nu=$C6tW+l z!tY2nc}w}Gxi6Xc;g8ELvyW`~m^}mHpyF6VJqH9R@;olnfAeCeMxKA8J|=RS{lyGWqLOQ-T9SIvQfQZzM19^FBNB zU+(k6coMXmq>#UBcz#r?PrrW4@xyrSbHQUm|?2DyS{4 zz)9#lTOPj9W-JU!#vW4Zt7NDcxuWu6YvSQTgBS){El7AAgu8%wGL=!CHTkx0Q!t}V zTo{afb?30EBhd(wQ4Kbn0RTi>k*ApJ(~0Jz`KeN)FpkyF4&GsI-0q0q8=8$`_T4iLkXT7u1URSvi8?W7l&zHK>!2^h}R{` z5r*d;pME%6G;4Qy(93S+CAaLipPS+0Cn47gRWN*+DqjGReaQ_V6|;8pFOR*# z=fzcNO8D|cK0I|_6VnfV_le_P|3FSqbpaZNqwjC?`+j^6tK}hi?d2D%qDdHiNN{4G zpWibcv{;0RNG#UbNzKLDqN3ZdC85>*pu|m;_et`lr9ENWx*L1!%Dzu%BR@fzq&0@( zcnzeA;iL%dL)aY8@NMwW=HCA9Idi0(Aup1`&`FLSq&D5}^&Y;Ax+V0w`1*DI1jh|} zf5_qhmfk4CFppo<-(|#pCw9kM(H-_Z;TiCM<|;)UI_G8|es|&|saD%8&)=^>fGfsh zv!&1iBiF5;!_ea7!BUlPIYh4)kDLhY5xi|!Q};|I$CC;6;C)w226>6OD?E@n79UmvrZ5gYq>6_>gwF$#a7PGhpx)+G!48d)a|q+1 ze%rm5um`cUKkZX5LYErE1BRHas}Lx&CrD^K<4Q z>*`Nl9J~~pC9UX@-ImMt$4C*?_urr%Pp|vuzNYJDR)jEckmq~vg-sg9f%s!17cI!+ zwll$8Y!~>p;zj&a^)^E$Ax%k}lGWlO6Q7eC%Qs4`VT!V#JL_GkWS-jWboh?pNl{*; zQ|79pN)6T|l$vVTLdTC}Wj5HE@gw3fs{5K4Se~#243}3`lfZsPg|lN!B2N zkUthh{1i${VCd>(xF2zvJ?U^-QUV3HZJVCZramZt)QmNsQ!yVbVw1Emi}=ot_Sicz zy!<-&IGGkT^d2hZGnDfZyZ}>Gk+tT1juy}m{xQ)ZYr3J~uxm0RgMNLc%^>xSLym78 zWCWNsu_k#qlj^qREO3Yqj!T!j5W(jO#%;l~eRWVJZ$O|7vn5secgr6S*azT^?isLu zjv-1izFd^Dzp){m?|b}^ znYZLX8*Q8dUnjmz(&3M1+?;>QP3ujAMWQTsiIbQE8)s-Gtd~cmfM%KjGK0g=`!q5? zq>$&M-u(z~XYHS%B&@Yy>v2}$f1B4<#HQyikfEsY;#=imtTn_sPZKAHK14|NF~i6E z_hV6LFvfd$I4+-tI^YQgnvGCLMy2$3I5rT=BqHA5hyM~>{oEzadt$f&8l*tQ_=Jr# z6xXHdM^^NFM?Z(jRhtZnL?s1Z2n{9@Yf2E{xWC7iO2zK&+K6Hr}Lc?$cbBhuT*b0ub?CmW+>CH~Y z_Zzg)d%S#&8n}cQ`fD%<%oF$HOy59;^tO!e1pPzc_;@>U)n@v&ZhD-Z#&pe;NS_P! zho@Fr5vsn1O8V$TiBrvo+=v}<{K4^)F! z@fB zjRFYRi?JcXu=uUvyefNlE~W9?H=kWl3r5lp2(0=tY|r)bi1@G#=VmDx@w*t%r7fU6 z8W73*`K)f*0(GIoXtji2q(ANDz}8RgIVat2d^=5Dh886nHu6J<#6}wM*;cp^2=krx z8yucVti7TKgp+wH&En5^e*0;=-+%%=SS{X_$J=PoW4L?0lzUmd=g_gdqv}>U$&ilSx56wv+r_VA{{1YUNR_}903aFqYcO)HV;`QZFuOm0ZRJjW$>hh}yKmcPw`MtEfV_Wa!I%V; z^XK#Z>O+tLPXH{Bu7@}?uIrPQZZ0wqNKg<|S+co1n9#!~xU&1ogQx;Us8kP)SwT&M zv)^`?bFLl%Tw#VtrvffqEiR{^-H&<$V6RiSa!>IdByg7rK+t8Fq6qoF}RKPkEEKoD?5h5^q#(IxKCUEeb4mm-W>6v2u( zcD-=Q)=%1btuqk(ob0&@abz8D?5Ps;=L%YKKAo??#?c`hh%Xywut|&+wP_F)0LI>% z^y>?>3Ebe`WiWAVlh?j{%wUt0Y0qC||9KcRbLXv^yBFlI9Nl=iTl^3^(tB7@MydNM zk62Njx;nE`DMGNPAr#{Ow>?C-XdcLE;<$N5?3 zcP{yLHrF>HyS?04Cr@+>@AFQ;q2@x{X#WFUj2Qu zB=i8bNi+97lDs@(=@&X%*9YbeJvJL?iqB(a$!MSU+Kc%Xo*GDc;SM&yJ@ETP$*){G z^LmYmHa5POgI&JRsHIQ5b|{LZ=60w)3C)@ z7Ci^SvzWVEV?#!JYt`8(t=}EvX>XK^mjRhZ@PQ|yHKrj;jWF0U6%~|0=eIj$boakj zzx#lcOCjx1oqzH4c!cD|Rk+zd?{M?m&-`@u81?m1Srq^9w-2LQfcPd_Ek8fTE&dYC z>pa;9WxQOxy8%l|^uvb3P4>3T$Y%8ij2)cT!YsTT-z9)$hdl(kG2K(UAp4?+AFrYs zJ0^*gFv=B~vhSmb8KWnYR3ukgEzz@WPBf#G(O-Y6boi~+t^ANbA_W1c?;ERQN+`sMSvxii@g%F}u zCMtL8_h*iDLU@_y@pgekr4Eth1GI8PYJpkqlc4Y0TQyJ07n(h+3XeWYeSxuEhwS5A z%VUZ>YQ1*k1Kq!|ByWyq??+;!fC3$ zhRiCBA#qf(j*o@8Rlm%=zZdBJg_h-9p;ty;Cp&e#VR7Pw#qEQ8a!h?#pM_Ht8FAO9 zZY!*R5K(QYqobF+vekIK_Ia72a0FsL^ST_p7Nm`V7TrTAG1br_B=?g zee7Oo-s(!?4cTFl!AhluXpn#qiSxMbFqu*^)O#2_h>AkAjX z7Z_S?ca07fAkB_y7I3kQm;{Qp6}Dd1$o^=~WNvWp{QJ0yVc2Buyz<(k{&u;4m%6!> zHe>g;_pgvv9ut!cSd&el$}*vc=v?P@vU`GP^9R-dvs#6rjlWsGnP8SSZ!OK6L{V7At{p z?T_vOD#QEjp_$5m#8@#xUrP222u6Z{z7#)5Vtq!2gxKD?>?_|!C)uNB)|7fkX7d}H z86Wa5fKoe;R`&7H>5Y~*P~t;bSrq5@unPDJh3uomZ+$z+X#WVmYU=ld$}{xj;B(_8 zAk93g+H#2=fWZkHekqFeB|4t~vJfmC1^;*s-a_d7I05CMFSCKg5950MyNAe4)Si5& zv?(a19&dVBOFhsslZ{`2fRN^;I`;h9{y;f#bwtEUGhk1e2s2z)N`U$!ai7#ws}YRh3+w8#zk1Q|!ZtXum?YFLc2T zpa6i+(gGGIhr4(QID(^@hyAHlGGR>!JmM&=d?(K6H7yGVT8$I^t_l|U1$^GV#Glxw z|45#PlD{+WmYzWq3U&n-Ic}=UuHhj{mn$sxB4bCPy^f$zKDr`Z*(lHeZpZI87&AK; zqT2Ua>>qcCDE)5xSxpRf{Q>QPFWBHqoFMFXrEg4NlN0$8T zkM-O#QMgwOS^js`B?A702zQi+Q${C2|BHPj5Ig0*nc-8kfavXk=%>-zg+!@=gS{`K z=g|>QMXdi&NiZMJ!%(ThGltRbAuT7%RSA0iHdvQBV}OOAWO2PhNqG5W>_HoSo;RcJ zQ&&1?Ln0p9G3T)WZ%M^t75Re*h3kEKa5J4@!2n_g|A3dHnzgMXOsu2-_HVfwzhZ7Z zZ}EE{JazSJ9;MKc3#c~k!4LqK!`qhTbXl%P_%(m;g?22SME?2(=Tw-#&m>owI{s#` zX*JGdzfLiw?bEsf4C(XAo{)kJWj=zy=71DK7CpZa2||ZrcYx&hK!VDB(vdm9rhDAJ z#GTpnIbs>cZ*O2#ipqd9+*>KQ+~?Bvn?;98OTFV&$*EuyrZ{ECl8E-uQy=z-{dhTOc&VkeBP{4ao1Fi~iOGoGsZ95AA+F4FJ*W@|&A&K~S zhX)VyK&C-o=To`3T%_fECvN*Cxf0UDKp4%H@@Q$8+&w|H)+WeUw>Jjw`J#4Tb#H=! z3O8iI#NV%fyZ80Je@mspxu+*`Kj0Fm`rz-0*wDI!V(ag`gP`uk`{bAVmHmNVjpIq_ zWK2h(9o}R0y~@{N1YvDTc(G`*+DqxPp)QCjKeP3E5kJd|?uxwPvTCq>{{VZl>_S4%7cul1-}a7L$*w~jky%*`WN?cUw?XpVTh zWglZ}fn6^oUia}R-_%mqdtRqIdjHfi3NtzRbh7L4sE)ZRsYxcn$eeMpyL^d`=@!mP z_pMFq0uuy?lF-|n%1gC;LYK3>exb9H0LGC5(}NR=Fsb9q)lr}5N%x_>aG!f-_K^+P ztR`_uUL!L+6(P|*Kj!LMm!PFc28$5@po+@(f)E``Z9su)Pmghy?;ypBP$ed<;jB_m zaqGRZ{obAsPe{r24e_WYu-&UkU5+h;8Pu(B_MO0yhjG6jyRFl5&o!UkKp7sXf$Us# zIH2;?7IMk&Tf)lYz^;(e`)cq{)7i7xkcxGht@%(&2kmfqUw!!hoVf-hh1)B?93LLa z77v#1c*<8u=i-)HwFZ0O=wHyPe}$;Ov%!piKhceFZ>bk_?euxS(uUtMSV%j<`?c>U zIO4Z28q~e3_q&A@#lA#cBK)tw%-d}}MC(R)&vh485{co!)C@FK@E)RG0(?Zd);kVr zV|DLGJi>4D{7vu9#sEI-Ld({8*wQ5|^y{ROMA=Forie{a*;PqI?s-UF#AR$z+KyuB zGISHp7o4!wuRn(0EXdUl3^Z*aae_O7=2&rhv_K?4BLxaecZPP_AS{W5EGnhKo*@_N zys*ZJN3Nd|zz^BVm`Yr51vlE0o@`?0k|rIO`CvSJG{=fT76F?w0O@)%pYy0oMfHm8 zlhGWt*t|^xpWY#K&sFL1oiUpE)9(T9+pf{gsKjL0A7P8j&f=;R`cO$)Ce0rVbUfJo zC%geV^E*lry~fL!YivHC;=jT|irHQb{b6s*DvwooLII-BELMg~6tzzspSV26!#ZYp zX#I$HF!q_Wo9*a6L$HGns-7-b;eRO^4y2llwikR9d#RnJ#?tzv-0%yeGJ2zh> z76JG;-Wdu>o3cvz;Y9)(uEfZ#^iU1H2J@l;oEMwtPnpT#l+i%-hUBxs?hOa^-fa6* zE5lLZZw_11z-@P*g_?Gf;1`unzPeE zE`T03A$W_r!f|}ueC3au8OCxHyl(I4VU=IeMt$s1v9telUYy{J9c>=>wL#|uut6Q@ znzfb*yYzxLVUoC4aTgdh^2HI53K(3ZqZp-m*BoN2?*}|r!;133+c-G*= z;W)kc)G`H=?!2E!ZfE1jK)!>3F=O7P*Z3RIrrI$9^)g5jC4WvmhA84-y+slM6uo(H z@5|@6<`ntYFRIH^54!W7H$uc&7>|D{7F*1W`S_l*8Ko77pNsV265<;c2V@;8E;2BN z+vIpgL?*A%Uf22EZSO(dbn3Z!sAKJsTrRLSMs)iG`NLa-g-$)3r zV7MiR{*Dtuo*(E6jNmP#_A$THm}FA}E}di|;st!(du+~lVYS&jAWkZ?y@EFKN%NE%yT?N1>Ts)oijq5Hqz1bO-CAa9U+09(A>J z+3o%U+JH_uC3jE5`*6D)$tMnGP6lsW9=TD-rRg#hUb;QW&TR)Yd9`2)UEbS{k$wq} zKJ%cJJ9Y9V{s(jI$6o=c2&LJfBp$wca1^7zkc)SK(ZwSW?`&}}U3kGWYXw zCh-l32VJ&Iv(}d9wF!FL8VT@0fbX(liB_yRl;|#SLzM;ZIere3ITvTU-K1pf&(XdE zL^EPwIgD)6DK1^4Xqap=Kv8;-`;V(|j+%KqkF4~*iJtiyYqi+;6W532xuirRax!S1gh-UI?h7 zwjO1_!};5~-;^f~B7~fya=vMEYmVvj#G6`#hDPkH>-h4!etGWF)o@q6mvi9jMtZwe z)Pyo1#&0nT&%AL)IBVkybBzCS=Rao|P*gF!(1utIEwOmdg-3$`DIY8QaSiIZH1IOt z+e5Z|JEuRSao=Tt#OE8jh*tc1A94S`(^Kpby@Gi%$Ws5D$5Oq!^zFUFEo-PR4QMs?RlLu{B+CH%7|$Alc#afZ?QYW@e}f zcS?iLc7|*R0Fdo|k)Nuh1OMDZ04y-#7OG)-1-*LnPJ``*`{Z%XP>o1K2DZeHtF$n8 zx2WLaBwXQ6d?lT!@=r3VXrI!z-v|DdxUWM=Tl*%Zjd2D}$@xA(u-?&4nHd8HWf|x< zIlg!v2_h#Q#=T#@k!~E-a4aWUN}!L?ui0oS(6QHM)DGls`oT2dtw%=o+;{2gflSM% zsI->7_*)3c{x+qOgY|NTm@03R6mz%c{IB z9pv&%zaej4zZBS`fr({DUFs> z()f-0_=xQ>xb=0&tv4JJvU@x_Eoj}t7eG?NUb1q?*0Qi*Z}_h(y%C|_v4^p3I3#>U z6&ZDpnidl7!ybyn5^j*yT|LHte@*f#`VWTu1*1OrmdkwE^E@ zU*}5RC9`GXJAa5f(FH0gFH2rT7I6%=11|0g=xP2wKa^_rE$sli-Pd*Bk6zdi#qrRR z-!WCP8m`@VaerXmW4dg{;c`+VTE6VJm#s(ZrBb_9t{h~XNXw`JUgXD%&FBfX#(2{! zE4=)63`-`PF5~0KUPu9U5`T@2-TO`mi5if9x<5x~o#HAdnC)?&fh@0RdTM!9Try|urvtc}c9RqP&a!Dp zMRKifHF#KLh%yjO80pL}vA;aGQZkk2dajwqG-MxpIQs{K|Outrqtv1Q&(C zQ$$T73PQq{x})D{Ea{q>n95?%@nEU7!@`&3y#%51DPGtazlh4#m9WV{M<_d*Zxot9 zFv@0Pz24ylC0$BLb+~q}K8~aPyJ+Sb6B6X#mxP7n-o7oir?$SmgST}hb#GrZ-IxDz zP?~z4UI9pW`!iQjf|Gn`jMN0+f`5&O@LV^We(_;I3xL8FCAJJ@d?^W>#!uh_-plVV z)F@GL{PW$h1pkqJ);|eC47G~#gf+9m6oves-GK&Qf*OV-Y&%XWZNHA^gLiH9W(7ex zY#P50P44m8ht}n@2m9%pZ((Frm-J_bc*mI+ZjKZBk)uS`V+-IkK%U-b(ggAM15vDG zkFP5BDQpd!zxAoBG>&$K>KU!E_bO!|DXZx*3&I}jU$X9oDI^{+jD&d!y6{ay!u=!4ujRM+V4p%!IU1JF z8-P*2Wg!86w!$rIU7#a_b!6@#JX-ge%Cmv@88)R?KF{9@Ckky1V7Co%-#MWnD@V*x z&fdAmZ`TnfHuWiTCbM1CeK~eR7P6bo5Z^z-jpJ|JFFi8*nnzu62YYg^^Y4d$r#1HE z>CW_&`1hJjYP|)J#mIg4rs|<`+WpT(6#^%lOk#ZkKf$vF=C<%t2NF--@ejYGLXD?y zUq}Syj3v{1afI1KFmKo*PQLp-j92c{`|xD?+F*__La6snLUZjU;kzCrSXJNE4zDO3 z>JB2`wtBAu%SZ5EC^RZd%Ct^h<^9WjM3;77t~%DgK;AYW96(#RGlbuSByW;P5hygf z=&f&?uz3sa)4F11lR4@S`Xewi;I)KX`gm908nWWL z^E$=csIup$j^mLjV5q^zfecRjGoJ4kXHFsNA-E3lcnIcaKUnAKj|2yBJkeczOU%Ri z3UR!VxD}UIMvj#wF~VCQ5zs;8fVVC&+B*k;SJlZS8eP(7zNQ9@s z{*A$*_JGGAU;FW(GAprvw_11iAA`6W{h_pul}a1eP0Pk;hI0QEddf@a&CswrxHk+` zZq4rXz|d3G}tOsX6uYv~?k_CEM( z%a8IqwWM!ceTM^X>JvJ(Y{WNnTg@R6(*VTs!ESh${ni4ygvx<|a*EU-wBFS@|E#HR zj{NLtR~=TmW_DNqmc}C8UC`R<4g}NvE@(59GnD9_hq0$lA#p1e`fWk5i`sOR64WW; zUNP&&PNbK=Z~NNUG>lB~y${df%3Yoy1YutijfV*dwn*Xl=VNQ?eO)k8)F>P85C!(y zN$lK1%LWq4Xj>*msz)cNJOfiTp$xI0V3P)J#E5;A?c8wa75{b6}%!ZEqRzb_&8h3!(U#+s>AMMws@UKJA1LIff*(GAFG*nO6|FEr^< z8$zgZ`o2y%as3^svUzaHFDMF98-%xbAPM0|a{*twnMpwL=V=`ZC&+L#q>bXkDB8=DF;;NM6s&|YotYQK8()CcD+rQ{8L~?5 z2^}MWR43(*CE$$APtK$yCe;+W*6&f(-S!7I2@ra6LhbRYw(gI~H{VovwBvW!kcIJH zfTDPutD<#CsTOk@u(A1A-{(j5w18<6A=1{KuX*z1iUh-66qI_Hq6B-v+KZ4}BZb)1 zyHmV6F+);GpLho(`C_s@F3hy=M-U|bSSwg7c$F-i)C_qJf4$F}WvT-Y3}3@9zwDcu z9u&_6qwOHRp<-jC>VWRiKN$2;ma^|Jk7I+~zRbDrsXh~`6WPkXe1LnT9qefxyJ@uu zFVcsWeo^W9CfI_1&zIqbrG(@b^a;n)qBuLqK`lpe?a^=U?G(kKdVvFVTF>G(%+LV} z`tCBAHyY9zyA}4gw7ik%$--r!HAun{<3J~{jNRNL zoefqQUrOcuI0o4yaqI@{-*r>OAWu9N31yuGo(T&r-1j~h-P;?HHWWT67&VgBpYPkg zk8#$W{A4h#o00}#JNE6oE2{UX?6kDw$(NjqclmO?3lk2p{m=p{wbSEy6ExVjnB@** z#s*dY0^NoBfvd?U>3ewe`RRes?f0GM->3bhR!bi02uq@`L;-zE`ESCxAF57BUrXhN#WCvrM=*hLNT6>> z*#zW6-7QXx^QXB3p_UE8#|gh1<&X`atw_|tkcI%emO`c;pI@1v2=qzFeE-LXWaguU zu6hs;qj;?P5hy`l%D?-<+7MrniwBc~$;fhUkJI=WI3JFR{XX_YCu_Fox;%O!Qs(R9 zP&#^8UF*!U11Wq}%`Vw*(9cP>ycNgrL7ZY9g1!fBU z4_s7*yDw=CmUWVhYTC0$!&eyxJ)zQSf}y6vG-hVjCeSem-hI>AslUSiW4omKJERFK z*3Oh(LF%o^ZRW5qSJft8fnc`v*QHq1T@Fn62K!^6VnO_1mlx$Qhm7e}phI%9G7en# zBgozG;K5^AN#=IU5X%XY+A!lwC-Jo<}{c%6$I+rHoH%eNLbF z2dsYRr+J=U3?sK`K2y^Dv3zc}6MG-0IKQdSB6bj&?2zak;mPuN-42EKU>9u6GFqQ7Nc7Z8RYsonMh#B{I_YWn z7lj~zT6H!kLQw6D|UE%Kz$-kK;A) ztV2)S^SIVZ4vjknpa>iT?msNgVfh#R34iu3Vpy3!d&qHRe;CSiR#lYgZ>%$-F!8Yp zkQMf_UH#$gDcASqN?i--d5B)oae7hxQ144CmK;io4h5+$ZJ`Dt`Sg3d+^bb@A}M=i zD1)nj9GqZTT{e#)En!jG(Jn;vx z`MoU8SqboNh9g89)cvt+I`g!XWpj?n)XsCK*Y^c$XmTUILo~f&ZKcmZA!*Q5?-MA0 z9?EQan&bXnq-V)ZzkHvsX6XC4V^aRdhl3@hCP~v+SXJB-O>D>T5ddoc4nx6r59jNt zKf=516iOubDJ(8=j3Im!-0>7#zfCUPp3c5n0qxws1mfq4Vesn}0)jD^fwJQ3f^%c0 zPqwhtFza0Yq&mKEVL^Lrgll2DeRemX5aN1+ADg^S_?p?nU_(u+M+!mU&++r?t#_H; z_9>CWVt8e1rZ1L*B1O>a#Wl>xrRDwv&T=n@E)5eqm)wS&n&zO94jgPQjC}}RA6*nU z$0qw?;122hDv#?+%NU=z87q2N&5Vx@nwyI_4_+urvVQ>%m&(Q>|K- zh!6_ZA4_B-G1LVDrooy601h*gtQ2jhxg1$G{5>}Ftz#cfI zV!b%Y@4<546qy9ORn$H^+3VtAH)+(;;!7Zl>B#3nKkvIxarqb2@ ztC~K)Omn9b2qo;i*UZ={h@op~?ZR|&k|(7W+>BP}zTf&di7)Mf9Iz-`tSVoCg)?T*FTd|9%Rv*k`H9U+HyW1 zz8v%Hz03WQWT%GPn$c#Q6Qq2ts)w-6{j<~O{n;AKoitd40OvQV{8 z`Cb1R<@x8NQqStj@Ibb>R(T*_z8L?0&arE(Tlgbtx*M}kbS7?|TshGNv*l->@>1q> zdxRiT6Tulfu@#Ed_KG{}uQOBaU-JPbzP6{?njD~it~J0O<|+3PD}yxY6ISZq%Y0!j zd{&-Pv6zhRb#^Zcya(>@Pt-5_Lh1Ebs%1Gk?X@fKsOQBq%P#vi=s=}>dkcAa&o=Uo zQhu?y%xCiVZ|V6in6n3&(&=MJ5@xSFn1sS-uQG5;BDCWR>-SeKKi<#%lJ)ZPa$){~ zUXHMI+NZCOqa^yVtb|YfIpe~2Wx@a7-H8n%zz2TiWIfHb$QY9ogg4|)FEdp(OBPq=3BS_E^ z^E2~Vy9mHUJ@%nQb#^|9uo}kS<9q-oz4rAwT!Ni?AX)@eeG21iZMW^%ruFv+9ZA6i zmt$P|vM#u*{fhvWj1N@#1FZ1-KInG@>#|)-HH5OhpPb5WDH>qn!3jBb!A@}e2-)49 z5kKRJ0{;hVC=FN$Ca&@IalFw3|MSj|2KfbZMcVxDTo!he=GaR_bX)s*!e11#Xv!tT zmCTSK2lsk{KgAVJ&VH^Dk*vgNyXz#>uGEhpMv9$oIu$Ia%iD)yvdFXbf&$dmg;2E{S61L3*U1 z>qW{V@k+J}fKm@&t4J{I9_Q&1KbnSm-M7f@*9>aXa^wR;Nz-ii38=F3LqC35RJTJW8#Z^Aez zh>U~Dk@_WrUD88+hUE|OXQ=fleIbH9B)NX>%R8gNyJPi>!upw6%^C}hjPMS#azyM= zYiz`ONpS2sP0v1D*!>YnSzFjv@m^5MxR3)) zb~c|kb$=&Ptj+sId+$<^l}u<+dN6Kfo=K_{vipl(7kx=#HCs-$2Tkoyg@&CUNrVAW zEHM&|Ydeu=7s?ex5Pz(jG(+<(F@bRLt%nq|{W7cjCENHi{=(MU z>vVFK5^|#?pWCs?1x}}Txh7EOD0qissTHFudrbD{sZ#s!dO|{)J9SIZKry(&*b#@p zJ1I;CZzkl(skJp~=}#%FOpZzc)uU5(KlTUX=)hmzEaHbz8?sm}IG231zD2;nKLuKD z;L4mo7n7Br+;q|j`g%5@l~SWHhy(HSm4YYV2}XUdAfxpCe1CTeoOrwcg1{yX`w^3V zZNI?%0H)!KFL6-7VMFN;;ILv8b9KjM?Ni?oX<>x$_fnL>w=7Dk(r^2fj= zA1G-BcGtoIg?+zr`#bjaR_HqmK&Atv71E=0o`JMaa`;&3?O>0``97xb$oPp0&>`i; zY{l;7GtiKQDEE)efk1r&U+kU}B?LyC7874x@<7qI`d7lgo?e$)`%)}ZB+v-s}EJ~H7Z&y#OryA3tFMkoEm>!;5XS;fc7{XK(xX1NJr zR{}~p%v1PS%sE-?5y}IuctOw7Eh3NS9ri}qoWk?_ixz`9FV|lDHqZgo4!r| zN78jIDyl5eUy>lgqo^P#S>hX#1j!)j>u0g&-Z?XSn?UHUuC7{v%&#DP?xde2_8PGV zUwS>Ce(5c_dPsly=ZSkNzwB~7&w0CNoI0%1Y44`Jn|^j7t|av;Qzjk@N>Ms^pB?Y2>%9eci2bgW`83Q z2{cO4A${wk#x*18V}2y9+}~KxboN^J8IC`D2@Bn5If5u9B))CN56?6@pO=Ka_sBY) zHTDFFyGb*F&CxAZbV43p5%eYSNd%<(bq72g(SN#{xqd%4e4N}jr*|KLlSTIZkc^W? zYmIy#xBQ&RP0txMVYUq4pXT9WyMeDBe%&eAFZDx8DAXe!5e#uf|tzSeipxdZPcD2!)mxLqG5@ z&B=-eBW(-z$c-jtvF?Y2sMs&~`nvel`>cR@{I${`Pupu}U1Hw!=Y1~o7hdaheTpaV~V2wTJkZl6T|V z5l1Rrwky5QS{xK@yneL;o`jqiQf}Ns!6#9|z1vG!OEbxk0P&6vWn0V9IHl*8RaG>6CIcQFnO z5GKd8%a{$ds_kGy;sZ)E<8WV(WRV@6)MxInBCUqkEruq>G9Uxt52x;;KAI~c#drUe zbL#7-x4iJR4`RvL6It_o`=mAZ1EV%vtL@f>YDC?Q;qi9SWIxtV?5qUHV|C^2`6RW= z8xCy@;C5*GC<7*V|{>JeH79A}{&!^B0>iJ$dU|9&QV!Bk#V9+vjZ5?A?|{ z!`>4e(CC0BO6hVd%W-1t45Nc z&6oT4CvBu?)S@OZALA^WCla!mH+UyiOp8wp_S=4}-S$Y^j^nG|M=>r4d(tUv-psL$ z#b9XnYeIA*vFG0naj57jG;^(pzhCwke$33V+#^jb?PtCO@D(CtNQ%HwCKIO*>y-@| zxwyC=qFJ}2&8>NCRg5~@J^e??KO24ZC`ZMr_W%a_7P1G924{6n;}M&Ko6cV7uN;rX z5mp2bW2GV2BrUw7h|grXqgy9QZ!@L=$`EcK^y2Lu%FwnCU;2U=rm>?y#0X*_047r|r1Da@s4fV$^I)|F!Y8x- zt4HYR)g8~gpSrfO^rDPjLvXnM>~CSWB~(oqVU>+=_Lcw`^W}G5rRyt>%WV7geM~kX zBBlV9&d=p{Ii_VIVtVsWR4KS6ZGvlD8?H!LMm@EDkQGm{ALQtH7Kn|(>)g|MlGYzh zqVZ*l?U`^<=WzOHCh7hzrC=S8lm1dZH*n%V*_(Q_r!5=0)VsUNW9%Hcv|dOw*ZV$s zaUNBnRKu?gq&0Bw-uFy9E7aw>xyFJlej^EZ!RA1}P%AI4%z%j?1l&4`40HLC{dKiF z1mX5ocy|NVgCMmMjTF9c6-}J$tAqCuv7Atgt^`Vd4;iyhyP#8PvQWp>B=B3}e1zLe zG7m1oJ};L5K8O!tA8+YK`L9P3eHNbFi=fZ^b#?arnt$)ikhZQq8PeY`xdsw@@5JeQ zB6A#N1?7iSbx-Rd&~v)Z%wzf*x;}rg1rP#c#{6|AIPr7HX#BilgI z#ht&&c&8bbvj9pcKLH%p0U5s)KjzX24a`8S;Hz*2 zzuksk6z_{_az7t+(@%{UwjKlngi^L(Qc3`S4esU zUI1jG5?B|;ewz2w?vx%MVceZu$&l>Z3)mpvaD=Pm^DBAx{RTH?T!S*6`!YlF2LToxo_Z{t^gKI(D>^HNb7`ae)L_FSRObSEOrwWAiGwXu=qv+?GVU_Fz$ z)d(>_#K-k`)7}ez)n13C_SuBGp~yh==6HiRBE6ykeJtJu>uh%nFyW(o8yW3b0=^eP zEnO-2y8dprk1;AhA9@aB}`6E*b9wKTIQyp+ET0*5&oOvpC%LqVoLwzQcje zK8!tMUiKS(^$60wcK55`PUPx73nQK9XiqyJnwEeNcvWpb22_%)ER;}$Lklp>wEDFS z9j*PMT7=e7wM4)m25M>3?Wf%gm|^a7RVATLc1S(GbtfCHwPT0%Q&@iw3$VOBVLz=c z^8lFQ^@Dlx_35mytI$7I_?0GZO+HuPIe3wp7BrP@ixnnv(;pf1`? z?OQ9oc)Z>Jq#d+@(%C)779`*e_;()8)>oVgTRvbvA4JmC-y;m`Ui?BduaNNlbQ+~d z@7q#NFUR>VZghKJY?OhY$E{pO;r!2WPQ9tlas_&1tgF0LX#f9kL%4RmNHxK=(eW@C%6F zYf^l`A!4L=#QVU-Dw+8=LzWz9S+)376eolSF^c4mb}x=s`^&w0iwgZy1Iaf(UPmsl zr-rJ5;g9*@d}fXojoew-qTOr_^@IDe$gbKf`;JY$E>IV!TkT89JaU-NOM26%-oO?MBgW*Gao&LF{95kM$D60p4CxYf$Dz8s*rYpkXNj2-PP0Pbpg~+ZpqpQ&Qr{im+xxp ztppj@&1^Py>fphD-r+rxA@BAox9UM`)@V!DBWDzs_~tU-_1K>65n99Eqc5WFumv!9aq;6srpnnte~~*)yF7g{-1p4l^pG zrf^PsY@e38hxb)ss~yw<>5KjETn^oxPz~JKC9`k)pow91Sf+rr^QkKswufPF(Z^>I#6f#HkSJd{;U~oWix}5p0(d5amDtX z?`mt^LwCtYBfD()8Dv3Ptw7Q8|gZP9g^Imn_3eL2EkfJu8l z$r8icx!7Qcr`EpGnbnHU2tM5kj;wP$>P@Of_d8G^ioOS_?{R$bFjncJ^5Jj_1Ht74 z_+-a!8h>P>3Gb|kfKTz#s{%gXa(PnT(?nC`I3lYPE?pgs@#n`sW{ROY5+DXyWn9+y zYN8J&)=`C6Kvb3|xrq4%=o$A$dBy_>elaww;gk1q ziOq@YB91|7c}XRwBYN~gkFegFktXjiYROOkt++-N*1Ea1(UZ9_tBR6~X@`T7jKv|i zp343R=a$imzhGiI^lF{!+ApkZjiIuCa7O3)uFZ#xraK(1d0E->CHaulk9lqn{gJC zd*$h*@tk6oD)M*9cm9Fi$CPTvc@I3|`J8W&c8>dqRGruJ@Q7QTse_0?bIf4<)$Q%6 zLC3Ko^N+}c&piw3d2^ii#h$W=4a(~&%t%DRJNUU$fSO$PV}~b^e5S3fMB={h`z`IR za447`%~m(>Se)0Ye5#QTan#wG-c6qXnkIvKi5DdUCB0fs0EmR=5c=^DeW)R&vwIoMZinVItUlVSN-#SbllQ;A5&HM<>xk~qn-9?< z4Qi#-g(bfnvR7cRV(s&~m(CtxlW=Veza}z~K zl2cao(hlQ|8{4Smt?%zvTb|l3riW~*3|ZM61%Htg2H(V=7lD$X98nj ziJB=;{Vwy+7o>sTb#X$Zno|C{h;1dVi>l zOPD%->LuYVYvvo!J(@!9oEP?I|)FdHe3#rJZd!x-K{gxvd&v4KgP>=r9ScK_bJrC z1;a+8*vLPF>!oa?3_t?v{h}gH^VYa)G4M%b>!OcprpZoa4H&IWJvzm&L5x?3!oB6i z!6QR1jU}a>Y)*jD zypdhf)1;<-I>uQXKX7^PZHh5i07hn`WhSVi->-tfFI;NdCv6j)&^Z{wdqc z8=9;uDXq6IFW=D7eZjw6GkZ4c<*5cY_7i-^*HER<1EXH{c}H>cr*?$WqNA~{_lDHA ziF8mP3ELpe&vFZA^#&y%E1(qr3Pnd)_3-Qs%2!o9!;Ygpt?L89OW<9i&{%K4f}(}7h{e`xs^3d$G^h7$vhO5wL26D%da%4VFj?} z7g)&w99tlw%z}7?crto@)jP4?SK~v}0(`#plht=9X~1IXX;jR9t#D$OFTB`4TR8(O zxU`_eGTM?nKEim$`&jkLfAB#97UMOh#krKi|F1CbDpizXHt@~Bw z+Z8H7IQgT#$a5QA7xM6Pcg=H1&Fzo#0J_QfR6hfc_X6T3F)Z`|W)5GNPqPe2wSYEM zNU9Sl%|l#zA3z@G*st@+Jn^k#eRU|xAm=LC7;1=$0Z;=zb|2GAKjeqkj z>ItiFe>I~*K?`52=n_z^=)dxwh+9^pxd*U=GKqlTsc9=mrElzCUVQ5g(z zUZP=V+FoFB1??F~_f~yW$H`t79U38*&mXZrP0?W=4R1wRD%o+5JsI(%LriE;ogW7m z5(Qe~b@7GD7YfCtne^;%o9pKD%&JH74KhQq=^vL#9rTIlp{(bKIium6urM~-Af%n# zU>1q;N5N0S?RzwhYezYbcib;2l*T#FUIMhp>S}=a(eusQ1~z}2{9;PWOV^=>K6He@ zE~wY{tyGoq^SjD^ex{n|sf2m&tR~oq=O*DnKqWGCk zL8waoPA?^+DC;wNzlREliVE3UrxdGTD9okZ2>(-2ZRTX|#-2!)_0E{9;tN#{agoX! z46650^U3*bc5_i!4ou~Us30SzO!0tI!Jp4AJOnLF{8%ElJt{GiW)G%_Xu5X4MZ8xK z9sGCwqRY?k=g(F-M8m`6P&mg*cwEREpzv4nHDMhTgzowvCF!~w4g}8Oy!?nd!r9OM46h(MEiQmjT&-LSUq1dYorkzC&>L=>D)JKPJ@Lca%h-zvkISg03KVY#? z-%T7O`HS(Zh+*08)t)OA)H-z$PO7I-`EEx66olRmnq70E@Dtfl3#=z2-g5Sm;RB7y zC4b)F$65?fft~MG?!N-v&-OjM!^bg#*zs+GT-$wXjLsrjxWO+#@s$(&$jUhi4yySu zl2^Yy>xqPk&}koj-{1FsLe>14LV|~EO(AN=oZ4kbHJ)_NpQoBnG}pr3d0AEXYuveO zZFOH5M33Z=3} zEZm+~C4lI{oJo1^2jilL=T0~dYce0JjZmJyp*%YepvZjbL?3pl}PLv0Au;LCTyrCr@7 zatny^(JC$FN&2`I>nR%PJxDBOx!)W3D<>;N#IpCEaX!YuCY&JG@w2Fk$L~`c4ZbWK z;ab|<>GqD`4|z&1o;0M?)e6_cj?w7wjpD=GmxH!Vup!Zm`l{%6KmyV>oc!-+kh7ls zekwS!4-0!c>9#)=jN?a`tXU@rc>!^RT&gf%rhLecag=j$78DR7kH80>i;7^S*rZ@)3_ul9U%c1f7A=2Z3~ zGY{&x=L(5)9^qZqnCj0B`4-Xzbtd+&c94*P$r=Joy3=g|lk*^3GuaNi$+^!XP>+-my2d}uF?djWc&0rX9 zSXe~_=M8zU9|>Gi+bw?*FV|Dk6o0OwvZ>bXHS?BZ2tV+Joty48w2rt!vdBALm!;B( zNs`hYqQcsla`_AD1AS=?CG*GAkXA*I!b9G*^GOkfsW0Z@;ys$4hcEfM>t>#IWWfnq(A24FM7o<&jeEWu`*f z<&|t5t#ze?J^`NmteW-k`T!tLZFb?zb0@)6wyFYUCsDksLU1oKV!WHd7Fne^!%=4Z zo{fi6sT<@XOfPr~{|9UL@f9XZsem|ly5Veh7d)7n)Q?J$o zxM>`p9-6F;hYBpHIsXbHL}6Aju2IJ)K6_rff0@HvP=otXz$C;YG3py2opd(ZPIhH? z$An;M;nnSHt^K8o8?a}_)q#S>r>LHV4ZZmQDQ^K&BVu?ic-0i^%DbD3tJ*dAS}$AYrBB21n&ecuCncr}+q{KJpyRk$I^Iyf$;c=&Wv=vPl3c_w!zfz{6AJ z^OD)Z1S8AaD6vlY5l>Vc(<=|*xSX6nXh|&pt%x1@v7pI_x54!92NzqL4fMgrw>(U& zJ2@{>o!w*~0YE*TZgo*T4sHBrvG{0)@tR6drhK1a`eM0otHS4??4p>eI#@7G)2yYR z&YTmE($^j23GgK4ApQ8C4OIxxt6!k!81I^p!+nCfGkWpcenVe*aAv@!C72NYR&v^` zq4Iku&KPka2GarHh9cmDkT7E5oQ)}rT3pbAtK3-3NjP=tH&Eco;PG1yc z#%0lyK;eap3&&w!Dw3i5TJqzo65smg^?Ls4pA$ple)DV=d8&)-c?F0$O>s`y{X7bT z4%Va{z`wQM2Ue|r;cT^MGR0XO&g;&N6XGOp`Fnk$$Qf2cJ3dgz>vj*bE1})x+en+0 zOyk$;c>ge<>0Ytq6i?cmikr#1w$x_1csX`wMqga1hK4Ofc+*cl-E?oIYhHclfolKc zJ&r%l#3NNlhjTpI6X~U^@ckbj>q~6ad=V^d<&z}80t+e~K*c$bfTaZj&p$#kZl<46 z^Q>n;0bRM7Ci;xZqy#9q;hWJ-QZdY^5AA`qhxCyUBn%{uP zx^PbvubcG(s>(cb4yD)PdInAC1Q+SjOZGDygnd%*ar}7Hxc>He=pmu=WcP(0Gqk@x ziqyLw7eA60;+EJB^Ik)_Iky!-_0T!Hl z^{t*M447SnWSeT5gG*<_X-_b@E7qg2iK9qm>PGsVKAkxDMIaM6z~k=T z&af~V-*BLDfw=ztlI(&#j!fQ_vdLI2l)X=*XY})IEaV2Z8@M7y*axd!Uw+K(`RKW$ zceWPG2SdhV|McjFf4_gE}xpra3xny*5Bq5QX_;KeElfyFm+6eb5pbkx%Wp{2^lS zC^vTdAegtvP?@K~eok)z?o1`_DsSFixx|_ydpsU_;(e!>vo;OcT7J_E%0#fkG@rwB z%zcuZgx6V*H8~Mq-TS;Cg7PU1vhyQ337KSHl8dM{<;pu0o^e|CFH+vt;4c5}vq79H z)SxYQpNZ$AOv{x`=xcSWrEtEqT`dj*M+YwO&Z_eq;La|VHv<~k+&Lnj@7W+@2ukiz z`}s1l{S7@d9_1l?zK>z@OZ(hzU<5u*R_{|MTCe;A6jG?SJ81J&cf^`L|87SMl!o!s z9nHsR+)l~{2ac5cQh;x*-#p<_ zGXlPR);-yJq3-=xFUZD&Ag#q7Q00^Dl?6?F%8i8YPrJe=SkK1O_J|?y#Hvz%pdA%g zfCp;re0e*z)5=cyzAO^SlJr~b^v1jsju80O+28;#`rcmN5jl0~R(t3XCqRNPLn;yg z-b67AQF8=9bzkQp&Q2bT(|P_?ul#ix)3|ISs2Nh*>!5AqI}Z6uF!93w6jSNQB_d=i zXcAHiCY`u_FszLbA} z<`yah#l0fnjudt-{T8kvwPn+XzO`hpNWsW1(m{UQb$W^cv!q`aEsZL2Q@*qLo~lGI zVKZW7RUNsH_Z}^|DCnOAoiyDQ`vyKdG`d6HPa{;Kf(@P__9;XX?JE~dpsTy=F)5<8 zfw`5+ppLD}9@NJxUeE`3&q6T3M!nPD9$vK)r*|vDMq0nl{-$Wx-D7JFW&<0d>#c?u z9xmnNWtUsVTR^oHWiL|^;U8Jd(mqVviV*m*GNiZKJ;K-^ zdhTY{U?VWus#LEF3`KQjoH*gjC2&*1@n4>Enq`O|bnZ$V$l{?Q!Z#YCPe-XuzpxB* z4wv%#>gU5(*;o3zGs0F(abY6bex7YdvbE;*RHKH%cRSmH8?nW&jf!;mtWMDh*Zob| za9DLeIv)fCLuc-fvo$y``B@`b7EYsX5A^o)&lDmWmVbmC{<$rr@|H~})tmq)pM>KpT$FPeaWBk=w7o->XD_hA?o`94UIIz-!^>0Lom z8XO+z=Uv)D7`GlllFYfYdX{X}Z(-y-yQxSGn}6z1u;@i$ziqN?1S=$QSwE}$%TSZ) zRS+Zc0248w*kA6YS<-UV%IY4y+`FKd1Q&fX)$W@T+xcIn9KFK z31^C^Za@MinLyq;$2nacn!oJ#PH_&bW<-9ML%&-nAoKaYOFa4Qk=LG*mqjZN z^Ub{wkbU_+Jjna?e*WWATx!zX7bIqMW#FsvLAMtHJK~Ba zr3@Y^KHprYWG(D^qM;R+b+v?)Gy*KEK1Rr+vI@J>*43YheL9iGrNy*Vcx3X18V9+{6XXQ3YF zOy_t8vFAYenozJMmrvmqSMgJ@`obt3_G=-Lt5;ijv57u>H!hvL(w~3?8K&t)hE=~PQ8oQf=fTU0o-Y3SVQ3i%Almh zwiR-Z3~;OwJV|^sx;#HRFo@$lD-(lD^Eu}Vy?dbxx+=fXHpWkQYQ5?-+*W-3V~FP% zZlKr5T8Z1D#ip~w^yC+@8le5rn!ZKCU*tIX-A9A|9mx6?bQ@vi%50{3O3ejDDDO4x zMpiszo9`r>lP{_F|Kg&zXH=DOnt9_)Z592zUJj3s^t$Z(h!53%;dcn!`|SX|BKIhK zE6tirhy+jKp0nL15}<|)Y|@AtGPUsXO>PgJAgAq>3DCj%g5-GSv*O_+Vtxoa22TqQ z=8?#zkXsU+sgC{Ev&XTh#<}Li_o65JCM039_UFz*$BZWWmq@XX@S18nzZ1#lpH7D9 ze@Sv^SS7myv?aqLJtVUv`pR3ikD`7>`PmrS*__^2fyNaToHjONc*~BPo4dYceANgg zexb~o_5lXwE^x{#B5C|zyM;)hYT=tKUVFzd|}WnF%!#;}uUk^}qCJsz~dm1PEA{HhbQ=Njs?c`qtVAZ(RUd$IJ2)g`u$ci^*;%v_af zR&KB%N`I>LUl0XNviJ35U@`whk&UP5heWT&-QOVCjM~3Ed&TGLPTa+J_TKQbPOE{UeyqygG#d+lKwWOh>Mxiy6 z1gy$Ed;mtm<6bmaM;U&z*Mjf|=$E34o^KV3h|HJap_n4=I{>Pv=ahcE0*NrjfUXxS zrjc8@VKKKfbPwnq+)C);lF6TagMHXeGOUD&o9&>F)@%Lsh)E;F zHP(FLGg*5Uo>=NFh;wSawWalL=(Kzc?)6bk<;H&W=sIxP+b&1uHFD=$%!f1$cA>KV z?vn*~Xhp?G7*%7!iTq<>D+NpG$G$?tH0{IjZgAtYzrsbtx@GS8dM>Va?khZLP++HV zP!AlbdXG{nA)2A&j2ti%^rxFn-{aAs%MolIbIvC~Ey6g2ZY#7cyb+3gsSs}do{4D4 z>?9us?@nz*BwTr-Y@*a}4hnaW-sJGjKx+mf%?D%OlpN$LDaq4KP7dfbLRkZkNy?=- zFVF=5kAQ?5dVK7kQL%uCRboCy(^OIXFOt5|8GBw;yJ7qBY?mp6=>7csav6UXHvOsO zHfO;JU4B&7WtKNlcjq6@53z-3n%)k*uhU5l&pZwX_k;)W2Rb%5K9E#pv@bI{F!#dw zN8MkowMS?F1Xl^I2QLq5{`mbMWq##ldgA^dzwW3CdJGMC*z2qNl$58?{`*5P;7OM< z1d1~@O^-y0W7-+TVi!LX~?_oJ1@ zYg@~BTqfG-4u!W9xZ{hgzd=CP)i6~&PQfOgYO+}RmFEv+3h?5Z91iiRM)^l<^w(3O zQ33C(56pq|mzLe-N4OUik$v}havIaYtS^H313~SRk7q&nhT!EBXY=@8W_rK7HLXO6 zqeXt$xIS2I@t^RrrM=A!QN_wY!g!GI8|dK3al@)1pIFtz+K+~Ut?YyS?r={&rtSr! z5YGA1I(a!jK3k3+nmE}3aB9=#iXtfg5)SA z;C3%mtoo_ScgV(A%+@I1qlC3+Fso^vxYP`v7ZP;Qx zL-gPn8qZ#PEWlZ9q;P2>ue#u`qCoMMtDlxaBbg1t~ zP$-Ej{bwxXQWo^Nqz8jj50vQY96K-Lczi)8{}`-yFs$v55=DqA8|P?O9?zDPGJt|`SkqGEtuqwV3yKEttSa_8Dx#;5WWHC}y`Q@gUg{)orn20@Y#q7BvIbvn(|iVG7b1m3gCy%M?* z&IQQjwH)I2eG7uOlNKi}Nr@CwX-|Q$BC!z|J}Re9U?^2-Q7!x#E)o=_Ec@C&60f?1 zr5%QfP#mpzmYCceo8*8yl_hWOaeBILqAH~=;w+ipn??Ut^p;!G6q9SgG)i@;nZD6XF-sQbIh%*%ZD( zv&VyK=Un(11%lgoGTNNTcAO^9Vy6KNTs;1q%7=xQ-a8K(?v5M;T)yr?zHY5F4W^?W zbm%fdfuDY46xm<0<_H&q{)qyfu`u;0y$(=_4@>0%{#|%I@#B)~)FpyV_&wy{6tz`>2}B;bocs-;)n;ieQv zq2OjcU_Zgzyu|@`dq(bQ?u&=_3tH%yhbOpeNSpDcj`1Q5({(LwbDp{7(M=95EDjc* z_<$Lw>WYu6`HWg0OjY}a_I{1(jsn~JJu*s+x!qeJS64r-fud@@qZug!qyFY@TL|*# zH7CtW<2RNq29#iw23=`aKjOy%*$Wrp;lseNEVwdnu@U3Vod{2I9FSAp);48vPsF>Oa2~ zus%OGdtX-H&Dl^%`YEG;pJ2I#W_Mz`&l2%O2>6)z8S6TGug`8a|P>eE#qFcRZ<~I09x7QDL1*x}G!b`!C!x`)qcahm%!~ z9RBW4qxTQ6>w8!BLxDh3?h>p1lBd)xOdE<*+7a(i$BZ#dim>Iyd>OS#8!yja%jxxAVPM{xhX^Fd*Y5$cO1~^ZHv#iz$>Oy*89Yp#pOsWX&zG- zU8S_>>gl!y^T7GM=T<*Pc^J_&^g$HzgjJsd4_KG1Z?Ow)-n?R4fdbjf*07-rp9M-d zg%=TYgzws;40~7Q(1@F>20&dOx$^{Plkm#y!64$B=hBh|!wa_72%UcxpGwP~i^Ku9U!(~x7>M4l60`F<# z-dJH(#uWw4;Ff~OkfV+ssKEgta~b3T%P+)e1}4!_^6jaZZK(ya+CNyr+G4>QE2k&D zKf@$gA#1f#0BJBC5K41)Mmc1V^nv#-oz=h-?+0txIKr&IK1AvRgF4^QfilyDd7Kw|Vx)P9YWBy>?PFi36OUAW25ci3c+~j4Sz2@e z$Ew4GScOmi5C!Bs`>B}vM6_X3_=26le#BP%!W5d-1S_$(Ffp}#Y<#`FNG^DTBpi)L zGiSs-xpv_F-OPP2pbHb1y?*=KrF}<;7K9?a=RU4K_Z#Ts+A*LAraTPKX8*oK`?oXX zFHq~tN2=zYJps+yr;fDK-&u=%arLe%$2X4h2}M#|Gl?@{mGn!A!+QI|zv8SneI}*D z9{weJV@DKV2A<_ma^|16hT-|Qi6uSko+fJPcyI&k;9$%w>x%Cqq^ZMwA>OT7gcl1w zSWZQGa<~@P=O>2C>9i|@?&%+jYYlT*x zs{SSdzx-g5Hn!d3dy04c9-*T=S`jfQ1nMn$?KykZ5FZ)rpv=K7*(3qb8}J7D%GKZs=p-_@jE^4E_1WF3|(+(@Kxi2h1Bi z^3x?pYyDEgZISZH>t2UsWWY|aP3VtpRN9Gw&b8jzw_wu{V1J-xY^1Eswaq~MkW+^r2Rpl9ATFP3#X zWrlm!?#BykyU?uucDy6L=-c7$XJ0+q)|S6@PF_VM1z8eOhSb(u z9wM;oycA6S^>HcuZjQgVPnDddzzg_2CKbi&>|!45Q~C>I04YYN62}%lguWS_9rnWg zoL!Py&g+BtMp1A*)Moo5B{alte9WBE=bAHNTevp()sVgIkzx)`6_c&Pg9&=$zWFH83 z3Y$~$@!bdc&{swOj$l3UDIDk8vgHT0g!_1)$;aMx;pOVxnV4$4+$wYa5WLm)_Tbkl zPjxuGYf<4(eQutj&-;Y+RyY}M6S^I-=Ofad+#1r0@UG{fK4{$15X$h`JMaP#aGhU7 z&Z1+_vRzsMb6*{gQa*)EyyE}a6^rlUjpOnDXAK1Q+4$D|ZUd<-dHiCL z?xbtOiE$x=={b591dMeQTV|PvL_Z!j5RX+OJXdI%uQ4K>ke~E-L=yFF;Y%wDD2N|?!0oIh#-FZ%!oBX~wZaMp0e)iR&y!r$E75N?PUy@+@mBPRE z1@dG!SPWj0WNJw;9t&Qff+=!4I9M9@R;PjiV5F0mmHJhsqWw}b`pjOvll92_KG{Hc zvEB&-(H80B7W|E%uEGd)A~HmmP^H+>o0A*u*}|2Q_IzpPbm=`pCfmrSD>$Op0~CK- zyFLo`1;{e>!9kR9Ym@pkNN=zgtDt0H2Lbo5VsY1l(#|@w1I!?*zF?W+>0_>vdi7Qg z%>)8kPEk2n{5_*YX*)11(vn-n{v+wkwiH!@DEdo)jE~G9A|NQ>8>0v!h)nYJeW<>x z*X?Rc5i!Y(h&-{6C%h^_{z>%J;DB`yo~~(N3y}ZB^8I_sLh~ihR@icl+w}<8l*vOwg%)ir2S!nE?pq z8NcjJfXU3E89;`ZpgcKVk0Fk!LA0j*yvqtZ>5ogL^d>gnRhA>B5lKy+;0FQW2LW`xe^P4%=;Rdy!VhB^25(~ z?FVgBZnv-EP^)Z8TbBEkrC;X5M7x`G?!PcB!*Am*sH>-bk`wu}3i7@lkCxiQe~yk6 zLEkHKcxW*_LUvBDYqV`$Brb3jwU*~WWzh1js9)Qr_Sz1;HeA6$aRAjsiGPQWt^}Ni zu@tQbh_Ei>mu?5yU0(VivGelw?k``zWM9hifjiO#bXWo&V(D7;hQ>B#fl%?$-!7-f z&)CP5NAMEff+MUaHJDLc_55B_HyI6<;$47aBU*&^PZZtN7v=o8Q$?Ma?~UhP_Xvt> zNZGtv3vYq^r&1v@G;?0hyw|_D9EHy%6_?!^Od3dJQ(RX+eAwb?w%e`dfo%-BBy?Aa zR9Pk=p^qq%xLzFEU`NSk0g>}{e7zdb5;vK4F{U*r8HGKG9oaPU^dKp@{G)>-Z{-;c z_mqMUVt~)SsQOwDWKH&;ds8B##_|dkgPvlnU4qI_G*#7>D!Q4 zd1s~lU?}_T4U^sjheqSgDrz1a-@D-yy;8h4mZGmjK$#3jFo#W1$Rm62knp|o>JAg0 z68XU2L~iThS)R`)zSweEE_=z%=NhosEJ1N>|6J|cOr4K?Sh~dpkZ@mm*lE^R+*j{T zB8z><)DweF_2{Ixc?d<&75l%`N~=Yux87lgTLVM!wYPW%(m#=rhVR>X#yhV*kt zbQ^*of98^_Dzgy-1(9y;>uIa#`)$_~u^FpI&eQhALE|`k{Z*_EUp$|it0g(8p)k!o zNN#B%^|hWJ9nSfw2XhizbwgB)>Ub?U+Jm*Z0Q>T?(Tmg z5$Z*M8NEkbu3>oICl=T1EQpJ5vQ4%M&HJB3+(SILAq3O4LklNwOha(IFnzzJXR{Qz z`mzmw(U)>U4O{yK7f$8*V6VVIG{EAk*XHy*eD7JgXCBrD4uCkd1$#HhmOQNj`emFu zYaf-KV0plMMW0P4@&cn?XyCuh-4ZS>-Jehc*bh|(kRv^r^}d)l1#y!^>aJ1x`$;}e zBq1qQJie=wo4)q~4AB*r6mrK%R#N%`jpT7({@@1761@`Hcm{)iUukkxZJSAXVnM^z#gze)n(@g^}Stp3;Xgbp!D@KK46IB7+STLMc44 zoIt1FeI0@b@B%&Wr6_U!(mB{=H8 z`f5@Be)?kZs%!S34CWg8doYYYEu?^sS{g3-*vFGQ-^>iI(WsqfIA$`zwU2=`Vn1bP zhTGfsEcM$B)dJwVvqVrn)AfVfdN-I*<2&O#I*Eh1tJ(1s(pINYg&Ei;7n=9YeZOz~ z>>p}3#vV9YSJ@5qljw%-S&2>Dm*C+|Is$V6Y8HDr^A#9+{`(kt?6E%=Epcu^jvu6K zFf5?NF8_i6;`l_ynalkJqa*#rrPTX$-LKQr13ff01AMulO67rd)9Vad2*ZbrT7-bG zKRXdwe+gRNqM%IW7d$bO#r_?lWZBLBrLFxEeelQA`pJ=+yBB+oolAQ)XPd+uTv($j zTBewU#km?De*mx5NtoU_naJ9u@x7Qo9?w&h;l&q1)-_~ACBtF52_xY1C(X;5;+WdB zp%710syw(q3~zA`pLJ|)FRlBW4!10rW_hE~r}H|0oMlIn9MS*Bp#O$4|9sA0vY`@- zdH8hUnmnjY6LgrnEc5H|oa|&Jmrs?z#(r`nH6V`e;|o)OD$|vR_W`J}cxTKl9ld=V z>kVcgX%7l<*1Qyd)1V|ikNsbEBR-PNe+s>gw*GE2qjPGn7cxLq=9}^ly)a7;C0PvlDlr-Lm4P9@u@J<6_K-4#y}a;Srd0=?_YcW6uZuCVlT57YRq9(;jsk8 z@v;TuY{aa`28FawQId&MoAu8!SKvXU2u3bg}Ex>mXmh)cDVhKeV;{I#f zRy@0D16921gG+9Q$8HJ|IMCg;L~ZqQ_D@^>JbJ~-?Lk}*UV9SnlhUChhm4-CN6y?# z>QDiMihkurxLNyMyKtL)HtsDmQCG2`{aoN6cNYr4IA7~+C)R3ov{!DiDgPU|@5S`? z@39oV^7gww1m00N-0mny-X|MS(<+nC7nPsUZ5^1f2CDL@tD}^lE8>1tf`kZO3r)Ub z;T+L#&!*8vy+q;9z=`g(d+i503{hFfT>It4pLno)A1;6Dz;%iq=p6eI%Zr}y{7fmg zwgQQz?T$drTeiu8$^Vek`tvd0p26Q2=lnXq&-r2XM=oE>n}1)>hn>^U&n(>|3X+pc51 zu`iK?v}z-~Inbgib&svPC_*T|7t}$y@Jep``@BHR3W(&B?Mua-Al-$eWQ^+`bQbv04<%?n=Kz&;a))X?DhZ3#DsekbBbd8_&! zCg=Tnv|;UUe-s?QuYPag^SvNQeD}7O@4^2k>+T4C>Xy6}EQ+ydlvvwWi#fD##e=Gz z#iBDGhsF7}(!RPs;A^&(sA(?u0`BQYs_Yh~;+apVl4~B%ft@Pm4^P~TdX!+{)9&vw z)88ko0LUIa?)z8Fez#O4`rdIIjCZOCl}8>PkL9)4xKw=t3_&aBJtj z%O~A&mggV)`${Ft5V4al^?CX_VJ~QZgBrAugDERdiheYO%mv}7G&*(GZ_u$MZcRW|atSc~l> z&r2g$w*xY-eYV0=!V8S9FVty1gdA8gGQt^+VISn=N0PMM(EXovqFXOtLp=rnHA-kw z!8|0zdt0*VKY*Qxrb)Tgk+yelYoCE47U7;5;BIOo)rHo|gk+db%nOscmFDIWYxTF7 ztjHdwy?;#7iWdLR=JaF1+PxFuPkd|$=S`o4=Jpp5z8}>q@ml6EVq@8#h!=^O(i6IP z|By)p7*+`#_92O=atIQ&cT$V5zdg1@-Z%8a1Rs8F4<~;$;MNcY{pJ3lnio|cxfOkc zID~WzVd03b?WSNFbR+8OOZSFZH)--xM8>&9NPl%|NV;cONa19^8m}Zk_D--n2Tk{U z%NphAw5cWOdjLf@&!|T}j6bKq{v40|21}Nn z4%wDr+wh*zGpEvRuiU!t8_wCRkUBPzl+%xZDF~V8!vZTpHGJpU0h-FZnMc z9ozvwHD3;QbxBs`(1+0=4hN9$0cz+zL_gvQ+9G4c)qE>I&jOc{uP{gNoxLeH;_Z>> zf~T7+TBN*cn7{^gKJ`RzyU&MokPMqV!msP56OgbfRl0LNv=&j75-le)I9%;R9y3@Y zBw>3ZZTBPnz8D^PKDZox=+6Px=d})=)KaCJXVAv#nxqS_ zpBQvr>;_f#;2ya{UO$HOcT4u|_(7B2izvkcXLNsz^rp1Qjj@8)SAbO#X2psQpBjk} zJJMwR^7|I=k`2D%AiJ1dwEHAjDA$d0C`WHjN`L3uOGsu;v~wDsei695E4Zikd``u0 zpP+GH=@@a)YR;T5_w>vv%IO{Ek8)0(Lp)W0a$)qq^<0G-20u)mBImfjwdUe9h^o_L zvv6Fck@dq0(7~A?dsSV4Nakzgl@kxgO*T9O^Wg~k)Yq{dgW1vhy7c-|6vG{xEE`-= z@8*%>ZMZ93FTW_=-_TX1>pM-yg_5>`^t`6Tm z^n6X!nURr4NypPY$?`hUvN-KON*i6bm%8klY;*9fo0mV+V|wC$u7A=bKV}LCbq1V@ z_4J$$jf`yn1`b1ioxX^xv_>Pqffa2~1F zP2eqqU5M|WvK#E^VvLc=L1pxmJ(LNLf;nCkd6U1)UV9KSqcnJ!igRlI`sRt?4&iuNH{S*eT)h5XCE)p5o1DHco4~Pz%;(`t4p3XXi*N= zXLO^0y}PW4FeZ~FB=^Jr<>1G8za=r1zE9xW57Y8wf9f}N!Rdp0CB5+Lo*ql1$urOO zb(O5t+#6IivI=za@aqsYfiuQf)~1;F9J=`Rk^!WM0{jwSCr z=;QI}Eya)dFx-eD1857he@xTiSW>GTU2m!0OhsY(u+npq%SEr5=ktM@yGT=&cEGf+ zxgaq@rGTF-tcQ|BV-mxeN(jPin3&kvi`?AHRG3M~Km8Sk!3XdniL+)rc#mOa*$%C_Oj{AgrW{)dOQ+ic+ ziu+wU{w6feU!|XyZp2LvIs*?9%yOkS_;rp{R=A+|=i+Z{OELXqbf4XW%R!NCUQ$Bh zb^QFP(nRn01-M4Bbq8jDE&RGU4-(#_YPPbYFMZps;4)5-QKhx=M3?sPZdz z1NbksWse6L7GHGU)0xP^Klb~QD~ij7<~}FW2UO!@v2Cc9N$Mc2lsqesQd8GUS7sM4 z+eERy5|*u6?7ky>5oZfuF$8tu5Ysbg%W(}cP)A{ZgGXj`cFwEXK|cPz^EHuN=0mde zpK^+vl@0gV^BJUF(F~w`CGE#jYEzTpG1P4NK5z)4>QX(z@vDM9gTWaNd^?qV6YrBs ze7OqW4O7ycJy0nN7_R;*=pk(k7}D(?bef&TN(pU{kf|sVd${OYYoiAwZiQt*;P!pE zeYinOilZg>gG1s8l1JZQ5?UOvJ({pIRL#rz{Y#D2`jFlK>961z*n6;B0OWb>bI*gtz-#z(b6@A*!!a{XENo?Yo*O1& zP%hMME{$mT!wNhsVMHZDZQD&KwGPI!2;sk>_n35~y`uWsE5CO_`+6*#glW0^J-QVw z3Jto1qgP1eV`d_cC*wT-Jz(1rceu0q_0Hdtdza_K*7fGbO0g>`=46m4To=c zZQkK3>Yow*V4QXQE{F5ixkY;hqw$@2<|hEcqJcESqtFmuz&xw>n;C$ths$<)8kFGo zoAKN|m1;if(~X)*zO5(mYX|PU+P^Qczx}?@49<@t$=6F@PEWPw%?ZOHoc7Br-Wv8< zX}`s#McFk3R}wV+WS=8Zv1e1J@oJESB4)U&EV2fr_8tkc19lf>_e8ceR!{~g#eV~O?!Sy*&KP$ zm47#IekbjIto`|XbzjH(>+;mND87VpF!(e)+LdAtCNKO2{+2K8Xb!Y_V@m}$n(*RxPa-X;T$vj56cGbv%^U0lJ^a+C=WjlCSNV1nsN%&t zDsL2;6SSP)wR)qTQ0&g8GEYnhRLm%N92phB*53n>(`6B?o8&@^?2H1E!^c8i!r;xXk(E#N8Z zZI5jXPVRz8@O9(8L(Q~X$z&_jQ5b7(r81iRQn;4Hav_Bt}Vw-2E07dv2VDYXqnWe zyxaqw>To*o_u5}K!ao}1V4kYksKxPy-%-yIl|o^VO(d3wU< z%C8-3$lcknyLXN{BMAuaetXaB^R=#$^)$`y095+jqx*D)-Ctp{`?P8VSJ3bHl-buB&G@x3+IHCpnn8Y7w579j z6?PrW)|f+LjvGS5cSn`Q!m|Pw9mdOaeY)Qp+9gW^2`(L)#GXD~VB}n(-9XmwHUpX& zSO+m!cn)zr*cOm9MO4W|OYC7}jsI!JBhCXI{y4bXfW?;4c;Om!Uj!)`M8xub1DktB zL!8bNc*3Co&2VEk7wf%@*22#tKO>IwnDXeaKKn3Dx4s@U`BeeqKK3*0XzaIvyGdIO zBBZXR7tT}qf!;XwxH;g+Z2iNDV`xdzk9!82yEymzqOdRex3)lH(~rB(MBsUe6?%|V9+EDQq;h{XQ&pQYZi&zv_lPZj|CLZEp z&I<3>`+#qI5&}~c@c2`vc+W$6zV6e`nqc8LH?zdIdIVF#7eEwm|r6 zz5?&L2tuWWaU?nYLUs88_mFtnTNJ`TQ_Kcs5G9kP$$ ztNgm#^ZRqI5DBBdd}Tm^je<=Da0!Vi`#k!}32^}D^^%59%nXp5L8YSH&qwknO!_(B3r z1461mm2s*7;fU61iWv|}@$8-g(VV!RxWiKl((zKccQ@hKX&o`twRh@;Dq-%!4$r-e zsd(o$;o)Kh(5CLKDL(WNM_`YEto};Os($Bv_*mn}@=fD(;qkiJC4jElK1hWP_0@_x ztox*GT$3dfeRMU@i1MI_=NC1#_Gv5QeL*Bhu{i^XjelPOaX=iv91CAr;kqTAy~C8B zqF1iio66w2Y5`=^wz!96T*#bPfxTZ(yk(cvC*qCZ`G99h(w<>spH;Mim{sGHK&Mk4 z_sM8lP+;Mq?P>mus!0)(o#rPwydXmrp-=(%|75a-QubZSl1|pq2(?Ar4N<6pn-kZSO(LA?@;O4bPpFH$%!Tz1SLF7~# zdoid8qPAx*Ws%!F;bM7&pIwW|OiPwezsF?cHQfe7xV69Fsd)DT=-jSAAk?qMW#!NE z@@8_NgIGtKr|ikt(Wf+)v9ZkbsZI$&%Fb<7f9#s7Gvph`pQIU2>*w{Z%x3x{hx&2< z90q?A&qk+{LSn5_a43iDGNThHTYl*u+lj##Z#$C!#%^1~SXDYykvya+hP z^^%A&zFJM_g|&T(7nmjNbIFfx#E)1|UtdI&zy7S0*<9jra?fG@(#<>au1Hm&4oz31 z;k|(EepfET^_CdoqwttyBt~gIVd`YE|2-><#TRt$@|RJtq-!nR1WY{kV^ACg{ET z@e;xt?3%wNT|y=N+q#E8c~?~+Pgjt-TkKryH~EUj?{rq*?r#*%=$>02ggX<#kg*Z_ zUR*ejyrY4;1Cm(39_1Y@1>R-||F<*Mr3rh<@P*8&;-r7)@FUGI-J4kvvO82cdH=Eq zXm;CYj=>utAc^f)`7B!cIiEk5lJJBHvyB!Xu#@5&OX5=Xn`N#29@ehv2a5GGcrJombgi9Ony0&C;{8o8 z(TSHS&(WoRw&&rVt5vpc=}nk6ugdB;KL%^PiA%EI@>djKBXM0OLnZe+d!sRx16CE7 z-CMj7C+l&)8Ortikt#(^I*mGUb6lPyc@g7R0bNZ0C0R@cC=-BAE26HVt2{w-5%XLZO zH8qq3FM*idlBoSmjKcz3MQ3SwwdNk=Du6j3%9C{DWGT)o|MNfqq3u`Xf+R>X@4rG% zu%1XU)v`VwKKsM`EW=)f=>&DFTerj*UvA!qP39Z$yyO*Ih3W75!`=}>m3^}2-1cjL zaLxLl%jeIao$Cmt!w>WlM)mv|ZAnEvtYh11y70rDz6djVmAXFYKVXFL^-g^U#LNpP?z>HT~2E5DW1BA^rS^feWL=S+PA@YnGy!*_78r4e3Qz~AM%&?zSoS)mp#(2 z%o6j&kva2i&J_`TR$taL(W}S+;+z`xLv@&xn76s}o+Zhvujw^p_lMcW^kX?Wcl8{SCPu~me}QbLUxWL_0Yt{JQRQJ_3m6QURUz^ajFwthMMk9 z7`cEZv*2w;*^$LC-J7*a{xuul<_N)v^oAIQwW0opMA~v4l!l8Baiv}lvF_M|b)7C- zNLqiJ*#HfeNPGs3P(DgAWFI@=)=&`8IKO|SK&{K{E1WID`x3BgaEaIVj@tN*q1*4! z6lDh|iWB)H65WQW(BWx!^8Nu1LQtVs{*&~mV}-^F-sLS}-1I1ZOCou;NA>bO3NU!% z(5heDP9?SH3g^ZQd*gho4~9hU%iSG*HbW7ftoSdcB_#fOKThz5Q;{i3$D7Sm1FkO+ zNhc$AfzKiRMOV*GJROD?92eD1z}2bux`);d(W-p96G`rCC#(^$sltnnQ#&v0wPz`U zWgJN<#!-HxulXAS?^)StGf{;E4@FMtfblz=YH4`xvvMmwnY$|Km&@rq$ooJ%j39u2 zr1Sd_+VKHbK|AwvcSub~1~vT^oxkzSdNfMYPsdNn=j#AtAN3;mPPPc&$UT3!oR zotzF1AT`mSXr2E$A92jb-CgG=1yAP6e(93=RvnN}-!(5PyWjVyaZ2Pbcz^n>*b7%o zK%nw|_Q>|Q{dj)y%s;I$Huc@R`dDMfzStwmVuDRd4^psqJqbMSR^mcqpAZK#plgL3 znLq7Uo`k*3tG=hS@vUDA=Uq$&Dw^oMa`*D$Y4}#+o2#q!M-`4}X0`_Q8W*SG^o*Y5 zQyk&aWvL?HcmCtvHKF-OLRBBOvDIY8{mi4z2L{OqW>1SmLrg)2_Y6Q9oz@)Xlj=Kv z$~7sYb_6A42k;>m!T%sbyN#d4%534yRLuU+5zYt)g}>IQwYMjZ8HDE}76fb%NT`p& zML`zU=wTXH{sJF)b3z5!#-~gnjQo+)94Us#`-Cs;!v=q9k<#lsQrNjpq$jqJ-P&-a z$pOBo>+PpocjM>YlCR51TC6f5)5VLjo{BIYBzU18P3)J>j$RD*8@bn13r3qKGZ-#cCrePtgSJ(l_e)x#dAz~%7A;#@VT;3cIYz~CUW;*sr)#j8iITJX9il<& zPD3lW%1%ebg4bG5vsHTlgH0uiJr!G{o~Li0tIK{-V3YR*f=|>PlBP=oA8`KQi zFso!+9c(stV$daiG50X__&D~5_qh&{7Y-!!Bsc;`$cP`bgjCs9dki(-%5s!Ae;WyK zj-hXm*q7+mh26>fa*(8hrg|mDUvu4yc>V9EV5UczHO`>frIt2$6Fx-Zr5NN<=gqsuda_0T^N1DjIqg(eDb_vX_vM!y3E-eR>XYU z4lF5<0)fKz!9&sw(Lq4l>6L`AxVj%IJ^Y{}d)QPSO?$L`zZ_w?OwV=SD8s44+S7sR z0T?kS$KSeqyiMd?>u1)6(=fF-edYe^fIRZ_)AFN2KVA%l98|e9qCBM8(038WprtGP z#f+r$#ZLRx0@*vr=W{_91DHc=e2sfCjdaP5i~N9~_`5~$3Ha+wgS!@e^hSB)I%8ij zhw%Gn1alajthhF^vRYa)2Ld`yIMqK~am|M52`|U7tLW!0%~PWAHQ)U>}WL5O_TN> zjVo(B^XEP_7N0*zXq&#-=(P!rm<5`T|Mn~pg11WsQED^Xzc<^ZzMF8aypQ}l_^NE? zJ}gfrk-((UpvmrCi&yH3;1BOjVM)67*-d1B+pE8yehEO#moO&NYU^V@^>565*O|f= z8UK4w=lHS?kT3l{TEpRupA7#p+k)vCS-D`>Z{a&^zHecum;>2&W9Apk5eYG%I*;Rp z(tq!JPNSC2c!&PYdm4y?Gd7$2V^LJY`JmV=rq}R2edX7!7|RoUOrO}FkX1%_2IDm` zP3za)Wnz>;yNms!bpHl=^E7@SuuLHz2Xd6Yplu()&Fw!pWkj7`eQfX1vUN~9;goUT zXs_B4Qev}N#_IyARj#|cWW^JFaZydnnLSA$C@$PRtT$-S2sp zE*1Mg*xmCVSNNmLBdE=-YVI+^X{M|9b5{!Q0*+njJpf+8t$yt7w$Cje5mCBkWR0KR zAq-GE|9p9awf-nuG`N3^{jQgNmc1pCMu8}Sb=-7**b|tsV?*&;N&UGQ6rXrQZ_^7- zmpG`7VwI`53>9{d$0ZAgeXX~-`T4G-Svzijfz?`yeODiF`~Y5^c*1dXst+NK0rD5o z*N&kzqBbMOfZ5m|*J-$*c%v?Ae|iFvR-*CtMa0e`6X__Gjhy?83Ur3-p|B=uo`c4q zfw@wL%hz0wGP&nVV05F`l6X=OgW%oJBlTBpxxP7i9lpB=iS z#>S&Cojrf(nfi5hH=WvbJ?A%fcnSK&duWxdKSi#qRARMk;ikr1h3f#U+ZB70;F&r} z3%6A^$PoCPHC_)k14JeW1W%E8p=tpRlkdk9T+CCZo~z|6sH0{m6Nk>U^N%A|r@Q4; zwQ%yj0v8NdE>ph3Wi>S0X2j5!wpTJ-oB2dWc@4Adi(x6ZulSiNAy-~HJbzcn!3)z? zv(enYaFI$*#~3Xd_*wNia=q!!G6}ahf5LLBiytErT{qA@2{)|x~@ladx~)@usa_^~o9E1L^1p zDs5pXGvnC2pV@c%uwXH--Zol;Qp8GDoO*h5Bq{Q|lG$CJl>+OW?{ixO^nXc3seopR)>!+d~y z+tG8(Q2Al!Dh`jB$u**d*Br^b1*VM0eB^+hz4vD|6n{ zC!VN#0dgZW2y_c;-KL1D;|>hA$ASEOgrxq&TA&hr@Ls`IpEB7a)QEU=lU--p%2!9( z^!K3eQu+a!?xXfm*1fU&$VjemDSR~FYaMsoqX+w>RL6pXDDNcUp48;e=UEa>It=tv z`26H~%Oc`pUfI1)6A zSUA#W>Mtm-5zo=`^0ASw>n3a5gNk+LsrZ-AB0TGo8y_o2 zx*RN!C+)ZJmZhrYO}IC;Aa!MEO~Wb=%~RgLygp8r_Lm9;)f#UH8KhTODoLD7KTOR-yVR-GJh| zQIE|;aK&UCBaF@Wb@ulCki0nh09437ila+&p=0lSe>ey=W<#~OD;mL;cv!Q=qJngL z*#K649%#$pzlmUpufWpFLlHs}S$Xs#8m&`(!JOFib-#2><*`em=iLO(0I3ZhCcNx8o2oYe7&kgD@f6(g7$u2+fu;f{i$ftrigEt8qi;kU zc>HB3GIYog!unMX)iNmAwN(TlHPmH4P5-5Ua?W09^JfQ_^eg{u^033WM#(EnZ(U4B z+X98o9iEHCg|(zm<29JW9qMK&?dOY540AMA2!HmdsmPAy$Lh%?%S{pVI^F@R8QUH={7$0-lnu|f>pienO+TJa zFRWEW3{T0S4Tr9nkxDF|)Fs&b*}lWiz@EAVX}@(DF#WTe#8CWCP|LbgFguRQ!A7JF zFQz2X#lt;O2VOT}y_!qYN4y>-<}T;Vhjc3G`@uwDSXW2nbeyF`@`BBbV+-!dqkO+U z&l^MtBQ(o12)_}UfrH2t$&7Es8aPp$S5jvsDMEv4?LM-3+e#wj}7`4DD(L8t4nWE;M<-*q;# z1c6O*w8o#YX(FHXp7_qqt3x^boZk1D_q!tlq=wO~kDg#=|L(Vnc@(K55#t?X>-JYE zlb);qiR+kl1MpvpIIhV%bbf^^FilE_gWd@bLK%^h@7o{-40L}l?q2+WsPLGv!k{_Q zZEiiwn|E`JTY37R;Fn#l+@;)a|5xq5b9&EmzO6eg*1_Mj=iymSa4E(i<7!&%M$%8m zy8X+N)jxw|Nc-5ybN1^G`fheMF|SMSN>k?^?sFup&&#>}ZDLXBsLc7i{f4$;Kfg9F z;_O(lr@C+o_vu`jviy=-9$5o9R9kR{cLHbe`5#YEPX@`goD=+12$yP>)+jT=|H4*; z&)}4ks833N9`ijL^4G$^DGV@e*F}GJX$od{=1TC}x<^$PC!M)R2+ch21L=0hHWDtr z_IaJPZY0I9g{Z&j$G1@k*N{ix{&@Gd+ckf=+T_NA?qknEaHfcUeUZ34GXF1jEc!R5aCIK2nxe`0f^K1GE0~f8))5Go0BC>hd8TzIV%q$c-ZoHkBSS&ErVg)Glk8+-_iM6OpQ}jCje?k3>|l+LRy%b zzWFI1d7$>O)d(RB3ge{k)!;jMbg}sY@>_Ed8ufnC?`nE`!7&ib@NMF5xfw*`dBI_S zSm?*|4&u^k%P)#N=U`IJ8h=H{$7wQg<_GEYzE~Y$uv&0Cd7|njCvw`Fao_5c_EO~g z7EjX`*jiUpKi?$KlWwKBzr%uq=!`i z?1X#Mcd#_n|1K@@Ys`}?mT(%bj%Wydbyep95R9gL=XUyo5<`Yh=+tz0%kPn!_5h4c zw;FDIreGq+W|~|i4eKZ@?Q0?bzB}r zr4Ai^es<}e0SWOrcx_nJJu<6LEok(1x)?AR)OQ(Q#5|%fD8G;VH&Zs>Z~}u)eq|4V z(%a22JD^MR7AiCF3FGc#%?wV+XPmg7!8AsCVz?y{AMZMy^@DFMS91$kRg~$M^YIld zK&>arzF}rLEPLaC0lQam$^^Wv4toh-1{*wY1|D+X!BA75x#Yp6u;*ij_%_JA(=ER< z0Gp)!fuLnUmYX7!E?QA*#p#UpwwmaiR+@XSLh(WH1UyVIy!g%MQWp~MZfojm;!a;j zI+SW^C*C=Ki1CB`p5M9Ovdrz^zinTk;8vlMR4Sw2)50Ym<>6XHZ3A?@nvQ=c0M>mV~XT(K87ZV~zbP84!{(?=A#J%hj2Xx*(PpjhX zb(yGx0>P=xMPy>8G@>;9Icw=eC@HCEt>NT0n6YF8%@=_DS-uRY2e znHDhfQ(@5#irmj3zN)vFc^~Yi-zwpLb3$ zCFxg*Ezkm*iTk6DNtWQ|u!@_#^QZZ3$5TC`K%|1#JVSnYi9Tr+v+zlMMW+J<1=(?a ziY^Ft);beDF^C@;_`#Zt+&K5e28RrP6>p|Fk~pAY=vmeG^+(IMckq}LU0MSB3GzWh zGx?u&c6T~mzi&>Uxa(L{*wf6+H#dpFW&Z7{{xsOH-a6||yZU}YHh?07)c!l@%O3_` z+1~dXOjUdH4v&fsj}EKY_`j>poyW3(g^beGa2n@dab*3$hBN5$jm$nrAGsmu19VE7ma%L$ znK%tBR#(_Qy*@&Z8SKmJ?O`ELl7YR9HPy&gqKgkQ4s-H!#Uy~%M zE~!^uEK>ofTy8;f->*yfQ z(vvt{T$LMxboz@N;RS_-QGwqzZed21@pJ*(YZq%K?s$mkij|Yav0*kJ~;DqvbL$SgFjC62r_P}9vxSP6x zGDD+x))nbLMUJ**!&%?mh$!>L_3`V5DIvUB?q2U;0vz~3n^S-UD&c&#vW<`Ur{2EB z?EPDumn!*^d!U2nOuV3s;%ZKtbb%-GhdAL@{S5mxpd@XSI&)H}Rf6rPhT{N_J&s@k>B$kLCkD}mU^V@kE6qmLw>z=jM5|d+)4={LdS={ z_9aj83M4h1IcVnbZCRLsj$wKdJ}(kYgkRidk|TO#0lMq0`ZFs&qWzp>5BrpZKjXsn z1%Kl3V`Xs%=~#?ZmBikVrzD?+f&s4~CmdLPx3$-F6}7N8@S2yL#~_yw&1ZSu7Bw5r zW&gDH9QI0e;wxg#VKd&6%rDUb@U)rDHU&c42iBX89yxQ|E;nMID#I&52-iyf+|~UH zENEJOHimL;XYlnu>A}57%e$quND$O0hiIxv@+o=!_?47w8vwF^5b!$6zdm?wAIwBJ zbzeyPfM2Q7+CD@V*n(kuDkz+@9Zo`06d#eq6G!POCfJ+O99wx^_%q*aI0H18?(4pr z6!Lt1MYV&b{8(Cr?Bnub_La$g3i$+TNe0)32hrzbvzsL zV_Gh!pWneIfpr56OyKK+iuFwx_25gSZvdtpIYu5LMt0m3XSKA}^Az4GSS282rmrQ8 z-?I6`7w<=^hc*>eCdYj&2nO10Pk*+2)!**62PLE6d(5YpI_*qef|sQd_q2Wvwz6LD zHgbc}3mvAsxw!eO#Lu!*%&Z?HP(k5{@?=~L07DiRCCY;8!0anskn!X)N;`vo0@ zaROL@8)TQdl%}r>7AawVUO!Ep9#Vh(RqTe)zg@i`E*`&PwSSkQWfn=p(=0?bHJUe* z9Q69egzhH{bqET@dXGi+^rhU*nFnWrby;C`AWus?&g#$XXQO}S2$Rkiw>&_>jXIMB z>%hp`j7JN1B6(`J?Fbnme|=oh-ckH~B9zCk})Rn=Q?Z^=6 zk+>_&F)IPG5oYFU4kwjF0mLzp){WNLSEdA+GC_^IQv;}UW(e0m@mNc{r`;dv10z9R z_xJe{>=!N|53O>RD_B4+4G^(hu2a8~mm&o)`XjFA7|L;bMD-aJh7L zGd9ON-QM$zNypo{9F3*pk>CWGFs`ZrrIsO>rfggq5={#u&}=tC-ZIwSYh1!pwIW)r z1<@0v<5zi$7rzp3ypn(K(rF-5D+`-+kH7b2;@R$TRVD1#{s$q==5}%(X(xaj0lx=H zz;SNp-{PL8tCBoj9X1l(VfmCJ!Ij0ncB;4htNHugnkSqDI41D;{-Oj=;5_6`(wC1i zK+7948=z@&O!+`-{rMx z);LMjE1+WwpOr}H``{e}a=LM^h>PG?Cgr3A60q_xUn(Z7j5Oh@ck;wIQs5JR4{rqQ zpI}oeUQe<-0^~qixfY%bNhsa7D-4e9y-6ln_jpVsK5Tqm4S>6sR5sb@5NTz^YN$}> zRejgrWc~XZ>=U0irUFFi*LP!kfI%FJ55sj-0{H{$w3!Z~x(LUX;n{^tz+$*bP)I`C z_)~T9;U@7bRrf*0v!7w$*x^kQ!RL52Mw@^pyoB|_C{pAC>$(s}T^`!%?!d&%v#QX= zHz3JsyM*f*)7tpJ^!Fvl#;&^qsc$5tD(AOWA;@RR zKiLL+4AD}4IdvC+8A(QLtEpY#BH-!+Uy-;X5;{WH#ZW57DDhS#{kciBrMTA|ce2<=;Hn4+aVkYI^qm_)ek52IX zw>d~GM2xgQ?NPoz#==@7KXMgLH z{c`3D8o1%+XX(n~M?UXwJ5m$%;HhXTkK>`q?iNdL zK&$nwSJ2_xXNj8|!)4a`dNloMD(zw3uc9;iXWnCUTP!Ya5Yv&)Ps*NxlE{A9cO3$1 z$_#(%|8&OF1v&iBPlbX`X#g!TmOmwB{Hu%1TfzRi8g%t>>V-ZbXnI&4n&-=%hAOba z&-+|-%c~^frg;M-3~4pNSkeS9L>kqjhxV3l4K^4K#@F}vt1^jwD7XD84pF8fl1+ml zZFY9Oi>dlAZDo|o;M}~|L|fU{&S3BK66S6)LX?O{Za}jzlS(J@@7proKkQXnO)MDs zU_~5f7D(aZ?XUe3G=_1oAFQJmD~1PT_`~DkXV~MbK|q+_bu#~DU#mFXt})i(!iU;$AR~+2R9AY3@lxqzE*fYw`bz|1c5ym2yK7(pVwXEA>J_SYv! zSjCU0*k~k7RbCH=zWu#C=DL8ro!S^cPw*$(s8FBBmj;qQwO=me?K2`rOsF_oSQ- zbFLur>)SvqnZFw@nL~81pZAaHq%`X0oJH^RazM)l_Lh=^4-M_%iN^p=qc){vXzDch z5gtryzu0l{hH7dYDvGDx>ORZD#DzqKmhKa+-JiE*9M6pr9WLs+hFATTu$e3uAK2B$ z#|(zY)06g`=+~-&nZ;fL533vZBoH@Nj*s`g2CDAlc(=weqQ|7M#sVjO_@LmK%CW{P zN{vQ5+Sxk5YaVvP`?hNHGG-)3_Po*k3&qDJXV7 zNEiUr+Nh&-oW32rl}>9kLwQ+Q3X=Tu3h_xDS6PIsLi^qBPnk#mCqYv zetyhrFEk;5f(IG}SczY~;rMKyW_`SX4?(CV8r!!+Ep5g1(rWY#-243l2-|i4J5_`2 z4!4hQdd~SL$4?(Nl11Q#KhJqGxj!0Kw_j6f)tB_ltj^VXs$ouEPUXQ+qo0p#*YJI% z5`20bv`A;B*48B9H3x50ja0q|j!$e!cwbZ9?)Jd3`a*6}!ukr=g~m>xom)%0U+=e? z8QAZFDMKRG_Aoma_jP+XIp7T%Y>PG686=s~#=XlNkJNF$knV>hw)%cQE#IqfFvr;} z9CFW3h#Z<#?U_ZvGsRfqiX(++r{is5ct0}sa(L=Tv}0WN6(jBE%c(sG>9PA2w>Jbl z2?6U zI*&BI)Vw@9yqZxl)w}X&CKUrABfvSpL8^9XC>jOg2gx1BB?>23Je5b7y|mW|@?3P3 ztr_C-A(Jl_08eGdmAQD;58u!Ju=&%KD4~kmbI{UcTO)YoNxBD%$a+CW$+*q{JPaX2 zNCZ=5^r75m`gg*{Tbx0&;Ib?6eV-!7pfY{m3zcP@M)+;{%CZ?nnXVEl^J8pYXk{&K z6YKB0+@_STh3|tZZ)EtL71M`6ic-b`^ZQzKVg*fE+8$jfeMScxQwgp}W6byL+db{O z4RXpZcB7@@$z#Jg^N+?QIm3KYeY;a)q2o>N&M;yv4yO9k56Zqlm%vFevVHcG?+XN2 zbi`|)nGKmXOXQm4(1#5P-JT)X*OAKKXTMdj(3K48+19xeJdXV|0Bh(hic{uG3k5-w zYP_PLSo3?9aoM2#s7F`Retr&`JGT8jGHfSr!L9K=-&~*Mb1HU?!|i*3*L^xShxytW zdTg=j5?aarF88)A?5vcIT3&SxYMcc~+3zFq_n9E_{TDm4MMRandCNT2bd=hjn#<=5 zT5tSNEkyM==;3O|I@Jk;!yU%6LN=#G@^AbZw(dt*_7=k((n<4PSN2;A67QP*#qskg zGDqQlKZ_DKI*{*ThL%z--b8Z{A1Y zCfP_vAqUvMxmTcTUO%q8aA)eZ$;MgM086={U+~hi=WMK0Q@N%_?Cf+g>^517iu5sHFB}ja3tF zlg(2+3xEswDPTU7#TLX{G9ORgTTxKn#p@ea7^0VvVHf+FIsN=Um6H%VClPMGUzFCU z3HyIn>=^II#?!#MCwNXRhkd~`)!l;rvSSM?3m=fUk!&Y6E{srheeiQ|AeHK;lvvGuU z?D_D|KLYzutx6vHLPIVH3!i(EKMdM<;JFPb0s9%$D;4)uMic8P3!KUB+JS-{Kyf3x z?{a>_-q0*UYhOjnsbmR=6iy4gzL|YLV*b>23pNF0QhtwvjghWa4(1^HPBCQp@$-3( z${rHF0nzHG36YBM{x~D=Me9jvZCF|&w3LSZ^zmVzGBXpNPWysIWeF^?uf2P?@SdIkO>ND4f7-XuSM*wFYf2xQ_O|8V8Lq*2pUc#F{7 zo^!=|m)+)F8ufXPK#UXfJi++u5=G$rm*|_WGhiULK5jUdWhiHz(0Tp0FTbLZbd!%0 ziVjyJeKI7FbD?nmD5JN>bWOfYU3jY4vV=0vxz6tyAnNU~!cFU~;ixCtC{NEaZl1bH zvfZ~TGxvLTp7sklAc&FuVYFihrUzOIregAw(@Wr&D%H4}!D5P*xR3lS(0$UvTjr=( z(JCiV+yaVeZ($NlHkd-xSuc=IFHPoeoz>prGox`OKa{sp<&Q0@?@02|^Zyo-Hiz z=ojMkEiu&ZsASFwhVJAS?(O1Upq2v0OKx;XG#wP`o6XlxyadY- zj%}O_t-q{soM6&@83qGPZxJaN2|_?5hPmhQL!5Dc8wD>U?+=@v!T=vsz?c_itY)dy z9yd(#L$mqHk*q$C_wV@7hi~q-K9V};_k6s)#f;RO98U(JQPhFt?wZ3$CYkllHIMI? z`C9QN&*=nZ#phgM0E|VQxKGgO8y)s_=Kw_gcz4k;hqpqDqnS2rB%C_G3UB5^zO4jy zb#iFo#{y+vo0K?J_Qhf6JO$@7|D8_<|A+?nQ>}1Lb3?bd^9fF8R3(L?Yx0Qp)>CX< z?ls9?g=@rtbXveG_HnPR$ZJ7j$9bKQvIWFxJp6Les`m=^D??2CB7!;DBo!xxZug+< zw|zk)a+Jy})B~(aTn{&o?cDp7q9TLtF&7BVy8fcIRNJreLyPj4K4m3p4;SN%$fsxZ zeH0VlLni=nK)si05GM6^dV)BpYvq2E)vQ0>)_q~Lun$K4%bYKq4kN7KJ{`OUzFzF7 zlw9+J<_TaWyh{+Ngr%9ULV4YvE4+D6u08epe2uT>e!?!79@OoNjzy2f3ru5NzJnDL zosjqEGvAEAY4zz+FrT1ZF$Y!_QeVL{B+R1KAAQ(?&) z>%>^E)z`Q8RXw%ER+Ezj-WM}0=r6QJd~SVv`r<{i@4mr-_H+PzwLhcSB(zJk?jv}A zerf$`JPzR<|C~~%{)iQ`r`Sk(9g9<@sOvOuZI!pDc_k%0s)u{dC7SJuhyH3*(T&88 zSQ^~)ay_Z|Kb&UVinF%>9TTu0<;i60;~2g@?)V{j)HYPB01#z$oXgLU`2NagNoxHO zFtaG;P=_&a-x~%dmie(`C}GbZ3E_kFsZn`8EG8Qsdo&@zb}wV4`-1-OUJ?Qw5@4{PO#;fG75S&k6Z!r+u!*i%=8Mrv|aF z`+$qU^#-kMHBYq4M|-;$RAXQ_NM_l-s60u>YNiQ8SgNcN;4ILLTJY{quP7x)4t_u( zq!g$u#@7Ylcq8lmuqV<32k-)rH3|ez6v$1U(0nuqs7j3+O>sE2x1J!w_Z6QGj(5pH zB;DTEYIrYB1rNLwQva{TTrQ9Z^_H!u1wotu*lK1tC=TpT%xW`pv8&)6ByWr^30;>8 zfqX!RmXJI~b{^7txnw+9O28nQGQa@At03+wUu4IFx_uxlKJp9thN`y&hir#BR3!LN zem*G6lw@5zpRim`ztz1E)=esJKkA#jpoK+l>c?EJgw1Ya8Tu#bX+Cx<&gO$8NMD!X z&)8nSt^3mRaIc!*08!M@I@xZkt&6umE^+29*SWF6#+RJ=`DS2iA&b|2OOxJSyobNx z&>VgNI+pim=~0e%L%j4CqZ$C|y7gM??ziqoB1tI&6p9d77$aaplZSbTs!l$=@4-fE zfcJke%?MXZSPl#ouYs#JXvnyr4J>M_rgXQ@)qG7Ti3M7a9=aTsjppy^MJNAz?c>|S za>w;9LY4l`OyU=`86YF4C|0leMw}ZAnIG*fn`IwD5*z1LZj@8C^8lnP+(DvEEN^c? z+Us+Yi*6VgjtT}QWtSN)3fp9|A{}8f7RUVceF&Z<(Oy4s16;d3>Kh}81o6q{&BI1p zUm!<8XMemsrPQ4$5^=!Wb_deIC?gc|X1kMeOL!$~aZD?P}qM3Kd~v4uh+Y0Mp;M>?R~EW303Rxlk=(Xss zQtj%B&{MygJ)c`wgbVV`yd7jYoZkXZWqTTIdp$4k8V2UQ!7P2+A2f9audDpMO`hQB z)#b2~Bg^&YSAsrDu7o%Hh?#&fwek2OE=PvkUQBCy?VbdXA5aoS$(H`Ems6AG}&b?*lk)W5ZB zU>72}cM(GW-?+C)NYX=IMrd;?EM}7TiPPR0NM87?VxdOoc$^TB`7TUE zllpYtgCRLEZu{_K*qOL~yqu#FWTH;{QhuTS+zavaSYdI4gyfx1Gj%Zay)(DQs6cuX1}^onc#Gp8CB%1R1hCC}tvpVx!iDRu_GIbA`|Z zu?*ff868DX^DfBUq8%`8KMKsHrS*RM9>|aQre{OaB|G9D8BD zCz3O4N=S<#tu}nSNg^*sHPubrO<_e+f!mAB>k}I0pz#yA|Y!!OlN@irT z^9RjiSJN-%FSkRErMEGTf3f#U{?Ki9oM`heeo=m^2}dow)B?ma8&n*kd0VSay4pPc zGJ{*6dRLsG71@1`5Dtp9a)B^Ts6D@5uBoF7_Bx<~&~w4Q4%vh7+aK{2v?cQT(@5wO ziEBK;gjd%px`0*ri_&yAzr1M^-W+-c9iD&w=*KBIJwAtzKie+na`ea4xx)$J5ODhj zEYZsleBUw)-HC z)B9J-?dH{eIBL|zr=mr^S`oW10qEtt(l7da@j=P?5&O`DWdkmO(thF*Ivk-c}>FCm9V0Zs&%A|;jq8}@zdCgNrszibbK zVk!`DL!`&B;aIw%-w|vDrxUQjaCDM~WeP3lBDuKXyj{ z-kywiJxh&L9nq5#SW745)z|e-UU+4{vmB#u$K&?nv$kk67nj>nbQPv)R!C0-zDT0f2_4wV! z`R0pOajzw*U_J{wNT$O}q*t};r|ZNXL~h}1e-B6uP6?C6cj6l*`$T)gXFw1u)tVFOzvrHssr@P3O_MHaDjZ}u(v@!5+|*ae5}FPlH! z=|23(m2$j62=XisM6+iJWq9T-5FN=(T|KYgWbVtoi+8iV*Tea-D~1Kt)j(D)Wd0+?$+>~5+*sa-J%z=dII2%J zhJAy^lM~`I`&@*2A8-sairF4q;s1e8sh_p@WPJEX;ot6VBPPWHBy99qfcT|G;3L&$ zSSob~pcmS%_Qar znW{smwr!q_Y)x;6u5*UZd_Z1w;le?C2vmY%&h?C*ej;5htMr+(&Q;!ztj_ZL21Yjn zOU8WkF56oBh?sI;;Le9~BDuw}?5k|-Pb6w6v{F9q9<`8%PxGB2sn-G0dTwd4K3%v+ zNhcHfVoPV#a?2Hhacy-}i1VW&#wK{0gr1PG?xr=laa6s;_dUIucVjuiQ&hfY0k(-i zlWzJL-I%VjtRDc1G3PZ7z1oP>Pns(++Rdg?_t@t`;g)gSM2!E`J~fcGUb}b;+=?uZ zpqXV+(LqKQl6^$WZ~J5}%fk|!BlK1%nffvL*h4CKZa#^+6ZiP|Setp}K2J`5feHgY zxw@!4KTkbHYdw)B zvGNP`72^vgz5QanVd%On5RWfou@9zptyG>z(8MBX5{cr7F$N zZBGTi`Wi+nR7m<`$%B1eeDyGXF*WGM!n8!^!c9E0j-Jq?uu(SCR9m!zj09NueS;IJ zD;o7@B?)-i>+Oi}3d3qF*+D`Ld{C9W9+`h69#$EexnF>~PzYOIH2AXog zMG%y=2%sA6v_F_)dvlfs?ibBH$f~ML%~zlX-yj-00R&_6G49(4!{H5o5)RDo#Gbz5 zT*f&pQ!ClMZ8zbDWY7&U#!OqZb+4u;2Ym{4p++(muVDjAPj0&?9Djxad=FR8F1nRI z2CW$qJ;sTB?m=>!srR!6@yHz7;0%%MoXM-#~QZjU?m|G;Huk1BsTU?B|l zwTzO~?}ylqWZ4lFg`R%=Dp^<(bAuP{gHU1!*|`LxJOrhK^Sk$$0Ll_fKHqz{&Y>R+ z>SOI;pLo4q=9DpdK0V6T!Tw}xY7llyDFL9ZPac?F_OoW2 z6>9E0Z~OB>{nmiZ()1)O`^qUCT%d+#@xs5K&x{FF-f9g9Ft|O$*r&}m`Ic{?v{biy zbeJXwPftkk{EDJBep>Q-TCUDHWFogDI@`-d3G1FS-qBmWT(P{PO58FcE`^mpaIA!q zA>h<&)VGk#FMC2CQ=*XU8p`ijo!_XEln_-tQh7oD2pWa?vP>X z6)HdH99pcWS+K5-;&VJgE zgOX5pFqV(`gQ=|}9G&X+Tbus;h_KoSYIa}{Y&5@xR4|AndDcmr6t=$iR`qzll6Q(n zikkSTiD?`?umvoUJN`*~_vg77LR;njNOg3NE)@&)nm-)Z`>r3TZ+xI%mEj&w`%H9> z(ExM`i=wzl!3VbRY`8CzwmUa~hF&n@B>v%LsD(X{6@FhbO_6i&XN2Bq#&U2t(%+}Bk@?dXCp(^t>GQa{2Xr5V2Jo(5 z?7LI8jSbK3*BgA^T(2&lvGT&*mjZF=m2L=KxSGs}OTQZ&WAQhx=G!}nO~%tON%{%u56fR| z(Dso<^L z?xns565r!nLb*>rQH~O5s~N$f`@^Al0OLq%@7wE;eYN}BOWlw5h+hSI%5i}JKieMy zeCf3CJ?h8vHHkHKZeQ~LNTV}}0ki3*Jg7H&rcL8=YgLoqhX6g?!FVR*!$a`c2bzsM z{TBiKo1gt>V_sTpzW=ZcT2<|@gD+8~V)*x#y$6-R_|${_`BI9%TXd2kBwyJfD2>N2 zR4z%L3CCkEbR)YTm1Tc1D!SY#IICZ_LC=5p+dip=pJTK-NAtv9Q+7}5lFArwkR)8J z{m1$7=Kn$srYn82UqQVqPHz21-~{e$P&cct6#J~NM+pIQb3Raxwb<$*5kELjscJl9!$+1`?Ndl!${?y*xTcO z?z~L2QqvyZl&$YBwt(q-}uHvR9Ke0bl zHl2k+e~}?ZH%po~N;w;jk2gCVxIFEA&;KmR2ch62BlZU!v!R_FFnCGP6 zwoeVufa0^WdCsz(tb%U~zoXtv9mQ1#z05U&zTrvOZ^T^L@JIfR=*$Z$)$*Em8Ooom zu!@mCNK;0rWPQ4VhNC$OfUR9PTtJ!%F^@h?n*2ti`WWOZwJ$+Oo5;lb1U;9tn8D}I zrMadvQ!NDfPSx9d`4J`@?h>p)jl3>VS=ZOt<&xzrftf>WbB zYX(T=$=A?jf=T)_7fRu9TWfVu1Yu5e_wjq5&-pO~it#G{X725tFDOqA%wi-2CT}<_ zm~0LF&?39`NyTI$e41i<0k11gQCTJH0|)g%s9}Y*P#3++dk!LVSH0OfU_R{bqguSn z@E0|VPd$D{GVE~PCjuL_qT|NnTWEe5dTTpna9g%YSb~RWG-e;`_;BJ2YGK!muerJ^ z+a#3x>ei`ueVkp%piEm1dh@1Tsfz!lR|987qIo;B-HnMQ>4rL&d+MY-Nd3~-H=o?X zVA;^V{oR6%lgf^(6K`DjYPqC@`59tyi7kGP<%Glsy|%f!&kh9FWa;_J9CS=YLIV3x z`?6jAt4J*S>{_eJd?n-VduCFCsDqfg`>+o5o#wT^^5dYwP4fYeuf;?8vG1iuR~SuBcz0@kJd%$mi|zq^p9T5!RIPp14N(~JA1mor>T&C7{4^H!Dg1Je@c<9F zJurr6MEJ1%@O)=fx2lyPv0MQ~Z-a^*(^q1X<^+e~e$xO+;P&{I?DML_`!pw?bQvLn zlx=w%MAzI+%cNF=_3vAD;QZBsSe>zeTli}pg#Z|v05RUm=V7TXKWP}MaAc7*Qi^Ax ziat4U>;Aa(Rs4K(drnU>mrcl2rvpM*4kL2-B3t4E=5N}s8~AB8a%*>)vWu$TuS&3x z{8~6LQyYq)s#>ZKBRe*DdT#1CymxmTBpi{a!(TBF_ifuWXCpi{3%VSAyd}%O=O)`& zmON_B9cdulV8*DkPO)Z|nI$2l6Za?lC-~NZB+u>7x-A9?JWuxg`W zrCI3+lZD3fl=JI$y`z`xP%m;dS4YWKy#B-8?3dS~T~>@#n$4Zwzw67FSvWBjLn!^h zpJl7ZeA^qHg=ciQ^2NDRm{UW+@zv^Iux4yoCTTy9lcUG7svI)$z(=ohZava_?ga60 zyDc#uT}S@B%oXnxvLPl4xk7bp)rE5ymskf!FR?!>%f0Yn+QQ_P!wR6bTqC-s=?f?5 zTRStix+7R+zsje3hr;fC+@|J7-)*UlYGHB<|5feQf;65Y;wj zN9W3qi{CEo_oo{(2d_k=p(t!j$gX z^;R68lPzi)oyzMCO0w$pd%&-D?xoBL!|(T`an<;1qHj$4^8R*}{(R(rXYuxpC*A)& zk1!Cw`tcL`24O(L{{TbR%F&!F7li#m4Oj8ieov3%BQr2>7mjeB{I!a)8VVD< zX=j5oiSai4eqWn{@~{bnCQ6chOI0iVZ4-M)tQ%UF1`b-dp>_B0OZv8~^)}sC%NJf( zZ64Y!$;Hnk_&@MdRRy<|%DAg!>okt0`dNIY&%&{6Qm)E$qk;NICp_Y3r^FGDq zFdC~uaN?h}-1E}0h5V|~T|H{$&3oHVgpAwkYPWrsLB9{i1~^lOYeyG!h$%~5Qe6|S z8Qo%w3Lt2~-xfK&9k}R-dVZW4=F(9rX}gu9v}The$2Gh?d%%tc3W&Ow^S2enuO{La z--o*^+xt!o-w222`IfAlY1j9Mxia>WA#VAlv%3jr3&q_bV5O^I2*Om2IGl!HTSLr?C}PRQ^K%9w zhSA6Hl2PjXR@CHy606Qky#x~QCBIDdfV2w?6ZL9dFYDF6OK%a#gS-XiR|E;yICF~t zp+rYKk|@~1UL`Lm=AmIFMzX&z3GP>z$eo|6n+}mRn3u(hwIzOjPIHQ-{TP8O?xoi2 zfkj73h_{nwsI|_0`0^oP?UbwXw_Sf6AolphY%;rHgd@)rpZA+czjP*jb=K#4S>mjl zQjoMBXO5odw$==bM)Ty$&F>(g>k^>V;8GgVHT-bPXe9gE&rUOstmiR(gs|*J|M@|Z zY3MaSt!(ZS#T0RhPP~Kn+5Z)bvm(%DTRT6q=Z|mOlw>?%NZQ|lU-n<(n}{6dy4T6* zoBRSXaZbwK-<&^b-erbbL=5~mIBNb)dPRF=zoBL&oSHjDx%3$B!(Q!psjk=FaD(5L z%}=&@k=2mXj&M$*Pk_cdBgyU4@7|~qtY^a$)O*p-;9dYriN~d0k5Bh9B+LM`u}TKs zV)VQay63m2i+$Fv3v{ccLtus`Lv)7f*Fj3F!==3Awac*DXYvcoee3?$Ev#r;l~EShu*x zS3!Xkmue~$LCv=Uu5sb45UG~JTFgBmiN-I9 z_wDvzr}{hb*B14_h&_bF>H0wH2?Eh#8eN7oZE#GjH#sC#{%i4g4OgX}XJy@&R%1E$ z!v@rRCjHtuvBRGSZOHO^-c<$;s~M*Hg?f$mMSn@4N5pYqah%ITcz&)Y3StYi?ar}_ zg2N@Ye_=eC1o~8t66XGWOftIc?9HhK)1zGcTw$hg6!XFuV@Qx#?peOp+a48Sb1XHZ z-u}%Z{L##D52f_{dVR7d`O4ZiQs3<7dA}5&D=9fOSP@3ZwaQoO6b>eEsyeyn6Wn#@ zXY$g0rj58D=iZ0*+ufG8_1o`2-|!IAY^Qur+;0&IFQOs?4Iy>o^W@JZd#%1Kho2=M zG$6M|%h~5f6aSi5&ckLG3C%k%0A{}cJzGD3sj>n_a-~k_Y!TED3++)YB!0Z`G%D-2 zv7Rp|q}dUp4BW?M0_>Lp%1_ea&bd8KPay$tATrV|VypcEV4MmRh9gA1pppPbM}J%4 zeD>_?cv?2Lh$&R$8~7YNU&w>YTL_@rK#|Zr`C(n3=AiiX>;2^dWVT*Mf38pELb&b#bKtVl<{*Y+KFsru+^%l<$VSX z9yr}^U70$hhhw8n!HNI&Xo&*0Lq2*G9>dQQ}V3@G0ig}KrX z$AzCGNrN9}4C4lL-*@F7sViP)E$;6w(5|ouK~@!Qi%LT->&ZW#D1JN^^;LhRH+Tz3 z)-)jbrxY>_@4w&Ao`0diw{kq@QJ;ii9gh?Fh`h$z9>19akhG@0q7hs^Gl)PH+DVh! zP7O5Qs#6o52w~nsoV;kDA-xmV zyg0-s@mU_F!tvH|A2yxMqDu4ErFhui*_}RVwPS^&VU52h(UPT;MLa*u+HhHIbx(<% zF93)@Xo;qvk6DG6z^fmpw}{S$13{jc+{kNF?Z04og;7nZ$BB_@`VNG(mziP1)L(RS z;4~?g_QFBnb=R>O!>$`3f8~m|pmo_o_t|!V&{(FQ+Wwk&t3t^H`12-Q`#qn0@~@jd z80{*>?w&Bd9)-vyAn!RG+RzMPgxS!zLP8vdsv$+U&&mCFW3A!&4iC77M&G|9YR(ek#(pjwIToDKm`o2A z;~y_nc>5o#?zrk`e0|OQ1|m8irAg~b;R>PVM5pigV=GID$XVdgCl-|Ot%!K!_6Flq zgdBr*FudvJZd$i6NFP)w6BtfJhaMk3oDULz3SM9eEzT+U%C9HA4!rJpl<#HSN-~_n z8UwBc<|!|l$ODo6G;OY768?Sv4)kwizr0ExiV8bts;FZ|e~No97hcN#N^I409i5jN zUyy#T@W*i}?M4NyN%Nl|yuRdo6pU{dwq~xZUjRZNkQDOF5lDvixyc{>)BRNY$o;EAz!&~ixMo(sY-sggeq zzy0pI-Sf8pU7=SkNe|B)YFV6G627k}pUI;P7X0U}Tz=3Nw;ZtU&-Vq1XQY=7&+`C( zsb2U_`_4-6uHQ5#mNOp^<+hU`!9~<0%b`+KI6QVKIj4))r*N;R6W9Ho8N5=xeQOD8 z8H3B=!Si6QMhI$#kA{i!TW7%;WiBoZ{7Nss9#**F0pO6sKLagDpT zL_8_lQH^0Ncq5Nse2zangxMyPc`tI|V+)O4ixBHa zlcawfW;sdxxWtRTREiEnc8d*^ie`^wA4TN{eUyjqQ9Y!Scex710^OknWx$M#pDq z7N_;TDYCgl-RrG!-93og1c`)nf(!KPx#-sKp7HEHU8%tUTmc_LptGS_)^XUT5}q-NEjsjmpxjo%p#Ao7!gTB(r@_OHjg&RIqX$g?{#$E=KhHP z*=HR#tBBUU;3Un7@^`y9^FBf46(nhRH5epJ*nAX2HHAR-tk}ARU&Ya%?1Amd%t0T^ z=C?jnp#$vI_zV<9h?!){BknuyZ2OvZFjmqxxJk=pKusP<4;};&ghR zSxPYLng_MNI!I-EBdsdk0Oj+j+09N-B0dGZ*VioV+7BNUy%it4p?3}kZFq2){ARo= zJYxB;Wge4rQGGPk7OxDMkM5?xS$!X7!LY1P;$g-+QoD84KI`a!*M`PC5=y)DiNk$v zUIdO_sp@w1I8Q&5Soa27G#{3@LEl{MYkTd8W_Y09@KfJaPF?c-fjd59I+m>SUpZ@g zNj6YSgM8^IutIX4E_cTv!P1ZuxrBHtqW1~li!ubNi=MB0r3Jad2V6;Nm#^#t$$3|f z*K`k9oTnrkF9>)Kn)U5ei&&KB@9Jxp7uN5W@4mZ18*PBxs>xPw*csh^Gagq&;1? zsJhWzF!TiaX0IzrUVENQpLgGh@E!ZY%{MrX3u?$t?T*hCtw zj5yJUwDcLiGNR~@5~_NFs-=V8n$JzQmRG##EPuACI(w8IDv%jGzmcQi$il#(TaEs> zRof>x>hdi~$vM|2c4e3Ybf-(}x-aAQ$j8=9T0mX<+fdPwWen8!6pvBRu$rNT!opw@ zt{=wHaK#Ajb<(qeBh-uecv6E|kkgZ@LOK3E2)MI}p~LR^lQ<8N#ND5b`<8z@`c!F@ zm=524O0M?VB=3x3j{N0Z6d%Lswy4E&%O`LZSXt|!x0|eZe>EiH^SN3V>qR^1p?bQ@ z&R+shd)!A$BA?#_N-31yofC6~F1ks(KUxJX9U1ouyqml(3L6m}Nk3B<9XP~IotNJ* z!5nEhJNIZ2HJtC!k``|#E|PqNelEV_a^TPrSiY?;-ERVD(A%wk_-L;f@VY_u#)LDw zd^bEVg?c9KZ#7;_`}yj;lR=$~eGkf8}!;-#sHy3aziII80g11@#a%Iu%3wi8k$UNL~XXBMAL_&vf6q~}gA;9Vj8 z*tCojD?#6@#-0@WO47`4J*!gya;EKV+X^a|3FtKgc_NDW^yhFGp7Q(L+=7uA`JiF< zR0LEzvg$#Yi5}Y?v$Ho1)K^OGf&R`sj4;W;e`xt4%S26H6+A4}FCG8ZQeq@I-#&ht zeX;+l*0bS|(m}=Q`!hGH3#P-aKK`@Hv1bl=qQ}L)ObbXPu}VOwTh$C5I|*m(k8JXz zyEU;-`(Ewh7EPLRoxtk;Wq-gQ>9T# zgukvYu0>ufmEG^y{62HAeQ#b9lAq_&vheMK<776b_E(GPAZ;$DrRDjgorEJm&o~K; zYULXwMsJu*Qsb~e9H&8(3QG=*R?Gx@d=u?!rX#&1Slad!qkfgA3Cjt!JQ`wVWSi?$ z{sD&39{6_m6qcT_y0{cyX232`zMl+Oc^*k-4 zpoBqv5i@*u@8;*LpV2GTm-VSX7O^9ncLu-o9Q6d&B*>QUASz+#?s#V?0`>cVL+noU z_?weYKHom5!&>KYHxIy<{v+wS*3@Lz=q({quGzmVeufu%LkE2AA4LCN1#r67~(+?ygE%EjG(tAu) z$&TUaus}j_cdtI7i`eW7l5`%Gn+=G{nUM3f6a4y^N^GJmi=nB&+@aLPc`Uo%xU7<97sop3JbgVw zDEGKPVqv)uwIKqRY%)gf9e|WOoh{7`wj*sOp2IeA^-UqN4@Z(uei9ONo}}rh$*eUL zj=g|1%|t0fNd6w+w`6?)xb_~itax+M|3m^qz3CQ7bG~%_}RK&vYaoJ z&M$uUkhGV29@>4576Um@-f?goL{}2`x~)}sg%}JKA5XZA`kGzx*@yG(#ksSu=SM$M zWcs{5Z01vf<7NHM=jXyqcR``mHsRH_Z=QS|#Y%*AkWaF-yz4(OY*rYTpByh&p+ud3 z50wOC12Zc*%}Fej2Pp3FKxg~tz|aO1{?>0Pfwd}Nqax|Od99V)W^rfm$&+3y1Ph9>9RI4a^2}i0^W1R>(y-LVs5~ zaL*j#I6|HW?L!c5M*FohA%y$YAr_7?3-88LX7wapNc|UY4%O&0D>U^N<&}4AmdSPH zE$UD2eg7=>JV1G9ueJGQ5ULj}M>hfff!;jr`3B3}g4}%3HjcfEpTiYqZ%}sfV2ed9 z@@)~FVbS3zv*%ut7l@y^Rl!{S1b^Pnr$alCiO`wnmuT z!cs?P5jjrV9e)#T)$`M# z)5LwFC2sktKV922KLydonVZDi1m#xfbeqIikZ2l1BiGc2s+KkoI7b4VBEud-+2pKdh; z$>0b(pN#)r2&5upD)yMBHpn7wSHO+%1k-Iffn~>=nVhL>2QMSv(OW#PD%U(>yBJD0 z{7%Nzevj?)=K1}b9ZKui9v3uKdmlZW*ZYOWvWHrOKJ39&qxwBuMGp4Y9z90L4{__? zeB<)=bwS$Xw{U8=*La1ENP5@=Zl8*)_#pl2V@zZhD8{}Jt`Y@U{}#iLI($h5XBgZd z)Y6$6db)!cdtq_}(x80VzL!SGe<-uDbg$4XV}9SIQ=#S0kKuR=e<)D|*0-%W=CgcE z#Vy*D_&xXwnA~*pIpDjwlj@ath)>C8(fI#;jy^L_q|m_HY7oc)o;o;4JfV^zH9rew zo`VU;m2teXl_;SC~`KA)H z6q)>4V2i+Gk`O3PD3|q{Nr)f+>OkBGQ^<^NZ#aKFy6}*@4YKsF zU&4rPg7Lspe}-bPM}`z?#lch5+_5pcXSvDj{ddDBXqgsQPp?t71jeyO@PXXH;Y4)b zoKBxx8A2o(r@Nu4A%~#zQQKBWUH+A@w zPwM`J%-%IXVG^Sn1MmG%rWFf_hqepO`>+QmNU zQplThk|>x0wdv-tFPelREA9e6=^S|n&oB;iefaI+0_OT&qeJ5%VG=QVar`7tmZqUW zf+CP)*fIC@_RQ)bQu%iCt5^0rF8j2w`U?DkJ=gQ7Chzy<;h+d0cR;5;y{IboNa?5C z6j8pGv^51wHPv-0817c~YRolZk0R&3b>duM^n5oTM>b+N{Uv)IaP&Ku3#akXJy-f} zA?*X4U-DVl6+rk6I)W&BJ>iXmvRM3laRBGiXSa&nM={@zPp2uYA?;#OxI9kgIWWn? zJ)o}8oT;q28kv9j$TG@{kiAJipr>Ufo|;Y3ayj$xoETT_`X{5=mvG2cS7DD zV`<(pp&Mda9PL+Y|2>@~G{yYralh}}|2Pv=CYw_y_NtCnJrjRMD9hwLahE_&nxg8k zJCv5MDh={$c7MXZwFPdw8g=uq&Lp#5#FG5&qoI=)X>&fGZ5#>Nzgo)@wMKmpA(M`%XiW-hpn^NsRMs zANq){b&r_tM)*)pb;8}8w_S3!5`W9DmAENk4ljFZy-ubpWbK&3D} z>3k3E?G-A}SX6B~bno$R%cJ|@`whOw?P66ORJHJiuXFGuuu~W6Nu7GyoX2^NpRlhc z9V+g+J4_EG1Rd+VzK;8_w+mPXt@-|0aq-zBlK$HTW6kP5OijS@JY3>Rql|0C&uMMF z_Bj0e`##^gK`!iJ^p$pKe&fj%Q*R^eJ_*5qJMg3yc#}8cw35=nBITDfO>$QRtL;_m zkGmU#y9%{Qw(?*A4gX>NzzQ#LpTEn)2z5M3pk?ugO0_pvoqiEY40+c1`CGquUK5yK zXIR~PIDLjrI1&bThQ-M3I8kmD_@}1h*s#=fJy$=uoT#-~y1~k;#On>g4O^Mrh7p_c z2YB0Y8;Cx==YQ2$HQ%S2yu7ML<7a9ehIY?N^azs+f7hveJrGH2)kTE(l2Ey5Yy5NZ z{8H4&0Tu)K8)E!b1PpZ_1eIJP{ra2=bm_J}%3vt|n#02>_g;oTI-q0URygL|E)WAh ziuWkrB1TxCB@E6Y5KI&3?WZ|75yVQQ9`VbTL(O*SMLE*v<@G$wB5VgP#eQ9{%N-_n z{!7RyBCn!Ol+aVd>i{0mjDUKJ=X&7cWY@!i+t;b8vp@Db;x#JI+%pV=ATnJyAkYO8 z>?LUR`biiAjOOEh&+laaYWj(9z9;t_fH)ON5dV?vBaq_wjl4cuxUC8B)0*C&7Rdv? zLX>;Iz59$OA(un4r^-)3R{c6AcFVjNf7nzN28g>~2_M{k7xjRZY73jR!7I`+J}`&J z#VE*-eQwT?jr>D=aVngq%rI3j>{ z8l(ny^XmsB;vssB#*69gA{IQ<fmafZ}JY^#j} zKSIE3%i@#X;cD<=3c46^QAn}yX9~~o{Gyv6Z}TeuhzTwQwfObX%7USG{RfofN(!`B&uHW$of%3^ANqT&%j2mi@`5NSMXz=%{{ z3)cUhB`9(_!PJf!-OgdmxP`QI3~O?69-m0X3F90;w(139dcTL~^>pl>;e02EcyxO* zKN(tN*8RH`M0=G09k`LM5!~eWy8LV-x^k%c^0s(k29=%@STG-mUU&w>Dc^^uuQD#0$HAv7dr?_DF$E@svH?wpN2{~sNyG1 zp+MWraUM@J^~K%>X(PFv0aj&BJ}G$kD1M*U^m1py2fT$EZ7eVk*GrlSfj9(~NzY&yOc#pXV^ zw<`)wKQ6K=%TCb<>kIO00S8O^w7O~P6U)s@KA-CT8%xFs=-KbLP#-z=j<3w5%-f!> z>pt3!zj2ovuQ{_TcdSdkE1~nr_mB3_CEF3tzlE&akkCJlXHCPUD`KNmI=m2$6ssDy;$9+mjj(AKLhFIHve(-jHbaF zcLp)_TgU$UtXT3sFok`fGqVt#nSJ7(7W@(6zcqJ#MUHjjDHg1meg(KrYY-y$9%oua zZS%Y>uXpxs&-vi7C1kVA&CO2=-g$|Ki9(AW&1;?s0(0Z@d`=*sgybN#+i8YZ_@SQ3 z#~g>-)XHY95=q|NV9{+Bt^WSOjNp0H1%N)FpQfN;3c0o)9X|>Vi6h@I8f7L>olt%Z z>MuT^X4G(~2)#+#1x93F4~3T$|`AII!PV9Ch$D0}S9kiI?N3TP!KrW23k z>m&wcJP+&gk%j#bbxBbsTeH^cpW^K}W&tB%C_uofz3bjP3qC2B{P)A_@Tg3<*I2V1 zr2VIMPi^(_-SH#Y{yo)58=Mv&uXE;`o>Qi_{g%Uyk^FGnoPoo34$T%pctS9_1 z--MnIDX?vtX?(9x5O~~9pqRlldcV|tXu_{vZ@KthHdccg zixOOlb($b}FmjCyqqgf4y~}6vaw?EkGOg5A@tcmJTE6i|tlk9vrRbevhC8Q4@ni zZm?(EtORSlSou8leTx}bRu#oZ>3P4Od2r|UtvPq<=~Bi?yU+=e$9J?%!fPpm`*SZ+ z2$Nb6D5(Bm3B=0t5y=MGH^=#sY|w;If@=aJ8~TD+rT>bKBO1c~WGpuB4+@yY)bErq z_owsuy=VQ5yKCpNuuC8f*IN;R%@1$oay<$1m#nM)1j)gy1$=4r_Z{srwlPf8IoYf< zMc1?ryjJj0M^-FZv7Pw0Y=qQ}eKoMH_1^uu_z&e1%7Ty;BVvHkb5$?IjW1(sa0a8%lihjaC2Wg5onw=tP3_3C^>cZS>T zq9&)8=UpI$6F$^)G#|#N{uzKz?5E}Ptg6@XiW1F%cx5)u-e$64v=Gj6L zJH5DX^RRxq!SX~b6#ni&3^Cej^e@|=WvVnC2=d&6zX6Yf_hvGRfN-kk=C-ZcoaTRsmFD3&v_YH57zPArEI{GpqZjubY$U|8#&m3Bf)E;OCJonCO z*h(Y~7&O!3Gb)_ZwQB;w$yM&=3^Cm*=7+9HyR6(NbZKVd>D8R<4n~rXsbk=-ci0~T zFRZ7+@C{<+pBRSWsLx+Wk*HW@LHoxaXK4=RU%Wr1e7;sHznlZ~Cy7aJY434^yc-T` z7k-aW0oPr9JGvh)U>w;oP={|@maZ|Ko8eQar?)g+4c}2Nf#jx|mp6+eOwolYs-$%F z*oqbLEb8KAXYfm%aec#!N%?XiY+>$^V!UMynoS47CsWC~YoT8Y8=t@_5@Vld&e32! zf)xMk;2kcK>n~`URUUr(g2;E8syNGm9^r^8z}Zfd_v+Gk`AsjlJa6;+X}A3SKJ7EN z!nVKubnKR^vRpJu>rt zmEThq-u6beWSlR6Kvt4e-M)Tuy5hO=l1b)6m7R~8GRLPfW83q$%HUr8EI#5wxYlCW z73&Y#y@y&B-q56GpU7v{8?wx{Cg25(@km9~Gz`)=CB0(%DD6&>Q&2hoz3_YHkCHr|OSVCuLj_1VA*RKSa}*3-JcqLGn(_WO%YW`;wQDT!Or6p(`K zqqQHhgqP*}KJVWQ1h;O@1ja0TvZuIW;9%%YG;=yF1IC?Hm%V6ydBeUMpCq22as)gp zE3fNDF86DKyWAhLrz234pjP`->iq#1FhC<*h>c4xnz^8{BL{dDhm8L2!g$=iTVb$L zR3D)g<>*)SKFoewo2NMUNVz|n>C;w0{7$Os629I*WK7J0=B*_C-7nO&jyesw>__(y|f zFM-Z26wRFH6WqpB=#q0LO2-c9;toCn!hI_*4o@fSa=39);imwVT=FcIy~^KIf9&PM zM`_|u14_oZ&3=wszh}=9vD7~+hepS6S^e|Cfxq`#c4cz@ebVSMPf3x}kGE%H?Z=$KWzO+8-UVG>*%&P?nWk%g!uV33`*Zx2`zC&lmkGzg?3W_p z<{c;XNkrFbpF#GU-Gk`+M|Y@T)d%!TU@Q3@mNbNTioUuY(^tku-^bGY=)_8@Z`icg zK1l^^iu66J%6-8l_*?!0sdtMDBfUO_wZ8sY=$(1c3dOy!q`OIc*AMGEn2+s^bwyVg zRiLP`NlG58O#!s?Gy`dg^j@D&Phk~>z}v|0QLPS&?LQbw@zlCIqy;zc-{?C4+|;QT zw|h}u)Bl|FY|>R zOmBoM{~XADiHBgO-iyvzYt!U3i7WkFf515sM^wM?0o6W5wx3J2+8-zCqo`mxSr9jx z@rzk?TGLIuyH%X!lf;qJ-a<%B02_&QCol1lOf;Xs$e~ZopA*rL*#hKn_UqrK6SMvv zP+wo-Yedvh2e%;a+pK-_~iisxyG!Z@mw$I%`ZVsh=aD zuq{9cWcY3$zvztP`vlxNJ}bO<+ydh0G}lqxp7tWl(%`_R;>MQ{CJ}Uj5+66wRTn^7 zde}kLLfzw2GM>{?E~EQmg<@f-t~dW2E|ji5h~%AFId`Cpl~$re?!!!@$QbZtU)@4P zgo$uu&ehSF=;57)9bfi{Y2Ef^`Rj`1j6doZ$*l#IO5o8{hMRbN$Xnj&6JY0#eN^np zeZnLM7qQmtu}lviVM3|qs_U%6O@5h3o6ngxwymvvBD`x7i^PMzGm6~!D+G9+65PoG2aBMTZc%>S}OX;dWy}rhgkABzN12P$| z*lM`u@N$!B4U*sE>v6#rSXP_U^J<{W>2gpnaPI3K!DQX*i)Empuwi`kT#m zJ(EER`{_HyDZcr69)VMD)7U5;InRB(a9k5ENKoARoS!e{m7OPq7w)^;Ak!NN0FjJ6 zp{!FhDDotGadn*l1p_Cnts`L!qIpddbGD!rEM3b zE1_gyq~RqosvzxWjzG*@A6@LI{kio>(IMBrxeg3DK`lm6_EO_ABqtNB- z%V-q8J+Yq3QNm&@!M4!2ZO1K}nfh=A2>8jNGVfARttA~AET~W*G+@w}tfd-8jpn|2 z_r@$;!^GKR1;+}NtF?a*{GHWLpgl#O->&V;pWic<%Ehu@wRondXPR1tBLOYGJ3Ph5 zBj3ZWr9QULX^7EsrTibDeERKoP36dg{NbC$;>VZsA_SOT5(3q-FkjaKz;zkG{ws6Y zKYqrYO2torwYhRk1FKZM-`jCc;0{*(yg^|1!An0W1u$%|K8}5&_O&nSU#_Rwcy{bD4bvTCm*FofQmIW!F;^x3N~piQ)dJG^aP|bK#P9koj$lGb z`<=c~L`5=^MO2ag)J-x-RN{a1UaydDXWgU9^#%b=(U+M_7#O~q!}HWi>{AWOd^|Y@ zyMM-5`&>#-cM$@ll|Tp=XZ^f{Z2~L!+dTXWeBp5zD-aRZd>$Rq_p6DHyo_+xSjtfR z{S3Chx3>4IdTw9e&R6&g&yVuRxMxJWo}&8PsShA{nz+UH=N?clt@&o1( zOf)j@`DgwCT*CKl?0WlgQQH|sKQMef8%Bahl|KK-`Rc(1*1g`mJvrzl?9#-&9?;Sn zag_y-fnZHjqPp+10^exD(Tp#>QAB;?(Hqoi8W9MJFaBo|Yf?qlF`br`x(4&31*`(^ z3Q=l`409j+32}Kl;;Z;xZ~OVeDdkQRyAxaZhK5+q4pZWf$^7|UKk4$mmETuliPVoI znQr^I0Nz16puAN zY24^Kj(1jmcldYSO45uWqb32P1sRsPZ)Gc0i)H~r@LtpDD0M7n1$x_3Oj4o zsIDOqz)0UCXF#;jumcFA(%WGlFU*z|4j=5w4dC&<0~hXSYb8U1t=zNtpt}}O!m{1q z1jQ?k!%IBH$a+*z{PBkMzeMCm8b2~O6XfSj6j8pkk8CJF_=(eVp8u|+b)*53ui}+C z$GDka8}FL7{PC@J7MZ}#y?d{}@QwM%>-QH#H^R#a3cf>5sHt~>SasYI&r9VfyIB(t z^NfQTYbVGf`aWV$h8mOLT>O+zHtoADk#R|+=zgP})Wdr;^OLNyJRg{p(O>Iuh%0nk z`QOkLk5($-!FGX9CROs}pR>#u#J02V+R~MhyXXYjqubS+%>Wq80opaH-bs2lJt_D( zWzR3P^s-zkbWKuSkDR-c_((4M-k`9F2yJg(N=~lt={NH6tIRU{?lY&fxua?~CI?9^ zyFQ)ca7;W=s^1`KBrLdyr*lfW=SwNjMZeg=DR=wd6+h|k3T6_7GKtpjdB3`Cxd&-j z5Q-E3T+GLJS=54OEr{?0TW1KxTyxp=o`d--ZPBCUTsU}PEe5`LP@=I9E|c?@OiDD= z|6kzj-nFZI%*(A{hC+aLeehzBI(n8nC5)F}yX?9owR1%kP#%0gpj`r9objn|gHesf zaXDdDN_nWZj1sr^gSoHc%8gQbW`E)-vt8jraBXnV4dCp{_=7#i_S{3B6FStvg$vx* zWwej<9=Y;C1t*Z3CzTg=t=15pD#LcAAdIakYk+8L>GtIS?i-82Qx9V~l@A8QG5e&x z#)yF*X-Xi2kQV+Z>L+W(IVDy}m~*aN-Pf6Az0RQY?`!g~T@u?Y>jNtR`9vxylQzBmo09#>z&7#s zvZVvp7V_`js?Cpd%d*jxS}hr3YqO90Sp{P|YJ1ixU5=mh20pSw*h4x$gY>>%{iXhO zp&d&66Q3smT&!<3qs^Wm7#2-GB1}q2EqvL&vlGx8Eln!>PA|QF!!^dBY>w)z+f4%O zgEeqDsWefOQi^(ElsbT%biv$~N<2(GJxio@JLw0Ty_+48`p%#CC@m!K&Y=S>_MNhP zR?nL!)O+l3`V2$kkfc^VZ||(L_Qlb*cH1-Qfj&zmGA+k3mycFLcl5dJufzWY;P}H$ zA^RVy1Vi}SXLN?Tzz4Hms%ew(!f%M%=1KZbQ4AQMR2MtioAbi@=*+bwg8W%A=Vw?7 zL&T-I=kH@BKM|8c9xQ+8)7Q*q+1Q@guUu6!b0ZPfiPxv;KOs-`d92g+`@I1mPU`)g zgd4vK5hu7`+$kiHeSGv*_w700_QdfPzMq0^|PkbFu=M4X<73Km?I`OB` zyRm%uIq^g(-0IKw*1A<4>ebSmsgDq0<{yK5`aSPU*;^i$K|XNa_d8PM1A+_k!!!gd z-9~MO%SicYu15_aS21b#2L1;yzGb$6#9Pw`%v?>eHWIIk$vg4vz8`hgc)lnIscaOZll0`?f5E*|BCj28epgrw1)vi}{ z&9SnX$F;7Qn--TzuOGJC`1$}>zf7(IF$G&76t9UPwRJAHaToCdm(>vMfl?Z=udD5dOspTp@7V&ZbULhOm3A+C4H zAQdq`xIvjw&PuK2mg;Vy0aeS%vpSPo==ze|cEV3z1)%t?i?0p7TUWp2{`t1kYA+Cp z5})sVNMUS4t4YB#PWc)8;`rWEq!44Q_Z_GjADRGt35s*rBqo1$(5EPz-!G@&32`z2 z!oJWGf0=)fgNDz7(&z?g52Wmk5plT^I_^-3FvmX`83>)~#dX@JM4YT&Mr3>@xhR(H zMx_R)U59u=hzs2kZ@$07gEOh>=#F1As}?)!8XS8o2nsgg9nS6g$!3f;%*1s zYE#^zzE4$Xm$Qep^yv-;2aFO-LG$Q&jt_ao*V?H4?z|oh^%HN0%oO+bk}SN`k9^wN znb4S^lbYo>*#qO8U&-{ku*FFS^nW286cUAf7cFQL7f<+8TTGSFk)P_%GDN&mkeF^b}>c?lJh+p;2Ix8Z7$1> zp%dS?04yLRIO|Uh)hF|vQtilMxkf`vI>cYLqIE*o(CsxCr=5`(R`Fd|aOTI5E1sl1Rcr2Xr><^RWgDkLDE`m(zI_6FA|% ziVW}HqJIGWq_?MZh2h#5-$w^dNXvM;Yp_*Clav4@d%R%(%cK|k>z z{8eztW)>BhKX3FPhd=ahEGUt9=$p9lU3}K{pi-!_NCap6=>B7M9|N0nM3_(3yMOD3 zr;VK4uXur2%~l97!ifl7KHFDJ8D3mH_)ZE1u{5O?+h7Qaf*(ppHYA!U3dy(GJi?<} zQOEasAg}Wgc1Qtq_eVedrTbQGWchjfI@+b7jbVViF3<8OrPjp-;<@|H+EQC~buuI* zG!*IMgOS>c4N2EW_DOV4weQ*i_%4-7<=^if4j{xF`g-_`2!xHF-3PdXgV*~R&b8MH zt;aWou~AaNm#2Ff?eBQ(y9YEkkca90>3fBaHR#HbQ>u}bw)~`rE^BrdaJ1PUh)v1m zTY#b~CY(NouC0m{e?K`v5gK1-nAk@}&5#b;9}{8o=i4KV$vGINNte6YG!n!c5}I+8*Rfw-fi)f&x`C;5XR8t_wS22<04viIvR^l=e8vvozsZiR zwcLj@)?SH)W6gcxV-8J@+*$YR;9LX5_y%-lD238I9s1GSvj!mG#yiw0R_3uhtmB*b z7?hDSUqwvGO8neF>^M_zrYv2T(@xIM37tvPujmh%lh;>6G9uCE8x@@k5l%ke#4I{04N;Z^QSSO z6^v@%UfXDX-0`iW?isgcadt2>cvlovCOY($2ic2P7f3+w&>D3AnD_gYLeQq@NXGwo z!(*```q;C3Y=8;NeEf$vQFR~XzbhYvX7vQlB3u}NlUMU^MKfZ-{A|aQ5fLG16B0p)MecMbbx()2>?$VtS{tdzYtm0vc;=E3Gox((q=CZSd{@N zY(`N9ftYNeoQSs#uc5w64qpWTh^yLm4lbqA+><}|hs^foZ*hqq-%Tc}^kdid`-C&q zBXBQ!ko|lH%Zt!2BFGYT7LRA9VXXwYN9JZdK?5T^tUZpa&!*MC5h&T7Y#K9}wlq!1WKqZj$e*m!S29lQKv zrblWcRpvRv8%*IJNQU3jA(t|ht!9mWpBeLXu~$`uHp`yyLOf2)Q3_AW??evA9udr@Z&$nX5n$l3?a31q*Bg+^YpeO0gZIV617a%R$k^kVcM8^IU9!2SBb z!7!UFong3xSW*ISy|^WneGvVlH2peZzH+QCiPif?adV*r>3$~%RDTbmWgZBN=V;fh z*qg}3UJ;T2D-VI!AY&D7qGaEdmW~&p5Y+_CZ=1bb`=|2Z>rp2YQ2w|kV9uqrV^n7xRDEwVb#_q2Ng7n~kPWvrK<3{AzazjqRNr#Y6N z+N6dwGGp{T0J*)K0ZvDqX7KKe0AIRCW#vb)AHSD;q(sN4~jf)?;HneCeX>X*IvY#mjg#di&O6{lTy} z4Vt`#y3OJ>AD9Nf!)&6p<{YvX=`=N~y}0a@01pVqVaTgr(ojAkp5`HWc8IQG2qSRv zWiKAN7ii?V(nIQV)9$89@054m=Vdx@LhZVC$3kx2aNLN>=L)}c@}*6;*WiD?HZV7R zDlOs__~BlcCBC*}SQuF3oYKx-Fq-dZ0=ION8+&^L^2+Cua?L_xc;6AtSIC^c`_khB ziBw)Ly(C`>lJboStqX$n@?0`*9gXwI=NrIg=T8g5gF~xzeg5f@lkbDKI38Vg@60a> z#VK`GKEI*az9aqY{keG1AzyRKV7|X?s@t20!A* zd$u{*O}TCRLla`pni zNA1$feM9%V z)YXuR7}&5^j(;V3^ZKZs&t5_>c4{d78@^tRty*_~^H1x8C+B6U%5%S8LhQc0vkQ3y zxE6E)N<%fw%U_H|X%K8QjS2=N%uC6Y!z7c0yuCL_ttPA{JvF|$5}<{lTIG2KyL_y& zd3>Tr3e%|biFpW5i$@u_Vy_OBQ$=$nxrYXe!2H1zzu;CzwS{!?RXh#iN;?<0sws|{ z>t@0EPk2(>z**Bjh2bKp(q0WPy#;ZSO4-jpC#^Y{zLMN%>t}Y6!msl4HG~NqAGW;t zyd0WiskB|nU$BI+TDJ1o`};t3{oquK&4(6Mm9;^xcmWOp;Ti4^hQG>Jr1;396|gZb z_1Zo#oF(ycN8A7F+Kg79k_fA{WQDAA0M91V@!oq*X~2^C>Ru(Kec{||?}@4vp?M3# zVf+>oy&@sL8f`3Xx`1*<>Xt1r+A*)C9_Ng-1R^M>=bVON{0&x_i&6`<34dP^K|T=V zeaj?A{%>bRHxw4CE=yhZ*jM@_4aJ<_DKxn(=Zt7f+x%H`b_ z`MPVwkzh)$>D~C?12B^>DA3d52zP$%jXkZtgekFyPpe_lR*{O{ z%kMO^-uDoH01xoDiLvzl?7OIwX#fea3ni=MlzO)cqGF}A6miA#K6szwO*z2-)RFC! zk2(n&b1TclAA$3JB8d{|INZ`$U;oZsSTPWUR-6SPg?7iN^)E;x#7BCxZysE%LO?BT z)@xydsetpM6{gGUCQTG+F6%Vl+bs%2@IwhW=$aEiiMg@!J9}}Ury_)Nkq_{1gm9MC zr(zl3$6%OWV9DpRzORwO zk~D;$O=4K`E!1axGbeJ#2JqgVIZ3GRJ7Nb9IJ>*;O_KLq=~`f?Hn;SQ2Cs7msMv82 z(TK|jy$={A@n8@QKv}~j=J5H6>Ep97M}^xfHtEC84P)O{a)oarb1jLBVW@#|fRzw5 zOC>Pp_GdxqMs{eWeNPB&hY`lNNj}8NlQ?BP_lMIs2kxKnQ)-d}%A{T|rw}n7)jj11 z{NwD-q!O2Z;)DGCSKy@5sbgBB^veU}N`WVDl{vkqr1EGj$oh4)3L8&>BU4kaYV z$^0YJB;??e0m7@II=g!FbuV5snE2+>tp<)=%lqLte>8Pm_KBwuY_M^&4wa=dOfm3^ z>?3!UVO3!L^89FDZMj^%&UYqahSU4SLFOT>(d$En9{-UcPUyJ5_i-aC8GXg(2a1woJ~|Qq!o>j;igPCC=o>a zKAB6k+Y_K&=6f7aEz`LzItvo$sN-#g@1t>Ho-EYP!|g?ZxFm1F+l3NrJ36^d*k_A& z?M+4DEWI9=DLA}XXVf-wpP?KpogG)Q{shTqJ&7v)(Vmep<6~J)B8;a^nN|J_&-(4A zc>R}%bV!o!hVk%w#{}MEIPYZ!!8J=~*4=+pzqUZ#7~s|+3UJTI{xmE!Mu-GPt^rJi z^CCGVyIY4OiJ=dz2;_Tr3FhzLFH1jUbAii(%YT~{x)}?}sBx;I$Gi_pp~z3j#X)l4 zl+(TPZcv`~xmW0vb<214Z>s%+t(~+oHim2A{-7X+cTs@S7LH3_25~PcAvBSc>e|U) zU3rbSZz5^-y&8KIW~|4{UOQDyFU2L8i`(lrnWcf_%lB1%ui|(4ngQa^EFktm5EbuV zlbR^BXvvYRh$GfpR_`N`{3`@z8yY^XJ|DMrmNh=-Ut@J$KG;u$owu#>Pk`Yjlqg zI)|&{+lD)421}DJ9*0y_`Sf)F2A|zlTI*5=iR`zSZmB0+^LTP#uB}jyoG9aVeRXB6GhXw)lm+~DAXlVXO&Qbv$E%`y*kte zewqp9kcMG@Z}${!f*VQx&XsdI6`gv&qtYh{0U(Q-KXS1ZImFBn$H%Ms0-a7e>(iO! zp?EzGcnmnyt%=nJ4vg$w;hnEOq@f=6wOtvugCSkRl+yWU-g1zuUdJj3!JRVW&}in1 zbQoumLK7qjGpNP**Yzr<=yu6(;#b=z!Mb=oC)QS2LHLAY6R0o@5z0b?T!#n`dDH~YZLP}fTMfnR5K@=9Z|tAjEHX)MIr*YL4^q34 zK`7A;-K(kjrCddPK3?K=pZqK&(~Z|N9msEv7C-@$96E)V&<)~hIvKFMRvh+Zs-kD8 zH0MZB<{}y@QDAN7g6z+AP*TXd^(+t+yaZUt~d zl2wgnjsc8(h~X#pqBnmAtuV+g^|f`W-lk@G}J%XLY|Tnyasv0 z8{s7%L+a((Qm}h&4#a+^Ah=@y8Lv_)>hZ)HuX@y8X|%8Q{DrI|G#So=-op1mnLK&0 z_xH$urZOcn{aCK@A%_Nx`o4T$mRh+-cT^QCp{qc>3^{h|Z?E97){M=4^GnT|mG}?~ zm|cX$9&$wxz(bc^NG2no%-TIb>+5r?2$Vy%J5QWF?iGCdlL7b{J~;MgOZR}GJ)d?e z9UwE62>IaJ-zz!~_^9}&D3ZR+JtBh9hbzp-0WNP%n3rl^hOv;pPV%D@4rwNe3rYPL?Wi#A$c94rG4f~&*_1*7FgYxh;s0%QFGG4BR*PfAk9iY^JPtzD<&%X>w3!wLS z%&teiMV+GU_h(CAtrpcf=jSKT?}-Q}^2?1oN%{(1ak}OD58!2I{&?XKBWRL&Y0~ks zJ+s&8Q=ag3NyS-W-U18m1kQG;jGO4g?6S9B7w<7G+8P-;${;upT|S5Dx)Cl{Z)jZD z_V04h*>I-lc!2%e zJkvu8q4M@}x@DkFwIWzX2x<6`bDix~iA7Myk^JI0;;iNJ42jX(2+y-Bl2j*~fvkKC z)>gGHd~WX$KRf}3U#=4p2W6X8tLBYolJtT5Cg*4$G$XmSbOzqK#&FUq(B>9@o zk=DxP717UYaNd{c&YQE|ozdUTS| zG5Vapw=IauTB}yotZ$YiafMUS1pw^enDPYk2>iW?d>^bo`vH3-g5diSmfAxsIa+zs6bSO~DrEH$eY9Dw{P}@%E;hXx0Tx-t9 z6EuF|wk02!bH$?3kNmZF8lL4K9Vxss{L(z){OjJUemHvm_00(>Ek@5&^O46oLNS}K zupU3ERCKeEagP@UOG|!CV3eqYxI)-BC$fl#SO}{nBSc4 z+=c$|_G-*Z<##3Db#PL$`f%Ns}D(gO`VAd~zw7+VNzh-I*5+g1XCzfk-03-(M zv=9ZUGF)A#BUJ}RO>;$m52~Z8&j2P-W)@_aq?G_|Rd0xtmiMS!8lnu}3vqevxq8p@ z`p4@esmo!JaL$^%*dvA2MUchHqX}X~iFA2g}+#}PX(#Yc-Ho+LMY{&51#9ZHz( z+sONEGGeE`JNSLcMegM9GgD+pRJa;QiB#SrKUs6{)5?>`9&?^Qky5x=#Q`kFUI*UH(?*!o(V~wD{=!an;PepKa&yrZjyz zT_w*PC`NwhQ6lcIrarFDcN4oMcnSy|6#3Ow`@QY2=B*&;-caG0SU>kPIOA52U$Sj# zgWV~-ZN9z14b?UHzTZLQUMkVLaq;mPrkyN0clJQeVGb{ieFYH0_3cfS>731kSni^} z&Y-GDwN1#ZRVqj5h{9pq^AjRZ1%*$~D7F=7enh{o5v68Y^X5~M(oZ^RlKRf3mrbe9 zF%L;unBMJMPg_jjuPtP}JzDX{L4hS-^OYE?Imlc)oFe=7?YYwjrkvPFHNH&K7zB#O zU9z7iMb-hfEz%m0MYj7MKBh$id*E z8iUVHF{ zRq!s)kN#fFs%c36=dSQy3TplZBRAA1A1KLtut^0bBbWE;LZeLJaa&&eDQG^a{t9Pk_(p{gL^R0$+OOuV?LsTglyb%KG;E#LUnLkZV zJ`DT(jIJ?Mw_WsuDdt!**?rJb>$~cu3+G-haw-G-B{z0 z!8fIC%9xU{tGPpGt~Lwmaws!YI!oZ7IV;HZ)wn4?A&z*yDXI`qP1t?({on3k$%IpcP!`m!~Zn zI-1&{P|BNQDHf5>iPIiAS`CX6cw$mhpAP-!Ec3rPQlOZ$KOL(*cr2@WQcVT%L;t>|Z)y)^<+sJ-vFe ze|m}9k9puLR#>ypibJ8^mLD={H`G&{AF$P$2*!o_@P{PZ7DMoqCi}h)zEC~aIucH) zUef!(>&Ze?thM_ixUorh3=RdmJ0_l0^pO5Kc4~gkdE(aAJ$s}|8xF~@=i$e}fA2fT z20>1_$FLZ5VXR=JIa&E`2E z2tsn=ivK3cm(-)^VRpsox*&!-6ma$odWy5N9EwV$ZZK|YM<4#M12_l2 zvV0nE$B);vhJh#OKeS@^#uB<$_U@=}`{mp%S%OYHoXSz;2qUjdIeIXP|5W0t+P!{)Nr1DrGPtiK<{^6Y~PM-~{wN-?rZClB`_c zh_`hQlA$R9@xZ(ms3)5i%=z#&T;mT@PLH4R2@Nw8+KZsZ0oh+8)lk*4C46mP8OwbB z$V@>!pJA3Tr!u#&I`K~vyiu{>%*TA+H2Q=2L!k|U%szpJ1D$IX7m<^}29s}(oGwm9Z+PL>x8FCO^{xQ5<5 z8*-27uJ+?<2bS#mYNCw_N{Vt*SN>pjU497aJ&Z&3aHVY|yB^7R>3o3IV;9=X1bS~T zjlocE$s1smXNJdTt-K4mJ9Fk+v-6+92XNfNDe$v*r3==&=3?S|tXyeRH$Vq}_&L`! zk(kaC=8aLs5ZxIHd(fKfx1V$Ry(r@0Sasou68p=F9~rpzJ?6khptnXxFtPVz z9XUTb^-Fq|Oz9Ff^Y`+Z3d$;hVU^L{hz+!zX-Jh(W(GwDjv+2av~3||gdgrxk)#Tq ze#BF+BZ_nqRDqOd-Fq>#ZV;aB_xMbnesFZ5!4o1me?P-&V)umqqR4`qfypxgF}4yH zu7d|3=l%bac^@0~{i@uiWGrJjyFp^lH#0HXf0N9kp~%zsNtZ2ucl^wFpie;KX3hQi zvRfl|T(BKl@Ci=5+Uf?XT1j~v!g5%v+mpCbbs~U*!?5$tgMS^z&sY(O3o^qV>UnT$ z9MBE%*p{*1$tS`|kX5*g-sCUW)IBxeNiY5ZX{82$A+cX8YRQ&);TL}xMgq7-)+aOR zdGg`-8w!;Hoe?0^imwxw_nON&E=}mu3;f5YFDNg$1dEdIEONKwb7_Cr1yL9CC@#rq*)$j_*zqEh=1s{k#F}m2VbO4B>{X@zZeMNmsd1tptEqaK}XSx5F(3K8Em_yYV}8q9mPE{*w87LTk|cwn`_V@x*=D` zT=Af#w8@D;Wil{Nk)Z(eQ4qApcTl7Px3xQ0btlN{x zzt7m+OdRpxMqRSTA9jJ@!j9ODDk4P)&c2sK+Z32kYIc&Cx6ALJZ8u7p-;?Ob#XktJ zqfB|@FECKP)Bfo@CO6^1OWm4-Q))3#q5s@hp*bY3F_VSx-~2wGr9 zaWv?&ZYg##HmJyIDh#@Qh$!g2SHFeDbl*){F)Kw6Z^SaEWG>xU{a1G1l0i<4t_t#Y zoiC?McE}t_{6B)2GXl(vMk%ZR4MgM0X*Gp*@&{%%SV()!X!#kn=qy`x4o3?RYB9yS ziDaYtqu(fJYKlHOT7IYrXz)yP^u7py1o{gvgbM;&80Bh>Gp4j656}B1J9=ddilg<4A$?*%)eD6%N;9sj6}X zi(}Tbw!NGR(kTqJ4AOPdKE#;{u&m)T^wgi~W8$fV%Qv(5$o=^^2NAK4wJw6^4(Y5+ z3ICEc3v_gvRbb~}l7mT?K^|{3xW??MYoUEODYiYn$tcE9u(C&Vf0{NMuP?hme@R(N zV8va`bwNWgEN^&?G5wMqEj5-)?Gh?yK)*>I-6!55KEggJeVs9pIi3d|!zbTZe!RTt zXW5o5_jFbT6!cGyE4*oF!q%SqVDZOmDF&BpBMJ5qrVZQ>?d9kz=lpAP3El!>AIBqC zl(wHCuH5ADe%ax0!Z4=C4-))fT`v#u9iOe=9zw`6!c*#Jotr)aj0m>Ha-ZZgU|UVp zL9vl@au=2kfaX{{jYHwc;DW{qpORk7uAw6H%>f%UWvk~g7b|_w59kgj3IcXz=%RuF zllFwbF9#kH+{QvaXZ@>^GfTF zF>X&6DR_VIyC4G+TV`0>$dQwn;U;#Bm{Bg%@6s|%0z?QoZ$ra4e>Xt_I2Yz}Q zd`9A7!OlVp#okbP+(os|qkQ*9g`dh{xif?@5Q$^YHga=O*pQ(<% zhUPbWr|^=Ig@=xsn!G)+K4Q6sISTP~ALpx9YKGX436cW+zDp!h{pqwxub$C>3=|E{ zc6kEJP0W}Kg(Xw#uT1Fo-<By?d?Uo635QYjEA;5{+(>A+29tO&!TMPy_h835}4R^moLjKso}u-{c$2P9`83 znGIV@pFso8GVUvi;>z|jFV0pYVw?GeIz!;#7x!Y0TH$WcyJIK+S~D-+X93dQUl1yy z^aXUgb1J4LZ!6rDKh-H<{^&U}ECd$xhrCZ?(c9lC+?ulv<7Df_x6fACQ{}I#rG(rV zLEcw@jwUY_pSKtzKklRaPgwwnJ+Fn7_PnN1sC?RNBp7(6G-SD@#~|u z7}KI;E}n>Y#HUvQU5F;^QsX;GKl?@B-~mrrFn}9u^?aLr`JhHRu(|S09jz~zOIKZN?l z2o8!cntN<>_YR*9Y6&RKx?Kqdce6kXKN~U`>F<3|Uq{59-Ha5NpD*5Z0|V!If_2F0 zETA}gv`>|(oqN%m&$ijSq*|U%u2Qf#(KzX90nxp$ffQW7@r5Y&6hzs*YAi*;<;JFb zMKoJ?tIue+`UM!72=;03DjHN)v@1pFfLwH&I)-FMITN)(i21@b@82j+vXq%aZd9%H z)!DgzZhvk=X|valJ(~tOW`$1CQraq#n!UO%B zkQpiWhIf+)RBPM6?F+)~!kY6aww!hmzo{Kezj`>3WGQH;k@->3O|a$ZGN`R14+o1PSQ0yLH~kR@Fa_p^ud?0Y*<3U(?EiKu?+D3p`5=DqmWAsAyJG0}80qO` z5UTC#{rYnQ(NjsP7MJG&OT3D`9+Tj9T<@YV`4dW>sJp z6?|Y!RjAB;kJvuw2ter7@-J-xPU+3KMaJ{t0r+#A6|m3Ki;ivM zm7eJ9urViC?`2P0v&vIH`c)9?SfKaWrTGk8A4rEc2aS|CLq8appBjb=NY*TH@eZXu zwz#;CUFY9+^)`ty(h9|)W7;KXEBHM3M8iwc%l-i4N&URv%$1&Ia6RT(cmdmA&pLPK z@lI{Gl&9VYfzXoEeGyPFV46AdlKbey`wS|+dK~}}@t(axbdg9((6`LMm0r16GpiX1Hr@`Une_90KF!T5O_0=`A28xAl^CCwaHSX| zBlZcksL*E7@SJeBs^|yRfk1ob;PBT^=LGzjxMizDdmQ@e4#sFXgGkrVXz`0B!I2A7 zlmI6iwS0Jg4&lkAeAVpD-0PiZv7bmF1-% zklZ@@{J76%=^hw{b=djM`jbP}RKfR7JyTF~7-dEYTPcbm10I{Mt^-jHcIeNu>L@0MB zJ9QdzJ*zK?f(`>?NT&s`&^)g8H1JQR&yzg1)xDe&D-1iV0R+&rPja6G{|fRgF)wgg zOGDw4IQcAQCxF%qC^aO`s|)+s;s~qqi3&ynNhA#ncImif&LRE$X+D+5 z6D__u#a%&_DT|Cs)i^5U6fr%HzMVu3Q^>xR+Lve~xc8f9EzpcadRE>EPEwEhhr9nO z(){!7GNk=`&kcWE-ViY5!ynTLv|~&DNF98`E?G15&*JtV06MwfNcTxcpQOxg!DMS5 zOmmk(YXo94_^1ef;kqT z*uqiOSntq|E58q@DBlA``R8308y*%0SLucRsdSU?MK&Q!lvWT*E2Zz}N=Kkst|Y86 z9sHKwcCNG_p+AgHUh5&|wT@tlag+A1$GW^1@c{T%!H0|ZB2zl7Fcd+9!XH_0-wy0a zsik%B#)2?r>vQyRx757z`cc_ucd<-g6f%siX;qigqP>MQE>GHt#CImdi$j|RTnh=& zes$b4(BB!QzY=nf;4-Q|J<0!Z~xd#_iB z^_hkFTdWw5Z&pas)1C-ok`cn!PwaN>s8F@pHG+MUFqan6QiAR`woxZk<`1IiKX3~Q zYxH{M5gJN6v%FZ6`mlYmV}y0gCY_pzbk$1MUM z&%D3mv}L>Kz_~tu0pi9G#PFrqyzhSY2Q~gaIb~9pb0Bfgj zKc8F+iwb}@(Jj;@$Llpa|2+%jZCDF4tdNIdViB% zWw-}uS}ssLTqd9CJoYlfm9G21H7|;YGk5WB?Y=gHSG7-A?fCXL;*+|I_4&zNA$Bt^n*viMG&?&;eyI^%G13aRjs_@eiA_ZbO;ZT7 z6Rh#k^SMuzptQ*bqT(W z+`&ne#(y73q&%9_592YOKwjwV%7T5GJ*d~;{c@p9R7A{u_wfbbcD@FxSfnv!&=wpv zao&y|NMT^GQ7vWl5ih51bu&oA}GMhKJAys ze6NNxTVyAVV~gW|>90E{uKSDyU=^T%R($wAr2Bl;;eJ5#hHFD|0l$HJz%p=}Bpy)n z;}5BR4Mp29l`*qZTawS!OIME4n4F|&xMsdR49waEgc`TZi*<7Qvriau-d>Z}9^Z0( z_Y#3dPF5hs?!ctmTN3tL{YmanXCWKwibO@1!o%a230*eg%uYgn@(@{vA0r+Rt~@^F zMAdLjZk(v0ZOIDg@_;5w)pz1rTXMVwZHGFoCshFm@kC zcQote`^-G?hg(HRr03|0C)2xJg_Pk&8mpXb8l1hkj);&?_&j3zH5kZKiVMz^Xx?)C z=>fM=kHgDGInbrQ9Up-A1j($lg*YS_=l#f$lcc0tz{oneJ?yi!r^Ra@JzYd`RqCYu z*0#wY5;2bzluIal9`{fCll2mLdVUIPk4*XLq1WssQ@8M4wGu;Ybg`W>UcDJWA8GzL z_0b#Vj?pB|x^u_)%$&7{lT|eNQ&rluus#IjdP;z{xb{*)V%LPEnVa-8)&acn@o)uQk zUntXuO_i+Q%fKd48ST^98AxjejaaUwHP9E$7bD&W!^txA{^S`~;c^dp6!gVcaGzzD zi%QoM1N|%-Uul5QeeKZF_5y4CsT2qGK;Moy8ck?J_d(ucztq}OMv61gQ~5bDHg!zT z%5V>h{l(*7X9Qh)9HQ&1DvvitUa6sSs{;%M*ti3OFZr4X(%ILZHQxQVF+>&qaF>Qn z1Lws!4d!Lr-|%-N`M$s72}92?xARBah~#+DU+1r3y@gCNpZixX{UVLpyn$t5+_k(c zRI5e^(~zQ7+w`wL_m$lAo`T=OohxQSf;HNwJ$|A~e_9a!0o{MPHY%XI1+;r=>RSCZ z@3`cLoMA1mXD#IUqo4nN#1_oX##Npfs;U1+g1ejkx$e42WYHNqNQl5PSn4XG_OXej zBH!|D;f6bP7AwEUoeWr3R?++Ix`y&QUe4JPDMtvtGstM^!F4a^H+eYym}GW*OKtog zKO=)BOwXP+X`fpXq)S8QI=%QG+qyLpo~=L&FfB^#Ho+Eb05+qVDs z6fZ>$T5+h779tHYpC8RPyPT1HW}p39A^Wnukes}JNJDpv+f>6*dZ_l5>)1W7WzO1B z%{+-SY+#8?{aG%zd`)iL#dlNf_VrFP;P#iHTbQpZJbUP{U{{%LU%W;9c=_9^OM!$U z=lcFj%jU-?Xgtji89^u96E4Y}CRHVXwhMiT8!01Y9A%G-N9Aj*+_4}CeExzhYCAPc zN9oX&Y+>y-*FeFReP5RZ#ns*Ge)ER@f*66md`FMeD=OP}M1p!gq%X@q3$yA^1vajD z;;#cXN_*h1!VOBqIEyCdK^|bK*m}Pu<%M*?E)%RuY%DgX=yEI+0{iVRFXd-(;)h>< zoWfF2QMG9BKOQF$c3(%&4N9|+Dm9g^>A8bsqz!6vdeuSX;6)ksreELrX*u=}<&3W7 zPwIO|t5Sh+9^CbM(4y|yy(SOU|Min=$O+^`)2RfUzp0<;xh6tVIlOv6V&qJ?l=oFR z>+Mn+ynrxLk!L2}$|_83n+07g@YNV~MnbbGMjJ^WAn(UqAY`lloxRN*7+3zZDc%=Y zzuFziKDwy7HM z*b1YuKXB$hZ|(D87?$uky!BtAA9uHVMbh^UNdcgAFn^GgNa0LSKMxGHl4#Q$9uM|R zv4yidvY4A3;cc)pGS(6`RkCd*^ml|!Pt#hYRo8d*emp$pONp84e6mr-M9Qeu`@MRO znJlF6I;F%4Y4QBPXH7T-Xa-|cVxd2EH(n;Reh7(yH+m#<^M$ZANeA6qrP=(6z%xDx z_SJm1u9zJZTR-!J#+%8ZU_1Vss7vn0~+#%yn>63iDjrDY$DrqUgC*B&u ziUV2Ynt-kEjX6K_K_*nyg6s4pUT?wN;zIX*1xA`O?9M&jZ&Sa~P^^jx_}{o=8>g=GsU*C+R-nDbgeA}QirJf=#;sJ;G}34w~<7oF}& zQY?jcnNBIp)`xvC>~j!Hb5d%#H`~9S;#e~H@MJ>Io9rhS=Lf`Y3x)$KaWAx6z5+MZ zS^Z!RI+CQ92&8NXrdZ%aBThMFtwDXjbX}0!z z_L0?;;p5n578VQlkUb}tiZtAH|0vj%K62*+e1~53>o(grY1nx)%H3=(l~Im#a@2x? zBw~K*MBxcb?R}mqJ2^J8tInRe2SYOMw}g}T%0IY8zpJ};Y`@T!Uu5v+^dhqN+5Tbt zDGyjmKRjvQz3DFkcNIugIlOSFv%|{iJo9kx5f2ezUcXy{gO=p>NvwG%9SH7G*#Om9 zk{@?{g4%MLJ0}LY-5RS-f@wq~p|ffT*d8k*USC=f+E;FSOl8hvW%*zzdjzZ=SFGhXB2Zs5Xy( zF2B9>wcp7uCY8oM?H}_onFICm2xw#da&X$4&jq^LW2*P_l zCkNVfx@n(i;WmI?h7G@cRsOV=GVDO-(Xb@SU@))Z@hR5x@<$vYlBHoqCsvBrOp=pTS)`;8|c-8p*1)Ff>#7&-6fo8{$St`hT9Oaq|AD;KbY8dYG+K ztwwhp@z4uK(D;uJH>S_UXYic~*N3~0y*DMvJSaQjG-b6>S!TROq-mZ@(8U5<`4E~y z2b%o>M3pO#4k$pOchv;%bb|P{Io*h>I8(p7vDCt6Cc}?Qvzy$0j>6&nKog61MKOf%}USY4NN_K%(J)Yfcd78i0H z%~sOO!@4+miO0Djav@ZoyuB}a#L2 zZo2-LUPyI*7#UB=1%>(shs;8H9tXdBjrrYqH&Xy8`1@?$z4D@BeH9mWLvYpW^VQe| zG(t|@9h(1Xa6A_5;8F1Rp8cu52;|V0n8+kR7XW=|+xE`a{#>I~&fbHfIF&il=Qa`@ z{`(Ca2k=0+9LT5peV(sw{!0?Ki$Gs-zD4Lo>0UY(j(tr#Kw#RsBeD7YW5sJ}k=yPk zjNXca&6Q{PG2w}@z|%Lsr;jjFmI0wQ$;9i2t{n^(f3;P2m{!0-y`BTvYY(B-eMO3r zB4BP?Cl7m$V1GEjOG$DPG==PJ4gPTV0~21u!*_fn_h?2JXg-sPUz@k{gV%>09=uO% za(CRgRuaC*`gX;iYA;WgRcT++e3hI1ruangsT9j;=|6la91nmP(xln!%i52A=-$tz zPiGz)&KuJ{ir*A2IVJ-EI6s4VI>JjuP;K(1)T#Rv_zfP6{VeXENc)H!BZruAZ|13! zzp_S2n;Qf2fTOkV4ro+Fb^YLX~qifu#VkZ9``NDJ%}4NgECHEMdzsFi)^`+klI z$Det-hxL*hC7F7-67oYN>uMOSyH^wNAhav~pkCrQQrx&C{oKnt<{`KO^b00n2Nr+b+r;U1rzePPtf30n-BX5dZ zP*Rj6w$b`-*x01r*}jmy8rXcM0qcQv-Tp35tg=CLXzn0;M+80~<`yin*BU`~?&J?O zDDj_$+TSI1btFAG3VG~d;`veFZCLXsXK4S$> zJDn{CPpj7CC+q zR%CQ5HhHvn84$4E_yMRPfl_qtGo7B10BqqPHd zrilmHGBo!+mqU`%8dE&puF}nMbG@$HH`?!%&EHqiT7KACJ$`V0D=jYjLxCB-MDp=5 zTulfYq`CH$;$ZnVm0Oe5(2;1n8)vE}pR|45=t&0L=fZj<>Qkazw80xngA%@iaHJqk zC-#b-vL_pD(PrM_Lm0SCSV1=ztt$CWWD!V_!$IBRd(w~f;G$@6m9VY{Hq)e7q+9Yq ziaVM&3SkeXLiX#Q$iTiX-nM|yD>H94-2;pjfBcfAg%--Yl|L0RCzzZ+AD>S%xLzLk zr0^s=GnUlY8_&@8I0QV%Sya0#C4{C)umM4G%8=!A=EnO}SGb?V`-6g=&#yNpKI^aq zGqHP{Zp%?Ldf4yZ&Bzq^A^==AGYfTkpB#pOH(vfL1zWyN=9~Bw?_WOw?cAOHn-xif z->R=LK(w-)UkK-KCutF{Qgc3 zef$Y!@-5z~4c6PgXEqQux>O9QAZ%FcXDYRVG$Up_jfJuEm9>%HVNVHb%;$KC*1gI}I`)aVaMgY{8n&dvq-f z$32+fqwerIiGRzd`x@Chbwo%9*c4lLUB?1_Bb(&{^8LL-M(U!>1x-s~dPGt{8T_{t zvvd zMUMw?ax$-A1oVE%o-?ag;p;sScedgmGV_$EHud>U zK@Yw}LzeEgnDw~>&u8*3@Cd*u!8oT6a3|-mi%$2IFsIxgy2@D1g*K|HwU}V>gRfvNV_;rMXfEn<6?`=;t2$6OhmDa_Jed5O7T_`oKH{a!Xpy$~aD ze^2O!2Dx$%lJ@x!os%kkR{8hh^q*hUQd}iQJOK7!5paMIy3{WQSRgg6D5&l0Y&wIH zzdPy#tltkwllnCi$Nim5bX?43wsu-y&)(=z2K7irje}(rS{3mG?)CQnq%=0~XxkmP zm@sT{8=SVHcrZ&$>C&_8Bl8ibi{QfwJBlTiPpe0RgAE_;kiHJ!=LrS5KQc{XPv1-Z zqz}jHIKh_FA-~7^$5O$5H3!;U4#9fhlx>E~8x>ZjaK0#qn1dOa@HVYtrQb;5fC%MQ z-mF>oC&u_*VA~;nNBB78DO&EyQ~FaA3VyYiO_WO%{%FbA-pV^9{OJ_Z#CM-g9NfXR z3sy4kqN&40_oaU&?+?J6UI)cVd0IVuA0zUFr#*Tp<|_)Ymyi0r!Ij(K-;=Q`orT#i z{qTPA)3aJ;YPZppDqiE8WO_p8lEM{4(1Q!c|NWJFfHISku1qv9O`=C@9NSjZe2wDJTB z&?MbUL?$v{=m9r)v4oP+($6{PM&9;UzS3nWL)?DvD5=46#=sPep=M{}#kH)ft*V@V zQ*@%^P!UBdZV)PH{xFa3Q|T-BRk|EaSc#HYB}?y{5x3}zEZ}2--Sl4%gm+fE*AFJ7 zA*lp5jx!02YN20ZHr%K)TB>A<_StuaPHiu~?8QL)q&o~e!~K0>n3(%V`SmtW z%+0u~L=_FQ5hnA;fg6%UC|eRSjU1|nq`z$`%Whg(p3g2B<@*Z9_D2ObCqs;gUxkg( zOj)P~f~0PiPpIRt@9r)$GIKHWo^p(8-6(9HG-k9`-9onD0<&{y+s$q%C@1b;{YFEP zlfNq3DQ3|`YjlX8MxV;>E?R0ng%Q6eDT%`x2Q}p*Hlq6r9fg4cV6f(%#bF~c8&8nD z4HC6a6sjpv$dBxf^thOC|ETaYvFaqWjNepuS*AkW(X7^o@#}1<`D4$lXF(S( zMJwfSbD#`?va>}mlrkYAQ3{N1Atg|Z!aq>?`Y7isP50T&P?tYUkiPJcv>kZq7@wZV zqRzjG@M!k!QCi(>$9)NypBb@E)90v7hIwulrCpD{BNEH%4{kfBti1EY5gxV%e5*~p6{IK>HR zu*X~x{>Zij)BWWY14NCF>cZ#c3tiEGMn}I^YuN(jSQ;(EmpIqh%VWk1tF43o$Iroy z#Xc(BORH_IcnrHi|FrbZ*b_Vo9<>y$w(xd#XV(e|2P|#FT@*!q-M>}Shh@AnADcTR z5DcyMtsKg;6T62C)S=Vy&D__^!xo!83Zal=^O5-**&zgn>yyki)-weV`&;+uCx*B? z^LDkIQ-=<+OotW_f0cmB3$qvPw*8418(jE4u>A8@ATx8r;`;LJseCMHx>z@R7Tj2| z&=<}uFFZ5C|FkqZM1co^k&jCHD>Ea{xib=RS_F5Ed}fxS>zeWmzD8 zq1@STPzrpWQ}JQl0j8gQ_D&2a_FmTWy{-$oSjsi^(fwZ;4aJDEmwuQ|d)!C3n&F%? z{g=q5n`SkCE1NM*e)-KU&g>xlS9uMmM%&NP=S`PF-r`p&qw=MH2v zr;yiNzgP~Q9y;+)gKjDzp9LDn{eeEIp+t!5Las1>o zPn1i4BvWP0dLWK4^yK8EC_fHSAetL&CUxMMDFR8&SroCngHWQen z2I3h+(qy^_7KMF2u~EOqY#<1-+XI!8z?Y360R6- zzYh%6Pd$IjQ(mEkN*dkFn(c4XH9L>Y&ry<9sy|75VgH3Zs7c0r1NWAUpDC{Y5T*MC z9Y@i$j_px3s=VSJ=lk;iB0Khcc(3yW)fpf{`Hdd|6s>Gj^Gw7abN(KL4m~NU5%t{h zS#7AVq;z!OoDUl|0B`7{0KJK}$0w(KIdPv0wk_Q_g3DfHhNw7AIP1SzTh*p&i@$TpG#Yr-oq~aT71>6&OKb_vwB3!dnmjJyXNQ zj8dN*Ud(NVxmg=WMg^xAhAVW%swA2sUp9EV&4Yp`1&)upU`KYt;>OE<0r&+72ZUK) z4}430+c}nbfepR}v3wNaI6F6GQn4>nl>9(8CF40>?w%oqfiNuZ76Rn7?jSTTs5V*J z{rZ}a!#Fm}MoH0y;9TEBxbOh^0JJ-NdQs$fj-;E^u!mztq3Td(uCSTW<5(!Z36|9BbRQC6wcz5Ks*MI(UF6Fo>9k0P?FdD%C{W*~3Yr%0QpY@+q>H)G@q1Q7s3TNRS z*{silghuzLQ&RhvZ!Hn#MST~`KGAhz&-vMTa<0kSjLQ8=1S)9{5N;9+Gu`*6+&nz( zcmh$YxI7L}f-OhmV#tNAJCMHqJeAlK?Q^3T%lq*-<9qXG>|u15 zO6t_X$~KTUgXa6L)yw#F?<1K0y5E3c%Ii){n!I>l=#bJ79(78a8@B9QP22i!WPsf= zzNtm{5c4?`f?0*rzt*9bK=qTc_Us{o_}ixj1|_d^xBqsn9@-%|>T;t!nVDyo=y6eD z`y?yO3H}<#;xRq^H#W7e&pT{k>#?$&BR}=CF80!C4>M)*5*ng)79f(VAy~(Ys7G3V zUb`kbwhuIy;*sx>JDMFrmNy_7N?iWM%>1wXSSMt9_pRDHu}fP#?UjWe5^rxL(H=o^KC{a^}+q486c0{0HTtXihEQvWLh(XdK)F5=tlcVKI-?(IY^f z#QLzSLIsacfZNQ^cEwbN^6rYVr|wV#JZLLGz5~yg>`ezNNM9DRQ&9%z=j51GSumjc z8FjqZ!qjjK9Y@Sg7q~T^*H8TUlvj0HFIb+0{S-AiusYx+?0C6@VEcie09wx;(d*F; zag@Om_e#yf^+Dd2oQ30u{1VI|)0E#m{QPXdqH`=5sJxwAG0{gue7Eo(eHvU(wIa`U zAN=tsrvW5M-(V9;kpVC6Er@#rQ~(!9Ot&rUD2}?#(TRZ`8%qc*Z*(n%t~ZduZ^Jcy zwdw0nW_RhJO1$*Q*Wy9HVU2H5peUX&V<=>+BsovmVP}*!!d~TmIapppSm>S9dQNO} zVV|i^)i6gsT9maO(vEWZX6HxUJzodoF!(|5foUi8Bw_#>Ws6DM!VQg)z@2g z(Hu>Xw2XiFf95O-_BsL<>tmeyec9HC_Rf>h=K)ReSK2=~&wzHL<9EI(;_c_1ZE2L+ zFxiUSgfnL=-M0<8NN&rAv?ouSiv1Akpa%E;&GwpBUiBy;gwKj1G>=$nA4<&d3mMPg ztsLhOc7(J?KhJa7!G0<13>z=0UP=2YGZ)h0$NH(f^G^VLu>)&j;EEGebx)MRJHdB( zN&BtXTFWJ&C++Y&8!fSY2Z!pn;PJY|@KiH9a+C?;c)W70YIfX_S)par^p&n*f`N;> zIFel=ZPZ^bwR49wdE4*~X!B%QieI`e{1@cgFupOB0Hk?`*jyYwEcNlP9}|tQK&Gf( zrYIk4{p|OfF7W{E2x#jc4?oXkvYEM$B3RsL;;Z%`dFjtLl3b#Ged;qg-CO>x9ewgA zhuw2H7w(agui;`fr6txt+*tP8z2Z337G(H)nVr{k>$pxYYMnPD%4{-tgGAfqe}E*E zY((6CO877+`SdqV`>Ol3SlpUHQ@UTDu=6#%3O@&XDS>sXaY;|h>76dONKJ2oy?9U3gkxdZ|kyhViy9{R%oz)^<$Ida54Bk5(DKsl4)+XlYOr zi}o$Ym#*?Wa_`jjfuO9e%NG`oDSU?UqcsZz2=Q*QE+|VXp$`EE+@X&Hoq&Uf(_w|P zw6X}@o&y2NL8jc6d6Zlehm${e!jV6t2nPkD2%K071 z9LOL)Z|=A>3Qf%H;}0)b4$3~_f>(f?jo?1SmUx2v+m=0j`3p|?n;Xgr9A1_5+j!TR zTmLnd7Wgi#Z8O>zRx; z`$AhRcXSd;I^NRkX+c4HpW0SOTD$!<`!};MCw^3y2c09pUGXDuK1cs>gbHRA(!PiI zz9UvUJ;cfYWtI7y|8aC)TZ(E?6#XS~coYN-AV`KcK~R*Oee_W5YYYo?j|WG!<(av2=xt&pcTb7mpXD7b3;ddam>jjbE8 zyP&q##K-m>CA=3NPTTLc*7v=*y|1m=v(S(1^RQ|e)=~+aD||DIibuWvNPmJ)m%$3B zy>M(xbtgN;q#d>XmdG<-7!OCdwwUUg$BwxsT`ep^%%9VXd^cWHaa$9_Jhz2FX1>2v zhykK6{<`gVLsVGeWs!D(k$OB(oS$lGJV!HzIs5TrovtgIgn=D;hiU6e%~qg z`;f&~74Dn(B2t3-rT2hVD&)ycOIXz&oCt2uknw$oM>$!_)B9~T)+x7N6uX471_p1u==295f zWtPdDnAp+F8rl%^t()YE)!@zdfi(*r2TJ!p{+oJ6I``qQ;Y#+0=cDfUnlihwy{UMA z$YMC9fQMOLMa9p@`HZmaeL9&ZYH%?!Ih4uOJ5lGc-Jem7b*%s7@he|v!L{6p)W4#NDb8+U&4!l5|@#hwKzXVJ)8UI}m{dvT@iudKVm~e-Q^ea!Y23vD+U9Sd4264!!!PNl=}lL527^11xE~h zejajq)8o1vlKIE}n#%skL5BmqQV3(-@3JpwGN?`q>Lkm!RVU2)E8h7?66LG=0GJb^ zJ;~=}4_fv*O`H0T6o-w%=;=I(BNOM1KJ|g??`>rrMsUVv0TCF z`uk~L(baDmS-e+Gi6+0aDDh^FkQcNqkEK|m(i;>7Wp&+BTOFGVXR^1jEx+Q8v~PkX zw%*lsE!1lzLo%nZc{sQdRc@w$S5kAE<59`bJbC$p+@;*R}0@8`!!akbVGXfwfp`GY@U()G^BjlDM^$=g1@ z7bP=BMIVsPM)p3Ib91E$W8h`$&bk_ZqxtkO zSC4^6wlvQ3*1!&t&mQlmaS}QXSDQqYo@KiEnW^?`FIImegL5b?XD7{DcwIYupgqT_ z*>A$j!DP-Se$E_MXtwb731QHKQp`ZZKP?r?H|#0+a^OBRaF4iJRbK)I%zgN9n)pa2 zVhZ)SzDNv|Q#8667#O@u-U*sRoRo|fj8GebzTNNHyGiQQ$&r+aev$MIyvq5JmJRjw zGt8rYq75QgTiB1k%4GNSOqTmVQ)#B(vybDOj~d31lxgz4FAu>T21%N)fXZp#uhQlE zKTE=(*n29PGsoWcn&}=}2lEy9`iPXN{Rm!@OKs6|fGtPrzqGzHe&qe@FUikP<{{>` z_Ref-t_wt0uNo(f!MzjLeU(2S-F&v$un4Ok2yOUIDos|&>hcN_4qeZ1-ea!<4`{x8 zjtw?>DP*DCO6o&AIDI)#VB+2`t%pL|{!zR?r|@UtFROqoO$wN8S{TyULlUeW(AJbf z<8SYeeyA>0q9?16eQNHoSWtHy?ymbAF3sd9*y@0{y(xSa5cIDvAwPzaVmdb;rvByE z36`~D2ybLZfSSVUa%*+0^4!Y z0>Bd_xG1&zRsZEs6tpB`11k(OcMO2Zdk9y}v*=X=e_;fYi{2eTV$qVLCZ@A<;0n(y2e^Bst-} zmprEWa*v-_1*}IxFtTe@6X7sw$HRMIhevt!Rlz#^-c5IVSj2_xi5b)(TAD6-`E!Q- zD&%YBc-Agq{5ub}6bKPXwQq|xpj%~1vfhcCF7uLHHmR<;L(%sKgDI;eyi`_luWe2ThkIG%BVfY;W2UiZ;{ z`=6{VlQUos+}Lo9p!bI#AK&2P@C?cU4F4A|p79Im$6%v_>@6?;$=_Dwsb@Ay5=nc2 zv>6dLwc6Vde990FX|%Qg*#j0HA!2_YEOH4FM^h8}9 zsEQ=z26byxN*D=9!prBKq>g}WB~$K%UUbeGRMFyNO}<9Rc!e!cbIdm0b>YpJjA5p5 z&^_)RInwq1YF7B@HS|@C9xR4HUE6S)u+l1Wy8pL{FO=~ks?!B~oPQ4j#c!WGms`Rt ztehs7W-cRFr`|rduYwoG4R4(CXwC`i<0DecR}eo6IKKcTCl8O$&Er!y6wlBFkA(I> z7b2>=;LM#omwFUA)fum?i{B?qMtXGYpqFlPdsL4^P{kZtHSbIX#87{UI`Mv=sOT($0;a)9pciO7*-4B}CT%ztZ5J-h ziaHDrBG4M6auN1$wPf#UbeD8cSytApk%M^B2Q#uDD61o!g$`rM1Mnzl;rC4knR6z7 zWoOO#ej8nKN(TTE+-iv9t$3su_ZzRG2>BjX51kae8)gAB` zWuB&vBfZvEb{^orDzp~lqRM=Dho6J{c?5dwCftF0KBQ$?v57K@a?O*mo~a7M42LtF z3frqU2au;G2`oQ1{<>ru$x4`xK9MyG(0rmTmyp{f*^~GMX)GYE0VM`?2z42U;t|~a z!+RW@^9X(P_55Se`GMqkGF4;GbEFC*rV)Co`#P07kViQa`yk$SeFnVHh+yA1$@%TF z`mzbwT}KwN@DZRj3ryId?zh~&QPJD}VXf)KgQ^mD&V3$f&+yrc&QG@2Ua5xg;jam! z2VqkCO;2Ppc;|@QQa^ZQF=_y38~KV_OGbaQz+gLW{3U%D9%hy!Rhdmvl_eTR2x&(C#m&>KNDINq)Xd*QqC1{TGZ{`!1@`pP?g4z7!i%yPjZ}he`5zVX23yR+0kM!LS6<$CKAf zN!nM`Xh7HTq6AMwYAc5Y2!DHaCn`2L5q*GtdRkhmqjOBkH-7*!d%^?u(>C7YM`@4665A^q5x_@3Drqg2Q+(D^ z8eSFOP5kbe-TAJ%lQUypqs#lOU`HXW>t#HpsTOlO?CshM=)!dv==Zxx_4c_l>S|WP zZ4UPXvn0`nS1cM=KxTEGscAgNzwRqXZFJk2R~Ycf2|GZ3S=cSFu71zC4HZw(9@u%7494I0q{wC-A*kYX8Ta zM!B%s@S{Ck%bkyzHiWXreP1-|s;~&C6{D9i<4p=PIQpYLVYS9UMt!}vtFrhq`Kd#- z-n}(cawec`#Jf_zjG-|81@k&X1RK}xGt^$S`Sp?f1hwPahtnZGM1HW;!FaRhUEHmz z+iyC5uu9#(kjoI__l-_tIa=8JtU(y&7RD``CgIM#~zL&2c{1Be@Ho1w~Yeng_ zg{|qB@a?k`s!fj;s#SkQ+B{ze-_`E?$s603Dv)+3Y~)qhx?(afD}TEGSQza&N6;;; zZ>FC4Vxx|j;HU86@3E4k9-pGCPP4vqEN<++ll0@bA6xHHFY`--NAZRogfcAU?-=E9 z&EORsUA*tT@N`O4z3i2p#-_4AFlyh00r*wR>^?R1dsJS^+U6F&oTSnS=KeBUY)CrE zRKQBw61AQ$|Jh0{ErJ{=(R)u6cE*ROj7!vzUKS}~E2ZM;+bC6y!;%^+c@2BYaYZe=v%@|jrhRt> zGA}Ty+1Tdom@(e#bG>tyh;>ER(Jl{1k7mp_C$l!(xJrIDK_`Z=WE|>y7cDp8rsyLf zUxK^#J)Ly=42@P4D~GGYgs7rH;D*+yO4LM2e_s|O2K)TEe@Re4ZO7t)t?BMBY2ji^ zP%k8t--~MkLqmS1w7yXe((8lf6$ZC(oOlF`-J3$MTn(crk`Jtzy85Tk_^~R<=#-)R zFFdH=^U~xeg6)29K0G->|GH1Y5y9kH+vR$U#b zbM}P)bG@gyC%}Mi@BjM_XFd;>Z4jRz^5JmyAiRAajH6m)#U5N9MI9b~EBw*#`E9u} zK1i?~9woWH#fGf0?{^rm(NDFP#`GYcT4EC&o1SD6L|u1(iXZh|-_CT{cLdHxrt-wc zTJ{xJMvnR#fhrpvUBFbCQ1JJ7`2usI@2*Q~?`A7?-BVnmo}48$x;03TwxK~w-j%_ky;@9AHXWc{5{RBaV?qYnPFX{h_h~;wT67jM3CA|j# zZ{N>XWq8Nr3Etk9QNA#}*Yp+>Wq&vvCA+65gBmm(oT%|wM3Cxr{6uJ<i?WwI3})ZE<=(HLMt_sRDjW<2sO{+B+Le z^Pgl-=3Rdj*p9#xykddFxDL50(h5t9Nfh?n$|xn4Nl05)w)5kvQ@MmhRUc&?x0-zj z7EbU#x%r}qRb-&o+k`1V$i`;=5T2_V$QC?@R$=zS`q@s~E^n0nq4MZqZJT4Z!eCQ3 zCi{H9kQ3O_*iZeDJPn*m^}*Rq{M(ZCx$hS#=(67sNjA=;oRReUeKe%RlIas zBt$OE%&A8ReUD=mmU@82@pyK>Y;@J4E4&Y|=VIRAevQb~qrNF>p7=%_oiisW08gcR zr2~P6I1GcM#8ldGjn6I9HQ+Q27T4#rAr{DSXTDD!lV!E1Ufeb&N3yXm^BmfQ8%#AA zkinkRiZ?3!u(%`#K(*^6QVzG|qtM@xzsrYszw7tV0-tSiON66l(cXa&n_k_+#o4=j zYB=EDN!hp^qT#lE*{aK(YLW*asLF;}wBxG9`9TYv*EIF~S?b`DYcjw==493gB09%Y zwSCaZW5suW%3P(;=XNemSAT?ptZESRRM~mPR<1_%C@k1IrLEtheCXVX7Gc~3VCH8n z9)1$aW8dz}bg zHJET6nj$)0t2d34yD5MIJaYW)h!K>9=RH4pfA3%3vd;w&hA{fjzwns~o#DJef4E{;cs6lM-z_6wvU~ZYi1jo1+uL zIE(1AspVde0Bm{H)=xx{(-Us?TKt`3Nb~tpsNH?_7QUte=cJrG`~xGem(P6ag2 z*O|e_S)FxO`iCdI7szd^ABvv$tNDXx1{8Ef$T(sGW6+BK<@f#=SXb_?%jJwgKgk)V zCsY?9#K|^ZN7>33v&^N3+&)BqL~z zpHsnDxizoXj62;R=)Q~9vfbws0;N|68Nt5Ykcadv109z>XU1pU`(;uOC`C%HeYz)R zZ9wGOUNRsH?-NQW@v@QM3>pZSk$doLy(Y^t@UI8#)O!RClES7BJquvUnG2L7!{S5C zP!bmHfwBVy?N@=E_=244tveh$Oa#lOo7;ZH~R+Uk*c1K;TgHCm|B9d%^)SMEbQcaG>piW*XA+E=8MTAeUl#qOsq3@{-@~Szs-Fa@I<;C+ zFs%mKVi8_J&CEdkA;aWD&J^ZidT&Nvxs5hQAMB5_RZiV- z=Mp|rCRh{S=d@kPQC8?-YUl%(CYyzVByEm|epAOd#jr#!pV%=RME` zgJF+#-s%;&x{NjT?H~-c^7CyL9UnEfJPSXzf>lVu&s$RZ)7rR#4{2izKLY34t=t&U zi9~wl%Y=Y%a|~K6ibfhz`Z_{sKLho9wSy$!0e2(4Pcm)Yl{CnJYJ%0Sh`C&U)glsbKWIgvFfOz&YHX z1P)d~q&`VFyy&XauB+q&mhx+s_FD{)5t#T-4n7hg|HMjpilX7ouUtr*uXp2%K({r0 z%+%c#Bfy6yE*(fi2Evc)XZ86XtSMFA6~r^T9CJqoodz2dn6X%g?2u1zwLL9+LK4x7 zim|pO7N{*=U`K27m$diPReO3TG4DU`?_@h#)1F(Yx=6ACqacz@XWq(=BH^SD+!^{l zLn*!Bw0?4eG!@k5>ZH3rvYAmC+Od9i20;~PfNI&5h36D^7n?SY*XQm!sNRI<7j`A8 zqW!Mt8Zefy|1}Dn#%L~R$`fqRI{2{nig@%^`)WM-VGl9Xx1R-OI^-Oz&H{6`A^KfE z-fk25?**=2i=w;BzvN|-9p^7q31qT%SI|m1TK9t^c;hLbuLrMr(rJ7=J)*UP;M_iD zg@J<_Tt7gKtjLbM_~Ikz6S{ucbGO^cOY$|Gs8`9ub4~{lLzqJeiZuYFFY1}`CwJJw z)?xO`@p`(dM)=-u~uKzT}`VQZ( zNwEvNX?KkD$R#Xu_hIYlL6nMWwDoCjf_cN#H6dtb-wNid=`u zqA2S1!L+@`7MbI=NRMg%SiJY}7VtILud^Q%$PA$!SPuVSq$@UFm8+QjbKRPX%M!+` zXl~o-lNgY#k{fhpQ-|MPh{30n7T{eQ;{?vi=IX=mr&!?G%Dd7HE^)sZfu*v36)j?o^i)|2`_Buy9l<5Ki|(VB319t2rRgvC z9lfANdEVS1xS<=<@=STN+joVW7;w4WbNVQ^bnMOrKh;ci_e*68@NppbWb#-qIL8yXyMyVnPC*PbtIfIieKfM z-{gC`*97JDlwaHp7ldjx>c9|n+iV-j__B_4Y!9_g^DqNI*$?EM7~gxc8{@%2JU!O} z)qn=mw!U-K<|j;zkjhHY_J9c^v-4S{mvT$})WVE4SA4@{>@h%1J#v{NrN}B5v%J|F~#VA9&Q45FgSdhS!`ElvH%~J zLjg{I%FG~h=55+;*f9gL?Hr9o8OUW1drd2_ykjiVcOr9)3>urj@i?lTJGsU*&QbCl zdVd#3GJnjp5D4VqnS3?IfoN|O(!69N7>C^BLGgKAe@v5V7mU2G;b$%Uw{Z#OVHQsN zS)%EDlO6i5pEk~BSEQR?4%6ZOpz`W)z;3d9f6cTCw;)>myQ1$EWc>L(d+OXCC9#G= z8;u9FA4e4-j2T+TynYpl4{JU?ibM2maK)+wLTY>g_X+=BY*@1U`+iV4yJ?R)FaE+Z zrx#=(*TahM=lVZ*yyGr!Z)iKlU``ypUGFPmXdzW^^a0~V6e|D+__pdh4d1PzggqZU zJ=U0-#-cojtbU&G+-x=XWL;35b(LMUJGYFp;MUQP!p4~2CgZ_wo%yQmJ?7KZ7J4KrgXVU~sO zf0jVI7ZHAxMo@k{ypK0_r}}`&{$yW}?>S|H8O{D0~u;sipBMjA!H>XyT_NAERQ@$oZG)8S4 zEOS=~SISkredF&ze!N(y+l;g9#+8MAAEHU#vYI<&Qxv6h+2AK%m3?6SR@r7}KdNVX zJFF+Wq#g)R=!c;7Hk*|ns?q(aAwK+hczBIR81#2LV9F|HDb5RTSLgP?wW2!YZQ+bT z;JAWf{2_^+Q~PgQf)gZ7zY`J;v}z<+c5LEDwXD53VqNvmo2;>qOWQNe)K}U1myxDf z-RiDRiR~LzN%a;J6FkXXCoad2e}9FKWLR|ndcJ`Xn206a|852y^#a-zTb>NRAFWF+ zLK)OT*sr79Q&-op=|1nltv2kOqUZhADx9__57Ed4FdcLh*J9E`H+{vM@g-pU>yAj&74y_k90gRGYb7exRyLC&Yfb)Bj^<%IKWOgJf~}Z*&8B(4 zaKPgzzFN_G*1%rbSFg4X<}sd}`HQPY+kA*rp!?06MJ$P*O7CH*`l+C_`K;G}ept%z zpi7c_z%fOZ@me3swnz0RBY}A;7_^3wW1)D%b11{cc2q$)J?2Vr%+58r7ez4K{!+N+Z7uNH{ZM7P8 z!{jLvx1U!#VD6HzUtb&jlVK}mYmPx3I-=HPVSMzDC}W`(3Y`#LO7_tj;8?6V8dLG&v!TKByzgexm6(vQW(gM#Oo(DfnvH*ej4 z3M8KN;T4;A;n)7|$T1`(7gBfYv7h{dGq3r6x)b45)&fVzuMU1YALdAcj%=wVy9cQC zgGO_&B_1yEbfLI za`pAMuN4mPp*L7AcXwPs1Dhymukk@=?MHjY>aX68&j$oL+L?NEs(ix48os&qBOsE= z4*`h;#oivj4((-rI4~V7xoQuj=yO>~M*wlokN*s~cE8x>P4ZaWsMrtLkW*4RYaJhu z7LmVTJ$orQvCq-h=8Zp~nsB zbsPijaRl`~IwxHDNO|WQ7w0;ef2DGl#y#L&UCo6g6`3jTh=&t1)BLw*t|vIM$<#&Q ziO}`ET68504R9vmsb^4=X=mfU2?khk!AZICHn-A1w~5yTmg(WfdHl%VVG8ai4#ms< zYZ1=(L%>%((+dx1ag>VNN1)3&g}ybitUHWZK*1HSBGFkv=4qIxEkt zo1Xi9%x13uUkGl<%$%|Tf7P^}f^5(_JcBK%$8f-oA>oVu1 z&2$Cp@o{%3iaNwKk!Qsb6^u58p6}5edS?v2dw9Bs310q-@A@*sN`;`Z#)HI64fTv7 z^Z8S+hg)B+CidH3$zY5uG?lK}KTaJ>h02cYu~(cQy8TG|Xh@ zX(4LbG$d1DI`4gU$tG7I9vt?p}x_rN5o){hiS+9GaI_v6UehKmZi+CEbRV#d%%u}5Z zCK*;EzvpG`P1~a;{|!RZLn+Ooejx}}O`7YbpEakngX1eEH( z`>Da^+}SwDy&Ma}_u5Xi9qzGz8Sdey^ey^nU*Wr`ug5a-n-Bm>`am zNjw1Je^y@Pi;eaLe_r6d@nta!LTmIZNUyZ>bq@IW>m^tX9B25-;!_p@`~ z4KuNC{mWzcD>5J9zJjEt6>ntc9xx2z*YqQ(<=8yoGJyK(7tb}ym3W00QB8Fxd>4Y$ zr{wfBy#z*ax6G1#+clMB{~#?`qd_j$yYz|u49(R{ItsGgQQE+(ZJAexT#sr4En8CI z{y4HF?UV37Z+&R^S@m`>>Zd%H|E%D!i}Nrxtx*7fL99;x@prdcUTb!?$#F4@fv|4r=Oksk_UHgH>7Z ze+kbqasdngZ4WbNfLD6XY%I%?FEFF~ks)f9Vm17T;{Wo%MX%;n)0Jo>Mpk0)t18?& zzTqSRob4l9RbAKx5qeTn{Fp8Jh7^1%-LRj+or{`>O8zPR6ntUM~# zzH5;0eW$?y`u3>0)%YG&SjQ@_q3bm?Cetgd0scGkFrdZUR_6Z(ZLEaP{B58C1{$oW z7+HWA@Kn`rvv>t%m?C6moA@gFE^i&=f8nydS9R)4c;1d?dE##Hq9Fx()sEuEzqJwg z^c)GV)S!|~UEtn!Nl(zrr~ap!J@OuY3-ux!PQ1Q4@i=U(v~-o;LGHr&INA-Ota@`l>b{v5n;W)_spX zi2^PNq=rf*BlqeKd*prwt*IlG;_cVt{j5j}v+A%PX!?0w&F^ADb1v_v5XJ&6$WFo< z(!%+rn@Ku=&k%0zS&;ec1zSy?!bmavyyDM6nJx#+=>-Sc^N}kWRq*S&V7Sz+i|TrN zz?JYn-O0SCCT|sVS83Wtcb~t2p{5m2SPjS9VME^*jDbUO!CEPOo?2*!*OT;cHI{vz z2wLRlJ&PS?R^Rr3GaTyc;Ak&RdU)UO@@-EVz3jKr5aw~;sna2U79Fm}_OjbAs&vU> zr=&>cxslf63(h?ri`1!u$X(xFr|1g{A#JOBmO_IMBR!PCEt+)6}z&cm%5^XL)o z=A0Ym$gFSn3xV5O6+LjGM0Qc&x|jGLmBh$-|Fh}D0| zL7?MNrre@ve|Kyxe1on~J6B!)(B%m7KlzgHW!ueHAV%PQi5ZA!WAKiVi1Y;~9 z*nFmD_p#~PdNE7TANaiZUyb1B`=X}j2dDfA9SLkZt%pq;kd~9_SG}#=^O{Zrs-B-n zr|k0?$gP1x769Q1iR$y*AgH>pK%?oO>udQCx;RIB*k3a78KY%5_F;smE>gg6cHvWGa1=01 zj3d=y`msL%XwV4h?N)y>5m@s z^m?zbb`jF6A|P&2Av+njSZq$+r3p}lJ)&$I^xq9Cyou<}GmCe>0rkg!GW75EE6~`Z zvi+-nIT++={;-_Sd+*QN--i6Y^ExHT?wLBBla5Uu8mML$PdZG0#}ffiyKv)LI!`8BW=v{$Vo$4shJv@+UE!*Q?nq{k>;E} zzh4Hm8S9uwygfhQ>Bq)=Ma6N`PRs!m-mqSQ3o=*Z`xP6Ihar+Zng>Q zZ@U40qwR52+N|zz3tZQq$RN5}Rywzu?(~hd_uIqNrqM-0+g8Jze7Smq6G_hygP0$k zfFD#0AwmUWT=)7_P5y?b@0qTGOAJ#{1hc-(u=K*9`1P|Gz*BxLY17xw?$X+=%Sk#_ z{8S>S&IV;jC+(s&F3jrhX<;@B08y88qHMVub3Uz@pS0&KH-3+SFV6GXESJNWI4z=x z;o8IP!J(qpP>>!6>yFPzScnLvJ0B99lY3Nv7)(<5=SeRX_wF>$v`bG-DIENMy}t)f zWU*Jl1a!k^h`$Vn*M7eJ>SXGN&S>3DJW2xps;HYxyHqF0kfI#iFL#5a^SE!d+AX;W zN(;P@HgZej*9iqJvu3uZH=sEN=P|`Hmb1M;TYX>17{*vv8gJC6ChFkDypwT!0rD0I}BM%;(j zAc$6*GkD~+F7@L_V)C~iFBTt}+T#m$&efBjVs8@XM^DPbcSc+ya5B%gNpd z;uGLKl=PZ+klEvi7+-)hwD|_rE+a*`np`c+b=Z#aB0J*Rl5W!ef!}yg5nkNv8th>@ zBK=~)nfnTGc}6olj_oIP#v3^>Uu`VKr=ER-@=Te`MNS%&rPYd#EAhv>nCGBce=XW6 z|7t!)2nY=Y^zkqqG@nV$BE5nr%0zoaMQQg-`R&^mA!au^PuivCf`9-MtJ&|CUkFH> zQn`vu>8b+|<$GUA5ZKFb`LT<9PR}D_J|WKNXTbAm;>S6LN4FV%S&g5%jHuFSe_}ZD ziNA+`%X^O_@aIH;$M2-=v^+94BY&XZPuoHgIzB+P(Je&VDw1~SoR+=3WX2_Xvw#U` z-X1)}oYs+}<70WYGtpwQsi^mh$PhpV62*@j%+)+xn=-Xz$`1h((3i!+6lR&p%WIFd zNOB$Ug=*S=nc3qszcTuAe$rJQ&)udhWv(cxbFWx)_jGz2f2S_3hJOoG@qu!!sT&*g+k>n=iFBOj{$d@Uij8E z6+taITG#Z(&>z{Kdt-dX@ciARF)h?^&)8LrtF!SFV}OFi>=#6vLhZn~;;36^08%AY zDlu2LpR7q0ee$55T?1xmkKz=g?tD7@PZH7ATO$bJt~oNcmxAVtUN!7vRZ-5?&szU( z>02*FJ26Ye5ISoW(xE96UOvDcs!) zmr|@TMcdgxx(+;fsOL6YUYjY~t0<4n+pG+mcwHihCqraC zeX*V`9rb2`rwCBRnDN@Xq4sjt*ZX|wJOhCuE=85vtg~}eDug-rJvcg@J_K5V?T>}` zdiWCjGjrX6#gh87E|~Jr!D`+A#ocX99TL}MUYUa;A*{FD2X`p~;UKdcA)eQ}*UkKq zb>#bn&u_%)K<4R=zV7)_0xQm2%|SLyr8?Ohv;Z!1*Dot4$tSOv(0jE?z;9le%SCUp z5smqB+1i?k(7&(SVtkA-=1>20o3Pd2_hAr$wJKwrHM|9{qw*JM7WiwN;YYXVbbbaD zVH2J}F_pZ=p#Pl2V_Za|Fih{OY5&vk($_&9@!p&qlJ6rmzQiPKhz&*DOQ?q_J)cn( zREg-dDXsRliar1L&R+ZQ(!j?=OMK+Zi#dMJY;d9>v^)f-lrjf>UI6B=AA+xcV0ArH zWBugV^_jvD+IfPY(|7M5@=o5s-L1mb-0(h4hvN_~o8!LSV%%d~18#2nbsS+kMN(Qg zUm5NhSKXL?0<&GjFtLp;XON*>;uhM&lV4T4n7$_J)g@Te4Xr7C-iA?U@68nB9*Y-0siGsnuJoKr z&vG}oP(S$@!*=F7BbnuLKfzNT7Er-6I!(YG)Ty}42@;OsyqNSaW(P^~iqR&I%DxGG ziNT|z8+&8F;r(?ApQg^_FWD5#(O>Hk{psVmzkB84K-YRt4CYq!aTeV;Pkfw(EcgKN z&0+FWY4(rd`aJjDk4SpcjUyxr>f77a&Eki4%JhdJ?m${Vcg!fP12DyE#@mmGe4 zwDCgY){?$i6;LHcUfe4|0d&}6d;<#S=XXYfts+^)6n_mx-)~zCgjIj?E&F3Ufr3G_ z!QRazv{Hexit73i!LsKzP2XRXf5M=*@KUI}@zTW}XdiI@?`xX+`)wUo=wXBVz;IpP z(VN+;n~`NL3oY#vVd`EdP=@Dp=CxGPE0$ES%PyS-|a168v0WTZj=I6{Rnw#$L5^(AmPj$ohb&HIUfEo>v5m$N2LW#(>$n~1*D+#nl>8x>iauj$Z0U>|48-_Uvf1*YnWcQanA8e z(nCDQt>~u8fT#)IBHilrBbY_b*DfDb9H;cW-?>@N%+r60)f_Ne5Yx^dNmsU=suDzh zNkpbcQ4kOTnc>(3@v3q9$I)ZYd@rQ#e0ht(oajq(ZapfQ|PC3&OEjW%P&Nmt7Hf7ReRE zeU)_u&-|I)lgeX@^`94r@|?y8bmBk924>6CAj$G12Z91@J`%&9f5xKjW@cyhp@%)~ zPYbTh?*p5t`GC_Q0*d+>6`*VPgIU5b1ay1N;V-(zsHB10hhy$jbEwLa_;IgKp#N$| zyX~pczEb`vYoFB3-+#a@5O*;PF@G6@2>(F6)yP``Lytn-3Tw{4FtLFo`1BDn&I5rK zq~z$$Ki$Y3W4Ba@vEst;0_qlwp?2sxzr;4+Riuz?hy1^f*2$XTmBNKv5tyZx9he`* z$i5<9w`(}f>UJA#yl`g`*MQ-k&k)G=P-S6Tq~@NU$vnwVI4nq6l! z>=&QiQnL6w;fZH*Qm}G041QWJ3Vk1=nEz&9&DQUa`h_f_f6(E*;r#xAQsi%X1&C|> z{dP9oloQ~_=UQ`op}1QkV)X)T8h|(J5vOD*nsTt;=A-rdDECM>%l{p$Va0V^FDPz` zV@rMtBnluKJY8vcW{Ss-4**Li?bKub~lJ%*aNaZ4Uq z^1h9shj=RNt61d;!n8&?y@(YBm}`!cozTHE8s@0(9Zk-rV+f=9(WUs!j1;PJEW-oH?Yme${i1V6Xg?hpWa zgqFhk{w1nY!k+cvb6&tReVM8BF0Rnmcer?OzWjs+3pm!8@C=9&=hNj;-* z>KqM#F6Gra9j+&ldE%h{cD>S0WwMTzWBjFN zUet`{pLG5(?1s?+Qx=@W*p5SVA_v>3$^V_kF%E zb`B031BVP=vhBFt*Tb{7jAIFe*|kqX$KpvimewXLjhGCmhM*HW>jJZ~qk}PXtM&u~ z6c^UybULk;oA`{{DbpWi9eow!Ku?b|Q+hSL{n&f)x~G5BcvMr2AV8CVCqgaK1nIo( z=AL~%wfcQ~k>OVD*~k04Tag@NP8ykwqxSvd5ecK!ep-uJQBkd=*qw41WN2brX!6!K6;R zzAZpTa_sF$;;b7iN-$rOf>`KHl6Th=E`)QFM?M zeV-Pm{y=vc3eb#r?%0#rJjm7eSa@1y64o3XaW19&pgxmF9-922j=3w`o3#Vl08kvy z9+8q)C(X@_upc`9@e@?fYOK3?7hnWXojYlJSFHnYhBd9PYjK1D-YY_rvX$)NURT^l z^cD_+8i)3q5tI2e2osqsSlo7wt{g#wU1)eM!$vd=I2Cs<4Qba3=9o7X!|OC=;rf=I zXuO!j^OJ@lc%D?_9j?4SYrx=%)L~!+GUA?}nT7e&afnZEO8KiBqYzAZTdM~==iy%P zOLm?w`f|Ta@5A>qLBrU~XoL5Q2y&L?auLyf{02fPsK6nmCH!pAS03&BtU}*~;U>NR zwH%aDjTkjD=(N~v|I^cmC7j<=1X-e=(`9Nk`S9DR0&BBJ3^TCI_Uq-Xvi*rWsjBWO z)py2xf6mxNoHl7!kLE+DWgznLXzuqn9cF{e9hsF!Ps@==cU+%hOGYT3vfAwSp^f$C zs}a%B+^FAWKY_w)+tHgTsNntFPBY;^TRUH?a-Q>@Ny<9uuS__E!^btnF@=4LIGJf5 z!K?)+&yaCy7x?gGvu00mPNo8G@b^~*myqN#J}D{8F<&iPdOdNbz)C}o?!yV%5~amc zLo9@EN0Ku0FrBzlY1|={u3wBjFH4Rpu|3JHGPra^3nbQ_Mi+)|4P^On-lE}mt$w}1 zTp`fsOAk2<^$B7PGk|6^4N^zBEVhJ#Q9qfj2G}rVU#3XVp5uF8kvplp|52uw34&Rd zi_Yx@XJ8M$uSnUY>Uo``4vJY)0cQ9|ho{(3x=^qKiliIMN%~+0@NUFBm+|JAkDCQ{ zx)E)rT)i&`p*iJv8DEJU{g#>Y6B|JF-?!3T6lA%F=}aCZK`s7C0Z^=jheEHew^~T} zqLG}n2()eri&JrqtOMe1@%va^lX!gF_6tYz`n`8 zD~!#Fci4+7_b;4j#fM%j&vgBP3DW627{`}}T;pfGdjdg=wLY0qLv87~Gw;V#F$ih* zap$c-_+|%h`jF*)vydT($5jYyJG81kEt_izL-D)I{@fAlo{EPPmJsc8`SiL+Y=;VL z09=57z5awbE6cPz9lIR$`sIn8+%V9mvm9Ry%ld1p=k!rau+!0ueFr_zpo#2ZSw4T% z_jmu5S*lo5iHxZ~XOA}F$#`PMW1F~*nI`r2Zs7W~O7T9Q$kGYn(T6uBX`r#dOU<4? zo=M{%2L%tPwS7}gR|OTyJBVp~2l;pq?VV`i$`@q%RLHtAIkqkDGfwsaAte97ghOK< zNQijrSd2LH8#}>b1fT`Ky4Jm=ao;Djc!)RWfNWDJN^aM#-qB^mzQmkkK*@DBuJFr8(*B%kg z!eI?E(eF%0>;#TQz={X67}xmP`~80E;08k3Um3xntB3Z)Pp5+k?o-8Qo(s6k2C&Id z3-l#aF5dv}h0mlco*+o>-(WoCzv`BKx&Ckaz2D{9aM_*p`tx)DFv_nhETp2aG7%tb zSn?Pe)erHuk0R;2-88WhdP9z13{-FMJ1WGmv0E}e9N(v>iWCj#wKT|Is!#tq{qSS7 ztT1ZXel08sBL1my6Qapuk{Mu=W@k|AadQ_Y1qXLHK|Nb2*aB9Y^2e%LR6)})*k{>> zg~jPwPfO3u;ZeuOTYQCQELg(90wxfQj!=YpNKV@FVf}`pC@v!c=(SocapBeX>{y6l za2|QblP`nj=vN_(J?)1+FjHS{n-<-x(T_>tXVCQ(iu%;g2(-sJAUdKjp+<8SK_b-P zD>sRc5#SQ@N70Y3gv}}>Oyw1_ZJ%Vn(B#$ZTiHibRluYuk98#UieHVB5ZX;?pUINC zsBCfJ;3%p@oqBiZ*Mr78j*S?ShE?+Pp+bnBC1i=bJiXqr&5R72LjzZpV*-oCSI^1A z^LW-9hF67<3XZ!M7~js{`{8yq>>^Xt6g9N{SxD03t4FMJzbN?Nn<2X5xoI??SjdE; zKKJ1<$=FJ5O%jTrH&n;{OgU9q1bw_T^|L6hn|7!@_QiUFeqv4N20XRq_9xmX$fOv^ z;wXd*)OSw+C&B+fu`A9{q3Ixc!RtMR&0Lwk;LWeYIk7D*kPl%oejhz{9tUlpelPve zbLuP8IwuwGTqKZds0QNIBU`&96gP!`XTnikSEJEVh`Bp;;^H?Cqo2w>9PFzX}50dqVwq}INE20Fe-aEzv^m3 zQHY0Crd=+-zhX(qJUJ`$x5g*NBzE@bWW5CMNxwEqadbabozcgik5p-2rmoLL0o!%W zhx`_sKPHGt!*27l^lIJLtLf8&bMca#3hB_%qn@;`Hs-RZ=Lxjwx#D?S@;0h}+Ywu~ z&6{lH`F*;i77=Kw(oeQK?0aK;84S=wFUEu?#2(i5?e$f-tErlo0YA1;V)Lg%03S0O z%5e}u|Hb=5=v|4*VKs?=b}CIl?}YoEC1`|P@-WzniFtn@w(K)9$APK^myzbHBcwha z1ve%6tuqT=@QN?&U82XZe0Mek9|bI{J@$p>15qFH%};x92WotHp2>|XpZmjMjA@-0 z<71d2YTr@r9+nyfyXja{`*lGN!&`*=rHYq6 zj+gf5k1buB4(xIDxYb$#x|!PHz%7>^HQV!8J@3C)7Q+nMxXeMGbRmpunO{-5&u!de z?YFN;t}j^LB2UWcnVJg^r;J5VAza4&(3i3ACD)|bPL)`>c~kRs_0vd?!oPKgx9hId zjU0%K2n$fy9vAtgTEvPqcFuA-nKirH=t{`p2%wx`IM*$+eB_8@^5q^2m1MyoP+AB{ zAoD2LSL&2<%-&$GRd(|L)mXH-MB{YdnBsPwqhKulph@p%RPt+V?00J>SV;UWodadK zWnPknU>@Wiw4R-7dY}+7m+h{8Le`P?J)d6U+kAAP2Z;K*C=FBivRUeSmtdCd9mZrt zW9D|008nVUhaV+__AOcXOc)LX?2Ag9&UdlPCRrgb9gn)(a|2J-_MuE*li$3*NavR~ zotDV3aSeKl@&dnk>61Z2Hb|r2xpU49*nQ;Z#ydTQm&NpI$K6wLb>%nL`0C5**!qOD|Ka<@yIFUEaWPeE2F&4N zUk4(m=Q#d&8@D|@Q`Ihd8D~>xen4m@@aR3kAR}y!oIs=a$e;7=_GGc1p_01q;;(x6 z^q9R!0oNN%sGkfBcGN|q)-$(=HVwrc*j`lNv}BRlP&m#NBflNIF_-UE%U$-0$4K{d zo2jAk^_*AIULdrKohz?`EqU1k+IDOe!j>&*GG5F1W%Wi5^v>_5T$9u`!%>H6@_U?0 z#(fWFpx<+X4tw&Es*p>K%=gK|Iq(*@Qye#h4}A=nf)uJh3{B7@4G z*h=!#ttjq*Mt#KB5`C**^w&sto#iRsy~}Fe`!AFRq^xe;ZZa}w)m6z>sqeto+I+2f z-|I`hu9_eVmCunsA%DIxDi-8@D$n)*s zqM)qY*9r~D>`BtpanR?^AW%g z3>>49)bHeHhhOoBoZB_I`S^Bwygwkx856|t^5=oXxqijf+xH?d4tVlKr^Xm|=mt~V zGCxA>eAhR7mNY0c-y4+h-#@8MA%eNKaFvZu0saKwO=J@LI3AXIA4n;@w9hX~uN)eA zJE_)kl|W>#?z8o~D1{c%v)a-Tc60=64d4@3#24jT#0dckKTeVa@U5XvZTPJt^?Nzg zulKNU=kexnx5z@p_QVYzc3R$a5?Wdejiy|l3g@ub$uPx47+*`rrz;`_fg*~Cux&!K z!n&7^r3%a40G@xJ2IgysZ{-0>z=ttEb2Z2(IVAXQV%cMpy{~69c7`E!wgvuuxz@{2 zy?8GA2thrcu5fb5F<%NQ>DAv<8&$arhP0`O7Z}9b}aVQ;oW|1Bm#WUqk6&@eH#IxP@^F6(0Hm+ zx1N1jaYLx4NWHDpXvg%ygkZey<2fPj(EngmTTG87)6L-}Jd+Qt|DjwuuLXTSgS5RS zOY6>!5(}mDoLJ^s52Fdwr0EBh;^6gl_Fy+Ve}u0nAV1Q;>u=K$4!NOcG!zBT9&aq# zeVzC}*o_go#1{ULJ&V?xA3}&QZB%ATDp#2?3HqRwke~@z*V~9{B_s`|%$07y+6DXp zDwy@9HLVfQewW9H-cvq`mZ+C)L1iBvx|*DRFZZbc zcvWG(?SVqvTqY+*w_UvR@jqPS?u1vTc! z_?~Qs5*Z0db(>}9$@Y%qQr}Y}fc;ba6d%AP$zKV&7ttUYbC10%q`e+{9Jq8dYX`*@ z27~zN4cJ0!Z8L=5mv6qW2tIKNNY3=$`!m|5VMP_@7BWzL`1y!+g8>NW(l>|YbbcI@ zhiO)CG0_A1HGMYfDBqs&((`d_KV~GLqHIPm{G2}OwMTt`FVOKgjW^r|@%Wtv;L!hO z$!aUo-Vef8Afmhvvnujqigj{)P%R-s9@LY479BqW?T+j!LneDoX=8tmc+0SV(?Axk zdl3?R@R+%{ocSaH@5uKY$UHj}bBgYO&F0McfZu!`OT`zcst#@=L(v`^0FnAL_f=97 zw+Te3I34!9!66BgR>qpkN@vyayg0DuN zM!WC0kIxjsdS3L|XxLIfxaNyZN!7mZlF2z;ry0UX7g2r!UWy$+>y_cpfHw^x;I>y& zHcKdIYME4>;C1`8*cB2H!^OO7&I@v5?Xs`U{9Dzo-se}DY6W&W3>L{8K+*j)ynBEO z60`jHMTA2*wXZbAG{B{?FwTOnX>o+6JL*?xLWzI-AW)y^dym_+P}E@rE48PBq_+@t zdqS}DPo%ZbM8?q(?DPrIJq&-2|2+QmuH zJv*+?XJ5IP)KK8H%Ri)~HhBR{Ye1fznzCMQ9~b!*%KvpGHvu5aXKFpIk+?cq_5v;7 z${HVvS!+#z$cLb~!N@c)Z$E>Bqu!OL+8idOLuMyB!wv%BQL!8v=q$O^qbq7|?cQvg zANrkG$&;sC6wKJOc_O{I#tJD|s4%3}s6vM&=|f+O`bwZauU9m11i1l=1*hjrRGHH* zcOoWqs^1`dE+mYoPb#0heDiBuz%f6g>A4fs+;6%$d~@0TE{kCa zrVrA^0m%GQ^mz1&$04YTfr#jPdvQP7Zg6{KR-a-BD_*0INcHH2lr@2&%=E>b* z}fS3?$~6BS$KVnGzlwFBK(r{iaE$OF;jx*5MZ_bc;kNaiVd%OHs%!s!tTRLh9yt?S` zf?U6}ow<$9W#0RDMX4}=(6?BvpertBZ3@eB7HRRZ&*irtal-ONDTx0pKlhpG?JXBz zQA9ZXQhhJqF9EWqeM}FK`u|m70*uh*!!;2I1O~B47nhsQ* zQnwI&F1!goq<#*9m=~05+C=vrl3`ID^}2Nf(dPO-%t_C)`y3x)bC0;=32d$!)&^g7 zDz^sC$u<$5#!_a0R1Fg7o(4dz;>`HM(5mJu8?yfCyfCy^=XH0@t}Is+sb226F`%1F zNuT>sxWRa$H=;YN{^FJRvC0dgK7y-3s^hn&z$vgtYIt7NLu;Osajkzc@9shQsQxA_ zX`&PT6@<1tfrz}NpuGKZ@c|6}@_kPJ-dI3*7bsO%fKs~9uoKazZzcO$qrtWl;L4M7 z`W{eshgpllQ=hBzl5@avCx}NR)b=u9rd6Upj>ynKZgQzta&dEJ6aZ>aq_y8% zC<#`b_lUKLRxoh>^ekxLultyC2 zMQ`DD!)p7Awt7^a>CQAfUS{U%^Xt1ucCwoYNvWgcRe)Z#Y87=nYVGPScHt0-dK{O+ zZSPyUsUOtxequGx1+u@(@`N()oy8fxxx{Okzzx~bT(Muc_AMX|7BJPff_phxb>jjq zNS_qEFpi~S`D`iOC5R0|PWbuxDB;OjU^HMtPbVprG-1EV(eeH;O36V{2x3nwQkya@ zrrS$xBH60vg8f>Z=e|ZmZj!o?xw>9prNW z$lqKvgrTS(cJ6nBcFdmPI4X04+on5CgsOlUG%=4z9D0v1S;!yZ0Hx-J*);=LA`DKG zda>(J)joVhA36-*)s2IoDW-j$ZZgZwe-sv_ekm})Kxy5&r?YQ%#p^b4gz>4V)O6*G zhA#If_LAey=Knp?Z{*%v8^3eo~ZnW!c#4vF6$U=GWZZumJI9KIP#zqqUC z$Z=2JRTgNIM=z2A2SR73k9s@nkdKsn?0-^kU$DMd;Kci5_?Zx%)YHw9{6jMfH7b)Z zUC9>n;nasD3q1D||ScP^H5`?R7&04lf_G>*@{Q|3c~ z($+?b`@R#r`y2PYOG9fygyxL3LEKVm3+;?kG2_ID-1J4@%uPYvcVqk3N(LzcK_l(A!|O4fXN{davNt+V z&Z~oc=T@%BHm~j#L5U=8;;eVj%Bb+u(f*MG_I$`8m2H*DScVBX6OaIFv7D^oZM`ip zIy${6gu1;Rj=^vJPRYxl%coll4Z?x$SPr{fs4pHSA1)bz`Wdv2pRm7zxu(lH=WSGF zNARK!)mD6HQr@F8)9U7)B~fhSzN02gWXXX4ul!TfwEcWR!Q7^yANtKm1}4Futq|KW zKdcLO^}WIWac#e^5+osF88}P#qfNEd)l^vgxt}zP31{JE>t1ls)p654hMLgHV=n z-?TPuO6)TPhI}mc?X$|ej%dbqe!vBisAzx<`GdUSdid4Hpbmbg=`kB6qByXq zgU#?rpdNJpwTk<$mGnLiq^N`thOqc-@+$IB{(271SE+8E?W5_7ZhCgMJDkfu6`Hpu zq>F{e!f=pV1gW;M&_+5FEZqp7!+!Nrc(W(^nSJ6RntGofj9koPC-=p#-+T)mia3b0 zXG-S-Z}Gt__y9VD?fjYie3oemZ7GEPVh)Qp#LdeWXFM$~r?yx4YE^z_I_EE2=3lJB zsj?Tnm;pC=fh^HexuiCrb+}gs4K2z+lEh$iW|rDVG?Em*}G0P3afmoWBX?Gl{ElUymS_q%!~ z6`;U-$~Vxw3h_42V4CKlo*0ZN{P{$w56GK&-^WD0UL`oGi;#1GMU>|=DlGw^?iSkp2dWFDo}wYi_}-3gEUUdf;1^jubg342@iLBF}! z`pYx2DLaX8S8TtCKV*jlZ-%xFIZHR@x$UX?ut`cbHQs`}%f%9%%klA}*sU6Pnx$BD`Qpn2p=R9(be6C}NjKjTQPdcG8 zvlu?IZjb3<&Zn_s6Fk0RU$a0xGR-;`62kH0Xm*T?-gh>Xs=M9&uVlB5%w6P4T7!)F z!8Ood*6mAJmz#O-li1I@%K5es?^DdUsB$P9ONhCN@^r|-cxTM?mv5Rk1x#w z%QQnyB%W6lY}b?v3bx1Yl9V$3WKk8}r_K4!S89eBFs@2-PbF_osC#@^0R<+T3UZnw z)(d~_EUpSFfB}|nPn&3kcHVd7y

N357}yHrxDhJZv-+;*R@l9Ns6)hQn>oqgY=I zKS9+1XCn@|wV%PdEmWIt9(j@HZsLt7zh_XJTa{snoP^rtkLwR#Ck@;lH3e;_z z?0AF)I7M>6c5u%t@w5&EUfw^V_SNFiU<1C7KWHp{#fFO?yfW=&!Fpd0fUKyD*|xf2 zfBx)N2U=N#$NPJ~w+~;0k1_tSU!2fqNQ`v<#@{M{58-oqJ3}N!n!nAS-2P^hD@pEw zmG5-?tx#+fgayBMCx3<2cn~kafBU5L8`SgX&D-$+*^@W>?1lCovpPl|F z1UJ_|X;1j?tlfvS+hFRyQ34JN-@DpFoj)SX-^oa+yV2JU5$57ySvM=CoUOx_f z{tB63AI1O|DRCp)3qX?eO~F7DzcJgq2DZHinX})5?NaQUVRqb_^viJBqP}7Xxu5*n ziL8|UUh6kBZjoW|okE=R+&3o%Qi~6QpSoT-uNu6_iAxU|v^+%1)n9uUJq!+cApBRC zoF4-J`RvKVn|(TQqz2LOprjIHvzJI$^|H}-0QXAmO`G0Ih!?kc>cl$Qr!%D`(N;@d zfk444=UgwZFbEw_sIQ#Pss`Us01Z2K2!eB=|MH0dRgWYqcp)5#_h-*MurXe*-qrbN zJ@!G2gS?b%pV`5e=fLDPgNOKGKRj7OOB0}Nx-&U0!>PPnNXBlsrvNIA@!YUo+^2bwQY{_&3ocK`0lG>YR7hE4_cofb%9iy1g*!~9C%%l!6bepJFqPJ5gc z>SPI+Opy!4+4l{}vOb|LxE81>Tp|Q#@xF(_k4a2!+d`zRm!G}Aq9{GA=#kto@}>Se z@}D!=d$i;pp;=E#s`1TU%NWKE9-<_CHzK+pmfM{pZVw8)scC-QwkNDR+`%dX)O5Yc zudot|$1)A$AG+@q^|e7Bd3WyTkj#nvd)svWd8hHC5jv8Z?9PU0)DhaZ6@AS&(xkhO z&xc_Q`4`3GNsEA7*_CETw2pH{9^0RDqB)m=Ks5Ek2a)W7eEp*E(c`bi4!7z@#9Ocu z%;LK$s8y}!bq_^^Y5Vt-`$2~mVdYX&h5f_@f#Q?iAXlu>+B%0{@#>sf7&#s)?RTn} z7Yv14TKRIp(tG4D?MXkDM;N`G7Ue6V3#7hUv@?emAKd}a6CHPYr@Tz*YcJai>` zT|Ca=5?w0|hEQOpWUgVxp=Kir!g=_k)l{h61IxsldWK<7(*LOE$f_&;8?*dW9qJ@`=0F(Hbt`ZuxaYULCl+VMpuis!@Rt5<@D z!4bIBftW``$mi&Y`WADtZgbHF4z||C1#(;pHqWB@$8f_xDoPyPmV{t%z0QET6b!_6 z9`Y~Q;2`v($5n*5WNlnK$CR)j_@SnWG4E zu5&{h()QEL?{;3>XsFw_y$h>|h*tdZwVjJjYv`Yt>K~2#V~qa#sgNufvEG4X*0uY& zDxP1ImT^43R^yrt?FuV0HiuN{otf%m-KNqGEK-(SA(IIwKYzG`=PYR?1WI^?AfApC zvPxz`zQ`XQZ7V4C|Bh$s#~9Q_j?zACw966N|8+6=v|cG^26}lq)~6LT!3}t;_3<_J zGY3Zd`{a68OefF|5tMFp)*tLxo?_5IG^Vie?u`!uG_B}Z3?eTB95dlg4=3s$Rr zbL}aAtfw<9L$Sy&<9+!4jz6dORIyz8_4XKY546uu3{vz8U}^QN2?j;&?%KN|J3jzY zwY29^%?!>9;&grhE9nn#Mv}YN_@h=Py~@^Wog43BoVuy9akT=-%zQutRdaG-?4UQ5 zJ50fHgOHufph2fkqu3u$ATCLNNQwu0^5r|I*{enx>$GoPz6uQCL=O_Y?Pt>YnX-7W zY>U0e%(GW%FCtr5*}QjS7OMqBm}R;*lxPG9%D(R(){-ZB6%|3^40xOT0{=Ngj?N25 zZIQ3~{N6_wGOkyNg`iva+Au#g0qYI>3*XN!1SCeSL{`oo%V8YhEF-La!FrW0%Yn8O z3B5dZ7rZpNdZRfLLF61>~AU9sI+M-@8c#?ype+j`&# z_j)_Pz~|}i8OP>H2bddh8VsWR)Vba%Nd52XReW5*2!^R)1@tiQ(j?6c_V`c;KC$31 z4-a7tH6m!uqiZ+U_N!~`({w(o4xv>Gej|Q1|ceyg@bC$81H}9$sPWk6El3TLw?AxVlWgW2%xZcv~ORRjSFf0OqFP_^?hH`WEn;!+rbaVI=?Nn^Prhrp+o&R(Yiuwb-}^@ zPg+Jwxpi=Vwd!Yn$w=ZFt9k&jv@hQ+ISDKte^Htr2Wu6#e=>2vtj~Q0j8{#+moI3o z;s?;&eHK2b8$R|6lJ&X0AIHaSf11N`dzT(f!v2UGkIjv$Tt%FU(@i=x9<=5}PRXyJ zz9L~c*|%+$zSy*OZjyAY-6e!nV;Rc^SHqc4qCI?7l%qdrfdqRwa8E5>>?P zc#`cyRRjRubm{NY4cBQqj!8FJ>D!_Hic#i2ExGz+HPr=L_l_Ea$I~#rx!GFu zyrlQH4hVrKo~UAkVp?r|%Y(+l5)tl&E-NtW#{p-lA%zoTO!7)$A3f@Oc2%NsQ`}nq?1F%mq2lmv{?w>D<*ye% z3zTxbQlE*I)B`+Z`Rx#ApV0;6)f{U?3D1f3g19OH%Up`)g6*6RIS$Fq53iKC1@2*z za*-~f_`Ft{A;K6X_wy4urgrg&17sY0ezr@+BT#*X6fD&__kDQob0xz!K8?hgpN;s? z?nc(UR15Ak%GW35u0y_Fz42Ayby-WC=$)VPUkgZ2^ZdseJU#E58~L5C zCdS=0qFy?FUODBm$WSTAhqaUUm5lgE%6I&f4q5*G-Cowj7Zikc)`BDqIq7vH+R-TR zz&j)$UgXgs{Yz8JT+To{1N+bMErD5_6JI>Kgf=ghnk1iNUmj^Ge#Npv#G%u%z%+Q{ z@a#+!5U_9%HRdOeKLG7ZE`C7)L9bi~5bBTp-SfEP+uS|aM6J}1mYoFGSxZ9m^({IK~RCjcH2!Ms(^m7HK&4+O5V}KhSvO=EC z-!~{}E79|MWY_s_mChKMIspgyzX$Z4!~43Gdprj~SJt_{PV67x_7d_BPJuem%81d>+d z*U>W`;Lxz_J5k`Tiic|$zvLWaX{a=?0#(0k3Pwn8G|D#D_d?lg94T<8_$b?+YVsdb z%NZhlUJvKv%d+fx-=Ciq77;%(_iHDAwCkRu*Nu4`YfLh}*e_>-OU=w&u=$dVFZ)ia0!cDU&>Y)#otchUPewIa@#%l&l)OE12QD{skt2xuqw<)B+PwKEzWw!9T~HJ3XtWh zy7S*H*+nXOuBO4DAU+QBx!)l649}qjzgGR{3u)=^kgJ8sK3KK&sztH63W>M7&5k;x z8mxPr0oujKCi#Xd;}|ORU$Y_tZPY-phAa_S-{PG-FPEWuQ$OEI9ko){E3@vIRSrW*<+$KNc98ODAD8suA6Vny5rUtm^I=3Bs*dc}!Z}hYNi1 zI^Un;*LWOZ@D-qa9f3)rzJ3;@;MqEHoKHk#r8J;JH@@HfE@DE>;XYe1;WT(AFmH?mdw_(^D0cSIgwT;*@t%haCttFd+y2V743N6 zYpFd?(wJU8=IOEL?cxX0ad!$giL99HbN`0V%*0dQ%fWLFosp3=E(z3jTZ(z_1BAAJ zJroQl#+B}e9%2?@f{p=~oS-h7T!!@xXbaYk=mKl*OhRS$z4+EQ(0ys;o<|6Q`5=P} zm(UgnGkQv$zI_gsn%V60aV4-e007(4xZo{4q$D|Ax9FEgq$K&#UOweVsD#SRnssww z7DKKCsDqBjApUKKiwU}wx|fB=U}kA9i|*RV$nD|)Xv16&0)Oz@JNYFd^mKXHfr1@h z4-i5CW^s_OL%AUy{3M4Wno5Dz>hBPG3>QfP&6XaOT=@$LU=mvf`%`^yc3R$`3@xY+ zhWFheBl^}F);$(Y7QTTS27B?cx)0tUrf`zmjP3?F@%&!hpmsihPXsOg&QD^F+Ql&c z^8QQkrwP!6iyriz^C#5-*n;jENdgINeIMQmdxw#a`bnyOTf}!($msUs0}WeMv$J*? zqMxQ8x43*o5Blt$f)YT+7$og}Z|-l$=505>_j)DWR*I}EG@6DzP@V*#a0<1tIOjgl zBB9baEov^@(Ymit+FHj+Vq2E=3fR#jKJlfpW_Q!e1wrj>5srVQy8PCz+DtD{==I_G z9BXjP(S}_d~V?o;`pb+Y{VQ zzJb?rG%>HMRj1r%FW~)|fySiH+R5>xS1%|;*>CH+k8<}1VdV)9oUU=wGS5@*wP48Z zOWykw{KGr4ha9`)z{IvANuivi9j?KcMVAsoLM%SSUAYW2vT?49KX?17^c%;YTX?tN z?QuoI5u!9s!R#gOy$GA_`O39w4d(HL*3qGsLx!D74YXvFf3X^dG5;QXEVd~tTsVA! zX9aRHvFH3+2IsAkAWsT>jM@DHAe$1{Vi?ViklxonY-`R^ebSB8Ye(tvL&rEJ?YNBFgQ1|6%pzg#&T5;W;^IY2;I zd(QD9vE{OtwY)#o>)l!DtQa_E87j-s0m`3_iB2IGA*t(pJ+a=%u`qv^mtO+`;SOzAlZ+<;@z0 zyU}QJA@``>w5D>e=LS+<(8KmC2Fa$$O(M-Y0ef(~#mcms9s_3rBNCMB4b_{8$FzSQ zG^|@g5{So3CFl~Bf7^RN9q0(Xy)8Qb8J$Su;=3;Zp^Ew`?-yAacZ*Hl8>Pa}7zT^B z`gm13jjqSDYgHnlrwm7Zn)aA zb?2dQWP2gYvs}C8cvv%vIrUA@GM`WDKph@zi+1mvyE z0xG_6l2hdzIyK6Q=$Wl6diFI>ya_~FT>Q_Ad#lED?jaw*8nItt;#is{0QmR`A7NOv<0$z_I(q(jV{UlDhIV6e zzGE-U)?gt_o`&lMTP@S^2LEV0p75{gA^o~PT$KG9R@jidP!qucjr^E#>Jx0eJvF*# z7n`N-tiRLN6$AwDXxa}@y7y!vsEeZ72g&&Ibd1!x0}2pFh=4b(-aG0;yo~$X%}H5m zlQAv;XSBrpy;mef@9bP_<2)GZNtDq*hChhEk#8sj^NKI0*{}>vXKA`xeiwuO?5od} zH?TA?!IaS0!MIsf2f#|c z4ApGB%M5A0%Wn)lJx1&)7mOANreM67-fxGef$R9HDj(bdb0dFT;7m1{<9Nj?z z8>|&hY%gq`5np0pi63_qMGwJ;wry$MhqYo|v`b3eOfSizbAM`YJ4j`3{fl?noQBuw^b zJDVB@6!IwYX@2XMdRV7A0x~Q|w~L7G;SK$w2{zY0PP4ux28@-VGsUU>6xMMnC1yy~ zWiJ3I$O)J(@^4YSN-0oQ^&hW0iu(agJD+`!0!U-*BLbeuJ=4M7j5+!lMyN<&u2!1Y z#8m{oAwTwO8s@tA1A?2bNZgzDLtbN>@a-I%0eH?n%7KYEd~YMK9gjhC@d8@T?Vy4L z=XL>BGWm|`D-x_9E3c0WoVON~Q*3XAy_vX?(nMc_F9%1=-<6Tv<$7Z@uLhbd3e~R@ z;^?sEnlfQuy0xz{a&Jw$?3jTxLgxc@k7=%ao6rC=dL$Aw$+XwrmfFawzi2I~8AEOj zS^!SC#eE0Tj>!GG9A1%4O56Gy$gi(-q=XYJ?GeQlK+Tuo(?<-Zd?k&ze}W$Rv9O&S zZ{!Y_IpB=y^2s@GNJrMxPH6cU={c+x2IhdnyuSqgbbMmw6_xD|Mh&^{WfO|mka4!m zoB~6G+eudTD>4tGozKi-7L2fabahYu20{y{20Y3KK}CVooJ_s29d0^#syUp=zl z;GC5YvWYnO2jC8Q{$=>&iu3|E zw9lr3DQzkMXqL+gq2-%)(g$DLr!UblbCzMNRgLNVky#B{oj;ZVL>@F5&Anp}7KOvs z0{~_CHw(gk4OXra`0%`>Qv^r5y=s^C3+=-HuJ0CO%*_(zZ*i!W{mpW^%8QA6d{W%z z8KkN=YRd-xcu!7>LT<^Uv}LbdjL-ElJJ!S{r*q7bKC zk%MxSYf5-ovSR@Wu`bWN*$ZE#(*IxvWO(sWxJ^2cVaQNlBUD9zW-kECyhQSl*xR!s za&qA3^LQ~_VrH@bjr(7rqw;4C$UcEe`qzOk=3A$!&`aNfuR>D5j#>U?G~WP)f==A3 zN$rpC_cvzmy7d!IcVxWVUvKRQ)BeiiAC%0rizV6#Up)xa{}k zzKFf(lq)mOctZsPjxRT#_^+IfIUU4}+ zyAVzCfT7rR5wMDY=0-W+mbfs=flIR~o|((%IdFGgZ;5m=!DqvQEodKG&W77cuCS>q z<%OZg`R)sNM=HPiRcEk_*Fe!O!FEoE%qEPzy(y#u=u6KhPvy;)ni*6pC zIN)Ad?Pm0$aS`4#JakTe`XgKTGY&(N%mGykeIQ63A)ef)YV+2+KkSRp5S{ms>5PWU z64VrYi!aTrI`ZqCJRW^-&)z#GzwaIxu&{}qs$55-#U7RtUuL+g6U+p9tw#b6)XPml z)7QsqbOI>$r~VYFJbFHMKY7vaR+9NpEl)9*R|-R`n|H9z=e0_O>7@hFbNl^u4chM1 zWyX9Ru={sX@0lM}(gX>}+PCQ))DT=^1&*uFx0KSOlLK@<-~0EWf%&jAib!}z#}(*( zKS`Z|KO-UWN9VrA zB!aG3cZSX>oAL8RpZjKy=x2Jd=2WM*;_Aa#{`w4R3$o(EadJu$C+cN^kG$a{yo&pA zP+goq>kBmxk!q(i+bR3-V+yfK75k@aZ_Z7u(FVbmJyzGR-S1e2*qycV5k);Mi85rj ziy_Y^PYBIv2#6#6?}9u}gTC#so`E_)Qz!HRhTS>Z?y*qzA4~laUiiB$%*1vELh|PK zBtcBvU%9L*oAD=iiE3vr8~5uWbLL=wn~FG|zq4{a9+%Vc_P~aOM}?|=g7+*Qy|}|Z zA;PreGqTfX;LsmT5x>LYjIYLdVQ&wQ@}@XA=;E;wxQbH#C4S6CEI2djOQysg#~3@J z)FBwgw&7aMz6bkCeXF|fz8QBYfSG(q^y2aG2)L0V2-#y_ZjiKpAU2I^wgMAl z|4Y0&10Y{cE{G1XCp&d z%PFmj7Rc;b{PDDB=UmjVal!FoRe*sDLCu1bG=g*7SHxg7&dln{7BU+VbMfN8v8m;(-_kk@M;f2iv^JY=S z;WhJT&fD)hl7&Wp#DvtLuj`u~ac?P|Gv;~?mI8`FZ9FccmMZz z_GDCL;yCsko2N@@y05|fy+-qN$O@ISfob4hZaoVhvopPPh_9ARz1H$mqU$ppAHn&) zAD5I0khS!EB{@H+l#}ANukZu*lP|8kWLb%n_1mOYuq!W;D1wLS^^d~wdR^V*)1n#Y zFe(_|#y-|*M7e_uNBGpbkgb45sgmH}cVK4nH{u!BVZ)4R!|#CQalC9|FX3@ml?Q z2D?}BysuSEIEEH5OMKP^-8)HYsBY$1J0B2-**KnoFGE|ZP}$j@UhE_h-NKtunxk$U z&Chghb1PcXQ0Ai=_F9-{lt?(hXNvL&p|SL`R%OTCr*A)iXVGCva7jRg8!pfqm13T7 zLwh~;WN;?zU}YvZvvw4j{P%-f_r9PisNWSh1f8F9F~(oJr$ zJjgd=VD%RtlQFi_1!qOt&$MO2Ma=cDN0{A(()XGSRd}NVnCYtW2>}jW=vJ$DTfr)hO={19wyz3BE1y`aX%;{?6=&4|LUiB zQWM)%HP+-G5y$D$UR=7N=Znj~KGscSQSoPg>hJMuYQ37>q+pDEb)G~hqmJzhKj@6K zk7D#0EOs9ZcJX}(J&av$B^Q<77m46g()%fV^52lH(D&HPx%;yKTHICfB)K{4@8>!t z<%Sk~ryhjIbvQ>*+^+Gd>~5Y;pBq&Lk5X-!0-Ips3(tpVT0QRL`8*kL=$r%rg#^#` z8%i=Cc2b-i%Z8oh0r*TpxT(^5`|9<<{8>zD_Kp|r<~GXgnp~X@FY?N4iE$(V_wg-_ zurKmJJIQsG*+Qdg@citpRB@CaQYZr1Y-vrREd!vHu{@7=Rl3MWa!e_7cnZ=Gfb+F3%=HWt;`?UN589 z#VbPfI6m!d$kP$#g{W;@{yc?;C2=~zd>5VK_{W6k-bFM*D1k;dDz&$1#|wofQJyH= z=h!nCxN06IAcRr)x!y;=bRN>O5Re#XPM%Z52{j_CHq({afJ&0qKRKo3O{Yr>Y#ny% zB2wX>S6&dv9tjeQg9@gX2v_>79~x(24(bUz$5dGzeo#&kGHwcm?IuVJ(8JsT>V==3 zvrzD*vVF!U3mHKWS;1k?^nSSu&j$4>^LU*p2gK$Lc48xRu$^2 zJO@2j-qHac0M_(F$z-PdADh@`m-$?#1r_o=hWkyV9E2UEVo8LYypRoIoN2Kq!2lgE z`$8YJ4KudTz;OF(dCx|_oUVJ(wSWA^>)Zv5fmR+Gynu6|+d;$NU9oyjRvMe}hqmOH zX^$<{=H#Q&=jbM!n;2cs;W<*iW;gykW5+9g(KkrNXyY$uQx8pd``z}NEVDP+FMJ7=k&{$L+>A-kgAg6iKQ~yq@wDN#k+@_U^0-b z#&Jd4q6E)f?;Mx|S)%P^Wkuk>Yr!XTM?2jiF@g%lTb9$EehGlo$l40&_;kGXY{OCe z?hls&-6!ZgkW#qBFJiv-0x<9L!tZn9{os5cWoq{iq-%pgA$`5xDbASJ_mST-Sys3W zul{hkzxG;}2B#E!up;koLPJ-5FuhM*MZJR7-Q#-3(9dH4iyh|tTx6Ic%J^lqYWh!5 zlSknDb_tw2emCvSyZc0iQKEFM^%D1y8oVYoVS+oRM2a+ul(+M(gpWA412YM zz=W<;=PQ(x-SYkGR_9jx=@-UrWcAD8d1{<8g_RVrtE%B!tt6;e;x8xE>s+QT zpOlhbB2drirnx|T<;f$Iet8FGE6HCD1bManUI;Gf4I3-p;q~}bJ=7kA+t=L5Q@Z`M z;|s1u{o~D7*sx?dYP&o4nnR<8r5~Q16zwV6k%NYNR&RSI`+>N@i+cHZ>R<|btCfK) zc+jQ_4ov`tuc>VoV<%9FO+B5T);(MTCKCB$FHK5`bFkz@%~bV8$g|NM43C~vc0mkz zWYIW!R@Qw|!ONI(60l>?aDYx^wEayuS2P{CrCzHuyjNzJJllKij>T3XI+?#j^+O0L z=AFQHxw(}9^P>G1%lNPR5@1GDVZz<4rZF;8KQ7US*slX+gSK^ol1IIS^c}EgeIcAG zIg;o|n!a~iP>-JkHzstqY)N+ySKTJ{V}fZa_%Am7-hc>%ZLwi9_WNS5@)lccB3$_V z9R)!D*@W{Otbo9c=8i7W{6B@6LZc#5H8$)?CLjxsOG~%szfwFs<(O^TVW?EHBljhtt$c!(DRF zA(FjD`*>j)j-E_|b97I+_;5~Mw4tP!{%9_s?^i9k-?bll3@+arFjty=3=pPAH{(k) z*6(xk|14_}0G;^jvD{AuONeedAaTF$x2FDWj`%#HSTb3|4!K!vQ7a|*%@7QCZw>YF z0(-5?H}Ngwz?O5T=d4h*uiI>BS9l_(5f|^bZm6R}D1z}-`iqVPmDCn;#~{od<>jD7 zMS_#Qp2u)s&3yofqdtHFSd(0*&A{W+esEGbXqbFg6Y(C`>|cu?Twa-)m` zpPl%*e66ql9Zcc1*&>v>dTGZDh|FF#2rZ6zYSl$#q3>C)AoI-Mk8JWyEMF*8=Wf-h zq9+dpsddJ*z#QwxXz1I@v zyd`I4rst5PKp7wBXWqtezuoX9yaOM`DAXu`j_y*;c^psHRr29S0MkUqI^3E9Ns$ZF z^a6Dfbp`cAPQY)h%c)}GW(ZZiB)=L=v6iR$xv~>BWDb8PD!8!+PRYOC*fpZEpuMYJP6y}2 zP-*M;*yhNcgay%Uf@i6E;g}p5JdD*d6emTLou|YKb7{8S6N{S)} zaYr%*wC5zeGO(fW#0^|pNPD{VgRczo*}mv z!1p@abO0{i&&|L<()Za%{QYfWMLFFq9VkyC0=!x|HiPe8@ebui`mz&%rpswaKk>IPVb?kzhZAx?(3tOE=vefeM1` zbtah{M&*uic%|zZ2=T=g#>u#j&u;EYruvq{8<_hchunm}Sn!nX0lqDA_02yL;jxePj&9`O22r*-*jdi zGx#^Xdxfi_%*(3bqXvI5b{Stn3qy)x?O9?ke&1$2BS32eWA>NmcD9K0nes|tq(F(1+@9;B)Z8ChK9dy; zv-^G03g-OdGcw0KaQ=n-Eu>6~>i%-v3XPrDyt?rNN7@ohN^8~y)>_|ZZHBOP75r1` zxGt*Pm3)r6x>SGpCb^aePYOYL?H(ftWcr9wtNGmPAl3zqyl#*2mhD9caf+{B>h?8r zaA%o~2mZ0z>agkSe<@*(k>>zFLhiv@z$IrFL>eQc~ z*LrH0#%j${7Ji?@EM-OIKKY=U(|9`27ZxHcxv}ppd#Ls|bKEr>hoV|A6B~#J%cRH?>nDj#Js5<&h`1&7RaPiC9M>g1-h(px z+)>`0u^T|!Xa&g%;dVHcugTfAvkQJ+TMGNR@*ZM|izDhvFeYdJHKGeF-jszn2B5{s z`zLt9PdFPI-r79k1?=h!@xphwo@y95ygf&u-#2Pm_VWZkjF7op4^cedm;~ogd`Y*P zF=Ze+266w(euvAHs(I$NxxIk}FM^C(23fp(>)}tA=n9}sa~W2i;p14qG%L7Zk;Yh??)_xYmu%=n8euXWccfdTA>~ zE7wmpNM(+J2_xl~S*hu*aUHM!LaV~YWi>82+WTdTJZPnwT4yl@^81@eDA@dIWXIc| zx}1?b>-ZeX#ilZB<4OA29c&#|v~5l=$sU~Sr{l%Ux4rbRpJ03mu$=o84RuYraFIi{ zxvx;IPHsT&^TSJi8B!Gt+gCSU@=-b=s^RT*b4F{8e!smy@u<;ybpmyNL~T`cZ{G)0 zkBA-NaBebDwtuLHF_nPQ)_r0lL3xVbiK1(GrsyWvri1Ze1d+RF<};K4#DUF9jPUnt zJmBPmKfcMT{KE)Wpd?$pQ&_goXL)VGY1V?nod8MyG4GWy$JbYZe1PlT#>qr)KekOu z=mrV0dj$3C3mNKZ4V>b;Pd(soFs<9ojdBN<0;DT$eh?v8bdO*o7 zM;z)L-uEsxn)GsxmzEo9I~T~8k3ISny^oVgna@u&F^K-xfsEI1-f&*8d&bn zJ+Kgg4nLlbaI!9?%$N6RCeUADg~m#>@ZI?Plu9eoedw(zY!`E}zn!Jmq_{Jl+4td_ zy&VNnNL!-)lAxFt#ZkE->_ut;@DQ_9)>HTA%_`y=ZOV#WG3-8B#@Ef><9DS(59Wy( zPLN$}@Y=;g;~`i}BqH8EFHH={%{j#*mAmH6$!NVTqx;CpKX!5dV&!-prARc<>J2~G z!%q#o9)ODTD_XC45B0>Jiv8U8Efbw^eBF9wEebdpbjgOT5^FowgnLdYyBrB)U%*PW zvN}k8{~A4k2;AS#XFCJMfYMq2;1CHZpVUj>L-;(Q>-G-%8@maTczGsk3d4a%?644Z zTJWHBCvc5UL9QhN+MUs7s9bYPk-}!B>+W{?+VmjpClN2<+VmZk!Kc}_wflr42uwnuX|j0}hetTKdoqxA%+-Jp6V~-0MRY=WmUwWH$J^s!+J30zr!0-t zo2oOTdo9_${NoI3`zx3b+j?6a{pf(?NZ;RYD(w7nL^_~|QFBXqr11$(FSS_N_Wj~L zfHPtfFl(2SSMFF;x7)-$_RHvh=mo#Oll$!hP>bf6Sg z2FZ>af46U=z`hsn=FU88ZzR;Fy@GqIJer>0-a@4H%vT1X;JFe?fgBxM^(0SspNTu`|hTL?T05d>$Th3;caRx*eb_zq))*DRLk;uj2F<_vrV^I04sQ~^yUuA z)vE%ss(v!F+u2&5KOdX9SK-coU=RzymeNBN**rgn&iJ@T{cW>wYi@9NXs zC;#!|qk=sGE@w8hG*;MyIGk4{25a>c?1K-fWmjcrOGc}OZf#=mB>7*xq_ThkBC>Jw zldsPU%hK`LG7lEQ+czhKg1LdxTxd0BKAYYw!wHyGLG(o<5`Z^lI(p-*o3ZY z_4{{Vl<>z}P+l+%_OuOHdnk4BFmG4)CMxq>!BhGgUY11nKNm-9vRbs^$rl&rWYX(? z52WEO4cg`{8qwEao|+TQZ0I9d8pwouodSrm4qy#+u<7~q8}RlBzKM;mA7 z`+M|IzFf3-Vr$ZV5+mt%j4sl9f@^H?gj)^O!+9r&n@OpE@6*d4zMuY$QLy_g!ZSLm zONNNipZ6Xr`Rtu|;gH$#%W8$yc5fpHF!?X3)Id76K|Yvg{}%7F{hzk2TOMEdj6j1^ zCcg}I>MLyQ^x~JQr#C8C33FA28$T`b9XuCpz-RH{9Ebq4ut9kdpyc40c;vy77&FEVTLQWU&n69dBl7sP4OpzrImugH4!koAJ|;wWZMhE~v=iz$2;x-`3OM;S%&hafv?T>~UZHuLIBn zGmxI8z-ixM>a#IV_szgb6 zB0uj39Ni$Lsc``8r)qLA`mXqS?zhJ`n0M9x0vs5Hw@FMK*Qa#Fsu}7CFJ0mGWjwrU zr+p;oz{f=Bx1>;VdR?T4|C9a@vgZ^kQaO+c$pi=9wB-X*=M1h?zr>RP3ngiSd1yE5 zG{9kLi1)Q{-UmmC^kW}h74>^`r0aqZ)f=CHM(@)zw~}F4gjaiksb(3o{11-d-#>pn z*Keiu0(NoIch{zx_oWP(3EI+SEJsjagqeH|XBE+j_ihh7?{6}-jr$`;soL$$6=tA{;2(aW8h*6qbhF%W zPqu(XJW-V$9Qs3-++JVt{%Ru9K6Gx?4{-Q^bLbDb{(1Tw)Ma|GL%MFhH$2}HLYXcc zo<1u*6%zyag+(JrP+Hd5qoc(b99eED_L#|&e)~r`-P*mw8gj26?8nkQRz#sXcVQo~ zQ{uoTgE8payQPeDQII8Zs5KwU#y8$h!5gmt_#quMfbMt=7YU_Kt#>T#k)JqmQr=(p zu0?|L$EO*;q;xuK&CLx-<|k?%BOG!pXXc%US@!F^Wmk}E(N4856JDc~AL|MP8s6#U zBKcg+QR)+Z8l4ZD@W38eKP0XJntS#)Z_j=C)HBW(f5oNxvuICc?eIs2sD96ux7NBP zSL!kmiKWN!Qp+O(wJJPhs2Z`(is0&k%_wGC$hq;-MmKTJC1!XOz8=ST}$CvOn zLVaZX62xcE*#D+?t$CS8rP95lTODH-R+~mXqJb9`z&{qy(wwzx`Jhukl;5=z9xB@~ z^q4P}S41KaSIlRT)VXAg&y7oF0Ec1y0UHszC=paAYf%AxM#Tr0O5L}<&zQlrK0A_J z=vMx9B;)o5!Cr-X<84c4^hH|oSo|im7DP@lLa@C)_OgFIeeLg2IK9BuxC{w`*S0y-+w=?SrO_`k^Fa*Bpg?0Tdi#$d`ExY`859SKvFSRz*S9%<0 ze8_s#4@jdESy>|?QA5h+Syh~=9 zF7KF$FDYXS)O+UDFqt>t^?G(1Zse_SUFmD(uZKF9CZbIR^{3~ZPaJ)P3kY~AXu>V8 zAY4A?MQTjpBuHlt1t}Qd%tw4^v#&FX-yQhGR}|iqy+nXtS5My#Kd>$&o9jj%Icx+< zabSHL*?%dcnTOOZChlZ^*&C4m?5qsULBoA1IOPw0;HTwu`*asl*RP5+;Kow^Qt0c= zYgRj@=f;yy%w4L5Tu+$s@nlvu<&~>+*47vUOcW^lS)AT7e6Xnu3L#gk=L>UM&R#sj z|Kj>mv0^Fvw6X-kd-A8|cJFiU>k-hsWWRkxVR!eBHl%7xmKT&-FfWIp8r^^?d?C{J z%bF9=BKK&bO7D_)yp;LFVSnlL=K(=pD)D$9AGIl5f8mV~&lYORL#}Ll;4g}fKx|}R zjdOdFxO0cu9&12>TVFlMmuYkVN(}0snc!~$tU>+Nfl_JDKwMr0tS+L1bJ=7EB)&H= zqACYC;TzjXg7i$Td_DCYYqh7d=|{wICTI_IK}Ay?i4w#*|JD9?lW))cL~*y@M^3_X zRXn*CwJnp^iSm{$30$<96K8=Dp*6J{$3;s7U6cCE%jjhbJ=#Xs-Fy#Tx#v!5*UCT4 zVhkSqX+4Df#}u|Khw3A7zF6U&Tb>)N=X+#v9w%Cjh8 z<1Krc@WFkdATeRG12hwg&FFgviny|iwC)f)@Q| zi^FPBCuS~@ zH`;o>o}o2N)|BM_yMN)@mb`<@$@l`7+kj*iq+!Ip z=nuJ{qKdqRwNm#ktKy?Ol`Ie)1kSg@&`t+3=Ry{dRNJ$6E&SfnfJ9m7{=3gfh&0|E z-;blTd`YOg1pjO%XT^NOE&A7O*8!Om>On`(f1hgdrEQ)-*Er|t;%`CKJ&3(pW=W{C zUWR_Y8U^xHydQB|w0+f9r19kz1xh0D)kBQ5e~HZ#bd^3U_g35vQ!DI;gFFA53XpZ5@s zz3rnL-O)$586SohoXyBP_(VG5UG@4J2GTLFK{W(^PxmErLGb?$5JH*$gH<2_Z*ko(=oj*m`Fb&8-b;@ zo?rKH^+Xqr9hTVp%dgAbT9YLd`}*62&@&&fG1PUDtlIVSUa14@8rF2Lc(&6 z#8M#|JR9wK10Uoy(i8Tj!n@IUGb+jv*vuy0lsO?PG!HturnsQKU+Kx( z?}3AqoIJ+N9Q_D9ZAGo+RML0Hte~_fB(@KN=BN&5f)`d-bg&4Uw)SS=JyyA{Ao^q! zP+%8_8PT%CRNHa6hXhlyPh<;8d|o6MnOY5*Fp-6Rd^okLHh<#8tJ`02U%QI-JQn{;t7bwP}q!8cNAhM>fdQR|_8~e)NA*WAByF=^Qe7Xx@7GQ|agH+lXy&w9Kf3)lN1iII^oUXD6PQ zi%dR7VLkrchs@V-1KGRvo)P6xCg5cWcm(q0{$Bc0pJ>^BZNcawT+_?-Do?6{SwmSb z+%uwoCWY97K#5s8<@YxVVe+ySn3DD(yn$rW*cyspN+Z#)0{a=jS^emJRe=kF;~b>1 z?L~U#+fNrDV5I*zZp)yc5@t(UADpwpw-9iXDKR_F?UT3OXR$N1y zp^HB3;xA8iw-v^yC6+{Bb+;oNol$RnYN*VhC*1TJ)F`I&@A(reK(Uei z{`B|B|ny?aS!AN5aF_4$n}i#(J+O$f4Rz0G^8^1 z&FiPA8tCil1nFMEOO5Ze7yT5W`SwuYZZ3zQff|MIytExl$RI#dFZ6p)z7`g z<6L3?M4w3yB@|^bI0%bALeCXFT_@*zh>k3hW+ODmbA1jm%huSGPerNYKWqo@2qYUI z0iuWPA|)W7SuIa&hH5P-J=Qgq9XUpO(`3(bjs%Um>}*`+!N)T+@Qlpt*H&!{w z+Q6&PuEDyOnMVgy94zJKo20!11ON9KRVqc{e;<-;Wf(o+r#Ac~PbBVGfW?*cu~&WL zKflO6%yZ0+*~Gn1=URS~YTs{?$)_=3VQ>>Omkt2fvzv`DRf?0H{-g-G@;d!WRfbvR zxuuRKd*C!U)=4A%n==jVyj5&(q$Q(iB|w@_`D^IOTa=h3Em&X15sl?C(lyiMwF9EO6Zn zh9}a_k*tin{N37YVvHwrLwFPpR8C=bF7$HybMtpXA5G%7DNoL4)d``mT==g4tE0O9 zICS`d=6=_~D}G3?HS9o=^_T?p0X-zZRG9gCh-7$epS0;uNQSL1R^p`9wv)?5kn9zqQaJT!fxhB}T-7oL{(XY4*6#lW?0=-B7 z#}<6v`~0#$%6FH+0b)bvr1F9~aMcXakFn>Iur|i)7?~XKz~&yW=bV|^mu6aD!d2@(?Q=3K>fQ-U;;R*z{Ec%e4+q7^z@i=W?;%21J6X_$tEvK!=A}HcAn_nx}=l z?z{wDyFJhWdB6db8@=!ADZNDO$@g!`qiZp>V{S(gZ==0t)lXfVv-^}_8Cx8z=5!Y1 z`UJ3PnzgB8;(=i<9iYi)A>B9SNF^Ub4YeeZ*pm$?zos+1gX%!lKJ9qbseS%uVK@n+ z=EsOml4cW6(4~q6d=?{`-3ORO>fdPrG=eXt^%d`t z*!nzu78|BvIvL^SZGctl;Gdd=WqO=k?$1`UlZ+|}*T#jD2U-iXszi*m4<-3fptTcY z`szg++FxTjJQg04^mT!uBMHnat?P|;dnc#S&|2Q@x=}6 z6cq16UGX&obnf@JIt;6xk8kyU*$b9!jcO>p7yYEs8za~*D(S4@b8WOq7{{0Q#)`B;oOqL zr`Bd}&i$+M^)JEiMiqsSbAaFw9D_JaVW=xD@g3KZV|Ju|7ht8{4{EM!8m;?_r7T+z>;Hao5{kOq#Y8qgn9*E5Sd+ zxQgV;avD9Q%l976boRZ}bpTEh2w!{T29`PgU&@E+r39FC6#kg6s!|~NNC8JjxkT_CH9$`S6>hDV!4#S&zQDy1Gs~pxS(OnN$P8ao0>zs)rJ(R^Zz4)z!+D3)f z&sj^Y1>+xnX7VE}AJd@|#D_R9`FWmUh9+F@JkGIJ@QcCjbEq>)M|C(B zk6`-)%HYwy`oKUZ8uD-p_cF*-p6<$-PnXCnd_j%g;IJM8PRr4WbzY{)H zJl2;J&E6L6<@nV3br*;^gQH&&?EwPY7xMTjSQpJX2kd3w*e)7t_KTkrXJJM=8jP;w z!?%k7xLGnbozzO0hi2@jJEvRd?R|ae+hZ22h9(HOf=-c7^glT-d23#Ept4G|R8(Az z`nKdr#j?gP>iz&5L}$-;tXInOcFOy20{_IOi1#Huev$gY?w#@Yc2Nm(uBn9I!hYuB zAZsl0M6TO71GW~wwb-Q+QJmEoNv+BE*M?heMI7~6j%EGT*cCpcGWO_eO5XE1`%RQS z@B7QIDn64Bb9L?Yi}g23n3z0ukF=)>yK`Oj3dI{$J6p2%HTkGB8XZ7C*T?4Uxni`0 zLL5q|TNxR+8;Aausl&huMG3lLgGLjmLi>=DAKuCOIs7S_q-N_mfzF%QQE+zX6(GYwKg|v`rPtdtZMaXQ$^>zDFfRojfaK;aiGHH{I?AY@949G zqrmWvHFrRb2!|*93;|qoN58dlay{5h4i_X z-p-`9MI$Ljt%GJJTmx42zW)q|TgPv2$ASqN!g)V`ET@+jWbzw=?Z zQD=FN1HRF>I7D>I-}Q55xd_)_CeRPk@V(73I4+|%bFs1<-elglmiMLZ(*nN?qnSH< zAB&$&>B+;1JiAgy7cOQrI0=*N?-UHv)6XaATLbgYlm?-Ya9M*xxGiv#xm@Uj<=feN zrY+NEP%?U~5I zptR@U%z;CGodlbaQEDNnTqeA0r{C(cQQAiGfL99yg7^Lr?;weIA0>ZFhRlnMQLFJN-vv)8r^Qqb}C zb(x+hW1a%aFx)s38z&ZHn8dvCy~3)r_PD{%Wqxj6N@y74>lOP!K%1b z1IXyo<5APM{p?Ufm`nG5>+hDF)YzIM1Y_a%I~7k3Oh4J@UZl5~P3fJke&mnOz~AQ9 z{GdWE_W(=;Na(d37><$l(}{FXsUYkdOwN1E;l7Z$ewD7*Ud#G7?gSCF(FVnS@r#n| zRsAUY#V)NuOWs9+he@lnN!#q4?UvvXh=|Mt;5AWlCgpRyKY>uiv+(tx(KLpCsn~!e zZctXoM?>^|$;sMlqE7on`<|JfF*=1I%Za37s3{NoEgJZvGx{woCHY6wm3FBH$KkI; zBwmtz3n6(I*-CbjPk$eC&OPUzxid|J_%FZZS(;`SOb{4|mEInUSsng-yDo40XYTLb zS3aySd-`&`!B_(&b!9J9$kK9!V;ijUDEjpt#J91(tM_Y&J={B5n9BXHt#@4l3SFIB zBcjYLTnxyrA0beRa@cY#;`2ctvVG8<8f`#49sQhU*y5Hk^vQR{Pd_nHYQ}G?hhMex zr*2Wg`(?D*9xecLGU6O^at6ty{qcS`xAMbjI|UtSRu8Tqf$=&7wwIM}maT$CBnBhb z-$~&*?H?hi6|M(19p|qm$?Q&ejjxM}`TWkGc4lHkg16_-E}7cAYvj~CMDL_Nzvr?s z5zc^WBXM_Sy@^fvsOY8rqkYLS9k$54luYv$WJKZ7)r&(=%weMfwALjjxlG@veZvjn zuBhD=N)=&rXd-wQ`tGw8`HOt<-rtYpG{4`izV1)p0#l_vFze2!Ye#AVm97yy<&g!(}4Ug5i<^>2+DpPP3N=VN{#_Z8#pB@P!f)p762AdG^}NTP#;^E^T`mM+$Z4s<)a|@$QgMZgN>dbpm7@l zf@+lC95*4Wfgm-LUTdBSbNp(QMPd%hwk=Gs7|ip=znF0s0X0IPCUuKtCGLexVyu0>5wR6JJAJ{! z^813fKd1UG!8UM9ys}4qC76>v13}ULcXl}Dwzcy`itU1&yoTMEyz~8Li{qd5ER-@M z2(H0#39pOgkAt3gwq5{#!*k?tY_WI?f*>h@}%L`#?MFsMv@|@Twl>qa$gLq+N!3N z!}OxMeM_{t_#LO*mTkV#MREyWHno$ajJ^%eob&Ygy)1cqpx{q31>UFIgAKtC`h|QD zG=1h&q5%03#vZ|?WsCid-ltNe#=0mUog!W&4>Zhq=YWZ_T z_-|=Ygxe)&0Sy(^QY#)mj}?7?%Fg0O2}p=x3c-842%Q_70`_T9Si($rA0_<9bToeU7{21uP|Z3?(~1k7MmQ%)x%!hn5@E zojxF!*H29!wSd#k_=NI9==UiZFW97oRk`QfC^)zJn|c{=L@{BG>LIn+rhjQg>o*?RwdD4LU?}v$4u@(%K?%$3;ZAJw@2eD-!%9~$119W$s zSIx8{m84vTFp>!I_yZZ8+nV)RmqM|(dlY@|?)T=s7Dp#&bP}wL; z)#J#<@R%L$V=9uqE;i1#;?D|usyCq?WRkFr*3x|ckR&s#Hj3~1fIQwS6XYRvtxFu} zuk!t_ve@KFL|L#bye-5rC;RGDZy;uO=oQ56YZJj#cucf3Ee|z139G3i8Wy%Vx;)+9SYHDyl~SesT|ZC(e5%gjzP$EHkvuI} zT=)#W?Ie+F&_XyJ^XzAPJ_V5fm%Bcu%N2CL+kA-zvDZOEFw8=kJyI`>j$f~FKs?&D z`w;n6o;`N7=CM2kXFaGzsPK`~VYF~?uCZp*qe8$9R!oBvaZRltva{1qMz7mKZi|kZieB$5Wio)hcaJd>L<%@bZIm z#35R%ewG!l)ayu$E~&bnon;r73EnfME_x(!$_zfntP}M5(*UFAlTJ3MsUTS&eB!6E+#bTr4DMMzdGD+eW)X+(vB-+Asu23E^v!6pI7Y& z>sC5at6yV!M!z~2^Zg2IRKKfkh+m;~6KkTq`r?D_ep#|QFQmbzjmHt^mrjkY<(D>n zWQIB%0H?0?YQlA*9Z&b^{Z$9R7tKii+fv&B&Tzk7hbNGq@2?HDmI1F9M38PRN|AYc zX>?z>VFduDQeZsT2)%59omA7TxAH*3vbJ?DR~AyzOI`v#^NqNN!XDl>tvlKNgx^k( zd57osa1SZiHguRQ0>7+J@39pzoIOQD5qoA;L2fn~uJ>&DoRCfgurohXZ8PRUb6JtdGaBAD>P)lr>Fv zNg&p?Rtqr51T}g0+r_R>8i8aI0WFj_?{5ZPWb0sjWYF{Y-Spl_x09cFd)}#ee~mQ` z-;$$c+!D*YLO|_kZ1wLUanxTkv#3e!hnjW}XV35um0D_@eDPvo<`|+AR-QN&d%@peC zp0evq*r!TznnFkO-!Mjp2E+T-&O|q^h-hT*OSVUPwYFvD_Q6S%FeFhvXVwp+*_HTM z`uf8d-VB*$)3w_ykmfe$R9t_G+YCb(;T)i4h{=(j_T>VHcvdzQHKnk}5F1LwH?|DV zKwKTkA((wKFnq^7dvU>)-;2QlP!dfKWGu4jdgs80Vk`F7oYcM}7A7IICRF{Rn+$P* zQu-ap_r>`EB9CDHyns?aZ}RQFNxPDW{mH+FwYNPI2g9E-?1t6nLEgp!P+1jjo64R~ z>dz(+BmM`_Hj&C-XpFkvm2h81?yIsuJK-q`Qy6xSSHel5e1d|3OR z;n|}5p2*3WD*<+d$lV0cW6z!maX|Rw-4&&7Xs0JoxkE0VmY8e;YBy+|%n{$bM;uDv zN%3_5L>F{80Ex-dpI1IxiL0y&xP#4GEk%AjbieDqJU(tCZzYCH(558ZuZ*R}mhx7V zCpaADeDI4;b5378Ux<$wka(KH^FKe7<2!g2F+N`aKr&vqOMhj^H` z-$O^SYksb8*D@~{DnhRG53CkK$6xvJxiv#5oFOHJOA*w;iUI(4y0{Yk==jV(l1y5U zZ=zD)_z!XMo079&7muf+u0IbVG0f&R1!JDl%omTwFge~!HkEw?wcO>jwuF5(a`!ei zBXtws7F=5*S~?|r?m_x8#l?q(Y$A*qK~51wf5flO_@^=u-tXIB{bec#SZ^!mC8l`U z8@P|myn154M|w5#k5>cAej&Njg<@Wus2>-g`oVlJbvo1r>12?#N)PgjHvs~Bg2kU# zr|M41-#z@NsoyR6g!0v*31)0RsJX+53D{m-4us;GjonW(gx zLP#9u_+b$y!@Xj$iv0nceCB8pcJUqi!IhB^Us7rnqP+RUOog}@2NDj>VoJ+bEkCrj zj(aW^NSC`XKlcwcnte;10wD12O6E(bG6CZPRWc^8xbtLK@T+BZBNQR%BItvquKl3R zIJ&pu8&az9VaAdxZ+W{G+i5tdy$(PrCs-9h32f|sUY5i^^nF?8?y$KB=@ZGV4z+%T1#mF=%&agWURnyOr*Rfo+HUBLAc#fslqe)rp9AEPM_e<*on(8 zpmXw7Rg)Ew>-&(ZJ`A+eA;>?uoydqjJ+Q~qBc+IKcCh|mH0V!$1jAF@D)`LCBjWi} zR(eDn|1Mvk(_4%56Yk0@@P8Cm9YJq}91ca0;l*7KqH_x5=mg2c!1qnh6qHU+(kb#@=yFqu<E=K}nRbs4?_DqE0KsuKa(f8{AF5}Zt zbUA2jL;IDO)U3xLS{IrlbQL=KPf2%Q&Umpd=`dknZNWnE>&hQ!sutNZe?t5mWr9l>NRjLc0Tj{-GLDDuVeb=K=4}i%u5#nwt}O;zdNk9WBz8VgG0(|^QY~{ z|GCW;8A#oSO1=X_@!qMwGPrKXV3Q1p$V6xDVfxhLx9jI&OrG7j5gf~n*ep&Alp`^g(FY~K@$URRootkkFs{!;kS1w^kJp7I?Xjc9} zJ~23fd!m4TvmhUQH(_QpyBPHy3%HJC}$gSy}2@(Af?sdM0X!OCJRzJanmjpP{I z0!~$oiN_O@7hWz3k)+dGByTIk`0^a&G5n%3CY9aheMDW0hXLa-kz(C~S|++FW$#jm zn;dv#9w=rbrbZ_;r_D|pAqEikV}~}A4($*2olEj<{_wG&;RAN^Ifswy$IhY90P|js z)Lr31mh`Qy#-U75r6W-4;kvu>lmOnEuH+MegmdQ-9<>0(UiKdRym*cbcX1 z_tV2CH5fFSJO;e^2D2?J_4ARLaE#cgMo)v|X>?Kw9)@-C3DYt)NO&*`^6>s60^&kd{ zp^J_e^d-L*^G?1M45WaV?`+VGl^aCMpN)QbPd)KVEJIG8nyk%+Z3g=yHg>3p6b}(y zX}iDb*jplWhvtZUKY}FMP^mv%tu9SzAoJze3fZ?vbLb5O!MYya2KPbB2ST8lzESEX z{PZWRd`FNJCHF`;e=CRwedY|;Z@;e`XFuMzozDCgP&+q{%v~(#HRMji!!H|gt^8E# zFBKm6Bab^=24w0tvkkvz)8|y4Up(q~^!I|4G`vK(t)w-AFhibcw+lLgYPG}W!ipKp7 zL}Gkg`rYqI{>*(IBxA+Hre&}c;dUEJ?EZu$#3glkWzg!4Zq}{>FMOY}@dyyabbO)w zE@BGPAIbf$L+yajjqSo`oas& z?w{+GBMkW+S>qDB?z*5)C<4{ngLI`blVih*OUmo)_Qr83@=4;qF5v+ENvSsD(OeXT zjp+Jmj=@JFzxMXLO-!-S=DzGG{LE(|fkH_w(%sQJ=GUzrtb>2}D(_~$g%Rd`W@jT8 z!4U4m6OjoYKXT6BYlDIk(sp`Zp`CM?t6n)$fABSn>6n-K96v-to;a!7?g+drW49m> z%BNM4r?`1jhXe8T3ezxN?D-41wm!wL$6dD!P?Ua7?(wrZ#j%E0uYuRY)%tNGui;bx zto9w5$b9{=@}BxLdzzMX)0yuZ8QY<#o?o}&rA69^#~XT(k3qFmXX+=XxbcK*&^$9V)ceKBI;-?ydhp?l_Eees z5Z~|kg9D(C@L-5~&f#T%BfLw0{u*;a-F!PAcgDIbq!of>s6Ap`fI&lSEZV}B^P(MV zh!v3oC{^m{d?09E0B?FY{0)lSEw478!LHKOcwzpux1Yebx=a-5mybc+ceh$O{Z5+c z@End#pEoSZU^<1bUn(C|UsF44ar7ykhDiyiIWc z!D!mIwTXNmfu^RB_XG;CIwQQmP)fV;eDGTU6zZt8(HW@i52&X@l}`Q+t5vWF80F~h zFg>|%2qE!4{0i+Jd58wc;9^GS+Funz70-};h3Q=d8RqcPD34oh*gChMY8A>zd1dd( zfAageice0DD5I;J`f5~Q)(=9D9(DaC_kHY+4UtYo=f~fW9N`5?f41EsoA98z7rFXz zL7^ftQ$(^UfJ89e9iU(~5H4Hm^xCg=EyNC=c5d}A9B`VCvr>cbF~{?LJ{*+GG=FY_ zG9DxM0Z>*+AB`mxCwMDfZi5}&VT$n-Ub+S^*60MD7Th3?&;IOYuA3^|OfBd$A~=x)%&CKn-h?2!rITKR$(-4mG9Q+h@95#4Lq`Jhii zw{YuFkJ)lkK6cq5_t)~kF(I3M@&g9o|(>~}UbQ8`3&b=K4e<>uBlyeko4%bmzpo(0n@*kv|Sa|aUd&F!b4 zKiom7#({&fo`z&|xj{OI)9!fFTA|JOJt0jAqlK^{d-E zWw`G5Pyv^*Z<%Uq!;+?YKsL9zijYFzGpq34-yY@$LAvX!5EZ#@a!ptkcCX#(w>1TzfuKmN`P*c6ck-6b8wR*@7>zZdH4wED$3gQwG>}=zL+qyVqs~!niu@kJ$#R6_tL5_NXJI(GN!?hOWWak%k3U8tL(BuBsH%Sdfwl3f z2=J2N4#G*l@U}F`Cu{YbS)7Py>fXx`l&Y_b>IDm|JL$>N-!yN{uhz}H@rv{8F0jI* zO5xDCf2z88KjdOxAA^EN&HYY)Sj?he{dA%n!TQQDW~c84dhd69#eF5)W2oZ=zVxf^ z$|2iuf7W92?FKiTR4A&1!2lClHoDo=Sb%nliUONly=~v&?%nvize|ti?5_kZr9aQ} zslXP!Uzc<7c*NIyYkUDDZodOsJb)^ZvPQX}TsL-CO!j=1I_tLGje@ahgz%OR!Lo~p zdWA3KkLnJ~tM4JuQ)OgM!|}x)V|ITIEe)ZDL`b;m3+#>hIq^z3%))-}$9)dgcfya6 zc`~xb+)sS+++Y$gnmNJ$WX`nBeb+PY`t}tPnB6k-8D0k9>U+XVhF8}6-jd{DgfhJ*wGMB{wMC%FW3?k5K{Q z@%BTUo%^^i?4}w#-!!=M8GRn=fxYH?bfs^+#_QF$8Pm-UTDR`*&MAgprSv?OUKb#S zklpLgygy_14yRJ*ko2it0T+}hIlHfG$7_)uj#HEG>??UPgLR}r+UVQBj3D&5aHdmG zA%3MC0mbcZ6^qM-Qp=QQK6s-W=&I9WjrYmkUVItGL%yxtvy2d`#mSWFW^kAa`o>L$=L~?kXl*zqo0iXtr5#%S5}t4B|@B; z`1pIRR5lh<9)J?j>C*-Mf{(8G!9^gLDH>o{Sy#XO^PuH3>b)!0Bk`%cXeBx?6i4%z z#&X`g``3(wzxa#x4)C15(w|f0PJ3j#*JB`(`R%0dc<(Dmx_x%HEytU+rjv(QPSXtqx?(TyEfW)13GqGK#hk0? zu2Wk-9|QAqVJ6+5%UGLJwtwi$Glo+Wk<;3~app&AecVJ6Aim`7s2l|jE}hcpEI_Ml z3ujt&fDFUo^L_9Z28#Q!4Jh154f{x${q=4G&pJHM;!y#%mheu|d0&MJvX3&f_C9&u zZ^_gj5z@X`xrrv&W{=#0wels6DVQ!k;uu$MZ%dn8voc1(V z?}xLX>O-)gv$$J1zCg`A@zP5Y(a&IGkK*ieazK@B%?rd>bA?AAEjcDO&9T%(&YP3GXPbEcmnHN)GiB{ZKt# zo;D~oZ2OKypv>#TdB%zii6IwXhXI;bhVe59;xH2xo#Xg`nl;y);|P`d%@I>Nb!WAc?;!nGEc_Bzfe_@a#S$h3ZB;$?%^JX&YgK25Zf7tAS5yk!Tm z`kl3@%)K$^i%$u}3?7O2;N4>b{3L&0&db@g4LVfdaebt&0h@UB)BIqHvD?=I4q1!@;8y_%W>DTD1x5 z8;W$|qu=yEI1aUtOKV86%pWGvbgdA@SYy0ns=ufgq}zWFx$W7sANn()~0 z1n|AhHQSA?{C6TBxqL4nr6zeJ<$HaPXX6^_Ex9q^HMO%!r<{=tYXd8Uq46>i9XY*~ zeCB?1HdtyJuhWZ6UrXz3`GxYq?Yd3~KneB`Uezy35FGET;+>fk1y&OM(Ip|9d^ps{ zUh3b8ut7>&Yc`F&+~q%EA>r|ngu?(zxo&XjRVCDeS)=s@J_wyZ8|K4^2owN?=5G3V zU!R_k&f-nRWuK}h&9W%aHJKaG#c z=r4OjNu}u}Kx6eje)hEpqOSKxwRvP}+4YusoUou)2O}4*|A^*cLh zLf)6`*F-;{M*seJw`Y083xx%5MR-J@4Ja7yGqZ6Dfj_7w49fC1DHiO#rK)4fiG{+t zsz4vor{|Vm$mPGU`-qIy=Pe1%W1*&tesQ$0u;e7ILcX4VzXdYIq}Q5F_vA@9Q~?Y~ zEy>AItnSRv9P?3)Z;^J`Y5D7scQEJ17yP6sGWeYb)$riGH!e;EFNDhwj+9c#(%NuM zy2$Srw*=;+S|<(*p3p$kZ~j2PD`p7IbI#Gl!b}oi%PFL5wtJX?`>ju~v}~c~`DjlA zzd$U*zUdHyQZ5&;=LU+UukxyRG<9BxWR7avonNKcc`!)89))& z5-RhL@&V5C9i=TH5+&1MQuRL35twc3d-#yY9HMxT#AHS$@2;H^R%h2DXRD~bFAa>?;9HZQV@L|FWjHc>f@AqVB!y# ztnFWD1w#r}et>s2qtHuiwnbSdoryDVPrUJO>N}S4f@>HWW0!Gy`-N@yK4aQ!ep}Dm z?dFh2=b5@I^FU~4MTWm>WATic!HwWZ>~LRygW0C%q3gN7yev z$y*4AS*HH!7Z?*9lxAlb9@u*egEY#DZkh30& zoFne3{Ik5@WsfQjY^1{v>$OXq$xsZ6-N$?CZp-T`kURZPF7`)oCYL>s3Qzu1{;7qP zo>Y+4FQ0QP-8$WcySSpa6}OPcBm^a-xctps#y-#i%db?D8pHEqYn71Z$#wir8EaO3 zg=HoPBoK>f4#qD@;(NFR@*90TC3zJT z^b`&*R5r865$><2=zYJ_z5x^D*OgqpHwfpTA4AsCC8-AxHMhBE*ZVB^&BCivYft6* zo>Guvc$`^gC5Ha1+Mn&cLcaWHV4-qNinfu{;8Rr_7GWX0eN=Zg40E4a%CQuQ1>cmh zYE4zm`N1!NuH0YRk8A>1fz=|KnLVC~dIaG)xAUIT3xs#eU`aU3?T|d0oiw$Dl+I+Oyxl4}F7qNfJ)0E6Hf#pxJ?7f{i z2+mRc5EKazSCboDAZ0{6n>!d2G2BZZ`w;n_JM7P&!ar5cF?Fh{Uja3MzP_Fx309qh zja`6JJZDETzBD3Ls%Exb{p`#@uSHmh_Y_*($MXx*x0^eE_<5u|ebc}id{yd9y*s^z zqM5;nkWaDzisyQLO?+>@A0b{V=Iu=*A;B|YHSziz=Kd8>aQ(TjXFVYvAc1=6 z2Uw4Umj#zBN9=Y4GZzKUM(+E4j^m#un?-!f@4Aa6_X~5 zKOV$GNiz$3da38z8w@`iL?nw*+4ZD>WO>V~di$OIo(~U?hTQK%^dMPt(W^$osFvni9a1Xgl0KyvP#uj zwukGRv7(nlq@?{uxiZe!332(df*JCCiLYdCkek@&Ifq1Tp{r`lde2+_o0Iy#%JGvmdu1A`JvAE z*Eibb28GCvyb4&^3dZYwdk>S>{SWm_3uI-NKCBk36M3bOxMv*7R&4Y_%Q&oJsq0Z5 zy_|dFLKAy}B0E`svp(ObO;Kz@xCYol(JW?U&p_GrlHT)zNWK{)PDCzk%wl?6v4G#UN-eP ziOplkUD=7d>fLzrgA4%@+f&-JrLHH`=l2y4TP{gW z72>4JB?gVkI^bV#`y259^+NE{!2AP1@10kysDOl2)BT{HVD~pUWzx9U{<~MiGjj7^ za5D>VdHdp33`mcBR*zmqMP}kHSl-aSkp`$hzK&?=?3JBrSe-jVFz$iuLDkkg)Y7TS zRZfy6J`a>lUb(V)8xWxWG$q7lKjzBNJnSD|`n1idOxdbR&i!32Q)r&%x$AvpI*0FN zA*%rL%%1uU?j55^CHu~Q3&D`#d=kwZG9$^$37qcS2ZYO(B>5YD`FySw8#SFP4NAj! z**{1rv02H&9xM7-nN)$_VBPnKTjuRAbu!p>L(36VD!dd0aaUr3$vm%ECH$rjwwUIW z=c0ZA!)pc5+74EU&LOZ^92peJ>ppHjP3VNm`=(7`kmF|q4mcJWz_!JVuIFv+Juf(V zCnt)HfOUuj2xYC{G`_<9lOfg(wceX`wfgLL+#mbHq8X?AQ%txPHS9b~efE9$j22II zaIfp3$SLPB8yN@@gET=6y#ROr8jszHmsUlK0^h&>z=OE{*gR z3*z7&7NwW=C%k{^YfeFy#qZIU=L|-q0i;18STKwh6k{gsNC=QT6)8{`yjyrx!^Sxm zdz?@T8y{PJgK5#{bD0eAuJ7Oaw6f5*E1sWRyRi`dZ)_?~Ab<~#*f(GtDynfXqr7yN zF}u*NMWq_rw7&;5d2sOLZ29JMb;i0>2NW`0NVy9+z*G&Ht6mwOB ztnVYqJPLiL`8OGN$B6iFV^R9IDuVwcSO199X;zJ@*xoPg2&?u$WMRfvGe}NUvLv1N zgTDdOmp&i!RA6e$#`g_%e>e^R3{g-&Eci8KAq&k=SIf6`dES<7{#@#lzOZoqt#A6n zL?MV$P@5~KHY848^!Q164@C;mV2{e@EnfC|qx=T0VhSXO_2;~Rz&zj_`B$!;@|#!)BiNO&`zHu~#ygA~ zwPu^4nZ3;KzoFh7zA9Dg+pPesjpIfwB~~^$@j*F+hM#TQD5^Uf7+3cu57!1 zi2A(GRvW^7PfKxl0iGdpi>7O>TvP;ls5NV=NbY8i$K^A>K|>P{{K7x%Hj9Gi&=LFQ zlBPT=CyNnl9`slM0^`evDpTk0v1y4bTr2d~mz@J=@$cTT$%S6Hb_Ga7OwwFDrl~Yj_vN8K zh%zUl;|`496o@AYO-vnzpr)1=de&TmjH`7AAl3+O*0ftn^ACa$m%Yw&6WQh08tg#WZTKz##2?R^dpWFvDCFUVr;~?DPJKWCfdGd>hs@ z>+c!5_?YOV8VtAw2hC*J0DzUBcM2li=QilZtj94`gN{XVdwr78Wq^?ju%G&``QnJ@ z(;Q~`7(M;pSJub36)QbuSGqQ!!%`~KazE%2ucrB%&X2)QXbv;okC%DApk?tWCqu5oO`sh%{yM&noZU z1)tKahc3%V2e0aDNy#v;u;CP>$TX&~V9Whc5~9~$8=(T;9$toV{{b;U)fVT#LQePf z{PZr7*z~Bq+rstpr{eU|S=4%MNg7}5sx=URugU|C@pw7Y{qyKSqG6o}iYUWYNvMrq zpmt4N9{YrQ;%)Z=%&YV@ultA!sEmmTHyRmzZp&~Hse7?p;DHDxitE7q*>w%fJh=;D z@VzGhkBD0j-!i+NR{R7Z_q$!!UBq5aAdB+!ZLXN@c{Vm?6+|;5)m2Mit;?qdpf=9IhX(z>fxOKGr9UlrO2n4F?m5GqX(!1i6@@7()PP?yeiPitk3pFbevIkkI z`#O);ovjAf%foA5ASS@9q*(VN&|i9{{{wk;&{+m|zZ+R1dPmBEe4%fAi!2hllF8|y z9p1Va1OH@I)F3ad2DcI~gjMdE0<7H-c5b~)f4WrR1Vyp=cP31ViN^=8Y8?DSJzoKD zi5Wlq#{=uDzd{x9weMtO#I8mNk@!ja+}zBN+6xdu!b!gS2`v8TQF;H4g8Zq~FTm4B z8SRIp@qNB{{kBFJH~!*332ARx{qe9`dV>OxQVlvOGQbq4Wbc*UJwYaD9u(SK9)|to zzPdOB(c(VHr+9we3{=T*DS6<#qJ${y`&s6%zYWW?UVcdHS#+3e%h)SM&n~9YBPT^6 zNQWUyT(+}`GKX^Cj!;ezagD%wL==N=W0sb?}e*{XqbP12!kZSl1GNd5}Y<+k0<$VKK>~pg}lY87h65<@; z%(~FHIm(^jPgrLr7({q-{HoH5|FK@|(85yfI~8fF+xLz?u%JtCvhqb6xhY-plZtcle&PQv=*+8s@kA^Q7ge85sqgRPT|oJGsE(4izTq zSE|@@W!Qzo7QErflo)Q6e)XR#7`y|zZ?s7u0{_X`y|~{HuFL(6_Qoa%)!?=z--7uy z1Y(Z(shE>dIlO6%Pmm}kK{gNjxOISG2pbr{D9_VbwDktuWJs6W4SzB?b1gvZm2>LU zJ%wa~e8Qd(m{&M(HlZ?KAi3_Rvi>RfA@Y~DpHz*WvPPnVI;+a%3l*h4|kX4A7kM-@85HEH})bq z$mIHKwvhEX&6_<{`vzx+Wq&}coqASYw0)v_bcnBf!yH)zx`uh|_>1eSobl4DS1AAJ zK${hk5vvG(Gs+i*+j9({l0UykG?dIx=pAyu8HT)_%krDYaZtCh*V!dpbztn$0mea_ zKD?{S!}G{nq;Z^wz}&}N9Dg(sR*J4gCq=wtkWb(40PkN&>$O$o&JsAvmxF3FJ@n@5 z1pFzJqrp>$-rJXHz7$H(I5p#3B1*Wm?&bLE^_q$HSd-i91=B5qPVP&%C3|sET~jdy ztmVUev1Ov*qFCZ9cY$AJ4TE%-&_B@4MJ;$r*&gIK2ZJ)R0g@*`u9hl}OQnzh6S?fC zj?kjNxnOfX8TN)lU8L;yd9lSox6~NFKH+`L=63NCBO5$3d=|~2}?-^Qz+qHp3 z@awH~&XWkjdfm8}eE_ntzC95bn*+U!$%JMg&vgKe z^DNzoktXQqoj##&&E4Ma`D_J^3JK};n4SsfwAuC^H$#2Kq5e|-cXZqVoY)d#rzuL% zm?kJu;Hv*rAUH#?mNXI|*&CuYqD^BxXGC^oLYHkazh1QqcNO4KPb1$0bsJz|4Z7w^IXENZJTuf=a9^0?eiK;L@@ymjb~n(1!` z<99`BljHaB5siZC(C?-N$OT9-{mFjL9>foMGQ{x=CI)^{EBUsE357k7s_u${d_C8j z`PlGR0!gj2R8PUQ4&OZDKBV%pj4!10BQN>$G1kk}xmDIPD4M(XgTjA{bSja(hu()3 z&jGuwtwh`-d)hGBgoG-#i#`qnbh^(*Btycsr2$Byldy}rixPN2e7W#X;8W`+BO^B)A0dBh3%$HC5q>^h;j)Cyhapj)bfH3Y=*fzc!4iHBQr0V^}{o z$_??NHzs6OTQlTb$s)R;RzIS>@oVntiMz_e4!cqJ3j#0#m0{d=o_LSRPwI-)WtJx1 z&Wh9p{1T{eZB@`)Nrx975VuOavs+@WOSQc3m=wb0wV=Q?t&hiuz*)2z>o)s%Nd4YO7RGxZ#8y&an*W z{rNd@7rK~BHvU21AWF*`raa}+?~B^S`(00dR#GX($sm@(&+2ZrU`n%Ff@Mnx6m#5{ zyA^Df_aeVN;v%z%ZRB%xAC3bzPnOqS)Fq5zG*=3ocmg`73y@Lx~3b>Gr&-EdQf^Nrv5T0&~ZNXvnIbB`!Wd7>+^ z2tp^=(3arzK!rIy%5NCFac$Fb(-I~Tm7&;@8Cx9pozCU8t&lwoIR+g{ugkSYU#eb< zeM!KnoKx|>{1TDMma${IFhV9m#`{jK71Z&Qw^?a1-dVoAEshe(u7tCJ+CdzC-R~hg zM{sVscKgBp>U`?Ymf0$V3tM@Mrr>6NZqVzB_kOPG^}iA*{ox?w=r3lB6$*I`r+GZ5 zUvD7M+ZuT=V?w#6@y)?{i-=Oa^goUaRo^_?whnioA6^1+fCb*9>KXF$3=O?(?%2jA z9HPEsf4I$}$jh>YE3m zW=6uLv;w4_D9)6~S}z+5tUYBC;h`$_9Ib+Co#+jJ7f7cU-Ulu+Cm!}D+@5ytE5cr~ zQiPf2MK?ojR&EkM`f95XC9^6)%#Y`+sonVuFSLuX;mjD1BVJax}{z(nO zzZJ&>Wd;Q?%O2wB1oV$D8thvAC)nWRkL$P-oWdu!CKhLy_Sv#)9x}h@T!fJsh-~$V zVray}vja+g$GezLFdxRt4vW-=BC;m9+!o>Owd|Sh#VmnI_0dq1;=GKVN)9TEgs2-m z-H5tNd8{iPQeV)-j}fpB0!#-JlZ<69GDJGaQy#w{Xq_?Id*7mKAKTGy$3gmorw3zXRUA^jyfC+J4v`{38%UP+5n&hUvfju+upkK80tc7CJaly&aJRze|#V`!0_TUWZ? z01&!j_)$?u^1b>Q*GnRSYrJZH51l->X>OCjS~-bfyhn*K&at0{ETatkX6kb~9rhpu zP?|e{TIj9rzumlrGR%8$gZfxaarZpgBBM^L{+)MMlR}R-JIoSI-h%_59OronsiNn) z?CSEkB1gEYcXH8)`aXpP`{J3S%D!~<%hHc$E2Z+fYfuZ|!td4PWWO4YZ8ubERIhRt zund-ldgb_y$q(2CpI~>q(wm6=LvZKzc;6G-n|*U9HjK3zdfAo=vE!e!0>ttL`YgG4 zZ2o4?mMcNl<&BY|)Pit+0E^QGLioVaa;|MV4gns(bC1I_Kgjpjy;fX8T(RG$^5rtl zsC0^WTF#O#*@r79bOY?%Q*nDA!CMay;V9vsLDI(ou$$*Tug-7Iqy9Omo3U`g&&aBK z!++pu>b5V_xscpv&LifBbY_8#1nZTC^oBgKuQE+cf)Ug;W=!7JDt)T*LpPX%+*rwA zXf$RoJW2M8<{PJa6{IfYJcQ`jM4t*34D&;P zc7z(Cw=bA;R>~2Nl83r!t*w_=xp=>#T}vt>iEn4M!Wz& z<8pMsUN>q+G$@aHp!V(Qry#<0y|S<;P#))fz2Ieqcuz0hInR+h_r>A$IrznpWNP-*0%i>?MBx_MJ>N@SJbleU+-x2CY;Ng}{{G-8KcxQ1dMW{j)j-;|<85vo{@^|@Ts7yFd%?zFP( zSjV#egX<%FJki5{8`46eP@zaHb3S*6Jll2DFE`hizjAO7AZcxQG#^4!{`ubAJb5Ld z^u!JxLK%~|Ox^e3E7qr+ASk>`s4j%KJSVTi5ff+@)7g1eG@m`gCCSzwR_r~r>$9(o zG7?onip}=C!mW3yOhU$rht3hJk*^Ta_W(p80Lmi(Ojkz36vYv#-*SA-&tCsr0qw>3 z4EMiowzXWb2umWhnevs~$4)&lvkzv1GNW^3=4uGFG*I-=?}c+^n4=7=9Gp3kt$VcHD^LMFRZ=$&Q) zGCEKHC0IfP5N$Ts53gorinVALmrIL$Qh{>-2ZuuJlL8fqY+)8B?^>)UXtUv2fKXZI z)n1r1CrIh4I$<*?Ywq6AR=g07`#kY0=F6k5&%=xVfMg@SR2f*4(>Xq?AUV~Sn*1xF z)b-{0M`vY7U&+2{z3By$lzM^*1tBUeeXf^ zC)eBzSVcJx#%gjd!Wj3jPeucVVD(J;L5t^>ra8=7ItZJeO93&G@bIUv^3zYR$JJ!F z>Cq0+7ZX)Eo}@71;S-y>eSKc+!yS=W&7iaT8=_iu$~^Z))X$Ij-D?CJEtG&rhf7waH*z$PYo8 z=tH9K=pZ!bxPy5VCNZqd_m|CKsGN>;RjvofrKNl0AL_>3zP!8m|6M_cOL$SzzS~;s z6lhgt!-A+HRwE=sgmn13d#AO1@=^6md4ec_iTpEa0s2A|W{^PdLDwB5@N@<|Iu*k8 zdO99xH~_*_X^Sr!6W^H6iv%L=`CYyWpM9FczM7slr-3a&U^XsGpeiVEkE{2&+)%;ldHM7DHajDy-YSR5u|Ei$zOpUU_#pbc{H3E&UOLyTtG~%7T~ppf@{I zop-99ne6p~#sj-KE2Dq?#J-51YvM~^IOtey&Ra}n8h-&5=ueFx>dl~K)&4tUp%VuE$M4golb5T{ z4DW_fA)ZO9qW^jC%7eg7OX7a*y7jM3!Q{p`tttHZ_*rK?$vG07g~@_bR(~gXr6uda>irpZS!+^V|P>PfjDqY6NY_I&zosdVz3>cQ=yOqnP8$P#I)&mx55iT97` zm-EB?KBdd~!bPh@H(Ae2xJ93q@6WDeaaqPI>?Xk3XMm@+TNLwZiZL3*1 z{?wfV>L;$a((gr(e&IbC49AXYQPRr!KwYjnj z>!?SCKMTixU#C$gzK^vdRj1)H2z-CLHq!0=4GJ(`s@XC6G~ zg~&g>BovYSMOY-b{gF9i`5gOnen3k%3Moc=6;6E^uk&dflP!TNq|s_5$U6pw%Dw3N|1-DWF7kijjAdou` z%3jQ+==u`S;&^0`NXVr{kAxugg?V`XE;DA&8ONm2Wj2PD7>K@|E}k*Zu?QFfF(LU!_9BwrZhBNP|+kD`Xi)iW%) z0*Zc765Fb{@3MT4b<8JQQj(d4;o*xx-Z%Wd4!BiBLdzno;7j#J-&HCp33~ z{mz^{tf-3Ha!jVqUcPQMA8qj+XE3b7p)FT-?pX~b45_vLYuY?O=;MEAX8b?`1D{|p)ua2mDLyf*b+B~8Z=t+uFhAqRM!*5<5-%yv*!?s zsvn>i{)L=8@NHn`E%JEk(KhEcDECqKd*hm%59r)}0lQa5^`>qbvq?PV9ivzUY(k8@ z*BDW{)$i9~FS5Xeb+(V&dhec71V!1G`=aZg<7Y1v+Vb4s8EmJhYcFh2Za?X7)$Lz!t++P zKu$dKczFGZRgV2%WuI(W-q`#qygt0FwW)MD+iCz4L9SOd@()1o% zr})8uaUr7=Vc;xqVNE3my8_c1EIXQkw;p7nA&wyz(?+Aw@zZ(98L7EU-w)Kvp#e?Y&VxldB#}#oQHWsyYkx zI}xGT$-iANSkNy0r4{wbF6{C3sM;P4xL-SS@V@?igGb=*x`2ZIrR9IFq92HTwO=YwJHC6ZFluM|}OU_+Fmp3Th3tJGiI?e5La=l+W3C2atf zX_>V?5uVzZprTk=RQ!c-4ZLtElAj^rslazwI2mcztip~Xn;w~JD5cO>j zB3t}D&O=v5`*q0^EI~r-T+O^v$iy8TGMMs5?|kT3*Xd`a#4&<*s-20@N$o|uI{hEg z%Q`y4`Rgk$c8GjC5Tu9j&Q5TSvsKNR_5EOq7`;&V;6R|qcMV<^WD@1ezaB)kooZ+$#P>VBOS*)G6ImB#C`z+Hb)q$>%>3>ZOG#$*f$|3{I-YbL}&r za)1CfYsU`+j$S#o9RSTOX(ZpkG1o^KNG?hMjXk^ED9Gu|jdxg1T+h!hrq~0k)Ok() zlZ+M!AK_Q1iGGjE0P+z8gjx2*DnKk9sn|6$aT)eKcss$5og%Hr1909{h}!lqXgAQY zH{W?R8V}y~YD36G=_?p>wM~J1ge}I(HmO5R-1K9@CiP`Fj`XL@|7f4bPGL|?xJX#U z)AIZi?^PRDY)f{KrSs`;5cZGY7<^Egzt)uRi!;MU7p9+;nS-1okva>)GyrsIMGAR#;#2|;9i^fi^1 z;SyI^;iA4*^z#$!V94HkBH$MOykj88cnj}nM)F0wsW<)#WvZ8Wa+%%UwR>tT`T{ ze*$~O^GS6gAMLimUkogA0P!yI1kmzJbr1*fA`GyJShDy1M>XdPOLjT%sA_oQXejk0;xcJs%ny5751AjQPxPKht}{U5W4pMNG`QA z-vq%lqF`wZ2c|Y>TD_cDNZg*lNmG9A+N$(I9gjEs-H6A~U8uaY@4==f;M7n+QHzdEd`WB-IRxvB%6yGg+C~ zW6a2dr9(wu!Yxx)yrx-a{FEn-PY3+2FcY8EuL9Oe?)=n2nJ7LwXM`c)3F`e828sP# zo<;lp-lRlvt0yPx?wGFoTaCjF_(0G=FULJ{?Az0P5Vy3xKl)E705f!=D#|EJRSgs{ zDxqztxL+Dwtb9QHt@4gMLyfMg=BJz<^#OSHo;ZzfPOr!u2JLGg+MF5RhY3FRPz@4Z zK*_7+^-C<}wiICW4c)YeQ~9epdpKM9MIAw>zA)jFrO&EaptAD=N^mgAOZrV8$#Fzc zMC^T`Jw&kSdwE50m+gIrz9k{U zx@e3LKe(r3AIPEqzQoRK#Aw;V%WzJBzGHfeG599}lt2t6P5(JdHO_M(A(eDgmoqM4`bvP(0IOLQ`BkAAqFSYx&CQ9em^RL6< zC)l%yvjkZ_(kk;#8&dI4YVy3Cy!`f^SAP!X<91%GY_?E4c~}apfx^;_=>q#7B=?yM zEZ(_2;Jai&)5Rwwb}ys6?@OF=CILLUZ1wBBC3oU&?0L5=e~+tvTE#(t(CUpjnupwb zOGy*0%aB>xoo|qf1fRpz>7o?K>Eu`v)@Wjj!Vx1DtNUx17rgLYH?S8WG$U zpz%f0jU~upArEqV;zN=unnRP9rk8-&I}ci=!$0n%L-+1{DqG|9ho!Q?UpqC!ezk89 zh%aXMi;1I(l0tdL3@K9AxrA$3!h*vv)=7h-%>fGczzS35hWKkQOM!-6wco4AAU9T$ z?@lNe4$6CB8EVcB9@WgXbCC@2h!-nzK6L5A(}<2JJMa`H>l$OmT{u*;(@&} zhDsUVGe8N>UJSp;`{of3NfP>m`XpNgYpbHAm&)OTYZm`>|}LlXI>ys~{4K zAH+$UCK>flj@M>Iht378gMLZ~M)5tY*-MvLH*F;Lp`^-E$Hl=AEa&Q4qWlT^JZdTD zQWa4LYW_I2jmaAItF6!3bx+cZlL3UD7q6mMa8bZ{;bGnb)AHc3+ExC|I>q|c^e`*M zcDhtE!e1}yEO#@gnXf`$AZ*qjRUPq_i(Z?s#mXJTOguvL)(yCUc(|547MeVx`0K)^ zBNP>7Or`l@>9tHnCt8x6uIVZDcWMM9I0Btw7ePIDHw{8Gn;9H6w4{8%g}HNZYTyHKq02bfulJQO8}2NA%@$ZN@l(r@zPn9IUQ$1A}+DN2aaU4 zQ;tE8&QP*3SfWuOd7+z%&M&Z*BoygFP2y(m3wg4p#}k=7Jgv_5j;->PGXC!PKbe20 zV3Y*6!{)-#Js=w3;MreFw~|jX5El{BJe`v`p4qzl5e`UJYHv4GJEH%2Igq+f+N-aZa)vmKUW`^MAakrGO1wxp!V^s zX#aRq!O1(0b^_NJ(pg+GSJWn`IZIOO%L~HGc>jgEEi}}EQGL(K^hD*0$cfgA+$0e@qcYf|po9sEUD-F+LV8kUS3^u!OR2BKc;Ir+T+ZPgFL$_Y+o z0q8q|PalGl-Lb+1G523_D=^)aSFK3{V=3MP>7UYXoxKi2enA*~J^;Mo*Lem}<@|Zk z|Edh`AthlUjPvZ@($BC#;sI&}>H58E_78R>ERJ)94*>DL9To2OX1A1ErTbuYLMfdR zur_X-kGgYsXvXBxe8{NLZ5Ou=vxeU{2Iv?5Shc0sE1ooV*<1_YO|HEU6ng}($hp+Y!-dh~FMk{72Pld($dh=7 zZSKQmh44m(fXmr$o1f^^o-DCC>qG)wCJQ_XzZ=gOl(Fuq-Qg<^mvWnf)4nsb>BCRI z?ZarSLoUnOZI6YMcMt5=nb47YfEZd`K2v!%`k|m`d)d$tA)tc_=)mKK@r2i-m+h5< z@O0Xqjym?Z@fK5eX5~E_x)zYN-7b)U$f;ywV#$K!(UkZk&sNw6sG5ZW(o> z2XJkd&GhhQeHv%lUV%Yb{rcFG`+|F4TJS+O`>Hh|UpA6yQ4BZsu6k-em4Ag>o;f`&L8eJu0$F$D%%U^2)0=9*KVB zvyuMoya8c%v{7KyMOGW@?uXC4<#dOSss6m|Q?OZ8WlyW0)ow(Vrb+6Ct1z#3tw0y^9Y#W8910f&AXGs_RDqXH8CaMw21C0Y? zj!|kW68_7|zT^|f<1~JjrOkwMSjT2^gwCX-iU(%+MwS3bLKpUhoF1TZb;L}1m(-q3krV6J{?uQ(=O_(S# zd=;j_J6}ehfP~na&H`K%f%`Fhrn>LmmftJrkNna{_MfUUP6bi8k0vq$mktGgZA|QU zm*yM40W10T<_MTOdVcuYTZGkyP*t4%3A}t*U=8 zY}SBNs~J#rF8Zde|A(x1M+ zz@wrnQe~L2ofKe_|0H>B39fx)W363{iWX+Wj-%p67^bgpEt02as=@D2vCfY;I6F=| zm?;`?^fO?NGoxWbK&r{LXaWJvV=sv%6l9<0bk9XG1oq*}?~CtHA<9)gkWVQlCedrt zIR(|FISG%cU0(lQNC)(f^c4F&KtteuiSBUmIsGoISU88z!O1M8U=5Cr>6eP~ltN4@ zO?*CQ&bG_MU$aB_Hqy3A#HPJyqJN)p)OG_uc4EiFmH521JxhX)B0k8yvy2ZV#LW>b zu^&~qw3YM`brw1}J(weQV_{zapm_NDEpAKD5m7mzdXHB)Mk=wLc>c{qs&aZau$C&V zF9~4>{k~|KA~V;q+gSfwO~~64lJP zF$v{%fQEg0A^?haAb0){zNmNxYtwl$@y*?>Q4$o)g2R5(o zyKRc7rTz&+lT7`5&d3hYWFH z#Oyhlu5JP}ar^kNe8KAC!EW4MZmk4q1?Fvhga@Q(AY$xr5sY8$hj0mlkF`*_t!(kC zApzs=#riZsi)!e>oNHjoqyY*;lI$%KeB*-gDh%1+hx1%Y+W67eq84YbGEUoH+q#T_Z7}wu{I6;&?ubvs7fDR%4@LEb~PB)W1+^4k) z_I*y}?^WxmQtf_~awFaL&UDuRrUcGK6J*JM7;<9l(sq2BEEL{AJD1TB^8}sRMvdwZ zvs%y#Y2E>BhVeAck@^R)8@#e`Q||sTyZitQp?;T#d^|3pHb-4F8cHH2j<`}AkN)xIh* z*wXuY!3d}OyS&%I{;4w%A*ML5YhJ12BSq2VdCk7tbZ)7LY2{TrCVDGFnM8#4&oGIp z-i|$O)dx2?nJ`SM?v<-^HX}rx3s+?~APsXhC5#LGWsS)^YgM?dWKQ ze`71g{!Cr5A-s?R(}_i*{lYRK>^RX4n`^vD*Cb|&yWE%^qlqJKzA|J_7bHYN7HC9g z>)|V~<0e6DvUw&wC2dRRAMQ}Ar=ZD6c^vy`@g^M*yiGdIqAa{#zx$hbw=8tAo7t`R zP%IIr8Xlon=Pp*Ewnof>@nHT1{NRNtDIo)59|y_%$iM9Y2btZC0H&;STGtOzC)x9L z5RpXTDHM_CtJiRrd!=aI_`KOibWe)gt_-KJbldOPGvzIko_#R|@sCg9N^*Kp+YtD& zp~oj#{pfW4$YqjJ{y^#Eb~v6-`sJ$lw_PV~pOh`=;?Y7|ho-vU!`VGdeB_>9WT6LL zA3CBYyo|5GiR2{TdN9BC5B=fEk7^pv`ht{al1|0}8|WRy7RAfJ(A%SfKw<2QB?^n( zUsxZ)h4>p9DmQM-b?HJp5gqND+H18-ST9rOu4$p?Ka=$zD@FGi#LxmI25TWGu@@R6JH)+M_ zvvy#PFfO7~>%9H^ZJUCYB}@RT$rN68^V2(+PQW1-#6TN;icq$Q9;~z6Kjc5TsI+y} z?E07y{DdYKn~1nR%Ew`R(3@{5iDSdk42orTwTWY~>deV%d*BoAHDw(In_J+3YE73q z&^WiCX-I%eDPM;zhJv6b_^D$bXwaBeJgw^#t$>3!`t>aMVT zny{WUcxS;w4kE~9r<+56cP6#+#G1HI+;G3^ul&)Rps5kXu8yrW;ycc$Tt3erxc&){ zzWiio|5A?O!};lW3fGUZ-Xzky5d!p|l3ry`P+r1p2F__AAcOPnTI1li>(B7a*nmS( zzX!-4lw(1E7K^HPLI82;B=(=HVqw=*tbO7ASqX%kE4`R!$)1l_p_$opq24tXrVdcS zbH;=X%bsEh{d~xw%|Df;e$DkC1+onCTff*ClTn@=+Gg zF9?4mGjy;lW(JwWeLy-6e#7;-hXH8w-7jI`k>?6JAQl84j?wR`E-xhowAZ#d4hmAn z9<&?FSD=DN$5}H`{9@mt;j3xv6Z1Ml6V5o8(DmWc;8aEdb%#O$j!Oab^!^Pw$>P3m z#nXMZ$M}tVkn-F`*nhGtyrBe&14 zgA4NTH9-dbdd@it1l;-At;pKE9ed_~5O*WJCUh zO;GAEufz(VylMFQ%v@cc$UJ=8_ruwGuTN#5m-DMTg1}z>WR6vTewKuu?y4^7)1eC< zKZT+J31EE;<o+onExx+rZaS9DTx7+_*D5 zbf0>H3#D|Dwxy3x`D#HlN;u}6{1ydSmGJX$zBgIykD>i~VKCqnPPD(Ln;V1>&Lf9y za;AkExcjN?`;`J%kxY@>xn8q>dON5lNGa9D$P}gbGNzNyzCRL_CcA;Y(e|VOnXT!d$N^y5xQDu5 z#L?dRUyiX3s{yxVUy4X+&|$b_A}D_Gt$MY_{F0mmFJ0p~S8_ZOcvVLo)qHrQu}>E4 z{QjP-GYBHcd4NEcA*VF5gr&KPI=}&l=K$}4m!u0uHKKCa&HgnQc&yv?(Pr5Mmj2-f$ds)**YOjQdw_XMWRA}T6S z)FB5|O~rx%CAZuK;(aO)iH6Rh%wD9jkSd2` z&%bvJ-?|0 zpP|DU4%s82ddoa9;+PlNMNaF3a4LSz2RW0Oz5%MS>f@6g6DkxO_^EtoPVcD$4l9zX z4p{d*g7`TTmY#n=!MMQO#5Q?vQll#t59P~3C;IXmR_6H#@~X6k6(fBHkK=)|H9j-% z(m%_E#7CK)y%aQ)WIQWI8)NGeQV;zwWnSOlo4qOR5JHwglC>8kt37jHU!LT)Lv_G{ zBTG9G*A%GD7g@SalM7-y+AyEY~cZ`+@hR{5qZS19*c)e zRBX%2mIJ#^z`=#X>BipE_fgm2CH19K5R^WA7&?TlIqgEv-FrRJvJ}$MYYSb?y_Iy+fAcuH z4lb+{TM%MH^^VG55&aLZ@e(!dG==>o>r&aJM1=n-rMUeWKLSKv6)9Jl~`IIyG;yEF7q zzK;t^uE9ceVZf(QxE8RBn57%mwRCnBHz8;Ds%S|0kggn)sP5@MCrOD6xg&hI>uJjs z4fe|nWN?LBKcQj=M5~BmWHe2f=@WAjsy~geq$T6;CuEFi*1T_7r z2>a@yEalnu{iRrmWN?V->3x7ucf_wlDSjw%-pz!uj*rC?3Ilf8AJ~2Alt@VF!w<#3 zZ?N{5Uzgz~e)56oYDcMQl}SC^rF-4l$3;HQa1Uzsl1b=!h~812mOjyD+x2Uh@2v5G ziI8!Ivt4_<9Gl9=#Cq{9|I2P3&#_iop5Uu^V-!oqKyKb0*44R zuFWMUx;F~5a0cl6u2@`ULJB0LConFn0xDknEPX&fSWqC_EEsS=#gG+{DcwL1Gy%us zlJod!^Fya9(9$abVKimZzofhi$Cr_&|R*nizMt5_Uow{v1N%k~9GW@C0uM|O$pL?IYmd|GNQqd2?=%C%^L;D1Q>-Z4N zF|EFZnd?7BJAxCt+H*=DTWUBREY|hDx%q_$PXbg|KiFS|dot4=C$uIli@62W$L)Mj zv0uR>$z0Y(v^8D=-3N$jm)#h+e$OCE?>kpbo;dPL#SH~#m2y44Z+!cHLJR8=!$vC& zdteu8T6nmJeRCEY|Iufw8+hk@xR)07{wxu8dy5us3K1_X;^bF83Who3X25eiTh(&U zLKP^ugnrp&mrB+*vE4uORcJ2Mk8#>*_Z&HANVHZux^7RmzxV2RHXd>9W3*{53 z&A!m@{RW6P;!&vUXjg}0%M-V%>trO3en#D%EBij0L`xLyk7CjCWc_piHEniIGgh1w_NmR?tJI3s<5 zkGguUw`dt^Ycc<1%8&2$u8CrEG;qkF@=UD!0(2G__4Y1*r(2R-WK`elb?|RDXctYn z2MwcZ3YP!VCtvSfr$UL$qI(;6**O|GjPQ0{4Z1^q_@c8%NP<36dnjI$)5|cK^KVP-udBsRvpJ>%tV#$ zwm|Cq*!sl5&E~9;Xrv57d-m;XHn_79FtH%koy)e+`)wue+0WIade7FrgrVu(Avm_L4xAD523OE3 zADqzqO)~9fCSQstj-i@oOsO0!y7X@2dw1a${0DY`8-x?W5OPBhQ3>5m1d8yAMUpk~ z)uX;R56nK{6kBlj&meOrgJ%7$yd6@_?C_V50jjgcV5Lx6&)!FN5A*G?XKr5aZ`yJ! z4Cz+MAAupq^gNBI5J%mQ)6locV?IYHsi$+;hrwW}&Gfj=hwO(&g11^pLEhl_j{W9v z`R>_oWaEc$=ecvk;t@qsA1m#v@;PWI&gp5sJ$(32>fvG+(ks)?KRuy_RBFJVFPBMG09=i=ZnV=phpp?U5%r-%6Ufr3le&p$2Gr#8m-r_tX7v#+%35`!i^ z<1O&UQlX;c1XeEn#`X9oUknI0SH7Uu#nEZb?<7Cv<-EGf3@Pn6PF&vTe*;Cwe(zy0 zSNj;P&yfD!9&rpIJlJEL&VH;>=}?b%oo=X?S-tkJE!Egqgfm=zOk}jmOC=$SKdVwS zkCHZ{@<2gz*uE{-X@P2u_!8LToxhy!G^)9ZGXO@8w?n+irr(fE7Rr9#2PwCW{m~8x znu6Z7EY2}6ZuFG0Pznh+wvVYRH2S~;5r|WV=unf71-o3n6>+19eej4OQ}dO3xLpEk z5&O7SWHe0K5yy7>&%Dlhb|60~MK9yH$P~@zQ2V@gu&RFFf!#j=acACht6+Ut|1FQ) ztntO@HGlsV!@2UF><#J`w_Nx=_@<}tmoLG+Ph;VH7ZA=-;r;a8*Ez-E{XGVvvl<`e z{2noBm5A{&=PTIztX=6M3a($6#QO*-ZtsY-rx6JR0Fe2#iU{UB1bZ z+ZLb-@nL!9OapNEiWS$fN2_fr@ zAiC|cJO9ZtZ}=7uueYwe6D_RyRCzUr5iqn*uFHaWn~c~S7dxdF9A_*N3R_0tRbCBK zRd416p2X)Xfc0}j8cztFJ|B;L`nrdtTgvw zr-s(@KG1B-TzEzrTN3?OV4p;-e)RWMZO;R|G{m5ygQZ~iZpRAlcH>M5T2z?~Nmd{4 zdO+I}S9+Hn5@H^Yh&|95ylTWv65gisr+mBz1_s*Uj@#Ip{LxfHHbkd^CVTru_$1U8 z52dizJX^$vaua}g@1f8_Wzor2qr@Ffwl?2aW#p~8-bpojy1IogfnXFaag2du9F*V3 z`z{k0muGBqrt;z|zwF~Kx<$#%b^TF)nVWWw2Cp@()^h|T2jfq7iF`u% z|MA&cLxjjTf5m+29C||d!=99CK|v7+7O=yB6ekua>(x6P?WNm z|H^cAB0f2xcORYE*PrnQT)DTsK6JkAi!|{rMCw{%eVh*kq38Ts97SCfSnqV8r~V*% zkAGV}3UA^Ye8)K!PvmnoiVn~4{Pf#CfvO038kOqn^6h2sdIz8aY`**CtUmOoNwhr4 z$F7YeJPsWYOS@~LVkFz8K1$X1)853%2ZXY!8mOP&?AQEq7UGlw5q|l)pOMgXBFW9G zx!o;ID`g06d$g>~O!W6fKP0=adgAj3w~hBX(t5Dy*3>5;p9pL6`x}~+ICUBHEO$s| zyjBQpw!8unsJ>BbrrhtzhmYOMtq5DevmWyGB&MJIVg}bi-HSR#AMrm;!0xwC3li8= zvI%$@LS7P~9I`{H!SfG;U3iD6xeBL~Dbf3)2JeBo=IFogZo!)D!#YD2P741gO%bj_ zM2)GoN1;HU0r1n?uKI$@Z;#JK!n7u!%`l5b$Li&mI6SQ*);g-p-qTMaCW~(B{>e$* zBU;*nD6YyCuVe)%qmLihqv7L74GY!6xC40ZmE>7uRtO%Ijo>+DwM6qLzqq5secyMO ze@eQw4>j1;-i){6 z(5Z$7C;;=Q#!ti3gbk6uiR(}ak=NXvbSaK6;J9aTU(epw zFR((z=w$|ls>(ab5S2S0?V9MWROyYjEm>OHGRYf#0~`*!7jiSaahNngoo~*M--Cvy zG+LcsLYUETHP63y%kBK~BHp7cUyY@}I&RMCrzkp1*&l~ToWCng(*}U>i9u_STT@+mJ6(bsw7a4|og z-3{{BC9jRYM}@a^JfHP*Uv|%&(YVK(*@Gc?;W>(u=$L^-@mxgrw?{YLp!wiF9)$xPe7tuVMfbDu*EkufO>Ws^C6|?`4`RUl!DVm84A~@@ zG4+D;fUHX{(jt(s*z;8B$gtCw`APUE5^oSkdW9_8=Vf0YOIW`0FM0Q=lX>wCPe^~q zI|03`>+vSl94>1#w*kWoN=-r=3=|GWj#T7L;l{a-0rq4)en6c4w1gKsTm3V6(SCaY zKx)|QDjpx4htA~!N_DWvrA3gG+q3csjZ}E5B$vg`Dn52o_k7#qRO_p7-Rcwwx6FViZpPt1CQl4HeWvRU}@ET|3R#G-;aa8>o-Y3}~hCa!z zCVn5MUlgpafpeMtjr?%Z`&<69_lYMxq+!lF6}8*Hg~-JB7M+)`wI;>{bV4{Z4Dv!}GWLCOBbhw<6Xu0h+x5sq=U^)cI_)pbU3(O5 z2Aj@!YW*bchd;wWs8jtlnyXJY(r0AaV^%38Y{RylvYLpT>$5-g)kP9E3nX}x$$S_OC8~N(@cuRpRl5T}ocG7C0;K!Ge z@mFLK&RF=+V;QmZl!4Mgc=fgb0sBXHri+)?{Dt5T51j=^`EI}Y4!v^t32A1i7yKZg z?At!=ws%3NppjZ__KC|B=-ZZm0I+4Ob(1byZOY|4Exr)s;F8C8MFpyF8c5ok%<;MD zrxCYTs)Om4J`G&6usXu}Iv+K@z8>X$5Dpo2#s!Yd@u?^`S}0o+eV$2-N{?R>D2puY6Ct}I>=+uyw=SZ@evI;{et zjT3H!72)f`wpBXQIbb@1LLR_{_C6x*_`ELJy# zL3cE_^vAevMKhBJCtP4$f#JBRr?{Vl;X#`oeX_TvzdtFZcg0{S zLFD56nVi4sQGo$!vocghWDgk~M(fAZ`gOgaI;Rn*gUo2Z$?^;!? zFf(4XZ9V!neYsF)yj>+;?pES+f1`9Jd|-D)Kw@PBT%&YjU)x7`4Oz)eWpNJn-9gHW z3gx88e)r^aP`K~OTxEx(st?-yKFeVT`we9`ngBDJV`P9bZkdufYYZwZVejZ9L0UhO=Qq8--1aS{lvlRr z{i>L!Cw<(nl+K2ctZ<+4)Ix2os7wY1PjS(tIQAQ=Do(229(4Qhk30+DG|@6b1Jjkl zldLx*63cYYy<7f$rS@xlAf&}4FFl_fQUjXvxx-sHh%Fp`$l&4w zoX$#gaQ7OXFLwHqOks@IgOsNL1FqDcPvha)Sce5FxWbuc;IR&HCIqITIE%7QdM4y% zsTWs+MvDgcL;g6YcL=A}w#*=nyL1warcv{G^dql`Nah+v<-0t9zWDO?IsmRum4?;s z{g|e`H{O0K?y;6H;Idn=!FXb2HS2`d@f`6K9Yu!URvV_;%isxy~qE5fg?1d!;$r__JJ+{sF zpbX_utVG}t$!)4A*DRIfnev$cSVKDEaFxIeyP%aX2|JX8sSa*@azi; zSO{;+u{=HjW6IQTaT74?s&`_}!y~M#9=oE5_PuP$rp)`!cy+c?2PFQSnqE*Fv%qWH z=HJPByL7y-rnta{+`0&ceJqwzvb(Msmt?&?huugA>66Dr%J+=^BlBm4AIF~w!V$Dn z`0q_?iyo6_;_>)=UG!>f!J=erv7){M>6kv{QsH55&BK{ayUYQQe75vymT$2HIr2hSVAT>PL#&7haJUETf41zRRna4p#^*{`w3rNepAsK9rqe1C}2vU-=o@(9zT4 z_eR~5^E9JTXy8KN|CHvC!bA3HQ&r9hxo*dbEFqQLzGmkT(WP<`>9cdBFn}r~&>O%I7MAZ@{2ZQTKBwSQb4v!pLPmQ)lj=ZN zdyKQ;`ycV4?DiRy6T2EYvj8EVAA|8c=HVyi&snE) z1u8sG3zN@&PvB5w=*;Cl_>W=_1+2KVfF*X*Ci*FRr}z95Y%Nb0|0K1?nmb9%DJHpd z;)Ac{fN8pNI+r}d2|HN8Yq$maC1z~lR`StJ zN$!iW6&SkK=+gccvGKDFon1>sc?j>w2l)O(GzuvD=p*)cS4`QzoN#iM<;c@;zqY#m+r> z43e!sV)$5Jyf36nsB)pN)-EFry<2dn^wUvye*E^1XD_~g5+0Z?^(`5c^XbR)JAo{o zd4(>XK`uh3ji0$erTB>oo14rtgGB<{WiLUI8|A@}di~U5<#eDU1D^FF0I#nxCI`_2@tY(7JSI0;U|`OZO@laFR~eb{ z;CQRZ>jy{E07K}mz!XEZ3WA>q%Zndel@EG@+W806>P(+0>UeJp9pi+A+rnv(WlXn7 z;83YaTFmd-LV6$Cm7zrQOWl2phKNEOBg*J33+az%xN7P?h#DLeOe}V9$Tu;&o2TvF zQ3dpgf@mr;G&RRLTc_@g&-XcpFY%=RLJF(x?pp4h&&c6W>Kvtq#J^FN2Ju5|;l+pX zJcG|1$$54=!1*vbVDH1JDUFYK^F}kP%5MM&6yAjqF`ZW^?ZdaI*51!)83loKLVr7L zdoVy3;~PV|W`*TuzCcD^;<3S@_tVGjy|O-&eQX-P%;ja%8<4Td_c9MO=(Asp$&xC4 zo`+bdb(4c9A`QRmd*&x%z4!a;$8o<)4{i& zJ?0~+x8?50z3Sdk011KNYV`FC_jhE%$E#b5hs7~9Q_qeA-Ul{sK|m`C&>RD`;Ke@+ zM*iiK>v7&>z_FPH=Eo-t=^k^dj&t5`-l|5~(gv!!0{b>39bk-`s?*`=}y-)TBj-L4={4h3kF&;`h zWt4bZsxMi%0Fq65ZhpV*UobJ9o&#na{yaGyxwuC0jw9tn@X}uy?V#3<`F@E8!O#0I zWIw~H7RiWUg8jx?W6UmZjQ~0H>vP^6rnHG!p3w}o48mT<5|m2ecU@;%yLFs&uUG&0$ZyyuVoHb}aKCZN0>u0G0!66hn(9?ovI{8WwkNVnns#0V(b2hTB+t=vn(< z_QHg#(W>YeoD2QE9x5VBe4Kl5lJ1J0Ulj~g%={Lt#$7*o)_gQmEj2wg zdr-ghar{&!lvyB2aJ~^Ir#jr9V|CXyWq9e|6+!Uo-uN&(sl~nw!fE++K&nGT7cj7b zZpZ#sBWL%tdkP*^$ueKLZ_*VF=^Gs&_&}?b9ECjJzYoko6G%I|&=j@Du1JE1eRPNJ z7Ks(HMmrJyds~0GPj3|w4sib%3gaCPBjy%+l zEY+K1ceF!uq`kMWy6; z-|YQ*`==^!N9aO1VyL5PO>u-_YtC$Vqe73 z;mgXf45J9-)$gK5`EdVH1C@ImXJZSQ?k|R75A}7A$y(r5e}MMxA-cByPTDSzuK8cc z->)cnJ9Q5#zGP2xc~Vy{1Yw9S)sREhKZjAq;@l zA(S(j`}XqH11T(`0D`jh%V9V7FhL)_TwY{7E`5=E>r`~e*3+gB%`-pB;Du}6zxN?m znChe&2k!vu;3AUt$Li%TcO2=m04xWorc&o4n^AFRzK9QCdRDjYO4Y?MLeds?wP$I&~x`QcPi zhx|vM_ZS5m2xs%MLLB&W#tYZYMPnWt;(EJ)xwHxCg@%vnpJTvqkFdn?*J&wvn=?5Z zHO0R}NXskNPo&T9i;Pd(hPRj0s-9`k4VFWi3FjDO5E>(ehJ43-!2U4y=CV2WjHrY7 z8f3iGM?jAvNRY15>#`i51|g=*dTgGCcWm77c8W9pd(OSbLGWiP$C&)NK?yXv0hK$@ z(@)-1$OU5mXXV`mzliMWTg_g%cQY3(6SQxMfY^`qq1fmsi)0!qC8H6td2Lau{o-P1 z_HFM44*5B3Z~r~8qztB#AOrfoALLO;M-;f##;Zu+Cirwh6@|)21ulTBesD83N_hf9 znBRZfC(uX?#Xpf#)!VMM4+|leXINjD1QjuIznSNI*ENrD!K69GQ&Kti5YXiwG%xA) zE}R2U+xMwVV~M*G7zQ}4NdzOP<8ienEY{#3B zZli|7lM)lk<6K1Xd+&s(dc}VIy`#NJ;cp;*oI;Bf ztj}bc_$Wm}9^e@o5+f?f*sW{3lfyf^Z?=YV$-Yid`V#+PhVnb-rd<#6Y6O+xq%XsuLwm>!)2km0>^CgA(#6nb_Sy`7o z*-)3>q1SPf0v>|@tz!anvpA4wAQAO3l?a%iynIS^4^xXV1rMq zt#SDYfdtQt#8+OR6qeWhyg)SMFArQEttcMBaCw9?^($cn_=y|W_j!@eH@|E96W4G? z#Jes(*AWtJ3|fME0$~jYxjvsp>=su|=fH=3Jl)Y|KCYMi8S*OLzO1cR=>U%3DY@%* zvH_kloC0+f{9nxf-gZhcQJn6p9W8u9UvIqK^vk9{NL#xY>-Z=~%W!Rg)3C+Q5Oz6z zASqI_=e;v+j7i|D#(r1z(M+bd7o0A0m>40SBP*E!POO~Ss%-uhevHg%X>AZ6}U92WEVk|s;zjJJhlXzG!d zWZv`A3MO!kzKs{*?GZ4^qXsBGK%apy-)yvmheHN5q$SxVn0e1TY}V!@e~S4v=2@d) zznu5xIiijt2^?x1P7>%+w&wk=jPFl48P?W?&o|Q~ycXXQ07bgm`|y$SI3i(vNTMGE z9tVcJ0G8-z0dtO`iiRTYFjgemoWmB&SNb}tS6}1Mc%N5&kMN$Ty{>HQzMBQFh}AL9 zchs%f=@hXZZFs?OCsennEv>p$k1n*!XXK%tXs-uk||8f5OIOv(^Jqr*=ut^CHM#KoXsNwxR-^~|St9^<|Az!Gks1S(k9m&gNXB&L6Oa)Uan1TUUq7jhN=0zHP`X&{2fkvM<$JKXd7-$)t^d$K~cIvWm5G3h84>T`nF*s^CLw?JG zTjvP4wqt$|vHfS1cg)e-CI8W0g88ieNu6$Q^?pop!6lFBYk2qsf0M^=OIHqD9m%Eg`JI_h~5G4S##%>^)o4Y<}Rekqs4`VClkH$sGm}Li=ozG6dzs_tD#qT{;!*-_B&(x=+b>=@B8`!>yhK$t>?RZx|pg2DFG;j(L_-e zAm}V?Qwul90>CZ?8{zk0Tfh{led^o#j+SbZFfh6U;%@OgmZ~Ah`&W))(e3_*9>-gi{*L@&xO%YK*UkVyMIXlHaf}_6Ak49aMqdy%mWqrwAS4e{K zu(P6I?9e{J(y5u>#|R=Yse6*NMdHNYXF__S7>iGP(zHjrSe8h0mB1L=#CXsm1Pltl z{Mk5hNiYz1-FJQ?3+S;p}tycz+xyd2aTV-`k`X z{Ln(}-)Zk7u6&>MygId}MFC)bc+pOse@0^yuTs@ zZ3aNlJwe#-L-TPzWCYXMOPPp)i@8ETgd**CIG*8Qu&+(<&HbxN6!@ zhwx7i7ayvOF=r9|TwM3KpPI1h)A#ay9;>eakJX;bSSx*xd+=9S=D0rlY=zoeJ_)ah z4lJoiAyRz_-wsSWN_k((6hjrwAHt>zK!g@)<6vO>??hfS4`5^iJ5gS^(}H7URXSSN zYf=T%Is3B}2VUcIQQjK^&nkPqeA9NDX>E@#Gfl)CEmr~d@&F#g<( zuf}m-WRMXgYw(EjrnyIni!@{JGr2LS~zllP9Id=ABdRakyBOG2K z3+-Nl$2Y)ZyF0DR$Dd=%jky3YXtvx|tP|{)U)g*+QZSsX>f6X3+Ymagr0uy3>3qp1 z_AfBjsSeDob72Ut{ldOBr?&?PSfDO=Ur~66*3~_9@t;~g12Tra572X*OK(bcL+Sz=BxEci+Q7H zpOCh#NEpwX9d4=WZWucG_s*@X_KqZ>PwuZ z(@Vn5h2h<~RQ>t2G%Z(`K18_w^cmW0F?52BJ#2E@1-vx<<+!!<+YaBHoZhq7U;G0~ zoj0a?JfBnZ7hjZz809>exiEw6+d)cyfn6(^M^p)OzMl7U zN>kB?jVYrI%kAzid!zH7g1@s~EctkS3xciG<_TGaVbtBdW78zWJ4?!rCzo-&u-V7B z5(`FQb~9wtk>ZY?cZyjVa!=8&?_wWUe5UVC(xaqdu$_pe`3Oo;2PN;9_inHBE;pT8 z>(B-lTL-vo0LM7l^D#4gX7;>Q=1+2z?BO_hbDCD3J`mEm=H+~-tX{p*w<@Mx^BuEq z^Lm@GBQvBUEawRf|*av z<|{D?$Ke>hP}o@aLF||$6z6iEYxs6G4^C_Nj_=VpbWo9Sw*qvfRN!lQw9kH3NM~kr zl;9Y4M@UO;hKvkP&3H{yysHbLrqYMXu_l6Xt=>fLo#B{szBe>hGz3eXMHWgws@Jbu zsB-*;zH+U1tS_ewKyEOV_iV$357=c>$vyFFndo2gA7@WuH(76k1OzIpI`tm|ALH*^ z7B}kJt#B*Bd{uMOIm4v>dlzrWEJ~+3gzZ%uT{BJFR~fnsv2Z9;zQ_2Zi*RWsrpN|B z72u4YuZ&IXUejjU&-df$BpzteRj%J(PYh6XA(*+meRK}q@!hee2nOVK0+ujz!5#E4 zjXxmRq5BVa&1#$u_9xYK{lX3N5$)q%@kIlaZdSVALzZHp*;(;-6&izkXjE3-)p-_I z-KEeiB(Rsy(jb#tX>Voo3e$rt;%ENu0&14`qTlLSPpP)a9Sjj#cfCKDbs1*4wU2y8 zFBma_o>0MA!xN<_(hH=W6jpl=booR0FZ{0i+yy7-Z~956=8$~n95!Cqnv^slg0{6d zC)+1PtXO8AHAUMozRMaqA}j{Ky+XV+i0s9>P>m`xUm+^_kI=o2yHwtKc5j*Fe$L>%xdM*`)XI z~j!;(^PaJ)OU2JR|GXy^At=Sg@7O?AY2aKOV z^=~>k`0Q(d{#I0nYanEs;c!LL-<14Jx_YeFeRGnk7JaP+&+Si#_8Maj7+HE=rNH8cC$#Ix@VLVONChhO+t7X`OE5EMP_ zx8wQCgP$`IVF9Tu??ydDi+lRB_jR1{)y1Pu*6J`S=^iiP5)Q?2^n7zj5(AoLukJ2| z!E8tUknr$Tp18(rRPxXD=vaK44~xkC;q%JlOK|uyly}|a9>~w5D`N_)bwlGQ)5ls{~6`>5C%G&yh#jch2S~6`>{% z=iBo_`(b8P>yrcjw!JeWgp~cgdDW_5y2bW1D~RY3PZc*kjRClh9S$VQi*;Yua!p{X zBuObjrjlJgZwE*v=NBZzegHP@9Z6s6vE3KV8pNG9&8UEmvAVW6C9?#`?2%LpChUP{ zIiar^sO#9UQQ7GLdi_vr7S)e*5wKLTHS%!DTQ*;R0=Ik~UY%6)MT1|9MnWh2a-PoK+K%BOvJeHA9q%;gg)bbESQ`3ReB01pHvg`_g~{5Zv+*;YhtQnE}Y?{a@{tk^P zNL;zZDLWE-CEEA=3ASC3=1un4zk4_UW zvB4RO-U{^LM!n_8V5`sHY~j}1C)-03@A>3U70IoKPICJRbpw1;pS?}@M=@2UuMpfc z9-dV>v{4|QmcESvxv6+%C2nolaK5N_EN&1Q?cH0K^x=Sd)6q;8Q6%(h{=m%m`+SYy z%9|`&I1*1;-hZU)$MTRrtw~bEe*TUchaeOP{nR>0PR`ERrv0ETF9q^SMjIf`*z8V1 z6vb!$q9W_`&K)PYsEj@&agZzWNh^<&SSRPUXsD+>-j+Vyz6btUBHIYCwtiM%ju)Hx*g_F(O`chU$<-Wg=w1od&^9e zVOr9BS->=;0qc{(27rRLf_(;^osIUyxX)Sh)&^gFTOGW#xqXlFLSdTI%*(?p&E{_z zKTm=}*-LW$L0b35ZNkj*qea}TN3h*j*Cd7Tv>%{xHB7 zx@VUhzS*7jUQVRw@hK0H_cGAZl6?kreKTq%x%0o_acF!TGo4TqrIF@-)yqSz1GC{c z=qmw~Ywj}*G^22m&iCTev@#{L(?<-3WiDoq&*OcDIcXTcdL1OK)JZO0{?G7S} ztKc4DT>yiIZtKf&zL{_F<}b`=^1}xz_TZ}hP+NC>I3y<)h_?0eN&c$ajgjl-+8f5L zjr&_N=?++Ivv2&)A^FI2gHW#}yguIdSuMWlGFVN^I%L{^%+Xr+j zIZA0zCY|z?;+sO(6X$*dIOZ`2n~t^OWI)Ua+odewA`Zmw`~%63uj}zzV-3{Y)^j9e z_6-Xg?g?Q|Y@tGn1FFc_%RPcuS?ztppdMc}W9P&qz8dP8q+RBFQ*uaYN97^Bx<%i6 zHS(|Ie*5AL8`hAS9}7297NGqk@y+-y>=)PHIE#|srO4?w@fJ=tKTCG~-Onr%h3Dr< z%CC_;rA%xOw(=%ELbH#Q$E(Z#r7kW1GN~rH{LTqo)k9{4hf>kZ7z0pz{EY9f_f$Ig zUU1PXJ(Azr*HonNJ`v0fw^O(T5NdxiABatk$d9Q|=+X5zTZ0lIbAmmgm@_la9ZDm4 zz^hN$`<}&+AusJF(%}O9p43(}ca-#bI{QC{T)T%QkFSoQ$Kd%`f1ef%7aBCBJS?`)=V3{rI7SV6ByWhLMd ztx+HQKgIczb`a_q(}box1ycf}5nnmLAr@NVQTt;V(9@j190N=b)LuEjF$EPv?Fo(O zc{?e)s<8ykcU~{SWhlM=6XqJ(j!-7;(5bY;-J{uA9*gvF+WZSXN+UmE)&J^JIx8jz6F2m6DrbLLrdN6a9II zcR2GXmEgjTbBS`6`xmb7E#@J1R9->XuoIH|_*;{7%BI(BF+-_8VSZBZmzaejhMA9N z9Pwxf+M-O(>!ai9JYbV{)ff50&QCWq#m#{Us-@I-+jcpiENmI-FI9ji*_kBLqef?1%F6_*OPcFq=OA<(M?SU#j z@QY(|Bu2G+K&EViIxt;5r|TFgCRfYaMjWi{n`rlkGc@lH40GU>{Q@K)rtK_(1X6Z9 zc-LU`jv@3z`@*h*%TrI5*>IhdJbo#XI>6%hG*<@`ZdmP}wE8T|8mn5*Sb$It=bz<%_DFPU&62Y!#HpLq-^!4|HPAb0rPEJna| z>^bqu6m|7b5!Rf=dvtI-jgUCQ2SJ8->FiOvdJ%XMgoPSKAO17eevESZZ@(*g@_KDn&)QZQw zr?AtxJlt+ixcrSv_)zzCv)Y&wbFOTnkoGyZ_PP3&41x-{;L}M_(8HUYkU2#S6P7I5 zBaLxBH~sjj)PCB>yI-yX(UNfj;Do)k{wbQ|&kUw8sASy*nRRdb9OEdvz?=4H%D2U9 zOpfQ3AP6*bf7zyelchhgKlwzIFw{Ie!>>j9EWyB83nfJV4PWf{;Ppg(aTGc_O1x`y zqkK4W)~5R8DKIVwE>7&EOP<#0@m~&g^Gwm#C#2-7jC$#*%{w>6xd6sw1=1|R%QNnw zj_O^H55OTv=5l)>4;3mOdGYRUDPk_vd|=;?xT46>j`*)pO5u13)F1Jp(C!}^xQqSQ zvG;HFx~uI)+b83|r5Qg-#6%Ws?Hk(6o3n~mZrt}t0vmaO`^6Rdi+5Y-U+>aKB(w`w z1;;b`R(^RuEB1Vxv-8g>0@>LE!(00YYJ82)+O5xrg&W$2CzylyhF5%k$^A80Ewv@0 zCsYCXxV?>8!_n%5i${VlwYWz%dXK{q`U+m;tLo5dn zguQ)NLVb!>Ch7WCxLU9KZg1bhI_e#z?>VN%2QOUqUmAVpaBw1MBoI7!58qC^!D%!3 z?9tc}NGmcn%!jESiPh4S7Em(AP%4_TskZ=KV9VJ(JaPlw%?}*m?DEn8p^KPR#ekhhvgAZO7`!v z#}LrYyyD=c&#dncrAU_G`C9{>^5rYS2|oCJ8tq^u0~MNki7tCTBmA;n;kArq-;8oY z;_B!9{o)EgTM|kTm?8HWw#o_wz!8=lKk|8>B`dumNYIAvjI9uPPTypb#GlR0iP zli-t+(E+2nN4rs$pF)ZQ70kyg?vea{fs@+uH`rg#A32v#O9d?8gCpT|_cNWXL=}Kr zis;>(7ZC1Ar?Uiq^f7=+Pj){h{@~)PZ#Z|2iejOFF*^rO!G3u?>29d1>mXkJ$nxIT z{9dZ)k{faCzRy2%@jRV3PrI;J8%?;occG{HDcv2ZlywVJIfPxZB$ghGV%Q>w#N5`z zIV9IAdIJa}_{6%Hcd>%lv-;>K)aIh)7BSUw^F}_SyPgkA;0S>AWJ>0+Cd1aq!)-btPuG$5%x;?^?d6hl7c0czNP~+4kR-KmS!1mmO_1JfALwuq3Fx9%vY-TC z@_e`fzBQTX0KE4(EGxdwSd7cIqHtI6$tVntwerw#L%n4>3_r1mc9IQ5Fvw2ejmw$c zC;D?4G$dE#pJ+&$pRf+o@pTDbsq0%GWrbt!2L!p_Zv^Gt28Aggu#cQqunt`J!7sdr zw`mWM;0xziPiP;T+e_%tYPImFs@ZOGLx@OG-gK6jVvr@i%yKwNn}JV~s3 z=CLx-_|$hB$y*<_pygYNQs2amN0KVIIlFU*F9e?4-anZfC?O3JqvH2GFbuJX&LyhE zP(GZj`3j~o4rQU@fMsWP*{@bE(~pxlMpCuM-zFu7$NVAf4NYZR1!6pS_wP?*h>ls? z=?cyVl^xjoySZ(l#TNS^ulOAR;ge^^19mg;8q-lXOJ&KT#NCmm7G|F#n#2Abr%x4p z8jq!+qhtYudLw}omPQxmERW@0Uf#%1F6ouvfmbepQ}I^zq|e+npe27Fi^6(SWjsPS zz{B-~0t5@QW-FY{@fsWXw+YwBzLuNCONdRN;Q;F4y-+8@w*$(i=kGZ@FfBBB&gW;^ zeQ4wG1l>JN;$({gsNZD_jpdg9xhvEcJy1Ib26{Q8`e=6EA%SH{(r*-&djUru)5kE2 z-uFG$=i=l^FY`#)VIto*b#InQUUqf<81R&%J6}ydKKD8A^S?XKf)xM2wc!OMRW$Za zt}|VcYGP+Ls5__3OZQYY05nVMA3lRiB!7g+TKLt@5X-O#exS^i0Kfn88>>D3nek20 zJ@R?FV1nnhW*9|=A`R22;VE85b#KYiKK|qH?E8{(3l5G?vk-=~V75?d%3C(ry%o0r zESu~+U7b;}p_~Tc85saW5GME#{5N<1L68iP3eazkfp(@PgyvFzWT!G$`Ac&C1kN7D zzClMm^cygBKMmO?e$|!l>%xP_W*4CycM{LDpTe{EUSbQ6c~nFU(pvqUWpfZ~4AWXb z!!AL^w%7!nPJ`{>fz{&aMnS`kGc_pijPZfv<+u&T z?q-XETMzv`-A7KsJ%nC+|I74pB1iSH#NOh^kLo{n51x(NM`3&J0s6D5qN?wYLrXw^ zXbf(W?YPt)q46e|RWh$WDTaME=NRl3;4SdMMgPCY#6Dhy_C$&Ml=<9m`*$9W)e$oN zNv^rkCcy^K%ThX&TV81avMt#4n?J9qJc!}NWmzKS`10-tVQB)lnPy2c;h<7UJRP@! z+O~7nM4#MNi$2(lUa)7eN*dlN6Xw15ks8vBr!4GF+Xv!gogh7jtD4@=x3}F)lXC}{ zaNVdk;b1kl;p6~jc}(65g>ighpPsXO)=ACv`iE!Pm#W$_K(*i_ zIhP?Gw6LQK#b+KYWc1R)uqgeQMP($CE<65WtliEGOb?ZJR&my=d3-*|5h!fZ)?L)r z&iJfq&>T-3kRj~&v8vJw#aL0clrj>wT(j!TpC$9`ek8Az&vmN2ZjHn|$G`imeObxl z)DskT8|#6EF4*$7FJeH=x~Y&hEv)C4wSNtK?i=k4WyUusBc~T2=zXMqZX<*vPsZ#r zOAyQlE%wD1RB#x^ALv}29>X)L+M<1m2GUth$pJCLjLtphilejqyjmqg#;XcC#bclY#3Ba*i zvChW6^nZAZaNTqo4P1Jhj^9$9U@~_&S6LDT?1%0T(ik&8fbjP~H(=??93QeBBP*U3 zea&H^grk7CggI6Fao^ijaA2>vZww_q*hpcy{%#&(c*0n&Z|_4XKcqi7D<`6&w?!=7 z!(0QV1ze#Fm4u!n>H-z}$UUF0cl1YzJHLkI@nUG!TIGIzVJ)c9nd!XrC}jdS%EN*c zT~7C*3txHz3ehZusOENkIp=n@ zlL(4=BYZun>xGp4d;#Tjr5}*V8ngXAQ$@?-;ehELgRMk#Wu-+o-4Mf1qZDL#z?&9@ z>|W%N(%6i|al@LSG+$e#veH)6$|^X#rVy8x`Sl@p@;l0>pZ_6SWgjQQ8N)4esdu+U ze2qvEtu9tB>hAhmzWPDbJgJF!Ligi%H7W@9sEk6~_nG&3+2{4Q`t->5>;s6*n(6yV zV?2~HgXe%o4Xs(+$BkhK`yT|(E?A47KNL!qU}mN#<#0KNzDFD(=OSH@QIXU4y&qMG z`u|?Gm^3MQ-bs#dKgK^k=YYm>UVsimuniQ}o8mgHB3#&NMgP_K+v=&4XE7ONad_>v zkB28@fxf49SV%bG;o&>szP|}=QZ~gY}tK}C2q&GeEHews-#QNiT zxyt+WB*of8wSl^BZ^_=~t~aE>TFfZY{Wkh&!s_5W?s1g2xpahNDaoFMdjBd&6xH_F ztfdxTlHVUA3bLDW<$>}!m2~Yx8k`X&dQ_Q2_%Rrjt1SI>K zGRo25Botp});$5bUkDk3VQs1$WE!q!u%!HaI^A8Cnd`aqZMVd;66t zQJ?$iL8M2Ff!J`vNwlBqX0_2l5}n)dJ}Rf;cY%Dz{4~yMe$5URc*hQQ^AgZc5wKxE znOfa356@4LoadQs_s-JnQocDfqF)=ECj|h- zhCYA!&0;N3AZ-hCDn9f(8?oD*Od1wGy6%m-6`!6haqglS zRB2w2zLCTCknckg@g@%aqTzJO_@huj2hDc&3m;RjijYq-kQ$mi|MnI z-Q>`%+*7E2qYZrkocDtW$u47Z+7TJ~2;O1mlH9?6+o8P0dP!uTBGz@3ShzW3lW0OJibh%6Q`Z6hY&fBU`x} zb#2lPL!!jbyF9&SVr8E_YH~SvfpEV~+_MhZ#peRt3r&RCje&_I`n?A;O8x2`7}@VL z2!(d4kENMY#@+Gq-D^y6M%MM& z8eWrkRjGY-*k2A!f8bxgf#NqTbUzszin8!vXyZbO^bEUuz1?S}yz*lMkBzrq95_~X z^HsEUm_DJTCl(rHn5NKQBV&Z6Z5lTyAG+3wr`K?>I_d~rr|+A94slaALfz&NV=}=MAb0* zN+A7G5EQV|@s5s2ufo&MCbL$~NhVQ1_{&#zQI@T)x^2KuUqDX_H5i5Z6`YpH~PXfk0YBY1+C|6 zHSSlGk>nZ1jQfw*1zsJ|>x8nu6iR4M;dl3*ra!B)54OxhVEVm5k^_?2Mxr|M8?y7V zG|q238x%l6&%=^fU}OZ6!->BY)0)qLx8tBXG zckj*ubyb>m`Nw}k<>rf9SgGn&`f<;@_I|P11af6%FE>m((a&y|2H7El8exmTLq`EQ|805u(Z*oxJL2n`}ZsrmrJ000-u`!ptFJytOV6-H#H1i zw?{oGv-7?Uq}r{lGh#Czw$2&s!G`61ZmwtA3ExlD$C__HTO4>t)c9u7pfG#^Wqn90 zf5-GR3pQq^*ke`Aw(YMa>8 z`*2tr_BBuE6ZOp4&H9T8*-RGj7nE(a&+>WoGrC?y_oKhh6_yB(7$}Hl@L0G1A3y?; zjZkSky09J1Gho}!<>Fz7AZ_*TLcUsmN&jawHzej8;?mdsW^Zl|S0^N9WKh$(I#(k>_ znaQi3-|kXrd?uvzaMViN-8RZFEr@+39?K$(u0_;$$gxr(pUyIx)@(3{ZVdk7NaQ9t4W#FpZYKjx37_9~n=OCN~-Jih((@G(z#0e3#) z31Tn8M^wWw2+k1<2Y)?m7F|fi;uZbLRwvsd#`AYx`k+4M?i1Lxd!xcSTq}MFoi-s* z^5PKR1Ntr-T?rT){~e$R{80lKqLSPD)S$^uq8gmC1gD)vXOs@qeuom1;I283pQNwV z$<41mTTA&B5698)!b7$X0$9$U5nZt1I~I;Fn@zRyhg4{MFB<+@&Q{U0izKDo=5UV$ z+wV$ni zcwmM$q&9<(YZ0|DQ(S868rw)P=@VQHjoI1pp1f}lP}j0{pphc?uL@~_lkV(oC3Pe7 zlQ;JO7M!}dLNjCT9HAnu(g8|m-$P&M?tL_dE%#j$P*WC+qrR%(2YN&H58e(z78< zzhmq|LAT66dFIjVSgh|}gL{t$JUzt=-#6yX>cy9nYI$F#g?dhdGW#4=-6dwK*o(3J znc2-G#H>DCS)bK{q#7qmI~>S;k6#icKGjF$IsJvY^9giQUI^{RLpgZ*UQkxj{^prz zd54eUw25FUF7jHwnUQI>Pm&yXU${_P0$PabBCZlqrvCFHXZ;PcGH&Y@onzEdgZY(d zkuZehZ!*qfPZ;bC@r>Bc-AC4L3}0Q2AL*Br4B}|1;%<}I9tcRButYUle)?Xy>%O)T z`ni*l23=5hEg{UpeUfsF(X;m>^U4m#Kh+!fcLR}sGvOPssOH=11fJ@Q*L>I`zh!20 zh=`N30ibQk@#kX4;F_;j;H>vRJmg?BdU2UH9)yVx5IX+qEyYkRJOEYy4y(!^Yet?4 z%^fEOZF6YfWm)<`bj2dA%*kfHBkc%xh;qWeyM3ppT}S{Z%s43I2_ob*{1rH8ncW`U zC>42i*G|89UsVPDnwr~Qay($I!Z&->-agw5r9`xRz|^4J$VQx~jhXthFy_KH6J*t!S^#2yXM zL!i>u@wUgp6Ugs$0ky~q{cfRPm|H5Cfz>bfr+B1(jarM{#0+;;PD(!BE}#LcW_-6! z&%2F+s7F>2`#hm&xX)IF;-h3=wk+88`M`DUz!?#;KQbJFni)#MGQ*q`3m^sDx!?Ch zuLD#W^L^TyLDxymXrU4Kyt%K+34TYNm^PPRl5-Pt^7ERL@uLQ12u*b#?cB4LD#NST zuB?_c5UQ|)E6p1@BR+#@-5=q&=KT7KsFx|91fEMr4LAQu_NNZ&JCw}-prkFm(Bk&5 zGsYy^aVJXp^EtV!J7Ex=v(vd(+?+@KIjw1CRWkf`dv=(OYbNZUSfdO0ExkejXMtK5 zA^IUZwtsC4Zk_>N;yFiXpG}l_qJOCNaRX zg^XLKI+B%s?khDW=uSQ~)dibPRoLsXD%Sh2u#$UQq}n?Shv@oHJS>EcmwGycLK%J{A@HX zN$tLaV?lMUh_Ajs3Mg73Eq+I(0tN4xW_)VQCoRih(S$r>f!(qK&pr&DB5=t=#Jn#$ z__*-1b+BS9Suw_?%3|SIxeMpV$+sfJ?1xA{v{UowJ*dYa|5mPE zx6IxawLc>boe<8{{YFIWxQ{OL`6y~=oasBrPB|OP?a5{zwQUq!cWdBxr|%2dhq#~L zp}>4^A)(A3)okTt*%{y0egDbe$Njyxp%cHJ%6mH6*!mxE|F{b9q_@mcL4Cu>Ff)c& zTCG!c{u*YY$J(z$E&d3Fg2RhRxh5{0*Zd9$+jbE`aEEMv_;jQ<=lxzD_+gb6oqd|K zaEBCa2tORcUze7C0Dt9WpBJ)^?}E3S?~k=jJ9!fhE!yhe+ol8EVvw*G4a6-0N~N5z zt3$Gd)2NM9;W!-dmD3k{1n^TC_o)xhEZ&0=cwFyom5ky%EUNo5I(-Y_H{FC8pU!t4 ze1E+;jHN>r_Gk3w(8_(Osh3(O^XtKx7FljJ;=+RlV15EGy4hpsHRt>}^fjBT<=3>< zW9Pygw~X@=^kL%m6@+BTAtM&2u5UdR5XRmmO|bk}oFS9!wcY|{{+}NmUmX;mf^v?A zPr}1I8E^|rK4-ns+alL5?(~zF<`AT+w$GaPFJ7z9K2*itSb29O8e4;Ks=Cd-{8GjX z@%14><54M-?x`o{vb=83blAgjC=*bGeND)oxA&qoi_*HF_`-Ai0+?Q(2fJVQIVg3# zOm5BbSUtL)HU{!AUXKx!x9?6+OJ6NX-6kWnwA2hp1|2eoxNz_5T<6-pgz#NV!rYnl zBr*AflD+R^QFwk0J9|R0zu;D_@yTNkbL_XKcc|W!5ft|K*)NsuTN5M1?Yp~u2$+m(9*0hE+YFr?w$2syCetzP2G}quT+Q!|!F!he4@OVUD=m<|xpx!t@b zPurtlrSwv(mdNL$G+sd;Uiubm0Cd99mpVm6>`N?Mh4*UC6RtKNvO{P)?s4$Mszqkn zdy!EoS-))~6^=CfT|Klike1s$^upL~)UA=YgrfFP(LemCiJYkqurHwvHJi5B_l85{ zek$2Ny~!)l@TPJ*(c3j@_J}8Ce##!osfC+)>~!xX)=+xN#y&4j*E6i?XyYEw9RNgK z(%wkF?l&6mRU6wlK|b4Dr@_6n%IK-kAaXtcsdn1Y5O1B_{~?x6T2-7UPsp8bYR;L-%dA`31)SN(8*os8=SGXu5az-Rn@ zq?S?k0S=$JA9^I(FhX44ETnfn1mRTWj;7qidzJD}nuPRZf)<4JjxPz)l+uV1{oXz( zC|1YNq9|ZN@3D!GqpbAXjN`~8H1q8Q#RwFyW{HcS!=<_iH*J5cAM~ahf^%LZynQa0 z{K!vfdXBB?1mRt4%4=FS3_%vW0s=q5Z z1E3tTzs$ye8^;z$Mu0vfhk~>L!({!!u!8BwdJM9&s#rO^jo^^k{vEjUOc$91lN_OmUKQ(x2bY>PC#`F#54}{dNwAc&olb`B7oe_p;C%%GsDilfxVQ!l#lr@sk62i+i6O-b^Z!0+Occ% z-Frn9GX}K6ML0{kQ~zc5q5M#wFU(O94`%}XZ|_lGi4JF6ENS-Fc~C@Fv(o;`7x?h- zIl@l_?Cv`Gl26hmRfBpc+I?Sccp*tCL8|fdMT7Ri5i0lw`%{k4p51eaXFLt|RRA~) zo}wc$EYh@#Qb4uj2J4^En6#aWqOg0DDuCjPx?a$}Zk-E+l^_b=-E#z;Hcb*Lcc0(> zcK`WW-d#8o5=W0S$2R%1u;a7OJ)n;yZU;NuUi5{!lu+a}`|qss?}Z|0soSz+5AT!f z(w>u)zg5*YJP==|u)d%Dp||5bS!XUAv`;mK1ekwj>co$7<1R>*Z1wo|7C`f*!iK4p zpz)nkgHTWxx+@2Q8iZKT&T>{2m31fW+7)aPo9c`8ykwGNPPjN@^!f956;HEi*AHPP z0377Q)JCrL6CFWC)t8#NXe(lb!a#VsbF(j=UX_2m+&F(ke*D@o#gC!+pWS!8(iA#w z$Bf!y_4(y#ak7l?RNpLg*3eDK?BF?~#PO43CZo65z8lC9K(P^f!k)TVl8!%U+jaAm z&TZ7eOFZz<(aJJM8HE@gH z{w$P;`m<~uuE%fe!HYhQVmI7e`3egE@M%yPI_Bv^NW`dvDa8cYnE6D;!j>yNKQd5x zRp6&n+D163=(nV7u%HPjKBhE6pziNi*Ls`By2 zo8w60%4?;6e$5a9VQ5!aR}URhqUxA*y8Yw}1V#H5?uK9XAVh$_6U4dff(?-1#+slG zCv{CyMII?LUkj-6=luCZhtm%%JL>$jKYcR`QCSGgnhL0J|2Ckya%<+>4-0<@ToF8h z8bM-~Pf+!0{< zz>${SDA}l+Po$9I;2rc6*<5}{f`b+W*F45+ntoG^XsPIA|AoQz1kYQ9)5B+o1yX#7*0mXjYFA@>qeBK^< z7+d+6=KYZjm){2S1S21=g+DCsJ97ad2B-6(3Sq_CC)BHZdT?yje*J!TB7ss(4=glS zeDA@TP>#=&Z|t|}uZ!hFE>waVH4NwTI!C%rRuh`@1+T&t-ue9=4N@SBt&?`mq!Zwt zZBPnyS+w?_6~v|NPTykziY~tq$#!_VvcyDlyoCqul*x|+l$(yPr4Mr@%dotpbV$oj zM_@Q(ulp-sSkQhoUb!9LiX+e(Z^Cy24r2SBa}xXWu_%`2tMf_qo%F!;8})VY_JGQi z>w15v@}IuM)WD{$WZ7nWKAT(=O)%(NjT3A$S4hDN75aGPDIU7p2l}%o@2;j#=C^Z~ zZ|R+w({M6LU1qQk8dB&zEbn3?GG!S5!rt=yR{`vz^VDZpDb64>mD+>#t$TK;HrD$e*N5w|mD1LI#_4sdB3q2w70D;0eQTf)YD;_sJB#uC<|=l)qM{|GuxKxB05we$>#a#^DwLqr3q?{ z>G56ofF~9^4i(+Li+DkFKfGx|dSo|%j*WQTw5g7>HF~J_Ox;fL9yW%E)H#=o3R}0+ z`WB5Bdw%mgZMQhg$l(r-Q6z>-5e@&TL1tN|f8^dDj1k{15=D&akc ziv8?-E%(jb-Sn~K^#=`>TTCVUS~i>>!X7KFUzlh58KhpzgrsV=yDGy*b}E7t<7QC+ z`UhrJcRFN1OakHy4k!6bv$}g_thS%*P4SKd0h0&)&X_|c%VyCx$s;d-ojDv>)v1T@ zy+Q5m*}B)~RMMx77+o7@&hjOqG+T+^#B&SpWBY+h`!4SUn%ib@-EYc0P-X9`7TbHi z5ZT2E!nar?U+U@iacJjWiK!1!1Ezix*IB5EpYq68b&8ecVyp5eas;!{k7g$mr3j>e z+pxCAoS`|U3cA@u%Ds$;kVmG>ya-g@pwK%&J>4d_x3#h}26Ya|FK8vN2CH?c5T~h` zCS5BwFbIuB(#TWGeI0X7Co==TD4Ei;unG1-FI(cwmw##?DRUW5B9j2&gS_pAw5f@F$V!3*xmJWKiQA;XJ}H7e$qldE-x zwpaV?s#lKbDSA2?{VDHI+gy4-0Tm`_ZUi!lpDzgx!fjMOCi7Btdw$V7TMN(eqqmRH z8k$#yF9?uEt1P~PmhL6;M~&%v>w88N46mO#h3xtFZ<8V7(>+;S+IoL{NBvIQG&QD% zgQ8Av1xLt?`V_2fs_$27$Twfm#do_2;zvh#S!|7%b5;CF??2;s%%!IlF~Aa{e#{Oc zjT#*4noqb=;-so?pGN06Ezkiui`P0KUxUjFw-a_c+!FE1O){Haga$TIaUJmZ)$eJ- z=OA`S`v`vA;bHK9oQMKeko(7Y-iL+k9nyoyou^}%?T1OA5P)wT=~ri@L(&!Vzq8<@enfjUs=WM#v&*goBRR^2C@EL?0|W814SKeme14R&UC8`uPQxRPj8YWS_e&)xD6J)_mFfZYdoM zuNq+RkW4R%sI7glBst%EA?ScVEW!1Bpt8mgI_OEfZ5#Rr^!y;{1FCKdDUj-}AtY*q zLyxuk)X6LP*q;x+M4q#jv3&1yGtHs>@knsfaLRuFYnSBo0)$@&28+x^s8T@b4u5>^ z0UL79Q{7tVcHxz+Dfqr4j@rGMR5g)q4IN$2&xTsn!!!Bht1GROb^P5QPkzg!`}Mu= zM}s|<_xQm+mJk|kZ_M01Z6^#Ta_i(+K6cQon7`3z@?r}M*TvRiy5#z}K0`^7gkV*P_D_2Q zG*>X~m1D`F-<*9omI+gHoJ-+s3NdyNLOY*+fG+ReI zksp4jB2E#*C6`i@%SRa}A_~~Cz2M5;AI&;~*y!%p&fMbJhYnHp%&J$5l7qqEFo3D# z1eDe@*SuL0e-dNz>}bTpi~oEPt_4(C)7$8xgCaJp&m72=)DFKgk2`k15}kY9V3SI8 zT|hN=)!?iIc~p~=Gn;vVrBn>Z4t{G7Py<5fL9#iyJ?7JsPoI_hnuO(cLIAD2$>t^< z`aA^jQu1s1fO6!x| z_vq8)cHqO7G9)&h?Bvt*ZIPt`f`@l#vt$LYQ9b4f#M)8H#tc3+uBycc%&m&_mD zjg5&F8eXtE=j+2g%vU-+(-4qay`cV~RYqWI*9i8$fHK51*T=F|OHT~nGxYTD-7P$y z=IhP>mJadWV4J+f+mkeJGi%L_CfpwT`lyEy>MS;OGB$3}j=P?TLWV0mqLn@WdVi($ z4p-A-Hr-)@3QySDG0xsF8DO|VuP>jMZ!I*UJet#{Utc`bwFv0i=(U_6l6~)YDGD4P zw%=h9W;9pQuadYvzWycuCO9U=UE}`Byrn4d8g*} zy992CD$cVGd+z>)lKcWSj<7q51i>nFWi#)SHQhB`{*ctI%cCY};2DTT1s*(U-Nh8+Bi zQ*Yk`Ra{fzc(h|j`nJ!wU0gn)F5Jy<{bZLjr7#a{3{t|c4r1nZp0hXzL-_!5hvm*($#Px$sLI$qg zM<0`{Zqsy%K$b0I`SU&>UjT|bJwL#1(PKYzG$o<1-;G3Tg>t5aKc23#I*WkblXfV) zgpW2hYMl6#9h`xF@{!8~!k78|W{oU13S&h zsa3%tlvCm7rd9jrO|Iqqc9pPP<^$#|nzVa+Ln-dp`r)6YIWmG6O3sE>uW|-=jxZjR z>7M^CGLnc&XkHN8e`XZD^2Z8Ykm=O2B_}XqVjor_26yw@iwV3(EmvHbQm0P8K*{x!3l12w#WGGJQdssx>u!TmcP|yu{km zVPfox#xhi6?~W;ld(K{q=##}p#G@XUo71$n5tPY*%Qt%+P|1R#0{`aICOII&u;=m$ zLBK0peuMN#lZVuKt@k^0qgOjWh0IsB>XE3l%X7I45AK<4rG`BVOE@WOyEPDS*(jOb zn7h#0uc7{4z}I7+!wBJR`26iAPl}!cEq(Qd?C|_d_rQQR+Fc0h=Ih?bg==VPj_SvUZEcEThn=lT^z2a`^}`^@0=xI{O5QLW9}geAiQsn!D9q<(!W5X zyQ~h-+s$>IdWmex#Fp?=pS=U-1odJh540l6nvibUGTdBdIoS4KwA_4ZQJ0E*lLpg$ zd;#_IrC~Gt>E}U!V84OQ@o8x90vcT?Og+&$wXQejVE-DU=Qz5&_K?oMw2(H@U5Os< zm0~CpXoBNPtQl9Z?>?5SYP`BB{O~-NEA06txzn}dZ33n!mwdL%nY?BCR34y*juSpX zXQJ^P{fh^@lnDb?^<+sH$_es6%1M_h#iSgH`>DI5p?P5(I!j^va z`Sj77m;&%rVqV=qy!_fYgYWvdp7)hB{6t&xe)Pa4uy#6}bL(;o#{mJN2rqaU0PSsf zWEQOtiDa0x1B@_sUxvT%YzbQ!)9EJvR>>(?GtsHSNENjlm46*}jMWvA5>eUE$49R< zu%aiTmYSqqb@$cNIqI=3Gxts%}AB;s-)&u^S$oy zNKwNSFxLl+pv;KjvOa8<+X_j=>ysp1zIn(V%;5>pLT}!$e^eOd_{^gYq13I^XI4w; z3BHU!o_xZuw`U|bf06sfF9K6mR$^^mIRAX~q(@ofWj8i5>*6zkNm4~&`ohuhQi|=M z`r{>`3{`MO=#$j!ZM6%=d|NB>iSE}Ch;rZ*k+4wf%siuf$EwUjn(wkK3m# zK>YQEEAzaWHB^#6fvA#kUw;ZwnD0VZM&`7RoTNDu7h&5gPzh5PrjaF$zQ2ReYhL z!Hw0p4*9nQVOLYD?P&pjcjRt+%`-x*q=Z+%K(iMbov%-`CWlYLohi0`QtQ$wsxx=( z!EYced|?~ogxb)%-jh)Ck=E7Xm3TB3=ZmDP=5|oGUQWocz0^^ZKM-&KC^pcbz`S8L z^X5Ut?cR&T9i?`$szJ}P2J)kSHaILlJCNwdfABox@+R7@+WJX zAb@PCP@IrI)L$vr{nNB^&$EwhLPQ{DLUm(9-Re{CL+^DWE}~2ShK0S6y4x|8`QioU z6*u{+l}3=i4`DUdvvzBO)BX1C&u9^!*?2s~^YPclXX)?#VEd1(2j$;uUIafGuMb;5Xvg*7wmF{ci;R}y zB4`58-r&wxd90$?Iin>WT#qMcfPVqQ6m`H)-z{@3f-a8o)chU)l;`MFy)ON}r;w}P z6V27pLyQQ8Eg$4<4||VswS9{@pcqu)H?*M-C#($pTLsku`mf=9$K`q} zK@RNjnWeZQWWz>-d~^5ZrmIt=wE(IupTd#rYIwmyM!$}|q7*M{6{_?SelPpPR?oVa zg3FU(svibH>vue(pr2rY&@uf;7@odv_Z8u%B0&f?)OwWwU(k0wLvsla<70Xm)ydeCTg-rsemhnvqn%$>yoY3Pae(GqEc4 zrp{Z^$PbLh`$@;=dXSY6ed07G4{wDCplr_{_B4xxr2_B?Ltv~7gtg96u8-Iw((v|T zh0Wk1*tJcLKkT0K1c@GO}$Xf28Yo**iI>B5GRq*>V5Y|dZz;xmc2|(r$aN^EO z_OkBRU`3^l^$5BB>o((!6%4gM2}KfbSbXA${b|OcE@~g9+|4pB4}A|iPz4{m5LI_r zdR}iAV958yS$asXnkP>NO@4X7rcaCQ8}Nshj>c-<_lV}^U^JR~0|)J(Tn*yHRK`R; z=4ukzi$bPOIs(4p4eCfA)wE9Fhxjp}x{hYDR!K$T)vfHbF>_niu-jK@X)ne7%mXWn z%z4)4Yf?rKQz*hI&67`1RyD7iVJUX2^cQ z>X>~znad3>d!nkFET31n?chXzoD?$sla05hB%l%rfYw(^-y0U3Z=u*<@yo3^o+$dg z2jT#3)myONxM4n|K{vw(V6C>FZCp-06JF=w;>`Px-0^Yn1NIHmP&0&t<( z7^bPiHaoBz`3&H1w{GB`!Vfjt8ZQmz3KP`elMES>xUCX7d+zNe#A4 zbb;bxARGo3Sd|}3#c*pHLkil#1CkcJ(QFm|hfG~d{#>LQf9isI-MT%e>A^r|T_J}| zLp%TWXXsPfbg%*^HN7GxEQO}~79o_9f5wV)^XDTutZj9=AI6LT7=g6WJxHoQKb5+Ly8^QnTy0`x)3RZRuz2k~FG zQ!Rc3%g)#~PEljxTHf7vKY#C;PG5g;HiNsNeLVf@E!&r=t!(pAt%UnLW=j7(RWIna z*u$^9^k+~nA%DTcm%`F-u>JhFUtO~&1BN}NWmgX2^lj4yYp-I(9bZ;0eQWrLN+ zQo2rc6jm9S58|8ZW*Eoi^7UxQ!v+2wi=C=@(ukyNiBI5wE<<607NN(B5;h2%jy?enrce+SA6Rq+QB$|oL$n$=S| z8=Ld8Egv=ZReFoubTn2Oj%7C(RMRhZYQMib=7XrJw@3QEosOx7f8p~r#doP7*fuOn zgZr(eHz`aDsubF|Hu+D{t!{o=t_BZ*HoUxzV*wedU}Yuucs{zqXdR49~d%C0XghT?p-%<~ydohM5D6zUe{MZQ&Yz5ir$yy@1n(_%JcC(tHM2Q^P0)K!RYI^^RUr{&v;9u_q1(r zrB8p(qD@oPYPQCy26N#{B?57?wX~0$AZ#mQZeJVu8VjrhBErET0NXMPIy1DaY4^F^ z@6ne?TO^W9E60*-os2S{@{@Gtyl`-SkRS`J+w_Ho;R%X*<;XwZBK-=C^QF7-?d$IK zhNoQYq61F(kND>iiJC3v;&4+XhTyYfNRzbQdXLR=!EpXOgkdY_H!XTF%k@rWWPlyW z3)<*O6qy~Sz_mhW3bR+7^UYWNM)aOB+B&^ug;44>K^@G?OVPFc5nCU?+&0*OVE$vG$Fzs=JRV$Za{?t^9X9xW)h4!~& zX#kFNv+N0aY9Rr`$#?@PTxG|sJ~kYKFq5aPNF4$xvLJdD&cW6sWCp6^|?e^#6?dV_pBG`hJU zA{O87XNEM8d@eV$5*Si$oMj9u@h@cfQs?%smyQP|J_kr#xyrg4f6@TMK0NV7JzP_k z2ul+x_V{|H<@HT>ug8&xCo6SPm?lul_*y;Dfi};>^|jP*Qli+%m;ZK2BV}jhx zjD0pFGheSk@*vCc9l!T1J+Fdb5v4TydFK7crqV?!xI;)+!O>cO{PS^xdDJ(uo$~|* z>$*P+kbs@^vv!HUJ&kzBd4NhzfviB{aL_Cv_2oM8gU|CVL!KVdT|!|s9UUiaA$kE= zkW+M>7~JInboSn7yZ$}SM|q!O8?&@`(Hxff*i1%Fg!yQX&EYzf;mQ!*2dpg~We)$I z2VFb53e!Cd}nnkdF-3KW(x_f{ZON`9wL>rWqB(^!OG?{?e&k5 zGM+9`gE@+Zlf&%Q_V=KP%%x1_XWiZy^9qaA*Uh!X!!z-5-@hmk=@sRxZr?oc zu*8iYE9w$_1MB*5^z7>eJ<4sMS0CDH3VN_Q>&yx7P7LcBMiIVthf~Bm`9y0OE@7eCdJiR*JD|i-WaCATTq!2TwlHAmcDfB%>Yo$2l0A zg{B=Ii8#^1X2iu=`KpJ?wtvw4Q$R^|^H-ca9_Wa`~QT^aTt&J88+C{Nz% zo*#Q?Tfz`Gc_O{=g;y1y1s#?ZFOqyab50oc=o@>?Rl!2Czl`O&_p#kWN7A_+A2E{L zTYY#nA7)k6!|%gByM!o6p8NbIYA#vILoqxCNkhEz|{rzVNVN< z0=^hfZ2%(~A?547LafZ}`YU(>+;C@Y8A)}hL4x`2LY^pGBhPT0Vjuj+bUDJVK6Zx* z>f|@Og_~tn^rIkZj%fw1BLP4}ck0$nL_B3r0#>LO>w7R3PTA|KH*4AN2Cs>*ubG0h z=hK0LcN2BEu+#)Hs0%kpCLoADEsou;*C@tgYofCYF43>)wF?^}7Us%v^Rg9xmE~|a z!A@4LU*16A5=D}q_Vf`*t`lt3zGhF9r5PWO#=ivU9M-?@L2-vP*)`-f2k3jhDm)3LDe zgLHw4K$4bAck7EZi$Y|0Q(E)s>3fy8gt%ro(d$N#M*EweMV7MnfsgN9xUZTnIScu* zHRAO3Dd-Q+@ z%y0g>lRh+>-&Uhj?612D!lP#oqfv|^?yUk#qu!{L#<$=jOPZ)j;Tps{nh`wyGNc0! z3H3II&O9@SwRnPK^kY5`$>UY;1-jGxXgBB8Rye1!=8y?{NY_qV0Vd-fAsTdjv6jBS zW-U}b0*{4raB+nIt@k__(@35}Xa1~Z1qZFoHY2Y1iTwF%GHnly!^F3G(t+Qt4_ed` zlt0T@ua>CM>SZI>qexocU$6e?^q6jR+K2GD_?;`Riu_$aTRGBT)EjV)r=Ui3F3j)t zzDfstIA!h^zyH8WqNcS|mANAz`J7jYU@bqtIC zNT3cm!#bwaE_`wg=6(o*Z>50cMKe;w8AN8^^u-#> zQn-BtNmQi4^$+K{#$Arm()7$DQJe8z@f-63kL97i&d2l$am!HyZ>l?2r+pS}0WsBD zGpm_x0PGHHIAGlS%;@imZA)kbM)bhK2ezUDn|li+4tT*<2aw8r9?IQ4OpFu3t)RWM zdcrr^!x6GthtFnnryh1YhO!(Ih=i>M5ZEVpVKMEWnkjFqp7PG%_rN@}`zX8BTZyVT zAud3y&*aZc-91RLQ1aEc(~NG01S_n&*6Z9DjO^*8@vrZd5G7yxP@QD!1L zF+QxKflKk&AHj_2L6F^iI`$M>klq}?WBNPrXna z+a{-un#<&rD{#AcU3g(1I@uy7Vvo{|q7u_B`IGH_ml=&W@%N0J-Z?@lae(#aglrN& zet?jq#w(MLR?q*bGhesPT*}%Pb1BqZ?p28 zpcrNTxg?=SFcc)}ZtF`#z$p zJu^Mme_3#VfSP^Xj!F33tFng_F^!l&jFwe4<+soN(8K?J zDtSBWcM;kLn&2GPlb`)ifPedJO#=CLeV%%#hq9Dg2$ZCBOeoqk{13KvsR z{q;(H^`i}}6$(-AOo`|FljGn+ajFC$Uyl5buX*$Zz2J&=4?#dO3RmGmYvbicVl+RK z`nfNj_J?tsPAVR+bFh!b=`YU}3Korr+i8=C+DjKoe~@M~EB)Aap9fb%i5N>XdB+E@2?#Fc;B-nX1W<__z%{caIxy-l-cBAk-_+ zpkO`NJ_zjS?tN4SgJYiq7c4 z;D=xMQ5_a~&V6`o=%sT8Nw58lyg8RZE+C}cAD#nUr9ZeiI!WRcu1%-#PrI(qv~h5u z?F~(n<*`GJffSib(we?-q=anKq3&Dyz*_rq8F$w6I;LZC-lwo(8Of(A-Duwa7z4>T z^XupBIVN+v+>{IzX^3S1-Gx7i$}zmzlB$11cT4y83yIA*)M=lVsF{cw`Y$0veTdeI zItIkcW+7fN?PZAKz$kw)Q>E6JGNrru+I)Fv^qKK7^6t`MhJ^)QJvv*V-tP&Paj6m3{j+%yl_d$ z+wY0Wt^>Bp{bG)PFqJv}*sxONyQm4*KOhbxT4xxtEs|!g>%EtX8$)=j zj%DAb@m_z)?L}lHk6Q&%Z%MuhWY3tD^usn&w|>yVkm;@r4&U>%t{EJJkH`fD`bqv` z>*S|{*-(4vWd*67UXu@zisXTGA^&u)se5 z5W~K?udbNZaZ7rs%snX$A$zt6=*Gd6MPf2H1Y6O)a}_sH-ANRs0&K#T^#;!U+k1qI zF&rSY_j(C|Dg3Gb53u11M)`K-g`gZ;c5%ox-Y@NK3ZE4dAHNdV15t+3Wj|NeJYQ%=IP;ot0%>n>e$t|Tt_HdVSqBd{N;DSH7ca9Mt(Ff)*Q9?Byln9{;+sW zVH-Hl{pFW#Z8LSApAQFvb?F$tA6lM5Rk!J0AFe&_PBVhK>4Lu;TpN}NAk-%FEpcug zpuR)s>TtP=olO{X)^HQ~Ptk`^p*t$$N~h^B&-t}On}{A#!R%@q#(L% z(f;3c%ky!4mGyxrz&(u{qiQe+&Isguq3EaeMZckX3Cfr~^|uAvlFVzw%i0|c*A{)Y zT5nJl)=>Fj+s9>g#aLuHH?hOZIU-=_K~DyKC%q%4n{;$~&WEYm%_9wE87qIrAES3(T`L zSmB{otK>B^Ip{`E182^8-4J#jhb;%0n=26CAJDU8o@~2%n?1aMO5cWk1Soq2EDnF| z<^9?dIUK*8-j^2#>fLHLq(Sqqwz;4)y>;qg_`P-|e4+N7f#`$uX);4V|5zR3|Fm}B zzwt$fabAD1CO%NGm%=w`IEDjF-8zjB8>)ua{O|B}PNN~YJWp`Vsb1d@io#p? z=<~9!Hmrg9^STsu0kO4xvtS?xnX@c(72Mz}vHnrqq%Jp`>E9u}E*x~&X67t05TDZA{xup6Fx-J@EHy&$&|;^N+wjOkY1va7`gFt6ijURWcFkwR`O^R4OJc z$=+UmM=yATIsCUKWsyZXA^&zbMNC>$g%nKQ0cU)`ZxCb87Q!oOfh%%(d`Z^+7D}vM zp(I!Re2Rr4AsFJV@x&+b(>-AG?CFY`ZMZH?$`{FK;{TDTlcK-+8_jEy~5M z2BL(O`=9nypl_+c?d5LoE_S#U<*N%Vq6mIhL16I)duKF$PTP9Y{0gqem?YEy?BejVCx8-zqk55lI9%HB`CaS3M&G13wp1zon2lWQW&33h35LU?|9EVhPDh~b zs&@bACzy0R?YT^U0^s{X9*I@(ju~Ym+^OMb$OKv^kcdcXmtPVzPk$Rp?1}qhslNivzMV^$rq|)<(j%3Ao>iL9uh6_$Vza4249Zun< z6lURu;xp{QZeiQFs}XtxAZ1K-PTBr`bcvvvwHEv)X@nL8e#y=XygHq|?EFnX3ZF`j z(57zo(=JxN0+!J?0l#>1nHB}r@SM{lLl4IB_dZ`?v-dS?LaW6SY8Rnwm8UbDn)LlF zfDCn%Wb{uPN8JV_2Mhc1xaJlQt^K`Tu7q}_m_{Fg$1oMlW8l+jljwAl`=tLzL0Gqg z({HR$;W{t4(gYi19YwGB*?oPZ0upcBLiz^`epz^qF3Hm`2oY}r#FtkDXl`1BOfalE zlo?)~TUX*IZSr3vi1?&(2|XTG%I5ZQ12S@oO{9-Gm=98-PW$Ce9)#|g&Q1unPDTEx z!jFBA&BOEibN4~qHm76KRG(|uo#6xPO3zVM?r%2MU^bA%rPf|2&M?&kZS^!S7P+8b zb^X4wYRHt3kwS~Uwbip$^xxj8j_SvH&p?a&weaZn@4Cb2zptb$$e9#}oV4ZInb{6^l8CY}7qFHKQ%wU!`zhSTD zMA~~@d6};`E{u!9| z__h0DF^04|o?Axyj)Yb!4gaVtNY34^{VhthFASV9MPE)jC|An({Mm0?XkPp#LZRs~ zD*RJg&XkDsd8!lClk(_;$>34A#N@KtKU&*t?u)`w|6b-Kc}$ggJ`kudgv>N^@ecE5 z9p94xZ8r%7I4!b`2U|t^NaYCoBkV;2_{yk%=IUNTkE}i=FDeRwq@$N%`P(%sX%7Oe zaqwC9i@a3+9Ixs5E%wFwj)Yfz1k-c-bnwx>`s})PtsQi4X$j#|c0XRVjBU2VExV#9 zu!G*tq4aYtr%B*t@GY1W<~93F7qu&yZ@}TPABe{Zeu)m->1N%!7(PKvbDz)oSyj@d zxZ=Gm-x6D4FxXOKND+2ogMr|=zNe>cqGd;Ec@gjE*uTDSCpo<&8VcoxXYL^&9qhim zf7h(rx8XZL4WOcd%*yKZvC-tz_|F5QQx*zB=) zz(V5EG8G$8*Ex7+xjFI8X^HswB`X@FcQaXScTOtmEml27yJ;a6C`Df=TT#-(`m6 z)d0`QiPORZ;{6SpE^IgHS4y7YgC@bSl3}&?#+MJ)`+P6&+M@TUI@}8TTtk;Kyyvtb zv!*%HKJNd}TA=YpjV)h`+{8UX6b`!KKkg}^tCgMO%03+z%OWenAE>y#ZsoqA$6BF_ zpYxbRqlu`1dhR$MoQ$P!f2Kc>-nhb@Ca>A_#9am&?lKrJDc`?EUA|D50pwtck3aVe zBGP-Fugh-SYw1t9UxTzkut+)|?Ms+dMv%cg^yh5MV{=_GZ?uH?vZHm5u5KJ0x=MV@ zAJa-Y@d5nyKG7;Fg&qu8^l>AKBP3JHdOO+t+CeLIWgOX4c(f$ z@xRNrItOnw%|j7z0~6d_m}?!}!9Cc;efi3ko-#Z!EUGV@r%M$axT?|;YFNWHH12`*mEI1^E%$_W zUf~Kmk$pLopR%4E?O?kp`B|4=^K?G1TX>A->Hdh#l?fO9?vU{~4m+t;KokMwLO;RN z-RzZ#QVh5RbPcd}_N+#h+dt7P6Aa+RPknb0PM6Q#0~VGbH2`J3&XN|30gOg#&MFvi zIF%1TXunf(zZ8_dC0{8$-JsBP$dz}0bf)Cg2@1?|oQhW0t$dwf%_ERsj{c)DjPSB! zmW@9h@j}1Oyg)`Tr;q)5g|vdO;i7Ydpfbn8!G%ccg3!jfPWq zID#HUYsKXC%h9EH+&_b3CGIErp&h|2hP>De;YYJ`*hBmCc-(*xaohcYFT47X7IYp;d6df5XL&6(Dnee{myOP8@fLY2x$$2wWiY=Ay9(81C~m+Z>^FWBUZ6E2y8sfmU;X4ui2YG{s!Dl6dankGi?>lNSK{&Q zC3e3pp9a$oUs?6xM0-KI{{z8y1&ox#GH1Aq#Cxa!)?EI zec)$-7IPm#t=?l@hmIV*Z%XX_{H2E9+7DkBhIS1igrOVvgZ0dW7tL1T%Y;C#=}g#& z<;z*V&9vA@!;w~Nhzp*yiz2XSPG+pk4Z%?rOr3H%ABgXYV5%O9Ap@MQlP)A$laOeXU@ zU@ZvV79Jg)dokhTHJRQahHct$FkZy22Mb&7ov!|3-bSsdHeQR&rZZdz;CZ|-Dter9 zZ_en_?+M1FmiWI@!g&|a1RX;2hmz2@kqGAO+s_*(92%8LHT+7&NKk%qc~J0Ik%7tT zNI&0D-^Ni^6^1~!2XwR699bD+AQS`Ii=b6#nqYgAv0j9(C+ijPOpLj$E!OVLxH%G? zLh*Xbo2lT8P7ahUg@NbiPX3_Jy{vd<8mzJ5K?SzC;hhRg_KmJcTCK!^X>>;jB_1S% zvZ!Dl!nS~kBAY&oom^R_qJ0^}?Kdr)Iac0Vcbu!y_4 zTE^LC?J0AYXjEQa;rS+e*yE?o)YHD0ckz)r|K|UO``{C zai>ClE8N1q{{}%Tvm$?NdGwB3_!?c`Ty?xYcT5OG`+nl%ai+hIzPFoaqzKYy}Zk*bbgk=QfaFUZiBiC1bO zDNcCGKsn;x@iO zypCBVD+~Clc2>`57X~=m`UdsIRI|?gO+LP+dq0Z7#^5U z_OQ9ut~%27VMS5!(sw7MOsxiOQ^4|g0U_X?c&6pK%tO<(3*oxaaK zaM#1t#<=>{ivT3D8_ko`ZNYMvi;f`QG?Ju=zinSI@+%iu$#H8=&N0`o?7SVmdj42? z%N##)+I~9g@H-Kd{mIiYLES2J&1Qcb8t|&tZZ%c*!6iZT05v`veCtA7kf4|%I zjSDVpjIBT0Xt~ba4ZtU;C^)Y@p^{?@mNd#7KJv%=H-Go|HT22eGghpNe${=EP+ZNi zFW(s|oRLq*AtvGibJxEGz$Wwk@`G$!8s6<5xOXvJJK4kcB}+E!p*usrah6WRer28S z$j`is%p3Q51V@>q+#!OU&2s#H{!}B-u{IcYH((G*4-9F@ipysZGRFh8Cv>&iSMTr) z)FY10c}F6JutFBSq0j(;KYw)6BkuvVj^O)*<1DHxJNrGGb#fjP-9AhX77;A>)=&AT zX@d9n=?}0h9(M|WoX3_SEDg1fsIW%}?{T`tG*9WSJrGl{(VVF77aug#VZwZo@)^^S zvC-90nB3$l-Oe}TYuF~SoZ{j0MjP5X_(YuD071B!-;br7gyR*47L)7xN)H3qJ&x;i z6R&xd0i;*5(ewSV+Hl{%UL^w>)_o=x1n8dBvh4V9bjW_vi8^QLX8Y~8PN)D6El)gb z2FWdmD|nRsHK_(>Jz)WDz1|D_#ABc}O3c~z2qR<9Ao5ABz0vhE`>h>6)ER3e7Y2@v zzIBKoaB(bCetmWp3tn5Sx%y0=rw8kPqW&m(cOZnPuLCgKO$fY0vx1sj#rn^9(@|st z4s+Pc)v(Py?h=92%j=aEd>U&%d%@3{73y=%Dm#3~M&_|c&+X4ri=CGS5sf|>$-@aQ&sha z6(*+vKw2p$hNkSN$9+D9Nd*tinwPs_oF>C^A> zAwh19!`I_b!9^w@@%;TSYB{a13^*^}^CKfpf}$4P1^iwQN*9!^&nLaI<5z;$E$4Op zDMy=_HhK?mk4$?(H>h3>DAi*h*=L~`mO;LVV&5cTa8y|ANz{mbadIIEjJzt9K`h)# zm$>br*o!%M4L~yejjFMac3C5U%XGCkU9x!!GZCGOVuUoMvNh}ZVDDIy=V^=<_-#?+ z52w9Mu^eP=fSms46(-@R{!S2oy2Ua1qU{HT&5mC|kO}e3DF!rV`%R*LgXq)=bBiHx zt|3FS>7lJBUtxLcPkvP9fiw~x?)DMxs__G41b#xnc~XT0#bEnJ!}N7*?6f2Wfh@sn_bYYl-G{CtLQSk7AH zg8*;D{q@Nn;#ng17ny6mKQ@HW{gSkw(|-RC%3O~4+n(}_Z%UKP`12{%N( zJ#h^)jXz9IeJ<&hyifWKkG&7*x*@^f$d^b(r9ZDFy?ZZ5DWspjTSxkkXgKd6Qm74Xg z!ktQ^;4}z}=hQ`(adbe6!cdUS6c~;c@PRb(ddG~gpZ9DLE9M46vm3;g#3mUu#dTCr zeBg~qY%Uk~#^ZrADJ&rz-7in7ku3$jR=6kKfLx6TyxtS;&B10rW`NY->xv{M7#7SO zmjWPq?-`;a6Y1Bzk0`n@)}i}yyGa!Ka497B(8t5O?enCMxdo9CuuBZJl_J6e}F8ai-ND~8RJ zwkuj9=If;@0NN$zxrBASNO%0#zKMzQs98*>y`%i*@=ECSyzJGpyfd5N^;C;r{>?0-Mr1Z*|vJrAw&{n88t-y$-Ky*l%&CbUg;FAWFbf2#N z@|y_gy&CCC#48NW)eIWp3@Y*G$bD&u>E4;^qRod7lL+wect#ZAV5)Gtj*({U*NhX= zMD}M^ohe#U{yO6kIO=wzw1LnB-QBMw$$>z(1C0YrkQyt0X>t6nz0NsyLU$nGC}buU zsii8Cn)kjvr0jIf-gVz`VDuf^K`a_>5BJybnC#lisPR%D{f2?GW%924vE?@YT02eA zM;b4|64NK{>7);m57Y(sXZYL%I8<+5ZZ1krqpbrT^-ad=w5~K3^gESDm<@+7MB20# zs`;texWo@yX3X&s?veaLd8c0`kC+m7Qsn*Ej2DK1IWHRBdfl;FCitCrYqvsTz7K+< z|MIlIJmS&s+veXOKqXIETe93>u zA+{?#x+*eI;sFI+$3q!s_u~UQ_IqzUu+Z%I-EEie?!bGROJ?jD{Wv`KU`<#iQ{I-z=$_$+puNU2-pt}jUQsksX4HA9d*Xn7+glX8f z0F4m#b5UPSV$j|`r?%Mo;hdN()Z$J4R0v4&q(8?QR9YdOvbyd}0Jo0=7)G@#u%TRP ztfxJ&0Q_eN31i(fZAZIYRaKy@AFL|YJ)mpG+xZgz1sk}eFH+4PheblpojyBtosaQvNbLC!aBd25Z;>u<5DL;R(K-$1YK59ndup}q(ryJZi{-@o^n z(sC%~Lnr4Jm~V35PU`b5S(PCzYU4bkZ;=R^d6a(37~LiONOd^hejUN{l?>^a44ao& zTG_X8>-KzH-cF@^eM3vh_TS{brJ+wH9WtKqRe8Hgy}gL65}o#VPqpfTE@%x#@c^2) z;ychn`qj^bGs=f&3}R2x&p?9Cgnc6kOwMw?~1+x zq3jviA$tbD;i}J2Juy2{E?Sx9CVNS`5D3N6tVnJFbfPk^Dz!m{LhsKsVTqR&8>f26;tt_XqJvDt_Bv2pZ4vt_J3r2&0Kk!J z8;cZ8bDpRU+*p}A09|Nk5U%M`#TnWI%O9$U1HZcgQX)IwBjyN=NwgAilsZa-u0ZSU zy9qK8|L(N9e;-Aye0(YqM!E5A35V`4|`dfT=%(i{4*`i?Ig_CHEc=NPI%E6P|+g zhc|{S#|a-s*5Bbl!hBtJ%O@R(>+sTMt?;_HX(FU$(%z^GP!2-w2+lg6ToX3&T+X@^4_{Hx%?)&%=DW7|znc`3`@#%N= zeK8=hdPxzp)R1%7*qoa1f?sj$$}7|w>-$*{Zl!jANX`Xac2sbCUiZG4mE*wtgh?Ne z_Jt3e`(}g!tn-S;(2*|6?2k}8f1sPvqiyYzdiF$Fn|+6cBQ68STG{=CGEUaMB;BIr zg`+aMwk-j@YjW2}oR`Cp+}^!~D`G?tfQt|`uZo%zdo}U(qj3)axK|9Vm44p|&_PAH zK&pjTrOyN**Qw)`Y$%m&t@-1&?J{8;uo-jr@Y*>4t3eirX@Mua%7P-^SlKVC3C$5)v}FdG*m_(P_1i zLO%sAZxdCgBTm1--0-onsVnZ)QI_KxI#JD$foU|s?`st(*<-I((EDVLqU7z7lI&^U ze%jNw7lQffy-hRAl+D+nAFT8J^K0DJClF45pc{~L&xclHZu_p|6`z+yBnz2fM@%j0 ztgb?KR*6{3B0Xw!GM99f_^M{Zlx!PO@5^AljL$hWVEUP#ctN~Gfa)$M-_xnH#=nAd zXO7^N=rnKqc=oZkORTr9qWTn8fX#U%J+iGj(H@pha3Q*LCeM<|7r&>sc%iN~s{)!9 z^*8(Y8!R;A%kMe)msUKe=x%^Vo>_)byrI6On#r9NHp|pYkzy`iU%0u?s)DafYqcDU z%o#2#@0#cCF*Dt7mIQIhKAqt&krSF*-s$~pIsMXTZI3=e+LDjTp5VDgK@3S3N9Q_R z6f41ynAcS+cJf>QmUaJx?4Za>2ZBp{X8d6mp&jU)fM{Yn`%WOd68d-4zUF@CFRyI(&Y?} z*c`!Fm>~kjhOtcFMcHo*LI+(^I7;r!3%7?ZaVvzXw~wZf{=pZF*$(&4g4k1b6-mhwLSXlosgG=r z0C?sn{gCrQ_N z$FBpSPbGC7_D=@YK}G%SSDA6TJ{?mvpr2ofm<2XNVQc-Ae%aDpf*JzRXW|+tJ`6na z2J0Q@oJ0FeF6Ni!x%2wc$LAI3V8K2~YF*RDCv0Y+(-K*Ey5l;38>^YdjSaM9WZCrQ zNWJCnVQWul-U;*7=&ijU?$6Tkw_X`J143Bv&gov4()sn9HjvuEOsLnJ+%pO9c?GRz zz^w~Mht=L}@&oj4Uwy`1v(72pl@=c~?uQW({>kX}srFJW2Xq!c*f{xAIW`DR z3GUy&bW)t$8U6S4&B}Xw?G3$%?_ewdH6Lux)PsZT)yriMezJQoF7lo-C8$y#2-+ZC z_(E8GHDsK9`d-TFVtHhgWd{4eiv3zXv<5`wjg89vcqg1X=w>NR`}1*2-Gw@Yi~fL$ zxqQgEn_qda6Hi)l{1Elt&6}FXstCTedKoa0b8q!K&A+sI5c8|XhMT0yVCuQmkp0XU6c6@Ru%N1}2d z8JAhBOWe`i<@Tv%u5P-Np#qlOmY?Oc;b==j8kko4^#4eqg7_rhDq%o_{Ykg&{f}NR zA;qTpJt-`Y*T|D$XT5)NK2!pEx6!sg*PMq{ckalw%?K`;Yzp!`fx5b*?lo`o^`Ol2 z<&6s(%0`Geg0Ux%4z(}+^4&uJw8=h}JJGVD#|`TS30NHD1JqrNV{JUg#O>vOK%8nZjMuQ1J7G z*i3_1*@V!A^sCg{*rxZ<4<$>!<_a#7LiS z1px(eK3&cthGbeRzT8+~NWiHP>0p531N{a7oqM>EEZT$Hq5aUqc@tQn4ZI1feUAbU zF>BgdR4`usU{rNb9-lpM2MPtdQTqk|o?6D1C{&OYw5Brc(ZKaKpCqEqW!=ZaApB3S z-!W0Z@c?5UQUgZ4xXl=*eRiRNKVti&affK{XW(Zv@5|YVrgZ^E#)V!S(1?C5e8%PR zBBGz5zLo8{$2jq%P-i$!gv@ijo(t_y_@U2d9LjCHse98;GO`&CoJG()??1sZa zTe(ogtz!BTZVw+iVS6Yz_ujXGWJ|sW9$$Wf>V6dB?qd%o{WgDemaKdEWJ&;x;U}cY zt=;4bZMo7Z?~x>NFaV)Fcy`mYeOD~LBNN{tQ@q%G}IT4BIv1O>D)N|@pZt(F4{ofETZnHr|wT}T0X5ttYBp*?lX_y6PCA_O?gtQ7I z83u3UfiQs|t^PZB6t8u;AG4rP9r^~m4cA0Pqgg*pVQDna;h9} z^`$p*7<5v7$;+MvMYcba@yhgR=x~!?IGmBf=}A>X2!{B6F&C=$gK&wW@>fbDDeu5N z*9V4nLzUdsM$L(%!aY2O_sn~q`dcIQxmWGA?h$S_%X5F@)??vRei*zoU3&FF4Q#NO z+DjxZBX{g~ghuH2)P=Aid9p2uD5m1jwDpQpS6O3K>g?AJtvFcb>~--^mz!@bG4_Wwb9&$ z>G|~1MLZ<1=y(cep;7_~7FAz;S3F`ywwWc%_-f6S_p1Y3nv#cfu-bM=pBH6La-)Cw zw}rCb$NXr>7)CU|0*U;0zxH-a2Bc81h2-R3w&9O=W<2QU;nqCEKFf*x2O)9Sra4w; zZD-GF80)dh{Wl&T?{rb_63fHe_Jb$f4xyJr43gS)y%}il_iLs|^dtT#lzU%F>AW7l z(2V;kJrPHH1!ljf2?pi6GO2ty&a756m<%}Y0X{GL`wIg6!$2CKWX1b%@TtfmH@}My zUyzm7?rwFQN0r;I6}AU0t#;efG@OUEiIg@k|HZQXH(*D#(7Dska<u>qt^?vw5rfzCyv$M^Llst z$T2z|hJ7&sU&kcZ%7L}=>7L~U6BpZ~@s0&9y#4p!GdUYK1&4x%s7mfIvi{|$Q{+1^ zXBiYm7mN7f3q90(M*U7<9}7m(*RDlrr02U;gwXoOb}cj4Dy^E3eBE? zO6$SHrTpvqaS1p)N4>M|OC3&bKw4V*?Gu|e)Dq;b(1(IfmS46(CF|wO$?4d(UVAM@ zLfX5?0_D_vF2KvYco6;>8Pk)ig%qCzW! zJ|_ML7t9>$wKzh$8qn%t!4)ivG3&Fv455bS{ZpKYKYOgxxsPCl2kY>wQmAbAz*OHW zJ81L+*H+$Oi>Pz}x-f^UfB!V3AEgs_g$yfDUFU3SlyakoOQM^##=fuj9xp?G_n=4M zFRoo#F@?Jh^yKcR6Me7ukT~YU2^)rBtlVSYG^3(wvaCBp9eKs`kt<+r2->HYzN}Mo z8dTqd>w5PL=9aK#Ey7DsIcbj?Ae79_)pvPRrUqx=4tQR4JpQiTew3#)S+z&Rf>-|F zx;Msi2<(zQ-cQYzN?3-_Fh!*R5a8X5x-zl=hV&IbY8hJt_#^fR_#LGqMQ@j4H_?%Q zzm9*o_Lnc4??yi%2}oOSQx69vI=*|?(^Ie+t~pZ~^L*aRik~v0btFb5bl}XxL=`JV z_Rak3>X%1C@`^c&fCc=h{wxN-lE8WwWSuiy8k%Q5E2uq$J&$n?yYQzxgB3SCX&&-u zKx@Ngj+I?VnZEhERgOSe-=Q@mQ2h{*3fG3WE5x-(JbS^3^YQctSDnJ>9~d*kPI$(ZKrhdqVW3Wdjro zABHxic$p(8{)T5#nefb`oZJUCJ_AIi&af58feqhaRLJMwE?EjGJii`hx94g;J;08G z5q3U+urj_RjuTBiHnaJN?<729gNBMECsn%uh(Lzjr}I~TQ!)GHM*2ETQj;|j?fs<5 znSIHC)kc4$z{nK8SV;cm!E5WW1kwcWYN$B*Mm&4!@d1n&m~HUlY$e)#Iffep7o7L$ zlFHRPw((5}Cxd!)Q7Gsy?ustr)d}S%=>1C`Hoi6&#`*ClKf5ZnCq*Yu&%=I& zqUD6TlKSNb`FuBi$6ChxMNmxrw4Lg2N<6)b^7-wl@wZcfT#JS%f-evM^T2lP*TnqY z-imCxDVCxjj1o^BKFXfWf>_L-))AgjSOGC{HI+~6`q0;bXO60&h^wKYk16cw)g6ZS zLv5NHhu&+fMvYC@CjjFVmv*@55tS>a&oI+GvMT3-4jj)pJYCmfb?N3Yq(&nzTXhaE!j)gl2Du7t?Nb9%?G=;?LcAr$KiDQ_&gsx}ED z@@ix2s{yyL6uzyTLcor}}ybxBimo=Ww+C!GSA_2VaTm}X%IYN@{VEBUC9KNw&2 z{8h38&WNCadl-_JE#Sv)YQ6ILlgmM!ZRrfW+Vw$1`~Ih19>B|tKv@rVEvkC`wxxbC zp$C7tk0)sG>LziSEh@S086?<{3F`5D`o+$(ITtx^aw8hA)Q4!FGJ0k(hnpRs>N%K7 z#)txdT0zD=QqdTkNc4c;Fn!4#?P2ey2!Ag2vvzKT^;4v6t>V&Kn4hv3h*0v?zs}Zm zIys-T5boc^?Su^;=z;Pg*Fx&3Y{=8BMz!_iaG+*pL-4L#Z5Z9S91B0~kULn)2%Yf)P8u#@TpmUDO4tBz)i@Ry!zME-&M4Zvgg_FvWI#1(~na=x_ zYbThZ3%F{L+V24XGTl*kZNhx3f#QkQT!L>(`27taG|Ca(&j-!WCG)@k2; ziudS{xk7kYUWiAs0lugUz>k#_Te2IattDyxm}hn6Qt z_k!poe*)R90!Ca$CRd=*0Q=VK{u)_$C+kRvukzFqT9}I08-JIF7r2(wb~(50e&Dn5%0bDfqL(L3N3=k`E727-H3yp_)*n*{?GfUqhSe=S+==uV!5 z()U^C+`bjBlbPTL1Sl&2RLjBs^Z$gXvL~}pnM~_E933i*sM~#m417ka$Ln0#ykLpK zx7X~15N*5MFCw}9#_y9lg~o*&Be!=|%tUrns2nwyY=tgx+P<#n(&q6hZ7t3GBtdNF z{Hpw-=<`Xvmy6Gj13|U_40oaWQqswB`Y>}Wh9tCAa(YRI<1`;$h@Wxr+`r)1J6?tJ zwz8Um(5=1Z)0-2;j)xc!&sH zsQG;2PId4;!XYu{kSP;{QDDlwHd|-az71q4OT+&RPOl~0Nh^uV_?v|*L%!{)Fq=ee z(3t!8rV>}OtjPVQJNB@oUhW%=qr3opOJ@;S*lJA6ta`d1t&w3!)Eg+DQgWX$3^c+l z+e4(-qJ_s5NMG6)9A(gNlh5kDAg;KT8gQ>=OM_Z$j8e|*jmY3D{z~0h`-u7|joHV= z!>lqT(!)sKWd|nKN5#yg3qq~D=Zw#6g6g*eq4*N?&?5Xzaq%6_nT&1Li0SGf-m>Fy zy}W*Bq{!ef8|B?Qb}`q1yk*@B$lW4X$>!OIQ2eNUA=w`YUQ$m+6f{*{h$nS*9WBz? zU=pO`TBJWHbbcuZoeC-a+AS);eD%6RUnT@>a^AN0EFrgL=KGpNrX$R8JO%ZrQd~^W z_1bH{hDdldt^TrR@tt02z$*r~AN{v>ym&WV1nBO>f*SAvgIPO%t0aU=$}=|z>#7;v zFD17DCR9h*d5yH)SdsW#@OAuPFFQBnGRflA13@3sX!~-(2wDB8SlBYg9+zF78B*G} zS_dZ{mfclzz-1_t)IFT`gM1)w5?9q$n+z$@Gcmte;YNg;zv$1&gCvHnF|Ga2ygm`&r-M@^z9-Od7{# z!LL8)(56w`!7huEAZ>LS&7_8;H}pyIq?Kn^NW8G@-YC3j;+X;ERuVCm2RgGVnE8i5 zEjS5qK_n5xJ$=9PreP)pBl~-5{w;7>;ip1R`ma>mr+2rQf)(Gr0soz1m(Y|`F3-#u za7X>hs~?3w!;Xsqu%~^ZY0>^_;?fcyDTg#;cAFIG;A|R^<5lNN$e`+e-*onByn5;M z*v?wa*iRQjg4;@!7Zr%qMz15|yS*H7xJ&i@5&tC$(N7vqoW`gB zk;b?dp2c29(eSO#Anp~Dmmj+(vHWcP2V|eUM6XpyZC|1&>vMQwKt-!!N(Y44=%f4UQH2fpWCnW6e z0eQ^N_s7p+z`(&lk9(90vtR*whzkD{Q1AZUOW2JQWFmp?b(je(hJrD|tIXr?LB74d zzYd_V*L0{-!lL0`h5IQVL|ke69!U0Ht|9eMa2(-%jf>a>>jphCVc+!MGeCstTpug1 z?^(61&Jvu4CrxZP=h%}@detw`kLi<}2^)|S8S!w>heczVFuxtAJ?(r!N970;(BIj8 zC;)okuBA(gIKEwm86}_KWaec-)MW-L=Q&mbhvjqswFHU$QuqaxwXeY!{Mr`3u-o%F zLkB`W+%!jw@dh!+pX`$H3;sWz&TCs$EQq4N zBpDthgCa;!;0+|GfC7@gz89x^^cc5q-{Udj4z;Ul&9$Vu_kLj=QEwvm6DLL6;7fU?+{4f*3WV_2l_Zbl`p=o-aio-jw<_-lD)4BS|=_=|zJp+mJX4FPZ* z9FZcN=bnZ+igaM@k)&^yUk#|7kJw$s9DF3<+{j>EbLQIX@%ldRDGTwSldZ(U(uHPD zeSNE=Of-&&4sW>V(>C8PTA{BZ^g;(L5C4Z^aj3K`kg=d9;!^A#E zn-g)(uODfO+_#zEqx1CbqAhvR09!4k4&`Bgi>!-9LGkx-GRXp4>9u`skAb}5^WPy{ z2vX)9DXz62^T0v!^g!JJtpu&IJno7N7)0RFXzxO`9?jMA z5zQMaH3!CMo*RZY5E~AW8t+w`S5eK-@3Lr{ea?q zYLRb13#8%`sP@tzRR9HIT{s!`l?q1!(5|CrqE&~q*vdhFh`{o=FfZK4GVDi&oHzH; z5d2Je83+UNR$Rsn?QsawmI3W&Q$8ZNC^K&OeG_r^ z8gm(f^ufR1!f8VgDqecoKhMimy$X++rBwJJ;?`t8w_qtozV5_v8Nw1(xHR5FMs~vH z!(S~afxZ@V_+6EgDp=l7H;>U~7>a+~Syb1jYr2ugeSb&SyMGmghRD#ADz~Vr?=JNS zuiJe)eF~4mMymsQIOa@*I+bls^uCkK^MbI3UE{OxjfGz3>07KE+&esG_lE_)0GXAe zH?k!Tg6f_Lj>fd|?zJ{{e&_*$j)F%7|3K;`Xy5++Z$b%w8U*fRl@=?d^0?4^8P0sD>!4*A#RBB`lWXDOc`_ z$F|i1I6FR+I2A24SJUZ(&kx&JIIpeQ9RH1pf#TiL3Cb=#zt|!G`G`YxSN9PzwoV6@7(G!>!V* z=oR9WlJ89TYSNl%Ka2lPidhf3!=&D!=!eecoZ#>h}C} zmB^CREAdY(G(=i+y&LEX=Kr?OS0%tqQ)iF*)!cW^)iOx1p+Tztl85uL!U7)q|K$D^3Y z3&#)hqtFjKLQ`B&_IGer)-&xx1&xO6!+~fCfy|N#ts7m?Ba9Wj zmospIvGAycEPKXZwQ8FF_{FPwp8L}P(Opop@ytGqvtLpSafgd6Uhb<$#{9#gnCDB# zl$QvPbnap&%jdD*nZ4qv;E%^)P`-Q2*@tofTb{#ssAlRT-LCAQIM0O=mQJN-<9P#w z7&deU^?hn*-5^G9vGgzRj_Nz`h+t?6-loGljt);f?Xh$2q%0MjY5cvv^eI9{g^!=y z;KMX%v-##Ti+S?GCPf#So$s4VpFZ)J^VbN?e5ewXjo|)0k2(_>E&4NCmgZuRQ!!U;|~_N zllFbbyjUJp&>??Ou}|LmLK4Olf8HjlTF6o{})$C@+4b{F?~G3~2= zSW!Jt^jmoxLV9?P8kGr02u$z=h$~gJBWWz0K8!GUJRE1wG|KJ^w~FywyTaofzFjLs zp&oZmRsg%7#S6=1x~j04moFJCG@qrTkg?mc+6!YwB@Abu|28rhU6Yj((SN9GbA9iZ zQ5^ACO7i_F(qQ&eY};FgAM_9IkPAG{@i40Gt?`wD^?}sFU*y7c&UHU+xmTFh`4=-; zOWC~Yu*B`%M+&0jPt;M2Lx{XTxqn;+K!}ju!4J>N)6!lIx$lqn6|rc&lKyho(Dc&VdIc@~p`Bg`53A@SmDRf*c3SE2(=_niGy*-Lf zc{-`~zWbOPOEon^sK)vD6l=1=ZWnH^6zwW2dVDh@=7$$5XLeeMhtJhJuT2Gb>Z z@k94Y9@Vt5N7Zc%N5X>yh_oeDG+Im068Kh*xHBI^NaED%|Bsl7R`lv zAL_K)&;|7@s_2UT`AIfw?8*0v(k~oZYsm7iY<&1$&fYedmm{h}zpwBB{@*VK0i?qq zhJ_w29*)+v(`ZJnlbqciOb0U~^R74Zv%Le#S73Rhr*`V*W$ z{+b@%T`r(-DJ1VUrP7#MJE7)rNKl{UM|B&Kgn){PGClo$&hEZDX(I8gg9>Tk*TAWw z+Ry%{8-(7Ug!wlPpl_TG`7>uJ=sxeV&37{+*3WMU4BlpWbR;SD4f}eA0={H(EE8fvy)EY z=}qaQWd~NmKjEfhT_m1y`WK{=?jC7fcDii%8PQBfO`?#u_da~Sf-iohqs@M6vl;G! zwP*Ku{CM`P2UQI{LJJjl5r>!^L@Rk{G+!|gjT5NV*o6Exn2i$zN!S-YU+KkPMI`M+ zDC5SyJch_1l@K;->}~>Myp6~9q+kzsirTXrNggeO8nJe_rGo#}{RGPkS&i(~MEs;e zX&Zi9E5%38lhzXvW{ao&Q)Xee`ZC$3xPaZkK1)=!O#PQ#JBEK6?NdDK=KI2$Z+&if=xer`c82-!`u5!0rZOfGNGv$88RXKJUWEV3{y#^c>TP9c_~|_SjSh`s>sdM(ocib<4U8dtsaP@sB@QQ zVzQ@)r;(##9p%~tCo6<<9LCKCi$D_h>@ffnCs|OQ;~>GEgAR;mNPY{syu4)uwO3#A_~cTM=WF z`xUnjIs9^NXmg0@%LIMn?RQ@$hN^OddwmXPBLcZTzNxqhs#2o{cGj;6j_z^a@GqCz z#CeZXQluPU`6w#~SjIiFN7tTSAS%-R(;MX#E-3<1^X%f+;SQRJp>u-YWuX;M-HfkjBJsa8*jG>zNGB+ zbjj>GEg-~wYe8!_C`WuJxZCB@V4Uhl;yjj-UnH`=GD<(Z1vt3V7ovz-YH}~OM9btfouq0qty7G}UxZ_4oW=!|iD&m_6~R>Tr$03( zd8kR=_d5|nqN zFD|C?*{|!n+feNDXkH@Wvgf?I)03s)hnv0NHs|MYhE6l>d->e~!U%#R#+m3dum0+( z`M#u`6=Xz;(b|;?VoyGri!yO8mfy1*FcfnPsNpf@5bZLgBNj@vZ(PBU+t<@u;cB{#O8O!qFZ4^bp%Y*o^zJ}R&H}2-SeT_hgo+Os zt8)*`9v4~?sNFmOeSU|2@ek_I;gTKpwlJq$7>e4TdB6l{YPc-4KBb5A2H9L2~jkCKxTjF$ahO91rBN!l;@nCwX}P_9?G1==AJ}cmr!cWu1a~j z^YroYxl!4GzUx#^Fg;G(VG%Z&zdGmv2R!ep5ph+@S89>}3gSQXx&%af%=Dng~zlt zPv=(=m1*rL?`f_?*<%v1PpZw@e(~3SkiZFY_lApA$6NAW5l2 zw18lIyi}R8pM@E5?0uji^|?l;wN zLSH(4kpSR-XA~jw<7Vi9^>lT?PEAmHt-Vnil(aG z_Ub3iz$K?cL+E%!lRJDKY!Nn(?-Z6KzfxN7G`HO3uy9FW2R{Jci0=TvTW|( zFOo|-?#mz+6KrA^2#?~*3iA)dI3!rN%*!u}qdsgDj`aJBLUvHT1o7i%nj4tmo3DpB zgGw{A%(?ozYZNXy-MOfxar+nT9|0GLSe`5{Xc}SWl;yA0F9k0O{VUKGvN5sWt%7ld zKZ3YlMY?6aKTav8K}4ZR6NRLj-`=NFwO{^q+4eO%k;EeV_CfXsuJnYT1E!ZxmcpaF z(`+8#E=Yn~uzP;LW0?q|4%=ULyv!$@$N@g?1uJ;8R8%U<^R#E~!kf0@2zRle^ocmtVDB-%4fmDxgitEl@UKdq&;-gNL%W{Y@(G zs#reQUaRWq$WQ7aW~($tW0`yiY9E?vFfed7J1NttI>DUbUQK%-^1C?royG&(Or=`MdGZR?TR4h3w8U71FZ4O1Y_xuB6$5Eg5p;p+lD^?TJF!T(-?2)ZjwMn{+L zzN)nc&+1v|iL4*_0)TO^RLN6(50cUP7-seTP`YSDo3BA@PgU>_z0W-NJ^!{{Qm6{J zyI#Jw44nY3CRy_bNAEq3pZA00V$-~g5k2#md~IAt&EGecVsLfkWW;heaq8dPnr2D>3I)yBq95JGnB`E z`xm1s{;ep=&zyNm66NF~J>J^ka6AU?!FQvZCg18K@J#Qy^B3Ho_aw1OkONk4@9$td zWm6#7p<~N6SjI;IqwwLP!A1bixqI?0s4VnwvJH5g_*#!GI-+i-d?@^yxW{}qh~(41 zT@CFp*PIO@o{Lh;`WEl(zM@XlNIKi4JhHC&HD+Tb5{GFlrTvt*H22Urgl^{aEVJl` z>|Djtnd$jw3XgYpzW{EsG;88S-$8U1zIogV-Lvo2GG!Vt~qs8sVbEZygEp{Og zf7+?}8(m~?+QZQe+C_NavO(NlGf&i{2WEIp87mbe3d74DOe$&-UBuQuRw!p*34*HG zLzqG+3f*FA(P>E!fGjgoPB*iA0fXeO=+Pa8-4-@2hM>&d93WL zVeM4NoQi1?26Y5{HFO>GFzToT{vAN~8BolUL-RLS6x(Gg9FF_JP7lR0ygmxKMVS=$ z+0$!yY4tUZly$!5l3Q}zJz;g?j^8@csD_sBoADYSZYpDr5A5KWvD+)q5TYkKax%ys z5ansRam;cJrQK8n?p*tOlhiX!qb?F%r{^bLx%J6>^V<6?mMcUN^Oq*cP?&@}#;X!02NPbLUX1%<(Neka^G}bNqc5*q=H9>>XU{lYtt(%pWQr9{m#q zXLss;7slM0ue2|n$>_XK%u}mAp7yEM9?mnrYdlu3g4~MR$FKE;d9o=Qp`@y)5t|jo z!oJvP;h#Iq<}{svLRRm`lWS^Cpf#LdqM<8JSGbW4A51X<3+W!RhlfGW1U^ZRn1jmKV0nsXE&@P9WOh8!H9-?G3N3t{ksW~a*Mbn_A()gw+A z@VhACJLZaNW_rQP$k|dW$nwXh( zBx+}$H{s&^A+hul#R-364v(4}_6R(LFZi`zL?>scYwqyulI4F0gr;h)j0z^3&Qf1CQU z8-I#^$-5xFaT5{&!b4}e$fL4{>Te8uCRdNUm#O{9V_Z3SKf+6+Buno>$kF#Su8cb(5%h&1^ z{d1YG6@+Tu{IZ{5|2aLAo^(Vx;_oISalz7{bteOV*6nK`%SxgiNi?VdWW1+rJ7%t% zr+?T_A-}qZp$z^(Tnn*5(y4hg{f#-Q)fu@R14kV^pr{i?kM^%bTlHD)~C=?Me3C4&A_zLstOS;#P-x9=3&Y(cD)#XdmMJ>1mP^ zGp^dN9yWX$F+d%@vx*nH6%2esl^`u!K{PJ&K0|JvdH7pF{a&#!qQn=U`H{tse02(6 zn6;v?*UFUlN4_0o7#gZ0k#v{8wEOUKPtAbFioU(dT9P3Ig<8Ipu3r^N_sjW}`%in* zXTjx^Oxs9w{U+l=T$gmRPwCI(1aA1^B%bj6skIk1RkfJwx}F8Xh_tEmbc?J(z)b0ly*cIZsFC^Ih)YrkCy_8e-^=VIPjW7E^mDS6(N#chK^_R{>Th}5j zwEn9JbdLL#j*zsvzEEGG9k6|2vn&bd zHz)JHrNHBKY6(6hH}eIj44qm3d@3dD*8WIa|Gai_Z@=T*84iu86_DYRgX9F7#*SIw zpDzvCv8i@=E|0Hx3QCDF@3ni%_>Lp-QMbE!etx+)8@G#6eZTr8o%X7tVV=?GCTz~Z znGetN$BOM#L4P$qLZP6iG;+T5b9gbmZ<}(X|BMego#eEmf#ogM_axA%|ImhqGok>o zmc5kn0Gz~d^`0of@9G%luy`3ZhZlM$l*@*K0GUV+Xays5u&68g2z*E#^5-keDYrpy zoV>sIS1LjSh8qV9nV=0fIO*YaXo9<1SM22E7yEvlUT%NEBm};y&7S!7RsTQ{;d@^v zE}xN=GS2;&AxjNg`p`WB zhxr{2W6|gIN8o@v?F^rIoW0C1-?dF`)6v_~U;2hkQl_7SqY;^qT$?ZG$tSxDG6|+? zWu(rvZWeFReWu4V3iksLD-ApBmN%kHuMYzn0K5tOgg?G{-XhnMlnzE7zde*{C>ect zRCs=+IH(N=|AV%`(GUi|gSVX0g@&I0I8wS`aE8(}!>Hyr1-jdO>?^vnf4uN3HTqrd zv(yPZc{0T@a%i;OHCWxyp%PN%eI#}2ht>v-_(~DaaGp;7|CY+O_9lbi3)^B861ou_ ziHQd_y|4QQkjOt3#|wv3j!&?9DoZ9c@z&keeQ4qL{l1bj(O$_%t6onNoK@bVj?5I> z8+ET<9fpRqmVQd+1gh9x;eyG78@^nvT46>LY7#YG;OO{y48Gu3VDl|zr(T?PfeALv z^?`FZxvYnVU=RaQ%`nrb#ECa?O5@lQc=7dBAb`$UQ`_JInSOMJ@T9YdPFRk&m~-TJ z+9hhbP9dl^)c4Sis_|Dl^`))x+X+Er=`wOzGx1@cmR7MeoXRLFr=ORfH_@lJshB_V z+ag3T$?nvbms$t8x;38y?22!b`B~r2MsV2HhKIxMaRJgT9u)-I@Cb zxCZ+NcjqJvmml%Tt)VLrLCM>g1q1NrCp1Bb#1 zcGd#ErQi%;e-}A8$R44VMTV}kBb=~|Lew(|^7QD!YcQOXvtuev0L-6XpRj(F2K6@( zL03X&Q+r0Iecfz8*jG#zW#Hm^PdSkY2|gWhPR8rVa*+!@p}QOzjq7|_@{ck9m(o!E z@l=y$5}mg#+Y8DM&e=TQjsHJA(ZG7ZZ=6@l(}ih=zM z#zrN|ozjr~=2Z_i1*1ue&?r^d*TcNws;RFeVvi=^rxFwgPKK>4Vt~^@GHTcSgSX-a zsA7nr_H?e_Gu^VUObIwpyqTX7EU;1ibi32GHBMlhKV0x_=zE6;_ev<7Hv!e==)zp& z6Qc7go^OQ%+vu2tr0cZ90KR;w0~E2@*ZMpt6?2l*N^sk@YWt8N_B?6d*_oK2dS_?eT$Xj5pK}v zANAz&^%H-`pEl$Bv-C5u%vSe`U$csimo1Wxk7rKG{2F|e@5S0Dr!}51z%!oiUiAYW z=`k19^m`i!Z+eugsk^D#zKy5tW3h{}92y#IZFcwMLjl=SNe?|!ocH6%{+(S$olDte ziypmsqc|Ic!;FHfuUyJ6)$v!!gCEutUAU{>O% z76`6cU%d&2+F&BR3#e;P!IeRmf#DxPuo*S36l>{=RVhlG(ttIFXL zX?^lI7)$7m^67|tuXsuuM7150ZH0RDLxNR=@oYJNOUV0rB5%KW`3n1GWtO}biPkrn zE{_ZZ=IY@vX&?6XV~C4rL2Z)O$lgNK`i4&kkh;(3TSJ@UFeNZzWDbcRt3`W24d3JuAehcD$|@YHxeMR)xH_8U2`QAK-|Lg(@-57*i~+>xe;!m8sL_ySOC z3N3x43v1@Z`x4b}N$hwF_#`gAgxmy{G$3U(`ZKhW98iGjEJIYI1g8QdZ?^Kt%7S z;Zw?7{s>(AQM?b-L~PfM?#_0R9C>cb=;i=Nu+Li30JLQ+8j-kJ|CzF*o2o_ZKQk5eNZ0!}zsx}-x#?HCfNmDd<};l5@6>~{vjqpADH-atD3~#Kc`5cK zYrSz8{NnRgQXC9-yh?3J_jj@7Z>kZy=d`Mh_JF|wb5>biNga+LgsEL;@;N`mxoMC- zFT`wi$;F3LaQNEa75#O9C(xN^OXF&&-#g}Xo`^#0EZGmgw*#p<9rt_sLXfRbGVFjR zE~Z0beL=JbG#a~QfM0{85IwmM^VVFZr|e9qfS|u;1|bolN$iJG40VO2$uya3;Wz`T zeeD=TqFmT?KDRQL4aDate2*K>3ricu}Ao7=f29a|A;tIG&(wFuF zH!to8{rka!y^{YFh7sr9bP;P|A6axk-%gfmYxTuGHS>`sPmC+w0QoYK)y;_Ya#Q`? zXiin__-tE}{grcWdu=%Bv?~M`6hl?RCLfo%~46^ZVWi^0&U? zlROjrJAu#;wk-8CfzgD9gL`^c?~B>^WW0y}-I&@i*gQ|3u{xpjxC}g9e&xp;Jo3x8 z-Cw0CeQW0T#Sf76Rj^)F!<5;HrMRW@I$@F7H$TM_k@)reCa?sGKCLaRsQu6__V!NEpk$s$TbXuKg=cRVvd-CUg)DTEo5+ zj1EQu$u5fJXB_C9n&tZU^|P>W>Nvtmip%KIKF&qH(V7-(m%DZ>S?G4K6{b{NaDt)jWj6IUZ0Z4{~D*l#zcQyuwTXa zhkn_7-(&&l!O!@|@3(D+L$nfLOHmt5$Vg&#XV%p=F7+{6g|f!Vq+*jOmmD(P&n&ka z{Sh%@MeHQvp3V7L#qH8PzBY9I^C^2D&nG&W6J>fm&_iW}Y!Phx2p6xtznMvH@O|y! z3;D9%_Cn(x_jb1p!ZkeI`>mfwX2p@II*BoZpjT9Q?Am~ML}_cbNBP#?@MC5s@O?G& zIA}hHAAsNcYGRXDg5yOh0CL+=9N{|mO`WSfOY}#U+uA6;jNeY5Zy8*3_E$q-i25S_ zv5%o3jO?@z9;4cSnloFWQu8FB#|&(vjuwi!ZI`Y!?cyLJk!U1jJw$0za(FZjIe7fU zh|hwQDE9>+Q{yp#RUZOxorJm!!BR31it(MJB`$G9*e{4^NR6MjYjSpLl2w#_{nvG7 zA587+h$!pYSDor4C1iWzZ;*>e;%ZGI5XIj0JPfX?{lsT%Q6?0{Md-P+gRo7V=;U?7 z2YJ`ZY+kE&6$L}OGGFU`jIgHR9+$5yehZGd{G9Zq1Rf5GA#N^0!q(p5H{0X`n%E~2 z@Y04qe(%FG_vPPVKv6b*M9&s6w|X{fpqos%b=N+tmez4Z^tfMA`y;=+)2A_4Gvy)I zR( zRNj>twjtk~8^0L6vEgwDGqgwy^f|#H0*`q=JkFR_y*L7+75L-dX~Nb(=_U6;;&SGF zY%falOHMxyREy=}pqrve*UmF(*BY-P)W`idcbnPW2kC<`bm{O>Uq9pFr3BqGk$!o< zrG$M1pSQ7ZA|Tcy4v|_F0GfOB+Q(6HIImnsPuUn!uh@pZM)k_`&A&dLKg&KFz=>`# z<2YXGh{M-$aiDK5kbOG{%!j2#^`?4mw}F4*CHXZ%=Y+H-Qm}cSS+d)2 zeYCbnV&I*k-Ekp*>S`FEqY%x{`@q%Ec)u@j%a~63kK&)L%1^bu@3JGdfofaF%z?Sc z%Pd9C=}r)~o`>c%vY+GG&2AvF;GCk;*Azfh@fG#topWO`rNQrc~Nxt%@I#l=l9TDK4XK0^mGg8?;5eRs>Bi2 z8o(u=L}r4V!z_oZ5a`+2L9yTu=c_oE;*iN8+DJ%O9k-`ZjCst$EDsPEyr^uuK>ghS z8K6Suv(^f#?L1ajH82EYKb0P}=tRoJJ>*6-7V34GJyQ;GF_MlJWLk!#j>RWsFN(wM z3#$MXP0dap*OrHjGK4+ZvxVUWqRBriJtu{)rhRG5^A{zVQ(?I03yRK;`^fo+RKDYV zMH5FPYi2OTya_Z(O1f?WM|szPK0z>tmu_@5B5_A`#GTn|@C;((SHVoBK%k07j)# zALgTCQx)eW7@>o*M2@W<`wf(Sg~{V`Z})wx_{Fz;(&g}89DfnB4=C2S4c>B93X}b7 z%}}(r1d7MJ5uA@^GB4au;nILLStJC0pB@!4Xz;&dJCa|I43-x4p1{%Z+JZ$hmnU6Y z(8c7#)t%hG>&z71i)!stRSDD}iPZga8Z9hiK^hR4s*%lg8oT&|g4mp5B^0LsdVQE{ z4OM<{FKjREkt!p_Xed%2wX%o)@vjZ#=!VoDet>HRn0}hf24SFAO;Ee*rmmeoxFQY) zblndd7B3?jj!os3TJMTk_Z2z!k_R>yTiV>`=oz>S_RQ}Y9H`HNq);Mse3ibv2y;j#c;@`wbkw+XsTj*|lm_{^Dx%b^!mY$P#V|HW_nMOyx3 zh$rjnqI&(6l>Bt|oLBN}DqVcBfqo28H2%G!l|5ZEt~F{#r{Vim!2I$7%t66B;f;dL zUAcYlW$mI%TeFqRQN`QQ_5GVn4jg*f;M&Db`B5U|A~!7Gu;A}Aba&u(y7xSVr|b2( zr|Bp~F7R3NjR3m633~t9Al2-tM)H-OIzR>Z!qjxL{NoF14excZvA2l_1ePit5gXEM z`%A98*;OFIHOtcgz+l8`F>c>J4ejl-aHear(e^Pu6AdC3OvQ8QPiL%2J?p}pjv*OIBj2a#?NIJM?DpJI(O#K{RPURoL9U4f z2Ob*-DrQ(^rM;a@3h5XT+}bZ3j1Nn|p5o*6dYH}xx8fJqmd69%2RL!C&}YL*4K!JG zvG05fhG-?8I4BuOfe-mF9gjH$p3S4LXNEyK-zL1raoQ&*+W?EpEZu|mAG=&M&nG7Q zE)Xf+jbE^})|<*?i97sQ^wsish4tEs0^do=-!U2&0xjzwsVo z(_?XOtwLOT?%QKXk+FX}Pwy_Ek85z-hf&MLZpgIIm%f$Rb7Sq~e!-Gx=~HS)X^69} zmm-2ddBZ>>8y>)17kOk6KKD}_#Mx~WKWJOJ{${c!2u&iJt5sK=H2x49isvWuqfDUh zs?pePcEc~nDm=c|==r(M@~+ep72|Vn(Q2ZHeiX=u+vuC0%0k2Ld^(;tw*8*{<0Buh zPqfao>Rs-wu8X;Zd;Nv+2IZnrr`&U9LuM*10oDHJ`CBC64>PTSAlp0cFcH()5Fq#psk#+OpdEv z87?E;smynN>^|Je=*yuS$NpN{*&uw7#myL(f4-OJ&c{-x%1=&X*5Gw~US^Mt1-;yy zdTDOR!k6|F&u}NP&cmTzTMnGsl;wU~C4PmRvPpvsxFz_Zr9VR8iPS~OetQ7f4=t>W zPCd~OPyWC=m(v5)h_EtGf~ZRU8AvmVONe=}^7y3(8H(Yz^wVUC7z(e@1-+~8+Tnx7 z_5CcmV%LMC_8rT;YW72S5hr22*bl;mM^#8g_^tk*K`-@ppZ1A#(d|BhHaI_-v%2~H z_t^?xDl6QUJXB-7&kOuv$;98+8MB8$xgqBzQH?M!u!{g{HSYETkk7gVGs-pc6MXe- z_MgMFZK`=WA=^jJMwaFBtDvuEJ>&7_EO_8=Vd8t7vxCrrSHEoXy3^| zmpjiBRa1AB*3-tq*!2wc)ut9P)5P)CENB#Ye}w*QW!B}VIBg``S@i_;i7L5fUla?; zF|SOYU;c=1`^CTRdz>1)Y1+=0D)*AH$dzE<_xfNLT%x@Q*l=|Vg?Z_wWZ!JlW2?BK z2X{tN&WrPlGOoyZk=!+D9~!`dmNB(0Ol#lVS~^ff>1)-#+!X`6JHOwj$G)dGtF@Bc z9wpAe6$tyB!mWZj!iPpwE(zN0i{La@N2WM@-A7TJ!4(<(J2d+zN=r7gYm`ItK)Q44 z>4Pg|9UAHPXbVWGjur0KE3HiUDT{iZpP}SEQC9l6?ulaS9=3P$^&=M{OpNO@Fm9QC z+?QYYK4r^rir)%Ii-B=y4&Z+hK#{prLE7S9xtA5cHt%&#(j!+jjXDl!@PO9@bK&`g#yOwnsE-!s$GJ}-z3LUC-b`3JF+3Q^A?B0YW?g|p&|-vo>e z+&rGnj8!KEEXtLuW67UpQ9YWL2;=xD(|l^9=wN=oUU#=pY%*jL)s$>CCa`^muOz>R zil%)A@)ofQE?Lu^$(zmZ&T#5IJiaQGtNX=Owz_s-6o_A&q;d|=xhjK1kONoSlS-iD#x7_<28mz}jAO zJ}PXA_FEtpXs;svA>F}v_(2_9psYaUIPpZP>g->_+yi{upT7d}dB8Klg!F<$Xquv2 z@DNk#Nha?0m7u8G7X6sG>8r_K1YD05@A|okL3nVAvAn`P5co%jDp2^$j>3FQ#PK>( zt)}D}%Wn)}@orIbO{@yDUmvP&#SD6sv_`gx6`aIZ;ozJs9LDn+t@kAnQq6(3Eg2OV z%c&~3$|ne#uFM$M0{Pg7)Typ8^o7~>$y}Hs^7;(XH%uPC7>Kw^IKj!^@5DM;pC%un zIcPlpdP~z^6^Exm=?3Hj&uqGI#O#yik^DY3yjPu#n8Qf=rB_T5bnc-kuZDVn)|H{e z!B9LG&|MjDxox*YbOU)fpraX1V~dT`x+te7|5a-sjc#WE$6O}_aw>W=>v3h+IPrKa|vM$0J3fVmu=0=J7g_*U-%OcfY`H69R9#~b>vS=9U6tNKBpa| z^GRaM_>=4oUtR1zL}4yST6R4ZT%;$uh3-qx$RBX}n8mYIXVQOxdMhRZB>tS9ey}|~ z`%owiIQ5{<%mfVMFny#new5E*AGqp4QgC2WUA@5(ZC{2uTe`c!1bn35nbfB0;w14t zL&GunWJ6DZyI2UsL>o2jm!p6S-5TLY0+o!P!`)M)=)Mt@E1r+V@aC zc<;%o;aHB~7`?OI#Av?)L(VRB!d_kbI4QQd&5<#DTrD_Alnl1zc-7UHCjl#a_Y6k1Z8T{-Mpj7Ia@3IRF(UX@@iu7#YKap*D;uVZS zy#1ab5?;PBT&V-KJ3(u8-{X_`d}uE|ThVFy|e;gvM!L5N9Fzodk}mX8($QbI$I!Zb5O6-E`xvUsq<=fJZ3F^%pKkE z83?j)ZohnP^hAQ)C`f9)7_H8v44=kaBgP>^U_ezB)8Vla{lGDmEAm`KOYf8no?GeY zP+*>M{kBRNt#U8xG&NigHx|cIug-;iNemF#z6}M~t+{~Na1*ez+valXl|9oZ9&RB= z9@9pLAL2WoF9zNT~2%^TgvB#sk48#6l2q~J?X4i+~`^!qAFEO;w@Lhl$ zjNeer#!J8VAZKU;bg(M?XSw}u=PUaDXO>f<=Tn$KguGF>*omrZ9XFjJ{+=P1|LzgR zXL8=p&v5cG%Y$rQ8Ph*Hr}E~B`t<4C*O$`@jULyiTz-97s;oX;uiWz8c~oNZ{>l~g ztq&k3z7Ty^tbLXDDf1vYP)W7?e7+EXyKRt_Xh9Z#m|nP^+3wP$RNjyo&<(;%2Vjwx z17ymu1d8#AdvkBZ@AF>s-T%AZj&Sm*=W#})VVR=UH!`XuSpqV{rXxZu z+dI29Dzhit`m5wJlyLs3ePF$d)wzeona3g1Gn+;xZz58p=6-xwBc&*h`x5ef3qOoP z(Q#g>@Mu2#G_^HSguT_v+-uXg{-Ivs-gRJG5dR)f!+wx773ws*+V+jX@^Wn=?rBn5X?>Z^L_thNsQ`Ywd_w}W5gc*qX zsiAKLF-%yr>^F5ig;%L}$OH}_;f48!q;u_74T{3>UvkOqBZ-n*Lik1@_e+R={dw&( z#u@vx+mXatbItkA=l!@rC@JBsqio-6s2}n}c!T+F|6#1|k&mIsjVN(BQ;=+s5yiD> z{bgssVlGz{wNrL9|Ng`U6e7rDTZo%vuqmNH6H1$}yG0Lw?RglzKp z?3yrix?jaNO;7702bB66a6@I4DWm~wlVeEBLdzhjAHIkZHF|-7Tl7BU+`}PnFK`RU zTQ<1ufe^&mHf(EPifdN8cR0_>#Ey0`Wsn)ry|{Se_tLbY6as$WmRVM0UF=WT4YOl zJt*mWLvevjgV+8I@km$0ABGbgTtV4ft?Y$dq=SDxLK8>m6XNh3r3kzY{^c^Zu;%?Y zP^p;Lh(4Cw_2e3Z=!IVd|x*~EK(zl;djJ$2XRLbPT+QeJFT!LS33)H8$!;+S?)mVHvi9NFCLo5uV4*{7DcDCeAqc7w|N0(ZCtA=6@AkeWHqUvkb6S;;;& zZ?gbeB5l8i+Hjox8lbj2p(SQP>gVg>joVsG9QZrP9Fa?0(<<6T)`DVHz`XqNpddA0++#82>kV&Z%~84!56`AlAJ zsU_@zt#(4y0E%+qi&#>@0R#!3O3$)tgj;O%hqixJQ)odr&7{?-@TS4g$~VW(}5kYox*i=tS8!S%7%T|faaW0Hdo~i3m3pQ zMq@EP%fP;C^pPZW+GWwHXJcjm29^;JaNybiRZl9iow{du!?r(f_S zUM&)*{4ntyIl1m|(;t>Oy{7kZy;n@rQPDI%)IFMiC&u(Q+eL@-n8RB8W>5j9?Y<-e zRAXkcgU0!+&p_?Xt-l_;kolY%`0n_YbH!~X{g&5}Zwx|`X#wpWI?rCaBm4$dL!ily zVnNO?omHqF-)rvn-FLY5&wh)ZR;@xTQAQAQU@!YLp)l7bFTBAE_#XN6YJ%clH@8BI zz9#dl@12-+`aqyb;(O+zq%Q@25Ap7F(R9%sj)#*{ggy9`Kmb~S@hPv?z0b$P!i90yLzoE zAo7P6dk=9oXmQl%)){I03gmCe{q?=Ci2#jmchRC)QSU9ats{F8C}wQ`Oq|)_zD=vu zHa;hvjTg%u`7`gQXza#2_s#44DVYy6effUFo9y5pZ+bAoh>iGN;t@hm~u$_qzwOBeMZo>_Hl zA1>RIZ*BRDpmKFnl)(8=07*-`2{v{hl+@{M@8U+qTZ+c#zZeS@fsG<@obOUOlY{;n zaNZR0&j)cAZye^rKN4oBCnbf%P7`y;~FYRetTe6KaJ55Ki^j;`T4mCGq-{bmGh zjC+0##zF>CEB+SYZn?R?iPDevBKfpy$@!^@{X_RKE*eB+JpJ(POV^4v!ZR-~#n-f4 z?)bLkyZhuj-~N5~1hz6@edUn*TrHe}<%ui@0kc#i29#_+L$={dH&Z9Tq;l2cF; zop{VG}c^x{Vq~Rj*9GZO5EZ`E)u$_C>wPp~WQ^P<>q4(E4yPn2jyC+9k}Vyk z+n$EQzZ@d+x>uWOT)5(^&I5s!{bO9TA$7Mu)(>k-9#^n@4=WLDu(z@)x33Cf34X(5 zZfz%xrL-!}7Ce#c(FxCZcJu09Myt&}H?+fpys_60{j)i1yC5Mel~@%4e|Vc-r{w}T z1v`FVBK{O8YTLzG^%rZ!#0TMC4>n~$ z)_;!YZ@wO`R~%yot!tR(ovEUC>dM8K2EThG^8z~O&&CMmpICkqE*ipP6yk!S<=y?_ zdiv|Iy5CNHW(HSZ-R0bv%DKqL9*hhJFKEpvQ2{-#PYAs-z<;~=A?_zf8T4Fx?HSnE z5PYxKt^I31+^!5jMAyPOP(Cl5M9oBVW02!aOF4>$*i zTh<%^0y~r%gLNmjB>WzY#`o1s!^m;oK#*vHghG~|)p?w!Sts3f351M4^YhTfkHv8+*{EnliPv~#ab6V7|&a(l`C1*A#a*vB2RQfU`iWN9%D zNv`1pD)s!N>Zf74i~S>{N$kozT~Ah{4*t2*S3kI&;FGGxPbO>NiJXzS5VOZK_Mwy_ zSDl5}4SZzO7c2yl0yzQ4_TKa$VApVoxEc6g7ecQkUvQX3R|am$qebE_o0{_YSqg9! z^l`a_;!}F81FYW$cnmr8dcpTs>~u!SltZiK&K0LtXp5Aw_#l3kojTbNGDVTGs_L=s z9on}GY>S$O{#3(rd-C{hB~J&yX5(Xk-Bg1$tKyRD`z|w8gztc`x7|tEbM4-bd>raM zgh5M+<~o{X_?z+RM@f0WyjsH)4MrXQoCD+D>qDFdC*5#;e;;<09!(XrJCS%CJ{}`f zN`ZSvyQV#M#7xc-St&Lfo%Z3rLn(!y$-}p2rS>Z*x0U16kR?zPVo|hhtvaX@=HXxR`3T-iw|i2#Qo>) zUN!qDg`eM3LLJEyUrI!})M$tMrg(N7Nlx02lKR6M;H6k%8$|IQ$^KdWK4N_$pVk~) z{_L~gHJRwmzP!MfG%qoj7q&0R>LoFGm+ za3pnx2|EFuwf#F`(v?CgX)f78g|>1X{W60wRdye=IjogrXy4gsO<#A-Vybm~gt@q1 z4`28yI$SK4?QM%Ri6|_=yf^1t7$x#F-XQmS*Y~U1mKEq~Np)Uv+)#dy=Dy)Gx<$;;dB(DG35;SyCW@d}6LEed?mFC-=`HOi-3D1fEg==34)CMZ zE-8CGbp$u{VS8Y1eJK;f_n6=G>-R;X8<4@~!Lp&`f6Q%Al`}SkNr^LdZ8iQ)5=C<1 z@;iHU08e60_ZcGWB!?qAV?&xYSa|x!lVh{X4{T{^~y!EP`v(JLi*c4S^r5kk;__!D`U=RcMGwlmzbv z7lnmym&+efz*M~fK(ZHkI$XMA8^N7>pI(JruTh)-NSmHZ-9?%~03zA))gpChD(mkD z2G2;yK}+HL@Vvdd5>PS+4?mA3Xy`Nf29L%0XEDXRYXFIvunTuCsA9QEJ6%xTKi z`IIwD<-@Fxk%p$J8NB>mi#5A3N#FJWZaCgCPUUngJTHOER-CkUdEVa-H(zNgx< zCs*0CmdD+PX~V&=!Q*KqO3N&==j-A`lMmP#RGW9IKUZJ=c4R?J0q2ZL@zfqLrmni5 z3I84Mseoc49iys2DZ!wqiT;vSOQL>78=9qc+*N$|ulQGdafH9i%f?J-;;`7^`-&{jmjH_Ha2-G&GF7c))39i#6$TigT{Ggk$XKvFTTZBJtw?`|S(eR-R z_nIGpDY>HJ`1_lXtWDH(<7TqtD-zTf==gzgz$&~IEfBUeyX$Y>40VWQ zkUrgRrc|WHVLthth?39gRlE)?4f|!TK6fm%=jb2VzONg}_x)p{x=-``2{Bv|jLvu| zdtpKNxwLbc%HE`^SKL^%d_E3(^)%OLpM0Wg%?LN;IIO21<;U~I+QU1r4{d(+?kvgq zkFPu(cR|BM)B(BhgiwV6RO&M=Tq}Dsokcq~y^(c&==U`?7VO!~e?$cz-pXe3{(a=k z8Z;2A%tgy(k(v*nxl-)%TR{o-k#NaMMBs{fw8umj-+V4J9E<;qbPIuZEBDOTuaIcM zm+CGqF?(4cbJz6EgvSlik#7a3OdDdGVJgRPLMqv@OSEphIPf-u;rBd>YJlz^qyDT% z+ZNY7m18_l2f0tPgnzw9-q0KW?8lNM^?+2K=O%#Wxp?)$>#lIz(a@QiPf1maE|{?{ z%x$==d%F}Y|Q$xuYIGdIRtZa zuPHmL4mPKzr?YlWhwlN0BJ~sUy2MpX2Y6U7)TV1sGdn#*RjsAj#Tr3*Wa-sx(HhKp zj~e>tWBaaalg`@fnEo#BD^(c3TvbLjl#S`TN7|FFf@(of=pSMr*Yf;hLXAm9CTb>7 z>vO+TRd*la0ZJRb@a^pmcL!n?-w^IZHa+BbfIba5=y38`W4`o_r5(-pc#vHTsM7~} zjG^}h1Hk9XBsE2&;FrOojed=j7+GrOH+;~|RoAVD6QIOzSTBjrjZZpAR1D`xRC}ye zjB6NpP4T#dQOA+Ly1K23b2HKQM;uz6r}Fl*`4QVM4(zjK zW>KSLpJbEX`4e>!r2$LK*5ta639vJ~nw{225MoNB+g9+N`P^rhnFuBL6fUL*D&e-T z?Sj^DI*j|eQ;=VT-LNlMC>Z9AJ${J~?(gfce;2oF!!%z@fJ>VxoW)5I_I%-$>#d20 zm-29{;M#pTJu`Tc4=_;4KM{wFinPx3F`4$mq+XAuzwP0(e>*n&<#LbtVZJMa6#Oe}rs2eus_ayrMeocq%}{CwBAt-`1UBoHlh& zd@@KRrm{Z7`6v1K9e<+U8M-EJussy?3sMXUrLi#6#)CpcE*$S|`De|2anCdV)1))= z`yk*Sd@ZW{=>P?KU(Fzk2!i;m3m~(!voA~btqx7mK;!!!igu*YtVv<^xzN43J7n7T zRH(aHzda{y`MIirpJ7JOI%iq(7(ZWIZ7=O;sX80rt?Qk*V{_bCTlBNA<&g-;-~ zs%ZJ8s@l-VqKWVkXCn1LLS;Naik;TuduAbBN6$P>-Oqyl_4#vTxL^2zVG*lLewT>9 znEd#-Y$f_sQ`f&#_j>_(B7>VcUK2sNyT6u?PeY@nSl2(`9=uQS_9?2-rim@TAyJcE zAtQ4jeY|NBgN#4dRTvKT@1yIu_N0cdMjd_d`^-yPDcpUXdl|_0`a+)3 z<2d&LI}QtYu$z2&>%yq%CZirbE(JRpTX$TKYaY=mLq}n>C-Yy|#KSX17w%r*$|sxt zz{JJ#I$52Eao1c=4)ht!H)yKcv>DQ&$w_H4C;cfN4tD2(>RfM)kLGl7kN&rqGg}V@ zoB&S21)h=i6$Y$Iw-g>AcZZ!0L2rXrDGx6Rb+b$UaMNoKr`z22zpNV9A`ewn>&)1+ zozpqFy@(r2M?w1>+EI+Y*JRhYOOFSPXWpMi>ENSFsy`6@xI+ju=z#EHHw8wCzLXeZ zNU?lB{(c`NIT??(o12?czU#R=Sz`RK5BZh*BDmR))FQKWIm&TXXY;tHERM%>lP3t= zFJBhgDffJz#uqvRAdT1Hw)m2+HUlCh^Efg`nIGib8{b6pd*z4mdRftt=D)c|bZ5%% zHNeS$iE;W4R=!HiW4`sLc!e;@RB=tS;EsaE2HvqwleH#VLQ>0L8lpv)-v<-yrTk9L ztOw3096s@h<)f#HbgT*U6c|J7U*#P!SNw^eGtWOm1k&hVhMcC0)Z-at+nr%9?H46= zNg)h^J@Q2gZ{-CS)nB(@e4IfPGUt{Jh|^nkbpJ#6mi#z5n@rQz`0fM=!8+`D-!l+F zw@0k&f>#l60)v_RItt^VI6R;4^Xc|J0siti-?la$ABSTL=@eV(c3eKtH@Ca?m3V7@K zcm?6WAKQIuw*Mqju}{nTqK(VvPf+NDu{KKe<4}?{P#9jq3LkkjhR)h z{F&}nx}Qgp7SNrK$XmYHE1I77JQ`0Hy1P(V2q_C6-93w(7l!rG>Ju1-GxwLb8cQFT zbM{h|si?bu)Ofu2e?G~|n4RA*`VGIMG&E3^o8`ksfk=L@s^iT~jWv;tQ^$9gP&o*H zmg&F!L|m^n@jDIHV;<4tev970^M6?r<0htKCAm?^)Vc;;)S4fZmsHtavO_9Z5b?bkStU_*rU|!kpcdveevR+3tiqaW@Kx5oF#*KZYsedkv!|l#>ui=G5b*mxg)=fzc;GE$eLp#aX#?_e zK;Qh|iUu+AHys^Ac(LNGbH^8$saoTDj3A!(!Io1Wc0xX9<_7Re?6m_G4G1$0V z@0-K>H~!h&O4@)oF`7qt&g)Beg2VIm-uJgX7O+Opjg<6+LqlfrPhzw@nh+fZ-)}MB zo@8SAZOPvwVuVHCbYH&f+YCf{Q)<3Jk&WJP{m$&klpjCl7e{77;7m)bxHd8;@yi3S}F)Ce8mUl?bb zEOZ5W$HTove0ugwn@nVqd;wU zokBl!!;4&~Am6f846L<-4vIZeSoW=MRPduZvN|G9_!FLJa=HA5{qAZR$~u3b{F<(> z&CQDqvQn-+AIqbi?I$osq3D$%`NMxwNys3k&;x;L^qZ9E@8~^xNM#zB`AXtL{Tfjs zpTGPMwozYhQE(!!xgt1GTY)#jHo1d{y2%LC<>0-G*d|b;|0pkJ>yXsPXwTp0| zN1D`#%OYAqy`qC`oBM*Xg=hEZpv}J!0BFH$dl5*Z3m=!Ky%Ufim;XbkV|C}w?O)^_ zA`4Ezg}%HCn-XVa89CRH2N&ff0iJmfa`usB?~LxQhu0VJn)EU%(J{>lO}9^t0p6T? zQlcJJR@;-=aA_w0#@0gdc+I1$ZKmGN-g{K?m^6MoF%e8P#h9X%v_4k*7al$&m=xV% zm~^{O)pvsX@xABn#$#VjG$=)?+`P=;)7GaS$l>pT{J3Ipsc9JL>?jarcsS*n)vJuh z$MtlG@>EZ#sq8L)7;i|fjxdKd;_}qLZ*U+b&=po|9C0St0l)qEv?MO`ra3w3>Ki1<$tig)0SU`cNCc}7W1Hl~POMD(LwvFGx zJr@G?CeEmNnp5+akiE;FgNl|v6Z)q{=k~kb$Z7le0W)k1e}EF-^@A>?&Hb)4*TsM0 z2Q@@jI$KBvemj}!42P;K+oZ5edp~H83 z9#)N~RwtqNQXHu2=}m5GwgIfcohlpE*Eb6v*XnzE9iUmEn*(siBj|>&aAI>|zn@>e zS*9F2xnu?lb)X(jn0Tb5%ECn5h!6icu@9$-(WpjG@9fRU9lCgLf4D9fCvkeqTQ0qR zR1z4vkJfpQ;2eBoseisjDxU=5N}xeJM#w6Y6(JHoG~w(y%X?{R#J)O6?jrH{!T5}b z6w{;tbJNpn#6mYg{^osNs*nN%8e#kqYkSxDd++UGs#TBQ%l|AOPCo zA!z$D+`Gv-e_@$)yI&uwCs`5oq?sw?&kcMwlW$3!G@4D{7G-dytYV6FMSL=RBIkUJUxfiSmf59+RzXGrm1YAC}uU?zJ#=6b#_d}n(@88@! zH$T?o9=h;+{(^@l^oEp@O!Td1^D;1*qTtf;G$p@IoL(L?=^?t%BD|F<`1!&ukYl41 zLbBxHrJ+9pJ?ZU^cmpx_hGP)Do*tJrST~T9&_Q^(54zyW$qe!Dn9>ti2pN5T-oNx^ zs7}?z+%9EJU**21NXLkXlXXtNBfst66s8F`5tsb1)*UkCd11n3_!=^t@&B`}Q0#i!&?@Oc01SScj!m|0^se zdq7U=X{*b>uJBU0FZJLrQy3-jga0CJ%=;9yTnS{+Znq-ik*EMY!RawR`IZ4-Ig?{oA^)hH4_6_4d2GqpN4eon^We^E=@R8^j7JU1jhY=|YrPEp1x2>U{Ss`>rL&x5O}z2)DFsq_6PT%^cH!Qe@7O5DSYcvI-A|?B{exq=3J3q z$!qpwY6M|El~VaCK)8`;;p@dJCkF6}<_+Z4cxIer{6$X)0@D4nQB_-paQXTE;JYbC z?>++q?KqC#T8kd&$DD@sz8>MghC$9eCeG+4HG zFgSi&cx&U21Yc|3xGJTZ>5)kc&x-z`Zp_`lD1BD`t1H3mN`}%SE)Vqp7_8-xnCCTz zfJj&k-Br`U!!rGCC6oX}J3S zaP5O~3&AkyM~-9HBN8zCDvL?z0mZnZpa4a+?VfH1wVs61D|nhJiYF02YQ!#!pma*) zk&WAPHT!H37Q%d6xPyR6E}Lr5E@pnkx3AIQ0NfK~G2GTZc8COe6~f%=C%V&B zs`HJ3IR-}dt#b1N3Sg(B(ItJbS=r5EqSSk8%lj#m*`YqU;l~(07$*#JVc9tsH2Xq6 z?((#lkn{`nMP6n^ff7^nm&P6NWg+ol#Cq`Yi~0;$&_o0ro}@??#NIv716jzu)jvy# znCNc|X%)J<>8iu^k|l%mSI}3aqv1Tuq2?qo?^+gmmgy#Fh3eG}ju#r*5sYxr%O?HX zB)@W-pdiAd>VcDqM;t`ffgg<%Ia|fSe!=)7w_@rw8V_Bo$fo902pDi6A=JAGjAEtH zw4XC_gZ+}h3gAizvs0&2W(C$!RzXpa+QSTGrh$&Am-IQ-PU;``Pcl~3clJeMt*^gx z2eBlctI@$=jx_B*omatQxcBVzLkZEccyqb*@UkGAIh3mBA5uaMc@0ZnqQ{nwli|u( zW-fC1`EkQDsLZ$I_e@wl`MKrOm?^K^qWi^B-DLLM3un)aZEr}y!D$Y-Xo1RV-amB_ z&K~(H*l6~amrpeURAI!N_RZ2Nq(p}?R<618A?Pmx=qx&uzfQ@V-ThYi0J={|8k{!_gkdtd=nP~fiT=h+Q{>qJD_FSG|^eFt!8 zOS^oZ>G98WgU=>rN0<%pO&Lk|@o?C=kjh6|xS@7lT$_#k*?xa-cj!v@gw$^Yx}0+E zXG10Y=)*PWy8RV!=C#dv_E&|T@r6W<=2M5bjA87U-8uvK_r~?N?6(ImFjCI{a8W1u zep{-u%3i;M3s9U#T+5BHR=bmR_DK{RMZ1M%kg2RZk(rPT4e1ks7?M2#s!#V9s!+hu zFae9M^r0^r z%P*<*I6$@|U7?cD*dC$Bv%jt+Q+>xsrE)mMAj7Ar%N20iz99Iq zUnc2$pjT5!P94ij;Mo2)xKtf3oKH6Eo}eLjb|{P%Paj#1{FfE4y^0pb!@Keh^3up9 zwD3P>9}VL%v6X}3$I68r+U9f*+^Koh%3~pC%CwR$wwqtDe3r5%ZQ$efoj=jcv;Y$` z-8Ef%+fEr>(gBM{DumU+quk!P?0CYjxM$6aDZO*c`C5{Im0yN4!|5R_Phr#C&9r>Y-D zlyK4LPnPybFiT=nW|hw;;fluDQx)julBSN{TI)UD4Y7bXdWx;+B69S9F~9jC1f`tE z*}nZp3eB_c$=gI^!mp14E|>$jA^r76fU+{2+Wj76LlxQs<{-4z9_+jVcyH{{{bO>z zur$!TSL&fZ!J1K}^hp_mH9=d1e&~e{bHD~bVayvY7%898LZ7*4iUk|=$+S!UT+@Bx zIz;h8q4qu#*TQN9hpgqNDcn8+l#Qfg^H6n)gH(JOvpUS`7)G-Mp}PNprp^4p=fu;G;UlSz|iU{gFthh?ByDI2EC_4u?W&MH(PY0wLn@U9OTRq zdo|AGw${tMPndy=F*QZWw>f?M+BYCftYBau9DD)Si*z~X>b(?ydt9@CiR~eiF8P@S zzph-m!jMbcuarC`^j3zw!kWx*mPn52pb^!0i`#{O9r41dtsR+v`Q4)T*ET(!>3*zdhe7)t}Y!@si#j;=qW8{NkJR zc2YjmMDoSFZ57MW@9kYAwHRIf)`o-==Rp!Q$>{;SUtj{GRDMNiRehXj{ zUUQr-6{#<-u9(JHNuJ-(u9I&dv^&SZr)Ep=u9GsI7NLA>KI-VEW-t3;`A=|dgoQ;u zq>pn-^W8Y^*5SvAjsHDMZI?5C^;+n*C*rghF!@TJKmrt&>^aUT-)PmY+X~?ummWQ& zu3hr$v9~Q*VBRj?n)G|nhonDFolm#kDY_3T#qxWB0M^^~WSrIvJhhP6z;H;uX3-%d zix{`fBKfkX2%?!+PM^~Z7rv2R9ry=|ds@lB8+ma*+neL=G4lgiPXdQ1vLDYaU#|a! zh14nW+mAduZ;_VkV)F@8f5i61Ax3N=waeFZpFex;hkl(uWwqZdFy?Kpq-*xug%Rx% z>&-n(UG$FuzuMrvUoLB;%bp&$&dqn%4o{rPkN$X_T8l>LX;ElBl^e5aXW0$jd7G%j z9(w;SQ^p^WVtw(lxU1w)ZAs5baJ{4TbpIy6Wx{IF>{?-cVL1h^*2tt*0m1GjS{K#6 zXdnW#+M}Sf6Wj06fOmR7K)XvK^ATUpJ;Cnp<5ZUMInO)xf?OFdKtCvMfStGx`10lK zzR_M#WgGMU+Qatl)g%9VGmaRK=lk$Fqd)1aVEyZePW}S`usF+y>HG(z3I-39=W->) z7K=>T!8%TxAQ(1HQDAAuOsU%&yhP{h`B5bv(b zZ#!QxC;+D7;OFIwc}5YBVb;PJ8am5hU#GTkAM7s_+NOouo_rGxAAVPS;MvE!|Bg+x zWxkYees>v9!!z{ zQ2NiYJ$n8R7RdJ|rFcPI(B>MYrBRsitoS^tsK#cS(S@TPyK%`rUp|cj!R|H>PQK=^ z$V;k^`P*kI@g1VEcPMb^wEYDP7 z0)1636Lp9(=4;#j9WAN*TOs$Cr`5f^yV)jyxPA349mV`c9!|kVv*-P+v^adp0K<{f zmJBi7a%+gEE`A5;i9zsBXdVv5Jpul+0*7$f81AL8BzjdYr^ERomR|EF0l?z!+1)a& zZ~E2Qx?QeRB%clGgfP}Adh4so@;l9rBJsKR_fq!e2mj&-;fKYwa&%l!$y)W>Gr}#L`!H*%f#S>2E*E-1U zE-#W|i?JiXSC9AlM_fd887X1|H|e&x#qW<8EDeRUSBIV&Oa}6~;)?<@Ejnga_bIa+ znhwhsb^1Lp4l3{hd;Pg|1b%o*&3zb<-9vO>2!%IMpRBo;%x>bbd2m@JjI=?0(H{5o zdS(jtF+65c$z+MKcrq(<*)^{~*%VhEDBt9Cs_o^4thV{%s#YsVZf9A{ zBLBM2V;^l9{BeVb=A{1`Uxou$P_{9^{rl{to^v-g0$0G7j3L2K$;Su8(_|jkeMr)NYi+txqyMf;R@A{j#6qrT_V;DB)MI zjY{J|T&^`A1dkt=fBM+o(v3Y7sbxy(3*(cH*Nq()V1{)@&+&kgV$M2{em&XAPybz*Hhx(q+q_p0f-~8WKq<&{I#ymYx&{;l+85Ar?UVL zYm�i)ZjvQgqV3{YeMF2~R-jI|2aUo%z!-I6hdID&(R69*^tBc<+y5e3PkjC zddlq}n@-wVi8;_11 z+0)VvSk33z5QL_Y9h1i6C1e&c2rK3#cZ<_idtL9B(`9H5YF+^+k>A68^=hHq>?rlFE+04RxU&mk%rjTD*e+yHJwb@6krNkP@~5%VA9R8nD8JXK09OB?%? zc_2eB7nfx?TsOa%S=myH_hx{F0_bVZl($1_{B#8dyo-E#Sa-5>k;~9bb9>WkN?{~X zO3)i0em=MoBM4gl?w^C*W*U+*84!h2$m!MXZAoV#Dm3s()D%FJ9)%I-c+K=r*o zn$s=(%DF1MQexxoIn13edPs?0X}!p{oRT$G6IQ6v zo4wRCf+qJe1)jSc1NB*#rq5gg+!*rsZ0%FNzp&9YGkYVFG(<MqUUS5~ufa%-pQi+NN5?*7YqOkM)DRS5nm%wr8r#Rh&b3rLH0 zeVqh;PBb!2a431vT`uiL+y?q-pEpPNE)X;t-h!=c1@5V2MRRd4N94i8)8)oAlxv(e;%JQ; zl6_Ls+^fGH$bF?piYJPTzfi7Sf4DcLW8>~w+_;y%)QC5-a_Zl9jbY2AKIxOh_gb8 zF0T|MT$;+MV`O=r8fFv=Pi$x5^kbt7!cA>Iy!RLZpWg$O%Wa~&bRR5GqhMp?sV~o) z{SOvcw9?_pxeWqhU4X0KB_I3Sif62*1G(6sXEg!?4VyD&s+be zXFEhktVNYPa0GUL6Ldv3k0eQ|mV9!@(w_Bi&19H%zlgD8*E$4V#CGiv?Xk&wG@OTY6{?dqB=3nw z{kTsL1DO@Gi#Ffy9maVoD!P(==%Xt8aq0QHpN>zS=p^#PCz?71bRd#i786m6wruHW zu!r_9)c)06X{&P@JIsB25F0f2))&WsDouFxYOy*~;=t+^ z#ec5e7p?yHJK;sLKIzg&>g~8Pk6q^AGWmRdFg`hhIf7#7M?*KY2?h^dYw(`#{|ZBi zHV1v!pKsy)TxOOU(VO7I+n?PUWUHw+hB@@n`GrVAQBwW+y(9Q|g#OE%b?{EL^wnII z*BZ%z=jgE7nyGiZf?3=?$@~2l3nI8=;g8{t-SwjuSNgS_rIqL?;+R!shD+(P%8GT3 zqsK5`_MC-6YUrVefZU`|-*r^BN>qmNT-=As%nVce+xRzG#FQ9nWRR79*XnPK7}6eH z(R)ZvOg=IpOax3r<~vda;lKaaztZWXQ9gHPI#_-UZM2pO7=qb=xB7#`IJ2JZ=m1zV`9CEW6#%8 zk@pKo^B)n?IJw$n#p97tY5kyntO~TugIB@`5N(JM;ov&}pvNO*bzgM~m`sKx!#z}I z%bZ;U#9BTzh5GGA)4txsyQoy-FtuH{;wKHW?O5JyndlFI#%`|FwC?q*?5Y4r4n$=X zgD2M{HyJ$Fe&f+PVOyIl0XNmDmnuiY8jP;6PokOc}J0 zbyw+=c+?SIy7rC#akBnbE5Iw3{oIeC-5zWttXV=n6^GyrJ@(vg{&BiewC#bh$o|kF zW`VVjSW4nYWS3<6+Tk8=f>CQ5;(=CgzLMDiizX%|_4Q$V-yWn0XO?tR1xnK2^7R=1 z$>_%6N`n0eppT+v0G_SnP7#&7RP)!D2#M~=e6ynP=aqnCbG7J@AKxKg3J)jedM*pm03DSR%KV0X9{3D^$jSN~;SuSZ zVa;4q&ArrS{JbA3*Z{n=o0c2#HOgLlx}v+L((2c}O^xNDCx_&+q@o3kh zwjKmb{`e!%dDzE(d~l(GMo(PT*Q*1Yg8W;_gH;EGu)b8IQ{%nK{6X-2ZOo$ zO7?3`Rxp9&N0ed_h*3+prz3(qJIws?vkg7#3GF9O_|3Xhb`x9zK`EXuzq{ri%*Okde6@>xxk zQ3Zil$yfTL(3GHYANK1HHvb8$+|Lh=eWv7@q@1KaJFd2>u6C}K`aBHS$dk_#sgk{T z^Dr(qNJ)Mcn|K?Ida3m{%q&SuaMQqs>>E57eyfHl?yCC7!#nkxLh5^dAAbkUvWtRs zKkwfZpm}x=jG;$n_E|hkQK^8b5fMC0@{A|M8#nCd{tcZDe#O#skFAu_=kFGhZjh5l zCNC$vHSe2?CGJ7x>$|<37k^%NnIDSqIgGSy8nr)R&-uMV!6Y7bzjtj#3SiJ=sZj?N(t&#MfFfLV(`Iluq%IkH{w1*qNRXjzH3iz)4t>c0AvpapBPnsHWBQXPd^TH z$dFnc9De?DAsTqkaQkNpK0a`l9L@was}FQ7ktZqF_-+eX2qDw%qk z_Q}d&Rq~!oMCwxTM2yuXoJ$nud?h=$DN=4((1?T;Q)@Y>9qP;3|L`_Dm8B-VitQD- zYP1bo2@{A6Hj)2Wx~^?Sl_2^{lHpN65D^rRNnEZvj&4RFaNhdX38GlG@ z()6hy9X)LPirOxZ7M>@YZ93HMO33Dsbx!kn%SKd-pkIbhQG4XFOSxQiJ`V!P%^zyr z?}@^#D9Eqic!+%pfl>6cIRGm=mbm}jsSxiACLDN6;$LeNY zFN7`hCqlSg_($YS_5;(H_zWdgvM$<#*zUUbvca#c{3}s!VMf^Af#%}!{Cds8^Feo) zrpb*5T-NM5BbVs*Wuh@>%riM!&Jx356zJ{@GGZZrx^?dLkPBcM7kaD!q9`%qTUx{H z2c#fQSVMpk36pY}5uU-9D{w?o46%i^yh5yV!6({}+qWK*;b{iOv%A69&wgg$uK%#5 z5_CF2Oq=Du|F2FC*ER)VlIT*dMZ87pAijH+-qs>-bD2g@$^vC<(N!pKl${>FZ*Rya zAAcH8smGCFuU_HlHW>a&2@8&-hh2ojqKpGY<9K{X(M*$56_d#;QRPvOU!Iznr_WcT z@1>RWK!&9jd;ficJ`G6UbhSNh%T!8(n9wCxa_dPdZfj?b3OlX#!Pez^EBNyw8z+(<3BKw1xZ|44V%;)F$`zHe|z^#4r`#;j=w_dLd1;8~!_iOMZ!ReLWGdb>`X# zK0jy=e_v_AjVdL<=#T%1)2$*_7~|q;*aM@p|LfeeYfU8U+uHZv!M+#>XYMf`Cd+B9 zYr8j76=OyFbfz5R4YBQ#U@k9pd+sxtgCZ$((}WMMfVX~^bHdqcO_izm04ikK7h?Ow zMksw_EZroz zGlSww@qh>HOnzkbBt}x~FWZ5QRtPqq&&sbz@3hca5B81K1!sEqmgd~7lQrmS8{5vR6pI~Ea zk{eU`HP3J?w_l-&D)0Vn&hPgosna99!o1!fReQ_Xj2I%|f22Ec*`E8o^>0&N)bjqM zo2TXpsQGY$p}7tA+EeTWu^z11gc(%xCJ60`i=hPY?~_?2%sq8>P>zhcQ_ zjqBBc9&P7#8_ZX{EG_(V<7yo;-q3qV<^kuXNNO3Xz^J_f?W~>GU(DvpvnUTKb+l8r zU3y!RP;9q9h2=hs(gAYKPPa!g)}JFhyrgtrdSXHp$HP0BN>zIwk=g>r6ToY-fMC+C z_Fr~Rrr;OhQ|7IDaNhidtV5f9i{eZ?1mBy5gLj4&lx-{hdnGOQL-Q@xB+9x`pbND& z@1hZ%h5O{a0Pli-H2bsrDM8hJ(EVKhK3WFu6a@4=MmxNA@JGA%$_U5t^1O!PYkf1l zXIrv)%3c?#ocEo#`crw<`&3yoq9Yi|XtH*_5A`wARU`$9m(MSB&?2{Uom=569E)swlTI zTkGI#iidHQ`a|!_IU^lVYkc}IIymR_Nw}+@HtR0pUotmF!AYOCTz|`c`hX+B5wcpj z`>`2MT1w^v&Z4-%;?A7l%WQVFjjKwh^Sbe#)&%H+Wrjwg%Nyk6H)_mMJei0to zEvm(RR+xUHdYo7A6f-k1_%kC9)Uj;R6w23&hmOmk{un6{7zl|?`c@cd$afb@om>f&gJMXE8c}`b878LMUB-!xM86%#Dm ze+~(l;QGv`pdolt@RHS^=w{5bSfP$Soc5|c0Ds`Z`JQX|V3C{O9`eHljdyCx3o32uN2Y?WK^K$99Pqb zJ(JES^N<^47jA^s@JQGL;0yANfzV4BUnV)k6~N5B4=UwaR#33A0bf^6`#NBFukeNW zNw=qmoa02D$n7UuOSlhn^NkviEuIVcc#DQJ$yZ2xe?am&XCIb8L}>;4x1x;wK{lxm zaP(~WS7(3RY`la+R_UOfIt@6no`hJ|a2e>55R7)3(!=Tf8^H)ei9N{6_tm}IP#(47 zL24gOI&hy?s-IdI+;YbFHtoV^-K0;BjPsi!s8XrmNaGmlo_WcU2vc&C;%Untq95&F zRVq(?S@L(W6YyCu!?)`8N2(32Pe3)Did+wF^>5MAP!CamkM!-s*(c5RaeiD^as`a? z=&x9?iog9B?cMd(yQ09TE|sshC+9H5z7N8JDMJ#LyhW-G9*ODP4^YH&mHt6RR?M0ez*t2J;g%n?;qeh4e+nQ~WP+58 z^ss2(KNHxC-i&*^pg3Gs$*0R4|H-7sesZ!SrpXk1Iyz}*FypSHxA9+iKagXI8 z?^~C^8TLX(9)$YGnbT~~M}CNlpOI$Rz1gi#>y~@(8>l?cVA{}N?oXo)S$#={ z2>EN9O>rTx&%NK~%rJMEQVqd@W9@7T&e050%ZX1oc<;+r^v57S9AYHRHVY1Wv_ zaF3N-B+(_J9J7T)ZhPG%(SDBSFm<&-j!f(PdD$7Z@K5U;Hb%t?g`I^^sWjxgkv7uu zXaXAlm|4X5_;AE9q~rV}wVe@C;Dphbd~56bQGc-edT`%_ers1Kp(S3nrL21OR7vjZ z=mn|hQkH(N3k65U@raqbLCz>9sA_C;~>0#()juAYnog+E9IqD0Sz^Uu&EvLYI-1n?N?CjzU(eRF>be5FcBHgn~{miXr7Azm%IaqHH z5yM6WR{Sy)M4x^+o`yC8ggvqO;-7#T^wZ{>73?hhwiNjS*v35-gm5S=;h^Fu6wL1lxDA}3*WHU#o+J?`~i zP$J*RdtnLg@_WvKUx~-P%+yVQf<3V^eEr7yo&9d?6#q3{CV>6u$oNPc!~d?B(L`|< znpRwu8)$88K15&>r*O{RFn5p7c*ihqn|M&8yBa*>bMpM&G&WO;`Nc%6GUwth$0+`y z3ysfSABumL0a?hTj4i8jiKI7lUxA1oMEe>*gEx3~?Fq}z=<@U!s+qXAQfj#SE8CXF zgz|>E53iGpze1(OMORe6JZFT37NaQu3CdWL_(jMCDewkHM3Q%|pb>}h|{ZmWT z!$}b0&>egRK)R7{<1i>6o7_Ev8XmGgmL9Ut?s_gJn&3U@Ft;yPSj2DV^5=X)3DjEQ zYnbm`N?ZN%STqYg)F&WrBvq@u49*KF{5eQp&R5mqe}F1+0IYmTi3Xg9_q+HZeS)Rn#nsF&ftFcb(=+h@4tCK=pldXr;b%g^T& z_1}rWvY)=<5yxOvlHw#Y!R5Yqv6$>BT;yJlQ~R+mA+=FAy3?Xx36;m90cbVJdSyB& zu#>!gsdhX~ES?SJC;iqpx&SEX?VX^r6w2e?Q3fKjqit0K0Z%+HY|Rh1m)57bs9|KqpwP6Uip!?NEp?_^Cm zrMJbS-eGXUNS0&hpN-nvpwB<72%oVu<)DHECcMP=a?n3(BdO-{B#q!ZftNJS^!u!O z0JMGa!i(!d{~izIgM4;ub(!pc0+>}IvijK#cmA^CZ{N1JPr6`=fu2Z4c{RxxC1%v&+}&1OO7R`UKl$Y~N(lB-ipN@^NtvqncJrZl z`-fBao1=N*sOmSVZzd#1h*p)>IhsaaUlnbyJy`20E&gaHaB*HXp!8F*jJGT59@59< zqkgshKMk@c{pQXkw{h)}Af4=fESN~RKuMSySgt%5O<*x6ZnU2Zpt>9}WIcbksXY|m z1#w+JJ^h}ufQ8>_gkZ8bZ$m(3y#74G=v+B+Q$-oXKCt0N z{-R^^8|tV#ah*$$9c;6&-X&u{9i`IL!@C>%yvlKqHn7j~XM$;yA9P(J`*FXi2l376 z-`g6;32AFu5;<)6O(gCi9O%aBK8K5Be@5uecgL$AkjFMsw!??_>UB#v@9Zo!X)x=R z$nButZ74*Qpbowz)X3(QuG1lIKDkS^&}{d%y6GGpXXE<=UnAg}=o#Lc`pJROo=%}= zJf85?5O@kCD)8L^G1;HFei&^1y_)IeI;mk-T!7X|8iRzo8G{vzVkrnq&S;IosrR`s zYCIx7W$Z<7FR9K)%W@v1I{&(#MQ9ccayE`PBP0f|!R2*c zjzmckRB)zy`lI3@+#hjG8I1O)kD3{NdU_9=P~ySg#gnjcQvEDrM2NPnPQ!Ut$TJN^ z=FawBn)Pa_{(Ofv^dZj8K8{I3cdqw+q{<44CadaFo!>G%ey@Pw|9(a(ew<^v{r82JJLbd%&9m z+FQ5j@ly{MVfnA^+D)!zds`tgrD1hddfn<|m@{=FjyiK18*P%y9Wo%c}BvaZh|I@WOx$)IF}_DE9x zcy*o7*5Y7x0tdewlso92cfRMd19^d8Pw{~Fi0>QjcS}yi&21ifLp$(Dq!OKF1DbCd z31VEBjg&Y1k!FYru-~QOE&;DB92cCb2Jm-tj=OT8q6G%xCJ3~V;-RpaEBmwB(AXQV;4y_rw zb5)vX4Glf{l?dUxmFAuD> z@*Kc~EBPFx%aJO4#R-KA^dK7$p9up*pdp+ATk@QbS}Efey3$)eRo*nlpb=I3g0BmQ zexIHb!Zi*|l;1+?3f=&|;O)-fbr-{d?(hpxAEWclskaOT0w2HX63lWx@FGTdF7>otWlebEK-aa;B$;N#^Rn?2m5)O~3DQ$)X6 z;sLUsj;zn@exIzhoeoa@`uMMt?C*<}0}ULvxJTb#ei`GdugBgU&Gj(MLc74}V&7O{S0F)zoQhN5S5PYa82!7=My*k+7oN zx5xx>aNv3{H<@r#)!8|%wN*DCu!?^Z@H{6ocvr@}iV$SM(+Z(y?ekzZ?V~{f3;po-kfXVrL-+FpBIJ#Ao>QoRnH~} z*4BIl(g1T{d);o?K0=2ua(`0?VRTgQ zQEB8uUn^Q)pvpJY!*A>T~z|I5g8N%E*NKq&>qp zpy)7}4_ALfexsm|w4-KkNGx%W)7N zh;67yG&u`Y#Ekay1FEkg^%n(GgorTrd~z>gd`_+mDL??E){n<334i-Q6s%;n`yG-c ze!tl%O@n)s2$KDa<%`Qv`X%-St*m^}W4z)*|2A|#7$K4X%Hx|W*g)s&=gnj1p>fc8 znL4Ou?|s9I*Q!tB)zR>((r#AZjp_0MKyp|$Nhu^qQjcq^`WYmI-s<3;x4U*?7MLo- zH@J`Gbq`iBZDL>v^P}ErS`<_fk-OXB`>?09#V=665uwk8yQjtt$>osNK-U8AvBmy) z*=LwW1gvl-1UGd0?6|mx=tfP~4v8NijMLbccKprWCv@j-cqNKpmTFr#E_d^0*}$U?`uSR95iRSQZ_Hy&IJc9lC} zQj^I4-oc#!f0IH1Ix-|c{sZOv(*$S~?VBm&7^1wb=}8*u!casP?Y;14^2cmwA>2_i zO7@)A=xOeBL<8qgvtFBA$hPGHPv~JDpFN~ta0|l0+AC%iWE1j3jE%eyfB|)GKUVl? z(1L|Y5)YU_=H$wV`tLk1f4MDhqxymGdN(WTqbG9yldxP3Mp*snt+t0ww}Hi{ds@e|S!~-%w@Ry2U+g2$uu}u~&JVu+9XgKlhlLE^7X?%JU9l=W z*(rvOo)4UjLPUArm_lDw&B?7Lm)XvzXIE*?&2Wjf^0H)bEq)JL(+Ftm+~054*8m|U zY^!~*j|%WEd4dof{?DI-gn+B4xzBMAZC|Ab@R-V);;Xz0wb|pV+PL1}`!Ti`$dQ4 z6FAdTJ`#`p&==^$gzPG$m!<_6Wa!}Zc_ow2XRPM*y`#01u(%g49Tn&L4emx?^X%8q zhvU)ezNoBr{kpXi{12Xbs>x8`Bof1J@7Z456%%$?5YA7u^BIm2q=SA4v?2D1Y1QMl z+uAA5fHQ-S&<|5?()W1W`&FcB@?rRO=Jv~y^pG^XB;7Ci%a8Y+-e2fHYqz6+*||XC z%BO8Z%=ckmg;i^yld$(>5^yg{skh(p4c+DSdl2B72$jDJzc1Sp)Hd>H;AP=$yh`f^tD(7dj0P{RH3e_6`6>31Fk z`Zxd`oo*4$oDa}zL%%l)oAdh>QSJrbu^uArmldd^+fEvTmpI-3o^tzqHrknPI@X6N zQ!Yox-}p@+jnBQSwh1CQlKn<+%7Y`6agSiJ+j{UDkPLFPvo8qSsW_eb=G|HC>e#r; zO1hbhb`zfQqyAgu1DBWXL*7(SFSEvm_)xr{+h953swpFMcA@3^Q%+Z5>XqW~t+{fk z!*IS5mBJv)79WU#5S>@TqcQITGJ^!vRlXkF5Hv>opN9?r08XIz(Yi3Y{xQ*+EvxlK zyZ-idTziTs&hp+TeSeg)?Z+GE(CFZXx-JNS(sAi&vDnWhlRtWE9cfRR?(eIrg6OP5Ju0f>%jIR29G+v}jIeh8cpu6k z?&Vec6P9tWcKTf$2q3DzN{Exa-mnzu>1%BZs&CqbaoYY(hOdvAIYX2w!BOaHF2ITv zjkIH=G5ZJ>R-T{F&iaZ<6nC8tX4&@=2mEYXPkaRl{$ynOe5&BYWS3we9^NtVTF82D z`-ElNr~Rt!Wy1%@{y3y;ho>A0O@>!qQmsx`{n`-uOGwdiQbGdt{SbNzp{R@UVV}Y@ zXe+)1tv)}Y;nO;Bj!YNm1e)!(wV$ru&JS-(RTraOA&#G68`R6@t#ASm%Cr;dj2hpZ zpnpC*&O>1j8zw#_JkXBDRYDcY;^`fV-}25u#B<*V{DM?+(w@n{?KU|my`E9Rp@TYwUscm+i9?nGm@2i$C^u~rjk8%)8{)61l!r3| zUY>vJXZX_|7>NZV?P)r7>9W*IH$8vlxi;$Flh(du^`{1nuy2oJDekt)^6UwPOdd`3G(|j|G{*C{$$_D1 zA*X84to6&eD{Lg+Hw|(zQW*YWV4!auqvI}P*0>FeN8lM1d+ns~b4X~_63Dj76tVL1 zjz+6o2^R+|=H=S!SMq%8(%Po#m7>y#ehI|#Wlv?~C!pH`qKn+1CL8VtzF(JjFX^YT zJTDG+n1q2GEaHsCbCM}g*Uy>ov;d@UT@=SZU1?O(*c(;3L_P>k^G0%s{pP_F=31@= zXo}nA;`N9zB#O6N8LZ!w%uY=h@l@j){`a&@8?(=r`oz)gis6Z|$OG z1(GY%O(TzqG!XswaIgBeIsU|vN0Wh-{f#emKTbn+Pn2%5fP~8%3Sum zV+6#Y8i#5XVj+_>wyXoI| z8eimv*4p-T$t*+irCSMAAMV9Lkb1q`F{Q$qX-|tR42l^2j!gE+S^lIJZ&+@%P3*x< z_i(z9wflLiA#|2t9XNa*Z&@a~tjiDSt`?m?&he&9TW-Qf4DLVUvbhH9LHg}RuP))ppL=C#^|#NV8kIzNJQMTZJ= z$2y0q3z3nooLu5oK&%vqc;0{?%>jyvy z<(7%zr_~&27u@-IB8C9Tl*eb+(-ofKZ*Jsy+b!=0eOx9KD8FIG6*@t!`-JfF^j-LB zAK47S-u^0E5A_=?Q9=#(jP0r=9HR-(a&$Rs?JWM&KgGgJ?3%g!9*{L& z@x@{U3uZbN+bW!HF!f8>HY*gEij&J%(A)vJ;O4!~$`PSV=)F5OF|mmMgnB8{SFJ6+ zudatlonu;&fC6Q`AW*SRzKFL zZks+W>dHR8SN^b+a=*Q4)?~GPi2sgvV5>EBq`w{6P;gjcx& zL&dUY1$;Wqx?jMh{Jy@^DWwn?`RtGnxC@x-nSwC0T0cHKk55MT5c818jscZTf2%LY zbILx1Po|X@XO~tIm;}*nB?^1duSjFv?fUd$=Ge5#wP~xh<`@vN7zZ2T{TI#YuO7;NMA^<;c!gCUngV!(m+@D< zarB5)V;0K+A*{GP%E=*782mN9C1N6T=hQepKkU!}u!GwuLX(T@zPFE^7oNEos#n!N?W^-#FZ^Vt9kgm5h*)q}^~!-H`0&A>kDQ`@;_+odB=9 z=hc)0*m&U_o-J7O_;)7JEcPURWSny>)_e35F$LXmgeZ>PHt)D`{XqstV2k=rsl`d=}QCkIreU zdE4hxZ+v!C&aaO??^(t~3~$JPw32;yq?&c1O#|}zm$eQp*M2|`|6l*i|Z!=M$mV-^6|}TkzwKH33zH;yBoACpr!$BR&@oMnT;l0&zPil73f?7r2my;`-BZ z3B^yF%H)l{)Usml*8&RE6!qe*NcH%|i}-e2#^_U~FfD#{=G-B>Jn7oq+K&5Wgs*yF zp6d*-bg)<=<7+xiOfR4wo}a*KOZJ`(%me#vX$#8@QF49URB&O)+51S(cL%v0=CylH zD>>n|>)52u+IhB{#_W>iXKuM>)i*bb4{J!@G!RC0DuT3LxKCu0j`l@$_1z-8D914< z#*JJE*q;=d(4Lb=?fg-5q9bH=j_^i$K;zbF*n7WaN@=70Y+nni($wD64SK2WbY@Ka z^JBrg3Ol@rmbkvA6WJ3Wo$1HYX8Pi0vO!=~hUX%y;wqA|vMugePpM@4f(JfzzbJvo z#83Nvow%^7dVZFNN}*PW^MCsBArMc4qG{E*g+Iv&Ai&9fe6NRGcX3t0Oj>r@=su$! zh+a4%UlLy>sF4(lk~bWihe*9M5U3mY=H0I23||_-M&cz37l99-7OV zy~2*}{AX_odlVRJXu!t95VHbgGER&iPlpq)Km!P@-~FH`82C-JaCaCI%&9xgTY3!- z3*Jm*{e_3L*`wS=sV<<6;Deu&C48^|kkK}Z5{&JLb=Ja+~!@&xmZ5;YX}eNCGkv+#?oiG?9cy%` ze^3Si9;jo4$0^>@^qIz0U_mRRk@)WCqvb*MNv2NmS(NJ38}#$)nAWE_SjzLWoPXK& zc`Caa7!>L!04w1JGCAkN_<2V34}N~)u|%M!D5IGE=;Zn7<*VAuW;U_2axp`n$I3oE zWB~Zn1CRKgri2CEkCVB}>MGOw{jw*+kIW}&($pG}Lf+N(BdNb)oK07(h3+4Vp&yt4 z6|Qe;mnnq+mp|00(3+Oo$GUV+3oM|)%NrSp_5&!s(nDp&5}!w0adX;}@u%?-c@+Y1vKypUZ^HHH zp#8c}(toaO9cqZ3_%PEJ6R4wa{n4{+ysHFToHev2xAwPRr4!*vOT1Pd^b{6|6?AeY z{(D#e2<|{P9s1P@&SoIX97Ad#tBk&~oN@*-u$9uA6J z2`6}QRwrPt#{fpNlrt(&c1kvWrNpsIrd=plq#2WXQq5K4@p0#V%H!-F&}?J40kemI z0)ly0gMJ3;%S7%gRhjMby zKJ1gstVAwYZN}Coa!%^ijtF{vdQ>Va+{f{jP9m8}BRe%0V>-`Y*5ka+r@71v>J3TJ z{J?iA%@ruf;T%40vAE(0H4%~pxR)TvbdbP=ZbvnRz)07nf?bFEC-GB)o`Zi{RusLT|avlwIdxX;;Zt%K|@cbbKeux9@Lv->s_>(9akMrgo3t@>-^wr)+*TD2S9mb z^$oZ@ahxBj-23dV=~+*P=&s27DvVI#cl#c?!_5zF&1Pow0%J4%`n&NS1U&a5kuZFJ zcWDt}<)(VgyneW?KE7l(qCZZ2UBP9KKc2oME|{!F{^0aZazPzb4^*f3Gm*$QSaQ>R zYpPRzL_GkKnaoXMh|vVpf?9irebNejC`gGp9sRhX(2D+MKjD^Fs{@tTRn_O~PON05 za55%UB7TSZ?Ok*q6}#1IZ)wGp=d>>_$~2HCQCx(T@*;!U%Mrj*FFm8BPp8*v-|i2W zgc0`G#(K`IaPS_36bD?%s|?*?<_wpQdPt}GaY|Iy92}+RQAt-0V<`P0APz>Xz{jNf z;l)X{TfGJZioC{swdZ^Xfk9HOu-$&yfHvuIGYX!6Ul&lewBZIAJj_zZo;$p|%dFhX zefrqo7LzAp8Q^yy;K`c&GOMN$yGN?%#OX;qqdmT_mxA^i?LN)-UgGVd`e^U%ESAHY zg~(Q(FoC*Q%3?z6sJ-k#&|Jn*Fu`v&Pe<}LYBPECpg#=pRHtE%l>d2r|!T~VbM z4mMiA+@FKLHC#0hgD~BG8nGuOGgjrc+(`hQND+kG6!;<8@ z(|-%`_?CAh7G}fDO_)2iVM=NV9*|F3e5=y zV5`2Q?Ndyq{&}(rXcx4v>3t|4u&C)|_fJ>a0m(jePpiqz8}yjhzKS607J-N@ebrwO zbm8rEiTw+X2xCYHR8QlAeL~P)(n;@|Sexd;K z+D$x^<1#IPvH$kG2Iexj^9lj;Via2B^?Il7wCys$J9ZanyF)ZJOn0Y^Kk;FUvXO^* zBs{M6iC`w)g%k=W0B-Cr)u;FVqc};3KBV)L>iXG>M++s4jc>ExwV(G^sS;#!sJR|} zi&&4eNA!XBT9lj|0HnNspsucB_$nA2N)~p{ed=|l@&=9UY#*9(Aw4dx5e)syseXL% z!fO4#b=)g;xZ6Ja;xoWd#E=KafKdEbcPXDtcr6~wW5)r9kIBEb0qwnV<-Q%qo9hat zeBJW#1W~;YVG*UeRU4W^dCC6iS+ZXp9q0LRyqsR0Kr=sz(A-`-aOwI*$xP|n6|k(gZR#TJmZZe-AuC7+n_gubR5EFK5y+XoGLs{PKRY7*^a* zWn>PVk4iKA*)6bSEYyQ?E`tm*7yGeS{CV@sA5o8=QI~*B9A2tU6u)Uwbg!Zx^CN%N zMG?0CFL!}$d(xEL^czuNC5%9!b!?;+>`B*sYZzcI#ckfe}L3v_)77IxWHtnA~1 z;W^|%5cjFo`(akhVQ(0U)e#Icu=cUVO&722Si-WFl6br|Ncbxc%hK}zSC|b?j+5&b z_NC}$&l4z6O|KW4Hg^fZr-mn(jrq5}jvYt~kfe7g{SEO#sSM4mT=&6V*=7HLA@}>V zY~90aa)Hx*c9jlcsSl^N0X)7m>oYE4B;>+<@DSin^6C9K68dzDkGC&B%*vD913_13 zM+UwTu2(*=JAgj*O9ZtMTM;BNWfjg|n`5P5Ni)Btr?Sn#s z!YNl7b^36d;PaXm8VCx!&U9H`?X@b&M1CToCrJ`g&bgOI^JPBq-3yy~yL_30S)Ewi zNfCM=oei|ose3eikYP)}JEIfgkElOy{W*tgE=rNJEQ4TpOK`S(^vR6RPh#KaBX=lZ zlLal`BzoMrLA*E1O9>)SBBXa^eY0e}>bKKQx+F#4Gn4}0%1!@8MI3~uor8v9l-x^alIip!_c1oH*VQ*Cz68Ut z$ZUN4sQagf5|3O6bE(AY>_ZFNopWHt(KhSLLqB^7Has{YEQR$Bov{leP|;0KtLXsx z*|1L}P{_jHae3?6+gOa3SGu1Ag+AL)ruHWcKZGz>8;aYnnRY!{fkyNmDUS~L->g1yp8!>RZANcs$Ha}RF(ahzEQq6FGhc z`2b#@;4QSgyF4f)RTUd^hXbRMno7%GK=NXG3bUe+sQET%W4#Hm56&WgfM@BH^1?m3y~N4zm&xa{5+O6kESovM5R*w^%Nz-%pQU&tQaZjX3*(9$!3 zN4d9e7cS0_IP`ng4&M-FmltF5ApPG1RFZA;yO|@XcC%=SULP)WlCec$430q0z5Ge2 z8B@`vsq1=+H)Z7xUBqCmHs@_>g_j{Z|0fD#f)U;am3oeJjzf5l)o2Q zD;!SCfdj&-TwTog)J0FBc;!8Tpa5(!*`L*Sns^MTeEaa7UYM;EPmYMng5<}&fNOzyu&;WLr*zmO7yoW8O&cdAOgg|4IhFC8 ztGk8r`=JD&BPlnpCHQMr7;DZe9n_PN7?c}CVW}KMDJ11;woeV|0vRPbf3;1VSD#ft z#g*0f_1+X5M8XhC5fKkYGO$J5Cl=VxPmD!4@D$|hLz$SI3;D~D5{v7Uj9IlDSyv&n zKNWoLp{H!1 zHtsWoa<0T`&wd2_NiH-c{$B5%c{}IetD-X|ZY4!O}Zv#0bu?M&I z?Oi`60W@6nJDf^0F)QJ(2fL=R{!3Pm3Zc^Hsr~EpPJxypzgt)_cKw=RpC_rsNMk1g z3kZ~SOnFjuLAJk~L8Cfd|8(VEU8l-$!2YWBR6+Is@O=0DY&D_2`UE8h0$L?t-6SK- z4j;_D@f@aQhH0CJy$wZ03KYxDg7bKR{7gqb`w-CEP#6D0A>fM!{nSDpj%V}kOIEOf z`Zp#P1_2pG6x%=M(G@N2x}c@Fz(9s`7k_!)iawAKv7iNXJ8ELX2~-Rbu1|DIZuC+g zju}a|r>v4jDuShH9=qjR;iU76g3v?s&5XWqlo?dl3K#UGWc7&>$#s6a2iE^7cP-LR zUje=~kHhT~xK?R8AI=K$PkJCS)x16+^|>VF4e5qLhFKSrF4?_u6v_7o;H=xuD3GK{ zoi^4#O;D%>5ly@{3O7SgX;fQ)fDr+fG)}zI)F{p!2L_XoKEjX&?)LmCwOP2m4`$hx~)XAsahiMh>2qrK{ESJG756fg#L? z8c=bR2X#X^Dj_2Y>VmJ^zFnr-+V}Q&EC11SU0bSRLG+ghk{(4Qi)6zaK~yqG{`%SU zU9(ot+-^mZhdOntb~u>Avc~66Jw(ADdcggn(4BIZL&Bdgp)YvKB5pZp!*-6nexQiiUg&hY6z8n}*iPIp*@%W&3S8Gd5uj{KWRQab&6d4b zoLj3mXce-PV|ab~ZE4E|0(o2(k3T|t@%CEp<(86SLaNN{w-xBHUVWVRl$KIsbch-OeeHaKJrKfu^ zH>74Jb-(YR=7|bUkQ%C$-0$I7ZqkQ1r8tJEzo4oZU%c55*2}p1{Q&?Hm1%JEqqC|( z09)U`VEJm|ln}kXD#{Z3A@F}~fCe<-43^Jz%XAWt$8Iaj;M%{1Z@t_mgNAvqjKI6b zmoTUBiDa_EykKOvxus>$Bya_K0yT2W+nj`b{g4bOWf_uD!!=ldpl9$se7;u>EB_-5 z6OKmv&Hl`+CU`KfC)+Peot$r&85mN;iU2TAePn)YuH~;A+iSUXW>#or<;@ z80t9eom!QPtvA>XTxE^m(9|DKME8_fGHP&a4%+gDt6sG?U76MG{w*)$+Ft7>lmzJW zRrJN1y6Usv-&=m2UDxG0*T|{dnj+9KH|rVh6fOAmM-2Ob$)?_Y4YvQg8% zEcGbB8QJ^&2~YiAukmcFAWJ~=VNZ2YM|_?42z`7#%h~$inHPQ29L`3cZ?Dn}R6LNH zzRR?>{Y|;dgoXMf7ND|wtuEK}<{j5-+?9C?whY<%dwW)1g9emA!C}jT0b0V)iT;?u z9}fG5)Xi7C9BcC$HN$Nj?;dZKi^R}+RO*HC`OFpFiE*&3^>^+H_f(|+fF_Iud>eX~J~HHrLdZU*NgYTNly z0ZGY)Fu_$!2Z;W!kMwY??sV`4Cx&2Zs63x6L>v*y+o3vFQh}MO)m4OAl|2;$q+*TR z6AsmV$0A+Fsmfr{P9*4QD7DOe#I&!b8z4-_F*e>mW*=I0x$1ggKSx87!ZS)~!(b1# zq|g*VjA+`G6r7~*amR!qMX{*ZmirtWzaaMv16@Xt+hGqeV9y`VH9X~O{b;|`T!#&b zKb;by93@nnA%S#;_So2vSMA9bNr8_*_z)gUu1@kvnkB=)dnA+tbX97;s`YL>$r;p3 z_4OMv!Pc~2G;a}N&$dBDe67MVp`!%V5mh^1rsaGsjy_gE+U-*;AmggSAe?-e^&jDR zyqdy|y>ZR}2at8IE{DQdhs;iP49W%S1xb8P3eT;#kbi%nmY|Qn@VJlrBMGrhv%2_U zZCTk%r^&DXl~R}n?yX%cFVZ?Sx%N@hj|Nq`OEB4La5cX7?yEw#Wzxl8`eyC+dW|n~ zT!rPf9Hvuyki>4WTHTAUVwm_T>_hL6RfL0Yt&1<=(^X8t_O5uo=+8U)a4#S)h?+6m z9~d#2a>=IwieT1nVriIDBu04dhqn=gua%^pdc8aoWT9@^jJl2M%?vyr!msxlYXZY2=xSPGtk40bA(MS7zEi1;K zRJ}@=jenijO}nX^I7NX<>$X@l_u;iB6rl(C(PlI3o27$w+ee-gefO!sIwrrilX54h zlTN%T`&+zJ02dw|EV(k~c7hgg;q61m?&F(jHz0=(b>l+kQM61K5lM-BF^cxg#R zb~65PGo$2uvZ7mdiGPr|XZj?)v)Fe}7~1;^Soh>LepGok{&;lIwyvP4%t0!kl<^jC8oeo<}>j-a(B}LB>-7 z&7AeOo=WFAAD`$S0Y*sVAhNDAytejhF;IZe+VdxW_;d>G+&9R?WGCm<<;2de&o{M~|miVR`UjNOl}UM_cA$?eY< zuzkN?u11;5Utr&ey-g%v0g~CLHrdTo*S_Yb1AT3-VQ>}pYJ#;!EOp!Lm;JQrj;cM0 zj>^1fv#R;AtW!%LNv@5RK6gM84?H+VD#kwzA zlD%UFJa&#R4EKQs9t7)ng+EZ(4}c$kbeOkrVVS#qjA(M)$9;yhMx>}`J9~=V-EXqA zRY~Yp15b9&;N+z*(8cALMPDmZhkF!UeX$t+OZQr2Esnl7G7UZCzWNFkkA)r2mMsZ!dO|&Q!Db0s*k-8ASg2 zxQ4H?BlfAAWi5LHc~g)$|HBsg6;gGLf@2uo6{MrBxd^Ld{$9})(qms{`DH>%I<)jV zey)4ob`qagS9)daqcmcTc{=ljvfoEF#0|e#cK#7rW6-pw{nRxe{j4Qolfa*bsu?kF_=E*>%~%hiiIQNQ*ci zpW!4luQktLLHL%}|J--cb=Nj!y}AFwb)`n;Aw#=JQ%0|};@@2P-~KOm-U;LK5>HkX z;+J5qZ=>Mg8HEq%#Nzsc1at={OC_vi$>yOs;t?Klg{~N9S+4W4I_meHOkNt)A}&q* zdza;)*JL+N^Ud!5NPk(y&5Tr1^)w+Z3P7{dVYL#;2$Q|~jNQ(e4 z|KeNdoq@a(iBSTQ^}R|kKfFpYqG<3;&T07=H&y`1nP%Wnf6XB%ar%)*CUrBugobwx zuh#jktXFG>HqjBnP^?shiVa<%71BDt{ch3oc)1&6FRf>&jse0MpU`%$-tXt-s2tcF zOS{5b_&PyWTgH7TEidG7pZYg_IW>3B-+F&C_ir%2(xgdNsAS`h3QV+_x%(7$U~^?A;Tml_bofCxB!I+en?dp4+b)U zPUgRRmj41X{v^&%$PWS@GC|RJQ~+PM6K*@(Nmkv#(w%YOV_>`!>Ek2T!WQXn@_Di^ zgxWt8p1OyOQCq!-xD+MTe2&A+7Zdm1N8NH~)AN0^E{S-WD#>n&$wg&Dqw(a4kY>pT z{<(aX#1T?Mmqk_Pw+SX#Mza(G1OFgvZKdftcx*fK_ax)mM#lmuMqCEl6GIK|U7GbB z^BaD(t}+nM_WP7qXP&tE6zX_;iVnkB`pPSbTOTaZhF4B9T?NgwFXi+Io$uuX?C$!q ze`^P`o%4Mkzypx&akJgoJosbf3D-TVU0H)>**{U8;#b~28yK7C{+&=Lkf-7P(68wq z_P(zm&(BI^{yD@bHlWP*!eAAn{Z8#C^=3xF%UdD!UXBqe=OGRFx?18yp!YyZ+9y|| zyc^ao>~_An-!=-5|wVe1SRJ{*k#*l$% zz%Tte{n_)anJ@Yiyn@!lk%PVcKzIh>zSoukbVX#P^GOX!U%8Kg1w-+#2PF8onC?*z zpd+$xanZb#pSl3m!ONC`iVnFV`Ubr$s=-xsO>ZcpgliKKhesH(35x`}fXwsw%InX- z(Id)%`#{uF2{ucR`z!V1^L=^_i6W5ac0s42wS_DPe`3^sxB19Gmw^cJoQvF^1n*zK z>FSzS=}|k0BU2|=`4sgzf7N8VeW}5=jSL(R;}?cMG}taWjs9N%G0?|3d{*1>EG^Fz zQoJ)aijMVAWu2*?V|jmRwA$YUbS{tO!ql_9n$9(5=!x!FsFB1NAaY)NNRMiGoAuUH zscP|8Mul-Do(hBf=ko^$Va^^L{T_F)e$PJn(v$cYgM*)OzxU>r;`K$h_gaT0OKn^1 zK3bQDJDdrdblA;3ZJZN(b;(AbVtqeAmnDxM-q?qghi6vgDUG?6`X`P#&J{C)@yO4F zZcJc^pUAsXHW2jq;$z5lE$J^h~owtjzNp2o4iT{4gVKig|=}g&((2 zs?m9-dBk(^1CX!UOlpr2yq6r68Y+S2fKIP=WxrdNt(^&-(rz49`}*F3!p?a(u%UXb zjR!pc$V@3;yv5;-_LYj2sj?C3IU~Q=*IqN>GI8Mj=>qIltxbZquSm+oQ`bz zO-+TZqXFSuOkp~oj&<0AUI2~M{&IPr>!Qq<3*&1rdu0swhy^WYXP5o)9a^7r1+rL$ zro@ta3%!)mZP&ZT4HWF*JBAZE-b?QdE0RyT@>>nHR*(!JXgtfnkgbv0FHgAFVmoO) zE(G+5-cRcUC{AGhu6w+ap?IlIlX;3$JD2B2RIIiJ=IayIIM75Eia$Yx)>S_rh^z}1 z>_N|`VPDOecl1pi-h#ZkIPbfn^;~!cS!L&(y2deYxE{-!R* z`LDi4=;1RlPNj0hM8BUqP6ON#W@FP(&?1@UAv?4&dx}eY|pvOkvJko8iLrAaSKdMaE9UnI!Ki5emp*>+-9e%$nx9o@i zgQTHM(>`Rw`R;QGGI}nFE=yU5r?2%+w5_qA@7l>Czu-&@~7fH zTnqE=eUH)oQ3Xn@;P>QbU%#)Wy8P9_KkBUPdMNUrbBQn-qBEae{=H8f1j`6-;>y+L zQyY0`C8M$v!BMq(4wJ{I%_(eOjClb-o3c-+pVy%`bHT>40q|V*Ba|G3;=fyli$$e}ShPe@R>!t0%_C1Ag z5@{CB7n#u#>YY(p_!)NdUzskE>bzUiE}*!a6ZA&qQ6Q!;A{r@)g>Jd-gHe#VFXdX0 zAGL%7M|cR1orSqjmV&eC-yhaRi-c?NB};VP-)iA}!@DS(NyZ!89^=)!wa78|gw~*P z49q{3ib%jW4!ekBsD)nePAz{zCM&<}D2oLFP?sLkOWCnyKoK(EbI4jQh!&gh4W#OG z5cas?O-c1yFQ??F;V%P*klXppCZ@L%)fH;Viv~jy?DMJxqRO-B#TlL9tU5RKjuO!k zkdEVB`IRL{v(Oyhi#rl`z(XRsSDGRZaNY~W8YoI85Q75@DX^>Y{JrNXNVTc0vtD*r zD=Lp|dQf3TjA=%6(T~X)3+o2<4CLaxdGFD5XfyN_?-F1KW@Nc(oV73=+#u8XDv!3U z^?lLq0nql`<}=rc2Y}#O?$aNsCD$V%6oxlKD|Z2(S=U~+dcdKw!wrmj^ZF)v-n3cH z*wOJ1=xmSOo}zrh;j{G^?}q2x+=UYWPX#LIfNtS!FBH{=hO8IZ%sRt2;L$CNg9f#78P21XpB2uI|*yBIT{)7hqIb@3aN|FyB&mV z2@9riB9P+~XOxLl_`F-?ttDNK1nSRP?F5RFA%j{>Z= zbzsPt6ySE@NSemy3e7*D+lX4zSvi3oB{A^e2^4>I8nuBsqM+pa%zH&OP@T`~!$*1L zZe8KUEpsf8!hA#Bf8!XOAieZ z5%d3n0kj$4u}H?Y;E@qpNOIBmuhZlAI+K)<=r2afkKw24f0b!{T{aA>xttsLIk@$a z=Ysa9`CVPazO{OdzV$=A{GpA#9 zM-||llkoUEyz5_kd3R3penmkE!a7}?^T!3%+IoB_7w$&9f7xaf5MrOwt=mUi#1B1V zo$u1+-Du zM*l+1^zsfvH+dVfK(#?ST5Bi$&@Rvm{XE2HJoT~xO7E3B2AE#u@DAwx?GxUA@_axb zBia>J=XwzwPsv zz{(_Cp0z<48X2V@ zH04EkY6&5hA%E+Y5L?Pqnd?E#>}RW1n1NEGuhAShJP-W5*UGRn2~|DS?xh(q#M)o$ zJTFp5z48hhCWkQ=4%kW)q>go`*FzAUhhl#8UGw0vU5>XWO`U(vm0n~MU^H!0VSMma z89jug1tOL>KN{fimSsKlRQRYmZLJKd{YBu-UfOINJATFJY%- z`gN5+j<>gdeG6^9EdXdn9SYia{UdJk0mxj-8QJ&iu>i5p-}@!a za9mNpm1S3YY%;K@NWj>xRYLL(T}$fqUg}0~_lZ*g;x=Yo+%u8YhW&{VW!BXlsKsqo zGHqHyV_-YSeAjRk?@h89-qVn)LwV&Nd6$Q@2RNI!$YBC%f@PbPeS{BOPq|N`m$Ek7 zE1v7mpUqEuI9-xxBG9e;{65OHw96?RHPt?2`8>hOj)Bl37WnI1W}|Yt?@TPQE>R{e zu|O(AFeh(v-$3kuydDoQIr6BZIcZSj)jUz#^Wq@}EDQg#`-0$s+CjKJoWymABI48( zi&k}m4^;}EMJ@_&XlFDarqn!7UOHgWSFVHC{@9%R; z0`8fSXDT6D^{T^uyb7uAdFw{neULSw!QrB{%q)I$dse}j;h}R&_{uo!9)$+l_0!&<~*VJwV1gQ$jxzQb47fVVymGK9vD%G0vBk z6Ouiwoi^VZRhtW=^>oijPax;z%}sk=el3<|l@ z#P-%EuRLO|^9w|ZVSc&$08}F0rv)cYBnUbj`Rd|wsW+v^(Mb3JYU|jjY*99+E{;M`z%oj!i zpNQwnl^upxFUy<}M)0Jjhp&_mk2(Qlb0qf<_+bW)5qh0Nq5JK(R_QN2_}V@rUd|Np ziex_V^h}i^s0TNIWwLurNzqNvE#e95dG>D^zMZ?vnc(ix)-H?;R7Lc9C}DHD+%9vP zT6^Ay%5u%+~gO?-@)7NOr$NPf)t<)-){<+N#`Z=jK0E1KiMIC=}$nX{Q zIdB|J3I~&aH6zppc$AcQKPE3QQt9>di;9-O?f&B(<3cD5r|~qm`b0sK6-|Dv$9yR+ zi;`mG^3@gACrmEEep3-A2a`v+_G)2B$=rI+KmN$`ciVikgN?;H-oSpWo7cm6=089?>Vg6_EASb$z+^N_w7A$_HhUB88?v^o7T8#k-# zieC)o;o)Z`6_rhuAiV|5o*}MK5hTb^&G0n`?c|8n^=sI zMQH`^qGf-A*N*;5peN|FXT^E!=1TT3g#d9Jniz1RmiWtshnVymAX+Xl5JQLa``0~O z4Wsf@0&(E6DxMQ8(uu55>yJIJdy#0*{fk>LmNfyd0L3jkn0}fAULB=g^M^pZeI{#v z!1n1_=`&)Q4B=|J(%;Hq_6(7TSBNf0zy^90u{h|j(RF95;~p%nOuV{Q*xzOop5wI; zf$v0qZ+W!oANULWChhT}z4}PeezuOE{^STS5$&fZoK@5HlPb32OM3z6XiNDHy>%~R=81lKk06K|1nX(3T z#)`I!V7w{U&^w_=;))B;aN}WA_JNh7Erl)5wB6t@@>^i&!iQPbTFfE0D;yA^gN%_N zdu=%#?(6}cVW03RQG1Mm%KrDNnuc4y_aaY%76|*BB!D{kVT9t}u+XZ1i&x?2i64pu zjtk>TPF#DBNm0Yd0>(S>PFwtW$m`g@o{8zc_f~VZP=qS9e)80<+{P*l1JgkB;b^1s z60p1*TbO6WvUjC}cq%qRuwAS7DwbdG7jp>?9P3-Pnb)YX@ww^6CH=^6gKx)H@d6u5 z%o@YIN07d1&*9w^-XHf1w^!C$n>}Eh?sYp{zeEIE+v@wAOY5|T$_FU>oPw0fo`T7Z zN$^-Y#mCWIZr^SJqYkDeN4%pqntymP`!|rbOlz;Kqvtxoh^nyIZT0qMc}-!jhXZ}< z+T^0c14P>I4_TP}YximF4U8?`wZnkR;`33xe;<@#_p9iu)=Fj15a!`Y5PQcnc<1Jm zw2`>TfL%BJ(GL4Mn(F|b;S~wD*4RDPd6>oVG4jpu(~PbR>7l`$ z59R|(-`A5ahS!n4hv`Fj`OXOc;Safl%ckw7WAKPv%H&I*N}2lls}z2bx``p^dX#Y( z;b8c9h1mT@SJ}re!MTWjO=*K4*=a)?`_mkAL-b5=ak7n7+hHBI9^?{=+h?xt?J^uY z;da?`-XtmO2Xi>~{5%IQu0#Phq_Xx6#XO*Vf7dIQ0|0NA4Y?)8xia`_kcv+p7s+|U$4Ox>FB(#F~x^`oN}WK6tYI<^1NqL zf0fVY^klTrdH`r}T6|aY!#+y3TA7|%I|Lhd6JC&pWQYb15Jx?ei0|M01}zs-iF7Zt zA!Ya4DmDn>G1Yj~$L21FF$;nV&U;PTlMk<@RI5e*>CMl3B0qZX5d65Cx3!8w^-PWi ze^KqKcw+G>#NHmP>bJnX``f$GXChoYxbjt*1T_bI>8lNlS@1=-MU04>pUoPROE3*P7)w?{U(7D!n)9N?~Z2!4WrCNFUMpptO#(p>l2E&&2rB$ z9A@l~e}lo)Puj`6*ZCG5-ENP{Av6&G;M+s|6(N?rvD#Vl*U;W4s^@c5sS~G|4{bl$ z7E&Xm7dPg<1_IlGf67Sf#4#DDMEj&<)UYNmK-i2!y;thJuip4~97I-7O9l_(*;m=^ z*#w`o&wjizcfWS)&reWDu$MC|=B79!p36Fu=F1WGiH|1t;g@9f->RNUZh+^upjB^_ zsX`;+Znv&wf#{e7P`DLlj+-ug55Y`F*@x;+5MewWbH zw<-`qMDDY_9Z+)vqzxiNrJMuP4zw^Dkr@D?1-_dTf;j?pMs-fKGStCFScqH1xV ztLwin4#e}<5+o5%Gr!0q^j`=|sF>;e%(yH~EB>@=sQ*+sn{0-A;T%LaVi@HndfPB9 z=`;#e?%~W>3WV*Fa4zqg+JZUn!=CZi6Kb(nEmU`#-~B_avnOdj_nEL@fL1y656IhB z2h@7B!=O`7;69TQj>e-JryzE-=aOZCSB$$MMW3~y71ma#JzK|*rmy&NMJ@fZjtu>r zeeAgmozozxKa*Ey-H8h?UNV^#!1PE`R3YIlsmGS3qaWg1*f-;J^+k@hH zl+iNULm$sw!Nrx z{Jgc&M-PC!#z(@pyugvFrbw~;Eq~l|P@4`?i1)1Wo{rG+j2_#;R0(td2w`)b+=D0J z^<=&l8gP2AzCHGh+3a}C$X9Ts38WB@BeU+Y zQWLxW?BFVZM_JK(TH?!AwiCSC)pEM%$Z@~A=~E^V3imffkKoLH-qPMg!;iAB65#sH zUyO+-$XIY|oxOi@{ksZ@Z(hqLmjhMb=1btAm0@xZC4SXx$(UOnq@SO0WT z0pq;V_^RjfyF<0@dJv4Gt->c``JCzfNOp^$i_PDJ#7+pTdq9blJr>`tK8S4=iPs8v zDbBYQ#9?%J@zz9_jV5J2wBk!|PieeGZs;!Hed!l0ocV^l$#F-biMKzft42uG{uuhf zAd})L!_=*CFa|z%i@ZfJmLKgqu@5(m2a(2zG~((s`Mfm7o%n_Fe0lu`c^PB*-TNU+ueme%Ga`GBwan*1J-mLK$oY|c==ZBfW})bewe1Zq63^U9>tNq=H4 zZG@ZBGhcUn!&QVn!@8Vj-w%^O8*hEnaazDcS|^rZc%6^v(d8@7#6AY6_jUUDw}yH^ z0rLR656`4uu#QBkDn5^oI`}K-%M-T#6u|3SuhL7yCMBog>;lE3+8Jj|a?N_7282z! zo2kg=*+11kJ*Ci#&|qn)S$)$nYjmP4?r}?#&VDaZoo7*fC$qOq@j&HC)GMZgU!#K9 z@9ZDy7g*$?DDrHcB`^`xdb9~5=GU8cdGY3P+Ggo|Dt6m`!Dc%KT_scae|>+j|! z381qJu%#JICCu34lJIt*?&DBWt^ntLFD2iS)o{24lnoa*M){m!9uN-gm$nYDaE6#U zbem-)A-F8wK2fjNL;f8}sBJ=R{ww;NeiZ(OUNyQw1RH=o@`4kxRNNk#j|eqz<7@WE z@kiXk0Jxz2D^D${SVKb;JVY zD6>l0!ENte{*d+PG$ZAzV0JQN_p$8aSo`txXozXFGIk5(aMGdd*`PHrS%z}(PF@&( z$>2;qDp8#fJ(%BgmLAvXs#K}P_NFv>0aVOhZKH+UPwP)oRJbL$#5L?DuW1R9!y$)` zav3$ReTolH8j>QZf9ACl-?y>rnr+(?R2`=SM5(t#yY_*sLmhb2i}@Yypbs%^Xv+%s zrIaFkBZ-Lf33aI6-UnLsEYyP)K&;RwcD%6Y0SqJ%XRg?02bU^FeDO83_46l9gAdeS z2t%YTrbSWp!iTz=nC?CDN82B>hV#PBd0!q}`h{D{5})s00EOlAF>SSUj+=F75Osi3 zG8#=DVc{hkQ#1kEv`KhSu`(@!6#*U?-^4d?>NS`*zQ9P`Z;@I6!-=ZdJ$%O{`6&+)uf0EO z^)_A4cynOE5}$B7!Kl?iruyCQ7C;n3;dt`1XbMlgm(qNynH=>R%?HO25wo==YtB*q z+`-%8-L85UR2v?Rc;BZ@bTg$0OQ z6LRJ<@icpTr#I>4YjW|%$9n7w#5QoDM=Zug6TdEihFTv1U#kBeAvbws-&0uVCUg_8 z-TJ#mk6&SNPW%0lVRMwZgUKD>3N{f36Wp`1sR4K`;QX_^{TE|v&(%5^d0Q5(@#KoO)*V}C&Meye-^o0dm8E)N>}jau;-Kdux~|}?WS(xB%RQQ zDm;x(S;0CNUAPMVHRd<<*`f-wC);E_(cA(e+GQ8@m2b8Zy{xuzREHJsUwR^@&l{E& zZ|a-LRDwo#5$FmqjGtJAFZ^ct&@+fLC~O!leQ({44kas_!s_Q09smX4dMn!>zU0qQ zA?LTJ8Agv)-SZ&*_X{}aVQlQvf-rOC#c>Fa2(YdB*Zr^oTNb9FTSD6EO-mQXoY$Ky zCf}y@(H(rK14shgXyB~17z#<9|0BShu%^q07{SmWO~P5%#2(a5I+sIM94oE4K^G8$ z->-{4M=)dP=GPnQDVx8qi@tpo>35VVx0HT;0HL0y;mPFccS&~dTpoaLsJ3g#_}*)2 zoJu;@=x9$bD+$*78IK>jV`zDoy!JS)K!{(qZ`DPnh%z<~0zQ)ze+b{Elm^MoCw?lA zWFQ@tG-{K%FN&>Mo3sz3^*-B490-7i*VDPZ5duVTr1U4#^6MPI@Dy64tz}uHQDrz0 ze8eZp4iBry=${B2{akgF!)@xIu>Yi_@TVmcbBiuSds4gbji$Iyj^9veOgBCds>p%& z#WIa%0kp?shdyWrKK4f3o1#}ZBdagJeebVC{qAGrRj3B(t``!{OiKBTIlKqayDhtY z`32VM*hF4P_*mZHLQ*%=^eyh*_&f2zP+^#h@tL$P-t(jFlSCzyV^6-yF957>ha(>4 zK?pCW_6a-z^!@8UQc|M|&3GkZNKOU5lKhUMxhij|t*3{e@EZhI*Ry}m<@;w=(4K)& z*ZU5Crr%o@Jda1){C6)V-8Y3xv0Es}ltD~Eoy`h#MIm&-Z+qyg@9R03w)XxpRTc#_ z(YjHw;fJVyO;1nz4mY^CB6W+nb=;F)hVXsi*j=i;j|Frq^K^mM7lo#t>rw7qc5TR# zLG1A`>r?I)iS}E$gIHXEMntpTg>4CDe-#a%^|(*6388J$$kKF(2)Ey+KaEuceEfR9 zF_p|b)L*p(9_aCM8LY6in`3-#Z0iy$a7W!jY9#ux7BUvRuj*K2Ca_U>r<@*nre}g-B!+f-)X4o zl3p=GyhZM=4y5hs2BtIyI`6sy6NgjR-|eM)Y1fo<``<@^=#4&@=j&{pyw43wF;w@k(!zw2S zMT!QEwFjyo%sntvIFNPmnaa%J<#<#>dR-~DD|vMU@#_2XVPx*15u{B|c*opIFc+^y zMR-Eoo_MG<<4EPns7X6nWBvKd)ws_EPEzAPc{a1(&Y#O*E$@@Vq%S5b%&KXUJ1XO^ z4n|sZcU*0YcjdiUfYUsY7BOGfo01~f&_=5=akmEE^SWA-c_%MN%P8M);FZ8|m{iMv zGUGb4$;!1LdvD$LyVdwMWog=re?~2}d_o%#CR-VKn*=G)ry+*>Ah3;N+}7;y0G+R8 zrdskVYW3P;j3CzcQF<8gTr6+DjgVJ={)QN`#Cy(=>!m%xn8?UsIv*Uz^rP9r zLBG-D?KkomvM1ex*Y)UDNao?a&vW;R$RCiayrjB!*uLD+yAj_=w7>5YD%e4^WeoAl zU8dPi(JJ)^T*IakbpQ|gLZ0_aIytC`$qQYBU3=w)JIBvd119=OhTnj2zdg&+CrM*{T+gFtxv0-kkx3(+Xj09401=x z$qWL6+#NjHS@gxpyV$;2H~n>#ncx7b+rBnxYlWm2MSQanyuu5WDfHrWuNq`++Fd^7 zkSuU8NlZjQ|Hi{oK5rIz3vUyljzSFS^ZahO-=1yUP9^%DzWwB)X5Z)5*RPwnk`htf+UwF`ss1Nv zD*UJ}p$F_^px!v0L{v=-6ye8$ z$?~sH?VX1N&S7`)VS19ry4ulr>}M*++pFd~4B?e{!zY1*JgkhVs)q zqgVqS7j%#K_syBa`)g`lk=|#%g+JfLgEqed8Aq1uVtCTW%C|{A*hy0Id_KIax)hCw zcY1W~UO=`;>Otq1&DM#?xVqGQWT7qS7(w}`n-Ybn2{!Vie&};pY-UxRcUwEr`4XCN z=$FDJ->7#nuN$HTArLbEMcum1z7qpeB=ptSY|T+oCh|-vpS_2l6DA zZlf=qov46#0<^g3fW>gHc<0wZtU50YG@@_j@gU|sPem>HbcLqY0HyHAiha#2g)c|0 zx<_3&y~&hQCK{M;MS3gthsrl{31;m0jUO*skHs7WGmlM)C@FJiDE~6cC8AyvJwaC2 zec({A+Mk;^@3I!aG4e~H6e9zZ@@WS9U2g~g$z#R`xU-q-~ zhwPJSo4m8SuoHuE$`-2sPyM$r-RnT-y%rfX?AaFEZk_lnbfDtH{G19AeT`)4kM74z zqdbhjO{)c84Ek&dE<^D{0i+jk2K%?Sn44l>x8v@=w&%O^YrN#fjq@_NjO6B}KjYe;aJ2=BmAy^h=c zw8;AxLdW1SD$_T+qfzjnSkRG@uS{!8E}5*VDkO7!jSE_)&lu#a0_GownJX33{VU6^ zZ4`w-v<0T_L{seQe#ZwKDX%VYLEd)1d_b>Pd7J=<)0B7*3C`S zcCGY6T)kkaRi1osTNR?gd5nELDPGqAmMD4RPMrc=nf#LLsCx8Rn-+-$V&P zMOXioktot`w(2#BdJLvJ|K&$H0{6?#-RADvx9_N*xDJ;9{pdfuH?8v`gcIy zTxxVSFWa5Sexbyh7u1JRi&9Ga4rMa$ltn&}AU?=InXBsx%*I~t!mfB*@UDU^w+ zx5KpUl|}!P=an5Fr_huxsTH#jgn&DY`SOZxnl6j{6|~`ZlhdxCx+|OemdgGPzq32g z00`P-zflCV8*Zd8X1)xjdQ#D=(${oYszBk_cS7S<|I{8u4! z#GURG#k86e&+V5qu>ug^`}E&_)96}c>@jJjvr-}+2Lmd6%;SCttC+HKIQa-6CA*Ep{ze$*>~m4a{08Cb zcUE#aFnnRbyC1*y{X2p01NAe(;X$=0ISexx5h#%8O+Mq4Fb7ilqh3}5OHZ#jt8rWQ z6+oVtXZDr@Q#%zxV$|~%pfaOwwD?P2)^9l&{@FH}P2enw95*ibes$-TAVkEyP}M$J zhgo$_`f?cv`E!5ylUDfZUOczjRU&QN0qQ_{zKl7E?M0X)PX1LyNFD8xxU57WkipbK zgwo`@+H@MA3OM7}8DM#@3tJTxa4d3vX;WBNwv8oD1djOLu(TAV3sUczBNeLl{6Iiw zlOMvfSN!c*Pns!7rfqu^X@{qB+@DE1TolYMa3ThEuL#PWXj~H%ywi_t=`R*>BGgCh zK4r;&n>+ZdRc~L1EbM0^U9o%v=8b3P+Vky2d|mZ4K85{ZLvKE;+h{(LA!emkOIh}E zJlwmSB530+i*tVS(_7<77vz~BCQwJOR_TTF{EjXoS)5UCalg(YlNPiESRRNX5h-@v zt}#q!)VqNVk>xcaH6uO?`)JuepgRa**RQ}wH|K++L9NtAPZNR4&Yc|7$b&Q8zueu>`NTux7#mT?Tx6rOL9b!l=HSQj*v14gw3m%BenA7{2X$3OoHvWK9{Wupul>zDDIcZm*5A;->vF|-dFnaPw&?M)L62PD-)Q2t zYP_HN`Tf1_ZM`NNyzp_M%~sKC?|e|NhR?G|UsDya=R6c73nJ+6ko?^MIWGjgz4?v& z4GIb<^od~f!=11nr)zW?59tXRf?~PH0E!wf41c@mf3~xQcvTayEy!c>62)|k)ma)^{7WVBBaQgFbCsTRc6j%oCam1KXx$7-kISc@Hejen{5JCGrp=1^0#Y1KOhdpZ%R9Kxlly zc`DBjB;IaMVUz2TK~Z|?tFWpXNm|KoJIh}?&Ei9QkU4W?o8tKmKRULx-)*+=E1|y|yESzIX6$M<^VpRyr$L;)qVBNm`ZaJ1(N`Epa9PA;c$V%;% zg+;qg3+ajmnv{Yi$9caCBwTYb-5%*j@=HA9wIfkPNNYi_Al9!vjso`Bm1aI_O?f$^ zLi8O-%G~$ep9JCIrStd`jL#|UYm-T4ez}Fh%t6j9^2;6ST8!~Ziwr|_Fi!}j}mYb0H;QXv*%Ifhac)Rk67QDswi=Z9n?$J-VgRJm~5N%=;VJJ9)Q6I_s zz?f!veBR(+vm=5a3@7^dPWEnrNg6Hmu`ZJORoK(|JMHt)Gj94{!_a4JOq8A0Er&5R zHd0u7#GaXZH|8lEwiMgKa#?JVNLjZ;f(-?DB=>q%U7nm`50RzXe%D`c2#;6=G><{s zN{f8R4goMK-f#zH0{o|^=Zx|6{3(D@x{CMIleZYf9t!9y@mS|8j?t7)jXM;f7~Rc5 z78m>~W5l0AJ6YoZ-&w8yGT?>ErA@Q2HOLyLV$mISD3moX0|y?64`l zDLGR;!hD;|CnpJ>RoTNF@i& za36S_XkU`Qpo5=AH|Vhh?Dn^YhOc=G#e`ArrRNW`zP}crR zvKx1Pduru1%ynOxW!`?VmBYdJX&XPi$NXVU__9PESvPg1GiHR4R|YQGqs>f3*<3r3 z(gb?59i@|Wg~3Mic8(6$_K96auEOD9tVT3}hEy%jznfSn?^7y{_}7WZ(f${c@EF+T zJDZmSL}rkgSKNzPGW%0~mIT3rtP_Y~cROUyw_e;C<8Xv9Gr%Dn@VfyEeK7WIE!cp| zG{-el$E31!1&qYEg1fVJRN3PhkG6;`S!ipXydWhYJ-!q2@Yc_||>^SLF( z=Xf9c`k)W}jSWRBXIo+LXX|~JCWBO-04WI4(?qBYRj3K42mDmZFKFU{=MWM7_kzjy z$?n%oec4(4SQldZQqGg@;lBko;rwsTUEhMxm332%hSIYX7g$AnNB&3_d^A%CW}}_& zu006=J|ivQgSBnWlqay;i}rIUsbgcw5V$s$*PJco1s?fPeq9#OLu!vFn=}?~*x|Yg z;Be7dC?@2u!xgXNJ)Bn9hb#sDNzp$llhTaiEQS}PLo!c!T$XKUaj$0Jo0(ojs^S*qJpbzP!~ z)o`4{^D=w}G8wFh;rE5BqzQYy`HYTt=Xc;gllLJZ=BSWffb@3k`7-p=i1Em>+`eAT zwRUjS+h#wxbNy)M5PQ2%aCxwB5+6=p@PP4zCS**z&q~>qS4z9|r6u1HWfoChFCVX) zS*Tz1#g|98KWwiqRn!Ga4&gNy4#qWKqR&hnyM^0l=Zhg$dN$Zoh03sZzj>{ucmJRl z$v&soI(KS&GCwR8!A@6mAKLN-TMH83i>E>G&fIBT35RrQ3k}zAd^(ClFdZJP2u_w7 zpDbtl4RLh4wa#!qL=|nOMkRLd^VGYawMMFQtzQeB42U7 zK@yj9mD)!{ls%-H z;FuCo3l+!XGzQ%D`aNW~UpVredos3<6;Auf^vc1jM*A99h?qW(cfnE2CZIq}qTIz( zMLxCln%UbccTK1)-A=oCqEc}%y;tTrQEG0;?EUWhKzrh&a?pZ$|MxobV(00oPL?NI z{8+|+RiCe9-d@esX!9bVJ=^{&2ha)zvvrvA=pQM|70v!;tO0eM7dHQ;=aF0HhzRYJ zfG7*%Q<=y+9u@0+KAT9I^}_9eLX7FkG_Chb+p4h|0s6}|N^SjA(9eBdOXQ7?<#J{6 ztzMjCy2ZYT@Qvid>_u33we?tDco`rsi`4sMMCA!{X3N4cd7i4_UOImF35GC+U#;3& zI2No=mBkxUT7GGBox`^uZGHj#KOZ1Tm^vq2@W;De=PZX%8Sr|kc9rul1DxmZHyIS8 zHEBSJk0pZM-mJ;WUX~`R^U+s>99WXU-Yb;zmQ}5MoQTcMH!(AMM_KArFIdv&Xx}yad?#eDJ)N(7=U^Wk&j5T6 zj1-C0WQz$`Wa?nkx<*bWKA)PSLF0JX8|B5vX3_II+WNPrV2t&O;ZzXkZI z%T&^@#u2=SeO0a(=9&(CVID3ar)5{$)%r#yw|RB>)BAy~Iod(4$$7~FA#OfXf9P(4 zemCM(QRt<1n^uO6mXeR7_Co}Gj0?wowMIOXB$IfD+lau%(>@I;fO>}fc*#vQn8|R~ z!V5h4yme&&>7HHwU@wDer^oKM{;IvBifg%6++Up#>h?bJC_eL;l`1o3{Cq(GGB<8;_7y4Sv}$1TT9{ZiBmKV2RE$NL!DL<@lXmB|b}!lLQP z;hv)5ProUmLEFiHi{a_b8wt(d3b8(})qghq@GedL2NMPEyDiT;yYDCQlS;4UVk?Lb zFBq+js?*Z=XUmlbZF&rM^q}z~_?d|GdfL}wNLG0ULo3ze?=#%|Fkaq^M#qQv{#{_+}-3+9G<< zd7bPJ5*dn_Sf~2SuvNRoKmFL8AHUaF^C~CX*xMdk(T|$Jk<>$WRX${`N%YzGzCA~5 zY(~Q9U@o86Md2Ne$oqYAo5ppYe1L2g?PK_`@P#H%6j0*(x&rl;W~`yp0R~cKp@6lR zK4x@yXh$zSqzg9m5er*BO{uXq3D(|AjZcn-wl`x{q=C5i>Kkv7sbil&y-VBUmF~F< z03etOfD+_dafU4OpM!)6KEsEY$i?^d;&m+kfuAuG+;Bh$cP2c_-%s}-%zDx%FFd~8 z$Jc1ULr%Zus$?{L4cY)#f@QY6zrf&V2*qzWY8*d1w|S3r6Pr&7f=Kqd1mHupp_J`I zCV~eMIQzKghx#3;KEE$|r~S0rJnDv>NknGsqqMyi-yXSW)bYO0G|#tylBw@P5fvF(=2Oqurm|# zl1z+EW^EvGkE0tSE-WIWdmF&PHPA+A+IXo;=dk=@3drc^aBk>J3CHs+RU@xc(%XL6hO;ok&;vo zB^5>%#V05H?QB9=GrmNRI@TXYKV`V&YHh9HPZpD215yvY=z}?>5Idb?hyA2P+Trom z2Md!%*N^QamkKCb{2nMc_C1*NGVr&T(>OU9kMa-82iGF^8OBLBxR6fppQ#T?v~#X! zlw$mrNB|bGMNWS0r(n_C+CuYH8ENhLr*3{f)el5ghX?sDh&k4um7Gv`Bu*y9z{GhG)(@Y)b|g8^gn7E;JhYQ zmC@q!hx2ezq1C_OPE)$XmqH;A3))qSf)2&TMyC(WOx5!x5&1Lul-9M#q1GD|z<jx`meM&a6p346rYpiEfm? z=EN+BK9sCReW)jqHUwJ}YJ|^o)VeqVac2{@v0#!XPmUv?+HyH_nSe36ZZcn)oBMhc zuPcn-L8fN{;wan+p!XQ3AIVZcKc`>mXQYJi)iHlt1KY zK8Ii&h}|?TvisP7%~an$Pweqq8VFu_H|2?V%h2wB=m0S`?s+=eBonWNF4_0rR6Zt7 z=|RhfDcrKAYrTS;V&LQ#r9eI*H6A}zAH?3zD1hm7pX`?jm2!74oOk&~H>j0y>WIrH zJO^8Gr@zT9IsnfM7dmiHK*|J%j>zour|#JgG)sd|TI*3RhU!6C_3Q72V>3d)(pn+0 z+ETP?97xf;_sw)7`1#!3(xyvrUV@tjkk}Az<=Vn;98Poke%Mo|M%N5@HbkS3QXAub zdk;DYH~i!leu}hrA@aYk&vqUn;|v`BY$aGfHbnYEuKCwy6PXRl6e8ltSaUwO^&N9g z@1L7KOQQE0)`WB=pjc{1rQk1gHJME-E=p#5x|?Tumr;pj1lOo>dmcagkZpK<6K|-U zm?=b5Vp#)ziL)(E*!*JGAS6;Gb&2RQKoRrcG@1HV&qp;pP#nioa=jLKpAUI?q|yfR=FK;PlngOr@%K?%*tuLNCP3}9fWLP z_|L*~>cuXNsE_^B&v_JL->kHF(9s4r7 zD}s^dp14u~D_*XWYu{hf5oi0Ha8g$^z3@0i1&H?XLq42_Hrz#y@$j7QI=M1F@x3E_ zHtdrxdl>T|ZuI$01^!+%Au!8y9{ZK^tL#?-sO^sHDxNiaV=nkCkuoeFofM01aMrK^ z6Z~L06HA9VKc^e*cHgwEO32=kW@U{~_UyU1;*pJb?o6Gz?(LU!KQ1Oz1kVn^*#r%W zGi(iMfryKX3aKdd_zJJ1n9$t?83EXWLj+~zs11A1J6PO)RdK7*xIFW$!a)MR+v%-dwhj zN#3O64jlP1W`%x8-3*CPG8v1IeoIHx7v`=;kUa;#zApVXOXR8uR) zwG@}V>t~T**s|y`*;c=K!MPsjL}LsA$?l)<0pkKm{fNE@Bn@mq(DsE{g~m7z13O?4 zC3(=m7J)ijW{ADo!K&`8e9}i|0rC5I9B&uorKcD1(&552re7c53_hhrmn&H6&1>B$ zMOW?kL^eyTn|0n*Ck;@CTe0ULkke|9%ezE=%!tNgG8wJoF9= zG?Av7N!?d0)$6Xs)4;hT?E%#c$a+3m^8Ps2UK(_?A3A)2%k$^G&q12^uZDjdr*-)Z z`uh1+_hEHc;!1yrPn*{{7vUf$0W8^l(Z{C;+kF9EMB3c*CYiy5m$mDqn=M5jPG9nw z2vAVL?p;@^zJEXWNQxPwt&pNH!>X}=XT9*EYb6yED$;SjDf)Vh&%_t6&*wv3K3rFh zr|?x_gW|fbh|3z>)5NN$lmq%jDW(#1?bDAz*ZAeaOVERmK}!qmG-kMIISl}%V40v zfAFWgeZaAuSi+gqCDe?b`boo-eKJv&``BkSRCCI`*sF)nDtVwz+Gu}E#?>L>Uaq|h zwK~6%|I&$#h$B4?xyJe>JQBcKI#C6f7d6nhw_&oUeIijll~Xy7F7Q7w4teUyvm}^S z`b_xui`j==^7!Sn*uoWYg}<_w3xHIGx@#w`J_>&Wi~&W zbx%e^#nw7r2$raRPA=MbziTJdQ$VNhCuXlMcrRrON=}66jl<>bSa0@|r7_jLh zpe-i2EPM`^=1ph0qe`hpVO96p!Q@UQ?eU@8y=UC^kIy#zdOhU9H#a^o zR0@M81iyE%_kmnU`fj~X9}Dg;=zxmvnHtt*jtaC6RIo|*kswNHIx4m~=BWW_|HOE)LT|ARd5qfc#T1(ig2iU+?^5ka*E|7%C#YgNGSJ?D6^`ZWxZKk0wd*3_2+xp%943Kf18?ST8C)qyV zKPLsZf^Lhy#`3^;tYh~DqGnUGoL)YghKUXIb(@|dDHFB%!ln#%%lG3Ja1n{S>gC48i^Cw?;BN&G=U?rKdnP))Zymr7hdK!(7?v^ z#4ARKy((@Rt^#5rBeQ5*_kJIoyY%G^{&~%tYEmKvQO(4mpU+QZ1-Q}kzF(CweOTLH zYVgV9n6%m}tV(;zHnPQXNqoO#N2)%m_fwxeRUIN#e|#H1LuO8lqD_2MRz2M$U^p(J z_i77zp)WnpB3!ox@KQnxo43Km!KMf@;w;jKS-fP)Y||fL8jNz+d5Js7&T9eTY8mljGTxXG3J)E$^^Az~YjJ#OpCVyD~OxnaM zc_Y6w36MS77%ujV%)afJrCbSkm;YbY2#Cl3u(_WBX7zpiDx*)l%MM_m*jh zIeDcI##b+CN<}vj;~t|K@Th=X^n6WMk~0u}S-weiuPn=d ze#-_K9mwrPZ$XI?>I6si4;==sFOR>CuEE=$9KK1dioz=okix}1JmsCqTI*KGqyJjii3Q+FqDq#R~NOa-u z`##m#QlCpp*MH015X{o-(#Ag43Q0e)yfKuI2-_5-v4aB@+4Wc6cs`@>*3@fwzAlTh zWj@|y@Ir9c0YLh+`3OJaL>~@Ober_!J^^Bg-}_F=YnxOs<3n>0_17U`0Qd`MgxvUG z*60UDky7@kO8ZK?8VHba@Wb`GkH2X>#O;ka^1qnAZ{34??;lnP01)}AtP%X+=)rvC z@NegI#B5!hjJQb_z5Vv7nVuK!;{Uq6AMMwX z_}HxdB^;^51JWB4l{nn@)0gTtmh?G7Rl);G1a!eR@%QOnZ##8kzo-|2il<55*D__{ zupA?+9|N5;O(VNC{yB8T&a8BJh8n)KDH(w)SqAJ`MzRlY{3hNg<9vrT``0XY%OuZ9 zc}mkqP#>@EVRwx5$g&ckNLB8E-m`4~E&ZQxJ35zQqt!f>rzho@-{gY!hZvYYqVoCi zF{;hM1(tyB@%F^txb@N#K_g!Rf?z~UlLsO*^KtEACj-bC^8oOKUt)d$*D+adBPL92 zriCAReUI1h>=NRxfmKA5mtuX^?D$ER51f;GVfaFT_Y>Vw0o zmsogn?Y;hhYvQ;28u`@y4D9uGhx;}$kB4KX^(EHCH(DH0 zlw3a9tEgnVa&nf&N-ix#RqB8Hr*_16Wib>K;x&s68TOqhLdtSd9f7e-HPzS!_>k9Wf;guSy+@oidsmNhn;EdNVMmtOAkoPK=cbkb~C zGKJEE*r_-*f>suk4pz5ndZR8d5dT38S_@mMWe-8OesG0z$0v6+k!12MAx`-Y=$XH# z@AdBTS20)jCiB+C!#Rdjgg!>1fL|PTQafb+=XD*mc)91RbGe~60S^!fH76a#NYslI z-}1A8!ba&%*1`kq0Cy1*{SxHJ1~WnL}#45P~wJ{l2d; zkqeiU&9OQ^3F3HMY{9?Xf&+w`xXnWVSn{K;C%D8Fd%hnDf3NFwcf}Ris-Ko*1L(C? zFIy2+t@C%$oPa;9&$Dx{ac~iR?CMl>ez7mFu)EN7Ttu5;1d{mr!ExS&tfc+~O@}n1 zfEK9{(IV_o${xSXFdZGI(VN zoFZR-zf7$n$cNzcVKBKVSP|no8@6%0Psq2pO!ytB6^Gk#?mjEH&l+Jl)`D+bNe-~>mCjIW*T(7Y+!rfqMG(IA^i~~`cvcrE{_vQh zSk3Tb0m6`ii2~6amKc2vgW_Te>QNQ39*eUK$ z0EmnksU415`nJpAe({fVN$7@)3Rj#3_ram<{<>4dVK^{wjt?Hp>Vc?}MO7S=c#K$l z#iH9Q>Xek9w@6R{MTk+o7gb?Hx7}@uw+H&M`*_QO^3U89(|?RmXMNbe@QLlH9|_E7 z*&E9}I0Uf&P?exABAeQ~W|6bz+%(ywZ~F=hk4YkV2k+CSAFHNG8`5l^e1DN6fa*Xb zUymQbO18pjXK>Tb!rCIl`>1n9EgzrEtuW@*qhJluVVlDwkLzaqT!m}c5xBe=eQl%r zJ{;fUVSiUL4IGgNA={tWu|@L{AmA$CDfjl{ub{f{#mkkx$Zc9)-}^EZt4k&Iu{Cft z?USS89}Z7WXZX_v8i~gv=ZneLUrYDo5PDIx2uqYR-cbppQQBC7aw6CpFwZg zW8G#`a2CovABjoYiwParj=i!V`~#R3=^-d+gTBZSybUM3J>@%rj*Rvhetg??C7VlY z%`vX&*n$^A9_cQWOnpz7Mudn}ta+s41vtkSq{)f4qZ4XPedhUznhff= zUvY}%bEVzHg|0>+!dTh;&NV-8^o83J%MXmUzt!RMj=Yf6_CfdDm*`uAIQ8;{?V#_z z?!lk2Z11Z|`@cl()awiT^5bxITEGtnwS0%kRqtE&`SeM85PL89%cD;AX&qT&XPWU( zKLi~WhzTmjErwBT{aNx;W`!=ZdE@7P`}{DcdmGiS>J+(Jh2b3*yHK6v80VO0Seo&e zBr?MUBy1hS_k2`@&9L(pDaYzdAKT|u6|5$vq_5NwQnf72_U?e^2S@mLrY!Rm)6B*1**D#N1!;K{~f?2yiL2-bZL#qwm{UsDuX-=X_)(MW^!mCNp$ z!a*~vj>$#87I`PaThh(vp!XjFcgLTr6kNkU+P|Ih@$+$>G37hbIy(gK5GOaTWh}_iJgR}}1 z{Z*fpu=Lv09f_FzV(3+B483Smr4O#TzL95`b?XysUp)q~T%DL!9ZA!Lu^(1KT?(Dg zKwKYnahFMqp9+GYenrG`rIMYQ^cF1C_ol~u_@X-0hik>Nqj^9EJaQ51 zUY=n5^Vdv0qlZbnA0~p>8}he|F!QJ1@8RkFmTAm}c&o_GR35kF0pyVKEr_unumM!q z`y%wItuTz!G40dbE@lCgG}u6otNaH+}IguENwzOE~bUOD8?Ie_V%s& z-s%Ko0exr=5tcD_9g~W~vQ=q_OY>$xj;m{#U4IUI*?&a{o{?F#OwursLmJA)?g@UD z=`Ooi@019*3vqfq^_e@<8>RpyaE;IPZ@yJZgiMACKj07_eRGMe_mY+-N_IKj#}C3w zDG#zlYFo6(?RJj6LBuXaKI3EQ5|0x^0mx5cFZX62X&TNa;c2 zHk`Q1OX@GjcQf2x!%36dIXM5Ypu2;jo?Xb&0BpJWJtxoSt4q@ID+Ifc5ncMT?ztlK z(ypzFoiE)~h+eDmk9SU-r-ZYi!8Xz7CgdaP5+}r3e)ZB)23P3Uy3hk5_ zWt1Qpz641B3V1CS$su@_Bvib=hnWQ_6b!eNzeCY^*0BP~FL@G4`TJ?57qZVj<#H;C zeBB!(;bEGw-6oB07cn(g-4!bk*1P2Jk&)n;E!hAxwFK~TX!cK<#`mO14vz3aq;eg>_mZ;0h=FrbTnBzX_6qK^ze-N&hLwf3RBT1&Uj;GN~} z6@(74+wHnO=zWOQ`9P-$*s#q@ZOIk@eu4t%EKF~LBKT!g$> zx4WNt9V`R`d*3^FHuveNahj#>VXcqgr4ujzv{7yAcc|CQs~?8HNZ8?qnl2$S@GIxAA7B51i&v@tRZ!p(Hj9`Om^yz z;o(Bp+#h+RN4iS*c4Gk{_Zf^WU+{r-PKVqx7M`I3dg}IL2L}=En~#knAgq2pnXG$j zMlsb)F3Xi395VN0KWL71U_7DJREhl@iO-zr@X&b%;vN5ej;DsC6L=^=h}41K*RJRH z3WtevaGuzGIGvo=&nLsoIljW;!YPLz6bT|#4ooQbet%|Pz=d>mG<{R1>d(ppdE@&E z;E%4n?e!R744$jA)(L3_^HMmyq{{nZ=-1(uyF}z367RZRQZjP)0giEyOYi;d@eafq z^~ObTf~V(m?NvPSx0SjAD&rkmH~41gY&0Q`BFw6yQG92b0s^hgDk%5{=OJ@PyOi|it!{IUhy|625%4Cd|@Zth*8e& zL5Q{cl)tyld)n;d=e5$SKvf$hm?G6VayUhV(r7jhcos`6^>Ib`v-?_dZ}^*AyKhG$ zYyk%(hD=GG%k6c!T~5ni!9x=B+H@>HGWNs($2m=obqHA|se|jHGmf?Pha1+iid5XJ zP}Pw9{WI`H+ZgPVf+HnZungGf&+>=P7uuK0()i=xLMB8d%w2g5v+r-y8r>MB`|yG! z_tZ&0Tyx7jY9WNkd*$viu^k@JVcMFo>w)1*H%TNnTiy#`;C)OdrtOQ6AqM;((dP_NL10ws}NLA2w!@cQ?Ouv`tqPFA+OY2>onYIF~{1=kaEd?rNl4v(k(p+0t;pzI zm9?D2D?((rcb8j3!_zb!cac3g7H<%xhfuiy>F>DF?xc4xS)Wcwc_Xo~Rz{R1WSHdRHR{0^W+@Om z6=S)1MjJS5WK4Oi$zISna%fnume_+o6|6XMEE#_(FFZ&&zT>A`LjWnd_0c)Wsr`8J z$Yx$F(vH)%H2q~9F7)}=P`=B(uIXM1sV`ThpT1ngnu4fU8LnYUVJOd8z+xMX{mVk{ z^?>qPD{G>@PL>9X`BYvh<9LPXULU|6cFQKaJ2={sD)h(tK!EmiZ{JfmKF&X;g|#kL zZXs?jHuW9rxw8+>9@ox%_-$If4J};M3iU8=E*25;2aG)28Na$u-|tB1>SqQn8mPsR zl>$z}4M{y!l0UVdKvh%bN1*;AXZ}fahlI}Bu7B$bJVTuxO&{pPC0wU52%_nxsZZhQb-=dS}>i=$l} z(o~A9**Y{;eW%{SOlty`7M>OI0KoxW44ge;v~eYPRfhoSSD&x^)iD-2knpC4CBG2? zg_)5!e-%moa;n}OFDKf++mp31v&s9fU>CXN*6D$ji>PbT1{{}H-hu()O%Or`J*iMm ziqsxgihq!#))2th{prm-rScP4eT8S^Jg%^fQ{J(QD=UH@QMk5rxMvQJ%SbIm1}x66U*7PFG|ZobUEgS1acF zsh@ZLX|VaZ2}fkT9CD4biv=z}zw-?C_9^}9UK-dMImGp~%aG=93W9@otlt}6fqV7c zAS9_IrLY&f_Z?e-$r~Yg`ToiGW0YuKxBE$O3q}=jz8lwx9;`8^JfRQ){6P#^a^9x~ z3md;=Mzu4L$>h&;oCi_4ZVk;Ix!BqHde5AZn(vEqx>t7l*OSGga*pKtQ4o)fqf*R6 zf}7uZ$=7Kz^zuf(3gUN4>sUTOrTb)4B+QqY2+*lubp(86Y$tT^tm%y+fEneGbJd7Ranud!r5<=pH->xX0&|VPiF6p#Vb` zD=HO)3#%#W=pP*tjmdV3{*v8m{(u&4rXfoTq?)Jw+SK>2P^%BK_SIay!;3|}WYxFz zcS^Fkm;3BGQ%q6+a1%QD`zZ2A=dhT-R+L%@R;N$t)CDZh_LB#Go;*VUOI)NIpZ%W7 zvJbBB`;*#Bepg;D4+wGzVpO=j4P_JiL~38;n=NxQSqWFKw}dCVPk6Dt806M&^VanAu|&E8_M+Xh=eOE`Z&#-YQz2w~)eKJ&vwu zzc476`Ft;C!FXG2-%-Euym>{C|pePkf9Q53fb9#hAj?j(gkZyl;@VEdGh8K2et zGcl*z+sLK+fkp1u8)B|gu8!vk@>ZI<9exju{vc~yB~v2r zl`NOA%~t$F5Q6m>fc^Ps>SK{Mncrlb2>UFg;TQAjxd^+kM_1f^*ffTssuYRU5SJn zQop_Tk2!azC2r3Mt%%Pcd7PLxeBtHz7fJJg;eW62#7}VmOf#`QMf~w^zpZD-cx$tW zJ@L7CF>hBD`ep(sgkYI8?|i);tqd*7Mmrdf3=a3)FH~&u*{Kx~SG-nb9Xite{7q!_ z;f;0@#*^uTz3)&vnO-}bhSwmtN4|VR7GdtMxPSfP3li1XA>L!`6z>5$_mf~bV)iNQ z>S-oK-;wL|$r*v0+;m%xQAIQW;h7-wrZh=(m;Bs`CMmu`4!sZ@!*~(T63e7^zuv?r zJBp{YJm0^w5p5fa7=_2SJ`#3AFL8vW24%b2$rd7PzI+<+W90VB-{&*9wDDuq{d!ku z_ZC zvRB-)OuDM+C?}fN#2ti)+nZpzbAkX=EZEY@t1+#Fb*(^OI`_K&2IKE69BX(gZHQNC zm`uukIB1nVv!zf3Vtnr5Mk&+2aF65X@ROd~VskX2I{JsPx;LAh1aX{vD6H8GbkS>I zrY8WGU%}_2Kgz~`tu24PTImOh?+7KIa=&58f{Zldc82Z-xppLZFwp>@1`VI;$ywIE z9jfkz!1Dl-%0~n{__mQZlz3YWObSuBcRQR`(}s#peGuXaQSjF4I_6T{@vrr7zfJsb z646!7-15J`8@jK{h$#28p@$19qctwIC1z&70^IcK(<|zP)X@?=d7znjodeC9wCWqT zu67S6(1Jew#gt}w$v+3roJOdQ&Yud{mNf!49;Xx{z~3Bp&usBXlIZ!Td(Gf=r=_fQZa zuEU-F(jzZ?JkO#~cUXz6*|0{F%o%*X{4(qRtKBoSj&>6e!@ z1TS1CSUlnQK;zlBCb%DB!<&BE%&sA*?qsDL2IF!nYLo|x%6rI%-e>Dk(hoU5aDpRf zucKcc9#46Fqg|%3SKlVAC$fd_&H>}DR6X<&vQ5q&)N`xky=SLiu(8HR`?R4aiV%$LwhnYta0=yi#o-*4#zckz7$1k-N{BKLk>mv@~}$~4R9jDyyq zyhOt|?1f3L-hLDzAWq!%maBycmL#gB`!1(3iQiUt3F}uQ5MbuJ&O6uk<&=!%4L79H zF@Le`JJDP=!6bpFY-h7&_ zm+=$d9-YxWKPY<;Z9~S}e4al;Sj8VjJ?Y_6_$H4tF|o`F7Ju83vSIMu(Ll2GLz(^g z2vI0%EJAWves#3s&1x#BquU-`0S$&`YWpY;E9m0QEe8)GQBr1+y6uhr4_IK_y<;hT z3F*ml+k>_qc7j^66g{h~U2A`X%NTXm?9=}X7P5)?L>na;0jHhUv6 zRhD})g}L85sD!nT+nzoEprSduWL_fqo~lxm z-9iETJg^%b26eDUt{*gIfJ3SrSWf)iAggIGko9PT_MPjdf#od2(0fj_mpt|jbw7P* zxLBm_>l`Mnb2R~G7X8zH* zYi_jPi|CvXPQiRqMtzDNX)2Vnx8+FTNif#CdVJ@+K>UDPZ=$9Wjbgo);}dnlsC>n; zfyKA|e8PU3K||P0A+PWH3JXe#+=qyi>Yiyyz9G$Es3;k2PC`y5*1p*h?l#x(xs(Ew zH{DYe6~`Sj8~H4)A9%ibq&G}QIODalpy>Iq_Ty=vZBgbX_v4KLIf~zEdSdvM)n$bL{Fj?-b_ut}wX6g)Aln?BS`w&?^A-^99Sk>|3 z@|NQav>FHd;kcpkx`^RIKMxOt%@| z#5s`pqw*WCbbIOit(_4DCrBp2BM6@HXVU&uK}zc`kIG7}P~S6boxwoHDp4H8%|5u$ ztlz`K!IM)yqSx3|^UE{(0ISCg_9cXg-H!-<_1f860n2LXD&MP7leaxu*XT)fF6HwM z5h5~$XgsXyWwOtlIvgVk68+mHI$z?uWt29QI#_Rucvd2*PVl@RMmZr5PFqRR1_0<4 zts+BKLs&H3AQb)1*+oD zm=`~mOynF26nFOV_*}QEu%GF#&>gP*K6~G}1e&gKIOrbhJgUy$6AG=7#qeK++IGn! zQ7s#>riRF_zs2LDebujNo~ovcQpfrVpzAuD+9uDrY_h~id{Vru`JOA_qT{9k^gank zNW`N3!xo9E_ftf)*W!5{A`g!qh2!<54}EC<8 z#_M0wMY*1gYPO)1$v?KH&Btud0O=U0KmCx&_tNG+1GUj|1#{#sZpS`j%2g96_eN6< zg!)MHi``sRJT)Cw4TS3^JDeX-{XQpQiu`Be61=QmTOdDopsbYnua5H3cVoj$t1v#E zj{GO{`F+iKKKcnEKaB*g;>2_r93D%%6PrpzmVl=Gj7^ zyb3rffG0cyl?QDabdw`z4(F&-IcC7XhBV)_jD$bl*--qsrx$lR-@`W?GeD`oihX{V zBD*2(H?*Qsx&dnefrZ_gtd?m-8KB&0f$?b0R)-g#ZFC-ccu-kV&G}Z3{zrdhqac9o z-DO!pIrKosN@M47DBrNH2ly;Vj_O@sJQDG8WQ!tGT93=|{x~SO^dxF`Y?fB*_`VD| zzXU~f7uKvZ#@}1eLN{1^#?|i&)&tS;&E?|;NalT_6rU3c-f;*1e17I__bG3a{y4r* zG_=mo`?`-=Txh@GWu}fPG-zc|x3${tOc^zq?NwI78`S=mob5&~z9oaPJV5HLK z>YE|6r4l)9!;1mhz}S^;4<>(H7bg<-xU^&0kt*&OW-~MvDDg;Y8)JrvIMuS~I?oS( zWUv_)0YsYnW!0fTw%u{`uX|=J>2t@u%Gy(W4@CSv?8&Q?7b&|tkkT4vwACJQqK~cf zPA*Mr5H!Y1i5S4yjE^&)9nI6JRd0f}e@yjVO7p;70M7V9>f-vZ4asixfv62D^?Htrjom_nrrr{Iz3x$*xaPcVWWGZi;p~YLUJvlO$jEWPf)?)gX#zmelxOZ8 z&iW?%k-g$xkYKI!#!#iH7yb%87)ZvoKee~qo$kh(J11wg_o0vklVO#<*VAn(6UFst z^yMC_UJI~`xt7DXG!gzjlb&9Z1`K4P&iA)9H&}a?aP-KZ-_V%8N69Wy({q>i{fSDL zcgqlsj~>~5hZG2$$whUmu~1I)Q~&#TqPKTz@~sg~}_=fdwf?`O_`HS9QJ zioxUH9vQR!mCF)w{vLVC`X3WtvKakoHXwD_ZF1Z%z?2*(W7Iv3AE@hL zq=WOo=-1Om#k&G?*R*I+=TfW%>qNb#sil0G6}{}~0$KMA$D}SX_u`E65%NAu5zy-@ z{4Xi+0&cS3<%zQ|rE{?Fi9ErcE8N&>co@h-%({}K@B{yuUVaI>?}7aAGa9}(w%43v zfKwfz9zM0%`nN9bu!m}oXHSN(JfMx^gy)CBl%oX#Dvwm+eizKF;MiY{k@z;weyJIE znngm(A@I0ydv_WSD$Wk;c^51Rv~6i#BSyg1k-72{BdKda}ZT^^{k0>hUfZK18*;!`pe{{Sc_q9Pk_&Pe_G=%;%pAdk9Cp217uV%ihC`vcX?HJ!_~dXMRHO+`@;kol z%S7pDr(S|+gn()mF^8sRpVzi8OdSQrHvRNDpUz+iBujsccoG5$sd%DC5b_wXXui0_rR0ilZ}YxS7?2bLM3i{9b4JEu-rg{#QZn26 zKR6y2**j*es&t?(yTJ{S01S<<>~KX+H7M?U`HVR`uL_Wh_h~eR)9&yhN>tjwLw)pC z5zi}^(8YdplY%Sn0nhM-JzxpouyNnlg<9SxE#4@=UkA8M=5KSnozH>p#r?GS-Rs7I zq*}k3juvjMPNmxyg1$F$L$sY3duxYwNenJI{lv#?I6%-h6q>Upd04jhY$}F=j7qib zf!gB@!{*CxZQqGbDZ|>xv zt%bJ&yVai8ZuvNv$*XgXa@=P?XCLNLTj)FT)$bo>zTL9(^++Xx38KXr=O*k$Y4$<& zH_sjf9AoYPE_*`@V1eBES5afWprfVX9yql8<60${ELS#^fEdZZ&dzp{P6}fSPL6zVh69-F`%r}$ z>a`w@t$kguj@Ii1V_%QXK6K31aINm;&(LCcf0&tayej01Qp*vwunUtCXZk~5q=q-A zTTw$)>K+Z$%+a|)@n7wIfICa~29WMlkG?we4uUX|C&fE|tF0uyUPX1`vvNwRiv_EJ z?7|pg1XTlXI5noGZnK8|b2~L!< zG#%Sc1z4@;cu&$uD6!y&WjEfR@8a`d7ww2_>Nl;IU?U>BjUU>di3_{uBb@@LPm&X? z@!elgkM~1^1@H^}>@&IFA&1ZVahR_(u}(?a_G7{9!&H2+^S|86qK8j38Nby|B&_G% zoR52&j#v1_05}?rvz+ewG47~R4C8$gV!{s(SL7-+R?2vznfXsA_)Yuc3`M90sKxu1Ueg~MXr4q_)h@Ou!9pbZlizTvBUpVkm>$XrgsXxKwWGk(GwDN{?= zhpyN`uMPR(ZukC21ke(yYJ@&oVV^|~{vmzglO{{vn7~c<(Pr*eE$>J&6N<+-(_?WB zKMS*L!3YIfz8D628>Hfs!=XIsT+f5!5L^9HyIVK|P4{kj9ITB|E$mAg-?j~BVDec> zwNHjob4hs<*hIm&zK(~(k?kky*9rT}YDub->dYOMfJ~pw5aIK-@mLJ7r1*-oj%bTO zHVIty(`=5UMdK8pp$v74C2HPQvBT#+$?@`*6w~Lu^6sq_x&Xo62-qi1pcb9q z3=6g3-n@s(S|Ib6n+D)-jg){|oaLKmDn+d>Eqr>pb)fsG=*~}kIcqs$A^$u^iHT;7 zYZGA>(yk}i0MmVwlVhg|roxN_E!q{p$n#(R5bAj`eRl@}30Sf#p zBo5{av&HsAjtRPEsKxxOF2yYyzNr!T-=cp+fm@V#E`eg0VhsOuWn zc<*rz{%qtIq1(>wmEQ%yT3R7;*Mdl8_n@dTbd~mi5p;*@sDAa$zd7O(r=siYmrLTg zIwKdbKUPn16~U{ek@uS{W~f@KX25W^n98>+pkN4!GP)^eZ#-PTwfTJgwAMEz%}Ky9 z+}lpnzxGgtWr%ZC-=%*YFOw|cM@l_!zOGf1&_`_(qPEZgu~^!35?-vGJA3(kjd zJA8)6Uic{}wLtdgTZd>pHv!D4K=j_HHZ@NvLkG=^NW7AxF50wE31wU!L}m~t>?Np} zfs~WvHJ>oXOJIOa6WL?L)dZEd;n`A~+@8likC>gY!MhmKeQ1OgjSFb${d2RPdsH52 zOiGF^@m6CHr>vuj2;aB>%y>E{N%`z_j-JYxBA0&SG1O@w5(0Fmsb%MUjuqQ}J;6y7 zd;LuiK6~AMl9KK4CPh6(Ki?DP7O}No&-+Vn$5qzQ{NbJ%6dLcS>*na94!*=Bt=gU+ z*`tc=i~O84?;on{7~8wh%Wz)I3!eyy3{hLyRF7>n7U(4OtBH>!wZL_YXr{}^41h7A zVAy-wTKWkbQPwuOulPY0N%Y4*6YP4=o+1+uQL9Nr@k20A`}||=D+Y6$E4ECE^59l-+FM~vyPe-Dv- z7{^obbZ*VOAMTUs5%ohk5!+H(#={_bXL+?9aScRcpu3zay~Hi97IL(3r+3!b29ftD*H?u^XXO4;defu#*o)m)Mf;%5Fba2{l0-xiW%B^9liF8=fDk(r|?wuNOAzD!{)nV zd;uz4dsFVia}ODztUv<1*&se+X?UKK`#kzQPb~a*<|j5V+3V}}Zh)AutA*~C#kz;V zfQ1w(kmXUw93!RMd7o-hUuHY3kU~q+%GY@cMzeU#HG4t;y}WMq7&#@jMg@LA*Fkl@ zP8x;ot2OQRKcA1eA7_zPd*~oS2fjO*xS}K?^)pcnhTJDJ5{m(EgSDRA2!aWhyGff( zbaR_TPc()HiI$$2(dfDCv70eONvo9g%|2D#FGwzE?nhctr8B5ZiM$ceCH-_)Yxeen zq3VF1tsMdTkgYHL!E#(P7*4e$BLohKtB+Gwst_RqNz&_OB++7-GI%Fp1Q%i9<)ggP zfbEw|ALnd8y(eukevq%_50EwN#xRp9x_*b`Gkul)7RWB{d2bfiy7Hu=k3WdDjVrYS z`C7Ts9uAqieGiwT6Fwz~5jgRUT z*6lO%%iWh4@b~Gv-$8<#>4`mLz6%P_tT?szqkS`B#rVeZn0=1^?J1EKYknsEo^y65 zk{Ns?9$WI*dw#X-z(BDD&@Fb12(&XI^?_p6TPxsOefBQpa+SY5bO6uplqBP&IT*-H zWUmFXD40Jd>BYZDVh_il{>Ti5VI}=a|3=%u&ZQ+sDfV&qT%OWZ{uiEm`#L|F&VA7s z3Z!%JaSqP`nLLGMPKDEey}U2wPD3+~4QU;}D^DCpVX6D$SCO8|V36Z{BcVS>5@0UR z7SgubKESKbC@gSh@MJU>5_uz#NH&Z$S7c>PAj#V@VlTd?@o@%ELJN#V^Oe4}-W@ zmbpJ&{+y{EjXccU+6&_2H=Gc+Xo852mw8`_sHOR6KMjm@C;TQ0@?(UmLf!bKJvC!Q&2XCXbiY~A1%3y{PgSRSpA+%bqi(V#iUV~d!CcFS;_(PbGp1V zH-DTj2LWDD;;<(kg!g`RNI%o6?LZ|m1%cF|ujngUT2jU6$?n0NGtoc_S`n3;qs=p` zzrT;D9rSuz@oHc4qnrWAo`e_|rSxuJpYUeS0ootg^E*pJ{E>1$-Fgeom*ZJEj$&#n z{C$4Qsvl}_sSiIF7b)WX$^{U;sW z5)*sE-2-*B^1HR^kM|i#Qto-~UzM`iZ5};O)6$vw`(?YyWnM63(fM+_LfHKNmDGzm zB>5f%zyaVVy$+$=L5E)(D;JpA zwfW4x5_pO)COz}d>pgpznSo?Z{Ob*)Fkp(z{};~uYHJ{_z;ob9l@z>YlKS$rcX=0U zzy%FZmef8kje>fDXGH>V@|Qh``p@iQUKvQDdH}ROT=r-07lFo+uqp&#=)@hIiW`et zsUA-67*#!)Ml1NEoYfK8RYE;}2*SG`E>x@Hd31DxcMu-L=>k`34Gr}adCZ!?czM^d z3!uPJe%nY!XWBS=`xyN4Q0CizB7c7YdFkTs!(thfPMKJ5tGYc9AW1tETr*wcRo`S> zf0{;p(=ZA4Yp;*L==kY>`fdJ^JA+vw=R7imq{lsp-%dx}CPkEbag&1Xw7S7J9%1O{ zA={_H*!9ab7nXgZOTsWd=F+~STC6YD(}&R(o)I$_`g+Nb5zwc@<)HbI?jCAxe)Lre z(u3T=3rcxj&XEo?soVtzZk6Eg|jMNy$PVAejyiYUwgO)XTvBALSqGe z)|tA)D|t23qaZoL=o}QGHTwF@r7ZN~$^~r9?;Ov=in4#dZm!e|o1NGa7y!R4| zKsALAsM{34mF!3VDkZh``(a>cTy_|NsP&m4E6zvp*w1>uejvE|2AvP{$xD|c@JF2f z5HOdCB*oXV&$^Xe5uVX`9)UgJt15{6?M9mW5GS|;L5`QkMtU(4Fj z!A+_~>2|V&+<&e@KEBOkICD)&>jAw%J)f3O3+)3Uw!13<71{5%xG3X|KGAMse&50( zl@**io?>~Do~5D-f=3)>`aB7~&7Fn3sM7J~EYY38@|RXj_atu2H09?`F{#7;HkR@& zUKS}jtAURgxWku0EopNXg1 zuFU1gA8kfqQ-QgLduRmd*&~ZiPTb?&O2Sj;>aEA4>M{~tv*eWZ&4_rOGI+G9%tiK*gEmh8!4b#Uo+BWxn&zbUrY#2L>eyV)#UA;Ec=2K#{NDb zqUTL1Mp{=lg?7208;ap=$}Xy2B#v`=x3H!_%&Yk0^e=kB84DK8ZzgOI%VjpZ zu$W1u5ne{aVc&{&Mh7A8VChaB^cwW*eNKoTJUK?2+4F;NX1tLw6?qU8p3G=Iu%U7Q z?Sh0iExcd{9d==TUOC(5B8&B1jqiO4;idGkt+lwqP>j7>`y^>>y8fOO5M=k{$56S` z+-&1%KokyrE*TZzW1|fYT{huwgTISxTmy4I3*UX+a!6R+>vF+vs=ME9-2lRgKjyZF z`Cn8}s4qXYVea>VJ$lzu?@ZG#^Z^-;U92;GsT^;4{k7_ED=VR<5IbLT>h0nj+n?JN zb4i=YK0jZI`_mv6_ynM!CjxABO>}`q3n`%A@C`SvXBo>xZG=eTNQv=lhBw!-7mW08 zBv;}W})3I zC1T6eyo3;p+xbX8*vKbg-jhZN1ya)bSK=hmocno1*dL(@uPL3`#>!#xU=u@=>?dqb zGihk!ESstUuw*)K-!b0*VeK=JeVF}2if6+j%nQ4HR+6fg`juN;o#{V!BI?``hi5^O&f#l&KvjJW>+KVZ!G1s>3opxYbFmv zwM`A;XsPP5`nBJBnRQywD~Kk>^8M(ciH@7Kf1R{K5lizpveU7DhagBmsmYGf{jsH>wCIc^J^R+%HA_{AN*}= z))|a+I1)k}r=U#vf#P|O^BS^-s2B7moE^=-rZ2<@+H*C>Go{O5$_Yt#KKd^no3ga) zsvxBW1Id&{c6)vM{X8O>C!(HSbsC5*6|0DB`R5}@RlG^_xAg%?5H^bkuHuC$^et9& z3q9KJA-APQU+ljTmNE}Gj|*~0R<5UQRYaHhI}bwg`SLcs&u!v>}7en|Wj1BQfrgzZt`6j^wsA_GuIzXb7wNL=fU~G``_;1vKs;b)8Tn`p62@VA#rfB+K>}O*u}E?0 z>96A8^qmz_&EKex+be{13kcNe@w9f21^SELQWtT!*y3B~x01QSxtV(0?lO92sJR%j z5Pb@-XXmyTkV2Yw{m2Vq$)(HeLU8bRNa)*ku~ezFbDChz7wx_(bQ;fBAkZ_s1n7p- zqfE}`%0J`@?uM~=e?(|5lA#p+U9m;1eB~|5^9A=hfR>lEkM@+cbB|yIahu~V7%vaC zPC3Qz@7tpd^Pg%$fjA@rj<#msc1fEC+jbY83Q_ww9hDWFcKq#;74b6w1Xrh-EuU=a zabZt6+2`vSY|nQL-j(A2U7eqgZ)`;_iXA)f^|;S~{@i^Sm^~d-0J-lobr-iQ_gyT9 zSeozo=`(qOMjs4sHHd7FPkNGQW%%*d&HX)JY%cACLP4(_K1d^$yVciu9~IyA>iGA} zR{+5(i4>OG1*@PjZ~VcCi!XBB>}EGYpY}(A;J26ev!B2&vQ6(Vs(pcZh(8!glyXsU zWq!h(`&h|H-sRY})UsMeUDy7;Xt&MZ!+Ng7%V0&k6@tr3IQD#QV|zM+<$7K|y9!%t zR$ogY@8Ex*wWGfm{Ash&{O4z_DretE0k`;@FxHJ5kOW6W9lQ{XZM<1_z`5|8!mjhO zFRz&JJ_UIo?hCT2jNXO=Sb!h%_Ng6K$Y&xlvwA!21BZ8z6Yfo$Q987rajE$8=kpOZ$l3pK%0p3qup#O_tP`lNTeigf4+67(ijc!HMbuvX*f0fepcY*`D%~+W2#~x zNyE5le-ZCW)~AXvuxolx&+wU>JN@PkGkMhuIbN4psiRjLU!@}wc#9;5k!joo*B6gB z>C}%A`U3zsdI0VIFb~Lz+~5c&pp87Yzs}#?^+gaY6dLKLOSHx@`?U%T4aSA0zg_lTl@{%f~B%9 z!=v{MQyhs&Va+U40WM={x||?xc!~E|a zFp2g9j10ed2ZQK<*;soeeh~SnI4UW;XjlL-a#$+g+f6jEx~+(Adh9S@Ei@@KD6_r3 z-wCV&Uj)jq;zI+cPS405m+S9&h?|AI-xm8L0j$zfSj!1u^^6&rhkOYCHDpfITaJ|LmUczQ z3!2aSx19G8E4=L{DJB3 zH?_-yZrJC_!I1(piDsy~_oIog`dvF0uDp;hqiom;Uc*B6m82It^X&D0ZpUp3{Z^E^{n@jcut-*{kYfG7seb#%_HDwiuV7M>nPr=GU0kgAxP3<~P+wVlMA%H35G|F)}iIpq? zKnlOYZhqv)#R%yci|6lNwnFRT!RKTflr-FkPq$EM1=FttIF;X7N%Abd01!6A%RPPZ zxg~mSx*9sv&d4)vw9i6vhQsmWwJ*Zx@;w%3q{lacqi-bx6foJ4upmA6V{_V6k~^Lx z+d@(;F1OQ>r~D3PRHqXuvOposKgJ#HgsVf41Rh;N6QhSu)J@L6}UP_)dFlQavt44pT8C z?tEcEjVN1ChB}v)*BT6_h>t=&Y$)lmr?86hm}KooKD!pF@@SI6Uvbie3w{o-<1>c? z-+o_TpIaTt^%$>v4g#YE17gc_8OeetNN_q2DwJm}{>4~uUd9u?e8wf=^+_4T9uP|P zN5^;N+aULpiXAs`3F{A?oC8B60&c=t zWfbFgy_$#cYf6vhT#AE<&P3A2onAQt!52=hTJ`1~b0dWVlIy*{upMIpSihwE>g(k= zoY;#G8tZw(&H=ZM&PrbFLwSY30c(rOVdj<#Pp@A>cQ>Wr<=Al>r#{==jeE+Z4@OHd zVU?MPgx#Gv%Z9%o#yctEa_VVcz`FHLinD-h>>+~5wSCOpMr`0OHJDwMkrF7@|`1!R`&b~cp`VaN3v)gpz ztNPtKU;Bz+(AR0DKJW@W&eN8~hq@8MALxNK03M0$t5xwsvN3=|>s9Gi(&5N-#6|{xMh`omuVo9aP4YM1`>WEy-PMIksFJ zb8N7+b4Co$?L(cD)AzW)zBY9va&Ow;Igf^)_DSj1??F8cn)V#$91M-7Un%}oJkj(w ze37jDXh#@8`~B*gXK3xHE0n_CBYHWawMPN^vZarZ9fkF&BUSQC7jzP1y{|pqKWNwm z)Vkjfi+|606NzK>^%-5(Cpz^N?=H2|*?;pNw6I=Obpba7gu+d;xjl%+*Y`J|Ij5*k z9-0~zVlw^~$&VJ@Jo^|O)2&GVGKe0SO^3skqBW$a-ifDt-ESP2heOc_sh!;n8^MaC z_O%Vrou8q8))}@`xpO!pWgFU24pnJ{&gD|bhZ>`O@D;v9|7l)+cF{)nC}NC217-bW zEYT;Qgeb`Um&ng_VkfFe2GlZL3G#YyEzy)PxeDaMT^VMauR*fa>T z!*5-LPaREd@GJ+uJ*0>mj+k^qDfV%Kqq?t)HbGFzH;)$ka5*g4j+(No2iB<^>hw%ssf?4 zRO#2j9?dtVA%Qt;$ZF>dt)=;yjTy5x4-A z56q$9H?g(3DD+^;eOG^UMrtWS%?$Bqt{*<<<+op^SIOI@#BI;h0f#DMUBOKY{mJ%W z0d#-tQVikRvEJm{LZO_h=1d@b%=hLcWXs;-WaKGIcoy|QSEQfmmoNN8?0&ylp3u>B z@ULl{+5E&XWmaGSx&YPp8QA~`Q(FfcMEh{yPBn;JqfI52WB<|w&2JmZoAN;fqe+le zv;Gl&=G@=xRsGZ~526FLD(oTBh%;-meU84KeIS{(=jkgw6lxmIu-?G?{=?>G6$XE@ z(1-7(_vLrpM#w>jO4lOhJ-K5HWQ>@}_*R&xzM6N0Tr(&*9X)+O9?V`x z-GA&~E?Jft?0u`_C;J0<*&r`*BtlA@zFQ9ec=u>cb=s*jpKYWLUH-swM*6A#6K+ni z_R}ewNSs>2Qcqw6|Bx#EgOoQ<D@{^fZ$@9Mq>th4#xh#zP$Y1f$Z_J0pr0 z?h2_}UT3t*m7MXwg~cI5qJ@|I9m!T#e|0L`BNC+N-u5#soFFgYvD*=eFrLLzc$1Ph zNZ&Jh(VhOUg1?7>PviKybxi>WQ|m<)9NbQ7Uj>gZIG3Ne>Ta8+SmsBzIcn)iR8g15 zl}4>z$J)ekk-q6eXDQvvHTwCFqg~Z}dAaPjuzlMi0s{ooHT0$rhbPnzYXvtgcVj9e zTdUTwERIXB-vzg>VuM;5NSBw(M-}oZUit@Zr!#>%psKDh$3MTppka>|%z47Q1aZG3 z`SidsLi|_KwTB1&eqL{QTPgv?6hc|;#3=rYu)tw0J6_aZz5dejP@QE`|?fpw1>NVf68`;=|f1E zWO{4|hkwKipm~mjIhhL#~!%&>R)*mfa5VJ`69+m&4{TyL=8gBfL+~;kq!2yF)>UC|YoUNUNm*)G zy`zq!$z#~uz4wR$!u7!bICk%scw0lsgRfF~JAMw~uw`!=u7AeB8m2|+i?6`R3{zQ! z;8vI4a*1xX8FPhT>_ee}y3;U}PN9Z%j!NrB7CunOpM&$bM44@qly&8b-!Hg@F+Rm} zFIM-}bq}mW{I0lgEektbO;RQ&KM%Wo#CNIW)yYBB9K5y z`>hZkLBd2Ljm?j}Mk5){@pee8_7NT|C=ge^$`t^`_oZ1;swmdr3IjsVK`ek3g#o>1 zsw@5BueywPgWmn;r?-H8~@$5~29_ znnwwMe)@nxu#OVQ_I$f+X1swOda8nW`ucu)Cm%mE7-gE7G0o)`il1+5d4DY>Y~2{Q zus~~fNH`Z$Btw$J2gI5^DB`*h=MD9NmH&ata2?5nS|O9fzpq|qf9#!Ka7^Ce!EP+@ zI8TvgUp`q%HAg;LBjs;G#m3B2IQG9I^)}k2p-<0sPGhXQq|9DX#8DBoQfVE-yEC!*8JGVgMbxcRn_cFIHyVx*S`Yh!$Y4&o_ zbe`8&Ct5E#`iD1%J)k2%TSd-KTQXl#^i3u-lojP`%hKCTmqz~hy$!Ol+SnjS(D;&F2r;xlK~76K#$Zs&pO(L)W3Uv znGNpA`oHMPh`jI6ad6<}17n^NaX`H62bk!@3?lu*53s}Ar`zDBmsrq%8kY5!cmSfR z-xsxKWEH{L;Kry9v5rIKq*C|?Tc3=d%w5w zL-@*4de5P1%>TL`Q>FZTdzt!neZ zJ2z}BO*%J75jr+Fz67_IWz%AI$ z!+=mxGq~F;3arFTh^WNxd-is-8SG1db7cK9Pu6W8*RVv9}bdxRar}0sII_-?n|0KLm^~7@J_^DJ9nfCRC$C~64{0E zc=aJPL$l%Ch7W0qMv-=ZWAQGXg>6Utk+;Lpzd#xxLL1u zS*)?fyM|AT^gcS{>rqR%wWLuJpsKz4R^v(BeD8?67C#6+_R&1}21)Lr|E9M-RK=i! zP%hrIxAP*R18UdWDsO$^oDW30yU1%Fk|3*tuG3QJV8@B>ejT+8dXHnq%|)$@N)9u& zJ1(EZZa>E_6kLSW3y6=|;HX;VYHut$4t^*65A0n9V~VtoEAQX8t@pS}@`)ld`nx0+ zR!5wEP{{_-(Ye;4qE+vc+nPNjeEuZnUql5_G~uGX?g#gY^ph;B)o;7?#w=6e`$TvJ&! zR@X-Iqd6*ZYr(m!c8pO9l+#_7w5haE4|L@;%^HhR<5by^V2z=TIFC|1H>MsOsN?NS zSnYL(X-Jwxy#Ni%5vLIYcf50t#DM_wH6BKjmfIv*(aL>{`|Nq;gW$!17#;gxrd!_IOuh%Q5UtzxK zoZ6zr5RS<4Jik2=DyEfE1#E(q&$T}6`HDz+>JJsQ8wul;br#Tzvpoa0W|&h;`3b*3?orL4})6Vz$zaP=0eu{YB_^I2^f5;`66N z4!Z@_nCR>9wKQcO4yELf``~Xd2BS^t`F+p>-DM;=Y=DfFLS@kzq;p`bYbs>HmsBGv z$dI0)ARZf-N@1Z&|NM%C0w3j8h|Y_Js3o|WOg2Xi+=#NrM)T9E&B2M8TIxfG`&4%g zPw$8M>EP38v#2a<#e8nkGh^AI-Y`}?AFX|sD3I7Sh0P8JvrGR}bxy<77%L7%F&U~$ z$h``u6!U%EcN#*o#yqwKA4hs>3H72QcV0fc@EwB_l5op|aKw|m$b^JRY*no%KNLmi z?IYg82}(F zCz~oao5n>bl92e=-K&%xCZ1=pUoW@#aT9GFDH-BspjRHEAFSQB1GjY^-uK}gB&;RN zC@fr_RPbqUhy5B%?>Kb_Q^~Jtr7SDbK*VFCrv&wI zOg&F~xexr6kAqc%{%imvWYddOjZt;Fo2*U{`;M`%6}~-q#9m2Z-`PhqlS?Kq;;Gr5 z{02<+!M+!7DcT2e>rO`SpTi0Ije1BOn zZJ#5y{yrMGiS`C(#T^uCI-iK#;dvk*9oIL#lT*u4n4bxZgh+_gJJTLtCX)2i7+&`= zv^X5@+1mwdM7hG-_rX;K#r-4c%(fI&f++e+BJ-n&ATxr1@Wv>U$Rvng--qh8Zr?7e z5fC9WGUCKOcDAqw_hn7wc0Z&^C1vj{NroJ~yhEPA!&SX>YWKTP`TC1>@)gtfbX{m+ z6RXF1TG5sYrkP%d7YnkC4V3A$;yDNlzOR}*j;I>@Kl8l(9_y!Sm-dmBKvf}A-?o@% zCG%@k)$!YNB+KkRGm;c7oTqFahb%Vo8P$#VQwEHY)`))jqN>LEy%^|>tkq;NfE`m_ zc#`BC9$RO4lt04!I-k;nGTj`oXvHTt~q0WX&%T-EtXN!z&$ z|C(ZDXC{T^ zGQ2Oarf8!%-?Nc{>Cq+p=@N^C!zq!7?__Mgj?BH`xOIF`@99pP{WbcodywJ1zUuAd zP%h;iQNzUhtHc=5@K&D07qg(5GOW2XGS|DZo(MaNzM@Nh1_K=^1d%HsTn!ty&(1KM5AoMy|3p9vU6u=p z>9l8=i0$VOpa7grRDW6_s58amug7*)k6`3t0#aB*snv_^pmxbpQAbrG4^n$%v61jN zAX`#U>YklY;n^}lFmwP&@ePfhgRwm{VIxI;T2YiUbm#&EoT)M;!$Gt?yCz8J3QY~3 zD_ZB*x6&P*yz<%K3h}I-1Is*}ioqZvif$Sp=T9e!kn!MIAL%*cfCTxD6cYSf>&{dDQgLn!{(M;Lnj2789E_t7>ne zySY%&&F(i>rSLwurlA*|C>kGJ4q?F}u6>rpKA@OKpzIHqtcoiruU3 zdl$hJL;QzmLXr#5(Jt;m5&`MoRw|(B;(0Pm^0k@QSd1k4ySLK|()$l@jP(_x&wp0$ z`;JhZSB!lE5z<72MbMrZl>ZQh9{|`pw%`n_Ua3zx9hJZ~f7cPb?nStz{OmXt(R9sJ zZy|;UW^$X`ptNRodLD0Ic3sa?FzEv%N9q#uMN&8Oqvh_={6HLtx)UBQ9GXDxo8dA9fD2*l=GRdiK|6^(TX_4v`OR4MBY!Q)UGX?MJ~fZhy@+ddmj#xfobHtgPDu!h(CrJSn6 z-B_#O+UB%xLo*1fQtcnA5EfG4O!rJVmhb)H%C*KvENn_(U2$I6Z15_BgwFcGYu40x zFSU=uZ2{2y(lB>#YZ}@pbJG#oEn$Y!7x=z@(B*cn0X=k}Nnj4)_AasGpxvsdx^&#N zN*w)`=yj{l*|03ypZV++bI*DfJc4{0A2rimp!u%1I9Siw)b?6BOIMl|^re*6l?+;3 zjOP)cbc0RhDuD|td#Ddf5LaEkWNs&@2>zAi(QNh>V1$ztDY;()-bhyn?JmT8tIni0 z7%XMCC4McRls`teG$-ns`nmimoc%eQj;5(bd;GZ$y}3M{aXtNRQQxY2rBZ!6syP+0 z9ysBx`k8j9>@iTHjkGCKxFe($ZxzDj%p8R3PDs2vUJbLS<-eUgvzN0MZ1Y0_w}fkPN5>=D`@+H<7r!SC zcln7HQ@_4j)#Hvw7`PSD?f?TQvFf*ZFc% z2X?3yC%(<7dzLT}d%_;h?_nfB!r`he91twrbF{C@;ZXsu$j%Pkr>odaaw|gLoRs}m zX#;P%e!V0*{=7k6jnk~IVDtK5ZJL;(fR-x)(7*62?$@G!ULkH)B|A?sFW|CMFLO|BoAzB^~BSR`g9x!nqMz#{aC(8j$e?H z+k;MUuDS2Ih|o)W%EFAEV9?j|y+p!qfAZT&G+P&)W(+!8PJn02a0ciYXwhUl_r4HooZcrX z?pN`P%J}vf>Gq|+mO&ZxOXvGg=)bDNlbak;ikI(vrnZccBx`LGa8(X8Fp>lBKtbCl zQD$xn+r(G>-W*JGpPfG4d59LES+#TMWDR|OLI0n?SsZG^)5pylKjsq%#d-Jeq;3F~ z>7Soz9N21qmKgmcd4L6_?=L&|aoPpu(?wo>Y%TkM#I_D+>)Mmtf#~XRWvhLe7)X8Z zt@r^hRr+JXpsXlt%3jfuXeNKt=gXm^ZD<6!go`|($PzbgFv#wIX%vyLZRC^KyELrA z97P+xlKm^=`sqn5dZeY_ci;d+3iC!{4@|+Y`X0HTw;Y)gq?#q^*vyt=rdBmGcC|nh z&fsDbFyAm7V>4Y#W>h{K=~MZ*Ka7Khk`UJ^W8;|fe(v(jt;ropa`V>TKfF+1#;97$ zYksu-pQPNQre=#=nC9tmisJLBhBj3+m4{%JT-_YvmThxlwrP~n;Bib&K&`DAWu+`u zwxFSDh@%}7no_$?}-1sVyCq@0PsjSW zJraYWrdRp}{h14!pY>ELUr?QWMhG9`guv@bXvCoqNF&j+v`xm80P*NEY-l@vqe{PW zFnz|>#5RMsO*t>$y^+$<$!3SusyPFqjO3AvSX1d1DwfMME*1{%0@%BCxiWX0%6HG` zwWsJ|Ku>T^Y{|40wB-AN%W`6vJ_zn(802Sm^6Yl*!suX64qRU}C={qMNk``n6hE)Q zCI{Npef&LYoN&7Ekcnf*mzlo%tEB#>{HaK0{0ol+EK9K2XIqumzT~S+Cs|0@-%=U5 zK%E%L5N*#P(8UMcGddeq1XWj85q!`H`-p2JiT?c2Gbfq?);+qg%Sk)V)o$rIUi(Tr zoUwG2!tQju!hHZf910m-n%4lFOF!SF=i_Y^Bs)QAY`q)eV295iw>3_pBs4gdL2mA` zdbR11e`lVs_9HpBxXPqvKSASo48xd>CUO>9!&$%j9y-?ZR5>ap{25&xs3Jk@fE1!K zP}M%(E>+Mh8WEA=E391Tw;@A(4hO}0oyl;&;b;{jJibFIs4@O0{2mUztdlR^IH>;@ zH)cnoZj(V0=s!=YJfyH{8ZP`Z9WDfYKaoimxqLi7&|!3CCiL`i?;HyaP|KXJPf&<; z@B&AAv6OO=RpGZWmn2NCqzr1jDqVf7$&L_Ze4J9bwtK1@c#$R5w?w$d6qNYEFoafd ztuar|d+&yDAIV}K%>G`zs3-O=n18UNbvJGmT4m4k1&8FPx}qL^S#XjB3`A0I<6ogZ zDoUhXsjm$gr|pd8Judrf&qe%yUL?CDln?TV<9my~gMexLZbI#RKlm%`1p(oT_($j7 z#fiJdl5o(e?78&o+q~sK$rzy500{;S%Jv+ReQ3%JxDQMD;e~RU3M}OKLfY<3CG~c? zyMP%?@&n}c`VUjFyr>uad@borF7XFv8yjM#B;Bi$h_x1{6-|6CA#ud2?VB1n`{#GN zaAMHY@qXK!sZ{a4+Pzipg~;|Cd?}*Zk;-R^?9?4!Q8#UI^>N#gy)hb&AjJsXo$Fu8 zaRf~-?OhWNDjIqnc6E?IoZkLur_X}XYRi3TH&|AG>SJJv`{CN#`LD@LWD@I^zqiJ2 z&T451+r25TpxQF}nR~$?1Pd4(YV{u#v?6aHFGO|EFA(Gvl-dqwUF@KVmVd$F;THT1 zG8;)!LOSDcIh2mdma8=piAsdHgsj5rN0Be1?FdUO>}BxL@+EoH-5;4>#Mg&l{6zX+ ztZnz#oDIiv$3;q)FwcQrKQAQCya{yp14&qQhI2{K*YCF%nipKnzfv|RbmwTVlt2Fp zUW9p5djSIPZC-sv@juqt*Penx(tTr=k3#@HZx7_nHE2LZy8hkk-EFYzoK4LBH-~4& z;t^a(CEQ{vpYP5g04rh3&~M^n4jp^3)Xz&_bO$a_3sm9i#*gvxVPhdapg4SxdIlOg zKwoe9RpVJ@@8z$Yt9Ou^6CPps%9$I-Vu|3ND_9Vnb? zkfSYpa~IkMQ>xXtEgKGd(8QYl=V~^CeZGHjqs{!){JfRN>v&7x+=%qpkzYgi7^=H6h-fxu}}=>ptX2CJ~#yZqvWF z6j3nD&5pnXwLw0qFpkLU^TEF90%0Y#SaK&02w2 z;hPUMw5DgV{OSO%4u5P^p^aBZgJN?tZFK3u`EzJ{A`+6UJ}EKei~Z1CYdC$YYYfiH)71Pi-iSl%OiCeVj# zhbuVK_0;f0V4ZlcIww_eZHex5r>OoLP9%9wz>&fsjxAaWn zf4*y+f?LIw3rqq8hvc2J)}Ut_S095+S8N%g0BDzD9?ix-1#g1%DDvRSoYC#V$`MqPr8GAgT$i01nSDAn9yZCz|$T;4V<5Xvz z+ivu)4eC>Bu0ZaBDO_AFKpr$o0V&c5NsU9V^;e@VFsJ-@xi~*-EK++DlSc>x+W7wV zoNv!??mG@g=j^UJ|3UtHD(-HcpVsD8)}GlbRWok4U}fY<6&~yGK{zX%sPV;Jk5-(! z+M+p(0yg-?>7xN1NyTRmf2hW&RPkeif7KTU>8c)CPIXvrxn4ys|GG7XMF_B&NpRY4j9caUwPd{cUN;yjmYc4Wjc|lr=cg@-{ zaQUQ$Q}op)gR|Z#+vH&eH-xHe|-l}rjCj`^`N#?5Y`Qu)czb!}u z`SExzKP_F;v*quJX<>N+Z2ab|X{+`CnP%TTtK@m%eLUS-#Jmg1hYepiSGj;wik(tF z{k%~74^8P8GdjHFin1_U3$DSIn=8|K%N@QNI%Kmwf}qU{)M7L5dT$FYE{DQtPc+Q5bqFw)ntgC7^o-W6ZuRxXR2) zHPpXmk_7x)^@<7=P1e46zteQ>p#0b%A4wm+y#|=WJMiG;83+NS=eVx@{fvhac`NLR z+9$d+_^|FXJB3a5KsqV9@3~p&I~L`B1L4t^KIcU{C&_D7z6X2}LY`PuFHmna|1rju z#&7m{(~zzcgdT5jk8qiUSCz`i)3CPWV7P*Ov-j<=nNNH=UX6*1_@J3{U>h$4{esQp z5nYF>ZLewz!h^U#RJz<>Y@^Z4_ zHeJF;;@;G!b2+|HA%l;Kd^|=7d_g?$(oPS|v=#Paw)J&06zz4p`Ndn^7plSo4Kqkp zBWj}Vw5Cs;9em1x7@b2NgnzotyXUdl^cWlmn_oOE5z$=DbX>W8V=5cH2h&a9LDEzF661G@|E8pay{n7fOr#OfQncL7M zm|CPa9BI(L7!3=Wiv+I}spy@JF0G93H9=8mU`^)xUpDc&L{cX{I*&PD-pOXi?$BO7 zV)kV<;KUz0KInt!1+Bc)TL8sNS(Ln%N9jf#e>^Ru`_(k=;rqgvDrv8{b7v^7pgAyC9z6!TYPH{_az6~Eh_ir zzpw16?qE269pK&U5Xrt^4BO=sUfQsqY7v-G_;Ye0`JUbn>V`(Li$~nN=)S1po`aj2 zBJ@xytbe@$dA-O0s|Rd1w9od7rP-E8Y$e36{EDKkWsKR>`=|E2KTM8G&(HX@hkJN+ zrZW*Z)@_pD>p0KJj53%`!FWvgk55|i( zc&>w0!Q&?@px-~pE>P?NOAVnn*K5h$dXj%!#2;?s(eYp&xPq9?Q#^R*?|BV&*AvMy zr!P4?o7wU{*S()cz`06}G0bpHmmkX|#V9GcXdESLWQQa_eMsO!a`XchaNERND6GHW zASs<@Got%re;-tVhq(&2{Vw}$Zpg*$)AfIMbn&`b!wZuts@%SyIVaKp3Vi`#g1ve$ zx3132{AP`q)8H(Nn?l;BgthrI+)ZGeg;y{Qo^~Mmc_tOgyk5Y0;`V_YR19WqNC!|! z(dkYwFPZ)O(>}6Pp&I)zgL;fzRfw|cR1H-vsHVKAN(4xJ;{z^ zM}BDbWNJS_ymI1ugd51&tvA-Ul}#%%l+9Ju{QLeU2^-?~XO5WKJNq^!R-6XKnVuRn%sz zhc0Xed$cDSKOUlgeg_1;E@6Dh5i4vwOg{X%lC1)10O>%2;8R4pp(h{jJDg^$bk_*2 z6K^u_tbP1EG1O8uq;3eBF`!L89>mcsK*Ml<)5^`y+ zpr|gWs~<*)xOd;f(b#W#>W5JU+?{-b0`g1PWA`1(=Xt>G1eINub3L^?{XD4CSdK&$$!yNe>gKc_ z!}q|ECjOx5EBRbQ5iSKR{PF1XjikLbLRuuMEW73}z%SC#r~~1HF}XaSm)IIM8jN6Z z!chd+*wC_SKfA@)uZrHTh<^zfhV19ilO$C-R+2=iZ!X-20dU2jzt5zrepI6KNp*c8 zjsmfaQ64ydq5KK^i2nHS;SqC7^<3Z4IX(J$&E9mQ5`hU<xniK2o9y>It4Gpc3@0MH!CdUh zzvsGbs4`EaEEkk$oC)O#ysyna=4$4|;t_7?kN-!D0kEko%e#MO!cl}3D@2Aieg5@Jq5ujFY3h~&oHlj zE}p$HD+g(DE=W531&9Q_GT>9XFh${ zeHw&+(=)$RXC>gwtwo6v+2mS$K%wACi*Bv*m_4QPXF2?sN{MIBFsg7sBU+n$CsRoG*S?5J z^x@Os?>iQuEk8xcl8w;>kYu|IPv>u0|NZ32Z~f$-%5i|*1!Vd0Y00nQ_WI$WM*aYc zGE>GkCplqcEs|+`-N%O^uy)X|@pM1l&q2*SbH(oc?_KEbk$t%!b+|uTkVypMm&Z?h zg9`GGzKBj)DA6k@W?^2y>33ggIG)eia!)RM8_VNf6b1$MXzUqU;o zTEf!uv$Es)g2mwXlxepQZ1pOTWmsRd9dykG(>;E^cm`VX2_Qb46!9%M0Aw7vXnwlS!2L z*UC`#!BqP4EkDgCd5Gso=k=0Z4s0~Ol4~|W3-?t0;zUe&_}nb6tEXk$`+;hox9N1i zk-|8PZO1b6(y-y}}82~EtOk7ZD7j8@s;}@V! zQw^T|L3rvX^BR4a{@dAAbi{R=f-J2jZd8$ydA7~%@$gkC*q8NM2>5RDTp~`ozZZCC zvmf|L`R9ds^9KF#t+F)mNJ_9%%JNH3c=#E17@hTDo@@*ND!PSB64i;=E`jZMsZGV; zBC1%4p5#+aWc%D3Hec&T2i5-UH%*l%adSG(7ZB9%d3%7E52TdrZ31#eru6cx)91cU zCo)*r*{uqJ#^F_toI`~4`|1xNz+wEyRxHtUr)>{{fP-Q#%~k(Y#_#a_=2!Mbu!+I_ zF1Nv{Qa=MYv=Edh=|2IbrAsMm3&wVTiu^h5#A&HXz7gv?!St#*Q~Sb(6;;^yF{!b2wzaZAGRJ;SmzD7Lob@_*DIvW%G;Wx zwr!Yj+^y7r!huOxc)WBB)i3OWLe@rlX8L|a>x`ev1kr;a(-(}yf^o@~BiA6p%N|efx|^8#?b|5myaDR8OcqsF~=N`n8`p)@a{)Js}#Y=#CE46egP6+jfed zdNTN}EY5B{zmI5W@Q?KxAFxmF>M$+1F3s`6?k^#Fm!Hgn3}ghO$2JCkHSG>ZUE%Ez zyjXmu{oZzIIfLp)2iXO0vP5W)lrz-Q`(!a=0RB3mH+Ax|$8bj2&di>m2zmrs!t~_M z0rL}1?ywAQX%v{;%b>m;FOPll(!?r0GJ7bu=uOZ2vcsj9d4HIr=t_!tK*wua9TRW3 zQ85#0&q{~Mb4}c}MkF!N+49-=KR}Z6GQk z{7oKczwP@hzek`F_DC$~2kx@psbX;ul4aV~YZia@`=I7^pY<9G{&EG^7&Y=~a1Kv? z%D33>nFNhk--(5%NUcel_lh(%lhdjAGoNw7!^PA0sg!)UE;Boz#1nEih}YA}3voEX znE#ryv7-+jPVkb5cwf#eU-c!t5BI(+AJy>1V=6q4OeS@p_r1=~=F#*MX<`f$Xy}vA zaCx_~_aNTC1$BZenrgUQLpjLqjI_=L` zOS+9x!GKJ;8mVB5cLM0K?)IFZew)%GJb95S+jOhK@iyt|z$-%uW?vRgZ54`JTa1r${Ab#5MR z{KeVCj!XUsFJM@BOzathgXTP1XR&Scf`tK`LVlT~IlT2!*YkZJZ{p1kUSGW%bd}8r zZXXq9*N=rEcn7eeLO%|D)v050!-On6={Fm`>8&Em|XelS=pD* z?~JLED*gMP0w0Cxy8QLkBrk`SzyK-DxpOl%Vqic3g|jMejMSc z67OqLX~XHkBsWe83LgD;B%njZNBs2Lc$Gj+xMco{U>&2&=E6ES~qqw-wXk@j652N7vqVaS* z4E$w8t6F5g)dg-7*sW&5N^#3j=0(SytJ(O~Z>2Gl3g54Dd5hlsZuC71AKLjgArGAXXy4yR<>-e233!DBqZh99(D+_Lp+Az- zgFDCK9b4nAR&D2Kpl8yS4D_kKlQXTClyqM<+?_&89rJwFMr8n=XrFfTC=gv6v&eo` zd@X9<%|}l(B3`uN54z~(CA^@cBrI@R?Gvtc%@hv*8o@wnzp{0OGA+U45(mP&61}+~NB+wpIR5;C zHAA-y6TtM`d5B9T6*0E?eywkKILe5#zlSl}`cWsS_-z|GA%V1&c`Lo{r~ZYn4Et^x z?((AT#CNBC0p)&16NP@F4|(fk7P~d zzw4&EH&964^!pcu?l0({<(I)m8SefmWE`{?-`Z9lHHLU&sgOg{AYa83ZG-WAX!zcQ4r`oNFy1?Tp)R#1&fooMo4m!#pr*!;Bf004r175b5$iKo7w9Q2 zYkE0s-VySx*6zKrVA;oHKXslcU+bfK^`85DKDnWS(y3s73;9((W~yIJj2AYYQlgjT}0*do#k&M4QFYegQy{TFc6;LFGI1Z0Z|B;VYy-8zC6ME$iedJz8s1t z&29Eub`NRx*xU)+68&gqmqdQRz>$@QMzqwb3X_RDz|qyPtDtK5cfJQ{LVg2jkkdy$ z_crS^um{i0s}+lt{kisS3rWebqZjZ%NW!#a^Efpr{Ju%<2{G|ydn?WLZcd~N1Q1eM z4L#H6eTtdtM0s9O+fjn^FeT`jqR$y^wYXKJ+o~LslUS)U(^tM<+c(uDgPS#FzSloUO%jXiQB%>R*0bTXRQ*8GD zB)%8*;HF4$fm^c(*R3=eK}Fa1Oy=);b5HIgOvd-VKiX9G8BvX}dKuB{KLnix0?fc0 zAREZlxB6ls{5T$~uYdm3Ou)>VQi-#%CA=GhRO%je^80O`JUS00vGMeaADBS`43(8C z@9}M>d=eU#{`x-dHRyi&Espog?Z$J1@9I3)4-@IY3Cr@eKqi}G0U+ln7w(DWVyO0k z6y=Y0i^$uXakd!sK|#Kkx_XlyJ#0qyc_u1W=WK2S0v$;nLBT**gt`wW@f^bolHYPC zh{_fD;SLEQ2rckWdOGWJMuMUOMC^LMy?@3)FvsTGjIF$e-fZZXtJv3QRL>;y`lCZ%4XWo~Pv1-8>Eu_^kM!hI-JlZh0NyW_}zg@!OKHUVHUj>PpSXZaXSMC`{3uf{6IU#}Mt3m$b%e zqToY&<(cASEVgJvY#Ch@ANkic2vxK=L^_;rY7}$4dwi#lgg&AQdRU&P8m=IhMm2ud zhEbZTkLG&GKig2hXA9QhiCM9CIbY%<4*ZLhO7lu506PZZJW#<-QsDQjd6$4f<*4AZ z;idHWl@D8HTZ)fe;X@8+LTPU`_Yy`10TrSd;RhV$wW`QqZMTz`^_^v>gu~+FFLsD_ z#;l$Nd0F6!7pj#~m;`s5q6x8m4E1lVS0~s)C0;JP#Wl0vr*RO=EX6gcZ@#W7X*~@s zdS|X8G*QwrQ-Ajq4vRVHp$$wn%#eb<#Y6HG%JF@3jwQ$*Li`<!eeAl7{xKluEjumGGdvIeKF^O#s7jF$kt z_&sRct)YFZk)J>cex>XE{>uS9%J}PRUd8ZFMK$SO9$`y-U(Fpso8XA^e7*^gsSJz}*YD^B7ZyGan+OBDEcHV6c-xny6!`qonYSZ?;po{c;K7&F z8Grqj;rUmSzX#_vlj!NqdVz3L)g_Bx--N(PH@w-%D%|DVX9}8zi`{SXh^s$-+Q;Y=Pf*YCa{!U+Jp*-1MVVRuz^vCXw2nZOw|jP4sx_Rk zB%R+#=Tffs_U)40=k}Yy81epPeq@b#H#u`%x#0P@rNoKkX6oC~5Ao4B>T$)X2y_9K zUrDN-FD5>gQ}~r=30!^0lq(Ifyl~$*R6XhTy~X|>2q0E@S@QN;(R!E2MlTv>|CDeu z#A|&yd7t!{hQ4RLYFP{-MVTS;#xP5%8B|vAsAG3^pb+OL;GB)LUEdCxjqn@J)ZuMq z`-b3WHxK3H1}y?@!E;dY;Y`w!d!pABKVeEnL$Z)*9l0kJA;TxNIBAbIt=2>zk@@|2 zX1OZkYO;O6;B)Z2asi2myIL!?)HB6CT@fT7Sjg?`D``v)9oK20%MKP$Phb4%$gTP# zwZDVrT3IloJ#9$usz?0T@zzu1VA_7n3?}^HiJ;PWNgd zr$4C10d{t}A0PH{j`RC5Whxai)ZU}(t01*tgazE@j~4L^2dspo0Dw5fX8k8f-Cz5N zz5$k#VWRDCv(GRu$lLI-Uh3gU>h!lX%F))AHRV&rZ}N+2eThWp5EcrtSfq-k5;JN_ zR_~qqH`iz9HtA+7OFT{1y!PH*53u(Z%_52;j*r_6#8nlLpG?!Ys|3v~27Jjvu?|qs z$XdIRy#U9@CN#xga{0O6g4z>d>z zzo3hMO>gAwdF&MI`)yR|eHz%Bhy(@l+l+!}T@b?(a6E zJtmdf(p0~PX^SZ&_62KM>{;qftuHN1?^mJ^=iv(!3x6KZ+v2sqm(jaxOVb>AR!q{H z%b-*C`&vEp(>D4tkL9?IMu*gx9CZ}-fprhj{V4+HPh)g$n4s$UT|y?D-&MT!3q=9j$P;Zeif^PSMuIcR_2mu~hn+Cqz;%GfLCKsy}|pg}@g zb$2x@Z(lUcl$RPrbYoeSUw{c*^#~}t1PoD$Mg;x0zh~DTm9SR zeYAul)FP7Yu2Fpe^rh`Dmk;<1@bYCY_wP8+w$IvMvx^YBoi|inv7b8=16_j}0}226 zY8|tl=05l&th0!}ADNV@(!)`8p<37hz8|7F$J?@OFrmgi?pL&D-^zA2(`YU_9VEn3 zz4c)e(a&3uA}kw!8~HwfMeXKLZm>;80g!V6vk!;%lkWW`JLSheJgzUGRRtJ~h=8lb z@g-#si)YgKb{H;xSiD#5;h4iW0GJ(CBXaffJbI#R3c}sQ11dDD6or<;-QPU*I=VZ3c=>CbWAqSRimdKNO2?RVXrCN^knA@YeG+XK94hmbZyLnki+Bg zM9J#Rb1kY~dZS{g=q_GkhVKmNjl0V4;T=cq$DFg9a5+xX6-_78#k<@Nv3zN(F*NwR z(Dv=9`mwt)NIv5XnpP-*(xqKZRuA@vRB7^ie+cEfdF9E%DzmR!yhW(?){@B`VFZJe zsJOK8G1rv>?MKw1g#h$XIyz*;*9J>)?$@iITIoaEY;pr&t$dv?wW(my!b<(i3H#{j zmS;r`j`~BQ2>ymdjg?%R%L8APyX8kpB0`2~+IXs|P0gMslzL+7$$_9~D{?|oXOS+~ zNATz1DlcmvC0~-vHlbJI+eF*tQ+upY%<|U0yl7-eCNGu^j2Zo!@BDm=4>64g`2E-b2)M3$Prv(ht6Hk_Jap2`-abW6N2upW{tBkv zwF$%L`~Exq$Q4P6c5L*At{xsh7}p$eUwY&S64X~BJ@L*9EdymF!`|eayv|&B{9FrL z;Sc6P-n!~jrG{>Ia{U*?6k)&9B_vcB=t@(bU$j7HvY3ja0uC3~(f8Z%$l58n!1?(c zAU5w%cVV2^@=wPE=X?jzj(9Y~=zU8cvK-*=itM|HS96&_-^Jnr875b_8TDDUGHLU zf9m{pyi%5Zh81Y$JbsCM_(^Pkcj17rS2+RpTw3+Eu>O015?jO2ETg&=Meit6M3~2X z7R5t|pvZebcJgyAKK}_#`|G%?a?9fyw4r}HA^m*PD6&4T*~5WE9p00_K3M+jchIu* zFw{=V4&&_#p9XyJc!h)P{XXHxvC!s^XDM|^z8!; zr+zP!{d%3CJc4krRP-YQB&+hyMFM5NL>b&8I%Tj0SgjVYgn()}7i8R;q|4vbd`w2Y zex2eb~d3re{y`qt>R=qqI9Kf&q3h75*c;j7npXA>S=X8E({t1IQth! z$qH06Bj?)diih7Oe{1$j;d$5f`gWF1juWul`@w(UmZc*n6oadvjy^TN%?h!5P>H{gI%8q404gKn~dgqnV3T>JygpmmllSWv5 z{DzcaDX2}S>PqMa42OKKCI8yo`3s*PEygb}EnHk-W2$!3^`k9L@V`L3+CbjvpQ>9; zN5;>)EcQkX%q_pcWQ+}e=FK$67qPq>DpJ7tK?S7kP}DF24$57GGJkG$_$&16%y~MR zP!hL@ouxX^{+NTZcDbo9_ok&X>4tJo{^<5XkPdk+*f+1|ByqGYlZ}fud$H(&(w7gq zirf8L+?S%m;e7y4C-Ey?t(T!b!C3wK^(Xo{#E(yx3U`>~NvF^A%f|{|j|itEe>y_X z%otIIioE?hKt*}EKBsYj--6n5msa&joL>!AH*u$W3LcbdoN8|~Id!l588%3JoIy&V zR4niA1XbrK>gqdLzi@jaD=Vjh6+@i_;gh1g9xL+Q0JCLBCXTCw(#r z$d-M~s#Eolh8O)em51}WE$AMJ58t3}?c=GRr&r0Kqnj`3ExQ1*vS_(#&2Eh!2FQS_Gt0r61~ zkX060-#~UzkWJw0=h73=G1IN6$WoP+dGlPwz*s5jupYr*(HE`CNqf;X+nV z%{gJcn}050xED--$Br508PRNQtHu4$9WuzW+GcvHiy6WKLZ*5Bea)WGR{qK{xi^Xw z)iW&9o)@KE`;isAWDhdn-Y03KXOtSb9}T;Odz#FkgyluoHw(}5&e{q}#4g4bynuBo zcn!9Jw5JFf$|<51%Kdy4!*QcP8cmf)gO3Go*lU7bh8PKy`Xwc@~Dhj~`x$u7W*KM#MghwFE_aqNbuz{1zcyR4s)$bGIb<&nr zPSxC-o5#ueZ4Uc;7wZOli-zkqH|{PK^v9I!V%U*$crfbc=NkQDpL~IgLa7tPC2p;U z-|sdeL5k!nVwM+sh~w|^xMeUq%?kn8X-+A1i z7P6XbFpZwj%S)^GW^a!No3}tP?}h}ZAXDUVuZo%V{Jrx@3O?`O;Cy7qJRnY`f0p~= zXASKY*S=Hoqm@v!;Ut7C3c`Vol3$~}TI0)1?$3YhA*!hc!>@UQOi|t1jtD1t**4fi z+vU+dgkb5N2jSEEon_3Is}t{*p=@2M4!qf&1N2&FSV+5RxvjyzRrweK>sF=$ttO}X9=)^a6(KzT=iPKiMc6wSsJ z_2G76k(_cTX^ z3yl$2scIkm8OkGk!wKk70c}Ise*g?V@05njyKI>BS@#)JA*W_R$;(h6Px~C z3nOio@o^m|#SIZ2Zu7j`kl=@FzqtwEdb7e=s!$gAo)Vk+fWV^ffR^=Ml1H!4=M>pj zH-U{KR*bR0Xt#vw*Rg(+tpJgf-pw+P^>51gZgH~;{j;#O>$yp3<3skb9dcaj6{o}7 z+Q8y{R4Cc)$M+Y7Nx{Om@&wX75j}v|4SH0b*M>6gsQNYD-L!O6sT5XULP}#Z){C;E5<`e8m;lRTJ_JwyO$T}|Gv8DH+T7+Y6JJBSdE-PDs4cu z(AeLkX(w*n9CYv0U3-KE3PB7~_N0EBgg9Sr^>NiH{wN;GiZshuD?Jy(KX;}ToLQG~ z-hHb_J&A`JUSf)k@A{w)lSV(J@RkBkG=Q=^DtnvgVsg}cy}Nt+ba1e(J5)%}o->x{ zfSRrvw&svF|9mi2@X;QBg6d0HgK^Y3;2^#~kU*Q!#%yc0sW7IqVTS^@_1+WEv#tPG z!rY<6czZyzC27c?qyGLRjPUeG&1=l#Xo!j0us=^*^-w$DPwp_g(Q988?3wC}A@lx^ znVgvhaeo>YGc%t(1^7t;Rn5UW=otxpfs4mSF$s_Yv$hBI0n@nDms{d6?0Dt(PZush;Cwaya7 z7yW#Wv6SoF#^TiL@_A|YXHdvw3~7%nkz}z_UHSPU@rNBqZuQf)fmac(J&mMxS!3wp zZYgEXjzOK5oIGKs-{?~=PUY=_L4HY6W~b%C!5do+^o|&{wPB-<5EXKJti@lRUqC_M z90%nV$#W?ZKVOoHW@LG8Y*jweWnZP--!jWS3ZXzbNok0?oDPqg^Y!q4zR0f!;zdz< zqs?az6>h~xVjwMU%U9%#2Blw<_`<-K<#s80?#x;dO$lk7DJLUa$|K__;z$hEvU5 zt58Y5EHX0q1GHZ}RXW}|awJza&>?gKTK(|zSAc>J?}iB?I1GRL{E7g#8CPKnZwqvQ zG|)y9pIqQ^@&xFJ9RsEH$LW#;w`15k(`}10NVPZ%*Ixwwtd{2C1l-EkNV-n8UeNFe zC=Q*(+*FBQxsU4F_giqS`gGc0y?2$tS(;g2;9~FehE|_u*Mc7|yT{Y|s{#6JG`*^&e~_ z&_ml6vboRv(hA8nt7ZYONDT!*waeUYf+;RwnP#vJ&w@TCBKx!LA7+SWkuv64pg$lx zv9^~&Ted|`&v7uNoeW1vYVo|S)UTQtWV!=3Ro^+migutfzV(mKFGUpyHs# z4@BUpg>DVF)gJ?N+M!FHL0~VQOLgeD`@rf~y&e>e)1orB`Ty^gAP zL(vO5Lg^%t5J+GOC`YqX&ho~E=|dN{@R_Z_xe%RaosPd17c1x2`Sf~JEtVfc$v(%f z3Avaw4e@Jf`K`bAMub6#tRMRq*cTCd!W*Uz2dE#5zS#nnPJK(P^@-4#SUgo}@YR((4!RAJ8YzTo5%Hw#<<~O*A@BK@! zN>GUW>jn(KML)nEFEt9+PaJ11d#W zEA@11(5SKx(NVMgGU{R6Af4Ub;9a@z42yp;rJ{pu9kr8R9vrev>V~}DZtFRXbJZOO z!Gx%MAsVj=9Y#9$L7cM9^w92lKHZ;x?R~||Q$ge&(?JT+#b^2vvo{!T1`4m@7m=^7 zfx|0cW$z+368GDSfik_KX&>TGQfJMxF7!7ZRQ&38!BlHM_JzagZ|k@`#C`ExE0jn? z3@Yx_z)BpkQ+ZQBCf&)k_;{@zzl_IZ6BfEZ=^VSphJJ;vDbhy2d1THq-+yuW?F zXlZ*WS1)zm!9K#`r?z6!t0@1wNZpFIVLT+r?wP!N3Wt1sW(#|8?02ItQ2@tx*gi0| z1%7ucn0C$6=k$G|HPC;M&zRsB0yo%jWsruOTPFkG#1*(_hkJFh|2~cjC-?OZrw;%- z>Qw@;42)XfYB>9Gj)QEbzvv|FXc*WMHA8`;*rw@#*Ha5zqm>4_?xxTHXgaIO2W8^X2?F2E_;-sZq1*AzN4Pph$YP zzRA@x-erL4b00+*E*U%$A$>hmr zCA9;CyoQiX(|!crU?yiG?oT-A4D@`DX5nPGKjOXj0>b_GXmRk#I0YzigKT|xyV%nB zw!cO1?_+wAQZ&r7_4f{9t@=F73#gEf$BJS(VI(r1%!8RlLEbaVGCiBG|;*c@+f-iDY z))mdYF8bs}R?ly1+(W#g<=LS=eGPaio$fvS0E6?n!m1nq7VN`*C)Xg8fUf#>71zg~ z;VbK!f-HN^uv_Oxd$=mNF2vZt(b@zw{UPkTJvTCodps$O%m;yh zmF-(bL8nzJNyCOcjw1v5g&cf4sR$utY0-fO?)Hc8KK;~wZ-v_ag1SV3<4lkz=Kf|H z{_?Iat12g5aWcZ(ecp^=e#?Od3FzzQbPo!jq5dh(F=OYEF@Li3th(XT7LI&~k~5kM z5CLJUU$Yc5(@z?DG2h9Cw9tJ!bSdZ%NU@+kd?h8v9hv+Vi(Cn9& zMWRW#nyshLG#agQmwQ1K$)=KUkBAT2lOPs@Jl9+R2Z&f{Y)$^YNW19SA;`L*e1S6d zR7RLh+8ij~^ zOCGGc#Jj?iwwvd>Ssa94-=s($;uU6}X7V0U=#wwGcO|TC$v{@%bUM@2Fy}@+b^IJb z`r38Bz&bKm%Rb~axk;Z=y9k7_?E$k?z#T5OFDI3Ql|`qluTQ~zfd9dB?*Q;|tQ!rW zyxF?HJ)WZl3E}<9h&SM9_K$}B=_&fTdE9KTCO0>ccj2A6t@+0pU^Tkw)i|ToM#97; zQsKaN-p3-HVBrO?cMR|n1OV-y8z+w&+UDv~`rZS!P@Z(I&7Yn)RV4ZVF!tEu=(p&M zJz&(kgE5b{i-ZC~SUyk=^u2^_)me*Y$M33EKqmLSC3CKMnF4myffy8rel$$O5A@04`<^t)Im`fJ_lII5-sOBFFlW#*Os&i?Nj23A%(Iq_mZOGJ_7xzD|j zFM!FIY2b^um(BG%)`2g)_G}{K!}Ypzv?uVTkv0%Q`Z{R$>$;R^>Ob`A3uAghyNqcl zKa8iXAM)RzsCs08I1~|*a}W)>RN5l)mwgC}p;d|rz_Z9XAPojlv$*z=TC{3-P9CtF zIq49*P+@*~p^V(2ndLmf!?YP`$%{J?_z=7=d51?j^MH{VTEwpT;Ox1S^;ci~K|3a| zh9d`4N?BTS4e3Gd17sias{IZc>4I2WF1cdORi$dG+F{b1l$hr8E{<-+Qt`LEI-+}O zfC`G`53CZ7WhMI6@y+xC1aTL1A%2--CZCr#%bb*jIjNX^N+hvAhxXkq5P#<>=Dnxe z!|1~0^y>#TgZTO$n(u9E9_Oxo9OgQ|-mqIw?MgorT7JTiR8Da$B*%!f3pCr?)07`r zCW!W?0>st#qKgyx_EKhR!(g9@BWWT8iK$eGxvAeZH|DF(+x?6el zh3K!Br!`{87}Ur|GG2N-&jg0Ud!5cI!Ufi*5T!eym}Pu-^Z?>reziTP9;p9{ii^+eh}eCrK`%^}T@6DE@lj`J-<^ zOHk*OBwC^${?Ur7U{`Y;A64C7zem>85ve_bO8I$eGlSe>7h3%LO7=*41&no8`dKS= z@ZF=TAZpHbj6PIbc>+X#50ZHg(GWdcL9~h)n_c{x#)9||YhNBICow2PsAZOwk< zj8S?l5q??O^Qns=`!3-$i+d%fxqSSc{1Q!MSWvbPBaaq;?NgzVj zRwk(>Lftb_ML8l$iirlH&d(zSliQo_oX;ecR0b|cXdnF4ZTDOv{d-|dzWzfL;=ao-pQ&yI%9jF>k`(F`{7iM zZ=1ad?hW&jsAcw;xIo+-F`#~Ya`L+N^Fy!M1Cb|Wk3PUn-9h%QkyzzU zLw#lA?OK~T>EBmWdI|gLDD_ROMg&6W*nj#Bmpz==&(~l@dG~FILXaQO#-Vn2=iu?t zkD+DPbb05k5zHs#{Y-tvLKYS6%gaOK9~!R46HGIvkUPm&RjZ%YbWEhIvL+v0Et#f# zu1n8=0)D;Lz3M*0eMQ7P+z^^Y||hAc)AG?tDpM|-yRKwtm2W!O(Qbrwq5qoUAa9RE9clD&wp9Iow%+QEmpvYPb1ylSa4pNx2c&`I8} z3^b#}^FFVk)UZeE+-d&&-H&)K64!{Z?>TsN*Uwpm&HA3ulF&nxP;me}sxee68AVxZ z{ciW0#9~_OQxL#1XdKMG z5*rpL1>VC#i*}Lb60oe zA@>4aI0qiA{1|~MfGU=k1GBL0A*w}{tCD>g4Ym$LzKP>!jOJHXj7-^$a*bqUCciz) z8_!zPOILxiHKE==0y19{JLF#(oIy^!A%w{f8Av2w{+_urt@jkRsw%}%mGjcyJ)BL^ zN|MW-?*aCW^n)kH(=CQ5+JDX*d0<=PWu)twjNz~?$^WwRfu81#zMJFsE2)$G%@@#r3UU4T4%{_xA9JTM zx%D%7LrE%TPzPRW6+J7`C@??%V@z1Bp&_8EumTbd8nXm{iyjewSHNwF6BN` zZN|IcN2ebg>`JlfMv9i(?t$q24%MaJ@!4rFM633m271#Nf_ zUpVh#0B28I?c84GlX`bn#ZcpY4i^J!xE1>21sIhF6)vaC;lsVvu~N!qa>td2ul0o= z^IJ6&mA$7E3b$W}p3Ltf&|*du`+NLxdy5qoBQdD5`{ zPn@;i??%P^1mO@HSbb{L!c)$Vv<@|f@F$h50yk8DzwCKEN~s9)3XohZGtf2=9Isr? zpHoW%XmZ{lt~+?{S0;f>XQep)3IdF6P znhP4z0xrQ~>_`Lb2=ZGP;e20^M%>#*v%S{mQ{hwZs+ z{hbiveQNs@MZaL4%QKWPS8)b1v z;=UJ`UOV&xo>D*m>#|U@g=v3(c~;f`-cPqkzk`Q8UD?4$PasA<`)?AxA93;T=TK&; zriA$riY?&Q;Sql3Wv!%Jj}q96=Cb2U({mC%|71npg6#z~_d`?WJ%=T7F2xSuIe z3ASk*T`uMB2~q5~#TiUrV`B98gGfXb^iE=?#u9RP3jJw_suLu#(1RKJ|=8UWF^z&rh)6U;J5q8YaTay7X&m z&Xiwn{(cn(9l69R8r`Q;M!g)axqhj+Q#YO6t0@)+EUb~A$NS6=kC=}bh|zs$DbSsJ z8Z?=x7?y?YLj@t9&I6>GJi82r2GfsLKk%xXj*(>4`?XyGUE`lj@K#{H;O{FWt!KWd zfOn51-2Zw&759D2?ZXN0RLDgax#`ZXbZ7k|4Z~qrHB9?0(cE0R@>eHUx2JalKZv+C zbaAW2qx`+w>Kr-N4C^OpUz)VSU}Z0+LjfWK5P@9?l!n$T*{=(uov?xa8@{y{m;qK~ zr*`;!PiSERxr$cGNVk{@#-%1d=b`048aO3K2Q_**!_8GFf)V}}-GParK%~UlIMXhl z=bz(;*4xoVbJ^yki+R&Ox8B#?E31oLEg#||t!yJ+QY^K9^)rV*PjQohM~TOhz5?6? zey;N4(d78DbNLX{dc`OiRSxP+E;5v#6Uem<%G?Qe5h=MB&?7*zJrOhYjd&aXHsoDb}!^es>F zo$t=kO}a+zkIZRbWu(4m=k-wcU*}v?(=zk#k)J&P|M$HuY5a5bv0Ld;sjtl_n}YSJ z$9v-o`fz~AfDf;0zOTaE{dRXLqNPbaV9wKi1;m^A^;qh=UB+HWKxB}*JB2$%?2t|- z@0i`bNDp&n`CZ8`EZN~ze1<{m2e7yqF6L~KTkRRi>cxc+h?uT+8onCC0e(?5ndX$k zKpdBy2uIC32miYt=vI41rGSIcfrH7He5m$C^Rcic!V_Auh^>o^xMw~N`|yM22nGfnlq!(&isvooW$#{@towCxDI%;lS$$kl50uq8MYNp;lu7_LM`VxjZ ztSTD45Y{J1BF;gJn&Di|Yu)j%dOgGXOs+hCayUP%xc75Iiv8G3mkTGy0>{J4o8xY$ z*Olqq@lTwX&xJFfu_A^GA7y3F?MSj^Pg8%18hwu?PAS!kcC2;y_RhSaols3rV(Mq3 ze`pRrr?%ar~=h}S&Lf<#!OHOXr01cMU zj!yu8t`m3ffI?}5yQ6(Zj+56p$?UZ|T__0KtXGEkWJJazCrvm_L;u5y?@$(1mlMJq_h^h9DSN@&E zdU}+4R4(S{Gx*l=eNUB6WIg5Q#*$JxgFD7hofI2{J@Q+g;x0@}$up*CcvDMXA zw+J%I;GgaTp3knKtHx_ZZ?nX1adOuc0-eW3c~+G*d&)oT`U`j%-G?;)H66&?ey!st zS#iQ+S2`BX4;Xv&&(u&7cBiRR;Cnu}Da*7Wo%J%jN&J)`D31M1X0J}~%lTHGdF5eq zE8o%W;rV&Eo$D?IoNOS*(nnzEMWc52+#%tW?%$f+Ge;Jmx+>^zB6ql&cz^3(Yu7Sx zJknLo%OH?-qmHNd8ulk)UZ)`c&WKrn zkf)Z~PANPdzK`IuBby^0Brr){H;Ql#63T=TPUfAjjIAkNl*+ej^&&cxZQ+l1u+EY{LgUZ2VfPYQzZ8Dh>-iGUN9fc}bgB+!{#Djqu zHvehhIg0vz5E*KfJFuEH@`+Q(y%he2RT6$9(Y5&|G$WhkaH1og*k8Cu2VN{txKbPF zu77$Y@A)hkaoh!TFkg?%#y04e}wJ+Rq)RBU^mm2HTs* zhP^-{f^^d#dFWBb+rTd{YEDss)zBt-*ItHBCDa_widiAh;$+`}Cbx1v7<_la(qE^W zs0}v;@rCfj6$YsAp$=noNQ~R7=SlDSOrQGwoxyADv7h10JBHq7>z9&vfA4&4Kr#t2 zYAU>sq--sMK_%Bc@xn=Qm{%`1j*shXX=BekB!vtXOvff?^Uvq|f=VVQKIH5ylMm9& z)CPTV7^U|a4*5revX*42W7XA8DRy3zw-gh*B0H5DT1O*HZ!>(50o`Y=eB+9mjBXmP z8Bf(;5`USDH2-`;i!Pr{pfOA_d!qb@goH2*mKZES&^+Ux0%TIW!y|wmuM!52%-BHo zsCu8aRLD|6Be*Dn540p8C3|#OXh5Z1ICkCtpvdNUWwU{04DaqsV~^hRAJn@0Q_~)+ z*Zb|Qn?1k9r4&@^>a&Y{T7XKGk0)t6Id5BgeQI*QaIob`4BorfW!&96oZ6hDZ$btHgK_!CbU6$>X(QHhlK1$-#32G-SbZbgQEERUe}0QroMA zjkWYck9+#1L=5%$i*OenboMHXahGx#;}UXa&=SVX?4__wr31PszPIp+t|;ADB|H>^hJbX0!rC2pQUJuFYbd6`>qIV``g6EWUVIwH^B z59vXO%am7_i%#$Hk#n^LcRQOT7&V_(&z?q4t>*d5y`8?Y)9!v43n*hBW8)J0F~`9R z<29#FA1;Z9PXFZA^(xn9ZZ}*hD~s$zEsg$%`7wS~eE|JLbAH!;oM9t6u^-m6=k>YJ zFd}e(mn5f5m-ox6J@xGt^!JX5&sDiBGN+Lzp`msb#`96LU(RRz zQH|x_?# zHk=C3SMg>6h5Y2arbh4Ip5IW5&-LVaw)awQcEexYn*Ng71~ahZ9$|}(OMSH_$bU>V z9Fp&A&pGFW9zMS4IQEs+z)_$$Y(SqubDyfN= z_+P>Aw+p?()~i?du={m`Rl+SfJi_0V{W<6(QDUk&VP$*v`crzRZ~Nqsh5et(jCQX1 z856;mI(`Yjes?iEw^TYDRie#2Nc!s$Y#BQ9zgq{U)?-ahhg-VP@ZtKzNad-SboF43 zIBD!$7(svdD+xOTkE+M-hGAAb!_Zpuoy*&u1*sHa40-Jat$mTrx~X5Sh~6}V0E-*x z*E4*!n#pbBX|t~Y;rB=QU{aF71dx~CUJqPX>`l`2PfNZIlo%fkgUK-zyvfouiOVAo z9O%yoKvr6K)NPa8cJBlKrkcBBO8x#J$Xn%yHOJ6w4&-zDOk=Vk2H}FHn9GZpA$A52 zgo&_#uD7_#m!btPFbZ-h(E8n3>*fSyDbOys0P#L@PLWkP+vF|QHFnMVP^nKQhiA80 z*gb4^v7R^=`ghN>xb-C4znAc;Py{(u^y!nqO7r&O+OjyL{khg^+~8smi?NPHQ&3(` z%BnzlH|F=|66fT4oUo@={PTR}ZOzplw{TC|&MrRJrdB^6kH|Mgt#U*8^VMQPhn5kG z8F9^x;k*Y(^-px)&hhw5F@>RJeINC1#)J98+>IS`WuS9dwYv|pt!TC;EPuNDDZIJo z2aWXU`6=3_juy3mqKxGw5qbNx5v)`~bB9+*hZ~mh(S*?0?dy;OaM!PuT@ZF4TKH z3G$Qu@Q3^NWjm8bdrVv~xY}VifwA7|-&gHBZ0m<4T+s)3Cf&+C0j@@s&3l(o*)nFA zVobM={T&|gXhhp}U{QJZ))oiq1XoV|qkbhB=5Seb`QS3R#|rZ}3C*-( zwjc~+j@lSYvkg3`?ks_0;M1=OtX7Zr2crspdGlR1 z)p4yImbG_WIm6d88Z6ehAIv_W`NwbYVx7E_xtd*7Tt+FrdXH;wpTwi_<4tf4#5h3D z!0j@0roLa9QS0RV$Mc>Ldom=TeCZgoU03E!IkhD5qhM-V2*It(hgb3@pYFNzZJ{45 z&Dg_~11+FOAw&TQ-gJ!%2ks6XyvlUC>%I%cSkTjC#~q^AH>D#J#m1*l7}oRjl7-jD zhrIZ8)t300073LyZ5@bcWgn)a+XMfO-ynaA2j>gt5WP##hjT41it}TgPFNn2mjS*f z3flSNG{C+=3G8W{!&iokb8$Eti4hZ<7^7pAX{MI)+kEI$1&yh~6N$fx%K8&;rEfs$ zjXexmL5A%^>Hb_@qr{phywvYUiju${i-9mA0Fyxmq3C1f?%m-JV&#IBoF6TH_V;t( zsc%TnlIv2fCncX@`NP6XU2GE0mW`(#9`eU{d!-E;u?5&j4So&x)|3Pk>zi1p<-sy4 z@Dd84nP~3QMz={uYe1B8TDueyQxmSeNQj9@$OcVpbP(d2y{2B^rg5eeax z{gD0yqpjQ&+ug?k{Aku=iH%sn9&)rl*k@*EGw$U;NZGfa`XXNwpH=wN`ZIJq0QGhi zXwQ_7GpAjlD-L}p^|+4F2DB9OE01Xi7Q!DqKH^$GndEGSS^w`$7y zK~AeI5Z8gy5%$XxvSiOi2jqkL!9921YvV-74je*_{e91dSeo$s+PurIJ4cgkf?3{| zY8MW96ULKA?kE;6oxeq#&RH0wupgpW-=}IOqp#U(QwAIM=FxmOM-#r$o-7;guPBchl1(m*BeAT{U6)Gh2{Q4*ibB)XgGz1UE5!B&M zY*UGW*tTMhCOX&hllBez&>iYle9m>*Xh_$!STCsqW5IMWvKqC9BQCEY5!NIj>-c}?~+x}GlYz?9ps6x?t2NRv)_dmwP39*-W0 zynTu7$3}I2)IMxgGJZ=i-M)aqIhD!y>`L`$#~GTIetXn@SNFB=7hU%FV;>SB^D6cy zy6dAWGW>FVqoeU1Z8e|O_tqg{U*Zlaz_4Z2dZ4g_BqlGNAKU;kCOpZgO0>gBAz%#i z@5a@#3FCzbwTk(>#i!4msSVP$zIq1I-+3LWY7ZA&`IHfzlnhm3bnx1Uk`O{i;)e)$ zxL>`4k7eCQk9a$44XBH7ao6uGGx>~reTN{*#iY9 z*5ugYwAU!cG46Gdj_=QE%H=-(BBYglh-T6VG)x(xX9VG-^#nW za&$)%XotJgoj}BSZ`%HAL^Nim#?57{s4r?g6&{}VnrF}!p5fABv=;XPvpB{An(`>A zV%O*GLB97y0i^S={DlHD%Bu z`!i}RXl#TI7w^=r5VqI#FMFYsXynN~hc1A_LY5vBJ%fTsr>}5ud7)Wl0FgjAF>RqJ zSj$e?ZBcHF?J&w&qG@?MUIVmuC#j`@ee}t@)Pkj2AAF)=4yISD4yll5m7`BChPnGh zeUtY(yxSw1o|TQqN@JP#)er<`E&_Dhme6ir=M}$SsJYK5OGMA_EePbP?33r4{F)c* zIT?bQ3Nzrjh}1Z=yJBNV?gm}|%9oxxmu)!&e_7ytEHShr{g8*-b^`?g-HnHblq)Z_ zmD$J%uVJRZow;O@1dh2;6-)UuSm2mt(7qs}_K_KNN;7lRPE2ruAIFQ%iN-&XQb zM4T}A3V9=A9^hF^^!e1;ew6>#E^g8vDLBciOC1^H+B!E?_{)7A*Y0aJgZ4T0Gk^4n z>XDNuWOD2-lDuog;BeU@qlWma3s{RF=ZVHpj3^Z`q}&h49Dz*xQ{5$7WZ!;?p5I;d zVR}s@xUdq#7Y@8tY3ilBxAyy6ewg^Q5KEeEI7)l#99sIZ(Sb(`PEPAHwCg^cy8pyb z(Je~jCk9{r2Id?b#b)9J`eSv1)!3HJ{55;E2a2pVva;;Q!+)*^2XX2#?yhfAg9)HT z?NLZn`y>7fu|BaY1TtI@e1`l{0WAJXJvdwo`jQUwasAM~+#Mb#qy7P<(=hvuqw|)N z`YVN^#|ML;SmQxXI-*Mie^keeTCZG#rQG;BNOZPPA)0RYq7hed&*@J&I-gy51YT5H z9ryTUf2#a^SxGQ`F#osq@4xZ{dieGg}-lXr{DheN|vB02Uo4qtnIA4OKNn%DdCod$ldaVL{fWTa)U+o!$8|5Ahy0 zC~w~>$atU9TObD^m`57+bG8lXeo(x<4+GCUM%I5`;%~9V!A}r0?f{d_S00qb5znrG zjMn}>XYnH%Twq=hfD2-r_oXWFX`v~f{T$CG36C2BDfW?uZBMp5h9_4HOMiRYiu88S z5v{T9<8hb1#j$0+3TC=wy=Eyz=U2j6Z)L5Lr^M5W-)UbI-_G&u-zu5Ng@q1IX%fCU zVLAtLrmZt(J4h4IdaLE-`^Yrn`>E+qKz-ont&06VYB}3?vFuB5yM8TPmam)lwibe| z#DL!K&Oq7rV4<9sQFKX@IO}94tRL(6y8BA}f^p4i8kXNu+R1(^PRM6YGms^t#jNtK zXbDA7=aVWkkU4>L39R>f-4j4k%e%AkS;+V4?Oy3VHepVSy`j6}9zybZg-|SEB<6G4 zFWBFwlpN;-x5Ni*+o?yQghnqGC(8T3x!cHQ~X^%hSeBddc!@{Rsoee2!o?z+NEKFQvWcM2mOOoBGpx_-#*?) zkA9A$dKq7P5+t}qrumyPy;g=pl`l?a6(xC`rZDmd`37Y+~Jwp@Xx0;d@-K*L0V zV_qSi8hfX>dLM!c-A)4jm3tjZ;6l00Nd3e6#oQyQx!JL`pNHZ50CExwNwgJDEj~;x zJWvVGoX&OVNq1D3nw;^lpc$s;ETF(rmUh3qDpOtH;_>$I-1+?Ti<6cnDYf$z#n}(H zg|%+#J-KVcn1yI)NjP~=4~GX#RcK(*%ku07+JRS4y%@ZYWW4lEyqBle*g~G@>^A5{ z8FW#;E$Cucwe9GPH1ix3%7A+;rS8Y5#jOB4XWC)`8OqL6uus;j^De66ZMHzI%+3*| zr_amLtMcZ7iJHH}+6LI+Bjtw^pjxzgP|Iqu!j0I!BpooNQKQdVd`zPqIcUTG49-HB z$4eBk%=2>Hk97H_txVp($L4ScbZvVbbq0y+{ch6zkUrx5y)ed#sa)hgSg^d8)>hp! zkznj}o>jXqu|-efv&dFMz1tUQYIH<9viC-e5BlxNBhvlGp)YshEZ1G9d}(RQqSfqs z1weTy9q3H=TC>PBT{yzZ1)z9~Eu1^H&)uvi&#DHp#jScgs^`#J%bhiQmwMB@}Uc*;D)^Ec+ zZ%z*(7c}?U9Z5bMdhSy5tHc&J2=39^90^`qI7b*p(0)v;r|Py8@>@N8plZnmOWGsc z6MNshxpBE)mcDibE^2R7N2913#M&Rg75YJ2J*wYQQq(c<8!Te_e+C5Y)fPzkG~^7~W&} zf$f+(RM`h#85!lP1EqrJtu0O zycp`;_%NbS;^r|(r3E3x0PzNJqu6z@Y$_z#gWQ~QdImgbC0>- zF@8u-WS9U~@=`yq+gqJ&Ym!m$IjG5`Q=L>io z&!d-xtJ3cTnih=#hsA;45M@5?Q6}d+m~`J{A#@ zh>l;B9AAiO?#HHk-ti6`r4BWJ_34V$Waad%jOf${+NNH*7i=_~SgR-`WA8L9ll30? z(daNk^(KT1e2>fc^`UM&LmKm#-eoz5{%wi`A~+uR`)|}J#?+1#u+WwKCcAt3#3K3d zLKE}Gm#+JK*w|`g{Y#Xe=hGU8z05tO5(*vx!vDZu^fH7FpQ1&Hx1?JS%>RT}*dBEW zKGfB!$nkIxEIcHphy6VAL=9o*sSJUuBMkd(LS8OXk05@>;Rzu)Ev+h#XG7VO5_vY zDr9t0Du>dncOAIcx^cTada^HeAc5#ZiNpyd1SIMc2OkE4e*MJ%o=v^^eA!C*@ zmohnep+TkY^d7dW`TH7Bc4#=cB))y_g*tv$C-7|;)z{`9R5#iND#U9~@3G@wRi6Qr z6BXw91(*U7>)#jAkdXIMHx-gbhl}nt}wet(!J6GvXnh#?~VFHPy`f|DO2`P zHZm?3P?n%<(Ekbl=iveF?MmBsocEmX`FtVd)R<5ZEC%DyL16^kwmL;I>QEXnLB=nZ zgjOM~2YBrwTqlrZz+{b|A|?XPwE(-&NKA#iL#PQl^l^Uwu!4tY#3r->jmE8tNNEzy zl42nSpd6D4jToJfS;12pX~GADQgHyN61GTGCg!ZV45l=Kbr-*XOK@}2r&ocJPoIXw zk%^Tc;15NDda;Om8Ap~4yIl$sR!AU8KVotErF`IyKwp{vj2H}=!*R8k$QmW4QULg9(k#5Dilf0!4U5rWK@^7`27dk~!%={m zW<`NmR4iaKQGU!CBT~pdc?zX)CS($^IXM2wfU5^Y1_Yx+8UrabNz$IIkxxs?>=HUi z=?uXn%5X?t$r+`7jYs1XCFP0|7KLvF{GJj{os`HK^#+eYsVvbcB^Lum+~?Sm8*zC0V3!_HPNiiFUOHkSf#cIz*jZIw=ot2 zR7__{kcC7%>_?oe(Wgzxl>z=Fos6?#+N6Pf7E>9`+9KgqB$a|vT;`D$A`q%#zHkmy zLkW<>g2=Cs_oy{?BQO^H-ef5);$v@90fn@h3y|Y-74Sy$abI2%jIlbAASEOPo=^Zz zP}u?&2>Iolg#SA7#T=XWYLpo%PcQ_N)|Af9&r`x?Ahj}YkP^vY<6=Rw0Yyb=HW2f? zZ4SsGYP-M#4^X&rMvNB*VMWLsg8NS?C`rPx3_osB$D#ES45EF(6 z`(t3{3)l!Z=dhJ%qcET}2Yn)-`f`ZK?$ijggr9cjl7u2;qJVv4i3T&Q!6Y%TF(c{X z#Bi-bA#|OU92lx((-y!hqzfewMuypB&_oDA&{xiBocx%`+O2%#p5{_-gLfrum!VOm zUhFb!!4F&@L~JqF zd(%0kFd9Yp4ar6k8aACTIn`oLVUHx#N)@7vqG{YFQG!cCLK)Oa1ultB;uqMp{00mz z_jojv$W7NHWsWCKV9UO@p+Q~~El9Kid^33I_>KAaVK^h^%) z#~@CN+il61N9VF?lwm;Ivj$@fTn|x$Tt)g*7RYO50|Jp2wlhrclozR_hRhosIhhQ6 z;zDm-IIV1=0-UFeY)%o0rm3fK7RmLb0V#OjBma#=7>0!+yTzc1lIB}^y+5jo-qCZ#Q7e$R3Kk1&eQ-@NlbWAnewEcDg77e$7vb()P?Qg7-};2fxP+5V z%3OwUlmoJdj)wd4bV%04H-mxSDr6NCxJTf`3UCXwwkBK-yCNn*+zHOFOSr*e(#H~v zo5gb`SH>g}!14)8afTC@1VA&%dZTp8lTpVaCNm5{Bx~11L?Ay&iTr4SRAfNSl7esq2@FmAK+ECtPoUVb6-^1?vc^;PFt`c01GqO-i2Iq4GwJpPMNrLvym3;% zZ$fM$?=l%+^g+j|)WLa`8K2e%ZC2n8D%0@i$~2g^0N&G*jz9oOMESEO=1!|Tz)b+4 zVYefia_lWEm~s$i!)_jlV*PDiou=xlGI{ z4-0&1cld4gB2 zbrE4Khasv6&`>xO(~$^^D3wwfrO3ir7PV)h;PF`~gp5`P=#wlSxx{M=2B6ymo*y$Q z3`&t15h+Ar1sZ{AqOuk#$ZXg$2F$1z*}--KUY3%A?+{(g36)?A94MKSVDjw1pxBE+ z3NTZ2#T=oOK?SiZ!Gv*?)Im#F-V{tG141>FcED>Fms^V>JC&BC<=G$w*l~G6#J@jN z5iBemI;DWIQ_!^yVmg^tOp4<=RXT-v(@K^SWx;+XAcUlIOj{JmY)K$}8r2pTD7&2j zYdQzLQ=qJM$cr8qWnwaz^GQySa)Ti_c(Z6tdaYHJ(is5;-t8s}XsWKTL#N8M{J`#{z~()C?$BxPX{L zuVhQ$Tbh-*)k=x z3~W$g&B>CC9QeYlRtp9V8HfWhn_e3b=;K;4>lNF@1VEWNl0~z50ER;-uBI|!y9#k7 zA`TTA#&J?+=2xVM#i#MfF$^a}A?U@mktW#G06Y}Hbatzefo5BAq=cLDEMc>_Wnole zvQuOZY`nEJh!9o9yn^3+6j5g|%|n$4aUjgVDadWb3JSSG7qal*V-QHzaX^*15k9*I z+aT?8;I;$L zrdAMXp}I%~JdOYyuFwEjPU;X_I75&q1dMXZO^GFWMiD^rzzWu9b#&Mu)@a~FUi6^? z6t}2LPzwkDFOM4m6C0ZXKmoa^556`msS7|Oki;19%9Me;#Np?p_Ov`gfH}HXnxa82 z1rBR`6F?zH#q^$F+<|#07ufWW4D+^AFY3|xUG@y_3y3kPz)n#bCNIiL{BFMw@=1(O z5woT;6bES_90E0dw8Jy`@UYdI&4M2U2YGbh^*i8F1VW2M4B@sM5)}>#%;;E|wwMa| zV9NwWy+)vrgg`>;p{<-gskXw(0m>hpBI-BTg8Tq9f>WA;Q~AR(M3QitwFbY)0k-2# zgNL8z1z@!BM_pSsk!5*et68XE!jQBKuBWNN^|xP!HBv z5Xykaz;0Dmg{RELaXIlW^cL1+!@`TZjPI4+!u^ zlY-&!5MxJkbXWq9q&0T<8xWL1n#pBwIaJG`n_ubk8`Xvgr8N3t0-Xdmi47=8g?!4G z#S~}4ehFB1@Y|C@0eq||KmJY1Y}6Q`2!?VX1-;Y{@nZ@Blv$!^jX)2%InF2XgnRq{*+xF2=B(-L|3jK$&{twMXFXX*+7Lsb4<;=^Bo2!^B*ZC`uD`_mzq?e>f%*5jJU( zN4T8MD6}ekvJe_VI6|VsyAl{iD(>%?|vUAUKgRrKqSRH4EUxt^l5yIw7P?DHZ?m=4Ms6D;5}ljHmePg0tIRm0BFt-G6gcW5I{KKIiO^b z0RDT%MhE%*N~p@j{T?=AluBBViJSqFPa-@bjbL`3=SxUZm^d0rh6M?)D9kU}E?F^S4r0=RUlOxh5}@`1 z+W}ha^eQ~^lF}peGBUSV3}XetX_r>2N`#VGC+iDn_%pKsk5QaF5wd3~%ArolpzaU7 zzUH`G;^MqPKVb)5jV~P|WZ)mHN-2tdPY%tfJU$m6vj_s5!6S)C0(vtnQE$;C0LoAM zg)FOg=?ezPKuV)_u-Sq~vbJQLw0WG-0%Fs9lDT}csLO=#Vj!p`tB@(@cE;6$Bv#OxBYQ$fJtk8u=~HnTbyM&f21@l$?F!m0&0 zExb=5ANYd<0$a4`47AMyy`x!36c7x*+$Ow8$_IWFtV&)I6`(nnkG!Cj2^>!-Psv;I zCp~(!Kqvg*3}lYc9GgpOY>X?K#c)Wi@k=o@g2a^~I+u6J*pMn9^8l6*ejSV9h=F;F zuZ2h#UWrPHJqleB+CJ4qete74Ue-&HOu&IyIGrG##z|W-A+*?pX(8NfARRtE;>zay z{|`hDf|WAJ6~b25Y|jUP8&eR)Au9w~B~FZRQg1dvCf=^85v&+CQ7$V5B1;=&B5WQS zEW*VA0S>}tDJ+VN*)H>>0$Otl_cLCHN*V@+q{i*g7}2cNFE!__+Nd>H;IbxY6XUNO z+*_=A5OgQ`@f8otGhQs5mit`UlvW?}MC=0aR#k`?PUI2k`Mgs}sCLMl255BC$3rGz zF=&sFghHNS-^zELm;ws%I*-Z*9~0rr1GzTrq2(I55F)LG_*ie0X(BP7Qxha8vScvl zG8&l17;CT>yn)=?2rZVd=KKK1*9PS|K|XJ!6H3bKvq5YSBjwqG41*wup#1VUf$K6w zRWv8@+Kt}0Cy8<@b6)2p_?i>OZ$&Ph+pFU!5!~G(uts!l4fKeTD!WywEqYQZ;4p9! zpdBDGZ5)vPnGm?H!aM@*bA~p9{i~2j>Hz}Icv!t!Qs8s}y*OPGfn?2Tm1|&c5ocV= zFb$PCzD);m2WfpC5P=c!7Gl)#gfOAiL9}6m3aNyGMU)U2HC}lXfc6$)4x$|_W3?6& zZe2kau|Wm^1mihJ4vnY^n99v&Lyjm%7#(8TDz@k>N@X5sui02K2k;$E1>WL0C3t8` z!7)$_<_C;`E;&PnfIboRC~T-c3U&w4kS!N5#pPj+xJM=E#`EN$}6GX>hemCp7cLRsc{SNj~GIlq3la=5xjiS)q=xroJ|hnP zM!3pvwh9;($QsouRXV^%GE#>{B{mi@OE90~Fd*(QR-ZfWrHCjBkWFm>7`nw+NJXcT z{M%KFqz=FoT9W*Jks?G?TmVkB2$eOHVyeglohiF7Q9wQ3IFV6_oM9F2%K{6CZ<7b; zUmOm(aOnmnq+>-YL()P7l1l#Ki2w)84{gGgaVl`AdNY99Ln8`(5G4c9c&%Vko}vj( zWw@I&db9F$1~5z!Q&yXUB48SvyJJB`AqqVp@JtDhK~+jpF|*#Hml7!@7bP`CT#bW- zULC=trU1hlv;45M3q&eKDlc;(yuOIA=dG9&Mw!x@k!7M9I9bp@%r6o-*r;PM@SiAZ zG{Kx6PC&VgIIp)V-CC35?WT?qp*$+_>EkS9GA+SG%;GMn;T7ImUq}&F3H!Ct97&Rf zGyn~7Gr?~pCO>8qNecYu;U-H-E5K(3ax3ix<(-!FDN`DWo%Fau37a-xgnm4!HS7s% zTtP@w5CWG5>_Fmf6~*wa3s{K(+++mN0OrwSNqOWbm0_b|E2EVgvUVb1h01I?AaWX@ zxvIzr5tCPxCrUo49L-wNaFszY#B{q1L0<-bKoejMDFK5?uiDAb%3{KcYV9&$t#Kk1 zs|*?e2E_`vAPxdhT1o3oiINo@Xm#KTqgAj49iJYIp(+IMT{=6o#|Av0I1d3$M&)J< zq(YpvM8GEvlN217T}{HBWhSsggZCf>S4UP3&3JM{0=i9$5;Y@_*fN3=>5Gfek~JOn z8)ODThI!;zUW_K)&{GF?7%q$x0-?n&lAwUoRKe`=rdT%_r0`He8kEW1;*2;0nOP|s z(de)Yr%A2UQH13~&!N=TB*5 zsLh^Xcxf#ZDS$8xzfToX${g(0hydhYs1=V=;b6>_@QCezJqu8Fhr;7BA`wA^cBmyu zqb!2!P@y*}_a@-XLYURQbkGlMBSfcE=T#-G7z~nFF6Ne51gu0X!$F6kbVAQ;Lc-WX zIe1++%`rX(P>_TSyE7N<#83|7D)vbk&ADd!GJ06M8XV2 z_O@))R+0#WIZ>7lMqG#iZVh@khF?DzkpNQ0MUR3JL0gOhm=V@uI6|UOuZf2f5?U?O z%PpKJ56Om*%O+#8tRoI~bcK9Ai>sV0qqn(=nUErZCJ6(?`Xapz2LPvsg35qopu`+*T`EtL0yO6$ zld*)pC$&0(Ulaz8heo0nq=PAU94H-TGp&&2JXkEqZ?2|z$mdKOLfJUy ze%ql`#C%bp73sbfe(h;%EuHnFCtZ4|^PuWl6si43Gh|jwDhpIMyOzP~Arb zRNj|zs6APmN=BM(hNv-QKczDlWA>4 zL?bRX3R502r*u(?+rV!RPCG%zpwqYL1gKCh=TW9Jh%%fsfH^b>Hxss!DCvhJvcPFZ zz?qh|+eHvuV7O9{u$uyA8aIU{=?F+;;Hiw3IJ8ANBsiUs6bx#nC!XR?nq6rXbfzePL z1dnN0M=5i`C)9&cXEf;&l=O^}%qqhS^|sPV6#Yeq2vRF)WnKqZFrc1Ckohd_;W<`ls@M8`OL`->2+yhzAq*9zVNF7wfgPV0y8B|Izi&!Xz6r~(K z2)HjUkd!Pr3nV_Q)}T}jzcd+uPeqt<$ZdnmwTR|Ohq2)EW>UGB3bK595RU^8EgS(_ z4)k#)tzwhkmdt~H0OTStg&0Vkv^>PWw;Y+^Oc0JrJc^iz7KI=!k)>i1tH7S8ivkSR zZUO;jD;rO^t>U!I!`OmpHD+WfsS+kPVK8z^a~SLl3wB2qL5c;7jtiTRWXcYP9$u|F z0bMpR$lfLxDV+_6&8QWLSTn3w;z)}WC>qLVqW+THs-Sg34&(w{!ekW^>byQ>(%WNi z8{u%PG$;@YVkV$)<-7@xm%unap^`4-QiU|2-aKuAd(nGAwQxDNs9%a zla!~81*;eH8o|8)fB_{U3QdY&6YYvv3Mqjb1Jhj=0PCu>F(puwI3Wta^3M!Cwemj$QS~WU@CIzcDG%4G3QB5`; zGZl4ACgd~g{93TDQzjL{C{)`G$#l`>PlNG0X>q7@;xq>S-wB@~L;CX>S;+8~pJ?Qv z+k}vYwM}l$1yUt9sQPIE%tCuy>2Utu6v7A}eK?J*isKYcEoCsd02Qf1@AJifY9Dzp=4?!&v50UA(K($7MqK>%>z~^g%Ivz90rX?<;q8t zDqk?GQ8;8=QAH{UEJsO%(6Ho%M86Goe@`@}g>m4a(1b$)4G*jrXaI4O%q-wcU>uw= z3$RiyWH&~=T)+WtnTXEdw|nw}gjyq{ysk8!3kan_E0``uOhEBU+T(<#gyX_+L6!&` z9Q<69IicNA1?iYHt`CK1r5{EjBwoD`K-=R|y+$8(dbJod8e0fPpER4K5nP*K1A0hs zD0BhRp2M_JctkYD$JmgYaxnB;@Fo--_zOAHcU`{R}0s_dqJBu;sGS%6Va*q?Z|j0&xN5x8`Uz?u$aRb^w^Z5>Y|uB_S!z zPaF8-FQnt3PKN&}^HDgJ3z4+W5g?6`Kooj%O%9{Wl-9dMaC;tH0PQ)S0GzW0PVjtW zz}Y+tp1u-O6!+%L&@9exm}xLzq{48*jKIA(T?luk^d-WY z^76q}(yGX^T7FI9%wS#$_eek&6sYN=g14@`@gkp*$S4Rrg7}<_(Mbwb7?n?klq!|F zK#^d-Lp#-xM9L&oaY0+W1is)V0XVR!;$k-%XA5%BRWsoz%wCKm^cI^P%cKm@E?Y9n z^mam|4u~|k0l`B~l)?R+Pzg|F5PIOynr0#`DOljuGQ<@0lmy8XNXaEe)Sd^!2_J!q zG#&vN%L}}2BS4(OKzoZt;!!n$m(Zw5FO=9KGQ^xr$Fok11;tw0nkK>ii_*y9JqANg z5Zo7;0H&ouoE-~!AZ_I-;cqck6p@0wy34YBA!mNF?ZGzRBAnd zVWmV)6~Kd%1_x3~Ym>nBEcwi|MUjlej6S8=s|t$EpsJH8)M_}mLG54fGopAA9J~|` ztC6y0WhRBWq>YF9?};M$c8br0@{=EAyr-<)>|w_4?-pbz9NB(6n;Lw zbSOkHrilcL>Em{afi4jb1Vk7W${1b2!6X+fak;!I!WM-7Y(^pu@j!fxKaG^q5#F$k zpnZ~HA(WRQL3L7)cA*IyFoU&zC!O~59|-($K`LCT69jd*oTv}Va2tI7q&;CZ7m~gV@fJb~8F<1a6O;ZB;M8(3)-!qz?vDvF z2|mt2-mXY8pM{O;^>3T9{ZO8Tqa(nz;?kHT>Ph9Ic`4izQtgyCh$)pxeS-C%(LgjM z*V=sw3u=XS4YMSHsNZ&xCB#gC%z&FqNgh&4EFhr(;HlD9R7lhYoD_-DOpwc4aZ#54 zd|8joWMWB0%x1ScbU7bN6WU@}q(VKAfe?n}AgC_#s}}^4VV5bFN)fCT2X8_;?EsyJ zTo!N|D8C{PQ!&fI?9KT?T8~p&N(bOEmQW#Oi4^!6kT2*nLUFUCGFs^@;g&&Z-BR+K zz(OjY4)6oSjyhmgVtgA3s1{4y8S@PGa~K|8tB3S#tn> z-1<>>vQnjXm9)5m;s&!jBHsr7uy^|Y_>wPV<`?O<>$+_s=B)mls-i7x*I?7~6;oIJ zAw8MB)TUnJEA_^YMDN|%6K{2~&HUupDK*C815SQUkNUAc)@{XtZWBL`E)_9{j?Q~= z>(S1SmSrBKzTWbz@UZ*6W;5r^d3I&k3HjA;pIv0W*|F=6Z`Z3u?i%g7-K>1GLHqI{ zhbn5H>?Ocgko{*@jx6jjuh+HAkT=~weztG&gi3zRi%8jI)jzMQ4xQh=#bacs*V`yG z?@#Vw$A_43h+>5cYk$IAIkI@@$-BN!Qi^lN(`7GOk32Z6xp#ixkV<~fpzqnfQclB3=_TyJ< zn0fHuJ(a)DKbz5h{D=C6kHi-mycpiLp}O6X1{EFrdkwqF1>0Y|f^O=OiW5IS`)mBN zBNb_>N&d+XHOTUV=bnrE^qGo2xclnwZB;rmOFZ*V` zy8RGhy>Rq}3&pa@0cxFn>PNe#uiCxwcKw5&J^Lke^ZBR3a%T8~@)Hklk4K58uHnme zM*nH7YJK&3c*^~sM!do0%cfJ$8r82cVbNWct#;!uF>9-pdRf@ou1X_bcz6`@KQyosuIn>e*I*aBlPZz=jK_e%xe4UtWJb z{>h;ouC7ft&wGCK?)?tY-?WS6BdZjrzIU$su69`aW$GF~<=6eTcm13JT=~l$S?}_` zIgDx7s&xk=t*Oz+U_578M+qi0zG7SGM~kIeyB;6uH@4ra%kws-eadgH&{tK51Iue2 zCI4r_PL6|t%>0OUx zuWlPYcv!oyy9}sP{buc_rSq-6e=qankmH!E&hW8Me>!mL-&<(9ep#krX)onF^z0Eb zt>MER%N`9`Tz^=fulLkd-dy$iP}92dW$tmFo}X_S{(5LDZ9ProHi|YRH=JlcY0{ls zp4?zaewwU!T+1N+bN;=D?UvQs{p9-E8kaumvDo!x`Tcp*um4=}_x$;8ys2IIkFn7` zWAElS%11svx3v#?;DSoHO!>tb<+jD@p4~dMt@rJg5p_0Yj(m4wiK+3Gr|sv?o#s0k zEAKJ2+i7cyUTrsLcl~r}!2AUR@HO=Q^#i)2sn^wd@0j+Q_~O$3qxU|1`s|tIt6yhy z{@~y1=F6XL$_(5!qON#DZW=Wy8_pcMeY@}SHx(+jly9BHeb|^vJM#zl#R=1~z`&;`M*S1=sid z+TM6fR;}NP6L+^Ay_|XP@Y1_$U$ne^QTqK^fVuOrud(qopp8Z?f-7-rGogqTeokYdXT?a_vP5peHX2r zIPl+^BX5l8dSqke{pl7jyp@mCse_*XegET$fj)J=@zlFCrP;1|S2z8*bDXWqi77Si zF8^(A<^SINcia5!#_#{fl+{*UxrDF3_3Xj3CMwZCt%vvcdBURA6HGsheR9mW@2kt_ z&j0+ln7#Vd6sA($J@c7{ku>|)*iF~o|E1xpPixft`RbzU-!XsZ##DRJzprnuQZ(h! z-~C?sx;8m{aW_3>;iT5OH60G`uibK1uB>|}xxDvPdQG=)R~>s_x&Nc767|CNgN`(f z*IV#lDsif5@5=O)EBD{Mhb+3d`c2$yntg&0?B9Rn;V-9_KTce+DOw@(rjv&%0`Et+ zER@!LH@tEFnKw-yS3g#>vT+6VtM|9(uZWgC23;LkoYrb;pCt?G2CFHMmQ;)96ONp2 zy8Y?&7P?r6kqb^7J~wu6x$Tm9ZEpWV?dO&MH}Jh`O_ht3qZ{HR zo3CHmni^I;WLjL~*`&o&M)^(0^A%5x!(Uw*DP9O3r@hl-4E{r3#BQDxmVe%P71FZl z($+KnZP0(4vZA+vjn^uB-da6%bl+B$etxIx^CzvBr+*()ZXVy_`(bv2>G+LbFO*-K z(P)0==+8@!+?K~%)LYc&^58-Hr?y%be&)ORw|(}J#)roBc|YZB=XvqG%A{={e-AU^ zo8L~}ePUVXNZt5H_^YlH8+-W6%ngZmzrA|7;qtiQXuAi`PW{n(6uN=xI(k5|+SX0) ztg+TAEbce$&*PP+dH=pnBa<1l*W`lg6dTy4hW?)qp)qAqAx@2ch`GW_8p1Z5`kuwjJ zz4vwf*&*63Uf-vy4qHNl-K9dI)YfoG}^Fozr?>@YL;=NZ*cfKLoXy?xB(RI$@tvm9K zZL>06=cLbH7&ON=J-xYClgsqB(SQ8mt{&X-CU&oWscX-r7M-t>t|MXdfxkBT<1z_ zrW$>l9tNMcX5;eqz19V%6wc2Ya`D|B$-j(h;vaKYr8b^wwTK*?Z0Y ztokRf_CM_K^3eEClqcr*ntOBp(OR|NU(hCfM_0AOzOkA`H;4RppY$tU&4ua_R)FY5bjf8yHy+so>>YF!yz|6sFbN4Z0iR<&EH zUM#Fe?5&=CHR3Wo2yg}JMIV$ZhLyiBEHD3Z`l116kj>}VmG^c?Dz%K;!?#`c_ip4xb1&qwW6q^>=@-{N_zp(8`hj@=qfN-NizIkNwOrW=EY zn$+Dq`|$RDhhB7VbmEZcCb`a;>oIi@yJ)SoTOC32#`C3>mUcL0{cqS7rrp2j-4L`oS?cTg{X8Jo_4z_GvQ&!E};dz_N@0{uyI)B%^ zQrKtonJ(r-uFSp2=%b1nXFFqGoH=;-*Z}UylP3EK z{26lK>E&7vcHEA)cH^LLrM`hZO;Q9%84rE27@5380p>ColaPnD8G8;qH`cEoaJ z^GiD$_V1`^zP5St=%FgyzP9(u4h~*-u|=;;{o_3e`RayA!JYDp%Rj64Y*dw+G1FA_ z3R1DbrQCH1TQN|*{^NaX{yy?$(>n8yecy0R)9sHAo;81ZWo*-)Z5JIFTj+WH@}S$6 zrL^_t(W}4YMckxu+=~k5qYH_cx8KrR<1Op$8-Li+bFJ*i?UVPnoQglVe*ST-GJU6e z_wOwiB5PiCx#u1k{dJa_|(aiw`Rw)<=JN?xL|b|NfA2szRH4X?*?98uKT>utKVmE#(9=_w@$706=fe>=v&uxs;PMD1XX9r zm%F?C`)1j-ig|-u$UE1&IOm8n`Q&2v3FT#11~=OzKJ)ySWv}I5$G*O{>&+Mcz1#NH ztslxPZ5J)rci7Q*$V>CcN%eRB_v+i^z4U$$Jaj?0~ke}PNoiJv0)yMCKO}~EGBW~(jer(Qf|Mkku+XtrmwC33O)P!<8yU8jsfr89yc;` zv0+kl!1UnW=BKYU-FkNRfw#b8N(L+*tnn@#(I|ZY*d4el6|l*SolN#ISdr-(2aR^EUi#V&vY2U89K|^483Ot(+ zZ5(>@7Q4o^ru_qSWTO|sIwAT4o#oR>ww?a4zv_s7>9#fNT|6}Siw_lkF6%!p01~Jp0C!js>gTY zO{4nbQG<_NGvez;-}avRFQevF@7T(2w)nf@p3Ed{#T2%A$6&XP+RgQARoVH^)OnA_*1tNMSpWX6 zc0<-K?|EwbjF{U8+5EYVk)|+^(ghX-wdDj*Q&c8bocBTcc80TaCG^? zZ-(uTItD4QcZepdx{`ureVXqpEmd5W1-G1_s-C>Rf9spmeba9`{J5lT`c#8CnB~Lv zSD&qLF2(*i_21o*&33nYx0mFb30}jR>8r{|t^DxWi2DcL9sYXNvhR$lkIEDc-|zS? z{UyC+9I<1xXT^k(PkQ|;A3Xex{q?`)qJySk;=vP@(<~|Agsp_KZAvV|nB9QJ){~)uhK`X9o|8f92X-`EmGz zN;8k$ztS+)qQk$d8Zz9mu;HEg)vkGo!(ZwCThv%xy9fR^Hf7pn^!#gCn_m57GV$FB zpP!h2V^7U*uKm2=jHpukDmOM~#=N+E^of&c^6P?N*SeMszanSTv!~pcv-I0t%J{NY zGmqB$;GAS?#p~*`@c}JoTziw+`Qw!h6?3%xI-VXeSKn!Nn<>eo2kM;ba51^8eYfvZ z$hW&6Rurm*noC>8e9dJWdx-w>r)uwPSj8TkGPa^>k5JnKXHNd$x!IuMq!;P3gl0(l zmA9Yt$l>kwJ*xQl)R(6g+}ZYeM5*n$=68loym6-PeMik#$NFCUb*8_%aG!Q@yOjq% zlmFNHNoQf-H-DV?v-fs%L7g!@Tec_Ow_H}V|Fc@PYc1=Hk?J>|eCMR)@y;q|I)2|t zyl}>_F*SZZuzO60%4;mq<8>#>)m5pLnt*okhN-pB|M8npXgN4>R+qYUUp$%p;DaU~ zA8g?n`ORlre#>3{{m@Y1dTeD^5?3&z`iH->-Vj zqXW(~Nxjw_6or4e-7vI!6mem}m>K^&b!hUF8{~k&gNBioHkrG-J)-{0{%E`U{PiCu z{PGui;YoeV#?jVo;~bf)FR&K#diLlz`4x%`IY^y7O|LHRR;CO8@Kxgan>FYAg|F|d zb7X6_RJ$;6Tb(u9?*<*{J^#R@%IdZwAI%%G*Eyt@Z~n5f`5lUlPp_=jNZXrynNLTX zE{V6AN>|@9QM+%)QuduEHLG0^pV@?-@7I5eMY)kGQ|&6<~*W`Q6Z556y zl3=ykU;VLi_K$}|YoE<91C`mf#h54yh#oB7GKXNjj%q!+`V{5^AS@8p{%%T8VB z!>(|$nj1yjas{M7%4`VWEsbT#*%^3^L3^sceC`?k~mSxel$ zNfU4epE+(QP}9a zI@N22YqWiSrT&Pzi~@1{byF|+LkF-mh@pCvK^<@Y}@AX zo80Tdu7A6`Xu5gD!_w+ax`3s_>zTryuCm?C!w2`4yVhOzEqh+~Y5rN=_4U2fy1=j9 zIu)t}xew>`x9ASp7X36}&?Wq*OKnsaUJw3caov!xqG+??Jt!w#)Df8+B5?Z}<;jxXDzOzaqmhc0ZrwEFLtPbSvr+@(wPy1I(i zx}(o-*G}syMEjGSYfxo>wD=gj%?@;~CX#l&ylIWb@L&JizYJS3x;*n&{T8)PZQl0r z;onv!YMdy4uX11Y=qmlX)IQRzW3!q2`nMj|xXFYAr-OkFv&(6oVcCw}#CsO0dQ4g|GeUJcQ+;4UC!cbr!7X-b>Eqh>T8wBcc;Ef$`g{}d z-!^n-_VU?J$96c@1ZjWtS<}hqf4{i@z}cSPKW)r@J$T-!27Bgh`c<)I;LrDtR$Dl} zYFOj-@m~7WR*w+bah23G5qW8nCC*Sfd5+AWkfB*x!3b&{)&p8ESJ#V&Rkfxb`Rq>Gb+-kq49R% zot63-H#-bI(KdW#?*GKz?we+p<=<;|{Jn!m{ne*#o=kY!jr;AXvhCQN)jN8vFF)wK zE^s-wcG^e1mi+u^^1RW*bJfm%c79xovx$e-%9o9-_v%7wqx<6Y%}*ZO-0C@dE`FzX z<1=R(ef;;PP2x<~x%#amUVVRSR;EwCA4awMVaVR9&vqFr*QmO)m287A{>k7yhpu}X zPbI20`LpSdBP`D=x*q8FX8#ZE+OR9>4^|q8)#~=X)w4UUnLW`(+cvEoJZ9HN=yE_~ z&7FTgnk#MHSsFFqhx}i=2lQG+Heb1%A}x0pKkRhI^5M-V|IYaQ-H5f;-af`wE_Q?c z_g3fDpI&@Cd+PXKS5KEukZ)W*zyG3h?R=jH4h+BZdmm%Ne;U2~dS6ASe_qYKRk3hw ztj^K@WgE1w-eG|MkCloOW1^n~-w<_cFV6f{W#Q7r*rwm`9SY0jeltH>bL}0hIYEyojC^nW{{ed92>9< z*(69Sz%&ELfWk~VUT#{Y1@c7{6#<%vg!#mc=@fUxJAO5Ldu!!1=3QQnsK*qq0 zAzzAl_l`S4KFXJ3H_pL=TMo$_j>&GeD=?rRGXa?}7wc()1!UY#9yA2qncx2Qw#2M2K zL-do_?V8PnH2VA=GE%Pb2^6LbKKGny*Q7^S>36VSDJW{~#!Oe4AXO>Nd=8Dt1v&pL zi_sgjQOe~oH&Md9=jJd|akaWrzya*jVGaf=&htBou7oWqa4_q~{ytV%l(#Mk`Z(T~O~MmFpt4+4f%ELa>5@u|;!8;c8bc<{#^J&s}}aK!Pa)O+-WE!Hbh-kxG^e(<9V}L$wfGI>IAZ6Xi;rGhoR^d3NjK@>vabgMz09caL`hq)#>OT z_uqe?koJo&yodtt`$+zs1Idy-MW7OE8O=fkHmNG3;k~5IBjvzagunUh0eSQLlrtVx zf4JtspO4Q*K%i&#G82vi^R@&S%Zp1IGYW`U)o}CXO}y>F`|-91?{V7S7>7`*SDUC> zRYSRkQknU%yu^=m-1#CMpXHDA8K1LZ9OEmG{zv@i2mdZ|6%$I@!evg@C^Gx^o6{l` z8WAWEY>1vG6A6uYqX^a~yL00br=?jv#=#5rGFUg%lWIL`c!7 z-IMeaa&{rwwBb1CnKKfF8OPXf z9%6ToX*5RMMOBB01v2gp!(oh1f9kVB^&EdvdMb0({>YF^ddLmiR^~+3$M=~)j6jX$ z%|n^!$oPa(PSM;367(5e*K&{{yJ8WH<-iFH_`SUUP_YoF5e^15%q`4gZgxiVFL7fi zN#)!sB?oM*?_y(f8?W8m#KFOq%JFhp0i`lQP!8o{LEzL3TR|y38kJtBgQa83c;GE> z!C|wF_4RFBySau&r6#d)N@IvA)EY~OB$DczAbIyil&jNR1){H~YF$iaeH=gNVUlWd zIhcY{3A9aoXs*j3$}*bQ#9%Vi9#wHo@cZNxV%vM%hbr{;2rX147-)>g001BWNklST6)8mLBBmk!;|JnFj7XH;GGE?!f$s z^QsPDNu!O2*|zUK^&&p=jcxRcGg_-k+-Z$4(6DN>)wS0p?4w|MveCf7-X2b#J|mr2 zuhUl5L#xZwStgy&sWWG7-y?^eolR7ztLU_KZ`DdgqHE4su~d^?e%Iw`{P4TapfqfY zIpFfAoyZrb>1f{ZE{g!rIZoy`=9(O z&R;l#cieYOz(WiH0ehN`7+mT%xZbo6J;!hP`5yYcp3N=oUy@*BvyB(8-NdnzOITc( zR#g(qsVUB6s)2it3;}I=V2)*1=(|)==NdmxaTwbWSWfe^2KFETE)AG~kyUynG5wUU zH-ZXkcPKLLj?3pm5ELpJcrW9p)Qo9Z@pG_I^tOOB!?<5E)Fbj-VqBPMwte zQ5yGeN2(#GX&cUjE+KjidHTRc@O4sgydF~q5=X@`E}lP)cfa#N84y`&8J<`)FzMZ? zsVOV{VfkT&>3|3oY7|Icx$rOCmvkAqJihgXNAZq_zYpc9Spx)mcB7>2QHQ2QVHua4 zJPnscCl-~D74_VRGO!_?Ag4^QWGSFPvjwnX;E$;*%cD7`Zn<|+;A45}fSU>LxfJ|dfMn<*gs?U#bkkl|ea|{a$(_Zjz!X_Jd z0}NzZwzhV$zOjYP13JS9?Y&!wG74P#D5?J4_IsmRks-FS*8*DYHYO(~6m2$}hl=ht zwzhrWlD2K=J{paA9PVujtT!em(C;0fK6MIFVFI=46msb{CbE4T@5Gq%9wiLhixQ)n z_|@)}z{(gT)2LWwlYj(al=nIa`yy0ukm)=+b|H9B?pD217>L{7(m!x-sGQBBISLtR zF9%FXX`W1bASUVvJHws@8^ZzivIILZotlec<5X2n0;wv=%}{GhVsCF#<=rX;OcT^g z5kBzF3rM?dX%Xo7?b!%K1}c%|wY&XT>*MWr9>?W7r*QK071SnYkV?2{j3M`7x6{W* z|LE&j9iH&ioR#wx^JQ?0-nw~Bw$s46@;4HkvSgCiWRDgK-`?@i!xAl0dvN{wb=fio zJW-Tjc6L!!IrJeryPKGuUQ$#{$4#Jq->D2AeB_)`p*gXrbdDK@Ngt(ZS$YgUXR8zA zw}1DeIDh&S{_~&zQ2{QpQ3RIS+Y~Dz!grp2319l+xADQBdM_ThLamMU0N_k;dr)IWTg-fYjDFHbvy;QsYq!xK3~~Sc7trl=Ff~hNg{%ZC zdpgblTJRv2R%P|3e;^RIAQ4KPj7puooH^(d7*JPhb)<36gph70R1)sx;9T0q{1()& zCZP6rIR zRGTOoVzN;~0cA8MCsCcOV{)Q_dTm0_Ha$J5G0-ON_eP?_o3CF(b9W#2z4P6s6Nz%* zwTN1cmaz?XTFJ2 z+LcqZ3)p|H1aYiANnDK_#za6-ES(t(H65eT8409Jrx2<-3}_kUZV`oNy*Ylx3ibwN z%+DXk%RraISZDRaqgRYo65}x+E&6aHd<3@Z$%(H zH`pF28xOgKC|0a2?&&uG6mr6iI*Q>L`>6JYt-hsbb+^fMq#3 zQ(Wi0OggL~0|{esqMW*Ny2c<;uouQVtWACwnN4G>Oh**}tND2Y2TD&kn?&sl#iIk2 z=S7IqA$pnzmhBm>Yyx4v&jz3KyE_=5TZnM0+eEA)lcANeg&eutAhK$7=FQf=Y@Gs( zL5!uz5`N&pQ>sF;(rxxK;gpy@Dv2$^W-vyE_2P*++;wgOciwpk3(FUfx(yd@jwAaN-RgS%VxQlX?C9yRD z8ait3UG^p*vv7E@i!-do$ z{Q*!HOC3nNwJ*OwhpS+Vsf0I`?pr$0(wAi88Mqku<60DxB*uZ|*w(;~6=OD^sX%_O z+ZKQdzK%BDN`B1`1uz_fdh^c|R(op2wFMS<7}MBmn_zU13~}x0Eo4a^v$R)AKQk?u z;&zmwRWG17Nbv1vpF#A|-}^V2gngvqrS>MZ%nw+ZmxL9LQbbP%aU4~~X^Pfi3)3?* zMs36iKJt5?#Qwpq=%ztG#^TZvcD8mD!K)6RH?CYtUO7l^M0QZD*K626JP?BrXh9k# zf&^n|)w#szW<7kWNSsmG;o+ePC0Pfb0S5<7r8YQ;A&0FB2pQA@>XQ?gsMjP0?035= zoiV3i4k!rYXy6!4?(MVGt1Y36>dK{PH{)c?0rTiCEOLMl0E5wj-jT~02EMkqupo3x zqhRXWAs)PZ#=pxcQUWRFLW>p8rI}HZlk()bB72g3UZxtHsN4g=6h(u|!TQ)0tf7j= z)hihYv=qIQSng9eHI!5DQ-CL$lN-S9X<~9x-7Raiioiy(#5`S5)fdcN^0pQhmQ-R@ z$Qv8Q*U6rcuZX}X&Zu&A@$;${i}oCaXV&9EVlcDVE?yGfrQQuA#jv|ii_pDJ-TMq^ zWAOI^cxG6Q)-y*fOTimdh;MxcLcfN=WPNNBd1g0Tp})`{y1v{?uE?0@_$PM$ok zi0t_B<6=9?l`39+0@l~pvA(&5_04SwC`D^iBuAsj zXo-eg;!?FLv^`v6q)1Im&$>)f3z4sj9iUz5by}F2U&7w@EeV>-jblJAMr(gv-_e*@ zLfR*g8X#Ay;n-{$^LrgEX9WQi0=z0g^{9HoQip*N2n?4g*j=MAYS!anzB4YIz@R4) zsQOz0fPpwK{mvp)HZX-tAs1I5$Ab2S*Hm{|l@!yt*q-C>X=}Q}3^&s*T9L^fl`0L~ zuQyB+XeqPPsVUo!vP*X!pT_-Xr$*_okp_t0CaT_o85(o`UCjgco}b0tmrr5&+#Sdj z%j&AgXj%+c1U&h@tN6k*Ep(z8%*@T;+=a_pQ!hUI6oyF;w{Ks=nKKu#xxS9MxjF3a zZDVg|1BF6e`CYP7?e-yZY_`M3Y6Y?ZB>@21Uj}8ID>}fzpld)T9iZRuh+)WO86J82 zDLimt0nB)^v^~n3FkWd%1z@x_%(&38a>-c=tz5DaK6chEmlG88nf|EDp#nG)&>N%Z z^&?~*$t18z5Lxm8H6;bz8}(ia_M%9olB!@!W2LApNbHNP>2wq99US6?msW6dtF5^* zR-8jJ(DT!miOq6t0iQ#GjcoAPE{UP{6p$)uk^}{^$_!l9+oFK)d-z>gUA>Ootxeqf zw)bFTeG|8DUNtaQuPW%?-rQA>3GTZz&52Rxp5${9@L4cqRSHTudc45zs8*^t*zMrf z3kO>1b!WBtp4EOAhqWrYgN`vZFTH^1!yo?5EYRMh=SE!x12R@bH;(=k;Yk%6^1$P| za*o++uiwI_{`k){$<2cUA-YTF7SWiU$9MncMO11mv7kD1AXb47!wA@NjaK$&2HZ-D zCK?k8z!Z^szFkO+bX=7k^o&;GM6qt04K<3ziprum;2aQsZh!wkD4yT9xxJ-w$z#Wk z381Xpz9nZ8B9y=u2<0A0v4{zvdQ|k8HRfrx*xGns&%#YkLmG@Vjfi>>crHJ@&J8g$ zGvh2tNt=o^(cPC$qFSQ9zyvF*(dHuJ0#ZUebkedWFs7EZI`dE^pr#y7k%qZc7c+KJ zJYu27%*Z(6)N{Mzr07bz6gqS|Y%kqOVXdu0j$h@4{l51`2xW^b&&o8m+DPgE7okwJ zPGUt?WaKgwBI}eHIzc89B3V?XR=a}~wQ2>Ga!JU#TrHtqpFq84YG^i=Vy?SJZAXc0 zkpaD8i3Tk6kQjF=WZ9F%M|o1cG|1e@Ue3y<3~G{Pi;v1;MhRqI*i;Cr>wk0krBh1+ zj*mY2=V*5ZxNz|-78jQUvS?(kzVs}vzw#mqNKmG(!&5VIFy0-{N~Vl`k;X$bNI# z*EhlLrp(cr7?WBRt2wt;y4J?lG!>=>q;VQ)V?=yZkuT4qP^`K-d?ozqz-KWY84wDA%X4G?m9}tB+HeHB%#gtV9t?G zk7>KyPP=9yu26Gs_a9)6vPcu^hA8!yiBT4cu-mp);_Eo9nM1_n3o4((jsBojG@cQfIuV zyAea04bW+KWKZZXMoc4JiZj1-ekQxIV21X)S}kCCaT-7Hj<@5k3-g$)Fu)?9a;luV zhCH=otk$x2^23BZS_o!s0my`jMNW~4$x*WvXI~ivneAismjQBCv#=#U8@&yrOXIv* zNj!l9>3Cx;7&P(kq~F(bTlt_-_T63|$nt1)y4c(As06j@&OXE&-Zu^XL2M=F4kFcU z)`M#cY-kHzgiP@vH4{o9F+IzmIYORbs25umj0C8e=7oNfT9Kg7@aF7F4|DEm`w9M8 zeZi$k`=YV)o(b|J3d-|1JvWKJ{`%|4XVl0@h=WcB>{JVANGf>`$=i)V3mk4 zA1OM=(hZjLGYYcX>B{LcO5zXuIFJFkq>mw94l&IW?*0td=X*h=w)h=a(^4Bfv3Q zGtgJc&(oNzzkxL%2?o!4?pq`|YD?@*TvYx^XDj+`T=r<+F|IUGO4?PiAyqO05l+W* zZqK@lXmGa_>QtV5?8CVU%icp@O|WG{ZV# zvqa%pu9D9ev<#yj07TGiZ_P799I5j;2{3df1r@y#ZCQ9{_0WY8Wmzs&QLffdtxcja zHIG4T&A7~=kJC?l#>XD}D_p&H4G%u}fcg;3&dyGlqZ%E<;o^rD_Cz0l_EzS%y%|%W@zoeDPGL8{4!TmRBUmgH!@O_ zDz;o#@&8B{B=F>|(G_+3m;{i;=e3>|fsV33LBR@hy>j+L6EV6%RC*|_We<*2<=`SY z=79mU(*c@Ug4IC>8J*D3C|)wOHaFI7)Ea)}F*`G(vESX@lKm)Z93wn@_X*6`jS&j> z89;RC<{8t$i%A#?EYxejLzm9t@*N9UK7UaHQ46HZK60f$`o%Bf3xB-=Rv=P{YEDWu zHe$C-KuSB!`(yq)l|7dejT3=^JTTn9%5>ufS>*Ghj8k|63V#> zqP(Sg$|Xx3%SKTL;o`~AxiHwE&>h5GX-c4?B%zlBV&IM)0tU1 zk#@A}VFFa1rXII==Ggv*`B9s@B?yayTrTohe6o+@GuBx1RbIqTl(@ zzjBa}M}ZrVT{Z{?)Mj+7e&tgHq#cY;pg2dRV1Ag&Q!l=ZM?d>{6EmqpVuBxe|9f!t z>UG>$Sye-tkV{h&6jDTL9AwRYB#Y2WQ>;NZQ6d%iz)K9_AI$$&} zG@3C5kSJHm2W8rNza8c6Y4^AMfsYy$7pNJ@=}nvoVA z_0h;9M0-T9QhZY*P%fcStJ@h2)f$j78jHm`tgf!2)9aczlTlh6V|jiWCl(1F#;ucy z3}t+|`MhzGSj})C$dT@STo6|7$z9&Vm3PNz$1GP4?PV*Lqf{Z zDK#4G&QLsQvm?C_Tsi3T=4X+(Lsd>*`U-C92$PdDxc`AGXiQ9_QmKo@p)EC% z#|%P9J3Nv$cG$tmox^e?gfA72Kx0)#B2@=Lm-SXX`kB7B% z4c}|~%kr7#>}ja&P@Lx$*ABG5VOs!m(x4%2juSTx!-t$qc;- zdN}m9T^H5eGaI4;qhv!z$)fq`2iHyzq#c3{+0h9JZp zy()N^TGj8viuZG5c%Tp;WYj%zByW&nD3n0T21+DnrH-96!G6-mUM|C7VyQd%F&Xtx z(rcnyT{D7&o@7c74t8Z5=*p|*Jbv*0)2No1p0$djAc|I7e+O*IkQxa_qb$>;qs?&t z**RP}H;XfO-i4`|c@LOOZ$rDZv9X3t^{i>4*B|1b)k3FZx(B_)bX>{&^#C)F87*KcNV8;$u zGZ87DHyyIqiB&Jqrm$Cr=9mW)4uW&HF=ddVAW`k*p|p}^NzMC@s^=v1HcgKKRkL;c zKC&BHDWR3Pr<7T}p>rCP-gbN7b}E#IkJvmipX`9Cu9{YL$Qxn0j?52PS+Xs>2Iq;| zoO~MLYhQW+FR#UDPfv-#VM_ZvO1Kc^@jpHD1fmap=zqz0gZxmjKtbF1q`6>_tceGa zPiXTh_+X8SlzK4AS|sj|yZ)MKl_< zV&25DLdC`y9d%@Hy0i<&!h5W>s2!>k&e#aipxIg12l%EG7z&`)+Z2o5r*0%T=W+08 zG_W_umxvd6EG;eL13&(L7bTTNIqvPZ{lQJx7D@=YCZBxrJNT=wd;>rD$PZxg*aD^| zr||NN&*14Nzl%zdrv}E#=kk-*@zM1dzD`GJ4ly_5&^7=C&Vh2e9>I>8f-#V=v2bCn z*KCKqLPdVFU%{~xr%)#=r+GIibvSz?h&5MluVH&*?9r1KQUi?mjb(%O@K+cj+W9Ub?LDmvh&cao%HK*j7aWRr)H)Oc{(6 zbXEuLR$C2s=v?#Y^b)ZZ1d6N#IBa#W*X+36%0zW@J@ZG}ECDMM(2>QYu$nrhJMTJ< zMwLFsSU3iK1PSbOAe+RoR<)H6KL5|>#ww{uxzoWipfgR8@W6;E@%MYlCo2vpJRcn} z$2n)TO;%L>M(hM(s|+&xM{Ss~xI<*>|C6X`DaE&ZouEu5kSZlNp&&#}`S59f9M7Aix z@@NJgh}y2c`l=i>DW;%e4pkKs^+`-lP2tWvF5-hiwl~U6N>~#ES8-?hPbUu@Q;z<7rQON|nqi?n46ppMl|4fi@ z93TAIpLD|!p%oc!y5j6Te?-O39mUXonMQ>Ko!+r>3&}@;K0fNvk#-e{e1kc+mvljv(eRr6kou*ie zI|3nN;O(pA$no(ucb+0r^BjeLeljI6H(A0Dz4Z)oOyN36IBIj%!dJ|sck0V1tW2=g z9H^D^+b`5`{Man6+;<l?#JxT?uTQN)F%lP6G*YVT~Tez63VS=781O6pJ!f*WR|6Y9(i0DUcbh$Wa zXgzO63XC8@)cYtJGb0xw4ZhdX4%P-#O4C9Czw^5v(}6J)^$N<>Ja%_GQme9SV(7We z0j48i7q_|DS?i}A$JR@L2MB3_S~MKexWQnCv_p7s6ZEA@OWeG1Te*Hy0b8z8PF|%j z)} zV`Fn4*RS8ge!H#y?xkwQq9s;_a8dH0kwf-nXO0PY_`xfvS9m?HK?6q84+y}GbJC;A zHb2Nn-x>Us)5|KO(imDRT4N1N_((=a4$7(Quwj*!Q1dJ+voR-PM*P-x5BXxn=wy#R zjU6)bJ-&70Ya=tHMWm({HJLM65?=|+} z_+pD{Y*Ni>+T4wS(YPUyjYkj?kK2#yvBX+18cflT8dyAW$~s??qV>bG`1t@d`Pv&d zZenM5M~z!XpqA^9fJ@+>ubXoU_s2**+&hgd(|Nou*~y?wF`bG%6SX>xiH4#h>XIyG zAOGVx<&qWr*G5n(_33 zXOX<=Rk#;Rr}3EQQ0X-~^Mcht84qtt1QOcG09$bn1Ns1hHBTFc@jVJw&3>5zegxEY zhKaF3r{}78*F8%D54oK;?mey+`1-^ey19lIx0k5YVwDDN7CQAh$ux!T#c$zS)B_d0{ zdm3VV>Tftp$n3YxJxeRaiYuLAO}Es#JMP&vd>t?tB={ktLYpg~kg(xbNJSV!sWL{L zmTVPM=9@fFakiI$MZpu<3#Kak> z+DN~sz7}rJ4e0vmvkcz*yich>ZC!cmXD)bSR_PlpMJ!;E74f|%ujBgT8!Cf}xEU=*#D`;i`Mc=YNA&jk8#q);~pZM^{!olXAyb1!3U zS?`fe|gGo`FK(Ggv%h3);poqpvQb0gY02Nv@ymUFg5%{SEa$f8m^ zDKa!%@}s9S;Du|eC{(ICfznQh3@t}Z_53D7m}Tg++iJ_rwLqrjZTH-XG_gt#-a5rn zGWDawa9Aoe?i(QIGdgG89VQvSBc+GItArzTwc(HST?k-;2G*R19seps?`)PK@3Dh2 zAd%OhTEF!7|K7M6SDfM2?QH=-bJ{+V3bZ3M51RO+PktH?Joo?}c<_F_{`wozxmcyc z1U~aeA4hT6MOC7qapzGBtS!1e3SNS9wg@Sl+hErYf-!TFZx$(zT$^}UeOQK~GsqA} z4IDqsGFw{%Tu&-9^Xes=iwM`QzNWV2b{2;*F$w@2yeXCApoC)?+GZQr42L$ElV)=? zV@p^UZjG1tv%9;Cg~bI$D}fEs!AD10D3eJ%J^*GJWV2d^<#sH|Rn>xZh?J9cU4ZFI zyl;Wmh-*KoJkh>e<%wQuss>3zuPSliAeO|zw7}p zH|?WME!UA$S_muxhz@gqbeu*&(ANRqd*$R5?m0gr2f$`IVLb%pJnxNZhT+hfC2{NQ zc4O=w#wyi(>$!P6cyStMPEO&%9rvKps7tIXXP`1xJE6jCh>1_NUtGXvIxKTC6265> z7HSAs5<8$Sz$yy@gT(inmWDRSQX|I1Cdje9cYfNn4i3y+>|A8`O==vRJU=iP)&}o@|d>aK!aUof_8zQ?g3kYp>aS zhjSj38lkva`m&HN=I3plS=UqQfQ)qvzFI8?3MF*fJq+B(avW;aD*9de9os8Rb%%hP z|0Y>*^VwBA{*_ha;xhjEGv7pX>B9N!?z>Owm}hqItJfMDP;GpQ2}>o3X*fx>N?qa> zQF^Y_w!ZQffdxk#L|1CDoD9+4{T`MVzo&*u-Q+kv^2rT!+w7{<6_qANldV@PWn4IW zMox&UBt-lnm#Nf5rDDp_a11mD$#Zp_WCDhpYpdvysnA4*u2e=HjU0zZXaq9Tlhe54 z(nZ`_U6YE{qD|K7l5GgR{>?aqCPdAHL%ic{mvH)+9ZaQ06izjfMWCah-hq7zxJh<) zcG2s#ES=$bFP7<9l<&uYj_S3|k#aNenfh^pdaY&@Y&gj=^mULkuuT=R^TrU5U*~rj z1#M{zZQ#+NNn@41HL3C%V^38OwQ}LS^2QpHToHAhCaGE^U$nLff)NXAp>=S8cBiG( z44>hB?|Q4#Zq8&lDGYmH1H>s`k518i`s2G`|L}&>+U;L z?eg4n&uKo+oja=ox(*Kx@zuxv9E0YTpV<+_iX%Bh@b7QZ&V;il0##(|#T}aigrg~k z5lE0hvbMjBy8CGkowR}zr_PMTyVBdZP*-Cw;Z+W=5hU#Gse>Xr{b{^C;$_rtV?2@~ zc&~&|3Y}R+5>t>mEX%7V#PWICr>dI<#DbXDc!*4I(aqO z;eCgGCP$8GcEO~Lfq^6eh={GStu4FOL}<$^5bD4)=wMV`IPT_Y+lY~}YkC}9b&~}A zLy2E6%CM94amX^k5J?7FBIMP5t^yzk>rv0E5?4D(QYCqV81KICB$lU1Lo=8PhZ@#jf^tq*(1^(QR|`mvoRz)$f_8DKSuVn*GW$TIjdB#xmP*~)MO>7R2Pscat*eL zfuA4D#_M}^LI89E?_LsZJya6J{icf+`2k}*RT{4}k%>H`oM|Dfmw~5rsO)bvj9u{4 zdKsYda4GifQKwlRJV@UrX4e=GrdQdZ&JM~l&dGpmO=8l<<#5Pau5kK?Of{ki~1BE{+? zc6avG=8_Z9()s9Ymcerk7BIgsr@Sy9LO?<16R>Q}PJ6Umy3tLFOuT(>D1*GYwua6@ z8$H(k`cD8AmMrLzL-e(g8%E?#Iq0=oMr%o#YHi)o4&tDyt7Yg^Sw<*lrClQLTH&R_`(3 zkw-}71R8p0drOU(^qm>-1MhtZ@qndEp&5}yFLr%%P&P*%Eqj_lo6rrs(m>&mumDYb ztb)Rq&mTZ!U=GyA*~OB9vS$gNmF!yAx8P_E__N$JhyU`w`p1Y<>vBg5{pu^L^td*E z4n9Lv&BkHW-<-R6LDcD!-~Eo({;AWa)f0pLJHGPR=h5F?_XC(hS4!7FdzvUP10m83 zLb|YKWnzvn2mzRf^4t+f7*$9ZlhEwMNTNDUpT9%rE-*s16Yc{0WKlWi=Z)8|W6R5S zgK*av7yEXj#BI#@KPI5EePT?QIeY$a4G}1Z=i+PJKifN-n44WNIyCY_u3SW@XVtm` zsyTv$3{{q^G7T!inrAs!*|XAWj8wx}8%H!YVtbrvux1P6o-PuPieWS3tTpHd+S&6N zea0~3xaq&6Ft2e$MbzawYOpx9+oki^?MTWPTgH3N&A@f->!V0fJO z5fOSAPXk%Du6dn)&j26CgNKT-KaZFtcB9k*f1FQ_H7nCHY;AP#L;u645WVN!4`;o> zz*?1()-M(m=$ZnO^Eb{9QH7Z=l~5|=P-ma*e1vMPp#h`#kY@^z&fsA{c4$bX6AZuh z^~bTjy@SoQb(}eUQn{#=m0KEYHC6JOQdeo#qX6RV}* zCtrzT_frG8NDkX=fe_|ZL#{qJ#SvXfl;z849(0U}&{$ zNSbtdJ|E*B|MK5cYiJ%2a(2cbZyLe;s5L1mQfdm306Rnvbk|`FQ;lWhQ&bG=s$(mRdzz~nT=OIydZhoDv z9@A%`wQ!)*wOJiR*t6O*9?i+Sch_HXmf@@kKR-Pjm=qii$2zFI&B>E~G$!mQMJ(Db z%kXQz_N(d?8glKgzPhIJuaTqXV)F=;j%s~-FNu?h~rG7du=bQ7fc22P*3 zsIGVvFbQP4=;|nye&hO0tgo-B-LDxAJ2*^%fdha*%ZJ>*)|C2TSOjk^XiaD=rFckH zxWU>#*vIV5>L^J1+v}Fk zbacMLc{X7U8oiw1gWrD{$OcH+13^85>{LmmR5BYIR&FuP8B@2wQpRqEX3zE@LGH2o z5RcrujI+xVID6>==8qkdX3AJvR+fcI7&4aQ1MYN8Gt1H0Bf{16yb0yaIsd9U8|!1# zqeSTeQ~X={GCZg2mAtx&>XL9>^)K+X9D)_v6+75%9H7x|MiE;n^F&ZfXP9oy`gaJ# zk&)1er^a4bIippWDF06#7{%-C5?ibQkuh>i3m-Oj%~vrsCasvAbHEchdCgHEsx%FC zRUxHf5rZ*}p7(bKH0UWTwcx#byhCQ_*MCS2wG1iU7;7wGo>BdVHH`+H-!IREOm z5ulgSM=qpvQKC+Pb-NJQ4(*RLL$~d%(>>#3-AQxSG)+CUtZGl4eUZak|H&s1z3)BW zpM`w#!|v`L ze*K^P5@u&654~ja`NGL zWUJG#bOa+Guk08{AihAAA2x?W6c`wR5M75T-F_b&uA$P9bGGUSqcOR{*iu=Jfrj4~ z_tP)m)&W1(+SnaTWOS&`e#a24=02JS`^HE)14D56$ot-*j&7lu$jHgb2)ppePaqrX z9f){?oSK^^0vhzVCB^Ut$u_gU%}aP7i}OV ziZ#kP7-Y^XDc6;oE4Y1oRRCTBJZJH2{TKrjt~&y!+LI<84Jj)zGHOX{RW|`_@mWa! zQx6pOrC2qWYS{iZ0L<&nC&2N63!`aFnZn3Yr5!@)W6+3bZhfu^^yFYenvUrx?}cKe zi^jqkXJLCYjGJ#JfeZnJDAmC?hZHKZ7M=YIT$`ci4g%AV26bntXwIX&AjS@b4Z&^4U<3&bsrWr zYmIpNQw~QWb_2!MP1e~$0R(fBBY-RiZ$~?;wYbuXWb>^54bOO>Pq8_+v?JLTyI0OA z83l^$?J%rx%r)Pq!=929^+w$cyVfPYvtvChC_I~1 zm+VS+=JXjo{Oauuofa2F82o;I=GekKmY0`}ZW%cNbN&))uv4R=b3^%DR66h^Nwfge zC9XfjjT<+xd%%hXGlW6o5L$_bd?0lWjoJhj78fx&If2!+HIK>-AcaWVC|A>{^E-N- zE`H?w5994`xkm=@=E_YR>>ps|)+$>2EuA4Tw>*uv-1nf+u0V!zy0Msu!{&jiFl!G40aVT{t=XL(kKl(M~ zOIDV~_domGtI7+SlQmAnj4Jc7sSY%notwk$l@&bq>~nbc_kSOXg$nA85?+7pHT?BA zzlu^!rMewgPDiNkI6~9QNxA6MC`c3SDsuCaGL1&}8u5`9DA1a2Y`k4E1y*z}j53FX z3eI1+Q#2#@h#b7r@ODhJr4Vmizk#*2HMHe~2neX&wuiQ3!^bI#qm7%)n;7dBx}Iv3 z94PP^B)C&9xIQ|OFRWQMdI|Hyyr}`^0;)sc>>xu$&XLc_=1h?&butSE630iL2UbXp zfT$Jn$eN%*XFIs(qh^WE7P^K?416U0#n1J#Oj?6Zl%h$HD^ZL^v@)YGAO*G(PrKcv0RgmM(KIpl^v)lfTrE{>x70OqfLfLQj#U*^r8qrIB#)$YFSHJL1$* zMf~BxS!8(V&x}b<5J^Bw9f-GBj@fD0QM7sl4Z-xd0D#sw*%hwKAYL?$U?_)F1*VHM z2^d<3hZx2ta+j@S`Kk7~LkA!Kdw=!gh~D+iw`EoiNQEiuTQjvR<^-{Xf)~~TW~H|u z@?&{jTU6$_t)`!jTbs}i`Z1+^Ca1zklN*JT^!oJ`T)cQr`F~CbZMlkF>iTEG#VGfd}qE zW5Sv!$(Z=UW!j?5?P-F^X))je8V%_@N=e$;#lXT*z36KzD{H+Md=nzlizyX{%(2B0TlfD=3z$E?P8TW6y7GbN8DEYNGVQ3oqmGC%%K9 z|2rR4Bsx7ciRYhx9?w4cB%*k4ysknH-m5D#H)_2-&XJGUD@MQ+Dv4e#VdtQOUTkf0 zLo*~kANQI{rC_wWqN7|MeWs9$C7eBT(R<+=lVIn5*x_GVh4l@w9wJAXIo?MQVA1dkA zP&y_7*{uWIH@k#rK)O3GBPxf)(RYP+P}S2;vHKv)RXN{s9%|IXv;fD@OPswNmA0CF z?)e@b;zj4dqnrly61vP2`*Z%ke7y&Foac2Ve5Pa2L3Ds13HBnAl1PdYMN$;iB{#`M zE^#FHl}l_ZF3BdFO*Xsh#2aVhl48elw~qe& z?+lzj&ksL-NP)o2H{bWZ_r3SrbI+N`WPQrRp>$RCme`8d;3|szdrc~ZYCelt6r)r$ zWcy8us8JD-P4C6V$OG3y`y&EeyrKh3o2#TVVCy|9Atjb4V!3N7tN@-FT-QVoMl&-Q z%~JHpon!s}q~lTCxULo5Z3%Suv|;(03y`V~&xT2eO{xf0a@3c+FSZbZ#5NDFP*^c0 zDanzq6^+us-lUmC=*OOpfw{u=p_>m0kqJ474w4^Dlf3<^1P6yi;lCCF`X?ez6OcQp#Y#> z!hFK8wO7dnDA3>06A^>!nOL#d4WeFUBt}V|kI;C0V$w%*F0N;C5I8v%kYJ&RB#nCF zWNMQXZSv`vXfW)f`l!JdL9vk+B4kJ2FxCb(aX~9CxJP+?QzX*F3iqyB&mRxUfhEN`wwd4r4mUjU9uQmJ)I8U+W{UjarTnf3!0jk zL?$yO-E>tJ&ao)NXjG^hA4dZ%rj#~Kl>h)B07*naR5{1&8MX+9%1m9K!29+hw`hc^ z;&vA_2Fi(w;4U)`3JFs=!*^#q$*XeSnAHZwfliE|#EFjt_48?-<$=tT1lohsLNyRU z!p2WU6S(q<%|0pM(5~|hl*KyhJ@h&>TTD^)`F7FLi||?G`JdMxjuL`!_|Ho&Bm>PL z;kMR1G(ut%3db_k>oB^tXCl~j?KN1tYMG%S(J1!rJqET+4VemXtfN_i`phkH&z`+_ z_|eDk=3C#S1h%=U3C}$93|@ZWdBia#h~GE>mG+5^6grvF+YAAfljx7C8uJ+#Efmq% z(1rZ;lnxT2H#%&5RMJdi?0!jMPl!?k3tC&yyLhQr@YXJ>$ZLmr`=TVn`_7!jv_>Fp z6xx;@?U&3KbeT5OSxFAo+5 zEAO9kvMM?`g;iAzh|d^A9XJHMDMq%l1YA=_I`GY{k_mv&Iui9<>|a96yiX*4%@&Yn zB^fPYY$}UrRT8U~^$6D?CLq=rS_+3lIxD8{B{ zFs@9{4gP}6F~R!Hu4Mu>x>0O{>nR?@UgcVvz6IG`b7`+Gx5 z?zmnoXzH)JN=a@$J83^3Vf)1=dOXSD{G80_=N?JWt&%2SjExa1D99P9s;<_VBAp4LW0jHbvY4DF2q8<AlG~Y-~#HDIy6> z@1bA4}&UVqFC4%fYZ>|NZ!_z*9tqX&sj8Mgj zP@l|`m4bBRkDWTBne2Stgg-*{YYV{;0n_aJdi_AJ|uBk zDZw#u9%`Ti-q8{(B`g3LvB#!ef?*AxTYzx`dJqr=t6Bo#DXR5sJc=N~6T#-qm*SF3 zFD~~2pLynhdXv^_u;i?=uBkAW$LRP34jev=mtJ@Yx4!WWx zI8m%zzDh}^ks?jjJFKVh8YfPl!ob-9LB`V6ry`!;^YF7W`f+GFOt$deaX-=YjL8JQ zAHHYL#^MWu9IulHje6Bi{*sEIqm|*=g}p}ssM`8kWcr3sTZ*6|PQ(OAOZMDR0FELP zxh&74M^F$C#x3gEM~_8hzBHMeR#iU7*a4CSDP}_s2GG2KZka6@9UL_=GZax@ETO%& z5lzV?>Jn9$%iDp&#+yyfxR#3)5{=l#>Y0T=o)9;g@qCVRMd>PJY0OkAaJEnf$BD6F zB{i&MuiVs&c+945RFDu#CRw}aPKO{fzkumN5!pOn9~jFO(Y1I5dU{u3@ce-Gn6+SM z(06DrZoIe~3tM7Xy1W~m3)dl*;$d6mF_UInIZeG7kBD$O6RWVsZExvW&;mWp*g(=b zC(oS8?+&c2`~zt{@P4#U%HmBH|LLU2FQO0T31h8fBA1MJyf)rbQ-EZWK%%8hh%jjj zL~@hvw>FlYVRrACkXUP~;%B30squXi%u|xAv0v^NLszDzrtD_~x3jImQCx3}1iuYG z$4II-LoSjBtz~Q@#fG3Wj*`b0bVBTL8d_`I2Sa6;G}3!RtuLDv@T%Vm5b`LrN8B7v zR@^>ip`uzshkSNS5ZQJ~;;VN*iT&rY$eVl*F59*h=lhOh%eofqT)zl~nT%_sL{XTw z7K~!CkRk3V7KSCPz5OeQY}1s6!RNhezw_+WJOxc68#{ z@ng!g2>lC2^uDp_d>iX}YH~uKZRhq)*tvbH?$<#70Pg?QgQ%;m#>CVF7Bn_u^QMbU zg4jiil;s-Hp)CHx>zU4FBy^z}bMHZG(YSyREz3wQRYp6n3NiAb9r{)sxY&>F`0{-% zn?KE)v$w@;ta)Yop`{{t%r=mcsc(;VbPQ=Pz-5bPvWct@X2wL+FR+sS&V^kHi!~#V~6hdpvDk5jJ zSvl(b20O5nc0{9C+PeZb+;ojSr@1-o-A5#$l9-k=Ay>~M0hffomtNk7zSF00<4rdT z{_pDO#P5FhI~+f_2hma3uQ4!B7 zYD-xhNfCL>0!vm6s6OddmB9r;0~bZ5bj665Bc7szTNp?R{esVXvLjaOd?S+>hF7^8W0Ow z54YCVqPw~V%Nv_f2cWhTN1UjM5oQdjaoKi_J-hrltNhuB9Zvk5GyHGD_yps1AkjYB zh>~-$C^GDQM-#~LTE*X*!wid^pkSITAz2kcyn#eIb5CVLV-p}W=ZRusY8v^uC~~tA zWb>3`&S>(iuD%|r>RK($CCe6J-NyC!#gFdCwiWHDDV{}7M;t5GT#R&GjoID1jj%?` zy|v8s$OD^&7xxbfH4~BJcp%XOptinB`%&>eZWXQKl#kt&c`1$nT5@jBHyrRL)K`%k zH+=?s9g$^8V06JFk}ziqM4A&Kj0V(zf0{a?#Z)HTOjOE5cWu6k-w`<%{fEjXRswE1zt;F6n`a$OrEwmGm48*oK<41LRR_` zMhNHm$e76gQ|(ft$wb3lJ4a{`rLXxq&iT-X~+rNy+_U)G{ zS)+JK2u48_jSGYoWzaxZ1~_Fc0Z9qFQXBVBa7t9qEuR-8rQQ)$(li;tzK*$LaUy~X zp1$OVj~>-Rt*s1j7&1Ey15}{ie7wN26sRr|@Z4+aE z(jZ^kh+%HtwGhG~H$OS>zGk=fRZ~L)9)0pjy!h->NR)D@tukq0 z*$?~liXkeFEs9nGk-T_d2*nHZ(Tq;FJ2D z4w6|6kBp(IsiE9T3eQBzsB0dG`x7L|<8h3R4rAr&m1wA|!GV3Rh;uYMZFcNIhMjx2 zuAxB?^r@4__4`b=ni?9hY~^y95>1Q@Vd(sMlnS$`O(fA%UysFg&FGFKP!~_2$`3KN zXLvm(of}3j*uJoFC*CKu3S}W3wJOquocJU9H`Cn{Nm3(f?iWH$1BynGE-3X!#vK&S~`1Bm11(0u$GSm&6wP{37SSn4JFahoP8hd}2NjhFgpyuhygX zdI@o%0Krb#h{!V6b2;NO>gOn7i2Xt@>Bv}`Lv?Mno|8z5N{Z=nE_OUfWl_r&5x zXvc_$H$&xMPUSdHDOicSOQk3)u4SXM%&pd0Y--ZPIRl&)VNx6n;21~vzFZSZFuWkK zi3xsY+FldU=N^kARaJxc{?$(~l#M9~+Hj;rL}$pxrbbOk&{~?Xt@UZlVzkWK z_P!P+m!pX&?)>2Gu8m#9`GFxRk3IX;b6Ug~5lL{t1IzZxTqQTW@r4zSiRZvY%=QB_ zML~KbHEQJ4Dt0a;gMA6RxmLZ4mXvuVWq8&;Ac2`)vN6DxF`yF0M9)40v>+&F)UuxgRNUPYy7dU zx&{wF@i-3b+XoaTQCDRIs+u%g7j7sfrn!?KUBRUFC1}9IRE>D^;SaKhTQ9nIh z)+?Eh{Dk)lNj2ZQv9SrYY4*PD8l~1sUXv`>ZHzLs(dJJOnF5{lmH9Ih0gZCy?LLmXax*3Lk4|Em+zTN`wicMc z*;?TVKZDn8UV^SBVAaYFbT3|xbRB2zYt7WpRUHlLHfKv4BaX<0QtO#+?DH#urg&0}V~#wqxt>j@ zAdFa>77P(qLheLVO@dNf5?+%R7j~!zBRGpoM8|}`GSML)+>rn~#I2GJW`u!vqi3I^ z-iz%yCA2O+m&;5E6;iB`SRM(EM&?x^tisyjwfH+B@%ENO@RSJmo_kKy6}}(%9L-;X z$+`Lux-TqtI3+?-=a28-hhM%hiBdeSas2wG7OdO20na}DG>Z8GnmgKX!Nzqsc5pw& zhDWgN;&$A2Rj+Zj$g7~Z93{tR3*yUdc;`0|*}Z$Gt$OvM!x)+!Ove7UY)aWPVSJy@ zG}%;ha^(D|%~vuDvcoJ$AQK%R^lv6f7T7BgCVOH<3=W*f$k>QTj=?uQuxKyex>ax+ zUpGi3m&qv3M+ihpLy2uxJ1j^e&CKC!{{Z^Wohw(5q3WDp0fhiZZUXI1i6n3nFwmQ0 zAz?7LhAvsJb9`hBJ&U{X)>~gA2#AYmd~8J3-4l;IfwgPbAzf=4-Qhqr$!A~CTBJ5s z8D{eNu*FdzgSn7b;=r%q>==@SFo_TjUayJ0UvB75NC*NH6{`2(7RhHC#@Iq{-zrxd zd$Wq4qE=Oy7|-D4qvw!JCB!@r8!sR;=LZKQm=s=*`~xn0j=>Dwv_BRv(;myMEo`@kz&`$@O*4)gO)4h;c<*>~fDHYK%OrkU&{ zE?B=F&ph)q?)=ja8MB#5(77Q@-u*+Q@3{x{Z@U@Cue!-E#M&`5EqZzXAv|#ZZ*ake z3$S_9Ml`f6(7k&2k;i2lP4k_)Y6^tq(AH>D+iE?@@W$F8d^h=@2r{r12rX*Iva=Fp zQo>!fHxBpB_OA77D(#1rD^}>RpU%yQY)6?{CIyVstiH{zmhA`&c;|<+Imlv9~>f-UhFtDp`Zhjt&z`qj1&i4AQBpGVjB#GH_2!TSdvQ z5++B`n7CxJ*tPpg96odiVnYE$B$3(VVVA zx==!t*Q^#zT-AK2=0fFQD5l-Q;P0U2i~*vPRO3H8K+Woi(9%9UotEhE`78!h3)=s0pt-VFr- zk0DMegtlfUrJA=aL`!oCOP4J}TW7b4y^&)vkAo&}2KRIbF+^G`k67pEdYZR4jT-S||rvy)Jjldf8ZAF0zfSFXf_5MQ~ zu?ZQjYcCk&*2@F7($X{`GUp2@p(3Bhd=J=@*O}#rmSmS1^O=BCtcmu}8dEpr-(rD6 zPF(j16>S1u=q{SiYWDPEmm{%8*RklYeUw}lXh!XNT$UzADJiO23 zt?)X9o;nG#M8ahxhClt(uP{7YZRdBCYQ|Y~_Vi%WrY(5jSHD)0*V)sJ-sQbG^~xbo z8Tao$d=+ZqB!-p{D;1So%u!^nIE!_+e-)9PJGUvWiqPf;I{dq_`;FK{b+*t7;CPj> zHG?n@Gb1CQFi{8-4qOOYtnSLlwu24>H}0^FV7*E51ns}Ie2Ykh4%LiV0diQKa2as{|7S`gO(FgV5HP8vrQwY zIH6FU6~?-iR>Jf&uDxzIHmzTw_u%zUPEBaR&*W@8O>T3-Zf%i;UTerU)rKP!B1I*;bAoQ2^$K z8?VPBk34P@RU89#Cm1KelE694`lurh`3gDJ+F_O! zhtwo^UHH_Ci+9;;IbtCg3v!|yE)_AD&0v;oNJLDV1tvDedz*;N;@S-h(c6_oPftA- z_pU}&I)-FbO?d*%(skP#T8FbdNUf*N|7Hweg()KuD}a;=dP zMTYc3iHDyRC-JhTipHDgDKJ_a&iWA|1d13H*#6F4@OB7KXddKJ;+-e3!~=Ckme=m5 zP_nhI*DA}vTQbJ|P1RhJKDJ`e5STej61e8c5psb*8eVbopv3W4hcyHDCo?gw!&?Zj zWZ%PtLnv7c(I5)U&z;Lb zqj$+7v^Lh_+Us@*?cipi>($!4jI2GgiYlXJ-a3R8e=Kp(dlDVlb4>Sw zQ!Sd8r?`moLdYJsD^;YOF#)j%iA-pVgnuh1FY_#^ zZHmd@*&xXr4$v}L&XEdBP_1_wf+s&7vaU{U&MxsE&@lB?)tZX z#wY&lL%R12BW+u15ZKFrfW4=0&e4o3wwGj zu=&Zx@joJZl}gn?Z6+Fi(3lw$g~;;g?;lh$$;6DjB;9{bFU;6DG_Or4m!oH<3>wz2 z9d*fM8VeWph?LAd7``M!8$_Z616$i5pn9RLq+Yk6<2l@T(=~YDHxJ6JMld=NzG4w; z8y8?@ss?S*l#&AKCj=6&D%tt1DOW!fYUfhAA!7)KbKnKo(c~C|Ct{k=aLojvTudhX z^|k(-5X;~#LvT+{^ce_KlZ!x30*Q)hH$+5i3}oF3+E>0+Wg;B!MM&cHJKn0`JL&y= zZ)YRGKyDgCvw2Na@b^SI)i~ZPmNvw(>w*?^b~T`PX%AXD+Jp{AVk!0dNyOIs%unW- z*f<|W$q$n_S7|hUmTMkJlGqIGcyH8i*O+zXIVgctweA`lQra}1A7KVTVqf<+sAqDo zm1o@!472pDvl@b7Ren z6d)}Gn5v~sF|nXgsw&h*F^2_T(k3Fvq4>+s+>ayYQ--Fv`e`U0W(r00tXhfJz4``x z^NV+3Dwo5u)hp4})qw+hpGQ-=gj0QE_^Ugv!jdK?>9d$E%wpB8Uqocbj!P{Wwx%1Z zQfZ0%@ZzN1&5hwnfN=yZp$LW=TmYIEj>UCwFn}-sm{^EyG#(~mG{>!v9X106AC@ia z#cv;a1erlD!K6Y0Gn&9goY)aRr0?p3*D;m(P1VI)mYHltiI6t^(*Prt{_W3 z1Kr!G*&qgN%*2eWDkl;Wd>|}XhD5`F@lG<$amq=oV*YrFv-aSp_yV z2+fR;EMpeg<`489EDVO;Sa=@cnN(UA2CIs3?e~Gl$&)W1M@@Cwo}>40WrCAPVq|DQ zupI+~v<_r*Tfnm3CD^#SSJheI3504cyni_C?BRw=ciyyv6>I^YE)yTE{}+@u=SlLa zx~a4_!a>S4W@C%y$VQaljz9SrlBsIsW(t~c;WMDO$WMRxL)`iC51}xV!_X)H3WbLs z!_t~L9G?W@yLX`PEq`o>kb4&F+rJOLf8+^e@JjN$7rS=tDrBZ|c>ehpH8De^NfTB+ z)xdjRUSIzCD+j+NY1$Y090msm%T=GCQ;`1w&e|&0O?=7ih z@6(3DKr2ECz6_o&kpKW707*naR3{0A0)~f1Jdkr_(O%nNAZBX$5= zETM#VmGnnynW#%6Bqmroa7HZIsT_(n1J2l5Ld4O@@v#ZK&{HiGyshO}sX6HN_dNAf6`U~w#xZ6$AGN_O23KIufvQ;-a!ap7|mY02#TFYy|z zXXD1tMhMJAfw9?HoSvT4;cvwi5S`8AE!&r(bwLE(-A!1rY6Ft#gnIg#S}(WhDy=JC zzY&EEStc5z7Vo_F9^YU0&65kk{~vrcbb@#uUoqY+v5^i^El`tsM=HggX8$Ce|{X9S&me)tz(Y9 zVRA_Otpr@SV+U@$W*7eD?>{4Sap~F%(AL_BQ%8@W@6=f|G$rugKX4s7Qj_AMExYAk z5ZQkDmJ$P{c`j5Sc!ShUw_OAsuYLpJOOTA%r=ga!YS6MuBbG7Q5P`^j7mNvSFtj~v z8(BPj^q63KE#ydCUJfly4Lan8Mn?5eE?U1Hc@Z=Wxd=DPq=$XfA+kp<)ES2jg3-QdDxQo_&8 zMImtu|7jjjyhkJg@%lCAU6m9&x4J5cR3e4?`dZ66V{vKxGcdC!Rh8mv(RI`A8E0b& zADb|f9aNUo1XW6NJ}h597moM7wVA~MaOqEv(ewLzl?vBIekd=S&Exs~$8F?QRj{?5 z0t%6Hod*+Rv1iP+u<4?;XkXA^NT72G!ULSY<^o)9*Ji2UAG8=8jt$9z@fj>I*z0=V zR~j0@Z{3qFm(o^JC7z8P7W~y)ZoLh4^$l7tH8nL_Lz82}_|>m|jd#EMHjLbJ4<`QM z^H@^DKn@(A0;1b4!P(p2U9JMT#wllf|F3_iM3()0Ay&yGHeGa)h(OOh_kw&&OnKBe zI*s-98YMRH!P-$m0K6}5eN+ZqjzrE#=tv2Oa{?;It0hpZ$lKaG(AL}{iE}0wd|h%3 zl2w$THPbMe1yNPgUqCHHpYvv7$+ing##EIvY4)I{;-)~(86cWKos;>=rnSH#N)V_H zSzA{pqAO7`t_?ctm5IhaX%rIKfEa~}mWK)xqxZh=UHHL0KSZJgys3LRdLvO(N37`3 zWECqc24s;AD{|IGYpEm(I;5o6U?X|feKC&*SxA=+(Cqt`>;*(FAYOLU`_a@b!^mskoLF*AB~G?-m7SCi+fXo+iH2%_5Uq9#Rtd!w zRK0t*Cj=IYJGK}#MaTU|M_xPpr`=VPq*wb&ByGIYh~eJWptU;NSTSpV5lLWyDgiG| zMHvsKx|T76oG}v&)MsMcPMEGpewJq^TLIHJaQGOGjwXygUIJ5g#r|cIV7VA zU1KVpRD0ycElI3tH|-vdYX&kp_nIC2)Xt%_y2VGv;?Ljp2%b8@CoV>#KAQ;llwkL> z+!DAbHf+BFx83?${OzCpCB~<6ShQj>x_dg&cl-p-oIHVs`V{{By;q{ECWjR_e;$z? z+qaeoRd9Zpy$jko8w78akTNG0%3(>{+_vBNqs>zK}E+wMl`^Kwk z3C29$$9?JL!x$cCu;J#c!0aYd%CSk#!B0EP6 z&ij&?7{!xMJ&l{zuEN>3-iGF62}|mLu>x>v3Mg&92>tK5!&5~|Rt5$J@x34XSfjmM z`%E}^NGx95qvx}4-vO-`6S=Xzx{_}p0s(ikgFc{Irc=QdUko#IGZ;8GU=@W|c7X^s zKd>(8U5Z*N8j_rtV2dH5BspDOW08?3h-+Uc0hXphNQR^8%~B$r8YV`x0x}tE|M4DK zGHUyttrPp6?Yp4T$$iSeS6fqusm!DWL8=f+0g-JU`}|Cn0!cX}JRw;RW#ho$Al~!t z+wr4&evIon7U3dF7%@mYc{;48fT)DAQ9onN0nm|_U}~t_;3|xkVOsSb5H4fIJHghW z4k_k`gj8@p$)?6{DZhp~pFs@A4p5TN%zDTt2i)nB)#daY5rxY8im+!{g4+l)8L?JI zNa*;U_TMJrBd)e8d{2Ij>Q_l%;&BYk&Eq{ubsoCQgeE&hi9b zMM^r5;|*;xvZa|jRT;O0=Ut3)$xKYi$EgxJMt>FxTIFVAK(ZP+G@ul(!DNnTSRC!G zt+@NHAK-}>UO*(7Ku1Tr1lH);AQHOHu^G^fnMiRuK8`!zw3@wqo1F2rD&oG1Wd6J% z7~E%7@iad2KYoV6SqfWKl!W;i!k3CuzehkE7wz1I5C4~U;QQbF8lHOkB`jOBTq0TL zPoKf@L$9EzHH|-i-!ANY%l|=S+t!Opl=$T9aV|Vvokk{OJ$q$+{w4WK!?i54_St@e zS}TbHFUF7u)3FZ9Yyl~@S$~sMEz3cdN?1rkr#a|GQRkfIPlt~ju*DTiV8i-#NO3lo zW>Fjqaobw{yZYm<@W}opEBMg!3~Fc{&8>L1A~NuLWJ*GMY75yp{%*374;1b z>L-PfG~RaxQ(hB^oFa0OS?o$=d~@~K5~i(A)I;r1*H7oY=RMb->c_FyN8b$_W3uOJ z{Ze!2H0E%O{ug0W7wJr9^43H!*iU9Q%~8_ne8I+Y2w{&KgiVz)&aO8vSb(uH_io_q zajFVe?7S3J2`*6U;b~r;l}g#4z@TLfB3A)q9d zaJa;;AC3&B+39JVADKihlR+k5z#DIU6EAPBql`DEeq~K1;ca?4=suE&<5JC*}vyKI0fOrrBF*p*P#(G zeLnK@k56YXp3mZ{^_^J0FpaM6G?uMej)tZMDwsHOT^{?B?}q8;5JoQ+NGzwAk?m(G z^-AO?p=%==tu|A&aS`T-nD_{@rBRGO z&>@^Sas$l|QCpovU;jXv>E6)Ti1P!(IDO`XWs+oY zCX%>t{aW1st29ho+;kPJ_s#%dy;GaCFb)81pzHCGJMWb0-QEKSP@k^H{lEOV;5ET$ zf{}RWa~7Nsn~^kmUy{ifCdQ{QJ~1Itm-)y74`?oEGq0iVyY<}JU*r8?@T6V@D;y>T zgo`AS5sjj=tpn-W8oORZkfqvUJ}-M~j$ZP;Cnv{MjZRHwlpuwkWQE{mBUyGJIbVc| zY)nWHMMFb_45o;9a8!)ht0hEam7C1xWMbWk~UtjTH})X{1FR!e0_uL9M&yY z*Wm#2&&s)W!ngcc?_t_>gUgum?_P~qy#-_li%;g!KX?wO`-i1rKQ=xpH_jVxcnz-D zz0JcI50WIZ(-{nZ_#;T~-;cG803{9hHIfI;O#}HgYccqdk6QKPZ6xl8FaG;ib-(S9 zu*#^lwMEqz;r)}R&M4ti@S!^2?5q+jjXsjhCIvNvH3Lt`4q=lJKYi+yRqQhCGO||K z{9H3@)~wO>^V!)wF}wD&XZz96&{THn6TwRNw`k6;s!BL{V*yK?97hWa1qNk0=B1Pv z^11U6;JV1=4K(QR4wIQuK)#vuO6VN** z)|YL)2s20fu)UZ@Qq{H{vdL&fmeFDMTu7cLnIUlstw~Fetj8cehELZ79#h~#C}v3< z$e*Df=-T@s{)FU$D21;-y<>@?C)K=96|RDkuhJ}LVlfP4&g1%>y=ZSqV#)G$bS~^w zQN*>P1DD!4a&@e<^7PUYF|xvf&$W;<*I<5@w3Aag>7-(SV{~DCIu0UT0q0xr`59^! zP^bz*W$Ve31GQ#VSXxUp9DGuSB>PnHbUD)7mc-3}qyrFA>89 zOKS1H*DaS=l6WVc zpJNU7)1B?@_|s2*0zdodeK>Wd4{v(Y8*%q{zKf@xctQ&=o1ej{lP7cot0^~}N};J~ zfj)EJ$y3?@oU}+(CC!dhFuln^hxfIL+z2(S=(!Py9LT{=Pm*)*c^&**;B|HNXlZGc zS;@%xew-aVZ=|l6iA^yv;OF51E3|^Imr9uqxCe!hEr!0SoW10uVL~3Jyq3^sTDXvh zGZ($}3XOn9bRmzuFYiTf?_wFg?0NBJ!D*Ueq4s_xf|{BtwKuG~wOM%@S>kYJS--C^BgBFKuAhrnVat~FShcLj{LWotU7)LvC5Fm@n=?$g1aEYX zz42Z%xnOc;BbP;ylg!!B=aw;xJ^Nq5$uol@zVaHV$-%&~ZrwUvD_dZjwrs(bySD4v zNDk%mnZD<4WWV$!EK1FwH3&=s7|sKO(?D+JDh%HFv2xbVYbX?Q_~tk7QBdKyV34g| zyto(1bQC*xT!DZ8(p^5|9Za5#loSp`zMwI!eV$q{it&H=y#ogh{J}IsXgk!^)?(SR zrCMj~r;0D*Yd{HuD<6u4I&Te$I9Og2M4V&d7=&apAY%M|*|f_o&yXaxAo!V0gsmcz z%^1LT;kq>!=y~L4@)#HxKwC?zl0;r}V4UlB4WKNySprem3IHB#MYJ|GVP$nKRt*=B zjwew~DP}UzooBKPq$)M!G)xG&|VH7Yx_H?0CQsK&ql5r;Kk21|JxWutYp?;p^dphiuvLk3}??oyj zn9dbrf)@mwR6w{^gH_qivzQk#H0YxHIVVkpB}o-y=~}R*om6D1|67$V%h(f;qFEpLgHG#E6lpE3(ZYiJadW zFe-^fLAEz}@A&((ntYS+wGLErVNCLyvCPmLOHOQ^aluJf!IMG0N4RE5BgbP%B-6;x z#c*OUhu=N?ye4bbtzCw@fBGEqr8>Ojj=#q4&1*3+aZvG@+9!NS<5OdJ?)jH=R$j1v ztzs|HSc;=Q@z68)+Bd$Are+e}XO)bQbH{{>qvhsP6h%W#0)O$Y4M-HTnkti)1c~U3 z;np?Q1V(-R0=)O*Kfu{(BLs&pBM`dpUbwLZZU4ISE9z29Y2an-h z|K)b1lTrNa`}gTy-Sf+zBXYy_yGw+af?m9l(fAM<5UBW+Q`W^lWg-zseC`Bitp%$n z+5h1KIDYyxuD|+P3=WUtiN_vOHAM)vrL9#y@&^wdP-0+y7v{2^7 z6Q1K3NH9<7=;%auXS)`X#tqevtMCDoVOx2m{JFck8z1}gPvQsP{{cqN593X5d?Wt- zYhS^^gNKn$q;#krJ9r({}`$xb6C?5YBk$_L=u=JWS6hN&?i1Q zZ_c0hCXfI1sZW>TawdGdXKU7607T6>aqr6qt);~Y6;A*Iheli;>1bHx#4jDvu35tS zbmZ_6U*m?@v104)>{2^J_ORZEWZTW=u3cr$k+%vNtc(MxsE9DvTY{6XeD%ThYAl1ZehD7f&JSoSIk$K4=Vd=nMA@_jOAl2yz)^F}aYwIjJ zd%Dok+3iM0!f7qZr4E4KFJ2Rgb>gVOG--@AZ^#Bwj)XWpHcrTcmPKLsTz2giv&){Xe$30H;#RSl%rqlS~-`tBrglLY%Xdy0+KFKf0)gKvu%j@0~PsR_r zudZFcPNT}ljvmK5Z@(3dGg%yX{9*jh`+keaHCOK}i9{4nmmfH9tb&xQ7s~uYa1Xud zBO2e~pQaIRK_oCK`KE>05>~ETg$Eya9KB0g@$%jysII2FVh3K@vj=H^|TfuT?SS-B!2ip^f@KYjKK^66mjkV!Gu zN=JJqBDCQx&EfFDS9DF(J4mOE#K^rvREZ=eYvat5koA#5Q*bNc=qpFPM>(gp%28n* zG#ryvkO|V^MuwxpBKH@K!>1@^n%Q%xhTe6g2;*#Z3*6@2)SKEl)ySJgHz6HPk?eCm>V<;e>K}Z$?2O*$=+;^7z z`HX;I=>l$f%?&tz-^1vlz*#JghD5dYWXcbDk#IfHk?0%u3nhwO#@CVsAE9;#+e~}7 zMYy(&(Qg5!B1U7?tyStl=2t>WDv@~*T9PZ>6QT{C7^rq4$|{YRqI6P3LS*ZR(zhT_ z!6pZCI>_#{0;BBibm{Pfq{>;z^=+P)cOsD#uv0ON}tf(4oOC@(l_sXidb)Py@Cu z1Ch`6NI;U5P_NB#@aBVsiytd);er^ypE+&TVb2=5ieb_QV4`52})#`rjXA~D~K@gF>AW`;tTQSxBU^m{*7;7 z*^*vt*?I}S@P#j6YHS=MW20I`=E)F8dq=At$l$;zlJuyEb99DiK~@T0WO_5m^5zps zAaB8-TO$K%Y9UV~fg(7wc=fBU)VR#QfAL!woti;SU9A>xfa!R6@?a-Yzyq9rudc3@ zKv6oCR=a0OZwIz+*(`Of(p*ktPQFj6WLyiX8b0;RGr0J|i%?(Rq!x)ubXp)$B{-cE ziE!Zj2+j?TVsxA~&IK%8vPk~rtgJaEM@V%4{=?=*reufD$Hb(xusEjI*r>#YoDXh< zps4F$;oJZKAOJ~3K~!dB&60ZR+-Q8?Vaobu*#|VHvtA<>Gp0Ya@_9%{V`yGbhj-t8 zn^gneLleB{0av4d4h4#QB!eJh!iQd_RkWt2&)?&}ojh?0k3RW=Six_&lJ^SJw96xjf?Hw&Rb?U5ai1`fE)**DwU@k#U3u583@N)$#aFWAT ztXP2uA9_fzYHM=~dU{y-+2}G4MJ`OudbbM#^!H(WWYiK|Dv_$%w*)36Gn|MTA0PGV#`?xK+6*k}S)@I4 z`@3($cfQUxjA@hb{kX^M(5R4n!@*!`d{)(4Tf>Tkn{K)RzrXhv*c7Qob1H=@P5Z=@ zBrpjjS3$|KSGMFT=pLx5^vMKIJOWZ>2eEN1!sxaUpN-oP#to^iC$giI49Oz5ghKo% zsmdC{pqY5LA~qDDCLByNyl`BSY=cj&y9oJri*I(X@ znaNX_&PDL&|K|Zr!p7VwK(+nGx8QZxycW5!eJIAPr9l*?zAlBwpL`y_ee`Ke3{7C+ zl7;w__rF7`jlX^15q#(FZ(~7IgU%zKA4HZz(!~$JYhAe{f&cNIt;kKAeuNd|l}R0b zj!%5*=Quf*uu<4Z+!LqDIDAl+wRF`d|9orjGbQ}?H@`x4EeR+Q zTzAz~xazv=@V)PS535(M!kTq!@z4MIZC({&I6Rl#72G6Qc*1oaYo{l8_nbPcf1u#d%A5cc-6>- zYKMj;7nc2cRTW@XM_$61ob?w?UYJ(E-@5yUXl`o6YhQhXj|-U(f T3N0H~5~AQY zhkR}pS6zD(X70Wlx$k@j3uDu0o5w?#pCtq&A+u@?CjRV`WZ@hzJ54q-VMHgR+4We1Ugl`U2->^4uwh6h0jPw;nvZ_i(PvY%3Ay^eN*Q2;R zHr~v`a5^)MBd;8mG`T8eAr*OyO=U1LGN`rz3kz2A!($_w`r)$@Y+Ed;N4sL_3a#Ic zo=#-OMsa?Gh>jED${q!ksR%<=46T&&9m&$s2+p28hn|H!xc0iM@Y8$mLw#ljYvNU? zjmA+EOQ4Eeo_HK-a;Jo3SnEKrwrvh2QC4Nyy;5-0D5@o9LP80xJCTyp5VGX<>kP?h zSy;?_>RP{U)DuP_dBCc*AU_Ug<`d#Kwy-5w{ETz-NZ|KPxGpc<5^FzL>&JV~&e;g> zrR(P$z65~W0a2%bp#(Ou#3IHL7;8!J08?pZNeTxqiHgq6;Npu~u%IoC-X%5YT(krY zbqy*WBu?eXA>(vKmDP5H`rAP`tlax%J1MD{t`=<4ct}CiEwph=F50U6zz;FvEZeUp zfzN3hOO|Y!&P=3i%>|@X1ZE;)PT}Np3}cz%&M1Lnv1PF}jKm8a@rj)%9VKUtCpiSHi>gXdHmI9ABJfVN0CTXw-}HJs{>T%!>x*ASJRZS#CIiYpu$9dFOXQD; z2}e)kn8By+ya_e2jCp0ySS!XNg7<=GAn>98eLqeS+6)Sx&O0$WyqJbgY_25aikI#z zsh@BGEgGkBWcjkoci`aumoYdrfG3}Q7LhA=?I;E1HM-Ni`IgsW&1Jjs(GPwMwMjep zDWx1w0ZsLF`18N`3miFh23sz^P~;?5uv+vQH3RZ`qEx<=^dM)Z}8!?;B$vB6Hz*t=s9zJ~>g;ELiHPyIo_jdKw zANl>0$WBk-J@0v^jCt<+@x9o#W4jQJ&wu`Nn4Ox&=;WB*-zE}h;$vb;)}*m4lG2r? zQ*KOeR`=7ntops|!>iXN;!BV;CZWu<0a#t|KAaoq$JErc8FrMjcRRpGMn)7wtKvz# z?M=5JnIw6}JuuY!g#xmX@+?>cr7zuILqW@ZILV{x%Vwg*9QIzR0*xQAtlZD^oy6Xw zeds&ck92hv7A@|^@nffS%_Q6qw%)z#a&)vcDlq)!caNf_wH2E$S}XJ>fFk&sEMLKum3}5)XLF(+*}wj4 zG^S%%7B_LA|LjXhLJr8T-+=7LKdyUkcRGSXE`u+9_3I)iGI=CnG?Sge)6cw!mtK4k z?X4{`C?Zm$`vq%N1$IC0U8vBvUa}3_F5QF&A9(-|KKKZVvvl5!E6F5_oX&=Pj$C(y zYk4S>W21Hod&9Dcjv!e@t9Ps5W%wf(Ml*O4{5t2Zhc5Lj1v(~&1tM0n$j=xtk>g(! zR?5##V{X>e?=snG^!E=485kNGEL)3*fR#>F%O<<4r%gmxLa)IXF0@(ZKSw*PO)gA{ zolkk3IC%;^-3xKUP1oV4Klv$|>KYN5oJ3n@7Olwysu4vh7DIEo7HN+7attq?)IHXL zsZm%WAx=2vec%uAeOv{S>%n@qRsl=INL9D(!Qd?GwL^vcSypGXDF<7=OaQDF*61ON zEH&HQMp_yRrb9qHqO7AJD87PT@O89yZHpL!re3nWhy7b{TXcameJpc>w04IRC)NGd zPAyMpFo7X&qGrJyHg0Z1Lwy2E7Pg{Y+yol~k-k%95+X?dPQTxyQZrFAZ zu`@>Ut?4H))e8I?OMGmvn;W=Yp#EKBk%1T)S{#+Oi&fcHR0fnn9v?d7ib^b{aH-_N z1hAwI>BytZvNW#B`$sNMTvJ@ecd~Y`^mm->n@rZ?qksDobgWr}w^ZS2k z?FQ>%lu#Xy;REl#1IsSF5Hpz^>g%f2FE$pasEMj@_8&fp4Qp2*&zr1ychjflAu%{Q zjCa4|UFdGDR|R^u?~EI^R2D;kltK{J0&wz_`b>p6T({v86sHR~Hq?))**wN*!cLRcj<&%8MeIQ0wCS z$fzX-n&CC*jElsw-B4xP!EO@;B>Uymr#B`&GtC);%cN7z-ft4ekDtT@<)vo|g5a%) zu|6mhAd@UY-DrznY~?t1rP zw^KhqmOyT13cr8sNxX7wK$Sc_3Mh9?a^G}jN(s@%4Qp}n#?{({`}QBfiPPs%Uz^62 zyDl*;2+KIicB*A!)x1`LDxAR1_d_SN^u-=lb-`ATwX=BHT!^7pXz7l70C<%V7Ii=t zlq|8ja5lLX0af{i2Jy{r{}{Wj*p78;mboyM6U>yf*a(?a;wV5;6~`-wU%|<~bI6_> z#s?1_2GgJQRoTh`@SkJ}r!yv~G`o2VratsRle~2~+VRn0eB~S8!Ob_nR*7Uw%L3i! z=bwKW`}gltkR_U87QS+BFF#|UKoN-Obk)_n@YGX}Y1iX5eEJagO15TYf?NBl2(T&*2K&AEJ zBs@C=2t}7P*Um$VGv}{*-3|EOJwK3gYJF`T(v*xJ7)C=Wg2q%e(zGv5rcgtKfyq!T zRkmSP)#{ZopBJkpp&?QZb-Q4airH&-Qn1#Xml45vlB{{jo_l4jB$oF_#6w$Swr{aZj596>pFx)Rfv;N9N9CYU?>kgqx z283MLG=u3-QV7T#D0N(FjCc+?6tHpLl)f7eu<$F`8{$sg5qYt#}D z@5xmk)tWS{HK>ttzlo#3e{&>(=mHToO*d#wxJjUsgstUdEv0|B>ro7&9@{ppz%>^n z(LWTy-+cZ7OyzTG@mAMVqpqb1Z~5c5Arb3BcPmNfhTJ{+$m2M0@D*gHXnh^Qjjy^1 zD^~QNsX2|o{`2_WJ@?}G4?l?Ny0o|(O7aud^5->hop7pW$Brw|MBychZn^aU_b@+b z|H&ix(NBIoZ={ri1txZ7DxvOg;iKf`5nzvNp2jNP1!R^5rGSCzG@4u6@RR#~gvd2l z?J8MD0VE=ET(|pbTz=#A7#c5NYGeYZ&z{Da(}NfvnNW6o$)>ev>ui^LVX7*jih~sf zKh#VyFShf~e)2<5ow4uqDTjE>-<%tb**diYB(EHdhl1lBIRTLfMutbQq`MnSdzWGV zp@Ycgr{&BiXUJ4FdV3dw6)gkg$`wnosAmO!aPLoX#T8qy`-)u}EBV$pzlHo%)>y=| zGYSU086%_P&K9;T%XAS8-ZXs#PF*mlT1BRSAmWZ8CK`c^vS(i<<}b5YCIEy)&kfK8 z(Kr`esN58R;m+VrIQSAu^yV|T_~MOvZ(dW#?7{+966L{1L8@#-Wjjd|7*SKEG+AUj zD3t}fiyk3o-rrcXgkL`Jd*t$S7#$f!dq=z8b9lsBFT75=G+ul44wR_qH!y@fFCP;O z+EiDI9XmF9z_*^DUQ*1)+-~LL5(w4~GnYY2N<&+tgr}Z)4tozC!P-?9U~FO( zuYUGPDc(^$`A37-626Qeo!~WZv`MGLk?okTYjbs&`;A>z1x;X{T%%Q%nLHm-)Br6_H!*H)M z34QfVHzJluN$iTP0tLqnioab=*JL>C;SiYNiCIRkw;JPikM>GQ@VNr*a#SLK#&THcH4wC(Q{NB+BV;lr zFoAX%d2#2MIJ4rmkw%Td%Dchtfpl8Mr2RTV>X zYl9LFlQ<>v5yRxz1b+Fm2k@o4zJ&Gb*E*_aR^f_qMYj2KO47IQ+Nt==?`QKlOFkL% zO0)R>H}Aoja|7lc>S#`IJvJ1_)>GMCwA@x>d&YP#A+fTtccS7saZ;)hRY<36@%twq zL}d4sJ4*^wf@~6KY3;!78()RbefBFDKRnfDVD!;$M(T z4U)u_wgg}6%XfVXo!vdSa_3evJQC_+zjLm?4^KYxB9f6La&vPS8XiHhP{i^TE3onC z5p1CYWX&Afl7Bev_@5;TR9x)K0<$;VfT_2<#lkk%%4`uYyzmU3c;Y#{_I0n3E%1V- zdc3&jWgI(p8iVHtM1oZ{=1!dEuvn#Ddmfp2{6YZyL1q_*40=y2JAmHUbNjQ{`82k*dV{^7GoRmE}r^*5kr zQ4fCp^IxbSXsB<*w#&9)I-il~)8tg9tT|5``7N6-(r4~nx)i6+^keVd1DKky(Mu*o z$#e>s&LfqX#=^Nc>JxFqWWED5B~xgk$yAhLI5AZD9Dm8DHk3HHf~?k|T78z(%4Ethv*Ww4Jv&an%bMFM=?(WVgM8Oa2;M)*ZmX!S1f^hhp^Y7sxXJ`V%pZBw^ES$*wK!}H(U1kR!Dh%NBEg@U=4Xo+amChdG_=Ig)!mBj zg&pG62;p+Md})$6X|WuypV_baCgHMX;b&nc9!Yt1d}`ZlbGva zxlr&}VSFneS(b@X5E`?#m+{05Qej*sSH?zHIreHQgo=%B?#0_{Nd{qkQ)x89XGp>L zyo)FlllbVTe~yLARx5EUOwZxOu~)S3xb`{uB{Us#cgkDJf&Nr=EY3#Kp^X*&1ajS}$qi z`i(f*e;SWH^0f57tZKB!5Jwa{w{Jo=mq%wu3u@9fB_Nf>d;vfE^~2Jl<{MBtm={n@ z5g`&UW-LpS{j`tend~cr&786r{ycA()*@$l>*_EtaJH-qkWO(FGJ*>)+K7*R;uHAC z&wK&>=lZa5<2tbl(Cqp>R42sWXD z#%m! zDp~JZrE4vRAcXV>eIpMTA%nH~Vb07SmMBw8ON%kV9a1$ z?CQeVbA#HcsH~e_&RKX{mYlWjVpKU z#ENALh31%Tc?^StXYs`2FCnK1fVea+I9b3=wJ{dOTaUhicshnn)q&sfpQQ$s?=eYW z%VGA-Z$jqAn^bA>BQmLd@Sz9Le|8jCT)9K!t>&f%{Py98aJFv<6XRoMlEij{Z`{?Z zS7H11t$6YIXRv?&E0`%pFfl$U0V`Hk%;+_TjuK9uJXt1ewY7EN>fKiw;g0v;$B_*J zxAuZPBdb6y;23$)dbAv0wt!*+Nj5sHB#)v*=_(}SDYJ#A^f$+IMQDtv&Bh?lWZzsP z6ZrJs{~gYr=~HWfi9+b@a(yviaysJncf1|XJ^d_(M@Kak)z#gO>#n{MhYlY@Q(Xg| zeRj7~aP)&Wj3QSL>nDwophHpQ3_x*!L{i z4!i@Yd#b{<5llVXfNrQgT0k_xi7-Pvc<3=XDNv(fZVpp3Ib6J^1#6erp=)6iI=Y+C z(AcWAk)6(~&C3tLxEUsoxL#&tjO5c^I*fb@$@x-D6d4D@gaX$_AkJFCVfql{)tL5# z-Ote4FsQ(j3RUBFA5D14%=0vY?{>=4>2U5rAgXFQPwhNcA(Yaotz*8YM!Q3j=PH{# z>H3Ca`1D=BLouGhrfrwt=)q%ng*qiJj%D0OPD#z;Lm&Adw(s1InyOk)G+lG2oDqc) zRF3_paQ}V3#-~2@X)IjQi9(UB@T3%t*^(v4NB%v98BIP=ahI*1AY@2%xHuQV=;(;h z3|_zZMlQE+#Cj9d3o^}iHkgo=I9=|^6x3Y9WKZDLn3PKldk(yW$kn@dl?-aLJ_w_L(5Q(IGo>#p04@sSa1-Le7ksP*W0^B#NZdHne2Pbec% z-%l_&$ujmc8m$w_*912NlS(Url`K68Xvh)8`1lmg^;1f=5!q>q7g_I!H>0h&5r6%+ ze}kc+G2D0GFXfE4bH`3Z6LZK;Ory1RfdW;A?s}0JPMtbo2!#h#+hifPcQFpx7~2d! zO|C@LkpK{T$RRN>$TDbuXLDJc?d!+H*f{E`OYaPNwpuv)#*8{356aT!pulwbr58#r z^ui0*BTC(ImpKhm!g959Q9@|91XU!NTL3e^8%D?ICDQcHGyCJ>h~BNp@J8L zA`lv$%;a=X^0n$}>#=(EYBbiTkcvm~;+|J97h&+%v^ZMYo3P`ub=JQN0w&J9uCzc5 z2`IC^=lTAIWJ~vq8NMfEHWK9(n2XtzTNCb65XucH&CTOyunM+=&%V!vfBN)k-21bK z@bu}k&ty*7=jZOH)ukOdW{vl+uBo`5~FSxz; z9A5pZ>+tkbPh)IsO8xosL+1s365W}aoRpk16S~o{5s{M=FC!7GT)7Gx*01+G$>hm- zPt?Y6V`1jP9>IEO-WCN!rBn^-VzlIy?fGl_4Y1lAG64jw6ryw z1-6stR@~>fQJ%r9@W46MJT_gGz7Qagt~!*%RH&4whrS`ALX$_t_SYubpT z?nb-wkbr`^3QD%>xG;PHfkz&;c7w^I8WWX2MEAad{$4!&y_Zx)r;_moQr z&2hn?ZLKMNs9e5;LaBn`Yg1Uwtmy%G;TnE;5~{4qa9OoR?d;*GD)JDt4keCbq-0sk z>V(-9zc}9ZGe7eY1R@E1^-Et7nQ-{>6}<7$H=$CavS6z+FD{~Tv5IS>*Hu-Lu*bv6 zoCxhOAY#!-S_CQ9L_j3R!Xz?t3Wi1yBH_+F5coR0uF0t>X&%9qaP$O*tWvmjU1 zeC5fnVQICfB!`4CULU6`_$+z9dEfXtyLRnFEJksq1ym~>gERP*rB3&jRy_L1o%a4- zna`dbd;$`Ssj$CvkOT68rb=#<4pNV_|+#tr@lHP(%Nx{t~IH*ReBQN2^U~ z{ZD-{Nw~=_+OPf_WOnV*H8ZiKArytX4jw#&Lx&D3fHgO_;%k5X4P3oqYml2xnLANC z_TYm-p*d;+RI3;tpU^s|ro_>sM=>)qE%75FX`U~`i#&4V2)1wE-U!%A8ol!7rV&3? zQvTU^DO~q+rkb~5GR4@f{a1B|kVn>q`qZT+DpE1YkD56TN^UltYR0es`fqJAe=>DT zZZcLmNs4Sqi(wsykL<&V6OZEg=T2dIasv0=cMpcI4(q-=^5}y&bNV9Aoc_KY_HG<- zdUjf`L#gzmcO1m`o_Se?geF5uC7gKR0la?poHz@-MtM>=^fO4apF#y)#X9wKtLsJ#x4N&Vq_ryt#y7K!) z9z0AClsEvisb-8MezsmIBS*BOUdCJR7{vbVN%Zt4v2{xyV#$$66&Nv z&#HeZ8=C%dL$igIFnI|~6qqpBv+>hVOxo#5Vp?~OBOZ+y7+l0HpIkH zvab&NeCnoAR#`bd6}5#JX7pR3(-Fy=Py> zAAjukMH=;lS|cR7WYLinIi^l@kwQw=?lQEQU(2hjiXBSeNmM4%y~*1`v0N=ziba(gQ?78zO z6$_y8)BE1@9`!`O{N=A95;8dd$l=4X-`vvME8=7!&&qBcW8)**pv~0c=V30HS@u*N zwCXH_HIvQWRgmm&_J670-_$U=;YZLy=BEe+<&sBpDh6=gEB+fvNLqAm+)N@#@i=DZ z=d>{hF(sQ)2n6f6_240q7x(Vlf&Sh;lw_P_aJLx3T2N+Eq=n|I3eN}NWQXNhCg?=v zM`rb64hM8Vj?b)MacL3hR1(Q#TnSHs_SE^j$X;IYY;dq&@NYKDO=l`-lBcc*(A(Rl zBte?&-T=xS&R(R%uEQNHP94z0gNlb``3}((rc}TatRAdi}s!#bwNLkp>+b8{_$Dq5U)9){ zk-bcYn{7vGb1-A)7h6?lzkgPJNvr^P6n3&R3flr9ISMR#>E};$n0P*O71#aVd zsP!XxT3=y1!kz06^Kg+uq0fux+3Ndv@){wQHkF z@|o1FEH7hvY7#xYThP<9MajbG=vYHQtE;;QiDVSxqvJ{(n1GpjtRXADY6_E!v7Se7 zErLF_K?7kVNz~?;SuljwDDB?EDkLbA5>flX?w8iEYw7re%c@;-T+{(zC%o$cIH4c+ zE%FP*^bilk#+v0T!2{YQ5>jd;8c;WQx7~4rp7d3(j6#49ebm}bQKwk=PINF1b_812HJFum%SBIzRE>Mo$ zjnT7cMGj za#7xT$ol2GcJGqg77uUsOxH6RO=b8VjU`@Qw1bES$Cxab@N;l=izF7{Vzvy66*sFO zE+R68J7d<6pq}E5iuUlqL~J zI2I9?qqC(6tu1LOD;8yfWd09=yws}WpH1+@PzfV+N;Rxf)wr3w)t%fhi9P(h!^1c5 z@|nxXuH_Mm1l1a1!bHWsTsDhX!Vn=#5(4OK>rh`=3)!<|#VoF2+tyCJ@v(awWW^s` z8yo#@KjpytVVnfZvPA&f)zCtU~ZTGvA9eOI?jL;DmXrZCIkWq zMa|}z0iSDV^yUbfQccE3NT&peu4o#^#;W|x_u*TQqOG+>&zJj3(;`X?%*D?q3qpCA z^oz7--}j{x@3rj98v)uJ{!HP~1&Jyrcj8)`rj=lNC_ZVW_Q^^ngD0Q-y0tC>9MN30 z0z=a%b+sgjmY86Tjd1e$9yqiI_uX?hcy?a7dJXwvUg#EGCA-=>)&5|slM^|UQOwniE{1VsF@l-Z0;-iF0`+y&*B8*9tYd3S6xS}j zj_m4!oPbs6@Z#Mw;Qcs!cpn~n%VT)p{)bRva>P+nXY6OK1SZ>M88yWtF^t@p#DDya z-^E&i`aLGjWhb-gs&h}$^Vgx*lr?8q0cLG2qduo(HyuNs z%5irdyHk+ow(WxwnW>aauxD~&OoATvJ|R2slk^s_fG#)6vYA@3pTqU${m7;Hz~Jcg zB=#gI&fp;rrHvG5bP~+a}y$#N}?m3@OKaF--q|U>$n!vcbs1Au4B^^C3BKf5704o8|-s~eR%+1zBYoDObL;=5rULZI0r;+ zr7+1X5tJDKnD7+xQiSAG2SFVY$&$$wIy<^iuLZH5XXR&$R11s!#b6M9J*{~2n;tMu zfLmBPKpgBP1i|SdG!9zN?s6>(Pnhvopd|zL)gWKFL_&p#pJ#9M9IQ8K#hL{SU1P(6 zua4)QKZ%jiS-kf>Z^tXIyo%FjFXLxF{C-rbB*Hqs3CC&K@jHKnaJh_QvHvv$!GAv5 zM9;1R>r4{bIvoNBoO<~rzWU@h@lzlEDfL7<+G)$oWGs%yKlv$X;aAG}hK;$B;3(HP z^#MXk5DKLN+FDxO7-?N?HY%X4WvD-3Nf!xMhYsDM8Ev8vK1ndxHY_d-_YDta24?P8 zvjVpOO%j<8v^*S5#+E9LZaRYUZ~8v9>}f7jaiTQV0wbcwwa-9EIC*q@0^k1jw_K7( z7fni}8#z)0&2k0p?d`7hNSzg$q7@KJ#PG&99LK3suYx7;mTf)g@9))~@_qg9JoO#y zJ9tnU6OTOnFwUL*zED2Gtn|8ILPHWN_Zy|d`F9&zruYx{WkKV}B(2%Fu^mRSKnP8x zGJ0zvbTEN((%~d!cP8U#io_8Q29esoJV;K;c#~8?rbD)h)A}N?Lv1Pa&-CXc?9l%;2!#ksCt%WciAQltOsw7 zgvettu>qG_h8Yob z$)6_#8Ht6lV{lN=ts&)zy>_u7HsVQzev{cjYVxoAH_p!sfhd=i9N40&V0Ly9#k>U?-@Z_h;xq|{wsqqT z58v6SERCGxp-(5&!Rmw6m4{`0RpH2(o?+mVPv1{#WVCj%4XD&-3Bs<(=7ee2sedGb}=xA`|i;;ku%9wnoudIV-8K|H>*{-?O5REipqgX!A^6l(JM*&z`%4 z?>+Z)qhKKSK&@p7Mp+U=?oVHDpRP^MHxQDA?%d2Ydi%HFdrzNKQp{w@#?kEAaKEz! zamU@q@ci>Hps!~Orl;qG7A+8^bjc$>BU_u?yD_@xxvG@!%k~F9KPQ!VEo@Qpi^)=` zQbkj-imq}UX^^WBL?jqQYdD5fG>T-1QxQo+T$~t@NdkNBj7^gmWNzd~wP$=Q%(ZGr z6!hwbmhG`vA(h(_FYy=1p`z9dlX#*wvZA(;G#kycy-y^8ae?#sOfoc<%H&bs48Nv2No;RTbRp_f44VJ7(jdhd2l-erV|3t3rkQ674&jv(z=r!X+XH&)te*vJWjyNsK@B z+c>b5Ba~DdEeqMAm2)H-*IuT*027XHJo%&?U1jLz4B51IqCuQEelI@oQ$HnjQEPoU z0y>pv^*Nac5@icxX<-e&_3!^9>Onps8>#-gP|7S~ZR$1D$~noa z^B$1|P41tO*R6<{jnN@=kl%!?gnDR-W1$a3_#R| z;O3>nVM}w17R8DCZ^72S4rQ=sU%!II)dI#RCsi?3DpU!a#ok>zuw(atEvmA!z!po| zf`=+*rwS=EB5t2L@XcplLBMek{CyLj!0}7WN|etqpz%E8V_0ug{kUKl*)@_FNhspa z*(je(d>phn)ZdMVA3A1Pyo^~~7V3j!gK2HagZ0FW(B*s5{_k25o`J=0Iztuvd>iY+ z+P%K5Wk2YTbDs^X`f&aktRgO6Jdfv|e;sds>znYGU-$~%@s1xtZ&!yUSJfJBjEo@j z)YEv&^$~=dBRCqdv8}(&*Hq42AeaBcZ=%>teF{@X`>$X5GA^CJio*x@Bi-Dj`*rJW zx8TOe4LtMANuX{$OjV|JLkSq%nwwfNzc8n9CO$9r?R~pI&Y(=j)dsX=m6cgxI9lv~hwsTzX#EZk#Z5#k zKibOuMkM0Y%dg_>*>eqqgd#9}V4fetXGhmd9_qb)=9$82r-vW87hnJCH__9#6+?sD zaPq~M)SA$NNUzJFH zLr+gngXztP5-EyS z@gS0>g6nzvHS2om`ZqsfM^w%QXHRgWy*pujt=(_{B^G0B12_!>9`b4l&?CdOBltaj znL(2?B;)jhYh%a`oa2lnIWq1BL&%lNLI^}q)Tm=s|ITbrEmO%8*HNP7GuM`%tkUKr zQfbxqJ$u^m(BUrhbfwYNkwSBG6B5Y?qKRhnyWq5t^Ptd0I@xROWg#Sncrb?9h@p+T z)60PgD{q_W$r%4h6D9USCW#$1lB1>=9C6Wj9c)EZ5DHrX%XS3O1UrLF_dxs|Sw?S& z)tQ+QU1IBMq5a!Wj$*9oQAFBzpb}1?7t>h3^jRb#mNapllE20HK_YQSR~M4$6u$Yj zucKNmD$(+OG%7q%#l835iT8i_!}5Zmr8bLFC9DlQdwZ6VP)rH(AAIajQGq=NYo=IR z#`H%_lOoZ&4XOTnu(mV@RF+VhJ0~(I&p#4MXXj=WR~f^(wv3!#Lrc2JIC9R6O$fYO zzkc-AG$Jgn@V@(2vDUbgu@-Uh#EIi|RDzEOPM8K(LZ3J4M z>6x;kWdvL>VO+Ry!440HF!ztjC8?lnZ!+Ir~%v< z8P#09&G=Fmg7(!py$;(Q^KpI;yz!t*^T z+f3X%PKe0$_tsW8mIp0Tby+>G?+7e)!vdO|1j-1z`Die;dVQ+R2{=@cA!( z9v9DF#kT%l3=IzGAZl%G!qn6}uG|=vyf;7660KmvVIfeZQW1lL+p)B?ptZ=PfE(MY zfDl?*!e~p!F}*~oZxYAqs8z}${ILzdwI~xG0L@KJvYBmaY8Ict5Fu81_H1R@?X(fR zC9ii{WI@2B*Wh~YnFu6;Lv=gu4X+F02#5_i@;Y$p)G16(PdQ>`O;ZeFvAe*}1(qUu z6;EPjW=ictRzi2(eH1U9d=1&m8s7G{w_t950T(Y`Qooo%k|Ur!eOqwi#Dnn2p2k&VE#&tXkYCn+d z#lwN>PgdC@^_&lFb^QbfdmyLe@;u`F@;|anifAp=Q#+ z(wRI1DJasEjT2K$@MIltL}y+%(JT?8i2xEcaup{h4SbAd{B27D?|pC&db>hsO2^UG z979V>JL1U}8UHDksIV|X9M_szG+V1uL}%CTm1VIzz~m+16gCyx+?hbmmbIB35}+ht zL$2O>j$U<9*kXh0phC`hvDlcqAqrC3bp%dAc{VuBr5VL9esT$m(d}s7dK+qyW+8Kh z*Z%^2Evu+jjT}e~h+>gGE%DIL^8jU3;BWcs}acHy7>+(!)&u8@CV z4w@Pvb>p!r&;r2N$OJz1iN8QF%1IuJq5L-{w5;ai2~LDm5K8qTwc|Ll%X6saSAgtw zRPw8`$8JhDDe)V*e%-u4oC~I=;3SW3Eg6X;x$)J8AXr2B(h^Y>6t37e*>+1Bge2T^ z&s}u}56*Enr(1Nua#PXYnovLQs)wUUfb!4=-IpIk>R~ylVo7##BqSnL zM&D|%rBM^i>StALrq*<>t?l7NQb2A1q1Ax;!B=lwm-IA)6!{AzS8izb zMeuS^up675qWx$;mv6r*~|umvOrcFElO>Gs97>o&bwSjS5pH2ta~X%Un9Z|CVfg#2tE*}evZcg-5CZ6Q^cm=^pKg$Dn9wXM zURgkg5uiM|)(FSl?3G#d`F+Z@W$t=TQAjXw5SK1pl$xaMm0bm7L{_J+>4cY330kJJ zO;Nz=S_TguzZci9k78wE5#d-24?gsukbudNDM9m`R64MKH%^{>QKnct*bW}pg9{gi zHFCU`%c_a5IehM$8hJ-)96WG92pc~G{Uow$8TD-$%lJPP2|UE>b#!)gsHG7JvK3=m zAMtPyNB8bW=E?{H%WG&0M$tqiOU4y?L&Q@u*NHiWO9o@^G2TPJE)`iMk8Y+;0(Zah zU09r5M1Adw;v=tt$gL1&65br~RkgJ$e6ucR%%<`pTLOIl&FH7vG;Wec$FqgWa8nbf6+#HayU}v!hml=d1ab?g zWM)xYy@^(dQ?XJb}?CB~0vWoj5Tj z&k1wMo05cw9(qvI4LpGCLY=D}7br<5!I0o|-z)U}LP5~{5KaQr_x8169JI+GsBASH z#<`1EP@$rtGf--fR5qD|sNeiIh%CN0%R`K?kC&7+=~P;gGDw)39-kzGBy|C}=}DO4 zmld~S*QZg}?T3z%D&QJ=K0n+}1?n3@IS-_b~RN-R+V4KsoZTv`!wH561`DB8hUH3E)!s>EH*BlN- z4aQSIu|$HOV`ys+9(m-B#)dR^OoLMG`fLX`l)fAi;W-3)o_sCOtaZr120Pj+E$h1m zr8wsAt)H}z!=sZn^>CwaNq7W;hc4R;YwKn7_jcjEKk^Pd`}_;ow{JH(zWNQczxXn? zZ%w1UU^3xvw2|g_dkYeoRcl0oZ-t~`6^DIKBqN$?AT$NP-5%Wtyo!I!Sx#> zn4F$d6-<<9eqqL{I=U(r^NpmKdxzh*zH*dwRKH$*aBs#kX@SRh0`0XdArA5MO zpU;#5i3vNMA<6PrlFn9}gm%m-nU9HypjB&j=$cNifvs#y z{Of9CsdXJO*IfVpjlx2LPaI|35D05bHaY3=21koL5HIq^R;;9`ZAwjE8)|V_>zU}B zojCzi!aex#pRJ%6OdyhOLrc$I)FaK51V(7|DYRmw(QapQ!RxdNpQ3b~_}+6bN+r?5 z`-JU@TpvIF0FIw{gW0^ZK&Cu3+r6%BO&&^sbE;9`nQwj@=g(i1u$%TNpW|vqycVJo zEOb+;CL~&V5#0VZ1~_lvM`F zR2<6-OZebVyaPSmG_=+!v!1mq-8&$?pPRv5^ zof~U0|7q+05ypD8{UOI&P)lKQd=gh~j!XMvWo1c@j;#F0 z#>T`AV9;bDOO%T0p}ar5w@KPsRpPEW)i_L}rD%V2XA1STdX zwb!|?xvtn&kp#3urno=Yx?{V+9}GkTX&^)LVrNGuUVQOIdrO+wtaCq7-7k(X-7G^v zbhdY3WYngLS~)dBw57;(Yvxv(GLYLKc^_45?ca*-_D-y3Gg56`n4dR)1UH(i1JViI z2qEL=j!+?k8n2G5RFE6JiD)Q{&R7HqYM=1E1#mfHA$cIK4MB>i z4oz0R)e6>&WoBy9C7?{R4)$6A6^=oYv?#$P6JDYsBP;KGwJZ$-wiq;Os|uXxP#sm? zZ}}3~zBLtl#sRCW+uPc4{pNLX&HSFUoT!He0b`ni|&n3QK~Yx)&-2 zTwK#CbQ5zXyriZ=W0HZfK;%a{B8mtZvydX54^#+h4QmYBdiqM}&d#8enL{wYf}K5OjNZI~cszi2|H#`Ai`K9-KaCJuC2=MlL7YE-8PA`* zq>)#y1ET)qpz+zV1>*fMY{JRTmW?7MqI-6MNWvrJBrv$B!rbU@Tb2|yh>K$uvAAxw z;*4YX`U6N>)~?D`_23Wz20|WAOp00Qy!!h0bx8XI%m)Vk-G9%kZ+T5=Ukx*pWAeaY z<5}Cjec+Q6LiQB3*}Z!gqTH;Ntg)Q~#^&emXEIc&vc4yKrCb<%ZSVF-NS;#?OUo;` zdE9a*W7LkPDph(d}LBN_IF_npw$dF|sYA%}Mt(1zejT*frFThabAF@oW?f zeQ;%)LFCpA;-QDkENQT0qe19$eXb4d1SelBbirB)R?#>iDX$LZrc@fIv`nOI%xwcQ zqghoJpZ)BA#cj9UhArK#7#!-uz_0x_0?9azRX6lH{;rt<`3RFaVD69p05w*oy50(& zdHNYV|H3I%4UazZkoE%|H+iUXyz$EQaUFW|^K+U@X2nG=f=7S2rud9B%IgwtlFCT9 z{n5Ld@zM8f!CEnfpZnM(#-|A{2O0!hvuAb|v*Z$mg6Qhmf|cbZja~*qJaiK_p`dkT zTowbPO@~8Os$-$cj8HS_hLkbs^+~8&39cyMbDN)^75~5{XN_d$o#nK4nJf?%kD08c z@%|)oA#&UChwejXM;D%c=6S5=GKeJ-8u>IeJR522+uDn#Q%as$BG_xDY+JcSsuLq14mUsn|0!JGX&!IIfVY=|Dj7 zSO}^k|9G=K{=2OW6CaC(s(AG1Ahva47rJRXCRIfzdu0!vcwBboL)aAeI)A z)?d4X{OB`?M451Kj~mj)`%59H@1Hq~QZXxYC);;~_6s<6^avh#?9EususvoiQcmEp z=%hwXkzrDWXPVFCBSB2vq^d(aH)^i4=D1KZ3RPH=$S$Bfp+SV0{7A z^(jP3a~SLj%V{~04C8(8`(eaF6`^SYoFXBV*9-W{lTTy##*C&+ys9mqZZ2zM@Sam+ zoQVxoSO{J;iVGLdAaLUN17e0TbEg$7H@h4T#WgU3izNryfAb}O^lTgJUp+fALEn5U-(_ui@EerZ6!* ztSY3bxf2sJ=TRx;aOB7#L}PXj_`v)D$ouVKdj@x2%i_`!zVqEzkZ5kz{r7xBpHLaB zOq7OMqe8WLa-Q&wQwa0btM6I(;3Syb{k)PQiN_eJ$CFQeE5`F z9#)dn)!DA~F*P}f^OtU*TCa%9BJ;6g8FOL!qU3tz^DhaX9)BIVQi{{Io7_YHLx;V?MBkxxO00r7Gh2AfjcKTy=!X zAw(EFDf6e8Oehox+SIR2<0~OBwl{;LDo+x89m2rB^8j`Qvy(hGr8YiaOZctIH#E|8 z9Jp>sLN>&(f;;Xwf?E#XhVMN6G^QtJ8u6i!FUmUl$gzWX>Ko4^9<`R5-y4RA8B%5e z&JyhHJGLt(G2xn?oRI{&CYxMK%}XuofT>i(QunXnlOp~;V;s+Y#Wk%#6Y!EjQ9XcE zFeJ31mRU!H0|Xo^RnkG}U=kb6Ws!O%WkNR8HXu?E42XZ=Q5#EooY|91n_R-Ii3YZf z!VoYYF#j7vdhN4{Yr%0;+a-ENd-v{EQe~s;ZaTo}4=bKH{*aHko&%&k==nf)RO>z3 zlVRMsw;SCpMq*7j#gL4WGf+b^#>tp4qVXs?ySmWUu?c=rl?%wO z7qFhqVR2zeioHaxxc_zENpM{+y1ixVlJPp(I)JXb{~5AHqWyG=%p|`C$W}U!tPx= z(b2&~#`q4#B{3LY6^bJu@pV7<#jj&MUqx$Mn?!Z|z4Z61G0W}cc|#!!gtRqvuoC;> zxh$3Gn1ID~80ZkNK^*;gpl=HvdHD8*hrEYqJ@l{V+1-Qw z<=Ma2Bq37^XQ2>ACns^{;$^HCix}Fu3o#!4v}%qeFf~7q(WzO~ z8F2DBRWKwE3;`XV{3y!NTTrY75y;*|e&!{tO1A(4|pT2*=iJM%60yM$g-gP^!geyaYK& zic4etdipeU_jKXmH=Ix`dFI&{@PVaqJf7%6sws&#z40-8_OqYYT9eL1A+J5}4@zl( zu#Yd{s33Ok+^O|U8){ll7xM)<&-!)alLfUO=vYfJ8JB4IgOLXcTVd_3ZThT&mp3`Y z+9$LF-1-D&#~k5o98m-EcNlYA!o(z&Baoa#ka><|m`#t7KVzekZc;*B3hsS_JO~%- z893b(#s?li;`=!HZBLqHu{Si-k89UQY~;|v_PRDEH=A05hG5vpocRja`}uYwKVP|C zL3_Fxx9r~zWF|4#(}sA=M&4720NPs9h(}D=iJ@h6WgT0#w5yfC@maI1wo%)|x803o zbE^covV`5~BU7)TkjF%zx3-*VJW!-^(gJoV>+N~;TT$b4yKccNC(pQP3oB@ch6b@?=YY%s`H3@b%@tNMBBIk< zgarhjk8c(7Ij*j*AQ+A*u^~Fmdv0!zHIOJ7O?096{$E6<$l{IyO9j-k3kc??P{=Id z_Je7>_^qd~b)X*~`S9D(LhTg^rrES!A(zAK#58{YKYa$3dc>v}=kFGCA$ zUHiS_I0+9L`lp^94_sp~Gw~ISFFyj$plAP|Dr{x3@!3l?5`@8)Hs4Oo0bV4t5lZ5k ztt|NqViuRHxHx>-RkIuJY8Et{rnV;)X@tDzF0(0 zPdD1A4kj68>rGWk1*e|q#&)VezGP!?yeZKj(A!?adNGXa6RVgQ8&`1b@9!58Z0~-W z_;~$#>pAja)2(iKaajtC`bt`G$Er`U7l;fvD-t*2kqJL|bHqn_gK}=50V|4rl z+_L{s%*~&{&9SrCy?X%Lw)F|k(S6f{@`q#qS8t4KvE95mip)9%rfkleV>upy@kyTb zNU4udmfK`|TbpLH=_SDgfKZlr8XAu=XwlCt6B@J0k05S4bP%`Pvdu=EoVuK66I(Ll zpj$qDPdarh@zyx+KdEJY4L9qDPGc-MclQay0^ z$3O7|Lir;8-RKx%16y!7%l`h~?^me`oLdHN@BI6H-T&UJsn1NJ6>nWQfKVial{`&) zIPXrKfA+H>bv*$BWZ0AAPyx!p0Q!f9aP`Jb6oOUc2`g}q$+@tOYJ~806g47-u_Wv%v=$xWq z1?=1tYk?qIDizGeVkm}!$Opq{+t!P{x8H`rGpF!}`7mZyR`9;}y&G4qUBPQFpLQZo z8wrA6^QP@V#4L<~fo)pX3kwT!2qj!E8D3A$b)rYUJ?4E(EIw{bT6w;dnZQ}1OTP{6 z8`HC$hv=z^Oyw8NHrt05`wG!{fQG{(P3b{u7N69TFz*$$wA1exh7gm}I>i(>?_ zu)HjIT_fU~5J%rU>hA1PLNhWlq4tK~YhL@Mk!-v8r({kt>~>HnW{ESzvAGD2-gc`< zn%AygLwP-i{;mX?<7{C@kO*5LNG}3IL8-_aLn;|n>ypW%MIw{PW{XUI5ANXioPlT} zCawqDaEuum^VG;Q&kpwMd7r|F$4G)V_fEDs*t<6YAtpc6V2B{M&gl(9stE1#nka{C zmdSN|>086NxYCWa_#gt|IO^d9LgY5^pJUzV=-(qEW-3}nZ1n4hl%^yVe)jYkbab|B z$}JS)^`tRBKW==uKmZRNKhEPFE30eBP`{*9LuPeF90RsMB=nV_M7d2wl}lAD%*|=d zl0;8*dM%qpOG~rb!B&U^kyJOf9sdQaWG#GZGN-(TdVU$z;v!n2IUMMZ;ic!khwVH1 z@e@D(R-~Fzy6H?V+1_7US;E!J*YW8mz9C|)xEanW+LAHD-F?g74519oQj+k7hmO~k z#kv`HE>e@}42f0DUtng%KAnVK=ocVXbxClN-6UHCw1lOKq1piv+f4jW1{0IpU?0zY4Iew=B5xLl_jhen^6x%Fh8?|R4RdJB8t_O44RwMMz~^&!70M= z;nDq)eX&=;*|ugG0)O2}MuNE{IrIC{?kRF>)nc0SoJSDMOk@KhV|FV;jpgT5WTgtn_-W zfQiWo?A*CsQyzm`2Sk2ipUeS^7Smi+uih?wB+AUj>-g~>eT$UlIHp51L(h|aGe>On z%5oA55sYFaBSVMGD9UA!t}3vN8)&FJ8HUP_2T8n~l%$5ApTd!bV$LLDmt++^224r7NiQcVA@t`|Vdce}-oQlky+< z+N>w#o{|4u|9Zv)_#c15zxg{3pmHsRM&8y4=700mJn*xrjqiN?Hh!}4n*LjxuE{tE zjp^0R%fayze(-e~G<-hqrZk@anV-Rh3m0+A;RC2uf_VD7-$gECLR2QHMflx%!(2~^ zcmi8`dbIawu|0Bg)Hp{@!P0m&uBGDm6&lgq^yRB^OALZPz^Cx8c{XBa4t(Y};tpHa zN9Q4{gu}_*i-60(;kaAkfVg%bc_*<*KnEq0oM@PnC#I{gvR)!EAwpoO#J@Ysa1j8l zmBY`Z)=nK5=pr?k#MV%kTvi`?P zpQFK%u(=iTe|}_I3WS6f`)+DGlP`rd$A*(!^n$|BaC&d=dzfYn?_Tz z3CpXCc<)bs1fTf$Cr~YA#P|8tfB$droo~K?k&)|4ggEkCTwlk^%CZtJUMtNCt>82^ zkiq->?BuvvT<2#XQpU$g52RRYAMSYP|Bah7YnpJVS4t@6GYD4JQ7$YYR$s+kdr}y= zdj<`t_^$@{`|2C`vTO?7Xc@;LHnUFYYW8+h9jNp`ZDFu6=4_i*D$!OdwWa4~qoi*FmK-|g%s`8^{bS`uMQ z^`OQ_MsJK`Eo<$A&542npzq1K3suiaN`WK*03ZNKL_t)Cj&1R{S`Iv{{AO*`0n1_ug{ms8kc}@q}o1>MEeNIA~Cq~Ky2#DG&m=oXXE&zcCgE?*0K=(yA*5PYi)jwf4DpG5A({8N852^ zY6-u6?>)Hl?mNZTpzsmRhA5IWGczw0RQ7n8d`qN<&YS6G;}KP>n3|cy>hg+uzvGir zjRVzG2OQUe`<@354=88r%e7{rPOOY0#)opIRV+x<+M%h|Ce+J#PEIF4Bwg=hYR%>MRHC3Hhq@bVtJEt>EEHQdrI&^j^4iIV<6&l_#A+wVGss{> z-hUzp;lv|t|3&&av|~fP7{hGxJmU z?zdjRsnf%5YQ#+8Y~;~tS~#M->D~lz@zVD#Nnm&p?4>NuO(eJ*{WnQLwxBp3Ng@#S z-%SEm=!5HlbFq0bBtcoAb~H0l%X*nCaPIfYl`Dc$s1H zB=}zJWpXonf*uJ{l3$h4jY-l9j&xOnIcFvHI%MPejH*zkoifMuYFN)?Q6;oXc%GYB z{@WxEQkUDbx!IC1!loI%5TcVXjT09UOP3O!X;ZXHC0dbA_97C@BNj^|7)~OWodFw| z>@$ne&DrRxNvHZ&$A$Cfl@!rFnCJEa=Qa>A-r?gh7~acuQX;GEUpU>$-uXZol0U%7&G#?_Jx8W+F;X@7?uA&Gwcdou{rX zVzJ)cRE6;qEV!nw-9+ExpFyan6-TNo|1c-lKfUVzwma~6ybDJr=J79wb|I6?p>Jys z4&Qn!1_t_3sFW~0J%gr13W-!oZ4}Rim>ikJS~eq%m)Y4FjE>ltDXUhs2E3KF)A+YF zZlp~9`^LzvC8p#;`Pk&qQ?=-v76Exa{9-$UePuOXH=|tqyHj2?M8%-=_ND~x*xfIA zZolqHNVJhZj-LjQE!D8PPUlTB_-j~L%h}X}P=gI5O;X=-ovh)OgZnT(Hi>M`G+;Kj zaLuUA@g5v%Ya~-9sR504)4zvtYI=6o#dkAm5;w)`=&(BHNMX2!?LFy6kw6Xt3m5*E zRWQ}w6ETaqjA=6ebLg?|WjKO-p(vdUCJ9PvouZ^~nR+{OevVW+ZX<=9=A!+yBYHDQ zVdBFxh_PD+P#hKYqmLxFa-yUb!-e@cD#0{XqdOXBLM={5RXYRdPZ4YDN2+T;Be&g& zB4(feV?^s&#r(0!5w+O5d$!}2TMyycXP?DTe~(&#<2SFFkyssASu=-OscveRr!HeZ zu2XA|cp@x0fSfF>sy)Upvy`u)y|o>oL=S%cSN{;##+UK^t8 zOPE4;bzt}klY|ow)lI+I&)J%SnUVuXq_JLw^~k+|h-Vn{;aR0`!Y+cP2?519@sQDB zl`ol%a+IbqZrp{L@#yHNGAJ9DYsV37>a>*O531;|SK}~b`n(?)neDwk~ zzRCWlAp-1^85z(Za9^?Uq4T|!@oMy3%tORN5w%TZ+1uQV1g&YAN=X;o{LJ}zcsO%B zlFD@aoV*SaZ@4a~4^bez#_OrpktJcRR#j_6IWx5o)EX!W9XN92Fj|^Zf>F7_xk=|1 z=4~Mh^skFkz`uL3Dh4HySt?Z_4TKq$97UrNe&RE~a^<>Ep)FgsV6cC%p%pI`FeX0^ z9#!(h`yFMA$sFu>7<03SB2D=5_x=!Kp#Tzz7R|=b&d(u&2rgZw_CprS%PYuc7sYs{ z;ujZSj0t2cih~F5!=e5C(%v8fv2AEOrl+Q~ILRQVLuEdjHIb$&JMB&d%%KZP1f<*U zdgBeqb|X;k_fZWUT|h@75PF5ZEfu$PGiH5~JgXd)+RIlTXV@Gi5(iNdCns{(+2>w}U zuS-;X@@?i=G3?*BTiO%nE?jo%v&IFJ#Ib(QK8e~Sx*s)c-_nGkZYBx#K5N-^6iOSy zO)B`D8m>(#k!L~6X(Riw5Tc-$1ol|T+w85Qbr{N^nC^-TBC(9Wjp-*Rl%&MWI|~cx zsEPYVew`H8zF|=(vfLJ`O*f~(UhS}3! zR18{NU68`)uHDDbyKSeCj;ZkxEX+?MpPN;Z$pavh%eYZsuaXQOTwL;_+Pv2_34}#bJ^0tZ@h6y=$zXV76&G(#V>z2stEy67M`)dd{TkXL8SEQM zV|{rJufO~%x_Z0u&Uc-_P=CKo2_nU8WXZuMT%gQ+`20Po&=Y*j@4&RndAOU%3J-4US=%U-jV$qX z&YZoVMNTq@pMYTYr@i7vytw#y;Bvt-`y|ZH>YX>+6OTM{!O!XEvHduvUav|?=D4oc z>o0hhGB?5J!QsYSF_Q_xNT#6Zb+E0+;}xj_V75%C()vtFfY>Lf1F5F8Mxm$=&kQ{t zvsMJ5K?Wz|V}u%JQ63hegQY#RfX3yRwUU5Csc16SIYX{V4Hu9Um?ZIQLL!7onXvHn zXl%5lyGO|e^(BtoajemcCZUmY#+-YTU{)xCL^Od=l)@WP!JA5~YD5&`S{wJ>cLcW_ z+@p+lWi5-r?E?r07)S$B+*?}8VEEcKeEx~YWulU%`rzFU;h+8Nhcw?@EUlX!xtQrO zG_|BO*0Z$Y=i;Hvm*Y`Z*8H+{^Tk(5N7jdau~$ z+KFlf)&t0`XN5|x=X2)X>MD3&#Vc88$ckG6eDA>_B*Pq!G>1cvpmIHj$$2W(u~H~2 zSx~#77Qplp32nwd@@)i7KuI#egy|l9;9k6T`i%P5JgjUC)yR)L-py&VYAUFxVaMPA zw)Xdmm^d*tV@iV!YM7~TDmidPT0?re2E5_e5Za;@wRF>IIswMZW6z>ZzFBN&KaYV0Cvu+dDOL3DNXtp;oV1(0UJ=_Y9yvr@oA`H`j8LE_QC)nq-o8`SMu=?!WJzdMZKN zVG4Ld7NYTS}(=i08N6Gn};9XlM;RJnSbZ&+Cw$j zOIH6xA2d!^Cu%_rYU*@bi-U`ei_S)NYGVKLAT#3{`%r#^`ou+0m$TBeevi$O`U--* zEA{vsfrme<&&!0u`ML}8m(EZKA3Msh^V+K@mviXo z=*BPn^N%X|GQaqm#zoJazk$E}^v97-r103A-h!R`cdJ!EgoIEgAv_-NN=U;2w6}Gj zv$G2=Eon*jat*Q-B6hDEfm|oIgMrXVa|eTUjE_yo1EBc%F947K8Mf@~M*r&EKfcrM zpRVX{bq78k>A=zHMf~!%?I>%?sVW6Zu6r3_DbWrhn_I)ay?b%zv7=~fZ^wG5+~0`2&_BoHWO4E)mk8c2M-M(8ro>nTF|v3gyVeKd>N~yD)RZV4*2!; zB9_+k4c-uc+$@%9PUQ;ydL73fxEH6-otJKnC05>_!4L`|6~O@7+FNnpz#c3vEMk~a z*Lk9<&PrLNNYhBLmW4MUvcryhu~N$8{U;70m7tO&btD+-f=bwGfiSY`blim|4#{ftgjOaBb2Du5*z@A0 z(NL?aZ!do4mwye*D+R1%>$o7x(GA{^6P^7RJQHznQ6Zp&%U(z_KoM1SC6eb$(T3W#XhA*E-;D_Jz zwt7pd4MTf&B3mls!ui*wiq+ru4zagR^ zMb1Nv90WuVOSYm`NuyScqFgJYT4s-M4&`DNs1u4TqFAI2@P^wL$&y^48u8I2h(Ua; zM#u%QO>N_smibe~%Nue~#j;5zHH2ZQG)Z)X4uRCtrw=*_nUpGJ-}LzLht1NukjJ`` zJ~I;H7w;FxaM-3uq?0oG;wVlmN>#QBa_fXd(}+c4$Yz)E{WGV~)*Qiye)dDy+S4Vz zMlP4f@Rb`9lliN^dIJ0Q9>#}0@{?$4O>17An}&1yehn~_=8zn-X;vLXm<&ZQ^+!H0 zCOCYCOkNle%S8tA5{l&_+FRPt+17-)haW}z!QB`dJO8&jjQ;7D{&C)cPsBTM>%;$%z z_{2jx=*uO>5Nn}&lyPx!5leFmQY&N}>gwunJzJY3;QMMChnfdYplNAkNeQgUWE-(i zQwMI^#||*ZRd9cP^Rc}MqKv!~u(P(G@s_BOku6k^EpnXC#Dua1it`w0*$_+Th2R+M zo*DbV1NY#<#Vc4|S#Gq8eH%8)Nvka#xb4WTSXh|H#q*byXo~==tiTFB!QbBDm6`-j zM&0C{`TrrbC+c|D{o9aCn6$A!Xc)UH)c|tE8VaSlo=q-Kw^nN@3sG_7(Jx(`K(1oQ z5U)`q>&^gB#Z*HUJcwML67p4z0d;VKPSL|9EzWk@&=`^)-PDdq<2IUWb_D@!-?JMv zB#}=Y76Mw2&@+ZHID}v#jX<meI9K+ z?bx$t0B?NkKBrwlf;bVX5*FrWaPHOf`1;eY*t4goRCwduBg#BHdgvXg z(NSEya23zJ@H{5QN6ZL=B1=5H9lM-|yABoiK-pek!oYR`e|Gb~v)WUSnKF~k^FcR; za7LLE6fwCec64-DW?Cuf=akJ*W4c1g$~1EMf>f+1z{CpT%&RZs>eXxL?Ciw+!jiZH zd`RBPSP#GnhVZ?&_77s)wgGW2Y}&xcJKV@j7N*8VMRd|Z8Hpm5PUx^)UR$*V%Z23H z3C*cEGC6vTvlYPrMfWbQ`~cz+3g_%XIDQ1B#4aS8kD)a2r$|K3qflBii7yE};KA)x|;_gDFU;iAe(wQr>HOCcH;RD%^kIpjr#^u%Hyl`Z}&&zlLNgjroNI z2hG;7YsU`k*|XnV2XpJX4}LQ;&`D*BM4&j0uVQilB}2TWrNc7qY6TPHYiMcTf>NQ3 zrG+UB4ki@9a+x)BcJ-lm%OKXWOL*bgrxXb8JAMLt_Uu4U?-t!pejZ*^W-X&}BYtLT zT1eZ!SW%EC*^HmJxhXBnW3q_X)@TP#CD4HEkP}Sqsx|RAY9IZ11hQG&j=w+I<$s(< z=KpzD^_fHuwofkL&v)&{T(ZfaYF9~eJ(;nbJ8(2bMTI)*lN4pcO|)}hU@H#YatK>` zsU;G`_}Hk{eyv7?ENA<=Uelkc5IZ+NkJTkAuC6NXP!Nb}fr9C&C*g_LPAZ&hnsv?c z>T+ZBS7tv<6gCMNS^wX0zIdqDfk$rLCL<$4yYjkFg=xG2CNyh0WGk93V9RlCIV&4z zwtj_vIxZ0d5DN(UPY`>%{n$}lzkW@!>$*RI09u+`)DPdcX9tF_U&ZAMS49RT?Tr39 z{V-cCTAAa zKJm#CPj_DPlP?ad<-jwBg_uVQIA*Vyj(~dROuQtzB~DxkTiZKOS~qmsPi*kDiTp~q zNuX9UJv0Ei<)G@Rl^W#@huM`mEbX&4RlMQ?gaum{?+a)_q zgrqyNg4q}T6!8%GWaQLc7xC1KnyGC{nacN`$GfR2oiaAh$vR=p{Tv|e{ zw2HP=6}Rq4V0v@}*M_g4qo)IR-gy9b-+5FdQs2f|TV2M|%sifY>KUB9JmyT?Eb)@! za=mIv!snj&Z2k4uF3UfFBZ;q{ep$iUSeP~j#450*r9~gk&l~e#;hXUQ;TONp3Y&jt z70wOB#KAZSmOU}+lA(~M4T4x%&49Yx)OF$ETq?7=B}`=i5qpIP4jsX_zx_SIV@GZ~ zg0Bd|G1%XuEPP^N9j&Pr^sh%To=v0J z{SN&6AHNCL&P?O8zxvk*&wl}lEghJhKZE%^ZGKGAP{DdM$4l<)pMq|u0 z9M$1%kSEu!-Mj9dZuv?WJK3aNZd|{qXT>PQpvM@oV`u==Gjq7-o_n-F>5Rw3fRH|e zh~H=;fChqyC8B6bH*0#Lxw#$bmKKdfUb!-cM7mqTG~|ffdfRp^PLE?~$1Y?uS+uqH z;L@en@X`w}V&A^~xcmNN*uG;Yw)XWo3F0{!8m+CaN+puxK%9i=?(W9&>Y9QY_05TH z@OiN{LGl;_6+H-ue(=u>NOVW5{>h)9{9nI>eOnVq<^JyOj{oN!!~eKH@n@R*vG2wN ze&^16QIpD|**volX=!bChpDv+668&>tw;H2p>wAD!oPE!uV&UXi%+pNj!UyWw{!b$ zCE6o5Z({GhT|ytCiHKTU#XY2!{^rMIoQXh4U9NIy$NN=i94l!+Nr~1fI;;kI4YX zmn}&!qNTM2+yp18_~?%wK|HXIcr=W7y4l8;h2D}sVx!wEFe{TwHjL5TczZ?@6f&Yv5)+M)Gah4uuZ`1q9EP#4#}RNCOnSiB2FnJMjmTgufj}rrbW1ID z4%J;%T{)ec&pd0rdsp}U>-po0RL>(stE*0(v-keK?|s+10+u&QxG-Okcfwk}Y|U?l zu9bN-bBpjd3mD9_uyyHPbl}jTi-fdjq=lHjjzp+}v5|J1 zT^m9))q#Azgm^4&Qm1AMXV0Ei$O>bdIa5<=o3k-+@vxxbXGo_rh(@i8?Hd@x#OMUZ zM+fo42Oq?bA9(_W;<~D7ezrt3j7pWH$p(fqL8Rghg_;caClLz!P{>!{O>PI}#}_Xx zW5?te@`Vb{&8#9AisJ0Cb7<5;2*z*0$j)Cwy1b75+6jyWA46tq51xGNL40Fj8l}2* z@wG|`zxIxoVR2y@!Eg*iy10HD zg5fBhedZ{lu`ZDqiMkYu%XsOXH{ky7-j94?LyLTVaS8qXgLv(0e-=Hx-FkkOmY0+@ z!QzF_2T3#}pR&MVfx!R1va%*riPwc4V0U+q=Eg(~NRs4YBAQ|$NGU|-=h67pUqxzS z5EH8x{&SypFTT6~&=vS}VgNhN&)_evzXc4T5CORf`I(s8D?^s8izW$<%>j#F9u^9$ z3)4u)jNqu)A?B=2pX9|xL#9hS=yTaJ%4HVLWm8enF;;fh7W@_pSVA8+RS^scXOp`{ zn{@>iweTzN{sq+PEqSI;Y4OaFqbL>2vWVvwN!C2z7zNC=(;lc{xIKCAnZs_hX7>5Tm2R80ha&;X>8b>9eOXJF|dF zndEI2F=kTc%7&%J(mrjPc+0df6DVG1e#zg)F`^O&tKLM=Q^s$<`C9l|HAG`Ucta61 ziHLZqeu|@3D~sd7_gE}b?Z9FIn7*`v9JvZDFP=WRfVqv5h@X64+_#A;DwD@?##B7B zLcSdD8A{I35zz4-@0`x7U*c|Az#l58#dH7lJKZ;;(5k#e_JOJb`K67 zx(%;?$8XBPkp)+&+|WOBYh|3jw2F&MWvpb2s8wjLl!L!fK%=ybNTY!9J`W}aQuxAW zzoO8ubXyd!d+p26)z0(L#`+w8lyW)Doj-?v{Os4Tk*~q8Ce=JYP98r7&p&?Tqpfo@ zOE`A&I2PtFA{@0?V>d?9&;UD}+-PMtL5vTaNgn-rF!?=hSPi9(BrWnGx59v^M2!WS z7NFl(*CDuNFp1xK$2c;{A}YmognfBI=266G? z1spqeRPYn4@fB8XJmh7VWECABYRYDU{s;n*pbDRSc0)5Ik!k{A#ilX}I-A=-joB2Q zI{wEyc4MHuz?dVM2r=0V^#Gna*NORJ5=T!=VPvQu$#@v2&M#skTSTr<$HGb(@TTEu zjUe94;pT1a_?{l_si zwGI+~&Ci{SG=zr7hn~)U#3B*wziKB=96ydwIO3=-0tiM@_=7)u58nOG-^I+OlL&>q zh{uv>lyms=-}(i7^mE@s)9=@T%mv4>&Xov|Mf)0Y#U+?h4MD(4_#fIBI6X_@Ot>dLF_I}|A!8s7k}tK{}mvTu=U&w z-gn*go8&tSO)@zf4|x*$Bq4MV1b!+Oz&zkw-vD-FT4-h)a8&Ujx}BGkKAFM z=x1_;mY2Ap8`GX6G98wVT#{7>i;^mf5Nh;m6|D*C_<7)wqeEUqTYE+Y3rWBv1(To_ z$gje~qJ&0Djz5DNR>wVy)(h*Un%q{o|Ayl!r2B_OJWIsl2u8f<>*Sa|UuQzG#iAUh^1vLVpXH7I7w=gZnoi{z8G?XX=Q4|&{=Vq2sE;R9-C#T>GMl?>) z39l2@5K*G4Zptfvb`$Xw$AkC6_NjWY0-r+Acu!3l&i`+Rt`n)@7_||hCMUrc3!}4t z3yQH_XnBL$7t!<~m1)Dq!VEU%kE4C!5Io_O6$;!F1LP)5$V-8lH(j+;SbzR22>85G zCCtvAL(3T#6H(y3q$-PNmF=lsJrit-cn#U;xVHUL+{oVEoIM%9$3UsB?p}mqQM7mU z;?`HZ1-tfKi&C|WO1XhTrG{dqiSu(=oZ{GFtqPL6tK}?O)eZP6S+r_-_*;4G8;$^t z4Lttv(;7Q;bf$36>t2d@lx9)-e{wMEmeebEm zvU)6)^J1{`gSmd@?snp;1!zai2aFrL#tM}(0*(yOs#1}T9nSzWwvaTy(bxv*=+~OZ zU;o|#q@rc~-g_U!-~9e|Vz zLJ7b2mTlNFV47&nZyGJku7>cP$2}MsAI0hOGqM65>hH$ zLVHIiMh1p4b>bO?ax_EKomP>I0#{E4@v7T9uy<=a9(`&Z@Bic@*tdNMZ+pW51~f+MI>zF^3K48$TT9=R{LQf#7`JPg=b%EH|tiLt`3Yv~`tqQ#u{=t5|I z4CCz~1R35%WWbSwUxuB@MQ9>drMa4!Hr2s|#Hb1ozD}`H7fj60!NQ%tQ&|p_c6xo- ze_#)mR@N~+ebEpECuPzilMUAA{?7eCMmmnXQAev|B~3_NMGt)s9QQ+B^I#}|yRYp- zSG0y`I0RqN1CNi{4Mb*4Dla7x&5T5PxACqNX$`7Kfb+9OeCvq|@OpTlS}p|%**+p7 zGTk#JhP`i7ZLt~U$Wd;$;&Y2EfyR0sKAKQDW>1$#s7@}8V>8VE&U8lJr_AsusvU>m zLlE^=O$bV|XB=zu7cqPIs~FjP8|sOE_(J4NnXEDt>p*I7k}h$YAQ? zd8z!aIdnY^Tzwl3-2AgDoH$0NVN|u!z+ASBGgGTLF_Ux9gaT^ib$FWLzoO}K#W~XP-(bb0T-WXo{Gj}1%@tS-ntg$8vHaBw#pZeri5R6d{>cMfU8y^0~ zH(TwaefY_dleqWZ&miDqoNZAg4<00ho~do;2j^jG6`m;(T&*svY5srLNQt2md>$ol zWac)jSGxQ)D(DO>;p6{nH$2T{F@it-g;m^m-3TU!*TD(Y=e}LQr~bWyxl60qv11#$ zdiv!8$;G7KLlR2EE<7V(`MQyCT;@Jvjym$Aa+P`6Q49|bAs&q*S1Mv@WeMj`pHk8z zM<)DykyzB^n~eryeh*%GLnm(98?Z!14YKM=^V>+g4ZroCzrbC09Mp)QP^x3=mOiX! z%Q!i;fJ~|b&mB9BN~x}}DSP-E=<4plrMX#+Q+j*auxBicSKpLD&{xO%KJg=rPmE*t zco5sh`q0+98=lxCj-5J#^A|3lS}WnZ|NaarEia1sB8GyVF>PN%Mn@I!TBNwJES{ywmh_G zj>ICHV+3We5OHAmS()ymW(LP+ng_Z_@N{YQda;qs3k6l)f|^|?i$?3l9j^v78sqQb zKFPyM4zO%oOb3aLb><0}bTb`KV7Sc#uNdYvb>O1eIWu(?^DGj|4U}s@nSKpCa5c7N ziev-z3V)7jCnH0O@a!mo_#1nAIx##rfQKJ_Tx*kiu>5YWFv)XA2>kxbMtCH(nIT+| zZhTI0W=aF55(W|S`|!&zn?S%*f{&q1JRhVw38~;<1H-a|h>3#6NU(HJN|MvL=bo4< z;%iTwlTADe4|nfzN$u`;=#^0!E|XOJAb9nDZu@zyNnIGV@|Y(qHFiF`JT zczp>t^;sz+_$OTvJ3Fnh0wdvf@7^tL0{1ndL*&Tu`6YVFy^Sa@ z_g2cl`OJ|=Gd#8hH{NtTCMLJx_*5CMy!&o(!irU@dFtXLEU%XE{KYJ$rkC_*G)idH zvhdalXcX7rM+NPn0uJuz#W%kEB_uN`WKs$2-P4b&ue(ZV$WjZn8fa82SX`LH(IZFk zZ{K?wb*~4f$w|29HE(K-OpN2^>-WPG@Z&=t`dh$bT_zts76kG+fKRhP*ARmtNc?aN z3t~m!O81m7C!-%$jwavBqu(#vqtDgw zfq(U3etA`kdFS?Bn{JCP+(&YU>vfQ6Bj+Hh`8_L7L6HrcrztHAcifKeeCwNX7W4(07;5*Ur+*8!jt$}! zw{1l#7Q*4@PN0yR#Z6bY;oR8`-21>f0--KE{O}`aRQZtlF)}uaP|$<>gLbjyM zjny(!HYqP-mqlqL#|kTJt5{iCl7fPTNk?ZpsJuyMD9KD==K32D>1xOJ?29~v|MaK) z|K%I}VyGJaq&VTfme6?(48% z;P030yWYSJyZW^!F}~V`^xZKZQIdSQhC-Dbhq}yeSV+*Yh?_b0IUcI+?{hOF_#c!j zsqnJ~_V3<_sf*J>6s(K4b?(|un?aoUM;L@}$+ad&_o6MsxwYfy=nn`9?Ck15#9PKY zUplS;DjtY|P*~w=d~YHvI?1wzv>j7wwxwDAtAJUw=PB!7|b#SEH32f-jU5f-NFrD1q+b?FztS;8y4A1ISH1rY3e~ z_9DuK9O^BHm*?@LXSiPx(Q_B3#ltqG=$H8{&Vor1j9*BV|7Vo0xNBI)L?-p7H3JVu^YC*YML8-y-ELq z24b9jwCc$CSMk38K90C=MU2`{ec=Rdy7?Nk#R~YrqqB%65*XfcC*JrQ|KwJbSoEYQr#HMw$=2mr+TQWV71g47@X0UDh z7SruEThdnZ`DM}LZ4Ta|`f=NAdUn-omkyr*Z4`2QWF>~hIe`lo&f(Up261LOhfB*$zoP7}@`*z@eyz9RpyK)jA_{>9~Xq8 zQxIKnb|bNzwZNJpZqe-0TlDftwCUNNcYjsVi7GXuqFrIikC6x;A0}BP-qlKjv zEf{(skU-g)Fe6Aqaxb3h065)k;Tors#$?$)9{{H{s$M5rX zpl@*n@7;gU0*st)*@)7P-%8bdG+gBa*DDWbLeeC_@xWQnZfGrvW5tY*SWFwD$*xH} zB-Cp1Yd-V*lAlVQMS{6Aa+a@RM8%2ye{vSs$Z)?g%UcFI8P|dD&(IGR9Hz9;m{u=R z!~Ws+%Val4#;4+hd@B05)ICBfi|RUQnB+yN+SHiN^-1CHNhA|i*bv!u5EM25T+{3p zJK8fie)@vO9DKi0TDaY{$EzZW>s{U@Va7Bw#nCL7FL(1+D9Gfl<-zqkdhxP732_@@ z@r1>LHyMz}{h4W%=D*_c2UQR#ufi!rnspWlEqvm>!>AJKmlDqMVR)@w#E6HYcyKcL zY3Uk^&&F2I;l@!y9f@*;>%)l?ClPFU;G+o;izOA6M$A*rhBI>D?{LQwll%AKQgaI$ z{)mdbNXGz%cin);zVN4rHWm?xcOuYtwUiF@fFL5{@rID>96&hLfoiRVW^o0T!yiX` zj0Gn!b(UE~qK2wSY;SKfNjqh+9C6i2IyAFFo{w~T^V?C?nj;2vx{aTSkgO(5B|?x z2z!^Yvfjed1`RI4$mJGr%?=M5o)o_Pa6c9cgZT1&^pqw%$ArU%!ANqhYH2op%dNNI z*s&A3m`jVxszga3Y3pd)97#wf)U-TwcV5Xr7%o^6o#?T^&BCg8Bk<@Sb=*aaM6!6- zJsA`WIV2Nlc*9}5{SS{K5=mgBH-1)1O~UjMQYJaOb4e()q!4iN-`Ny(i!p5V{WopF4q zR~ZOR_!T|6y0naRCgXTe7<|gbaMk{+(H`~TWAFV{{N^A271kSVs5dI=u(*+mz03to z<~K(OWE0CI%d$CaHpn7?i<$4!DtB&hf>Rx9Zn;RR+o~a7$f2ui5N~?(+cD7Br-!ZC zs;c{80l{LD#eijG5YD7I5*gV6Q&Y$WmSZV)M<%rjhs>*jnel|{HvZ|KQ2N-%u%$PK zWYwJHUi|v$z5@3}dN44vfWN%v5PSh9&>9NzBul-6W_oH@kQ!JhKwhpBA2rHpsb$q)sRKJY(^ft zBL^i*I*0~8U#U^S(7sn;!{2R+k5~%n(d#k&)YlMPJ**6h_Q_k&3bmohLV`$wKL}qa zj*i}~$_3&$D7oKDEZzt9vacYW}1`63MKKn2K ziZ6Zjet2%b`IZ(RtXL?FiLG0aNT%?_{}EIrvrkVI#MJh52P{+cvJ5`Xf&tLpTz{;_5Qm(%q_Nd5{Y75^0Gs)P7}*6YgY%IXKX( z7}ZdO`3^C}qh8F;uAoG7p#l@%*wxojY1TyABD~KBEYr~@iPOUTyj%$_=F^XTd-r4S zNH1TqJP0<$s|y7 zBtNp=uGX-1$3FbopZy`oMd5w<+!wxpdYv0(Mcvlag$szw8zCj+#tjf7M};bl!J$F) z_4T8>t4q%kXP5k)rAi6)jXVNB|MN%;bYU|0A`juGyEM4`>Ham?jiI?keBj2LMbP8n z$U=bp0+C;<7HPs}87BXaG55f0MN+iodz~n;fG*v>^9als#{GDJqTFA>iwpzk?+J_>Y z7M%{8Yf;^0tt^+tjWVa}Bstcxk}IiMQlghh>R@K!BYzCOPrhuuiI9^;Bo7(K%t{3in^%oReAsj7dYmqFqUDdH-twSx`|YR~ zvzUMA!%~g3j~zli*oI~}$sA)5G+6+}(>-YG8r8E?$Y)V|;-hGf*T{0m^o4T@QIb=x z6B*9;z{E>SwDgO_7*E7?ev#}=UVs~o&FgK?R|Dx}60g4dRkkmagzxiVBVR?Rdkc1M z-HLM4gViiKa4l@)>bN+c#q$?7aB;beGSPiiDt3f>ed<8GPc?*8~eLsdj(~lbt>_Rf? z!9xnnN|Jio4CNuPa)cT@ndF99ePWWWEGno0T++q>1rK+`exNhtHmehZV4_pld>T z)OBd2>MB#{XTfgXHVfCtg^QOPE{#Lvf+&|t+9X?%!ERst28+cLWcG{i`Ze5f$Mw>k zudXiP@h2X~g$s-F%4fB_zOkXvOaI`Y!+)@aKo43?6bSsBUk-MncX1sbyyn`?&>W7<$T?u)$wQgQfx_sxrPu2qN6E~# zI8q2nOaIiJLW2oqaAatsdUJtwXAi; zjtbumiF3)0n*_uwAa)lu;CoFa;@C1Vf|;31n4RYuV&Tt&mMEeT!nI#IMUkwT*m1jQ zkIs8z5t8)R@k_7ThJd$$L?$jWAGuQUAdr;LkU)OsT#?O-B{1@k*9f}d!QbEaB+4F| zq?u|!`8FhkGHRRNEza0R*WKB_x&N4Bt*Ia6qaZSA3+w9}`a5$vbbf}fSZ^WVC{whr zJ1P?Mh+z1R7o@=t@3{>NjZWRZ%;e38Wd?BUJ0C%~ate{29cV@R28Ogx!LYW!?|6&49C3us3M%k$JN zK=~PayE}06?YF3r64yoJ;U+FFHu35=y%O0CV53OGFd9}hv9wXandvN!o?pXa$$S+w zQr2v(gl2IK!OAp-5~~d>&mreTYTF7~j&3m*0K}kw_4}fO${+U$Z@>OO z;rWLTf3THEw_|qp5{^7~9M2y+ss&LhRgp@k#9HOyzq-0C*g6ylYo;vd$Kye|Esptx zB?mqZqAk^qSS*Beq=LWuqfvNDGdOl;0f&!l;OeXTFg_N9uf@3J2>h{YQHtGk3fINa|R4n;Kk`94M6({DV zXp4@;0h1H?&>uVYJVK#};+FYf4Gi=n5(^vL?R3zlqXt%&=5f=GDt`G*eR%r09RA`T zXJs+kI*kTH001BWNklzd+ zawD{udX6b{5UBfgiUf{SIXcn$vezQy%P$rVLL;0*+(xOU8j{1L<1=8*oFRcm(laE4 zdkMJ-0|P`*SG3P7_JKPogO(h5qHNin=E^NxHfQBd+U4&41YUd70K6O_r=oy2sCm6R ze&Oq~NT@YhDA7vYvD??d4xn81JVFJEe5Zn=abXV-A*QckXxn<>!zU5y%i)hr^F8SL)Np^-m>2mbATbai#>%)a5K z9XPOeml}PpBU+Q+^@_K{^D969i>*rwD_G91V`XU`75YH8AUjfayb7RTXDO>j;|I8; z7A2xJnp(JotT;y}bWLcbzblSgcQ)|uH*Li;Cr_iNH-*l04Y7dwceGk$Z1Mu~p`y%= zj#xSP;KNT&`tjdBa#Bu)*B!b6Cr%v4#`@Z3T=ivcL`xe6#|?DplVL??hX^?=2)JM+ z>8aO+9;~fxD9@bQdsex0EhP2dbpN!)B+bu*<+*uuC4t}mxe5Hu7w6##B-B+ink%0z zU}a?yzwp*qV?CQgE}O-~=n&=?*YM2Ai%bQvqQGJL+B}bBL9+%uee5_oy1J3hq?JLj zZ{KdGn=rUvscx*!>kTZgF6!Y}Tv--rw6m=Z7pKmP5JYn#tJ*oQttbR09wT8eyxHyW zJ=;Px#K9_ezcvOI2>gfFOx3*HzZmyw+yg?W3k!3Gu8^R}DxX~zrD9diZmrp1h~!(| z_C^d1^$1OhC*vw$;)#rkI2u+FZ6H5~1~W@5YshBHs8<+}g6#uq=Pdj&op>%;KO0zR<+AVBqiQwZ=G<(lUg4_0aL`CL1M zMzh5YU~!27OsWlXp%f(fIs2(AfpmBe{C%b_kXgG>4!6s8 zc~&lo+|(2_z_a35!#?~^7%B;~0XsFN(sR7vOh+0+;(r}Oy66Bo=wL2i|fjkbHH zr~u%Y;WDp6-YuJV!T#QohS}U%amDMxbBEX1y*7q6G~uJ?f1pd3}##2dht$(_iz!l?VAi1`|*KlKr` zM{0Uc-0Q^)a8w;CTdpvyV^|;W6USW4(O}@9lO3u8ClZgNr@ISXJ>A$cIc`1}d@UAL zz83t^461<+jE@YV((s~G1M*0Ob+nknGxdyC!$fo2)<3U6? zo$#E3os=EGL&ab?&eu7=DHqE!B=UNBVf^~pWYDX$z<0iO94|ctg#0ULwz%La2cn#g z4=NY1`IWc$Z?urB2JlCpm_vHxI-ELr8oBii71*2Py3P5y6$#uJNJ?T{YgcEN5&Af1 za~2QZFJXJKV0*f|Woj`qGl%Wlw`=|-n97m+h{?N=Lov63@v$Mzed-lDtJz$ix_!R? zyYIRgnN$>K&R)Ry=&=6&hmSogw1IOavinV|OBl}d)2wEnKYCQw#k4%0oteSd*r=pj zTx29*xwAJu5A;`{^BJLkT3_!R?ZJghD+tFsBngy>6t&4L?4;zd%9Nx*ZK933LaY=; z%BX3XOPLvxiaDQOod`W6%=>~fR8u$5!IIFcNLakbs&=i?)x#~n1>+rDwP!1KPEKf} zv8vhbm6GK6x`J%I@Nq61wg9PcER1wAB`7VOYSX`Cu_Pi6*W`&^`=!a=@}jHa3$k+f z=XgJMPR-(d*B;VLp3jpAUnIr3jf*6EM5Byb!^54#FFtFO1vAry&!Yt{89GMBI17X* z)koaV0;ZH8M}fA=Je151`0|M&ZUQ@XdA-z8uQs$M)V(@~k$afgXu`&Kn(1GW+Q{GQ zj{W#|+Vq{%oNJEn+eJ3j2stAUem2_UyXbEx7&BW*DX$LA2G5Xn>()SP{5DT zkwK&~8C;sZgp1R2LKMsm*CB?scyO}|w%i7F<%Ib?4gAhM2jFiN%r%nNkKaT2y94!` zqJSMOxk!d==pQvIP2Bsf2WAlPDA6~hbzsdT*<4;mvFE3 zCa;Rt)s75awr{nj)DH$k7*}9(EadZHbno?;YjmRFi@}p@`KLaQc*mg7 z>_9k*ravLi86prI8F+m$^p0#pBb*lBqjLH|^c5eKX`YK%=<_%jt)2_s6BR{9nm=>) zjPi66@fdo0`^^6V9>fwU?A^BqW8=e{d<{ufh3c?I@nI?F!>xDT3<@S{LUw_*d=m?+ zRXlrc1J6#aW3@;#E-Kfo*lISa@U?&_a_9-IVOx3$U;q3kWull)#u1PC@%q=lRAzT1 zW8V4FH^Gxkw$rmq9k`|Qh1C)AK_N+q8$a3Ue1nv&@!{cr*F$BGkVuMtp9jI_B1XGb z@Vy@|U~b(YZNez&xF2u2BY=0lVHAFj6-s5BQOUxe|5C>3IUd+q zMI^h`q)CPB;N=&K1U@9>Ep&F9Ga={vYa1K-K6VR2JemzW_UNPN>l+YhWO->tUfQg7 z1z9=dAtDQO_S#rp7Ykp%j}NS)$>yAsJc;WL?!wM312}(SM#dPKR1y#T_-Rbfts$LC z$|pckr2K5ooQ=iQkt0WR7*f8(t~nl0YL;pwM+-XPLq%l)0gl<3DJ?=C?k~CVARhh6 z^XTm#6D;bQ!LYMuW$sp{Zp1YU3tm@t3NB*eMrpHmeiyd}*+#Qq^QL7s1N@xuoT(ZNT&!svtr^qEymVeI zfpdM18_brPYt;_^T%LC9E+QcYH;Pp+{`Y5o3wRJ48Z$O>kzFeoh^_`U zGY+`Fb1#w|ziTb+j9}cR(3L{CoD2HI_!}(*#CvKvoG@!-#6^omFtX_w_?D=s|s4Fnn`=%n%Z;EyE5O=xcOn9^0b~ka&AR{BWSS1RP^0rAcBnmFU9#Xbma)w& zc~Cw3?6ZQ&ND5>p(bwAtf6&GeZX`4hRvwZ|bBii0$Y7?21AiZXj>JeV*tS$0ue|d* z%wC$;&yNiB;`y_e@a*v^6bpF_42@WYPAg+c49%|k@ZrPiR7j#^aY2J7COR4s$9%li z)yrA3hD%H+qcv$TC{KprvF(Df=tiinr(DtZ@qN1YhSyOGi~(HEctEzM#UcWH;2iT5 zbFp(mRa{zP3v&C~EDjvFk9Wyto%Y2|hXhCdd^{4z&%EZP80hcS=!fGcZa%bFCepx6 zc_JTl7h_6ZTSvR(RE*>;mu#G+a+BA-Rz}w^|28@kehg91^y1eG@(O%3J%mGNF5=I3 z>_XmS&oeF7`OJ%~=Nt@r79Dvm_bEPeL^mnV0Tn9ak zmbhNXO>jwKu4OTQhfq2vu9}XAe10v6%@0Bi(FQFXs@7x&Hay^*ua%z4p2cmonm?GaevW+d&`r+LVFHSAYg;4w|V$k>q1F zC<*bnNUWn|n|mnj=1u8f^5uHfWTNfi60RR3`@Mx|BBf4RJQ2qZTIvqvM3C{%{hi39 zjU;*S&n%U2?{|(Fbgu)}*>^XU80L+j@qv?0>t;^qemF&k5K*4Lj>oqrGzBwSmxi^wQdVo>VLClss^op}-g+><-oVlGIXr!4 z4YTW2sW)h)-_p#CUK&k!niX{T3)tRW!otz-;h85NMj{-0Px_7~I z+a0&)m=4LXflPOso7qh_vn08PIr$6x0CX$l0!yaSf{}Q``ZHzhAKXAB96$vD4375W z-uve8&HJB#m(j~&sCv;KTgAKY9z<^`ZXo9Br|o6BvI?07(>(`|a#DYX+i;Vdj#x&HW(hmCC4)}}m!R6K!rlHW(u z66XMHHKcD{nqSaj9vT`Dr+~A!g~dgbi$(DWC|}yMV@L(X{Nf76hX-)>;w3!v#4-8I zx3zaT(WmT~?S1fiKL7kt1+w&Xb?X73N?~GRLI=3Z8(>9BbccVpvb3OToe=%D$!!Lo zQUhMCNO{1`i=T$w3%j>YqOF};bV!;+q=Up#7DT+}yeIn1)ry%V z<>-0fm2)J`UpOw(b@;h=pti7zz3nf^^YO(G4d8=qqqyAe>vRXl?V5 zS1uxICFJDeRw=7y^up`Wvg|8h-AgO`niITu?0>XHZD{nI52%c#uRi&PNH@zKVE?%E=|pa0zsQP;1)+-$jj z@r%Y{>P!`1ZKGi!yN+jq2*)(!agr3d_pl(6Tv>`VD^#xR^!YP@sq^yO8M~ z2EuJp-&Bu$8Xfi1LIqSPIOnJ^otFJhLqUi_ncs)TPtM-T^P{`33&X?1pma8oj44Ax zMHffK&UlB<2>C4+=Nq{Fu0yET!}8UrHh^rQg{h?~o<6mT<1;y|mHFE_hBo}4iaJ_K zw`v7+N6OgURl>vH{70-UUXaDPKMWk$K7{}M!A}rLxVA;eE*XoXUM1@{Y`WiuRc~&X z25*L2Af!@hrTOt9@dL6lC2=kqi=bL68ax(Y>LMAiWqjw`-$$ifRAts`)zB4b;Df(2 zi5*)SAl=}xr)v20H>U9TnSyQ>Yuy98_v6geS;31e1T;TXh3h_8jssxb;6z?@F4)eF zF5M`q7kEGs!eLI5LF*G!*fToTzpm_Xm=Hn z)!-|VZ)&*bp4a2%LsttS;zqW##8l3TDqp5Zj*g8A8fGpCefk~_4#cbaie5cL=v2l z0v&CR^KX~vXnTga5Sj+vo^$u_4bowvAJRkyfd7Ugmp6(VQF zwAKf|Q?8|yHQHv(wMn>K;deq4tqCK-=^lnW^oUGwFXds+z1ZbQxdnuHV9sabnzOXQ z%LYMW|2zH(#se_HvQiPXcbg(Wdx7Kf=QayGT!~Z~f@~ya9jLTsFH;Vk$9vv(Ej;BS ze8DEtZJjFgwI};IYN&~;*7SO15=9P@`^9U~Xa(?re|ZR=a8g_*5}|FR;36Vcl<`X$ zEg@4~ZAL(o`Oi=)Cr+BzQ(O<{dZ^fNiaIMgT$P7o4&}<>?ZmdxE>Q*g4OQzxPbi@u zKX5HBHhZOH;J$@$8hzu};L^FL5Dt2A@!3bw(V0NAV=v%iilXC%5R9R3Xe%0#G`xWr zLX}n2p8gn8;fi=%L{+$Lijc`{;T91jV{_X0+^&{J2|gcE=@>e?x-d96h>$-Z{+8Dl zKsaQa91d*7`SP{I;|nE%IC?6F*Zk}qa)RV=o@QJN8^HOw3Z6W(bm>sq>D3Wr2AxdIyy2YE`y+B4-IoH~658(E7Jb}MlAf@+LVrwNJ~|M0;} z#uI37>p*)KozPenTWqw_99u0s^2j54E!zK%Pi&F3u}dc6&vU-U3Y|IHER?!4QQWvI zqb6}u1gZsYqL*$Acj7*FEG*_`XHdvx(c9gPQmu+RU-EL~@>x~S`9cxQuOQo*hzAd1 z6$wr-6ERZ~5v?NUV&W)<4sSfv=^943Du_aH9TzX~GhPmVVaFt66emYsb6mgunFXQy za0wQ4!kz>XwLG}(=3DWWH{FeViHeUrR##W`{ggj4qk+Z1+UmN-5d1rSW!ln08CW^9 zKp?unB89KL^N;@k(`T2^7Xx~%iF)zt1#|^IKC}}Do;iUhCns@aXjn68jXkgEGOyeR ztf6r_OXoVVcy&8V>(ITH+u)EN-RIdQCc5J^oBP`sL)v}9(~9%8(Py<(cA}yAU{ZO& zP&`vyxZ_P8v^+d{(D9JAlt!~|Rzu?;18jgYnY0QIa=3I*`<&R|7Gy0gf}rG;{@!sp#u~C|NQsg4jh|%R z4Mw1}qugM6`oBoQ;uu)*8WL4t*cRUtG&yz7wxI;Gt6d`TPbC+$#fcn!^3FHBrUm^D6gM| zlXhbJJVX;X#t4Kp25Il@$7+e;UW}ur<0ZqvTA1Gej$bI@nR9EnxLQNK#dOZP;=N_U zr@*khk|2j7IrIlF;=WJ*B?brjkj#Yf-LKsTPk(=ZOO~0<2KMaP1D~TsH7OpuYRdOq zSXiz*7M3i} zorWH*7Jl;7VPv!G2!_Jgf8c-uqFABwGbtg?A;U~xn9@N^LgvUo#z;WTqGC+Lz9KxW zn$!(rTW>_6Qpfyq4!gGx4Ss)RG^SiCf=c~f_9KW@MMPWb#BhtxH1rGG`Sn78Z$ZdO%}92^p<$%wTeII^I( zf(zeqvE)naqI?KN(n3b^>oYiU@@a8OXs_*dHg@l=V3ESv87{iq6qjJbE{hu>uie<_ zIDX}q-hpg>O%9a2)*LO+;j+7@N7sOA4i*U9Q0Y|H#j}9MNl;3y!Q?9P-R{U? z#aq#AvuhQ~L8iXi0mMBmNVBqPRfcgy16J17tmsyZG(7}t?N(}(MO*hzd9c>MC z%K(o+aKBU&O&!2llBHcao(q*bfk|T9yZkOkez~%`ivGSnIkFo0(Tbd$L%KE-GYbW> zgT~wpn+;2k6!&OzrtJ^~*{k}jxidV03JeEgz9N>I&6AoUYM32w6l=_l7^f6i6=Zen z9Zcdi*Y>Ha^~IPb31#KD*IiDOx>n45aZ(?}%`o1?)2Ehj|KUqE6BoR1;}ZAamt^n? z^@?kbWLC9B1A@ z!wX-fj-j0gvFPnX)fdy=SAiG(JMX}SV^1PbS;oexZzI;f2a&#gD0^cNDC} zn|;2G|E;Jcq8>o0>cI~m{t2dLmvHB6eg=2lb^zpO^5N&t(Z*nD9eCtq8BZQx!)%V0 z)wYkgenRx5Xx0nx)C!nLW==KYvGiI|c_C%}fZ5 zi-ZRSyZfqGuFMQ)N|X^XxX8)~hC>!S;^>H3sq()o54=VDU(S$7N@14{WOHRa_}~vU z8{|RB8$U5Vfvc`QsEXIe)U!wk8*A%WUS3i+{Pa_Y#hmB7kcWudHSoc)YygLBMckn{UP701w!jWHL0js1z&mf#9ftq)lel8_a2e zG-7c31BjB8lt_#8!cLtJS)o`(HplTt%xsg(6|ApM;lzn2H%}keGu^Ge4HWb!D%yo< z)v;;wUYa-txvbA`r4g8B4^`)76W?!2x~G;=%%!7UwZ_ehQu4Js2Gw)%}k| zLf~deJ$s>8(tMTP`jn(4Paeh6Z~VUQ$F9r^=YV|ilLB8o^b&ME@CcSzB;0hPIy-Lg zR2LEI=9+gyfi~rPj@QYR>H?Q3ZwZICd)ndXAP+q7m=nTe!B|{88dnmoO_?ejHJkw| zUH||f07*naR1QF{P&9)iX28@~Oqg_!|A-q@W&AV4qN-+$~gz9qAlO3vLj~x4p>T8~4c; zKKF0WVtSQ`quEKjGDI6+mo(xg^346f3KRQGM*g(!nO}wq7}r2#b&@O{&J+s=UU%JL zAw`U(w!_)w)A29)`uhC*-j*G@O3&oqF-IYsLf@7{SgNKdXh6&3Lws-#0?9!vo_-R| zQ(r_rzlOHmKZ{m4gNBCzP((Jo2*o;(Ztq7h(SaHRuFm`z1H~VRU&gbLsEZC;=U(&Q zZevD-muD@XLynh6Cq~7Y(|u!ph|iCuwE~_!aS`X|Tj(6#hESqQNt<-z&6R* zN9B$?GrtJtm9h8?1W2s)py~;u>hmI3)be|}0;y6euhxiEY_p%XSAv<{dM6)mLsP)8$i5pdFpq!C`c9-KOLLS4!B?K>Q) zp`jr<&^?xzmfy(g@ZzC9J~oCsZokD0TNu*h_adLqir-KvKNrXM|vIuc0P`Opo~t;YG#F_DcCuIYG6N`iDMj%2D0wQ32EK6(V5y%Uyz*Jz2#@y^BrFNb@a}mvERRKI4L&T#Ip(5mtFpq=xjpzf(uhB@@%vL`1L2P{YN63VL z;rNTk=L_Wu{7v^H_MDl*Y$%LR_x0((q;zpyaSxGB-H~N#ZcnF1DJ(c|H+~bxfFh(h z2Lky@A{vrV?7-tBBT`z;!koX$EpAAVq|DPrXx;fd4GP_pA4hn4R(d3x& zfng`@jAL9vCx6EF3_D0Tx^TS44{j$;o}V7ngo$8g*1Cm zte8<05dc#)(BP+mk9_$_G+IH_8khM7Y!W3sWsnn$Gh&CfaXT&})K;Lm#g4m2iD(%N zI>uM-ILJs;x?axc!U{;&rPr<%-yaJI?tcQg9WMu|I+_iPj_*eyJc^o^IWrBkJW(XK z97206jN@N<4}zf<(qq@5fNoTo66qzWkjeoM(mmsd#M|HtGfOCpjfXyj;rN<dCIpkYOY~6bRiMCE4;71}FLp0{c%t{3(FU(_Y zrGOI62m!3k%_87wpjpkUnCc2w5epH~wSAls*{ymD1@ddmRUc9MK!iInzm`Y2TtL21 zf~T;6tHvYv_9y=UXHOonB0+Jf)vDO?d-m)?XM2Zo2Nd$d6f(}g3V9CPoLqH_098du z@*775JYXFn3J-EF97Y(^e56_-OlMN0Qi)Kx!O<)N2#axn@y}^Sk2XZ1(_$q=NJyH- zL^IPf@-3jBKgU4)kQS`cP_=!f(-vhJGU$kN>Wtk45i{H$IHv%8Cy z4_1lV{(4mgPV2dK_z{$q^DQ^+0Yw5-3i!hjM0pS^w8<)8R>Mc0IVs!b?K`&N@kbw5 zNQ;HBSOLNgpHC&>vG0HX2fC5WTOcIQKTw)QG=)x(J9g~SsDlLn$%=&ZSr8Damlbod zsBVA?2$?E5o1R-N@%`}7ZR<#*v$GSacv9XF*}Qpu8&v2;k@u*yf%E5|L#a%HsMmZB zoGO=#lMBm_ z5lPTK>X;|-_1OiJ*h{=PEcJ%XYhAgdtCVub+{QyNGcFA8);_PX;`(R0=H;M|~md#MLa280pagBs!XEI1M?>JnsAkzV*bc z_9<6&!psadGURVq17*M43LfJnXdiQuEeV;M8Jz3kU~YxH)+Q&V(u!jaHgLw@;2z7O z%2h_V3ug0LNj_ghjj6cY-{{fepbSk<5L@=W0!tMh+~!Of>_32bssqRW^?%~vu0bq$ zyHW8Eq6T_BM9~1pGeLx-DI~f^5s9Tx_eJ2#&7gDU%LsU#m}-r!YW!|JYm`lT{0S@+ zy-0U$N7u+Uw0HL*7LOvGj-XJi;mn0~Y!vFKd0MD8{K!^ns258*OUuP|1dG$?3l}lc z=|xW}fVR#!lJO|QetI+*HNYDB26E*RHZ}?6qO^1+);=6O1u!1(Z}4(?RS;+M&`r~BV?&pju?%+=RiE4d_ZJa4cTk8Fo+ zamYPTi<5FCPNM9ADc49aw2GUA7%qmR&mP0-#+t+0GR4GXV18~LODj2)>k$MZY2~ax zarm?{zM1AoE`nQm^LO(9Pft%Pi{kq0ZxS5u8V)5AF-&ZkRMkl+PV8hxo3bdV)l?jC zhD2DDg${p?1sJb4S=PL!{bzt#1J-bc&0k$^6QwH zJ}&gdteTy`6sJhIQZ{8pLQT&M_e`df@imKl9_Z#332JVfNyd@g$Z5t_Ete6C(yS|j zuHHUm+A~;OUXjN_Bw#a8)=-?w(Ph%(X`($9LU(&YNtuCnzE2U`+tNVnMSj9heUb1d z@j>jrv;Z;!{-(EI&$Lhjxx<<{jT`dA6H&0Ub5(TQIDgQ3yMnL4mP-ait}~)zxy+)X zyQfPwJN0LWLH<`6Uq|i0 z8MF&`Us?3KM88e59d|U+Y~tWp47csdXlzNIlRwOT!`v+egX>NCP@+t{L1Me12t;Hl z75(auPvh9df{3179o>cmJETaraN*}B2hBK7R!GSuR=GEHcQw_AK9*znW@0Y$Y9Xi0 ziX-E67$=VKz2lLi{D#XY1z(6Rx8#`c-mt+n2U;tx_&VK#JAvdRD!#a^kkK}Pj=_C6 z_P{@&qjn0pQWNp*uh5~*oE{=5Y#>Dn% z2Z3-Nq?oR~l`LX#;!f}CmkfoKqjgzbUkO`(-#qfy24rG8!@!!{szVb88jRQCfT}e!1Qa^0jr++12K-?2Vu(1b}|Gig0dT6m zLqt#Vr0AGx2Q{OzjRU1<`-*k-EJy+zix5Gs`|zlU6#u7>WnrYZ#Y7 z`!h$@$qo!|yA3P#xQ*X~38cnvL?yq1+#??VS`|b`ZbmuS2|>($I(Ax-;}0hg?;Jxo znt?YGM}m0?wvql{)@72fhZ z+JiX^gx3-9l+{41VCHoT1`vx7$>4ZDf%cA!&R9AT2LtA@;1ci(Mb^V|8@}7iVT1rmkz2VX#{)7DZooH%^^B>yS}=3Iv&)7{|!S zAexRl7Im>tK6ThC#Q>SEG&C{uBX|DjZUWp$_yG3w^vMd76)&M~5<^&pDw3HV<$;hk z6fSBDF5&|7ipMZ>=@K?pS5PPy5R1lL%ZGLCuoW;c@k^E>VBp!oH!g0c3xGB11E&iQ#Hk3aaGuXT>tYUWI zIxde$G%l|R&iduRrcKmxB4{1DvA%-&xtUEVBp*7lz*(q-?0w4c!(nE-qXzk82FM<1 z;hs0Y9oJuX2;o=^Q&Us;)IWSmh>^L$IX1OT5+zHrfhGZM_ulP@r-JzR?>wktuv)RC zKJ9JFT?cwnO`x7Lw4>I-J!i5Q&Q%c)07EbG6Mm|zgg;9TWAFSD{EY@aFuq04t;>Hg z!W*sK*=06#Kug8o6#d-KbO1Y@r8-ronc>>Hk~}ACV4n{IgMBKv+0hyq(Ji`3>Mkj2 zn%yQf^?t2uvt-sfb|lvBD2{85->bZr0_Dn8A*~*%$k-fMXUrm+`v{Rwmjuj%(Cw;C zE@<5`_dX)E`fpbh5qblT%+Dn!x(<&FO5^8nWuV-fq_mQRnTW5=vM(zQTt5jbqN4sL ze)+C#@HF#?#G?q%Pvr`ffyER_pXFLpd?}ZK?~|IMiJAE#zV-B??29+YB@PKuNQM+3 z=E!Sf0V99b9VbGUxM)rlDkGd{-XV)RDT%zcL>;*Qx+52N6k|LN$GpfH|M1U&pnWg- z6&ve0jSJi&!Cu3Ik!{zZ9vwr|%i_<2$d;RsjA!ulm;MyJ!3E?SVWcKsh9=KIZx|jW z1$#yEj--bWN%df$Cxf-3M={eZOXz&aGgL-+Z1Na?-YCgIQ8RQRSlS0^g`M6lxMcB;*$|6_L?lN`!Sfi4yfvq`AneCKIJ{kEHkf#yXZ) z)=?=_dTuHmt}Svi_zySq9uJTfGtLR^PR6;D2WSc}z_y6{7}L>^YG5&C;OT|<;EjLFRZ$4kN0*18b7 z&<76?3EBLQ-N4e~5=xblZbENQKjM)vdiwg%+t+JuUw#MLa^y9bQ$k?8Y(*n1BsNzdw9bXSgDox7)}dverhMx!i&Bos)pO|bj` zU1N(&1_#+7!!;N#7z{RGGDbWb+hB|_*CtCs2nE0blu?#uMw&c5(>YgFSAJ{n^PTF3 z>-W~RpYK}FJW5MzW;#^;|M!323H$7`PaH>&9mUA-h%$bXh+ITOHN-%O5)q04QL!Y$ z;?p^a2H3PQ+b|^BNXR9?rCe)j)LY-T$z1br)4i9Mi#T!ONZWvllojfmEJ0CXmYItJ zk093Mo=IbB<5BG0dk$XvhSx~!gVR454gdKEKZNz`*W%E@!@5@s9!<(t!^6@EOixZC zn@ek4^gv%P)(rNcr?-IOLQ$F;1NkC;`|3dq6j--oHdjZv*u=qWZbzhC$6)3c{Dhz9 zDB)clBRFSl8tG;eAKJ8~%^mO-H#$3!??Pa#;Yl?9p*2#FzEJm-dcPrHY~Qo4Dsg$5 zz{vU`A*M!Vv(lZH2l+dblhbX4j-3F8v?UOcdL9!eI(-HgHXp)yJT%e_u-TD8J1Hi) zv;l1Nb%QN~p<PO4ijwH-ZNo{_k`m*+xh7+nVWMlUw<@BKk3yklJEE1;XqD+F1+O ziKwt#yCQvTVroWM_KaSo;#dqDdegY-!hWQvE7ZYx7zwShhP`Rbv-yFgWwwEmm=~7= z(@5-Q19v?>jz^9YjWIN%t%MoUTB068Uf6;sjsX*?6{Slj9P*hk5HunwIUBVVZihO% z48^umi;EUn>$dAHC@`X(3>*xW7OVteb*cG9)4AYFB)@tcnS3`k@4XUJm5g{W$oHam z>m?}9oWk^7A3-7#Lv-E6XhpMVMB->AvaJ88L>)_K(KWagna(cMsu3)dDN5yu9C_Z> zaiU;Gs+%nfnna*4p}91H*1{od$d)nO(?Sw9en6cnOfofP()2GR%A}b&HUX8BfHgQz zCHAy9b@7yy=h(?XA4>l~zgb#Z6wj};ToPKx&K<5h`Gia)KmXUCMr7OetpYsM9~&ZW z9-cir_h9!KyK(T~Q|e4$6wf*~4-=i8HfN|!7ne*Ck?;44X9VnoO6$?CVX0KaGW8Kc6sn9rvM+pib% z+yb*0{`lSRLcLxQ`a+%yg+J!zW)-ROp0e3I3LP2sVCSTyS3&>45aQ7qIwYY^jA^Xv z3JC|%TA`uAW~{UYx>BR@K|E+t@kEn-&B^k;=sOH4v4DtW2CuPrq7$M-Ll+plNSndL zm#j@QhDeliF|wGOUl8QZM3jk<-Zv7#`dt^Jn%X4WPJMxnt(PFz(Tksa^-r*dWtjDs zNF#v*lsLY*7EOoQ8!f~No6(48Ef7)Ho*^Oz`y2b-fG%1553VbZ0fF~ zw=08q)Fkk28ZXN%puJ>{ZS zER8eZR?yhO7eDuxh-}-srDd{_L5ed@7%$Aw z=7S{BE?>yw#PLzV8YJm0F3h1+G4UU6@GG8u1q%5B?z{g1wN}!(a#Zkgt%`f@y;r3V z3M=uZsdpeb)EWmGH3XrPb6|)BArc$!O4x}}fgtKz#8{>V3~DbMW3n&1>h5)3JNc=^-d#`DP9W_V3397hH%R z{^*BVPnI&u<%%9!Pj@c{279%J+^h_k3&X9(tf&z|<<@IH=o#Iu@%*`qwbl6a(8yOEmoK}V)Aqf#i z_8Gk571!YS@nbmn^ijO&y5H09GG_VQXFr3JrzYA%ZulI@mtb(iXGw_ntTVPCm+jDf zR~vPVY}kZyX#tJd1Ni-`dr+_P_sOpyTbz1mR5s)Mj2V3Yy8E&5P)Te23)$wMzW{-E zbX}|um(DC86^r51J5DpBE#*0Laa9EVJd7EGvCrg_1VKBiLugS^~MwDjFm>C^g z!sljZ6%a7VGUOsSL@E|mt7>=FDCpoll&AzQB5jf84YX;Rt|G89J&{>51M;74jkJB@ z($F4Qd5|I7nTQ8FD%m6a<`p~8mtI0gX9p7Lw8bx>_Ai1U*R~nKV%dTXwTkl0B7%vz z3chvsDMaEn5mpk?EE_T)Qb(DWAw7YyNuQ>XU{0UEqc%l$&jq<=O`{F#qUpTil-Yf) zjOn&J^c}t-2cdW``7SIhS!p5+(4vh`cMM?b?#nS*F|n&gZV3HbFG8!j zfaBkJFFH0~gjyqkdZdAPGLL4Q!>?>YWGm4Lql@ zKZ*5)8oDzP^!Mgel6K_Y$eUJ@F>Rb6z0Hh8VH-$sue+XqbE=5!7eP$qf{>GXPzH_r}lcVuObR&lFFDl&U1QtsvZ4$tCGX+d{1>FgoEuu9dw>UL+fzmFFhai z8VQHigUn}q-+lLKEcJn>I1eHzGUnmKM-?db^-=gKfsR5!giuAuAwaO`J1XK-xmre} zO0~tZbv95LE~t?4+8AIc3Qi=oE+`|@qbM9Hdcpq1!AD%*u@E`c3`RrGXH>6C4k z*34U5oS5Mn* z6HF=19D-FQCmJ$FN!>uKwXUj_43xEf?P27}ezM!W6+(Miv``Ev|D98Iw7 zI?TWzPb|^ItFPRQM6-%QX90;!O6}qd66kEL1(F|4eFRh5rGsJ19UaxfPtD-LBNenX z*|nwwg&j~U{0I9T>!i2Lo+VJOzb9o(nVHlH@eR_}YS9Z_8oU-IrwSU3$fzJPyr=V0 z6a<98g5T$7@M$RElh_|iM3lRxpwPrLgc#E;-PQ- zIo6JhpczRkG38oBk_81uk$4WZSO=o{wc*}u?fn%BLWV*uo-p$;oB#kI07*naR6=>| zG4!`ipgYq*XD)@#?yQmH13yA-qKYtVa;W6RHIIkEnsp5Nx=7n0pcD!=>DSdlN;HM) zo*4xiO!yfj2|)={l|7(R5E21C^YM=$vSZu!mW`H2GLv^MfR`z36mdetG?E01i;HrMjAHme7UmXFZ`N?>CC}2KdhF3BL~NdBghr$?SsXupQVQeF?EJhOEe#AeFGm|o-HW_}WC9)eoP?Tu zV@aZwDu>B5HmG*W!?Geqvj2(4F*Z4de4ZjfX>IxO$w~D0^#=*!6mqGQ#;Hs>d3+flIpOY1MbG#Q*#?8U}%VSWbhs}tDt7tVmn(7#$E{@Ve?gJgmnk3kUFK~6Lblz)5}DW z7@Th%$l`@(bE+Xrs2v)MtderX+7(4&Z?LW15+>%D)HR?Jy+TL5Ft|668tK!n}Nit`7y1arpOr>tAjoXA_b{<4-7qs^n}kl zN9bdS)Urk02Vk*2&n^<~5SMvQ=DV@=j4LtQ$f4Pap`PkS-_A=AsT48s#I3T=EX_&; zki5KD7Lil|jr1BcQ@s{5hB4j>`Y1%Dpr(QP^Z`^y@5M;IhIFioOgf34&K%MyCW|X= zoYK4Swsa0wWD**JEH(*HbkBn#F0IyC9V4`_?4mG)i>i*^0?MRWfn8`dwY_PmGliX) zpkM#-4i%c4wVRgoC68X2Vqto5)iExICSWcX1BAoaQ%k$>M_3K`*&yq((yZS$g^od@X)@e7`h1EenZS@~ax-HkTb8Ieb=k@8ca^T;wZke=NH(=Lk9GYiES07(J3EWn znI+6Gv1hc5ay^Plm5w!v8p|-O{V9qzq77RlS0E`uOL3fe=3Z>xvR#MQ$W&&nj~+RM z`yRMY5KnJ!k0xarJG-KFWZgcSP9d8sAe+y&gAb~)IV;(nJq;tTUA3la7-|)Xi5o%T zq_smsk~f~6o3&CzfHQdzjZMw=Ln>sJaQNt9)M~8DMKo8Q?W$~ZVi3XrkmS!?M**Dp z$#MY?XlJ1tFMQ#Puyf}Qt9z=erKVOJq9=upf;bx|Paeld|NO(c*TaX7qOZRj(Fg;t zim6t%T6pQ@U3lRo9MM|~`WkFuiyDwa1aDAC4F0@wfD{rJ}XotoCB-fu+kyp!X2 zMyZHgy@6ev$+8lt|D3qW|Nq{`wb5?8czOXx<8gdE*P*VWo~~{|bF>BC?kmF>YSx}P zGbv%_N(MPIK_9!!bLrVD&&27wPZz{4B5??)87S1N4b0Ea;l$`@d(1K&8ttL&M^ha1 za)1jqdHbCqZV?T?>*?VDGbUHoX<+3JtB*^#ES`|c9^Zq5>{QyI_Dsl_m9gubh0hae zu);YoD0^iJrWyRYf)t+0;Lro&=}Dk2_rZ5kiKGqvQh7=8)6AR$KPz-UdMVa5YV19Xb70RbaK>UlwbI05k&1=6EcU!&N?LNeGHanC%nm*3cxG7-x-;zw}i29b%-Zv2T4zaNn^cAw4)&?;?kwn}iA zNJE=eA{wcT_7DHggF+|5+2bOR#1kUa@x>^UKf?=r=%EL7b6%WhHoLU2h=pQNNCa5W^1U5yqVxCGJH9`Ob=(YFw`@`OfwF7%7faO1JcL7Let->P zq55AFBZF(u-Pfb6ez2p8;jSwBJDce1>p(7@Mk*UYvsSitns^);4l_X=#l;p*j*nq- zu8z@DvnZEZDAl7VSGlPZm|tY3oyF$Uo`HCpa@2Nzg7#Yt+;`Vq>gr&C#h`{SCvFM_ zU^yq9Mj=-~B5g9Q4wHI^gJ94gs-($up{~X?XOKW~B9?i`MNr8r78TONbupcGn6^CC z--?SkaOj|R3`4`~g*@=}mh0Z6QcER_k!5hRbK5qdKs1bdhUf5>SM@1y5ro^I?m9Q~Dp4FB zDrwZm@GEcp0g&6MJ!0ZG7U}=~(UaJSIy$1QU&uE99K{sB7wy5XP0iu)WD=k4=#-<# zWV3DcPm@p&^8qw%(K0Wq@f&39$pP&H&znKF=74kgZtU5!BM=U)EFg%#Lgm>C#wI3k zYK)p8ZdYi8z3y*Fgk@>L(Mkx(x{UlK4o@hLki6K}*Q+t|p0oCL z3toW#a?v^rr`*qs8q# zt^38q+cY~O8o|u$LR-JWApVxhp_}$TAM=eYVv!_DNF$l>N@;9ibWOKS{RozzCDosh(l9Fng|1GOd~$8~JFI+=jC!_j-!24Uc6P>~uOQFto8Awq9|Z3vV85$c`yz2o+*13HCXhK5 zh>ZS}x+1cw*~Hm&gJ`RYGzrc168bxVzRn)3S(C@`P!59weTXJf_|z94$B_vJ7|bG) zipt1>=EFJg^iv9wh-4^0P#J{GTB^3irD~Z;QVb*4)?Dy|O^DIkU+C~@JT$SA?T?(5 zk!D*KAx9qSbQpyR&WX;Rxe{^)HA2FjI+h@*U- zG#P{}pHFNu5FHQGWu&lZ@d?AbjMnB*UHuSfry4LI@G?IL`VlvqplBR;T4a~iBY)u#Mb7RON= ze-s_nqv%bSth5}XUrQj9jtebUD`P4lw4UU1qET!FAbMcrOe>%JNOMVo2h9+6K}aVn zOhe^8bKMj~vty2Bs8GsbEVY`5&n?8y=AKAWemfGyyWaJ7M4t7`3tJQzV?bchC;#N8 zZU#ughz>kFR?}`MgQwBwhMk=@2~o};pyt88ef!((dwf9IYzi}EDW_7{vGX*Xf8p7< z<9pvjUw5BGKyJA4M$NaT10#yybwN5--YBn$(UT(s+|Z1M*n7NoWEkm85=V}V%E_^v z&!gSdWeTs=td5%faIP?jgNV?o&CCTRDbTM&3(5yT>E~2h3TXnq)m6cVoDx4FU+A>y zTPevz$plD*y3Ga_2SHb^R8_GQZW z^gFkqu}nohGL2QC3s=q+wf0Mc{8~70yn*XJK8`5cB`HkPXo*b4b}|x4pFKW}GnR@N zs8n%UH>Aq=i`Red6?p&f8F=m^kK#a~3;(d5Dx{XRlPf@}a|Wyop5^>mn-9>dpL;*^ zR$_q8i~?Kr%hz$ih3B`kQ-j*Avw*FS$4{I@d8ve=#M+FT^2i8I`~xAroB_nq z^9m{29S}rOgqk>$A+)f!pGgQ(T&7#);lKg#pvcQA;&ez`##&&*lhxWO38Jhtc_Nh9 zZq((pt-C9Nc&Zya&VD|o8y%XtAoPOHxN9Q@*6qdU!(UU^3GcU_8bo4nuYv@AB&F}8 z)k%~_A49G_iosmTM3J};G|PtnClqM$c`<0vjEi(qqIn|iddG%zV_ZGdG#13Ep`xcs z%Eo=+&C&jo*vOyf0-9Ehm5B{;VUS|y$^-~)Uq@iwexLi>Pa<;BGoRV=tkf>p9+*Q{ ztZQ)dWRd{_4+0hZSspGr_KsW*1UmLVxle%wHzXebYjVH+J8!~AKlTx9-nAH79})F$qr|JUUduuzb)4sT!$? zhro;UUT<}h5GPRbG;1>j)+_Ia_h@C37P<@F_`nB0gko_)q!$JSjI1+M?$ULq6@5Sc z#KRaHKZ)+HUi1(2qpPbI?|sjo=)LO|!mU6@z92)+airzaB0l*?7hz-HDYWV(v>HS> zn3FhqU=SnkQ4={^5q$l&DSY93#2>6yraAK5lcD^?pMUM)6XGD9Hdx|ZOCr^&GgAN~_X8bF{zc#JVX2_5z$<8i&VqWH0jcm|x%fSZ4 z$kpXgl?=l$qMqJfba!{QiH$tV?3UQLegh_^Coy__G>F<6mx%!bkyh%E*g!VZx=|l| zVEJomF4YJrTg`-q`YX~H;H29iY3yxp5m;APD}qb+tic(>)S<~B!yrKrc0KU0EZAv8 zSZ1aMiUmg`&hZ?coGRfPKR$t6N2diMY*BACWv^(%cxJsxy-x@xCMq6((nzfRvFR?d9^)KDydEH-vbEGKEaAvUpPr=JSznQ6L%9oQ{R1 zqPSMl5@1_vqk+@Tc^;78h)S%(KB?6Lt#E$LX(*09CdW_0cO}s$B!NkgY<6i1OQVk? zT{@1zt`gEQPGz)q&YV;dO@=?q*&uQ9#8`GW4vCQ~O)-(lAmx~eYSA9E48bItZTr@u zYr_}yKj#aTiW*qRGM4iU+?Vn9NfI^NZx)z)Qsi>_vQ`V&baI$B2ARD`5s<7e|=sV#{RV5lMb!S#T_H{ojm_&!cHhI#I<4uB!k(Epue9z=#-kJV&W1Ktx0_KBNwB-JSEa% zvqi?Z_dW+kuB4;6lGf?*wh!HpeRJEae_XxtEo|Gi0|)j$tq7Z68>&?CnkNn-mW*O; zyrI&=|5sj4Tv~lSzu;K@KR=y69^8d1pV)`b@7RTd6c^$!q`+mGnw|>W9ws$b^5ni0 zS0|7VxnF6c7)U5s=NYBuNU?;o&pJ~Y_ZoA*DoNp)8a;7Jq(vHABBsiKg=kuzInSE* zI{(gA_&|m=Wq`JUl1jS$iXsjMepjeqW4!?^KYTux<&JVMyMrR`81FY(;;ziq7s% zv|_YPLn|(-WO`%c^9e zE9xAR%?fA^ZK1eWLKuyMWJ%e|h-yPhf&f;{R9*F)!>DN=6lI=#MKeJp(=ZD{sFNc; zxtMiC( zFw@x6Xq85>zO#%-lW2_DX?_-49Vtea6+bN?3es?h>$z~>^Lg@~jmt(KXeya(rKbQG z_b$ogTqh&AQxk|uB@rYm6&Vs?=u^9t<3eP?XUHxE1dRLSj$3a;w_4{f?@&nDNjdecfD69@lJd1XSa&-y9O&K2$Q4?_qT3mxnfcC?tsB0A zTWYQ|$=V9?4k%@#&SkKx?yJvjW-Blwg5b}9C3OQT++#585KeP~oD ztp>y@8js=?Z@mwd%nr1Yaa?rXMOc`d$G!L8qeGeR$P3=%p}1sj0ek0{u(njj4(gcv zZ@^BsqgnX_YI4a;>>Evodra$!tK`bs{DV`IyyEPnTaaB#@N85|G zIT0cbn_#!1aR0MGiCXnma?YQ+glZE={!E!BpzJH`>{a*S-{YJ3d&(k&g$Tp?^u5(V zlCpfV_sx9#tLx!E&-TZ+7P|ENhHe^6&tPEB?%mdk7iKnS@6u9)7C?~|1*4jg)Kpmo zs*AYj85g2hHUyzuF@Z0>H#t`nfAiWlJEk z$}t7V-q8j}Cfry%%E9~N=Wp4vNgW;D!pLN3!-h>5A0NlW__#O*^;!ipQ}fcF5nm## zlcpI4iDx>!VD|$;$86D<{qBJM?5f+MQN=Y^Y(XYbMxm>KSdwK$dm?m{Dqq%{C~{me z8S$!lC&fRi)T_Alp&67Sgz}mgJ9#Rg82s6$+TH1Vi3q!11Mii#PJ9D(Nm%c{Ct`y1 zgO9M}ijL5n933p}4SkcLxT_EkpOqa>p9keGqU0ig^fP>}3SbxvGD*{v&$wFo7ne%9 zcdJsgH2HSx?q?z0zXMB=ym3Z+9J$aLZtw(JnL#uX1=NajXfB>YZT>jcWS5YRQ~!dB z#R-taNW?()lcaqrc`6t+q(r(mlABJ*&$1(hC1JKLoIG_3Gt={J5-iI-ERT6f%g`DN zX4T!(E_FG;yn@^tdhHd3H~WB_yIzrHfy~0EBOv4>EBU?@2BoT+LOaY2>bb!}S!lq~R z{5{@_X}DYMQyEWCTI8X&mu+UgCnL>?iHV?lu_C%+#?nl3cV{;~_~8$$1{virc_JND zOJqw~43dYw_IG~^l`;ii7$}A5dQoy%LhwNeYC)cH%uG#+4EmCbhjHWgA3?bhMRzWW z!Q3KV|BAghb4MRqO%Cm`Xj}*iTBuYL`1Swx0HV2mL|O^-_oPsZr*Zt~gl1w;!IGJZ zMdfi^b>J`x^%^!8m;Sd*i#+m2TQGgyK@>i`NuI7%Z6Z=_0o5j=H4g3oQgr(D7OKk; z6qlN)SM#{(2V+P?li?_$24DmjIGL zZNEI)z?Ss|#3I(tSDUG0tlGe0xrIFSKP262urv1(IUo`+v(7nvu2oH0GjD^`nvqa; z#(C(!HV5Wj-du&hhkldUP#B18D3 z2L7&a?Jv!`aP&Th;!-lmO9v;^I<#`|! zF7%;V!>REx=^~hFUDeu+on*&4cB3x-j|U?{7=nP2i`EbVZ`+l?J5p;J_3$fJh84Lo z%$m@jb?eB`Y??5Wg6~1wyLt2GcGkx;KD1^?Q`3`HPmhu`ZIPaz zI}bt}!4LuxRQQA{gbdPyhHZldJa112Si#72U(Jqa=d>w(YUd=8ZvB9@%m^I=DxNm?@qG z#VVNrxZ}2OBl3(3E^O%wBBpSV6Nfd00Z!3`geJI27%B4baI&FGIvziMTo0u!;~S0P zm9KpjI=k3P$Azdk`1i&6d1(?14i4beuluj~&<8$@ z1RYxo7@IiNu1l^iDcA!ub;H&5M0eoa)Z9cgxSFA^pS4WcR^6>?Lp>SCw&pTMa&4RaAM%%D z*KWeZyAPx16I&6@gnnxsD1#4~CG#8+ePKp2wUEH4{{Bhqn_43$V7=FRDk~$6!`Bob z##6|5WRYiYeG7ui$z(ru>XeKhhjMi!EBL^hMzDKZ9?dGJdB*YCFQ3BS-8zL>f(Vx@ z)Ftuk=R6lT+<23&sl8_+CJF0()voQqy=t746;(mcip}w?^x5;?Y;Q(&ek0MCVEo6Q zctYoa?O0-UONp+fJ;(h}UMl1A=Uk3&ed}B8(i-2}2z4#2U$+iNjvj7bE71Ttf{uJg zTbqQ$#dYgPMChVjaU_gut2V^I=w~*lGaR6F-v931JLTv#%9*9Lsu2NMyFE2NC1cBA z%$%B?6`j{G*MQDX`&M69>IS2#s-fd8v&t9-#z<5Gl65(fgnZ#TB96qw_nZbWb z({NQsR={n191<7#8RO$qYKik6dUAni_-ToJDkRr|&&g``E6_WiiwJ>%;K*ya{IoUL zwU$mZifn;`Y9wmfU?8rM6CsRh##P{Jh9rY4>^GKZfWUe*X?uG8H7ynF}OmVqiu zGcJDDMo6WcX?uj%NBiS8iEHW|cKjTY?s$zN9?C~i>%ltm!Lvd_C5PZu#Z6FG1T}orwFa!+at`9XyHJaEgrLGFjnanZQHvx| zEf-N)m_{0l=!uOZnJ}>_?nef54(-RHrhmZFso4ON^X7R^Bsd1z5+k=!TwStnW|Bq|og?YDj#kqgeZAb|{eau4`n zjM&I2;34GAWK%hV`a+8hjRHk?2wQ80IyYt_hHGAN4SIX~gJ?+5{8w8{1fTuuzs3H? z9x-AHGkG5e%7{6g!LFTWV0>}{S3dU&OwP<>%|IWvY~PBFn>H)h_|CU)QT=6d{1hgp z#;jeF8tz4w9hzc=GVAW{>XCpGCkYaw({;|xYJ+m4I<(@>*CF5o6L~}vWPD!<;+-kF9h8<%a zJ%OXA8o2pKb=>)65%C0vwZs%~*;%rnl)tOeP^e4r(36lfG&HRJ!@&Ki{rl0?WuiMv zOY?}eO1SoAgShI75j5&cs7I2x{jL(;^H)!zmBL%QhT3a>StM&@E*9HD{ckdaYcHFWKfiRn7d}0bS(^f{(d;v+AljK~swzJRzV2+OJpiXwPXXu};bEMBR z(y?G{wv?rkdIrXuFrqfE)sZ_UVET8M+{kpDi4VWVJ>J{fheBuGh<_q5*W|p2Dyobd z6exvAhCxoecS))TWkm`7gh`8T5BU7rGi+LQy!=_4(4RLFGsWGS5leJ`&TJuW1 ziKXSL-B+lSlRbaqy@xPa&RqM=a&)=HblhO=IP#TGl!tV=+=4Cz*+P;IoZFg<}-eF1AzGl)f47BPg^)N8F3 zQTCc&3y6&+5*E0*P6FE+IjTT&MHgsFu%Bf#~**x zSgFBi_-A>Uz@5043H-Y3J}jg2gCheN4N{#NFB%9aq5pfe7j#s_qeSOj`1=w`&{*wE zMg~SC#xP;*v>m%JH9LzBeDHmk96ts`k{B3R+b%18?BgHA- zvz-^C?=Wbfv52V^jz;syp~Gs4GRL*7K#eHRFJG9#TVJyaktPF$7@jzk!nNeN>1ff#S0B7LKIxF`!_an1bI#>pz%PE z3xS%RakGVDsjUAQ=%qrI&(_Ytt>+@$y9<>F12OYU4E$LJ<^5L|XHdW#I^$DTCJ9`v zb}6VWp>620O$fHGF6Xc*X|J#pW5Ff6EwoNS8CicPsueb&mns8{O3Ji8Pbza zK8g9oSxk&gs&}9D86T$9)xlBKRxc8)mZUgOUeJ#@P!rve5o@&+WK7LW;lzm(;t>oE z4r*!~GY3a9nDttqv7(Q_YZjbOHh;<>ARahn?k$7QoeW6ygFh$r$sj6a5wsBw>FCPk zB7St&k90V^#9&ZZhuA=NgiMePO?lGc zp)}IzWke%cMB;UD#^(*UP2*!O1B&(pVT9pEzL%P(%H% zeSO9@3RCr>%D#E#X6ELwed{)io*EVDiECLd&g1m;b-eYJ+p&F99^;c$92rmH9iO-t zOU*9yc9XNgEXHJSO{!JG<(hLcHa4o~&NY*YA-OCfahaj@bLD^f{<46~vP>rhGT`7$ z5*qBu$qC(SHka4=;OqrjGVYbR`B@x3bSQKNL`<}XS|jneGG;=c<}d;QFA~M%92m8W68$#o8`ewuoCDx^WK=fJTCORY7e~3$(5~k!79q@yCPpWg@vZw$p;WF2 ziRL{xWX@|g@hK)aB8VlSeIhCo`76jUSG1{si4;|q{ry3&5GjyxicK_|nX6W7vA zpxH77B0;s$_PGy`vbE6j3j7@g0rFizR$JGdh+}cFgvF(zo*hfBX4`;xu7HiFUxs3< zUsBDA`PkB$DabEkaSTJrlZeN}>%{98@oT{*GD7GX{@xw`g0Fw= zpVi+^NRg_2j4p{n@PcSuD1%C4ry5e&$e!Wyrs$Zh{Vt8Z-hL6gQUP)cikpgZ=jJ$3 zu!3rxbs9Uc+}J!k{2Uru)p*%Pr`kHZHEdqHqB2FqcEHHuwdhnBKkDksHRt0<1Mi=~ z6%Qei1lHI*TNC6I#6mbD;o!l8Z9=5=G+X584|8><;?cBceC{~Bgy2TVAvu2EQG?Z` z1*e%i+TcH9>}z(fl$1pZ{#`1HR7j)5?+^B^!G=wzFR%%KyMO zzWVjhj$^Hx&%WXrxbdcMOP$eJ+P0oNz{6`tFg|_?o3?Dj#L43*mX@$*Qx6{4H-@2g z>yS>QP+D5V;7~s=_*v132KZgK@m(eTT7a=Q$#6 zac^6 z7{nE4W*EcMN9(9!JwEc~LqIHr>6sb9m?k}L;xHCqP|DSU0+FDCVwxtI25DP5!?}fd z>^Xh6GE6=X2EKIYmE|H(U&Q*pI2KDybQPL-{makAdp>qI^22-NTqsyZAu83CX`mZT z9Mfz9``QZp9Y{;7<^dRjz--ub<9%-6~rv~vsxtOWS(+>~Tm0&H*3NEhAFvLFTxSRSn#^Iy?veFx zB0i-mgR_`Qyi)CJHgVGrpTg0(1R_L-q;Fs-ly@sQBFgKR-4D-9rDvB~Zc8;A!XjQv zD8rfXlAC1H0^rM&DNArx^bl5_zXh6}Trn=!2=U-xNUQqCG#Fs z^Zsx7&NmSm9$CZKMUftBqb3C$Q6I6gKDG|k>bUr#XR1awKYLP-G;ALaqa^dj0RTgSxYINtg8|K6^14h;0;58v_z{L2sS#6SMije0Il$l_-(duB;$+t!_! zpB+a&oy0p{xfLf)9>Zt9b{O;36f(JjYVah6UU2pn>=`(P?ZZWE7-F_dg-UUNt;te~oiCzb(tuDlXENdK>_^7J z;64qyYT1}u?n}y_Z{M~(=vBlesm;1CogJMO9i{Qyc$Wm}U7YvoY0whaoCY*`}U^)Of!R2?L7 zx$-P??L6%?4btIyF&jU1YD{g9EblOw@wq7clR*LP3T=dvgLVsWvhCPCX!oFBz50Pc zZ`r&#A?x2aghHi9pIIQXsC|xooz9WLRnriiW>cl!LV-d{hS)L5+Oy{j1>YE z3u?J8Lb}4pWG9ttSf2t&2C$afIT6y-1FihbKb_-c8~_V$Tr+|H7Ua*F23hjYSQg_f z24JaZ{)Na112ygiX+%&nCzZj-jw`T$PIWb?WSWR$c6u5E^?it8IozWKY5dRlET(}Y z@ViY4HUx;lk;uQH_0}{i!=Nj*J(GiH@29ea0#XjQauF)J*zh@yB!>y0o;3PIO;d<8 zP}ADxgY5~OC%024VPxGRI9bWrc;|Rnws`;|Z zE(WJRKK%G&_`+X*4#o14ZsdaV&&P=q$2H_=b%wm!DXw;gtVePXQg=^}=C0FGQN)DN zFdZK!9nKe*P%SO%2F;lpEXGKmJ)=}oqt=5#IW4inNs40qQxnSqxsRXgf-J1dw6k)F z1vSNs@JPRX?X4)bZQCi~3m#M&uSA*~$OK#%gwOzS12fy1pP#|W<71qKX(a;H=q&s7 z&B;Gkmm1oJF|erHj$hcGK&&%eK#{vlZ|A$X9X8gE5quiIE3UZzzMM;bLYrH9e2sp1h3aA3RY(RWHjj;s@h9p>zb0kv7#B>uUC!=`hXAYy4R#LiByzDXi@;a=%`-TJ3*Kti{{9}! z&n+1fi180U;oFL%;euGszUzuU{{H6tg?lF3kNY zqpg~IU1!#{4Hy*B@Cw3}4od=AW?r!bmf6LyysYjUvE_qvBO9N=3LQRCLS8@lM+S{s zvZ5}K0NHwtm>IaT|4_cMJrPu715zR<5lV=L&M+vjE-lNPX|Rmd&-W*?LegbVXOC*; zeAXOg&*`yc@=|DHmaCYYno_xi&%pUpB9v<~p>_Uv5{s?wPCv*Yt-y{R4dk|Ep$t=?PldID6w*c`3^%AxK=D-Ygn960xM6p&DBa1K?G z_w1!_D+ik(ln}ZQm>3m`*Cz#ob^y=7i~Hv`auPOf8fp1-Gae$V#~5jfK8%Dy*7T1Y zIVQ-fTH*LrBPvklTx6`)YgR9{+L3(_746tlOz{jJ(?B4oB2ilC1kJ&3>f)Tb~v z!=X@FRI6njp0z`RlEh}MncXHrE|j%ejdpNwSjMX(m&DeMYjDx#84Ptz1gY0J9yrj% zr@!(vGTCmSGTD3vuYd76yx^JCO{n6|pOo?3O9nKqJDOaJL}n0?<}zOU&f9Tx%Jw3S z1jp?1z;t!@-~}(f8ejUtUtzgiL{Bn~H|#%xQYwkvtui)cJhc3`hY6z{DNN2Z&~@!P zBsWvmF=R2}R9dN}g?&#iqLJK)>puLT)X`SI$l@n#o5|+db#P^(LX8O5Ib5u?F7##%;Lz%|AdZ)o=4YWUNV+ z^T9k8Ago3bR!Crms&T)V(2WJma`Lni6xQPKu6zy?Q&V{6g%={3j^qCO9zqv&PhzHc zNKFL(T(P($gu(YO$&7pt&%!-p46H0&6VIU6`ulr&l{lCZA02+mI)7kBcX5$KMnfrh zue?-d(LCR>JAn<(s4E$Zqt>($_Xd3@Wnbu==xjW*_p>S|#cbLK2PqS@5~*Lm@v&@m zoHg!QF+X3ZoYvpwvd~6I)JN^x2Hm@;lAK8BuHZACo1x~4WxiXtZxvye*T`!xmnizP z)aGcp^s(#kb3GZ1c{!0tAMc%Ko3J_0>iV7}p0%Cj*BbJj1qGEHY9x+T5MATCN`y+P zwe@7C z3kqbfwXYiO7G9zS!UX~X<>tYI8M+rFx@Vmg z43IQcSAkO)h!%p1+itx9kxd)dwS3OC5q+#rlumzOU;rZ{Yt`YvAw<$cr*^)g>CnCv zZji9(a&;MxKKU4mgc<7%oOk~D+PwSs?b8%OhrQj2d357-JU&2*HH{1ntM{GbEg7^} zzjH(Vwq$zJ>2mQ&AR>gwC|}u7wT9AiN!LN1!s=QpKg(fAmOS`<$tqK7Ig^p2cevFy zI1OOR7_F&vd!#Ja<*KW$LaDfbAO6b^WgOXpCo%~IKS(qQz2Ss{85!$gMU6pDr|j2d z1h$op!k_aNO*f>gO9&4A3NBuSgt#;IbzF@kFbfsT7TVs3qVQ#X>2_F{<#PxKhmi0d zuKq8-iF3|9L(#U8Sr_n~o4<|QZoM4?gM-Qr`Fxg(Mf}%mUW$>Se*E#DU9W2&A3rJM zY|yq{=cbKYbx0?sPU5A%`eGEv9>Ys6T@(?rN)e(+5`X#CV|e653_U%4h{kwu>o|W~ z439nXC>EmYaL$${KKAx=&}dps+LQnQAOJ~3K~#|d#Dm$usp%%(bNvB~FR`v|Z1_2L zu~ciw<~uY~gyj(`(w$jv;@2nVBwloSwvNt!XItcnSR9k}2zp*Og2Z;~2(jRe_iC+- zY)9XJq>B5Vh~Ue2jD;4dpcvSqm{5;`1nzZZK~<8ymW9@F&(R1Nbl6fb%rD4chHOH; z>4MT**tB_@o|BWjh6gJ+eb*#*ZSBSzfA0ZYefcmt(=mMFn^VDHa4!U9xDeRzY%!R& zwnCnNYss>Gv@(yxGd>G6jeNoVWdg9P=e2RK+_VqrGQ&h6W6EIiAJ>}{taT_`QE!@?#y()bgmUy&xJ!yr;1 zZGl)!9RYMobl4=M`5EKq^SsJdDEKfWKy9``fXKNMA~L7hTknH{=oo!8v<2e42b0SU zL9<%zth7tAW|tHwA2V> zU;rm1hI?t15R{!nd+ARuHc^2_6Ft41QeRZLHIyI>iL!vfe#g*%-B&=h_*E~x2$>Pp zfLk(%ebpPdjl{*xn>Myug4#^d)MY{0$*^|qkT#dKW7vnO&CSaU9-=8qkLjV!%+BKR zM<2mi=bo)V2wMMZ|*M#4kMgYWG)tl#ndjDTs`k`D_aDxr)auw++cLQPC+_ntFx z+Rklw=-~(O_Cg?BqLMCa!^f^v&v?)QCL3V=P*F=x}_Z$3lwZ^E$VI~0U>j9 zzQ)fY2wocTpuqNyWmSCXp1F=;S{cbl1h2HI1Nn+-XcF+rUd-~HdwY*aL8 zilQ@*J^BE?@%67^Vr&6hwr$7e&Fc`UmvHRF2|V+HOE5Kg2)BLzK{>-?M-R6t9t<%0 z`-c?7RclK^UY>pN#pui};HnEa*{*`pG7TVmhI9Dn-ygt<`8d{%Y(Sj~gozj`%O%}I zUwQ_gd*6iw%@JkokN4PI##2Yi`29bB2uKbgmoI2NXJ+Rxx3GYCEP|fyZZYlGu3d{Q z4?Kjk8$efO85eXI67_F=ov24K8I2+T!hU2gEwm$bJ-^UpvQ%ndVm5=f{rOL@80iv} zXYja5?vg{nGtL1%Dod%CyeK%86IUtK>a|?4+{4^>ufy{Fl!3|EK)M8)no1-rk;L9J zCUDyJ2Hx}jQ6!sH{LOpM!;9Z^Cn9lB4W;6rj~D(Qu?hYXAa zYfLD{B!2De5;Y@_gtIjm6jN@U^HUBTJ|rYk0!SSl5`{W({D?BILx&E^k?HqaEtP`g z?33oaTx-AsXFf}V(hECWU00T?-UhjUt)OXw8M!FcD->Bs~h| z%)IXw{`ThmK*GvKwl?Pc8FcdbN>@VVNn2OJ?`pfX_Hq&aLQrJ;>u1{1!_YeJ89uAd zLP4ky_XPJwxm?Bk0wwp2gFu^QmVdMd(DSD3Y^+7?$@`_Vrd*<7@DqeHI9R zhRk!J8;O|F}jHi+4I~~pRAY#chs$-9!BQ`67ET6T=lCET^O08X=?6tHV z43U>VQTvIN8I81HEt}3w(BP|pGI%h^z{vP?#(^R7;(Nf8NGIR=a}v5m^j$g%&gHNY zlG%VLzI)3z5V__zuWrpwmDJY4Hzu>TQZ8Y~mdz$(tcg>6h$ef+S{~5eG{}vMZu&5US?*em3fLx8D0i`S^dr(Edz%Z>PRL! z@UoY^3=^l0;>UO0t-0eIEh}g$u#{gilz20^A53qGzKmO(mU%^EeoQogdb3dNge@LXdC!ToJjJ_mH zqgc0ogYJD|?6}tORaZR=7w;({Qf07YS^<1?8sgH*;gkRH1SXf$ShsE?B80iiC3Hn6 z@s;Z@N4+$QRwRK)+ycXTy(Ed_a$^v${-c{QRqjMAkw(7Ir8e5dg?Y8vavd22GBAAk zkx}I7sGBuhlBxb%V+0&60yAAHbiRBI(z~-OZHyGrVh|Q>U~ICC{f86y&_5hO4J5sp zLGbPebzsEV&dZq-)`n-9kU10*8aXbUdtKR0c&4nK3rY@|0Y?_QtStkN{=t64qX{8D zBg5VJm0x)wKJoES<9TNmap1r-?tGeU&Zfhlx_f9t;~w+#^HV5Pn>1^}E8&yu#TbRY@@e@`;iBjLhkQAMRKWaX7+}&v15LZcV2rlryz|Zxn#a#&3ncjq?21x{ zL&XLssU{tQK1V!=RPZxvOqf%A?#PzWDX?A2KB>p65yI~~(-Ve_r9r^Nd z%_cFbR24-$!jc|?B`Zg`I2oO#1`fqIB#AQiOq!CW^PkO%7%Cf8w`9ONm#pSZTdq2` z_FW`Mxm(GDkiTcs^=ci-Xa&D^-XIdu2J)TOE6jCKGEI_dkT_l@>ZjpzL>V~EwuQr^ zi}>y%v#2&rp-`nPAySs`SVnIpEl;>uCZmm{;1+E>iI{vwd~eMAU`BgF*Bb5EChr@LOozmS|hODRgN`EwQ$TL?UK@M8Cwd z*S5bFz-d+o`3Ygz9iOA^mlopLL7-zZnyD^SM;}5q#_ZmPfH9$EXCHkhIVG!OB10lA zAoTrhdB455E-K-y>O^R_Z%R1J_Nzqv!q4&FuH9nXH{*$!zqO>AewIF5oT2a;j#zp? zsTRnu{`23rnk`1dCY3z5w16A_>1H%)B{U+8W@~b;L>sg)YA*~mQ_Tk_G-Q3R=Bya` z*73x?{TMxdOwp)2LoYA*jjLBXMHnZ8zTQ5uzS&hFcqfdBW+b?{xL^=qh~l_`r2ZG2 zxr_-VRF})BQS~se!PO(I8R14!A)}TH!mgotqa^BC%HLDWJt+DpMq&76Z*U~~!!3iV6 zpDiz}_F7&8cIWR*;MIoQzZX158{X3<2}WMPb=YzKwbg-#)uXGp;Ji!mlB-`VZ47b< zXqX;*_|e;=MYun$i?br==Zh=I-mg{0CdL(MPFV{l*yiwg_LWixo1J@CmS)~;DA z!?!rMfXecs>Wi;>*(JDm+ex7abbhuzjC|R4*1%b3Zp6#qd@EvI>v7Jxm*D8(qsY{c z;!7Xeg=V9yE|+GL41Tt#1+kTQFVY?B@Qx3E2S4~p5&51qGDydc9#v*Vqr_UgdeA3l z@b;N`EXSf)myKXo)M}RhtFNc#fnp(v+%-c;pOG~fS|`FnF&=>fM@l#`KZFl_?s2KC zSrO4E^jS8=44bnsShM%xK&%g2$;f14DZFG^zXg*F60|2(PbS)B0W!~=;O$rx>qkb+ zKx!0j1b_C&Z^wxv52CYv7vA{32PBTeQMPOi_I+fvTT@^3fKx^%v=#DmsPe`seEOY` z*)VwK%i9*0tE^WyCCo+xb?&+6;;wt{k@HwuTv9MZq=Sh=yKc@vIHNS zeb0}K9}rrd9b)Id>EQWvi57I`J5(OBOqpZbq3o7tor!{J1xVgXY6^OE@*1R6YqTdY^5;nQV?ZM@x(wV(B@hw zaxN^11tft1+xEUR&fgd$&Z(B#G*YHYUm+;tp9~Tt@f--A&3Y3z-*pft%PAp$Bw;!d zYIezzLfUY_`?{|Lx;ndcjpQY0|1|0vT17O9!3~M$o)n2^7N+oW?YM9FyxB#=J??%% zL|UptCZfn>Q|gW*qQDLXmLUycwMoESV=Kjkwn+uz9IH$c>%5*F{Sp&V(<5kFkVSRS zu;(=iIVcrMtApj8Y76neKzR zcXcra`yyq~P_B_Z4>}PRw42s}N_3&^R_EAD4XcvJl^}${P$*l6^>EUocnhKAa{KK! zAo8Vu{CvRvDbw1(KmNl%p|7(C4?p%0vbhfA@?rBOQ*sJclL;h|@F5-`nCOs2UtHWf z@BBd+24!`3CrI%|*l#LSA`wS_H(9QoGMrXoFm*O=Y;VC)Box@t+yFNJdnMav7GR@a zO_3^_WB4@la%G|VJ2hKnLT-<)^ z%~)J2qu#9P`Yt&C0yzi`vI?5%LKr1{Wy5PKHB&?LvJFQUoj7$23o}JjTbxGDm$7O6 zP`Z;foFfUV%Qxm^f|6f=p7dTpyWii#12t{7pm$#?S$h^GlH-VB-MT&; zJoYqF@jTAI@C>}@SFggO4?cjKZ~m?}FgNXsU-Vpj^=miFF-=U2i_pa9vw71-46j+M zgZIFL4`8sr8|B3!-u%klSWnU-1#=oerAk?6(^*Hef{V`|#DfRwc-JQ%M`7)DeC9KM zh2uw0;{I>H3)fxKC88DiEhbRIMP_|Ii&(M;nOq<4d2k+o`q_K1P)?w;zZa#&62`|T zuxZN{OwUZ9Qd-82#UfrhF@sFKfz!Ky%)en;*HhNp@q&2lat|Sh?yb!2zq`Fot`@Z zTbG6e*V5@E2Kok-Y4YcD9UX0+f$wYnJcANuY-*V!>$_SN37Up|Xzd!!c5yXD>7+y= zc;JEi709^pW`aT9ji%=XeSha-waZ6J+g;k$9FQ_-q5%xND;4pk+UGPFear03pmX2w zzKASwjJquG?VUEH)XG=qrOvLq;rc z;CrVMaXfQt9wP;TdQN~2pIDkeN_SP&(uRIOev^po&*JcZBQ^f;Cp{Mri1hwH`9 z<7XJp%g!qQ69IjB8S6G|)a(J5y=UOXfRD)9($WIPCnhYxv_iOoV$KAjZDCSJd(PyM z2$}*12Bs|0hv13l$ljZN#`Z4*O)mut?Fg-qwiY%8lK0LamStlmF0zk7s+o?Hd>A5u z9!wKqQj0ui*pLg8=tA#?^D%ww0VErXp|e2)77X11L=Hc6=#U8*hIU{VJF+R2CaUDf z0)Iv&wJ_+4|K|NrT7aAcww-6#)yJV*q5ZaDia5Gd$*w)H5Co1w0dfbLTh$cgUU zi?^}d@cF;{%a+welKAI;`WB`qCy+{U+FuGMMyC*uwnShQZy;rAW)21Nq8ZsbQow9f zFi~JoE-e@FqdR{H_T4%$Np&1L>=;K5CnRi?&t^3WGn*yjm8AyXU{uf}E856K+<3+r zFl}pZ@8IF!bx~x+`fQtG>>E_a>4kA*@&@<0h(;vLS5V+0bxDJCPK}?kjDTaPt2Io| z&S|s1>Q%2&Px>vldXN`|5v)Q(FtBk0ax^asb&2alzQ=9O{>lM5kNN8tW_)Kiu zv>A8bc{h$9KZMbf$50}lArPnhK{}e?+zHQkJquhNAhZLFK(0}c6h_5*E2p3>v0+2` z0n9{-xa!5fhSN{qiF~00n>KA#z4?Z3eFb0q{FhK#u8Q?arNq9$0h=N@eiD05+pX;D z$%6;5T(TN0Q53E>>)jjHuNTC|taWI32$>Y{&fgqCv@xwRR=vTovqWC3H=4sE&)Jni zJW|KOu`FKq{zoy`w-ulL{NLd5C-&p)&KuF0cp9}DyB@4YN@g)5?`S-OSh5ePbcX_l zm%jEdF;yEvDobILS?u1k7kA%tCq{-ww7`0FM?gh&&~g@mmLl+0L9)E5?2i& zxwjLs2+<6P`AiE_EZ4B_c`mY-Kg&Ab=bTgLoZ9#9>U~Xj_H;TcBm@WYV@o{lD+C{GQ+Qd*ZX-oQM-6lhLTTJs}5s>@$pdS5I%$HE9qn z_PPrV%FxsFIE<1CVGIDPNxn=iHuVx8g`C2lte# zJOa3`xd>S-h~OC;0@}oSK`Z&58(_0-J!S!+0mhr1kW6s=Q_M)lruMhE{-}%lAskD zQ=NwK2xS27U!EHyO@h>#o+lbADG_82l#bZgl+Xxe?@33ZwlEiOxo$tx8iWEf~epq{~t%)~#FDWbIE+P9`xd57t7HLxkD{dhvP@ zC8H3X-JSAT#A)zPBw!?`TWglLq_@DnoMZ6UtdXOvQVPe6q*J4u;RP8f)H%_dsZuO; zZ;s-^`6$etciVUi0USu3yMvfK%Ko|d(#vA+o;?caMUG{@NKStBES&`B{hgD)+@Zj} zC?`IHd>G{(Q3IBh7Ih?(Ud6I5igiM=kC87)GS$lc(q1CjzyF?ZMd8)A-qsL7Xt5S& z&YX+E6@vm#JG+o-ZWr^F$cYxSO2uPR+1%QAY0wCDoecde`js$9MThFh~T%Tr2>t?l|fqFgOr!wllghPJo|3)Ui| zLsX^!C!q*DM6wk3o_bDzvlX*GbujC7)%(Uq&PTPS8gG2_kH}S3hXHK1t z;n86!M7d5^3+adS_gA`4#br zKm2%1PtV5SK!3dP^>@UM9aqG=-}4^9`#rtAv1-lgICSuZc;9<}A&wqC95254rZ{u* zSp4?y{t*)V&8cindDGJ7G14f@#=Ry7?sY8;!A(@({a&@-ygTX`lk5v-|UZA8c&j>X$mJi zpAzjybn8JAeFmtlhjd#-}D@`0TKpdEej)J&)Htw@*W$TB^l( zRmGf^|F5s-Cn9G1t5JH>s;KPf_E_hZdX$CK6ynVALOi^yHSYOQUBpiITMn9YsfX+t zr;o9y5fqX=Ci1PsV&L)ULhQi%dix|~M*D9joT_apO=~51!x20ANG)gey7VbFZd@N9 z|HI#lsmby9rFZ}57(O>1ecgkxZo{hh(bLa~Fo_eqaG&J>ggvM;pZe1s{JMTA2cKF3 zvj7s`^E>RTW|u$<2DqW@&xyA=HhCrrdy&tlrp|dKA>eHBALkOtn4l_mAMyS--gu)* zTV&}#)SX?OLi=!h!24Ohfc4_MnAljAwrQPd2MknA=wcMs3_;qahN+A_zY|dfwrc>CY}>($}h22`0@Mh{$>KzGD}=eIGhz@fEiqM_`sgnbMTO6 zr)Mq#fe_4cB3)XN4Ee%#b)Az9C?r674X}dIe=o!be&b`YW%G)t&(B1yJ|D3dv48*b zapynXsqT>T6XP*8IW1Bo*P_~|#6%M5Bvrxf&|EFbQ6>h8|8je$x+fA_Rs(d(j`C{@ zOY!2D+!C8MZql$F^c~o!^aOwTOJ9z$i80lsbkJZC*B9g0|MM?JUvEXd$m8cny*y^iJELRm%i>#~`|0@EJGx>? zBn$U6dorOjHQFOfEj>}Hv_-kv8RJuh_{sNtDVC~hVr*(AuDt5%II!!}{Dl4E5p(_3XnEtRXuY;CT|*;Uic3+hlw$wk*|_VmY8*aa zj(z(N28fk{0}K=gxL%jWff&e(5UJR|KBUS3q~{OhY0{Z%+l5%SZbKYDepGc*>jtgwn?IyK{iW_vV}k5tb1bIok_H!;n37^lgNtf z-i)+auG-xayhpD2ldRB@#93#bZ{M~}s2$hCS%yd^xRkXJiyuKV2QxVSJYkcw3~7um zDoCaT2^d`9?9-=DiX7e7-)B)Yr-)H(F(Hue#SutiIvMh%l#v}eYX;H-dCm~A9WAfP z^HsPfjhz2iqo+x9=7g$B{uo7B=~5tgv>-d1vtrf?XAJq7GcLiRlqj&S>hR!vqgJQ^ zLhzm-5c+;bMuu&xWHTc!S=AQTtOw4Iu!xdTBL_yUB86fL=jIlpQl)#sIt6s%eEETc zG23Ww&IiD8;a$kQSqFCw&=PDiCfPd5u5A^UnhD654m&bD8bd1wV{XAETx(;He?@=pXQT#OcEY^b|5Ur}Ch^{Hl2y+;a_-}`& zQZUj&Ny6xh{Q#UPfoS^G@}IdXe<_@V_+z1Q)gwT_*}}@R&eJz z(3RBCSyuo60iU2zWxX^rCG8KKzUAqx!DGE3&QVKrFfyT|Lu-jo#&_ax*~bKVRwJI( zpSfk3XGfsn0K!Q|bkL3f03ZNKL_t)D%4jLT(qOc#t5Yh*-QW4gD7@mOFKcjkfE~a0 zz=P4#+byV!1IFS4`?1Mb@JwXN8EVduG85GqNKp_CJ*{ov%Yxa8ng>sPl!YZ*MuBl^ zX4-QZ=vHVW>u*VfERX{82gvN%Agaq&S_M&EbkQ~~#Mt=uq=S(}K)O16;-;H#k@Mi$V-&e&YW-~JrA94& z?wvocVOk0T>y5bK+NVwb3 zXFm3lXeo5YC9nN-yz17S@#i02715YVa?R-(>Ukw%KoR5wht(hDDh{CdiIie-q3$|z3i1pWr;)83Re(>-kDlPF| zk3RZn6GqMfr^|T+wGLhk`R6VhXSvxhx?GuMv(1mdux8X_WO&3f%$mrz*bJyKbgl=x ztbk$5yrmoz@7Q^j&g%2eKQCv@6j9cKubegKv*2EQv+>=+Y-7*Y@VRpeg1H~MBt(8p zlXWO}Fbs~*@9+0OJA$qjpyIL#X50(%?-_C7Pwp{G>t;mHlM=~xX$iLuLMGpNG9{%7 zw-)1IIy-2w#EII@DUgy)GIHRcpejNea?OzQ2#~}BL1_;nucYuj5?h0mQq4M-Ehs1A zkh$l{@d?=^91Y{lU$bKev&h3IVt43LObj!tDWiz~UTLvTp2 z!G2ZwT5aVQOl?i&bw1k!+PUaou{Ng0M#MG2F6VAGCA3L2&AJ-!=4g}WbyhnT`kzWk zLYD{>@(hP0S=~$!@X;W5C~+!DGQ*8^1-YTrp$p z4jg~h&6jVNs%T(^+6R(j(zU-(qC6l*aL%nMveBh=zjEC4ar z7M0aeLqBrlNIVT3JT)DY(^F})T4P-s?EX}5w-40Ouc$l)GuddgzMnSZt9D1;8?`>_m-mE-XG6C^-R>$;3s2vKEP=4 zLsDCqH45e+F=^aiFtQai!G^>NbYzdpOljk4fv3PERM54O1;$dZy?Hlzx?aTe+-z)E zvo>zL_L_L~*~g<)FUJc<4#y>zUM|D*%rnnuw5^@3ktsPUnpo2;lf?1T9!C;ba{y9F zAeT{qM5S~{&6}F1vjzq7mj89XI&gk=gc#rK)OhafwSe;~NQhR0B+k^qoDfzZj5CsXhrf^nTi0bzTl1NXz{K_ej4d%g+5YhCjycouK~w0HCP@HEJd@3{t0 z2m%5EA(AXa>Oil|Nig!jJwecv@@EAb)uzBvnTEH=a{FQ`1F#0(hwki=(3J$&JcEL> zrvYwBtHnXavH+V)2#FgdvaP!(8byJ>v`imn{5wblnfmbF-=X)xL#Rb(t}l2PYaP|(YHhk<%O0~^mTSCnCR&0 zNp(ewDFNNFIe=xz=Aj9&Yj|H9K-$_WF}QL-nf_xBe?Ru@eL-^<$dI!kY}&jv)^A!DD+dOmt=cYFijCVs zIfvh&kH2AuFg$W9KKQ{8O0*?E<5%8xYuxdw7pojYKsG%+8NdHWpNo;P$yic%f=M&1 zt5A$;H99-p>&)-ma`W|Z+pRBkR?t$4!-rppeFqN2iWNg~_0>Ct*pRi{^_}m;6Hh!A zx8JlbUU79jP7N=`C;skueCESf#r(|qxcHS{iJy7LFUQZnz8DwvodZZs0YV~SUNGmv z9YA!zaNygcQt6FKTaOIopZ)EVaqp9}(P-&3FQB#%|NhYNSU)}q4Cl9HET6&vYgiDo{v*QMolO^9=;+rxCpv zv^?2W=L6VS!BA~cr4O7Z?>9R&YmEuD!IeCNf)0tcs(uG2?(ac& z7n@|p-0hGP2cAFojI-8k2ucs^jf6;24prAzZ8~0eZEp;8w@Q;l1CJ`L+IQY(I198q z7`){{R|Gd?w_m+?Z_E^Wk_JfPc%@V0Qnd$)sa(KtvNRo*AV?h@ZIlBM(OQV}!z1Fq zku*s^f-F9%h-y+HC~s1a)Cd7(_zNC%lx8rl<%A*g1XBOoh3biUHco!#8I{X}ok*(Pm14>1OlZugTSn46 zys&9_nxCD6ihJm8SUEV@poWGaA)=*bf-%~0<(092|NiEzce9!^OWS0O6!d6AD9TBF zu~|5Tf74AQN6FHtCwsmYYuBxdfu6otziwUh3=Sp|qAwVSJUDJhuQ*wK6LS?hlA9UWZ(H>bO+FDk7bA6+eDbW6&9 z9)0u?NzBeI%&I1uq0wwKFTLcdST(ewNgj0HwuweL=n?E%D8`L1y*=Ld{&&XI*szFy zB7+qQGJ+Wzg2Mobih1|0iD6*)em*A0rsDMJ6LD_%yh;&s^R!tdW_*Ktv-Uan*wx(= z{evr1P7r)ru12*&ZM>*f(@GTsWQYkA2a`FGgjqiIr=N%?o_tmY0wdeq*&V<2o9~Xs z0@;cQGU|CQ72=oQ^WkXJle!uip|~GQv1#KP9jeju6EQH*760wGKN_?1knYL~ddLO` z23N+7*I%!U`pBWf@#Vky`xqOaR>uF%H(nXrS5L&Jzw~(2TDs#S@7xrnSd7)z|6Y9j z&;Bu9a?#<~K8XCY;W}{=iVieXap2pGDu|U_i9$<9lv|lL*{}Ng{zH@TiNAU-PEWT* zYkP-UiQf9y6VZhZ{yI65;%JPybP`6TT|N|`x@0k zXGqrPcQ$1$cAPoSB%@!n9m`1;3vu}+m&UWZcQvO0qT*)*Wf&C)Yy-Wlosju11SQf= zNvU-fcHvBEY&66#jlFdXGD?LqTB_w*HvpbX9$l>x8h!YQFosjxvUy9a92$sCn>M+= zN`Lv{V(i|%H%5lf$EsDUlmUvgC?P7hawzq;4&{36A?~Y|00MP1(3{dBDv-64Az6p3?$Zqa285JG|07Q+oWu;sl^Kk z$wD|;eJ`~zQ)Zxkj63Kt+{|>dgyMT~Nl1uqnsCc?^8CqMvmKmew0NTsSFZ1j zt5*YOQ&zFQ1V{xs8b*+;Lm_ZOQppZbmx_h>+kZYB3w5`ZE8s~pHl(eP+8xEump%vq zgF81eB(Fqhe%``&X*9U?H5hbd9T3*Oi5h6V%+;8mPb#-bs1Ht<5}kru1)GDnaQsQ> z(5=Lk=pX1;2@XFYf+IF}ZccUwX=_H;11FH!=Kby(y%BAkJlD*b&IH?x+~n!4d4N-v z0s!6OOLIt=qPc(+JNIA(Nm?Q4)Y9yw6lAKEQ6yiZ1wssx)HL=Ym%ZeJlN__BOFCeK zpzThP6u73+T1M@b6Ov^Cr~G*;pC`ekd++{66xyn-4KnV&o?aO=vgfO=+!3eGot4%) zY+=nmPcV)z&f*Pu@Jb#`BPmI-pS_W3pK<-3I@WS>#^Iy3*w;Uxdhy0Bo04LfXSO?- zau2vRII^`fOq5)T=l37bL(OedME}aZBvot3p9d(`XEJcPC)@7{xrYC9rmRdZjm0zy zV3N<#qlaW92%e|~=c#0wxW(qXa>vdXTCu`B2t|hGM0gsiJ12Pa`MG+0=8K<=mLen| zJ1|B171Z%&U5k};DCLAj5qOqrC~Vb5U=y^IV0<3@!kmYfmF7w|{T^!{7Z~Oi$0nk)uat;QM=f<0BvZWn~r% zwKv1iX7m88fB`g&a3qU+_lYp#sf{rex2u{e4BSUmBg zr=z!jMci`JO{$4L^zei6)vtX!%4JAprC2?*I^O$>KOV<+-xZ(z>QnKnZ@WIWtU4d% zLL+)FeSaJpEl2(6U&O}lqp1gZS))L0N*D_!M+y!$ajp;!kP4-C$v;=yx}pqgzgUUy zKf4h3{b(Uho*9dUef#1adk(}*xg}Pvti)v)(|_|tkWlREh|#ycDM~NDIUarV@#cV( z`yQ|$PhWp;tY5b_9)9?-SdyZiOA=fO#z=E7W?j0<^;IEC|0Z*wbb}xjwOkxNj%V-Q zz4|=%7<;k3wW^V|W?3g#HVqoe%7vq&V`*THYv9zV&z>7;Iw}H}$%(0EkY|Q3L`yno zAi{b5bnX)=Rs_T3+y#!hklKVaGvbCJwxqf_0Mw*&_Y+Q3GQ_DRPYxrs@m+Q06|r{R zdfnF)2;EXWPM$PxfF$GW*^LF=;-35b)_cw1s--sK$vgluc1OCUR7W;uI7Wto&2^MJ{gRTkpC?G^mq z*nkD!zlfOZ7TOS{KI=IPypMjK95ca2hM=2JbebZ_@AG?eGblnGSh(@2)WglsNdzBeA-rvv}KN&ngfK zlIFQcqFFWQVGNBlm$c6s9gCagtPV&MjoSJ}= z?fR1Ey0p8Kj=ku~y@)Vb$SMa0Sz9NscSh9mz^-PA5ab}0-7;UyLB8$0B`0z@8h?O# z=7Iv^TplD@B_Wo-NW?)03yBAkTNpDzU4&FS_k0dj{zyoz$^~jcwXQ|hj_^2Xp9`UY zX`rGxc!~I*MVJzrarbw>9);Crk zj!GRAI4kz1(1j;tfd|UZv_VzW^i)9zix@nzU6{VWTQHV+KRfc&(vdPIN6C$tm>iR% z$*6&)WV6aw8o`;Atn$2UYF}zaN?quj7A*4L`q*zq5r#PR$|UxZBPY(4hN6h%=}rvRgtZi+ zz&f}!!=p+QNiX3jDOgL-qsXE3Y;`&~AUe5T2viBQmPtQA(*4RHKoQ7RzWUX_iF2n< z#lw$07Oj=m=p7u0@zJsPtrwK_=z~{~n8+e|v z`^}wMdDO9HK8TD4skTSm4>+k4=j!qKzuzCv9G;7v(+lz9XLiS#p00RpX(FmAde50#(w4}qxPcfWA~oD+RyCy?>+cK8DNw*SFc_fKYa8_`Xd#j@x^&?4?e_M1_^nX zOm?n$CIJs$Qme(H>d{#>6!~yx)HtSMtXsP}`up4B`R7k5=;7a#vCzJhf^&$YFuQT~ z)a9Aj$r&6UN4vhLOa=z@_#{2)2|`WAO1z^IMtV6?(r_Yr)|+zyoWbScFg8FID8l%l zvdJ~jg2lh#u-q}Vq_%3E^)&Y+XJ&&dR>YN8TrQMtc5Ytd$8kQ#jva2+ODD!BrKhlE z>sA$4l^`U-BF~(FGaGhi?Z!QM7ShsBT|?42NIWVW0O$mc#{RBCJIu6&Nk9eJL{5}@^oIPC9`I&84wk|_#E~H=TvB9YL)D0gPUb-7qxaL z+ndn>ZpuT8JeJwnzDrK5wUCv9^<_vlrl%%T$-wpXAHS|EN{t0^GLrG}J_St?#BPMZ zO$wes$r^p{$rEvK#Ko3}J1 z=n{)@)fHE&UE<(D!{OcCy~@PU1yH+9nuL~(an^c~b8%mzarB zg7?xUYLZ=2t&rdYg9;}ADNXL5jq8V!I@k*lJ9l2MI^(zffOTieGxq zuf)(0tw$HI*X{0;1ujG**VLPlunnC9r{y^g`Jv~4Er0J&-(Tw7NZC+knX?gR<}6Hw zp(Z<3>0)*^PMta#pZfHtV_|+qWKHgW`^DR0&+gsvlW%xqy!MWl#=GD1>v6-4H^t=C zxp?@8&nhZiw_$zk+qYMBL--E8oo&(I->3Gaojb0GJ6`)L&B=K3sb^L4xb5Yy&;ot` z2j7o>_}1NOxiZ_iEjqd?@oVpWPnn1+v8BDNVgh(lvpMI#N!9k)ictutC%yFKZyr4-+O@NhhH zye}%>d?c9Y*@WMsvXss znVz%rY&2ru{#|m|tOu_@dE#VTv~`PW~0Cp0X!oT73l`dFUV=T1Id}Q zR8i;W^xilh5(tnjIT~fIwP+WaI%E?BIVTBcY@1OBtKg~rs{u-Gx#s(7TY82`|3Tek zN&kTNT!a`7l%M7|sLc>^TM{PYHF?eC_{;vRWwJD6z>2O(6Eqc|(S|yw?k?Fuf(*6X z*2K4{O^?M-+z1LvCz|Ez(VqcLz}B-KPzGx?BM9s#$aAx`dVJ-+{ZXiRm>O_B3808> zlzVh@S7FZ}TOmo+O`z`ILGm>D|ZW4+hGE31+p8Q2C9FP#Y2SObCU@j&%T4Pb@SG^{q{Rz zZ1iOO#b5o6x(_gnovjdLOYz#*-WoSvb5;De|M>^8VZ)~QPw#kZeBsajG+uSx>X@6F zi@_aliCI#493o#m#Zager7Tb z?%N-y$7jXfU$bUa?AiOgh+v)+=l~N3M>s%`Ajg;kOQVtsBIUUR%`@$;BvK*94kM)l zU5w~#EykL4o$>sE$zWKZryU|qYh#JQXBFtZ&Z?!r^F{~k2r#-3w~ib+*=%u?;8%hg zRZmU?vK)A33E&*iWM&cuR`uW%A#)vM-y|TK2-!)EpO(R8`(P%ukra~v-2!>twbuuk z9@mP_JuQBt=f_lXq&%l#VD);OK7Bg2Y}%Zr7ODw4krLB1#l(rClZrVB+&9SO=;)|y zgG!^#!BP(J6_710Y1kYH3rHK>34%240W`Cxr+*n8n4h&;Wa{?FaJDreoYkxCZhk?W zFY_jBm^ENZ&W&DmcNb6+FtN_YnzA5*KHWV%Lfgc5N+NRz%SpmIDcE8wm+gcnJ+fKN z*MJGd~N&h$Nk zoiCTM%ny*T)gq-@lh<$5yT!jGms}l(<^#kIyvG-tV0`8{7leV#LDy z9)4oj96xs2L%ph%=x8^h zL3XXqIs#6S8{O8e_ex5fS!L7ch&u^07bTAzP^m)gwx$I%xqGQ=LM@=F9al+v;<6~1 zNa#XF8tw*3*t~vyW6MRGwP;U2{j9PC;J%zW=Lk!+Kt`PA83Jj#R|0gJy{gTHhMlX- zeMv0V=7p!sK{cfMQmkIJMv)!PqR=RcbgA@W{i^=F39$>8Vr&YLB(p)&(K>p1W_ z9DDBjZ1N&hR$Z1d%}(D@u-iWPA~;}Uoj7q^4*GZy*t=(M zv{fqcGe7m_*sx($eE06Vp_{SSOE zo_K1nCblii*W->iyd}Q*4_`^aqRRwif#^;A;?Mtd+@}E97Cr?OG}KLi+JKcd@UC1g=k&d6*o?v*WN&JabYRq`N5U(t;;Tr#ksNg zkFVPhZ+_*PXoiH97AFwIibX69omLFm~Lc#cIT7+K_m zy-d(d&>%*1omwh93QN;gTRcVa%*a@rADz(NU1syoH=RLd_v3SzL&BC&-#?{^29m>b zapag0I%h;CKN;FaBnsJUBZ7S440Em7AXpk)Aw!lqIY#+t*;L@uXejB(qAp^v=kc`C zLUBis6OoqKdG$4d-}89}N;r1xSaK?L*$os?8%v9_A0kYr^Ox-t*W1tKko1ev?r z%TgbG9r^mUrj|q&slp-gY-GFIK};M(Fm0CiVqf!KPFU&+1hJ30zvN(j#;r$zqtQL4 zU_sL%QD}@t+_J4bddqXs-Q6xEhG4qXVto;U4Xww5%clyYC^r;J@%VwW@!ScL3M*@h z4}c7Ix-OC1m8>|{b;;RDq>?GtNeJ(vOCVR-m_oH;ipawaXkAdc4dkWxx>c8O7m%uh%> zf;3VC}w>&tF#boKPa zv(G#yqrqX8+^9+hC8-}`Y=I&?>Jk!`N0{aoBrTHqSC96ibsIz}FObTsDFOYLMXAHE#fWyQoCD7d^~Pc1G*3Q#!Y`5|aQ zlc@w_Xw#ZQts;4Vxk%5ZREjxE>bbti;i1 zAwKw_--y=sh7`Fn2f?I{Modpk#I9$biX%sk#@N_+JhSUSoITBqbQ548l{#DRilNo3 zV%>(dv3}ipLAh)+j0*;w7ElgGe@~z4o{)kRv8Qs0DV3H674w>*Sg?#2Yw^u*d_BJL z^>2wKzjf=D*t2h+){qR~WiP!k+N!0v@4iQ(rL7u+0|O$qA|p!8nM26;LqjVxAnU!q z{PXebu4m$|yC00!q=j!7t)v!8kxLmli>hU(`_$`X5R3Ei6F>3BxMcel9XNOpU-{dA zjJB?>_}pjzI-dOJuSRd<@n|iRwUCW?u0275NwYXPE8~?28u+h?ESRsrP$r{Gu0<+) z14b`*M{5Nl93;oZm^(BTkN@o5ab`tl>?|+F>bcoCG|AMuh{rZ>h*K}x9KZ0Ejj>_H zWD=p_Q7%TKr7b@HxBKH84^!IdkRXl7X9S{+VvJ8tYecqS{giQFY$0<&s;jm#DX(7; ztoJ!iqNsINZ5q7~P0d`0@u`_+Cdxgrj_UbOdJF6c92eZ8-o73~=k1KRcC8r{@#N{# z+9S?L2u7C)R5GTCgeL9%#I6@IBZhY}PC5(LBHJzc zdO7(d9iIbssRJ%@J(jxWJff|D)5P{%=yX^|0y`WdpDQ>%p=8pneH%xaU9w3;tjoz=@~=ke7C_QcE*s)ZKXVn1f`IIZgh z?tEDo&*$5TN>ZIoM8PZwg}qfLP6{&e7;ERx9`1yFH0ofRnmZX-gG}lKZHD8b&k?dy zjg>1`DInl|9Jp~WMsXE%B{H$JNWy#>bIF!se0;h|Lgm>ksEY*+1jvs_x%*l13?Hk5T-wPTzov$fPe_xv*eqeVQ^2MEbTLk2+`pCZ2I01I#0nFL?v_sQ4GXY%?ikdje?e282dHqj;X7IFZ>&mbzIMs@7) zAzf4MK;Qu)&~g1W*C7IKqpH@H1n(rWVU8>vAb=vc-hAtAcf>6(zc!XMlx8_9W`nU& zPo6p&`}gmSV~3B%-u*Acp68!mE1#3jckNwNT@!3y*UbSO-(=p6o+b_BC+St8kPYjPtsN+IY z`FeU(nvfLetb6gP*Rr|Ru3i~CF5MpgboV_GMdp22E5Z($AOYTk5f6S3O%AS=-f3#T zufOA!(O6oDZ~fDKl56JQyW6Yr<-hxOeBl3hM_jgkCa%4BAlk|pZicUj0g}oN^(Yk} z2m#wU7!+IyZ$ZY!fu_n37>tqyrJ_Wjfjnwkv{XF<|9^Wt27m10SpS1P zadawTvKF!K?bpV}U%Esi)fFg;SmwjV7;El#*YQSt^pnrTRE?T%Nn%Sp>lu_57lEMX z6|5OWvy<-Y>yFO$Hmw!t$@Gk+h^d!TgC)2Gy_#fZ0jj30trD<-C@NXpRKFGIl|*?6 z4A!n*WtMwwL4DxtK2R%u=fLxa%&g8vBnADvfsn*hF3F_|qhOwGV5L)YJqTRnG>Wb% zi|wC+c3R^)JKOd7S$dYAPB|%KF;cnw=J$dksHBsI8?eZ4bV12%3(FDxn7ZSd}g-+7SdS z))&+!E`5q6mrCSdgbFS-35{g<3i9SX`dE;(#D8q#Y$rUR3&)Q}4dn$;9Il_>juI=5 zi0@U0Z-MyeEMEKr2DD92YkznmryZniY!YoMwFvpkZGe@fnRwY&f`Uf$^mMq)A)bgC z{y^w;VDS_H8ci<6#B?pb@xv2QETc(ba%T>ZSjT1`zrBsha@5sT?n@HUs+%X6+&T<) z-jZFe8P)W^EtjUfkBvOohFe|Md>(g^+w^|4$(s9N!e&On{G18?J?rTD8?H%RGL1NJ;CM`o zpO-)y3ZG@lu2B+kHB0Gd!aVOIw2$+Y$fR!Db&$?AX2d*S`-Kd|j4ZI9GuqNbQ?d_F zft*!K9bBrrVf#f}g)RVR%4s5JoN8f+iR6pR+5$x1%y*#ASt?ek)hNT2`7rVxnH`J~ zHj&ZJJs$!tmJQz9-4g?S13K_yw$w`Y>y9r^w%V@nMo!W)`8BRIThpMW3g}lzWDPm{ADz|Y zorl5Sgpg{D_|s2+F8T&LqmT%shS+@Y`4z?|bA40OWAO{W@GCNqWLpGBphqvhZbx)= zwZ(Vt{y{7(F2wo`8)EqEIce!rAD1#?sT8ekOe|#3OIx&6D=|4et-X?AJ`9_?KmPT& zQW4D3aH91ax5jllE{X>pxId<5>d`+ippm=VFWMY`{K-F$&wt_nibo%PD5?wR<1Me* z8a>Q;E->JWvIEEgf70qhV1~oO24XM?7+uI+L5ulC2exrj^Neo+kk++`wpnuLYAM=HLlHPCX(wL(w4^Ed8^ zBj*w6vO|)38$1Hqw*ny+1kK)=SD_j)#^1KDV>ltj2jvY%6inw3QEwY zz!S%q`7`-UU{}|zUY!PzA>h-V5TZq0%jr{RQwx+4!3)oYo|U=pR?Bj?XI5ee>zj9*+OTx1dwf`m!dmpcvkthH;_Xq+=GyW%-DA`TxuC7Y3>vzmxY zEYJ0UvO@TDImDSbL3Hj=V*dbltLrJT_vM^Yz$dMXguwDoCIc?U)oVLq+ki`qmA0x{ z)pbTCOayYp^F*M_cGc~q5hq6G;@+puMzzu&g%++cJ9&~t&z4c3gkMM#4K;>1wQutr ztbDsXFF@qSxjF4&+i^QP-rGLKt?=1iD#%JQ-udq&7}%k~fk6dJ(hErA$nC$(OCrHx zPvkm2=o8n2pCVD>EG`Q5bw?Rr8uKp2UkBi=;uzQ zCiBtvll^114f(8R6hY@bp@&Vy#lil*2LITahK}Uuq%{#($YxY?PTB)*IiXHJ*Bm0G zJ(&m=7e-L|@33EU)S`t?gb_im3_&Rr)ejDAi0UHn{PfhchOI#OK`^EX!=yk%h6^}O zLsT4PbC`13A)^(!Opq7Hj>;%PuGeLU%4^sFr%s)UHEUPLGfzM3zHEpdE#+9VYIR(7 z#TCt23*3t$G}S{be31z&JWw6AGVNv<1z6`x@f*MO;pk-A8V5Kn8k>QiPmNB*+2OPC z<*$4>o_>0lAYn6Cl0(nJ7%6Dr-c;Ld3f`E-pADiT?|R&H!>i&w?|YZj%d#dzD>-Y(G@44O&}3kzD?QT;a?EFPM3KBXLxZt2;)4sK?$}8 zq4=FoJ{tEwU649sEEQ#JKpx0k2YY*iaq5Pqm)s`H+Al7~_$2MSZQ^+l;FECxiwg}) zdzh(qsQKZjtPNqKav^etwuP9{jiu-x=#_Jum_YJ-Mrg*=w7WQR;LF2MW|#)SIQvVo z$BDtO$$Kf_lM-DPf>~M;X_1nL*yUu`*cVzm%VdB_E>TFaD$A!$bNHk zde4Ig59r$Xd3Kom9Yg7nz&4nW_;CDgAI)pFQM(?%}=$T}xU zI!hFRG*`icng~QRwps0xtuZw*m3Su%Nb69$X(nCgEYCrU6*48FCA7lRBpDQhW0rj? zgb~@~49zwZwUpPOIRGD6w+da7_?z>tn#>+2m zk7{E&+Pm0uNHK$mEXfCO%?PzIe9Xkvyq_Yz`}m-8DSWfEsKf;pw|WsP_u`AmM|_uayS+S&3v?);f-!u)qVz69;%AcAXR*b4`q z$&CCw!-+S&=*6zZC0+GgAIor+SbA0JbkP0ER%`~5nqhSBX{fNj(`%t|RD_5@6&=?FX*GljR2@#`< z!rZoP+hWhIXPatkd6-BhXsPs}ZUYBGe6Atng6g+JD~Dokb~*-!HpHKN{1b8ekG(V+ z)aVpo&c~(=n_^Y>RJ{3>mq%xX*%C%^Koz9O7R@*R;aT561AYh;s?~Vvt@lQ$trYVoW@5*i*G2ogFHb=Nzn`G@geGLdmk#0*JcUNg z*4D%ufB72`mA+U+>UOCnXjI}eiQp$VQGz+uI6FMz=ZVHcsTi{})6v&Apa72Rf!{%m z{=#mZjM8K@A(se1DL6Ao{K8q`JfA*&wmGjvwdySAou|O1EJXJpkss!JB#HG*W=y22 zrVvyj%@ORIRqrzfaTTNshsiJ-1<(>gOT@*61v$?hJ9fnSHS1$+Y*hLOpoOQ;o@$P> zW{>1rG=wjdJ*B6>^u7d}sS*OGp(wF2C1heLOdN-T1E&Qf#YK_JJP;ItX!CU`%UQ+OWd&yR?gMOrDj z;R~n80;vOmGYkkcrP`X1m6B#25RhdDilcIuhY5@zH5&eucowatrMPu_B^q?Yba)<) zgp(QsJss-4g0MJWGZM#r@HJnn$JZV_8uLqZ8yM~4X9T;fi{-VG@-AmOi5eNU&T|Kx zrL%W=hMDWa8u5Kj@c5qKFLxCmD-oB35xpSuov;^x&x^thPnY5%D34s{u7Df@`llBQov=afJEd|M0UnrI9GeVu8 z`-Ngj3JB7fM*b=O?ophbg?uFP6dp&dRo%Z|>rs4dhrgPZ7tgRKOk zScnrRPkC0ioEh+wBmGR0W1;gQ$s2)-%Fa&g-2^GI@EC2J#|wuKim=Fd+)KA#8a;iz zViBu{G>LL#C&)uSbofZK^$TJTn=K#ieB-&q!0%Y|6Ke3U(E~@tM!w9o;A=G^PpRa= zVfg&#z9@%40G1D~nC>Ziotc`7-}umnVkSvSvtCDz99A3N#*G_e@7~=apJ7OeraKW( zDV3w6wJo}P+GG6ucwBqKb@9?$Z;em>;U7ldiWM<7ij;6Iwr$(4YuWYOQzBmC5&52H zisWgEMqrNsuQg?lY`f_ z)awO*g04uP-cAO%Q;xA*l#{_wa!$#D)Yh7eQRdp@Hs1^>^6%>ODbm_ZhXW4V_=U>%uV&ooxa9b0xc2jD9Ap~p{l!rqf=tFvh!*qjYv{Me_Qwa%^{ z?Nf=Q(e8}ox4JH>9`duW7^~L|2~or* zBrL?eQlHn)NMK5famxmVkwx?mc4_|*_<^>mWpln3^EG#MxE0Wl|L|BnzVpnP2!z`H zjRp(BAbZ1!nl&H1P9_XWg)tLK6Y?Z~0BS=?u7=2zNrNg!r`ZpFejp3BYcAtj#E22o zAkCf->7)Tv!AY7wzuB1~u89K_cqVr4K6juJBq65|`%3qflUsri5?D&&lv#7Rhi6I9 z>8=-R*kFJ4d6XThm1rl(Nje}Nwse6*UqbT)!tp}9`Zc%7j?GNf-}=MknEx+9ZBE_HbLTnr7Z(gVoJdDiF7q$DV!rwL!@CZn*x&WH7zyS4Vz9q2-tv|=DMR1A`$zG_kB&&i5u-)sL>m&* z9`_(CENuxxjvVY6X1yo$CufQnPVNW8F?{Z9+;!K3@gIKj^)WU+<`%q!jVZ{`Aelm} zU$Zt=ch%#LS8R%o%DjRB+T@&3aO37C#L|KSPPht%!a`7Pl#Wd5=HoSVoM!EK&-;MD zSB%Mf#-lN{80)U;iPCigO;)hcu2jEI^2k{xIrmjtc)1wGN+mx1m0j^qkK*vU!~mW^ zVZZGmQv>SGa<9P9o(W+L5aUAzM<$eO(tHfUGC6?ELBfSXVHqmN=-|ZjSw-Z9KwQsr zDVnON76VEIsboxKd{ozEU=sCl&k)F^1VfXwc6qQ5-8rfyC#chV)+(UWlzn%MfGgv z<8*Y;=4L`7zi(k96QgmGlq%@%n4O2a(5+|9{#IE6Iq%dZ#C5q0WJoxVBF+g^UZ1=# zazKXzzo@$&Tl#8Itk4Aoicl4Cj%Og78>N^P`e12lXWA|C)C;5W+;L_BB+Zu8ao|ig zR4V2UCyT8f4C ziAR)Vjgw%S?VI<+#jsY6X9OA>gaZUk=v7m^JXYLro&M5fQ3C!U*;_&7=NSZHzQaYm($sm7o@D`;*tLG+Mjyt-MMaGrRrD0RnFX=Z zBE>9rX|elZ zD0iERC0BDc!8*dkC#dM@>W+@iuITORmRA3XW5=Uspii57@1E!4@C!%Ohr4m}M$K2i znC;%XxA{4_uGWOk()H#Co*Au(tT6gnZL3+U;eyv@II5+kEqZ$f9hb%( zuYFC-)o0=hpa1I^9vzQuTeru70|zvgRTDZ}N^#XySI6O_N2R2RDqJp;ka^`V?wxC* z6?1Itd<+Z>#$Wu!U&rfS_i96KxeSx*ZCTEiKJ%7R+;Hs`v2A4|uGriWr53UVj23l# zY$1o8G8ciK36t;?DlIq`_b1aC;X||}HhH;%fujUbmhcP*7KoM1-Ux(I4cc5e^u|$v z05jak+j(w>qkR*34-dD+J3oAP)CzsVJ;)q&f6gVF^BL5)UWk~QMhUQFNE(9?)Yu&) z7#&z9@Z!wf{$+-@>%5Dxih#aB<}xcMI5R)v3AJguUDia%fvC?3vg{tAtf18LmI*Gm z6s`gU@os8D)ly+rSsjdRx0g}MoYxw1-mxtZTWR^Eo-GKqVVw{V}n=|92NWABf)Khc~~goe5Gc(hx>@QJNlKQ9d#1!g(!!iAI%Q0F6-u7!{t&t0Wr@(9 z1oVt=Ahst2QP{_8uh}8))cN7@c;Vn-$u}=Cdj`a$?2R{ENkjmJ7QU5 z!ILVT06GxQJYw%#jV4coT47houKHYM<={r#ci;bt!q$zOMa;K|L|KQ6LxRyB=pRsk zAmNgvMV)I@S!aOAi-)Dr$7oTf31^Cqk&lJ^L&PU?jG4alFUyIi2#KtOg`|~>jaHkR zm%s#)zdC#%3hj*h_2fdohaEc*8IJzgv7^pXlA+Ay2!6&rWfZ}+9M_i=J*pmQ_OODF z1=!xlR5mzu`mBNxAn&{}^QLEwtms%*K$UA-K-bjghgPkMi!a(1DylJz#d6a3Y zQ-bv`#M-rMqrKg%d$G?ct>`%~4^+y*K6VScL;%I!Ccwcgz${T)hV^e4)ScXXiv7oWYXAxoRRZ8ILT~x84^}* z)Z(^_+oQO+5Z(O@RAb^H&d>e+#^;JLHEoql)w2r`<1abYtPkTP0yW&sKGMG3}ycf>XC~1cSl9UDKK<~n`8ta2T z2R4*|54?rvM1YlBCEb$gfE)s9-YfYm36Y`|Q@+AJLYxn{cL|+P8Lp+IvJ}6kSrZCg zmPvo?M$ zC73KS657F+13L$lO=crInk5siXjGbg~(*hIG0Y&D_#LkOqiL5ctTVFr>hv zOqQdjrOi_=MrT`VtXj1?R<1|7N4Xz%3kY}sO!OU})(Aa;22vQiN)i1?rL1JRMZ? zoRP6+Z3uovmTVIKQnx@dh`K((#7eb12@j4loKfc>j7JQ?ls!%hAwNGid``XFycGtSJz{fizo@d6YrZZqWa3-i>+D64EqBZ~+vZxZ4g5R7HZ5+_Vd(B|suVVz zaOxD$u(>4%FLYRt9ONz^_EdWt?RDl!;PjVKzBD(WS?X|b&UK2DfX2Y&WRtNDBFDNT zuEghY-I5uOP~b(IB(~O>?6L!OpkuqG>@;QJ*`C=JgBZDNmCwIAzbfSz?1;E(09!I0 z{e!)#oii0yWigeOGO^A9adtYp50A&;u@;rYKyvW~@Fbjl+S%E58!gP82%e4M>kv<( zZluOFe3#MKgOrvKN|L@vxh0`9?id37S+$CxWF!R;daXy02W#Poc_+>1sMTU(d_uf0 zC7TNtF_Qh((66$bx=`4G?6^UvFD&g z<)30H+S-lwE&sbMl_jXryhtUdmP*j&lob{&wq_D@wQ4e?L;(wp7^u{uyO$Bu3S6((U}-6W{yiJEPFs z-P!2q=vEg&Z?9o7j5?ci@18wcj9lmDhFBzY4Ja`%EW<;b(#(U}f>zA|1=)m2OkSX+ z#K`shal@mYqs~|Ee!w`8U8~NSq-t}-WoX)vkcdh}B7CBA1d9@RD)qHy0T^nI9=|-N z4ad|w$_2U4nfDZ%xeg*QB^5g!CgXK+)|ok;4}wKLiqYHM?dfM}_BernV5dq|!4@rN znkcv6$z?cq_#JE<9s`?aY+^jd$Hrr9d_q6tAnW=tMvIFozX)26x-uW?TpAoh8xW!% z^leL<+_I(A_WaO&IJIsOs^LM@Qcr*C114K>kkHT&9hGY&P7(^R#%aS!s$!C6M&Kur zW(HRbh&v)m4Q)FWq`U`|C4y{W9C`jiERw+|ljM6pL$^d>Yz5aUayRr(sp~(z;}_$S z?N^9{LZ`&&=tTVL`+qU&OBT1ufn%=AX82W5pJaaROiUO8#VW*5UrYSQ*WC~shT0>R z7|%Vc%&AynJ%Jw4GdIc6S_}0kBlRqV&7&17Wt_2%g$76=?j^m6HnrAC3!n^4nkx=2 zLpXF3Ez%+}iFl;KW*%)^D#wrZEX4bM|Djl_4w=xE0x0&@ZMWVU-@WIaG*Z^0WZBrV z$5FLppObO&g_FuZ&jtzy$(Ic}Ba__@D@8f_*=fDJV5YmAPD9Dz4&N<&X;OE)1XVf)B zz^slUwq&RrNV6D2z?~>7#TSvnd#Q-J3wt`#H8lkGR$Z4%vuEz|6iykDB7($ujfMM#jZzgIQg|+UA$1}6eJO?-_Svw;)Jmf&0Gn4mNF6Dv# zu*QgXsSBh~QhPR^QDM%;!c=TqS&f12vNSGK?ktqzq8Gh6N^M;+H9ZmMN5`VOt5X^% zob|IKqe`Zi7U5$p#ayi(_k8!C<7Kzr6jM{Pap2&w80hopY$0r#88RDp-ubO4ba!?% z`uhjt;_cf#fJL>hx!AR9cY;F zYSlD^WCl6+$$@kY7K7iS!wsQ@0VeL4C@C8QM$DuTl`RM~AR>vi>|mj_wHzx}tc+DF z2V>RHnrQ1_@*W$IcAr|DJaJsn9uJxK<63y=MBUVGxo4Qrv$GcP;GQtr3$t_T-yJzW zVqNj1B4#9npaH36GAbV=j2Z1s1O`O48WOX(5QBq5g8A9#D!;Jd%jTgFESkMrh@*!O z2|nfDC>ek-sXm$`@uUKogAC5q))9%skO@n1i)D|R2J_)$uZIUy1fs^RidO*XZ#lJU?D zk+@&lUs-n`L-I0aX`C|7-TL(yGX#}P))FJWIZ4hVr-d9s?nB{pX2$*Iv=Fu;oK=!@ z<(v`>a0ba@GPByf=}E@DgaA|uT%?I%Hg=XL#~5RS>S?Y)uE$gMW50MrcJ7Aqp22D3 z)G2?6gYd5elU$?cJacY)=&FgOn4Yud$Gpm+jJ!^)aFv%0FFRm1Q{An8WeK1e1%d|! zdPnwWzEg($Gwf~z2bpIFnYn!�Ub+y!u$m_oY>F<&pnT~Cih zZOKEya)vI+eIcyg(IS#wC=IMZWG)pf^CbM-bGgAKUlZjt_)NCg!#_wn7sr zi^bT`Iv*R?w2NE~Ii9cTz{Xf}*)7t%IDP7*o*e<|usA=}ICgpr$S~HgTj9@b6ywy% zQ?Y7jWjyoLp7`g7ABvy(>9<68cZY%=Y}9@CKN5fY4}Twpf!?0R#g|^@2b$ELo_qFb z8DNZjCfHKs!hfjQ@#DZ|?3UL1`sler)fRrH?Lqi4lM{?W9rg2#?_*oa_M$$n<0SdUtOHVIyx zofC{YK0X-Ms;41tHO)S^-~ zZ-k5%@+Sz$xpQabOw^i${(Xw-IaI6{a2RX7a^+C`)PHz~)~>IoU(@|Sb};Vmd*8dG zwT&Kk6O`Mp%OYp4a~guy|8nm%nQemTT~e#+ z+1S`yJjH}xt3_(&K∋9Ae`tx#zU58N$Zc5okcVV;|&>CG-}WHDU$KN$VpC<>dZt zv)&DQyd@pyfc|k<}Tq=$ZI8>P*Nic-Lk@J~RA(A(Wj_0`?|$iXfg682eJK zuC#V01wZdK+6OD@R^s)#r$kCbHzB_t*TE>_-aZJEX!<)_CQ&da!DTZ_pAvRTQoa11 zvbn^^$h;}e3ZuKRZQ~Q;S_|zRoc+8tX4Lwcct_?-Ae6)uM%z@*mNolLBIWb>9q~i> zd1E22Spn3(6g|CNdj9NbMqyJP6e<9df5CHl>^O^Y=-f;^eFCJ07G(#YLLd?c1&1Rc zG(znZq-7$Ug?}6{v&SqW?T!r9_*2`S#!~BW5V+*|3WezC=rn3krPFCZwnQbIBGVUZ zaqQTUm>8e(-UKa9B=wBWDGA9l2@)}#&lO^t9JSjk-F?wSshx@1$EDaIC%i@!?C5oF zG7%};qpUiqmf9A#bEmQ!XV2r(J?&M3dP3R#dF&r`>ZLQx`0pIRSjs$NpgrR1^*zzo zO_1;8fYQOX7r!A2ZSZWSWAyxp2=eT4Iy;Os(aP-c(|h(GjVmtQEHXF2*`p6V8Bgur z9Y6E7w?uabq6*)q3RGKF*s%R5)EcuzBS=`^r@IEN@JYI$3mG?=02rod3Due0H^K6`F&lJ0kIrKyy~ zyysA;21swN>YcP=a^S3lRh!4zBS15!jFxM_dEr2K2*4{dQ`5SBhDwNal6LUQr4MSAd`nASJ8VQ7b*yrgPVw%EIDg} zF`%B`BqXT@?h?)P%v4NI;q<44{$RK?xh@HluozQdK4qF|4n4o0%Sr5q{(*jtq{jF%i=)ZpPDCg6 z1`3WG@JhKge&ttwRcpO^Xtk&3)n?-(AO7`NSe&&iFu?#>Uvgkx7-yBdhw7CH-o>cq z4jfYOSG@csao4>Ms5HR$D|#Yc{gUmmc~xf=P;9Kt(g3FWHkx3*LNVxFPEyaxIL(^3 z=n`>=l{F>1Oom=6tG3u$Ek>nB-JC4`fM6S<0x&@!%8V@mrsIDwfKF z%Jv2Z2h@&gncFm2M%UrMJR3v>369vCXUk|{O{F%Y4yh)r$$H*v*Z}u-+jy}C841ud zN-@@#Wty`x8-XV0L~|JyL5qwK=9;!La?VE0(7H`x()3Sg17)dgTQ|kYlc%*$O`i0y z9`lnD@{sncQAB6Md^YEatW%?V7wbB2ZS4%}s;Yda`fy82tQhDQy2WU8`h90+CKbeD zKygay;!?ukS~^A@G>^bv`(J2AL1zW-mi1CVE{o!7feflNlJqD1KFdApoDD0FriqYA zbrc(s)dwA3fZ1MwWXwmkF%vrn=VQJ$A497L zm8f8wIQQ;Sr(foe=e@8sMt|AwWj!O35lWjLKx!c-sW4_m+N3DhY)?p^ zX(Y<_f<2-DJE4u@!l`wZ;1G=ub09MRM+geZR+4d6a*~kstaqU@a#Fm__M7`rvY7$_ zk|N7OyG_>5Du0R-pXqsb%%E$cHt2Mox!mo8h1j~fJK7;dGRc($wQE(ZzxtKh>nBeh z*KHH{@h2P?C&V7QHas#O9o_xW+s(e7)cPGhbRzD%|G{|0Z8u5T7CTKK&F8-BJs*g| z>Y<^=#g|;71>jO~R4JoK2F(vKF;B%=@PV~a_J-i~ISS9Eko+LbIyL!4C`ZZ!M5vjcS74#C z0S_6GnXXP5m)1^?rlnSy;W2R@#J(?U!l4u>&yQ-j(dg)TIaBI?^m6+_SXoTuvLv1X zSqev`dOX3IGT}n3UcD*?2CM^c{KPT!NTW5N8Wf!YQ`5@+wJ9?piuR+FNnspVvfSFm zTFU{bR*fRrj9RtC%w_YV+mQOKd5(Mz!G~l!6>ZZ}Wzvn>*@{I?YXmjmt6c$)AxEOs zQ>RX=zRK@FjGP6=B~vXsb0i~V9oMW~6UUDo7ptC6IX_||C_#!1Mm_rbAc;-L&|I_g zMRD70uM*LYwfTpy{Y^an#3R~ICJr)q2EIU2%yayvtcTAdP^47AtOFcR&U`m*SRZYz z<#_1PC!)W%Pb5PeU!%Sdmv8EgSH9%Z=;>^U#^OXYmgc0A7_>+#L#RceK`Bn|*;7%A z^k`=x6KaJZ2}Yk<%8+|uDw~LeI1{fW(B%!0W45XC8B2(0Gi%6(l7Mz(x*EU!2am-I zXDEM>%|+DI>S>3;{UruO6P0LsVxAkk8S416bJ{!qH(T!kCD~P74e!dKtGcUmo}TFm zJy|mfC})9ekdO!#APmMfd>;lQ0V0@eg2M;K-~>X(0)qh~2@6SpB0(bwp*SOHa*myI zsIFZ9+WXvF-FW@2r8TL$s@{9|o_o$d`|QnR(L=r_L}croxPg*>jip%+R&(4ACF8S` z@r`=?MqJjxzIHYC?>l6{*Byqu_gZt@OKvvXCLo+ct1Hj^R1~Y0HEa7F`Vz*e(}QSj zZWdhX4;5d@u@WZ|X0gOZ^|-E8wFe`T=WS?cRNN3>%C)nMKV#J&5jOHAc(7!en$S?6 z#@N^}W+unf&lXR>-CM~av&iul%`(O+N?(C(n}ysW0;MX-6rmanmAsd#283Jqj$Mzv(C(kI;0I@=o?{5{otp#2n)j>^j#$Mlx zad~-pPr8-my5c_DbXI7a#Jwd$))sN&yc$^~N@dBFk6ldU$SLVahp@Iig64Dt2^Wuf zMFW?-36)@-3eEBH39T{TX5yJ;=$gIPb1%Gt4eQtFdxXgnMUTbt&;RrvC{_&p=Lf#= zjem&tre?h7{U1hP!@xk5eLs#?sE-0*bd(m!Hp1w$f8J2*AqSAIOA0m{pO_R%;H_-w zJ+FsA&2B=S^c>fmsJX=1mt|Xi|A)TNQRwV-wB{ zp2m(RpTNRG4(ryfsli-E_OfhV0o(PpJT#>QfxX6JQ3p8#ieKy^?07ZLKov<=&V-tr z&xNllg%~v`tXFzH1Zb?%Yt=sY7+BvbIRBo z3M8Y(3H=h`Vuj^2pmlgH$)FnSZq>!_!JgDt2&M4Ff8B{E4>IvcVIgPZaC}Zi3UeCl z3ic+0YeF>ETj%=mP&wD4NMG*0*GyYri z@V@$q1DgOcp&`0=uITNPo`c#<4k=lJgB_~E#L!io{*Yk7@bJSAqJQ-&^mKP(V%(Ai zA{q?5OceNM#uBZ z?4BFH!u%SR7k6Br1sY{VY%+qend>ZFN5QGGP+h*i>2z44EyFV>{AE)J*4FUVxdRyO z`6#J%XAngK$-fZM)U3^I0?*p$rZZ$~)yT5;Jasn8Ys8XWau&=Qz|auB4&R@ztAdq{ zOGnTp+-SNB*1ltMEl&+Mif{Jo7Sq_eBw>Gv-{Od|fhtxvR?*i=?S-I81ZESXSQ>&Cb#cJlHXpLuRCT3ed1a%G3a<;KRR(cIL49Zx)q1N)C66tM}4 z6@5Lp=IV>_fB)h`2yETFMcxfGFX6#W@))xb_M!=$N`jI%)ZJJ<5Q;=_Zk4|$nT`EG z+nAO?@+PTu;Ig6row32?MNr*{8O#t{68Ids#EHIDF`ktg@{<TSR5rvpIvHIb7sArZl za5AX!@A=t@xY&9yhWE%YWlyVEwR$y`1<6bP-?xUrKx6$Bq%*dgEHDYz_YMH;*W(`Gaf!P;2e*p#!K( zCq)nz8QMYU-jUBwKA9PpP5JOk6A+H%t&vPe!e(3(`nQbGLP8tA*CPaK+2|l9!I4I1 zCZyy!7~HqAtuL8Fq>3kUtejGziCh_}k%gZoT!LYQ%Zu39m_;;HK{8EpE!QGFXv`~s z8A3i+M6P7h7K+_LVBg6_9GN1*WD1##6&y$Pi7b;H5~2AlNFcQYz$~gwrI(0^6?1ij6F|jM#|iQiGcq1@nhZW_k!9KHRoMR^8MZtGVGEA zUnCRF;cJroDV~St=1Eh;^bFKKkrsu;v`naq4IL5GrvgaQZI{JRxrmKd{4sKfiAgj% zG9q6VuSda4GUVB&nRzd!X3R~M;Uf}_(0o zeBjoPAh3DE<|?y4TKn=4w8dYL!3tk=>1JDYBly2k7R=6rfe)P76~!y8M`;<1CJ~&B zq>Zf@?Bby;8y#UKY>Uz(1IpF~C0TXEpXDOu;u34s1ybLet1)NYYYS48AcqA4Q=Kz{ zpI_X99GShkAjL%`)++C&PA@l^Q7%bz=)y}bLo8+sl}0PiJ@>2&qJET)G@2D`;$L7J+YUVjP<{Z56?4MehnD>*dIc$m5Ym9zoHO#~4J2Nc8shIBrL=CJw_X zg!#Dz^z`%^FQASiU_}WzX)Kb4Fd{Koe>~IBgudPm965R%eJfYu$)|pc)|O_Z>dc_Y zD_0WE*^VCa=V&mp*Xl?Dn^Upphm{S>gz+_S>!_6;d z-`2~d#cp0d&m>2ZwBBc)_XSnF>z!}Kz4twU;Sq{dnXd=YoHK)GlpJ~0HdTgpyrMZ> z#+$C)hVJGhiaCx}vAt75fNM)Lj75Ys4r$iGJUrBbkboc8EhlD34vQ;s;4_JZ&4n-$ zBaxP{vnPmJd*z5+eM%;A)7UPv$+*()K2EJHq>X zA0`F{GY5sB$xYT}J$|n$C=102X&n*P<@4+6>~g#oe~^T=u36z4$HWpECU)HKB-ipi z`H6daR-!K5V9$_fnbY|90oi`l&bR3bqMbe&^GbL^uuSlVae$w{v!@#eUU^AV06c&Q zFEe?kW{HH2+(@VrOcz^-iW!Pyx+4;Qqo@&4HFwyPm?-TO*=L(XvlUiG(Bo%gY#?i$ zXfBHw7C#<2uxCUx!#G$(bbNJgKW~YKA(3`aHYF-p8J|HS7Dj>+)=`VAYTpsXE##3a za1R^OVMt;Szj|d9l}LjlD-s>HF>6a&$USq4r7Bu%ZPg$M>Rgn*;u>R7Ul<-YWk87QJ?uS0VgO-+0 z-Q){wdmEP_m#-jKs-iJv>%fY38)fF@Jons7`1W`I6M>7*zd%ov5H1%izxW1Ylt9ariE;3UA&RjsxV@O2#ye7paS8ORSuDty2>w#-#RwWB5vJBOF9S zJ>AiQ$S#`vaW228N|+nh_zZr+gM=+3Wtl5lSsDqWqr(a^c0f=oBdOP*ro2hWQhY0| zd!b55n(daAH#KE&*0$|9bLuGGaQ!*>;oZ-R)4?f~&dx5`OxKvbwXr9g5aB&*Y45~_ zjprbrTfp%2hypujm9PYdS z=lXnHle}K`t=UQ=bZu+OtcpEc%GW}*fGsPV@CTQ!M|~=Y;^H_^rSz?a8pT=AbhvDx zIhM)E2SS;)hS`eHT(i~~5iXml<}--KjOeJIFee~93)?e!t=_c?SP8ZTx{rNr7hXDL z{EmP8yRTsFrVTc!;6N0soSaxwrHsMB6ZrfW{~p6b6GFpMVvG|lT0;FqLSwb#l-s!1 z(6OvPsWMr(f+B*Q1t< zwN>LSZOu4%V7I9yy6GiaIdjbr9TdW#f`X&U2E8wzfbe@w34jwHBJ!F_r|mtM{8emR znXNiL1MYve5B;d4zgD|;A5F#x<937c$Cqd-}{6y1QGn zrpLx6@z|p~@XIG2N8r*6FRV&2F%(uWQT%`+119^*#+s+RC-*h0E*_N1Oz488#bYCM z+-xL~@WxtJXtuOA>0oTq7)NgO;5fs~UWsMTHlks0zf>PnY0EHK)3GNMtZLDF@|xE- z_ep^DkE|ah#K02-m$61Y?>N2yjts-FCLd{J4p!b@2QP&zN|NH~f$UZBf-XQ3pyR zv#M!tZ^sKSyoiaZDJ0`@tRL8@1De^jkuzB_SQRC|^L$R0wiM*a=e#T3oW>K4cw`d* z*1oanivnd}Nn%44yLP^y&&wdx)zu+4#+jLU%+5|@bZi9aRD-IUGp9_xdSqKbD>2a5fIx}Lk+TQ|Evc|1!AOoG^$`k} zGaN^bOy8X(WO5ZK?;MGcLsLc~k&L;prAF)s+q>nx+Lbp=Vt55KAI_BF12|0{(OGESYYBHF(s!jz%@#^m@P537gW%I zULq!9WW9W=02zpB3dRFk6{cE>Mn)up*45RGC!Tsr2hVF>eVv<(vbf``=vv#*w;Ei} z*)z*)D3%TZOH$11!jK34`}EY14n(4F5>I1*rORxwP#a6+fv#eQec`Fe8aYiaeR>_n zLfUgv`^2hk{+aK=*vikt>*BR?-*ZngQMaiMLuV|3V%#+HDEB@IoN}gh<9Z^4*CggG zW;Qk?FijMt^@lQt4I% zt7YWN1%$bl#2BRNsy!pF$%X7JCdbF!D5bUWylk`Lk=GP)Bd=ZpT}hYPR>qCL(u()@!=&w`&#lUZyVF(KAe1KW1? z9^5l+@e2A|qew)mNY*hS4x$oCW8GzM(mBI%cA;)=#LP!;(}bF4O_$}hsjgvpqxYT-GN5iypX zUx3-x7Bw!x#jYNj6cM@6N#u%PLHg(H1DU?H=0=$jE1=oPnvqe=L!C~69V>dU`{h^A z+>}9UX9wyNY2177y;!|^HTEAo;0TG<(%{BXZ&E(%>}gX`&1Pp!!qzr|su)%)t`E!4 z=bo!$^b_8p@r5k}es*hbgs^sCKwJXCil+xpNr1@rctoBPbjXn%it5+~;^w935S1H4 zQ5%=J?6NC#kZRPYTE!EO{|1XWCJA;(sA^;|h$lq&qviq0JK~I#O4xs3uU@~mcco-w zTgeO2A~%OKEmLRErOG2_raDC;Ir*HB7n&<^Jceik?-@A+x?cjj7!)TYm&}03*<>1| z*vM!}f!)lc3i^CR7C5cIq@yvD!QsQlfH1dr2$2Bog^N0vNctokn66Lb(1HDu-(^K$ zWTGXjW088IQKTC)Xm4thf?8*HC-%Jjyf!gqVOhm+jb&*X72!mO`4cc{@(!i9+^CP<34Jf0iLU^%*?An?y9c{oc^O^p z9U^BE1u5m{aQ)@$(UvA@X&U9?yhg~_ZZK_2l9y}(g8x%m!Tf_PiRDNn|31z@>&8%H z5ei*#O|a6ov>@ojocxHDX%~=Zl*4SL8}I+h5d?!#eC(E6(casss)^7vZz$JSN6$)! zbQN*x^a(t%<9E2^@{93-_kTzuUfgf&4|q=#iiJ5% z4kZZE`uExtCbGu+M|8lCHyV6tRi}ujRiG|ar)x>onS!V7TO;oIgM+>;BJw#`Oil>c zXY-@g32fQC1$W)^V{F*C32Robb4jG_E8m3mv+ybR}|NMbstYLUnq3Gq~<`uR)B0f4PDV zR<#;s*2Fc&QPeo@zUQZSe8=NTT4aVKl*=l8b0)QQ$Mxmg)t;x~TkL!->trtM7|MxQbQH zA#^nod1OM75E*&v)o;auxCjAFu_fzln#@}1hMqA=&~phAQKq6V6AY8pmPbRC=N%KI z5T1DU6EEg|T1C=B= zE`cCg=cecvfqcXxcCh90+*pL5n^1PWGEdB~R)dq-b;29#)($A6RWGf%6?OG#?D*9$ z(c0RM!Qo*o49obe52TwK2}vhm)vA^1xt}>Rh;T59);1FL${IJEo}AFA)4f0Yg~45J zq{hRDg0dY!#xESpa3eVX!i&U6W1{#c6s?&vjYcrEajm?BW%zUZ_wPniQ=_Sj6$+S~oN-8p^@pj} z7KA-Me4LbI&|0RDdKZ zL$~U1*7mc|*WHev{PY(h;$C#g#V8heP}>yD%&ZCKbocb2UTS<+;t)~eSmd{F{}=SE zSb_7-JsWSo`JMRb&mPcGeQ5uFq>^P^x}^!B$|Q6(w z&>BZG#71pEH!0zXc}qwe`6D(B<;NTOti?cgtp*FYhJ~m#=Rk)LZHgu746(Gi_0{sr zo;RC!8;dE^@ky5|b>q_`h zILAfOeYeV8sA{f=`MF83-V!f@gt8LFimb9Wn`cAMeEY=&du)u@k7=rs4pE_!!dx+9 zzVms8!$NRK0`@H#7B$`(P~IleuyMvpE)ns%2|T1Z%FHC0ujLJ`sE1Om6wnx}pf@&$ zSd`NOCgc`PnDjOIRg8}dIcvQr{#DAzSAzKE?rBs5EGCT5$^@Ti4~r{<-i;t@Trs;h zc8`syCrrk*4m62Hl$Hs8FsOJiHa1=x_cqdd7#%$;5Rax&V86Y@k?;gQ`jPh{CO-iy zI{8|LRGY99V;2u)LFq~sIGPwhzLdk@$Q=IRt6xJrY4YK^zYcNr&r7C*M3YN~K>1ce zm7|Di@fgyq$vx474Dn_QT{W3=LC|!WL$LL4Zrri9?#VZh*&1V_aYph*<9Dz)mI|n| z1mNmpf+sn7@=2QFNW{vBB}}ZX9IC_mOW&*ni06x)*DT(>TBsA)a zQrBbThcm@7I_p`2!7PnrAIj0PSK?(&jRayUg4Cwxhh>ly#2<{Hv7sLAtu0m=i?9|_ ze|$EZl`ElD)i#goUDbH-3=FK(XJ()w!H-aXG@iiN@E8Wx_NlkEee*he=ZF7;yog3i z%5;3_$})*E__^vTJrCNIaFCP0Y>|tEj%^3_ACyrD;Z%;*;xyV@>+!8morCF-{kZ4RaXj$5NfawFwP*O;s2E6e ziu@J+Tx)Aft?<)lc3Ha2m7G!^#hOxe0c2toTzh^yuDI$NJo+-((QSw%Sp711#+1R6 z2=}8O{}8h?(`apMLZ&H$LkADz#y7u7*G=mb@s~#_U;yX zv3=XC5Q&BK?3ux@Ska5Qg+=`2p1YNCcQ;mX^Xtz+pgbqhryv;YjO?ot6p3EEYG) zFN0McTXa0QH=T8!5Dv1YfAE9v;TQKmf>ph}xbctPjL(1JbBIJzI-qoqrGjVuajSqW zz$uv0Jj_`ZGf7a3j_Xl^WVRLr?-Mq4yb=Bk4;*nagqSfwwdo2b^W-Nm(Kkm}Yplpz zO(R=&a9a_Q0Ea+$ze6Gt$GPWi!}YI!ok*UER06lY@8ejz`CRFW@YxG}Q!?xzfTiw- zYhNrS&x{*OJ!>9jj3r+6&IwStpvu=YkAw))$s|smJ|-wulU_vC=oi420OgrE^+ZmA zLnB0{tM%E98+L#2ilm%O=z#Xg2tS*dSrMs=X{tjb z>yfZfU5O_NI?iDo^%3F}BICGtM2JY3`z1&MdJ*|z1=*b47oj!PD)yfk!@kj=5@s7a zH7CTAQDm{=g0`VyN zS9jz3YhR6y&ThoR=G4mj!)-@oTNC1R*s$J$;{X6407*naR4qx-7zg$r!M*?UbBs-n znc^fBST%vh^T<#&jU_I#us5{KCe>W#sY6@507{~h;Hq&{3a^>33HL6~k+y~qRx|{} zMWEjT$9q|VoOR`m$Obcrg@Y>4Ooh@R8&2Y0d)bi@Eg`mo&3I>gR+jAWx$SuRIb3$h z`G|#0GlFNe97R#VyWjs&Gk7vKqw5=mY<|-Mfwc;nn|WxPS2-V)w@%i9T`a1K*Jzw< zDox0O4~`GXw<72=$~V`DqYChf4sk-t3Nj3uAzB2t$OVlDnZ#Tu;^DlqIX_JzUsro8 zM#d(QWAz^hVEx*)3PL3OFhi{)(PeGFh%BA$?O3&JZCP7cVd$$1R=4KRdq$C-orFT*r#zb{3sGAh1L2Di%^76&U zjvmKiVNs|KgKR6so0KAwcn9p=yIU0r+YGF}$0x=$u^G}p7KY1MUv(xBkszW9^i`)Lswb*^4jLC8@7P5IvP0wjGwYP7DD(cyp2|V`buaIeK z#@NURuD||z44oN5OHY>&klcJ$<3gR?-KvmC?Bs#N`*-@(Nj&!O!`QH40L{%Axq*^s z$LyYKf5(m|G_6ra5v80-H(!2sA1*(y2bIDc0u>qp8Jb|`PW)LOy!3`3L`&f%OC~wq z86s~%d<7Z~(eEQD(I-_%JPDh#Z<0O_Xl^-LHbd5Dp)x_00! z8zHV#@bW7=@z+GRRoaWaXqPCrq;%n@2ZPgtOu%dCvcMsI|6b@Rpn22s%O% z7Nt22lv@N)Et#$f$7TQGFFuO)o>eBP?zlL$SXk3yF%veA28jIU#J9LU{2^_e3VR(X zjC%b9H|4=7!6Jpl!{E?Sunm<;)vNOJ90VH2sZY(gAz5;YT$y{NT1U>mz&rA(^{_}u z<*3?{+@nlbd8m7-U#pg_fU*{vAw8Cy(;?D4BRt|_+5$#)vp%;m|6@^LTT2CzKmnQLN}iL`mMCx6d<>x$QB zZnZYC=FbrQ8X;dLfdCPLPym1O$2VfrK)-YynBaPjiUKMffx|`s^~#f09aphfFf~{v zb!BR#@I;pYQ3VT&3s_vF%4GuKC^c_LTuv%MCE_4{1+#(x6CtOS;LWi}EY)aH)yTGr zlk_lI#Pm!SKfe2Zp|jFIamabCZS2qnJ6~+#j|r!^dCmZj_lT_=LuNv1VaO9CS3ohB z$C~aKRyT3VBM7=n@^cmfb=Yv_O*)T>u*t%}8A;jUPmLTy6!?+7mV^}ow1!{uOA;ba zl}+ko1kD10ulK~Wdn5q1ed8*;=Y1bWAe~B9c_scasgg zFdo2aVTklXvJ}N07)+P?gHphvJJn(y({pnglj`p7)B>TJnI}oIV(DmaM`wGh0)1~s zvw|ySZU60?-@$a2L@i?q`|ITmlCHK(aQwqIW_nm$2~`mlYD3IpY}DpSNvA(>^3KB3xrA3lw|9l6G-%x` zzl)*;4~{dMYa|V$;v!y-jgMnxPbb>jGq~=Y0QMa?ji3H*QDny9u`xXl!eK;N-uR}Q zaPPf$qqV6S>oyFicg@$@vEw(+?8*9V6y>2zv&c1$w8hU;F6MDUd z6?pKOF)S3U#lz3HYGt3E*PZ|Q1Klf*igE)^jZa|B`VB%_jvhLKg~d5+-*z_EtX)@Q zD03Y>`tYNOL<6||vP+fta&t;>B^JRGPd=%BJwG>}OH*S;$k&0xN6?ZA;;M_*VDqYa zR7(p=3YZ+2d6btncMg*wQ)@IW1y#%C=Ij9D=smkQ@WdLfZ&tPEFcKJInknG>R2Y>SqU&h~k_VXwOgLwaYKY)*X^j3W9 zj_)8CHW_n`mN~~v+Y^42&3ep!kMMw#?JUQ#;>Pm#Eh~TUS{KlCFMMUHXTvqksyRQ0 z{{CLv{I<6VJ;`L!N^I=sb*wt#plun0Ihnu*@%R(J#VdQyU}$8dW)x>Z*pII*{c8RD zB_f%{E>k{Taso7lx;Pd(=$YVik9i|0F9l5!_Y_|D+E?SD2Ol%EGE1!rr=%(pAFFXw zE#(WcwPwU%BSV`nh8ZCd8DPBQ-}4@FEzyL{jNJ-4#MlzzYw_UY9`=Uz|ICeq8Kmwb|?F;x|tF8MR^o+TKbb+5nEGb2hIMJ$=XwXePmmtL|B z;ec@!+#@%lpto{%C?nsGtvN41#ee5{ziK*X1rcYwYqgkR`E6jgs z?JM~aM5ZLe!}6Z1CZQ!Fjup1TfZ6#RUfHz|_ul^?I8h~1rB67WVV970cilEgW9WkT zI;A2O-LzRG$hLXXxq0TXwJU_ShA3!0OYR*LnHA?;jc7xU&!@g`*%z5%w^f`v8lgSu;<`W$)jhpC0TBN;R}C*z>4mUs+_4buW5Fighn)K z7B*;*m8XnM#5|5*a&lZ5YggxHeBtjthWmf}1fIVA4t)0y{s1XfFo6h8&Q0UM>}~rRNz(C<6QjgCUHFlMPA|iaMY;T1z}}yZcdu!B=dxm+uKBn+;`vz zayc`D(Flq9gLe3{BL2gxFA;x$fvbN-AHMtjA7N(E;1mzHXtc#WSj~59!oxJdd_@mBNuDN44NN0kdJtHVpLl@7rmzyP9M-q_9 zaP0U=v^3XaetHVM%|*QHrt`4>cnM><7PPdtV?|#desa%! zf>DnjJBoV3uf+m3Zd|YRMPz_U4DXNcAu?fP@ci|!9>?7LEIK+`(Ys=W0viddJSg|? z-;X?J#H-|n%wY4T0ijN-R`zRRn;09Bd)y?&N+KCuDR+OdAqFW=@ddBVAmi* z^R0KIo^G_GCQq$Bsn!h<%rHLvsW0H#>)wI~e({j1N#9rY2c$y2OB&P$amlh04QHNZ z3JUn3{CXlh&%_{-#B?B?(Jkyg$Ae zp))DhA`b#%*Bc*#NtgU=+>{mfs*Q&;AvL6jd&A4K^I&1(&4j{qB&>DfEvRKQ773v* z9YAkg9trYr5@96j49WAYBi`R^Hjf}D9ULcNbUKG;kJICUMo(OihEB+6&zWAa#ld*W zBx!!moI#0%7(a!=UzAU`ghI~3YDd}ks70X!iB6(XeDuTbMjMMA=V9RQm2V*}PZDgM zSTVr;>dp0dO-!b^{&;UJfieVE#6h*|mbH>K?psR@oFl7^vbvE7&`i&s&5}`|B`_{| z;3%Pxj3TP#5GLp5anId9$NqzRYU{}##>@AKCVXNh3dVTMqMI#Wwf;2O5JWN&MN>47 zp2h&`6ERuTN5U~wV@a&J_y!;l5o%=#x+Q3SomiX85g5H#q2o09GtNeVjoZc%XKfG1 z?|Wv~UYxyYjkd_#LKYwX=w}hwx_*6?L75NT9ta&7nO$=VfqgAw&GVj$5Er6f{4{!7 z`tbGd-ic3t`jhBhzZMfe`#CmE=6QEsEmg7 zu^Tb*7pg4Ik659sgrcprS%>Dx$hZuf7%;j!+QhQofApk29RsAiBAmiJhXYRGgveGqU>cR5k^yE3ayO^#KRSA8t9fBvGwtS zIB;wV&mW{xV-@qWv)bTPdF1$`NO|V-sfDHyFy|ZYwIjr~cIuB@;QZW7Q1}cO5Lm7A zFpDx#lO$|NXo*RfnoKp{lgfiuF&VrhUWIGWGPzkI4_N?ZlEBFeuP>jeZ_oj8=w zbaWU?9(0kMGeT;yh~}mygO00JAt=0_`i8WAZhB@Kn^&Z8VrU9^qy)9|(4++|6Ao7J z6Vp?uuS*MQ;k8_M{S7#M@`QR`(O3fG6Jvs$IgV)Dl%S?1CZ{L#cbu0_5z=IZTCS?< znw^cj;XoQL63A0B?}cX;XL-Po{xBTk$+VXAYXu&Rt3Z@3PJ4jsX% z!9fMA3obZE%>X`!=bn2JCr_P5cUL<$tRK)AAm5kpB_Y8hM~=4}I+={Q3X+3eLUo+!_Z(iJ`OW-!wK zVXeU;zWkMc!3}SCJO1mx?^fb&35px{;%oZJ23IlJUU1=LnHK)i@!+&hltV1>8+^P| zy(=^&?j zUIdUYxY2KUY=p4$_zZ^TV<C_(yZ%Ye+ zu}K^i9+FA?!5?0UYp%RNhqXt1{CIi|-F20)aBVkEYG{UyZWDzdQeaZ-=4j}r5PZ_- zNwmJL>o$Tw&@Hx9vOXx7W3A2cP(MYHyx<_&%ydSltnNFp8D-`xbK0V z*`$p05v*EQ>q;CuOMLw^G@~h-oDr9y!onnuHBA+?HN+*@rbMt(!K!nwM51}EcuI^z z4Gk&1E|C+VZVqX-`{%@)oT@8d*X_8P^#RW!BDThZu$J}M)HG)2@<_x3Xlh8~eYgA- z0^7H2(onaVVc147Xv_XABA;h+>Wu;@X7jlEHE+Yp_1(Dp{_i5)(vI~9PvDPQ+trVp z$rq8PhB`%7xOl_BkB=O|L-RALz|}K%un!d;`DMY}d5=r6&IDe#thG1^krg<`WYC`V zlFP`mdSa#JY&A8yRVs^MMn=~M-uGuHl@>8EI*v#zf*p_l2J<=gNQ;QmNh?@Fb3+0R z4Pj*JqR6BZAh$3m_G}T!`ZRhw+oe`!WUC-Tu>|gYXfIAo#soj}`%auZWn>TPl}l}_ zB3}ZH1jP*=Q=d=tivLcwRi-ajiF&ywci<=CUdlt_+pL@P@1@`CvH zOcZ!H<|*t_fs^U3pqXYnjg2Z8j~qT|Z3SA>hGJ-IYtg-6KaE@m_2AW)kKpi;V@NmD ztJin>%%Fl&LprU`TPT;&)X-o$40E$WdJ4H&tnLcn&96HLFCU%3#9}Kl^{u%7!3Ryu zCq~7(f*{zfTeo6#a!j(>Eltfz^kwfRX=bnRDG>qN5_oAt_NtMFs6GIA8 zJOH9`dXX4gUXw=EDw>-cF*#voT1@O#tyqC_wSfG>ESjP@Ty{!6Oc4^KMAS|JK=1!mN8xk+#FW z{YUY=|N5~hin@cFzj6)mSH?QO*7zJ4{~6+uh#M%tLE$#J(82`P71uw-W;4I0ug44!}xmL4TPUg@Tr;7LA`UwO! zZyexkl`=&^*~$P7cH<`yVM78o?5$c4r>}b@?)>jN@sW>y5POGqqMA+N-RU;0&y{d0 zm&g5sXAmk^aB+JpHYMsrLV0m!0{=cTf=TugD*w; zDAq=y4>8c(rXP&3g*u)8n2DD_tsEZU(A2aw- z!Z=*?vU4Sep#=@~%+@#(RzWZvz+*d(<2TP7#n$bcF*EaG4adK#_~G& z08DJfL{Nkth{S2VBcUpeIOa)wUdGxJ*eK=8O~BW)MP(b%XHqQ2Imtj zm;E!TknTY)i%g~w!$Tv8Cu5RQW{6^si+&OXN_RQ~A-+Blp%ceXptrXdr_Y?$dSFt( z&%k+QA{>oP8K7JgQK&*MX8>K@J!&N|(6u(VU}}0Ai`iU_pe6kcwp!wGkyRVg^=b#4 zJ~O0hi)}4h*AnI7W^HR}!OZNO#8VWIA|WMWoWh8ON~ntzaoIU-*tlss_MZ;ot_OZ2 zgp9wVy zoRd?t*uM2FG&D8p`xqoNGQ~co>;2Yxz;5@~;C3c{xh($p=6B-LpZzrM_-z=)csGXv z#gX6~y2za*ew7PoEuF@He0Vz+v$L+>X?=g2MR)uRr{^!;iR%mdV!#(DCX_|;RRJ^8 zbGYL_euUoDoAJs^yKDr{RcbXv!Xpz-pJ6$&VDL37U6WV$D1*V%PJz)W^SSf776VzK zjt&o^XJs#rA31<%G>-ZCStn6$W1D<^Bk7Sd#r-M|Ie7<0_rvad@dcMp=IlH)vXHH5)7>$oAb=ysPT|gf{{gbO zxuvAXi5!^{qZN8SS>Q9{dPpTg*wU3iQytw+!{#(u4WMV+Wr($|BKD|O19cI!#+F$K zC}9?gV2CvTY$$`RZ~mQ6`W5dvtwTK<=cuYAMTm_h&wQQ#`ps%~TO0oslLp)9) zlnN+jLKQZ>sp~NkRRcKHuStHBJyEOnI7J|X3YpCqq^>HUWXX#+_#uaZpO?sj z1v@7o;i?`Pmq>UbZel~yR$zfn0T1(kuy&<2bLw#Ep-t|YX!jVHm_|497AZR_o6DLk#dUje5!7o4`1bouq7nm(7X!KM4L8oOt zTN6?72flGJ@rT>+nwTbxXe_*%Lj6zPb^ovkY?L+j5i%+G4)b#`=N@7{e_ zxpIa2_Usd~Z9-!v_8~n%sjazLo85?1NleX6V?%ESzuR?Gl|p^GL48LmbH3>{S71X! z3cH?p5krdwoMZx#&uSxa`hd!j)ZgdNaeRz?7wd_eMnYRhn;i9+5OMaq$Z3s0wWe?1 z+|+`>;Xyq-CPD1W@^EZvYC@^N(bs8iAq;dU@b))eg#UT`IG)=*D!88SbHx>x;ivaK zpbbqVVf(giIDF(Vj-MRFrhzqBy>^w>3xoR6V<(+Z3GWxHIII52!%%z5tz(k9WIIe~ zSc;Kx^mKQL0e$qyF?4iv$-{x4t+P3a^EWo3wK1v|1he&Og=(ctf|%*^P&5-M{#%4& zUz~i1kf|O-Jeou-$wVZHaHxb+3+oW=xJWbROfGVZSyj%K*fpX)ok3SmpOR2^5T&f< zDtk!+Ga%O7?<}bJK;qXb*Rb>o%4OVq^V{(29lylQf4>WJksg%At*M=*sFd@lu-Yw* z;b)&eAKBRvGu3eghB2lt^34ZaEJ@kTHej7UnTGJ&D)6_F6n}-%q78(%ROn z*u?weTX(*S=G4>jc7i$a8L3eu#dyN0FBmUmDs72hxn2q<8VDLmwV3xP6vp0Db2vTE>OX+R zyrCgt&wH3$;ylJ#3YcZ2LH{(} z2%lHWG+`iv&V4e$>-7_H{5y}*P%7I`KKQ=8Ul@Kp8<~=*U_s9)@Azs;kcGZ2i4oN% z6?|`>OVS|*n$&PD5RLyjZ3y2hC!$TSm~Y+jJrz4FDlDlnE{)>0SLAd$Lu{G%x5hBg zl|nkn^xM3ILdgcKzVJF!;Y_(gw409Ak|%#o%izx?p1khm+yo*NUhqu!PwI{VO_%XG z`0w?+BA%7px9?@Up{J|MIWJZ8q4*DeE|zdO;ZRd;3TeX{->ZuD)*#;XmLBXqK8%SY zF}x|X3ZwH`+oV&dr4?jI2(iVd;*U7eRn^B*t$FncIh-1f2sLxLr`O3>KF--te zaOU)&ra<^yrlxrh9aG78nd|{##i3G$?3C7asTrq$|stfa#Rzx$s zs%-N)o3rPHPDd9tG&pK&>u7m$>Vt>>bxDqxcDE&=B7Xc%9us`eU_k1X|MIW@hTFgO zuXy8MJ%EwqIgS8mYejSPm04W8Hi0MijN$vYtVJrE6-q+bR%_Us&gi%@;;0X0oxF*Z7g|M%rD;$t8Agi{iS68yheuCv5IJHE79`JMX`lQ98)`=McYNdK&v?C45S&{{q z3IMuvHsY^8eVZv(8XO=J@vIrKagt&bL~(zOLF$t88^7kS%mm@ ziKE0QKJr@Tvx|z0)R5rWLzLSTOF0^Ah?f#f$I&zSY#S-{90VKZG;V@TGnjauU7D>4 zQ{D|?W;%zj|MMM~nH{fj&}>S~QXVDcs{A>o8^G3%7}}d+rrV$-I*9g-7b4xUu2$h| zLQsp|JSr^Vuw+W@LYKJvq@TZ9q2T1I#lvuu4%CgH@?_b%1)30K@$N{dfByd45Lny4 zqAEfXxdv{^!1@)O%Vlz4!YE}Ptj;c)BnXN-TzO#wF4~^K;tN^y&9-5xP{mWTQ+Sa+ z0OblUNz`FeJcc!yR*V;Nc;(Vpp}J-*vU6D+*>?b^4;{wr$S4xwAfgJ029Hvzm>a-v zF0%Q351xsOTpQhj^OXq?ci+3`hVTq_9xVKGU0uDPB;K4To%zBf(2zMwBPp97<$KQ0 zuT57jz+!$kSijSkYe5rI~zqI$;9NRIX%Lk z6@f38$Lcj}bdY$y)qw*}q{*?Y4c>F!W!xhC7^2YA(}lr7j*QT8~d@kt%Se)+h1d$ zkTOM03c5s1ZnmSf4MQWtB4GA*b>Px%XW{4*&mk30;;}QQ5K36W$5GG4g#{g)_46W)?{Xq^AU{pCl%yCa`8zKl=OoFg!YeXJ2?;>$tiFhw#`#kKw)Ve-FO$y=U>j>D59$ zELu6@Y^8v%!~!N}3;6Kmz-umCsgYnJLOO_@`(BL+y{y$xtHc!iESMQI%GP5DbF)+U z>es)CVwtdVOo-I-wtyu73g=q$2Dy5HCLcF{UqEd+EbB$E*ec`t;+kP#EfjL{W1#)| zH*Wtr{`8&imP(|O0r3s0LbH_QI)0UJGa4dbkh0eI{JeZBy!^Cg`Ndt~`*v3#+M2+P(KW8SU+D_}r&%MTL^; zHQ0&YV@X1-)#Ta@zRLCouIcyKOZo$KdD83GsTCI-9VhR}rbE213)e|5Pvl@msErQ7 zQb9>8`D^?$S^jEKII<}Zf1$#hG^1XLOsz}>RafE@8BP20x!Bz?^1n@$F%EK1j!!P& zpZ?`rDC8*yXhd6nPLj3#R2+F|-St8Ax5m+svaxi&VK_+t~I0fO2W5QtWD`B z6MT!x4+Z$Y=jWsWCM-<@IeE!yw}cQ%hzGKG?Zqv)vaSPTyQudbMzI>eSC1Y+B^<`hZ5?PX zRneJBAR7$fuGlv2_^@#X7`g>hV#Ae;y&saufbKzRw%mPCpLDUpw ziY8=mS{tKb5al6C$dES7M)tIgVU@|!>oKcm?~w0pieN@SVz6MfDR|OxE|}mfX6M!O z=Q`ser$~|Pw%tez|Bjo1vdI*oBFZ5Wmh*P#>gvI&Reic%LisN|^NdJu+`JTQ;`dR5 zg0Na|caL-vNbt-wq%}@Skt{E*%|oAD1#VF3SOl~9_&Zl3R9?jM`{wbzUkq!U%QLn+ zJKAu=>)(L;?*9o2d5)L{(At>9J8!-TKe_!oc+J-B_^+2=M!cckTn^mWE#WS*=@|qj zC#S)nGB`9OsGZ5nn;OyH)`tBD4x**01@U+o)6;YEq@eEsNsY6VzqUeA)mej* zmIl0hklG3y|FVNch*Y>L^-dn-Ox#|5^_4hy;2?&EM-Zw8gv7LWwxgKOAt!5KOZt2O z)7}UNr3gnyKmM6*8Xiir$)2A_S7(Q7&y~gVpz9*Lvq}QAQ3DDR!SXCFKW8QS+hYia zIbzAapc8eeRFG-u$JKB60D?)XQwB9dKRG^up1ywdj?GEXh_2?c=r_N$3VqK~!cNY4 zP^(pb24*!*Goiiv_T%!)FLgW_Lk%tP+PLoc_zC>z2Y2Dax7~tg4lm$y_m@zSA=t8t zuu{^%cA%WcO&ezLfj4ea@L|#6s~KZ`yW{5foBwviJ6#laBI(|;y+d=cLx&IJC-?pm zqmxr;X=$}Jw9G%kw(k-FvF3#543P{9cWI65NBj420=7aZ7Ut&g>@&|`<;s3^^>$)> zd=#zCP597X{vUk$vtK~jIo9%;s7XN7&hJ6qFV92ZTF{uHGdeO!=7xk; zl}SQOY9BJjF#hro&Sn?fvoO*nZy?)TzEbotl52t0YhPmwTRKTbr<8BR#dEuEt`W8p z7IQ=;IaX`7#V5wHI5)m-imCFL$Tr_Tqce(XV+ML9o*h~`91nLu-%7Xcw8 zfBoqXsQ~oP!uF7zsN}NL5G6l?UQ0&o@bw9SPa6EM%M%U{olD|huAx*hB?88MYWgwU zlPt`LxS4N+jY{To+&g&{iDo}e#Kb9)y0b$g>s(ik!0(IK+Glbx!^<3-ODu1J`EBr? zkB-gYpa1z=IzO3U*-($0_9>gi{KoDGT9OgOqplSf45Dkp*{EyZ=+up?s83V(h1X;V zlkI6f11DDH&;mmzoV##sy)N-g^x3`3ERkoY=;`mdMn=1h%a0s20kcI3Qta ziCk3ERML2%Wq}Qu4m3A}(HI@ZIqRFSrXz_24TWBgqA(iWCcmm(Q^Si1bWMty( zSbbm7n54Fd`5;74bZ7t%U2iaAy;W*#Gi!@Te}OW`b!plJXGHvHsBh3h=O!JWn$`%B ztUn!7l!vr@yX7NLl`AH*LvPL6-q|HJN?$E_cIa~Q(eh1UL=|_EX{5~D5ejqhP|OEXFGWLejhiiRf(DxDLmUox=FkBpT}*uy)-VktI3iO2Q@sGm|E711!=N zfOI^HnfV3j8N{RXWSGaF+;|a=j72atGl!io?GcG{{lI$k_4UYo^o8el;?(IgNBRVLP6$yif4lyT7%fLv4i_d^b76SyYXKZxB#?PG5i*akXsfj=lMFUzA zMV!5 z*`g*ywTf4-E8;UZtrA(7|87BeNw}yM?EOSR?ew-|+u9FCn&V-)m|M_mfBuVKMZRKo z+fE0`+CgqEe)++oz2{|w9TaS5n@?0cp~4VwOZ9=nhYsM>$&*;UdL5E!+A+`L^MCzU z*!|**c;M#`Az!9)Y@&t;c;v)4?8@ql+9bT6p2+Nd53ElPwbXoT%ePQC z?rRR2R=x7)%^8!$kn@Y~^ii4`F472?m{9iJF>^jt~-RkrZeRZAzd1klyji z7^X{xB8Y`g-h*S^^RsEPp;FbsFTRE2L7JQ=M_!BdvKaObA)TPWhIes?y@AtlRL#{$$L>CGVJsP zSnQBPM9F=ASdQ3>E9cNdD;~A+Y9GND3~Il#W%a)jUyn3+jt}?PnZYUC{>^WT3smI@ z?=qFoo=gP&Z9$~tF`@Jln@ZMW(~(@y&mNz{wr&s6P073m*9S)2OSCqNgK_>_QoZ zatx%*+4 zKS>|mYb&^4xu6Ms8k9s-fr3^hea#>6%58ouM=Dw_5DpIyVq|F8^+2Vm<#;8g0LH_4 zY+?#$Z{Li;GeZb)aR9njRzdp6JRGY|z;1 z6SEkbp!pKV#TL-sRENH{1tf^_C943%sXp$X-HrlIkJO+$X5vw~ASlbmx zG?c?TZutk)H?KmzT0${bLR)8-BjEX7`x4pE2O|Rytk3GJFb_jo)nTZX3}u{}qTJ%V z0ggit*t+5UQ?LS)(@A{vgCE3~{_bz_^GBb;gJatAAcJP&r85YCdMJ^=;Uh=T-O-HCf9~UWe8+F`-S2&0hbTXj z0K4sQBKDd)DJGnSl}Se<+AI-*_#qy5f==5w>=)FXNCXCUXxt^;?hn z`aMzOW&N)N(z+IAm+kMXjq|yY-H;u8*6L-URZyZuuNX?76R{zJo69c<%`=S!tIVl_ zYh+Zq7Mr#N*B4)1iI$rnQ{h$QHCr;`_n2?{_#}e7E91Obd;93&QT+S2zl&1U?jOIX zCcCw#4jq{gl5yT+OB!1T&PAqYgYi2+ZJLzX#=Am5MTYxQVz6Alp+?lTXUWsWMkEcX z)c*665ES#G@Sjj=6YAss=UMiLH{6WCPw#wR^{)H(;*t$f-2D136bsV^cLtJ(Bv<2S z_dJP~p)w90A4Ahs@51g~zeCH^er)SWW1zbS2M&*8-+^iLHa4L-p1@S8i2rx&kVIB) z?OKUO$sHIia4K0N;G zXAuF(G7Qk121tl&KreLm_F{>cu|>I9lx2J7YOYpsvpS|vftkvfWi9{brW6sUWb?c{ zSv_;tZ+z>C8exYd9aV<3+;on8%`I(u@T}x*f}-k}%3hM7uxZ^YJpJqo zh{sdd+R=nRy7?xoXx@WJa6yo|`hBGe!qEmSl-h9Ush9BD>-$g)F1W=?1S_bKzCbXB zP`nNkv%vE^kK)o-twk(2CO-rdA7ZvgQH&TC^7Xj?;hi{eqJW9n0CFY%&yDPbO9C3h z;=~To7oq}8bOYrDyy3zaUVHte`0$q=!T5X<=Uw#DD;nL3_Rg@zNw8jf02AYUHYt4MV_(GlViAR61s$Cox)qiraVy!>)DoKF z?uTxd3+Ar<;Ne*R-X>97RiZaCGOR?Aar|4~_$r=$>PeKVA^iC6dz`eh@n0Ahcu#3J zuF06}f)0Cw>uCg)#C&$%VvXZb5ryCZ?`PTlq=G$L^1Ya-P^Q~4)SYgLC*^5c#36Wg zc-u4>uP+q};G7jyZKbCUM`CUAfvp8U6}6CGI$Y#SF;T+KQ?v+nvdgZRQCwoXV`0JZ z7naa4K2N?U4asc$(Z)Hs9y&Xk@wv}@2&IBcAl)M8eO8g=6E`>IQgOcuiE+Llj0rU! zgySx#5L!l9(vS@Bk*yLpE`L; zpOKSFwl9|^*8G0u`}#==-}dpbz$X$yl-yy>pX0&HcG6Q%@5ViM--}X(S_~C*WuoYB z52J~KR}K*gChD-B6AhuH{*K%=CN63zIk7F0oB8uTLGt@rE8go$I3-1&V6tUGBC*K` z7_v>2%O=L$x^PGk-}5!szZHSE-gs&C&tBbxS8XQ=s{mA3rG`*VuEg#4RnXPij^Uqt z2X!Uj;F(Da=oDR{3tl>j4Q+iWvU)`Y4dEze0>C$ppAf|Rk^a?aBH__liw@^TkvnS= zv#CkMTcf!2s%@xmOdwiUkD-Yy{_RIkV6YrSeP1^cu?!YYCvfoIF^mkKp}G+QB`4?V z9;mmOCaR#moPscWW7Y?dvSC?28$wCdnxO-e<6{^l#4Lh~ zDJEv~R0A}pKqeVIy}fdOG`P1Q?g1AWp)2bHoA`;cOlKWS7P`TSE*Ln!1qLP&5}k>Q z*-eLZa8oaU3u|U(TG=qivFhvTI+;*np%J87Z^*=5d^XDjiFVY?3@H%eGvRb9smTID zU<`0{M)V{sCJrP&GKg^j@n_GRIpZL!vXTc*DNrbf@6WCo>MPdfiKOKE$i51d(3cCo9x~_O`5?_F zNICUye&cI+?Q5<@x~UzXxN|R#Ro7VMC`4sxOqY=?P@2bmpWKSN>a0G$wB%jD6l=X^ zs$|HA4{WNrB@B9$i0_DadShaFB9)0W)RYIG$Y*v!z z;r`|AJ>QC{rBRNhuBieNw1W{Zi2trcyur9DDZs45!$r=R+-ys38%G8$w4-Lx!j% zkqHrcXJ%^ql`)2~hY2|q4ZG42tj-wGxUsPgWWL52XFMl`ha?XJl4PuHjwg1HVKUF> zZTFf5p63}DWN$=CuNo`w2sZ^MHBG5f+JpxSw$FU>7PK`ti5svqE&{DG}KSFPgc(W792;~hztSJ^ta-Su%#mn-=ir;9P$ zkavUMS@2CyPRq!S=!h2;<7e}&Wlt9Mh=J~dBiQrI@hF~8AS_Y0_7G#uJ^%9<9{<(j zSS-w8OK&|oGZaoUE)efY`@nW&dbij_1o<5ev{YXb!m7QmL%*%1V9BGoKaw6~cF@d^ z3|V)2Amo`z2LX!b)TgmMY7-D@WfMt?MDT{U{3!y@|L9HCHGOmg<7W$_6o}!K!A(f^ zUxB;6e-CC}dJ!Fyrx4*`AE+WhWjspbhLZ?ILgznT&OsDUtNnoJk9QI&q4X#*85tQcpDLRQ_Ii_r3GvpUOr%7vb2H=ooMYo-y3Xb~)Cca`kGH(@0xY(?4yAY}P;v6nwzQ3_;cSG} z8VKyu60hVFeatJ^8`Ga_V&nS{H6AMd)E4cQb*5ckrccM|8 z#@9am3jF$^9T+H{B-hHVTeoS9k)%lS3;0~RdwQ{N?*aXpv)H}@H{n}f|GFjytTpBcOn$<^Pe?TV2wGuUqfSmZshI#c$g>ICI)=PQ(D)gJ;Glu0 zp85+i$#$H&`3!vQ>kr`Jv6T{2@@zog|L1o{P{vK?lyS|)t7NmQ0Ms<>nLD;+0E$3$ zzY`V;dQOC^*&bA)VB{|gyfuuC3}R$t41a#;uXyIUy&4PTflRcB#Mjd{ZE|NrYqs80 z7EQX?lMi$~a}3k^=Jg;uGmArq4k8(kqgblo!t>6=Ti*OSY}@+0Dz<}14&#sa{u%9U z?Ua%F!YF#)AOJ~3K~!ff<1#XWD3e(uIckEyNlLR=^mg)$DOX;35ngu5#hPMm zwEzqu(8!=0d(~maXRDTj9cr8;V3NVV<9jOxHp%O5G|`zRsSt906}dc#;2nCNI!K%2 zh-O@5&cxnR#MTm%UVnfKcIQZ@+dEt((fH@BS%{?AeLc^Qg}g1e-rxH*EWCy!h1!hB$snXU2%Q2t@cj z>h+H;M9Z?7^jRCk+S-O1@N$|7Itv#OH%(7R_uctg@aH`;$-iTp_BC&~0fEWKUrkkQ zQyC4i%822QFRVbU<7C|btM6h_VIOX}=@m%#vDz?Kz*;qgEe{>S-yS@Om5p{poSG{8 z(*yZD?jAUf&Tt$zE?I>6;RH%NOsGy5C}E;Hh4zJYP9ER5mA%?pv~Nn$2f!elm! zq45Hq+j|TrZ(57f&s>dEdj|D-2KV0Ahp&J07gEfl0TKyQgzLO^ zlV5BN7+h&Y6pe>S#msuL*1vc2(mWL0M({z@$b{5Y=OG_Ky<#)p+$3F{y=coYX)vQF zI-@E1aO6tm&MFmK(3ygRf}cUr{E{PP(cJcY^}+9BMZ&{a9c!n~B?zllRq!DhjMW8E z6R+5%s+8)CK~^|qT~m0&_yt)JRF*oEc+D-A@Blf>M=4=^og~nk6o#(8%B^6*`C5 z*jQOY72m&o@hf<4%hTuzjpEMFUWP+MS^V=IPa~P>b0#isOv%ZG_w@8(d~8gIGuIra zTaqbi$A=|aC4CRU?lmQd6O+@bq*&plJ34UVJFmxCXPs-6qZ6yr`ru~`+Gr~865&9qiTZ;`0ofr4{@Y|L9(P;l3*BA-dCc{}?QDmPm8+7Y*^?6{hx+M1{KPw#zzTG|d-j6L?UO=VZ(6i{ubYs!tg}V1l z`bqfp@V38i&B~4_ki@)#=$*F!+js7;>OX75wpU&8GF<)Y%kZ~no^=kjMeN+UACElt zxQ+f6i|WTSNnoN)h+8hPZVZy|OM)ReOiUoS<`{4I{23$oZ|&~iEKbFBH$2b5k5Bqm z2H!{RrD{cRc~5r_@&ziqHk^!eR^yr%uj@dlQdDb-V~-|)XOm6*#Tc0{vh5f}FcQJu z{uw-Tcv`55NWfuhT?nQRa?*|bn}9x_h~$-uJ_}{-d2O2R$Q5+>F<<=G&wm(+2nF#B z*=_O+^Z>kfhvQ!PB!T-_;yx}pkm9a8a8+PhjPljFwFashRj2ej_qcIS%qzi9xai#U zeqK(k-XF3i6okocpYqa-+3Op7_#azy=UP+yy0kRmU=$W%IAo^m7q1WlKNfVpC zG09~9Upx`h2(RK>J%GFK_zq&l14u?qK#O0CPd*pv`Ky(lGgh#*Zb(XNI>B2&8waVS zWNOKXohwRM9kR@y_k|0SD5AV3kY~hizwa3z`2P*+gH$TG^0jY6VB)b?HjL26LzIe6 z+_T-N1T%;QCJ_x(=D^v!2Sgj%@Y%0Eh}?J@YqDkZ1moyn?CV05D!aJg`^y45Hq=~>3O^HmtrBOaY-TrRFdRErFK@o>Qw~aaRT-xjYtkc4A?7w}fouWJtMa1Ta%Fp&9m#EA=Yc)1Bz->CtB3AwM{9 zT-L-yGf4gu@k#;Kcmp<8;uyZJmo~R5^&3IRi({pF`B>vpSg2!0$!q5?RumjbWtCy` z)V7(piCO`lp6LMvHZB07Bdb@hl6oLn+*6ZNs#xej;J7R{IZ`g-!2UyKdKDw#hb;!W zN}3(5ve7DG&2}v9jUyVYVDrW$IPH{G$i$AKQMLYec5(vQd<}VxT}99cCa~;9w;<88 z$__XsYBnkHkB65(=(5wCf-qqddTJaRwB?&^2T$a6 zNP-iDQTsu`y~Ri1;U!syS_2~^Ll_(w(E1%5oWxz<{ywUNkfmc%K_Z^g;jwthV%-X& z3??%R+1?*MbVz%4c<{K^8{4HUE=2G{4Ig^X%~-s&S7KwKP}G_Cl=0i&{t;snK_%-JZ?)+iO0zgUsob|_l^TJq69QgI*lTXTn#q$>o39yl0O9Bj;@O!LTd^p0R z)ongWuq3280iZKboIs!RWXej(E;CtZ&!((f7`-ZjJ3~ z8jad2&N!-Ctl=kj-+^#x0BF!NK8cerdNryIqBta6x9hyJxtmr};`=!M+TBNPlHiSl zV91$1TWeg=cw+J|vB?MDBK2yNzA)o~^G{d45rL^EUn!l0V2~m;M*OqBk->mG5LwxA zi-j9$Y}uX1mOW974EE!?S8haGY6JQYhOp(oeu*x6o43XAjcrdO5su*9%a@~@z#}VP z8RFD&bYd8Txe0W&hp_3SC0Nwki5dfXB!p@JI6iS44dV=tDj?*sxl%w$72 zc)T6|@rwxzOpvUjZ6^|-;I=9=%OY}Rwld5nR#|kVA~!;|AIM$cO;@&FtBZdiW_d7# z_uPCPj_uin?2dzoGLuGKW^iqsSOcSf*e3IbDt-P>?RZ*ruXWA6j8}sB7x&JwSg&hX1`C;GdnwzEjY*2xj z5SO!ECO?2xE;kQ@6k*Wuv2ks91|Fg=BwI)GR_ zfG>RRv&a?5D7OCG=#d>*y(oc3_vR+Mx_QVszJLzo(zFpl5B!4+ogL>QP*3=EA3(b=%^>6pKEF0`_~g`&XE{}B8Wt1*1E+?7XNYAxA5B6 zU5y7H+lHU-S%T>XCmh^FfuAaH0efj|0zbd)OcV=QA!-C#Jd)?H(*pUNYt{sh>EgE% z72_r_Atd6$B#MaQ=+Lm9-3ja0;qzbk3U==~Dr9P|J_J9jj|CFI3LErqV_sgmwjlwu z3okkwZ@cbw*neOT@;SOEn(>ZgsjFrD*Ux@|v8h?Dc|zPeL|m25=O%GBO|XzHZ`v9f zS!*=JBj6i)^nuESNmb!g;-u~h*S6^vc!bgS;+gmpX&}nTNsU#Ow$w{>7;&_)`G;AD7pho=Zc8NQ+Q(gF-#VMDs(2?T zu21sG7=N-^C10Tk^%4T4?y1@ixk81bmQsFXOe88KEeoDGe9lSq_Vyv3V3Eos(TY44 zc04Dh#wPHaAAJ|W(kK>f+>ExqRoVkQd+CW2W_v;jk|A%pHrKi_Mu)`$DUiBW3)i;z zY3|>eEf~k^s8lJ!#qNNiEndird_({FDQ;)Vsvl_jbahQ2M*ygcYYP&**tDpxeP0l z9hSLpwa4Pf<+B)?7#EBZik5KVx&`R&OQS)rhHwU3}sBShai}c5mH^*zg2UvZN;3*@5BF35?h1?nk%88X|RINid9bPdlQS4*aEm z1dwzsgKI#d9eh7l1Pp9!gZQjXN_&osWHH{uLM{D-7Lmzo&Rd3T*`8H&KA<+MKZ0%Zv2^(=baizL(P2w=?~WI+ZQIl6?26)?v#-L!wWl?m z-#i5Fv;Vo3Favw3Fe})vx2GHIm%jVvcVor!m3aLdUZ*O_!|c+hSO3`vqrAs=-0=-` zWzzW47e6nd7e5BKf6sQDyzwN&(hF@GL}Rnw9EDX>SR;vzs+slBmiF-BV_39kp#tX} zcixF@Pd|&>KK>D`UANAZ%H~R>iil>M4ZaqInwU5U_Sg6%Fq`KTP7(Lq^9P)B=2__I zNUK*$awOFrPdoW!^e$K=*pq9>h;dd;HT(OHi{K4he1bJMiSYMzZZ+Zm-B)!I>LOw$ zp)m{49`e@r$cU(j_uhO1KJcLr;Hl^L;eq~DIFe60gLfZhE}dEu9a)9exwzP}lH!g=F*P}XP_2YBR;19*Rzu7VT^?HE$kgZ&62#q?|;y;nmVBJ#M@nw65GXmFjkFR~{(>g$HO|=v=4HYt^ z(61#gEv-bswHGv@;1o7}Z=c!#kzfQ{w{64P6HYKF+$G4qjn-W2g#Z68iEf#R`DC<( zFc{k5;d=kOUz-NWQ`FB4(0KU=c5lIRPyb1Y(&?MdLcFb4s3@;lCh`pNP@U<< zEj2Fhq@!E<32vh~yv35-s^g0o>doh7h_=1n`Io#3f$URPQa-{#C^`~b?q27wn=3Bd+#oE_4Fb)If*^{cjCn_ zy-ee*o^kCDy}9tW-}ppd#>a+48YRN@$3OlNfBK&X@Zk@97>kz9vlfhNQ!v^2;eY<8 z*#DPYaz3WAIeg+1pT>gTK78tvAGe-wt%}L9aSROfOL4}TFEZ3XM866)tUUqq7B6#&4K1L}7TkXMio#87 zsB&nHw)sELZ70l4zW8Su4Y_HY#~*(J)00!U{L0I9pMB!!pMw$6YWU7wU&SRCUW{Z% zH$M5}{n%Sr>1bRKRWJ1hB7q$K{ifAe-t7|`n`+S9_8bVb)sFGJ3cFH)d?K)# zH;Iwj3}N8sBf7-4gD3EDe|2lab!8o;K;%ZoFtD*61`frf}&E!x9|E7lr z{(1fZixTcL#sKdW$?wh2=0LF|KN>0~z4Lqyd^rjel-UoRe0+~Y_e zeRkrF5;iPpLppBK?Wz!!I5+Uz?xQ#~-asRoRKltRp;|+X=1}5r5g{{2OP`<-)#AuG z6KS?>jLT%kO^gpb=y=Vm)-J?5u6v7fNHtjAo}WVrj9F!^zOGe)V9&k-a^^LXB}b~e)bg=}%51n>EfwxJr<>t8aCTNWj)M3Vju7wk6MRd;w;0UZ z#FBTps_M&-YTbo;4d*dQnB8(s!+IB@uOb+Xq1K(|pUxkTMS~K({*AY(Uh@Y=$s+C#X^tS6YPQyUj6$qm*SVt6f3{mqV62#)R zG!_Nw*f_5T^8zunQtSSUL~^XDOa$r97((mL#q-HDMklf;R7=?N%me67 zTd-yDXX18vXchw#HAKn4b-~;gq4hVp*-d8H>}@#$xuLHI;XoY|r5Z|vuxTspMoLB| zCS;nUQLjc7r>$RySbiLf*Pe*+?350fBSYhuoH963nLEcX#Xk3AMvk%T)D*qXx=#*x z^ZmT5ueOxUIb|&0hOnNp_g+^!%)N&RWf(cBWfRJuo17Te2p_8`!ryDwuK7Etn&VSs z<`dH6>yzQkfWuxYpjfM?K7e=L^lm3j{EuxD+q5lih9y>&!VLcVH@{OL+qP|+ zvisY=_^*g2VtDr1t?2IQ#KMJ(Fg!epfBn*zaK@>p;hi^LkE6#1ap%{*hWFlb3s$dP zrAmp*e8;wDv10W)^etHBgoi9#_`qmA(jbNgj$&SKr>yeceBBL*A&ejX=sQZ9q+j8X z8=_H!BeRsb&d%V8zdefw?*B9HzT+!s>uwV(!ui%I{*Kn1#|DI=N&Mq-MM|c*2VG_ zD`kX6m{c;nb3|%dA=gN_$B!RGZej}SPdgbOx#K}RKDKmDyT;&Z-wq3-jH_0T;N5RH zQ`{9Z&1rEH<_bRjeWGB&&AphOg->>TMWv*>Ue)0{JT!#K$w|F0_W_}ALZMyV-7?+c zA;~pvuVDl}!t-p?u$nh%>%SkfquhoL2*Sd}qFR&x@tyA>5H@oo-e>;qXX}llW7R)b zlZ`^U?bePgFArz8k3EO+*Z7|L@ zf6lv7`ZLWPZest>QFPRw=S+A^z3hdL@4Jaj*n ztvwf^aJTLw(HyyA<_k&^y!E=7&(WBWuW1+S_n#s4HaA3Mk+08|)PX$*F*G`gOh-mK zG`{%b?|$Upw_&ZlVlh)_teXb%w_5wljTd|Fg5O6<1RWuCZmwkagB!vSuyZcD3W0lm z{K-apl4^03W^G`$7(%HMm9b5zI)>G~C7iOp4T0LE0tofv>#6fF6W)M8h*@j^vpK^1 zgrgd=tK}Sju{?ttuYWrN;W!#J#i$al&br=EP}!^0otVuOi|CC-(H9J2Lw6@OboZj8 z5kM@+{!Rq5T%`FTj!xw;-l$_N5k|CXvGYbRQ;*Ogt)x>Y%k-%YZjLKI)Pnes2s*Gwq0$3)pbM z8ORn(D9q+@bZ7!Q_fkMAgj6Dic*G9Y-b@0kR(7f95g{4wGoss05wbg5-_fIQL~(x?+V}ycQtl9&DCuJGhw)@oWyc*)e?P zQ=c-2F|b z%2>v}eY?ewKl_50Asiu;YeZ73dfXHYM@}mx##)rk+?_6dv}9>9(7d^>u2GdOX>M(jRt0JBpC%uJ6Uk>cjJ z!)j_~Mw*7?Ry@D;c?=vM(q1~W{}4WN+if^y^CmM6Y8aBB3dAWtdRBrzY@0B?>y!I7 zPV;_x@g$dsjgE|9@!~}`0Ww#;&W~|9YPg|bCh}9M&EoMtKZtWLz7RkB{dWBDxfB}W z0k}~{u0H_@HTh6%?is}AZam9c4UV|jWLZ1kdlSX+0#U7M=I_>m;A%^@DdB1+UnW0J z>1(>Mjtq}9XTw#Y61ry6&x1V{)4peMAT1S{DH#KwNT!0gTZ@{)kZ~6GEhT&N;ym4T z*LOumRj*uXp3c>94oAe2d?-Qiik7^09$Dc2^A($kx#YLKt z@j%jkkl~b(fSDZo=_~opxUovU_qDIT9P8JvZAvR!!D3FG;u>h}wTQC5s`jKr`+mM3 z_d*mygF}eBNhDuM`$Jv#riq@~Ynw!Q%M8lSf9Eth*WW{H+D}6`@}kpWFc`hnHt6{2-SMuY-sU%7f*tT&72Tx;a97;%}1 z!hW4uelpM6HI`IxG`h(bbOnVa)82mFB}SgB&?Ey}QegMVMsp?O?X(v>@zbDLLlJmw z=Uj9p0#E(!4w=R>#cnvgI&x7hH^Q{r>+V7A_zWG4=%|eQS*%D)j(H$7uM&EZS}^ zMQ!+YRB7zaw4+$8VJ25ZZ>9$)Y<@M0^%^FI_o6s6fqcFUq)$M7`UO;TLmCZY@{^zl zQn`wii+Ygg?G&MN-=V`OlsNJ>r2rO-GI#}%iq`Q@XD`6~PGCV_QeseF`oTVoWz9{H zQk?Uv{kYsx8Vv(!_csG{aF)9w1?ZSYrSH zAOJ~3K~#kA2u~`2+UDkmHTJ4OR}3taI`-1eJZv>L@1`W$Giebn*@tA%lCvZUpo9Q< z4J31NKD(_=!JZrqnk$`qVmsRBt;34-=c8UP<1Y{X54JzQ3pc;}Cd^;54Ey)*!_4dq zp4;*Wa=9sd=>7j9H%O22%-p5gcf4IZdWRK3`e zc?(qVjXS=K8*X?z?tg3_zWLV(YT-5$?DxJ1n$NbL=7z2r-1)9kQLPn}*z*1O9KE!x zp1(s*ED3g`OzGFVK+oT0EaN1TxfdKy$D?O_KTZqu_a8HF1IN_o^JJf$)iVz{&EUKJ zpf%`5!=w|Uj_EHyL!%>Cg3;4Pv%FG*JQm*(dxW zN;<+M4}IQaqMb^(U6R3{H)Oz`6n}Hv%-t3 z@sMKTz*b0CcZW>ar1YpmujX1OR;_wM8z;7i5=+k6xfb$1^WbBF#bk%^qEfEm4R5*v zYgVmxMH!O=6ECuT?h=0`39hB5XX-TtEJ;;6CK{ESu0-Uh0?Y4_T&Wz99QVt$`@9sh znGUG{GAgv|RW(JJtlqYx)V};dZe()bhj*uO)BD7#YLD!h=So@00KdAs+Vp(+49L0h ztqh?|v8V{0bb;h_o5_qjS5uN_UCWu?LuGQGD3@O0q!Urs84QRI=D0!bbMif-F&4Ze z6kBm+uc@2q$c*+${k3@FqU%Gr_O;_K_~c4A#wL7PeiG(?bM^(7BT#pSt#<4>Se z%47fD9XPo28T~Bh{xyc>CIT{T3B+Tx5Cx(k2H_O4r5bh~$)Y(6uOx z+}Pi6Xy1O!CN9CbAGi#U{^H{Z{^eQBObw!qn%WwbtmBk3PsZrvBxVa`932?K^mG`CI1P3>5>DvsO#?;cE* zlE}_dQ#^oFl4dG3^&1Hq3=dCZ@q!GZ(Ik!!j-s!(Q*+9fowEWf76dUkJcGfpS8I+qYx!;>BoBx8v#O zU%>ai_hXi!s^D(>;QJ9tw;`L&VRU#<&t%V@J?QW6R|31`>8DXF7=%k3Y%|iSi>q_< z+pfnYm%UsSB4OiHdlHX5`4lLM{i4mAuy5a9OioN<{fX;UDciklO+EOez(cTeld!*o z9o?zq72~uK9U4WbzDZzo0m(Jp@$)A_R)z+W`3>Zp(5 z*PlKY`TUfdlyTnn4we_R>j-o@gSRMCe0)WX3>#OB;OXQ)sRY2E1{^EYJ^-v2AaGN`b9YTX3t%aaFIJqIjyCsB0ABMXFw7( z(S$PX-J{y0EEa4!!tN2*g-1MmE0UsUYz^BXUlI}_(Kiv~Ox2I?WfLGl5hSILKE(>X%}}i5nE_J)c68F|IYxBrSTB&>iF+_2j=ZnHwG%7UzT4W=RHR z!RI6v6lJ4MNg~l~SvbJJvtJESontNij|uVL?UT87)owb+82`49n*1N9SZG2-Rnt2O z0;#y6)H>H3Pl7~DCQ_`{O?b-mT5OOmEb~L1>~6w=iH8si`KlNPW^7_YzB=5Kl=X7I|ma)43uNjh%+wz)*8O-qC z49ZY1i8sZKN7QNtIq|hCRU^R&df~W4jlDtBzxF+lYCVXVd>!xo^us6yJIoLV5EGd< zli6xlM@N(0t{~{LH$q*U7jCDB5QQpa#9?yBiD&}xMir@849ixXfO0Epgsl;2;~cTRh1{7c`7EeGkEIhZO9f2E+eMuAdQ^r zNW}wKHZO*bcA&SDihSLOL>u_!ANOLsKscg=i#9F9ig_gc0FOLBfo(?u`ked~i-r-8 zQM00k&P)mijtpV-@`VzInV8Artkc(E$Ie5z?utcNzrx;gHebceOc>Ky&ZGmGjwF~M zMJ42BVj;m$T#K_&H}7=@#s1*}{`km2jLvfS$mFc~#Y32+u3V0AcogmF6o@tya|P+s zmx={+q$n6uK&2iQ35>Gd6qUU8m3^2lhS0tE4e0CX#^As)?A!G`mMmO}^Ir1O<^kkc z&xUHVXWgng`0P0;Qpn99o#{X@62PsuzFz`O3+K;6Bx;9ZdwUy#;h>VgdGmVJhbDpO zg{?cVd)FS^dFLHUs0h;?9~cB06)az|5e><}@|OiQiAlK%p6fWD9fw*lwL0EcthUq?8Rz!$&x6)f%R#T(ypEgpON8Qgv6zvKEhzaAI8^XQ)dI)cN(_5R;x7I##!Yoc%liCYvk-3WMO|QBdFTeUqC!-udx;>3w{N}fq z-`RCotfvyMO%s?mNGRv(7jT$H!*y zt%pK5UhZ&6f*U7eB^9V*=5OCYM=FXx{N&517sn-l<`EDN%llTz+=G%4Rc*LAa=hLI zs~G@QT(%Mg-zu^LwXV_U!J$Es7kSXcVm#EW8rR{cF;C+u@US&8GUI}X2cszyYFDrY zkjKc_D1Q0tKO*e38#s1tq&-f98C%`{ic3?6(IYBN{T(2#4N9XQo)v|dn=zcMVIiC*Sma#A}&X{W=Ut=pxiQIhoaKo0PImi!$(&M-d7}z(Rd~hCLi!D{m6}b7Uw}Mw&Co0VJI{ z#?WL5I}aC-?p}m>3)bQ7Z+jokx_AS=`h~l3?Ab?9tQ0X@h#`;j5J-0;I{HmCD$`iG zVIB7D+>V$N86kB4-0@@bBVa!-(;h`EOcbF3BGQRi0EuV-y=F4StrD;Rlz?EmG z(UakZj*6cUAT6{JKs=f>Lm`od%)df`p7Z$(e)`^^5{no1P2v8hM-dFSOU2MgdoFW# zeMLT_dGq=ts*=lQHBQ-?Y~Y$pPsdo5W2+0WclS=9mc{1NXOW5zVe5f&u=$+JFf%!c z!-w``@2={0p3;A#9tUZc~E@(v!BDv;3U5O zjXMyDM=>)qiT>kbGV6Ksb#FymqTS8$x4=)XYgR@r$dy4LfLFcz6?n~?uQk;)w&>c- zd2?=0-}?V8gQdAhf=6cj-}(Rdv;EB=?Si%1RgSOVwGup}>4ORH>$6*)#?eFj#7lU~ z=O4j9eOc4MN`acgNGPMe|96-_uMcm3%>_97)Om(Xx`Mzb2^MtiXM9qir|){Hb4gXY zUZ+-S>&M7!t!Wc~{TAwZuSg`L7!J8N{63p@;?J0PoEY9h5||7SB{f}pQ}47fHCEM6 zJ@YgkeDDcX@FFOOgUHPm(Akx-g30~zNB{|n^wm&XM6>?pps4%kf-s*k3nUwVq`bBz z8aB4b_Mka1^8HDGo0y!?!OrTBYK^lrUZbXg5(6&+WU#wWG^9=1u*8K)Qn^gm!>W`e z**fHxZ%y%c-Y4#Nsn)9HLPx}?OA_c(Nd%>&vsXk-A#vObRlMic8_=FiJ01v;2&bCZ zoN6$%$Br_4ex6&vdtNS-kpdin=wSV8z*4^bd|IF|=`3cR$$z)H-y9jcYwfx?C+UGyC$0j!jay z*lN0z%|yzczvC+i&1e$oe3C#Zt`In`SHA1Vclk=;`S~em1X7Lxe;9KT4d2&0C%aa$jc@@km2S2T7QGkwlb6 zPIaUxsf-4m+%b+~C4mUDJsPHTpN!Pvm!L8J5b{$;P$?Hs%+HttV55pyzz%x~pUf5t z`n*ME+vGiDXAq0T5DwSS+rcWOj&wYTbdr#NNPYp@h}2hzhLNjQ@!*zWBxCH6C()fw zA)O3Lrt?pa?m(##$4r*uDgm^&8JoE?%^qkClhb)Dn3qB{P{a6S5oew}AIrMSh(zdX zU?d_Fn*rKWWL29|mu2-v_L4YO$ivb=|G)(P^0yH@yT7P_$wlbRdbm57*m);MevY25 zE}=&xKb^WPgln#SJ@ySn(AJUB*j_Xl$HdrPj2zvH7oGbiB$8b?ba*EY?%9Wtk>j}j z`kUpZNVt@^g|7-cA=CPV*1se3e0pkJeLXHU?HqTQls%5=9ys7{ool{UzRd{q?x@_It6bxJKk#3pPH` zawfBcaIlU|ZF}&Un_nSx#aG*wBv|EcC}K->(f`@Se8&v8qR<~I`h0e)>^+@rx39ST zsF*4&aX6}~;(cpFh$)jvscV@Q2uX@+ttyU@q{bM-35p!P|DzwFR*#@svnejd9TFye zm1{7)AqoCIH{p0kFynji-@PDGbBe*S-dW*m!a>PG%Z!J-0D7=c6_G!`VBS2bq#B{n zUX%NQye^IwOPX8-8^z|>wzRcO7@JinCtAo&U>k$jqlEkAFX=RGDw zu%vpcT2b6*5uqBFU3Q7ab`vSeJ4X<4QpI+jw<>LED|iT8cJm3f894H%Hi`4S@YS%| zT}lR=_>sF`EOe~j?-CBre{i}C+9#HMwjlU9?Hz;KTYAmDE$2zanwl$@jQhpnH#e*M z8Hv&cfJIzQGVRqe+dd6MBi7!LZh|Jp*k*9r4Xz7F9T$(*`nH95EZT3D;3+w))=@6y zF+G#h`NxESujkuO)=Dz5FUAlnaO~%2veQ}vl#=%unLR^KAhq@7$&hx9miUMt)YMm~ z8z>~44cKV!7BCoN_$4SHCaQ>22)K!Z}iRM4YSRvw{X9SNH5)N|%5Kp@AsRz)W zCSeYko}Sj`pfJh6;Gp_7{J?~GB7*elNGGhf76{bP7Kk|KiiN;e~_hH|$3FHbSa8}Wl zitBJsL__H5NMhUGL9AYq!Feb3Ar`4363E*z%V)#uC+ST(+zlZ&R79gUyr8hK5yA+4 z(eOnq*LoPc_YGige;M~b-j7hU&Dh>95F7W=363}(5YZSWWRYMIH@#{(`g+-0OCu8R zMzpOP;YbF7SQPt@PGRTvehiL{p>M%r%uJ1GgT3SJ??RXw<;tY}nqZ}1jBLHPvT+i7 zxM<5(d9b?T^o=Zy9fZlx&?H2eEH^g@*RB}s?yzGIkmR9VyPn7B&|zG7;iU+tI?cA( zO}(fFanjjTcRY6VFcvPDXXY@33&o)eARLY1>epUlYd8?nxaf6nezPQV$H&JpF+Bqo zS({Hk2`|0$A|=7oGqV^N9Md6m!#m!AbX!Kjj`vYaefQ-LJy!FcczV{x_4w$gK7l+X zwne%%4-TII?B4MLP|acSiuG<{!p&VfGn-b>o5L!fBYo|A-TXXF_*V{jCORbqgKQ9) zl^M%l^;QtLeWkw+z*oLCNfz= znJ%s+6VG9FUa8a(PbIPSg&p|gAMQ7f1C{mIDsq(?gE0?UK2HfFiBnLvq)Mi4HZJL_ zb*ZP$G1g)Kop$81mUbhQv>oTYkn(2Tsztf9k}=P=M4{N^JMc3R;iHBD-$(a8+ zm%(_Hp-F)B$%0dp(KC0jy20$Nz2omI|6WAaIs0OCY#gH_lQ?kTFrIp5E2e~Gb1gB+ zHN>4$ThUMr=be8h)~#EO1%17Wxr_;nRg7uoWnv>}O|1`yWcj4qo-s+xd~Lr*ZK{k3 zDxcBF*o1Uec+h)9O6?rlfBQCsv_othnxs$io+u}8Z8)2Z^E6;TD(csz=b`wPzY=Me z#GiG+WeB|Psw*1WJRG4ZSF{id#k}B7y{r>~Abo@mgCu9QwVS*oADlKqEUbf65ET1# zP8Dw3&V3je9hID}4?-ek(P~t%MyoHyLpM7+ZAK>!>SGmf>c%zLzVDE+zTFLGuwpNb z&>30xgp0+<Dl7pqtF;i6Nz zk%?!KOr%h+Gf|1!tapt8DTH)8GgvaZnH;bON#aWgF^-7}ma@;3E7fs)h%DL??t7vi z*(y~R$(rQ>ZdDAQFV_Mq4laD!83!A6bSG!bUwXA3!8Q*wsvd{2lfgE!TrF&z&1w*o;tkAS*f0_?nj}rDC1UAImY$ z5vi2ik{l$-Q4@aQdmY@n4NpGyAWlEyZ0y*vN6(Xq8o#EC`~{W-R!W%7PDwP2 zt&spn-OA*|uqx)YbH2QQfFpR)ikCk}lP6w>q)}DLTW~+_G&ERg-Tdxb(2?m@r6kL7 z*K_w(yq|NH^JOTE4a=6}Q~&lEwUW3_eM`baher?ZM{arqYd5?IJn(!4`;W+h@7Mb| z`+pQ&A~Tz$h5%WSJKWW$kg^qj(~Tf&Ky9{hjY3mh@J=mT*zOg|ERwo`Kw>1BQ^8 zrigmi;ySdF1xX&uxzpsk315570xIn38tI!-qBxQzJcO3H_GR|e-Y%{Vr!2Tn`QGF{ z@Mq|~!UU9Zz=W{<{WDDkLl~G~aQ%@-!PnI2yWZ1WCjH;@Gcr+-=$vGjT|z~3_9%H4 z+2&_wte`IrukWOjSL6J1&qOAbHV+18&SiCC3keW15Da2AH;cAZS{!1Z9P4+*2j5O| zw$ZNbpyZe6iEH6l;_S(&PH@Si39f}{X=7`=QAnc3MMH|U{X@feVf!BZ=}(WML;|-9 zltfoOa>>O@QncwFSk)~F_HYor-ATOh^{>P7Weat$&D_lnZA(B*SH(osEWtHSg0rO8 zy|%S8_jfCpa~K#HM=b!86{mE7)~`p@HetKexeo%(-=>$XR$_~2VNqNjZpF)o3IL24GHxiPBN z3#M#rF@W*$0`~XM;L!0JUirokBa-Y;&{O5F%8;L29ZLJv;7D1liD=M$&_l=;XRJ+O zEFC9S5fjd9#*Vef&B;eBavtm;xVyUvUD-ZoVJl7UJf_i zax1#hy*AF}dX-$y3|0(48jYpVkV}5fKIt@k@c(=ORp)I%^voY}{5hfyTc3R#r@rVM z@o#)GV7+B?74=n^AAvJD*peMm{8c3+O`G8wN>wV5+U&o%!dgP9b>y7uSVS-(-}>BE zOpOho5%0pc9;u-iOq<#wRo?vExh5BYXnh*L{>1qx6ee6n?}C!+{d@gYJzFk&b@f>FORAaVdcz&RNMk$fKFwR`37JlsseAnzaVxrrB% zGh}w-obV#-&(;pVw4xmX=FuXqQEx3xZUD)TJXm>fvr-%z8&`rm(n5a#03ZNKL_t)d z_N!DN%^jBFUL+o~5aJ={<&?P|SOhU7d`rNS=xyCPBD0s) zcH9DMSGYvbApp8xZW=;={5#i3SM9mDz&GPH@p*3Bu^-?6;jb_|J0mU|+hY-uL8T#6 zLNH={CH_A@rfQKJ>Lc%j2_~-}m!t*=S-{L$kvms`xgs{0W zsXoRkdUj?O$yA%cB2^k$RFz#a6Q7x$L|$k_5QmQ*RnLSM#?4}GY?cX%h$v{^=EnV~ z4M%dgkY{Fd>eZZe=4sfvZ7pbA;4p_)DQ>Mb2p$nl#6>q#^ z75?kjPhqOjg}U?-*gvw-6;&mglePY|!BZwaqAb!$-AZwc^U!XVnWq>@fF$sBB_mj~ zEP?hUvwm(ugP1s~!`~xPhpQn-q7*o~v0V|x-h;z9VM!X7pVxa#LBiG)1_ z>@?D)hrw!__n?eYwSk#w9!3ou94O(LLkScE8JuzYsW@xX=?IW4%a)G2C951hcA5cllaKTKZa_ZS+r%{#lkG6 zrpBA{sJ`0qy=F_4EK}#R;bCy(@KFVKjyw$sO^W0Vcg1ISotf&9&CN zW`Yu^0G@nm3-0}&2b&{}Jk0nW9%(S7prk{b2Q}lL5Ack2-YS~+od>cvQuAg|{(HGE zJz^u_r5LZfO#)=(5Ad}m*u&O_P&1o^V9~}FB4g;>_vP9mcZ(AWG9h8Rj$_~~ zsOW0S^{Ioz#ksktf+vPD{`0*|N!A=>$saSs*Af#|ra}zDhN6Y)xbBVDqPshTXgH<> zfw9z&L;AgS=+GgoT)EOVmxKM)TNgRpacsO@xU;9{8uW>8bFI3y?>$F&ootBlZIV70{#90?!iom~r^NS5WTxCt6 z2nL5nv3kXFWjPEstoE3h^3UWfGc#A_FE%a>OiWFYFbo&51bMiCnK_q>c>aZ5(giRw zh{BK~t@+lW!LwTEXec46l7JKExDX|jO%9X?D3c9BT}DZ4^&`31i9FDmjjawM4y0*_ zpC!N8_xQ$>5Qdgy6-VJ`1RWsP`Fc%q!s)(LEr#i5b*ro3baXlgJtk_*ORR!sa#BGc(uVK;W;aU6V8Nn=n4X}J6Hx{BvZqzeNJGC? z!P13kJhS~6Rxa(pWoOSrGL}a&O6~z$3>4tubFtAeYK(I+Nzj9)Bk?dIK{JU-CEG=c zp;yM#G%dM{;+8NOqsUE&Rcnxy24Q~Q2dgOBlAHsksJ3O*^4Ey?KA(Yk>N+yZS3i|i zH3h3o`ZW|y;Ai&?;mq^S!+1W7^UpX3`(F49Ci}M|-LnLzY`z$wWDgMJ=&Ma>5Q4I5 zB5a8Rs|&B)?pe~#7)X_vQfXuL8n?m%Air{@0&cwiCVcshe?>gmC5Jo{M6$7;Qi;lr z*4J$w+)jXs2$ijSavg|daYT*+Go~>wLQyb+Lx&C^Un(M#&S->n!TkAh+)Jb~(sTch zpZpXDcJ6ar1oC?5U`lfzgS<70>7;;p&F7qY8b0!gkBXeNcgM4`$__?jSaZUu3Y0{T zh*)r+@w$ZwI1wOEiX!YRlOh?w*qE4AsYci{LTd~4@_+W#x4xI0pmwWPJtRz?(&s<( zS={oTTk(Of-iz_bO5JbceslVRfzR3q!DfY|%y&up1?KxF@k$4R2)~rH2LD)PjD_&}Nked^WMUYOnN&VH_8N)8g zw}41aQYaD^zaSVQYu`rh6j+6xgz>F!ej5jm3^m21G?`K7h;><$2Tc6DnG=f??iu-; z1lgKxZ;C1Ts*Km+c>o^G;j`iQdQ`&m5_nJ8qGZhDpS|u$K(owH@>47ooX3tGoW?mw zHbvApF~-D*2R#-2iX|#H5{=@aZd@*|Io@~1c=_Ep^01Aj+BhbY6wg~=F=(TgBy1Z> zAPf0ORFfoJ$Av-}C#+eDtFC;7q}!V@)=j1eor=YfotY8OL2JxSeORW-?cNev^4b&L zzr*B&TekAe=@vIyDc=X4HzMm9x4|?rLU``^9r*b#?^Oav_f;l4Okn&ds*PS6AAtAr zf&aZ9nM?;Ryzl}MSXm?}A#?3#?jI#9ioLY44`W_;7vAyq*C5lLaatVQUreHmDC?6_ zwi`Ik%HLU({v(pWB%0?H$0Qr&GDgR;7@eBX1Q(NDo|x7KG9oC~uJ|@?n!zS_>>10i z!No%VK1#@hK+YMTc4wZAy*99!NW%Nyc0nT$hzsHk$I`N~(e1Ke7 zbbF(+AcLVv6I-@tz4bX_E3Sp17R2mfWs1$8ExvR3>?282pyP z*M71cv$eD!B;#ZSP%0GkowQ@+hLyg1u!coFDeOKljC5NH=bfCw>V=$Y-~uTN0#C++ zA~J?aBy|-x(G)U=!=VPEBrmEb)nZ@so|5coA}Y+>nZ?@(n9?xqFKWnF1h26YF)|aO z%DPCEM!55%O-?de8u}rP!ZPStdntloqz~mrCt~d}96d0Em8V>a+VC$Bsb*2F2M`D+ zkSiq7KT<`{lGCts%_(R^+EHmxQ=VEIZe-E&5fNg21?AHeKU(Ec1VM$t5DJwFzH;dMHouT-T!OAvaXfR`$JxQ)j7pQ0h%X=mFys(qg zmfbCI^w=@1T(t&?6z#+Vc>Jkn@Vj6CLBXF1MoHWk_C$@fY~xQ=rCU7AH>_HL_rCvD zOtKAE$s=E+J81|foV?k|Ofy-fExB3F5|-pTx4q@&rJGXBt)Sbq)Scs#;ag*Kf3K3+ zP50Dfo8W3A1KaBi4Go~Xs{?!Y?8Pr1I)dkhm_Ry8yc@S7LdEtI6a0nY0et+%m#H8S zqo7(5qQHHn1FUFmLso38nvV4!!`AJ4^f`!pwYO!&k1=+)vAG!lNqAnrZVl4uq>2$9 z-W{D8adOOkFD{Zaiw>R{R@pTWjU|*oQkuJ?vj^SXJv#IWrK_(SXyB1Y9>uSJ|36B+ z)KXHRWOM2MQ1-1zCJww-*-=L=fnY2nBEY!BB#y*L9jTLgV%IN6GnAd`HqO}BpQ&3!EL_%xQ+n~M) zk&iA;EXlbtgwfGaB?Lqi#Lsc<6bbY=Sl_B(CbUH2>|hi3CmdG6q4?qunG4Q84QFgR zT_i?cr$;UL@ANt8=+>4z=GvdfgrE1?X;S!o zVuvgX6BY|0MB`EPbhP6YFFOaDHl5bw-3eh8QMTpcYRO|wHt}9#h@ZpalAVp5uwlVU zo*GTd4jwv+P&A~3mq}fO!h@W&FoK`cL9m<0YaBR!3|-wlN-7y!JfU02m2a<8v3HJX z9Fr4&9cP|@83OgKuW3-khT}bjA}jB>f^xkU$K-4f0|PVIb6^02<2mFCVN~fDNeDL_ zN2asO0!YG<3K4R|J3@_inC#rU8@qPwRpnxblw~$n?0QDCW#L@t48R-Kug9J}yD>gF zhD0KTjVG?db6dA5Ss*)?2Y@m@w|I>KXMJtom*Kb?4?K>8^!D^>fpHNtm@A7GyLyh= zo73CoP1J^WlQBX$>UD_;>5wRKHW)%mm_Q_w5zWPhnT^#TqbQ&vG7IIR!_feO>~&XZ zq*TD--ZYl4o{#^&?+9{L5;{c|n=}E!)`M9L2+uOpDXC4}vz?y{#Tz*bQ za6bbdTM@~42=NFvDB(U%MQ|>fl{XI-^T{wj3fq200_E@g8K>684eMYpB?o&g`#nGn_YYgf+ zusuQafP07mx?T^VTqCra!F`WU;IcR0h8kQZ&IFCYL97+$@FsZ8QUyN|Z2bxbl@NIJ z{`HYR3w}NO?29#a%8Z*MOkAhx(`sVE`i-*tj*-ks)k>SPAk5655C+=^d94f2Coq{| z+oz#W6k}tXg1!5wVG#uZ4?^m!p16S-D@-sbD43WBuSQqhyt=p(M9(5YtY5bh z;ULhJ=|D$kT5SgE6|`qE+Mk?e;-N8r-h4sswl+;1j)9r+feDHZsz3mHcJIQMzWPmP z6W=;0t)*!RA@{2$8x&h8Rc|^ctzd64jt9Q>kK-692J%#tu1i%2U%tS}0n_=HWU_Ob zq^l|qs%b~4r2{LUF|`g<_{hhCcEtwKQ^JpI%bY(DcWLmwSOUoA(MDfpIxPZ~U$V0;im-F!0PM=E`BWGyjHcg0YuR`K&+ z-GjY*`-RA=Rixy=ls4_;Xz04z(@FFnIf~KINo$KU`6|ph!mw#qc&>={i2L&Q%oC4O zZ84m+c|Bft&8tzXkk4hjC{A_xV$dTq(jcn1c9G(l*RAl<>rOkNTE}!Yi(Py6Yb~+R zU;(UnDdN84;W$NO`(U(GpT_9e1XiyxV?RGu>IuJWLo$B&FBNrMmM&2_^SsLtC_HhA zVyY1w2&=O4W1oY%0z3`~^%8On$xEHpq#(^Ql@J?x2&GySR7H1p^qHoWe|@h;oq=3S68KoOar2=<3cmPl7Uv<${|)psO0~ zH!TPgu~2{{nM9;3>-m-#c=9DZd~T2#I=xjOLlgE?85lXm!JDGKDTAdTM615dy4Y@) zH=MCUl}eLUb4XOxV^*Mq*l6^@*H_v%$5~7B*^WR(^hFt`4&FLuvNU>f=2mlb!?_4a zj^Q>SB9ki=&?d7N>bwV~qkj0jBFdlp8L0oawwUS2VlbLtQy~S{1kbzJ2XXsE5v@dc|6D;1Ca6`N11-`{U5rKTUJ)iB#42T z$*Aj9dM8!h^lyLrTbP=eR$GCIOIy0#U=%lZ?V&@RFQ_u-zcX3q!AuM0sj(3ZPL=TAj}Dq;YgXjrJBufBZ+rbz)2l#3?a>!xIE zY|#YPENBX<2-lKVWR+T@Zh8YmGyI%9N21?#>xTss z^EnbCC(0xwWR44@ajmSXwgjQ&1)v#tO)HcHU-NqTXHQ0C++rfb1DYd)LK)mt06!BG z50cj?mS3qgGy>k&+bxvK%PkW*<#jW$kUh1ez0IqE@y1I$Gkz+$b~e<8!ZDr}Rai)< z$yJm@d89w%rp>asoRULcFYgaOvvFU_s$|7?afdEHqo1Pa>FK~Vuc0+O+iFoAmLzUY z&P*cR)*<-7%%xb+wB)w^A!epXEk{Wq%q~VZ6RjqB&+fbUABiOP>^p+r{_amo=y_f! zd6s~cO&0Ns>w};3;K6P3SQ3T!qltDi$q-Z)6+Fqm=RxW>v<#8llmc(6L3IJ-XG=JAv>(w_2ijt09KsK7 z>UEq>ptwj;4wlNc)u-oJjcrtoLP`Y6!&0X6&xD3m10g#qDT*)|VHRFOM|)Zt@7y@t z3{x{%*S8~)uPR$=j?ayZPpXH?YxP0f4kvyelOFc=!b);jO;J=zK`I)?%yfbOgq}H0HWPDJ7p&C8<`#L>Y1>NykC{6E zj+H-o6@=%4s0UJrFS`{_Y&(dVd=-a}9K#u#Psj4b^N}Cfj&vrCP?QI<@fJjC)wSCH zThYKnD1xDhN&NA*zs8kUUX5s?&8jdNS=E}Ap(p2YO>?YKN@qcPR>n~=%VU0@p0g?n z8+G#|y6RD~Vxl&MYa{dz3}S3_3){AvaaaU0jr8xVnQ*q5} zuM(1BBxd>)u!Uq4_$f~!9*8PZ>Rs!!g<1X7P2K@&m z=^u&+2ioea1$dd+s^rpTQ)p!D1$+ zGr{(Wn|KSF{)Kg3EzuV;=M`hcQL+P<3&D~E(@!u`q;Zy5wEg*^r}6NkTbg6mzD?o9 z;mAqi=b&{xxdtYcVAB-tbaRKT9sDh%&A!K@Jw96(1}hn9`@O9_h=2azjp*rK=p?`m zP4HY08=-8eZ2GpT-;*LXij!boC!D04oyp?yXSONX6lp!qNh^;0JHHI4aOp{(UW>$P zCtt`}8^Q_=zBW-y|96HU@OB4VP{nMngsE%= z6=wNJp-`+KSFB@XqKy9G85GK7=<__KDj$h@NyL-JZ1(WD7nsoR_PiDBo16naaB8+w zvY7B$(fWVP%**A1NNUW&m`VH3PhuZg)J6*7%ybq$ zyQ)u)jCM$vWUwuAO2E3TSCHylP4Kw-v@^LXvbg~I2c|JNl*RN^L2x_WGvm=PmMrc? zCLKXrihX!aLKvce068l*sbZVka0uHtUT5E?Jebrmei52ga>m}gETv5ZiM2 z5BA`Mi~bJ=$0v}>*^F{_b_SbHS%sPHUq+xjf$_8IIn{ zO~8@1i7EW%*FVRlm%kEiX^vf4*6ouu23#5c(5{x`pm<8;H-ET#20oLY3g?@h>tFLR zIxYd{nuW$Vzj#*6g>n_ER;)m-P?Q%1Ew|tI-uI!ew+k0s@c-y~?|940>S}zQUhlcR zPH#-Fl%a`;B2tV&B6eS~OEkt1HL<)g8Z{<)HBn+zjAEieL?D__r6?VSff=SUFn#9E z?e+Bf`>eH}=iKWbziY^ynS1Uj-|zG6XYaMwUh7gNM3gXIyl|oIJu;VLG5q#{`>|}v z5{*jneM-VPo^)e-bBt)elIAA@|G)ocC#~}esH453UC=ex2$OOiK643#^97JCwzU&< zpE$u%ui&XCpU`8AMef-$7BB8m)yt~h97u!s;VricPUq+0y(S`N5UnY_@zAtN(keBg za2)sK50xBLDGf}cqLQIJ1#3Cb7lGs2s{EW#8zVT|lQ+EYdR0k6yhH#d=PHV5xQ0jm z_a>Zu_Jye6Y$P)Ss5Oie#QSatqD|+p!a8y4G@gF;c|7&x)2K1w4pAqAs*5%a#r`%C z7Ec&8?iCRLvigk>ZrUq0%E)S!2d`lIC`E~Qm>P8MlRCx@KRPI5rF5zpuk3La^aXsaN@W`_W?{y0^y~lR8uaycC}Cp}M6VaNr@(8k^T)od5_V^dBONwP zj^wvt_u7iuIsF9wzLW<;5&Xx`@5bT7r<_Bl=@Lj|#kGhiST{aCqPVTrl_TzIs)!@J z?hrNA94mYj&Ky(1qgpod?Z~|D{aahl_!aMb$LnzM`Io8yQaeaIJNMpoK-=h{N1^5? z2u9{LEe$h%s$gtl3eP;ZTOxxr*GncC3sQ=gJahfntyeKNRKSsv{mJVr)H!{n#UY-V zCBJ&S8}T%Ry^ixPz6yckzd4tfL9^e&`F^Q_IdKx_q@k?GE{bPDJHWdJJ1;5Ev7pA zRp%YS16Gd<2C-}R9wgE&Shs#X22UJSpcS!FQm1pC^W-|bdia=@lPBWL?-d(dZvAd9 zCI%2r$B=yGN5gm>%zPz?1p^DQbm0Jc2iRk6L8f{T=dK)-hk{kab1etHW+Y--@yfVE zWX8s|sdnz3#6!;v#Xm5=o z8LJ>2tzuDM25VRKqq99AiEsLu7!G5TFuwXW9U@csQ#(TfGeJZGVI*5(m>i!$`wm$8@F$w>c9v!U03ZNKL_t(e0wt4KO>-t$qhg#} zrtGa$=^UYrN_?S+#_>#jE{yiJcHKKl&GInN`*YBtRSj0*d9fYapcahOZg8mA^E;ly zrVSe~GdnB34a3TDwfFBnVJVQjmuzSVob4s zd>Xz6+af$nL=yBC@6Ohk@0E!Pf6o#VPRE$wl9C7KZYXF!7?gn&--9=3vV(b!{Hn9ZCaSvGQ_*XiKjc}>V^ zo6kj54{K!$&38Fr%w&4)iF06F~>7t;$vr%tGxAhduwwH z1VbFe_t1osAws6F;~KPXitkNtx(L@?c{#!%le{-kthxQ=D|WSM=85|GR-ow@u*f93 z+`u!>@5PznGx7@}S0t69!*Nh82Yybr;cTBce+m| zo4;o|5HiwAFfxOU!pRE_k_s2Ga7};)oj-w@XsAP+R!O`~y%aTqlp_t2JVq!uE z(c)!G5sQTI@fp*UgiBWELaBkX`S1 zJdLS*9Y4SO2>$2MGngz!ML@0AjLqNC-ioQ|S@AE-KG-pk=anD+0BUCSPVd4tyUo7y zpbH?6rQK0{{2gnstc(5MvVt>5>f$M<2uAs1E_8Qj=CcKqiWLN6{Yb68V%r)sh|RV*4=*A|ZJAc2T1>o1BaUv|iw6>u86^ttm&og2;O1129RA!U^@lhU zZeA9R{%Ic=n#G^9vgGI`;bg|kj*fO5KXweSzIq59?Y&}wzy7k<%Z0E|V1-{d31(;1 zqJ8dNRNeFOJ&n*WnV@)QH&UQuLgw zQvCr?LfHC%k5>RxZHhue(?WChtd>BdAK?X!6J6%-)A_LTvP!j-K3;TrWg>)uvGa zbx@Q7FB3LxpS%=_{Xy^pu22U7TV9>rtDgAo3q>dxPRgJ6@ zRsYR>zt#2PS|P`diB_5;rZM`z#1La!Ud65@<8~I$sgK&8c8aBx^OwS`JEvS>?}LO# zI5gdG?Cx_Uro>EgrT~2AYcFBzhJ~mUhj7IutFdM!eI1xxco^CD=vk3kA6u}V2s;M9 z5VA4SoGXo-1u&n(jCvTHxEXl$o&BeFl~wbsZftDMvNl4}A*%2Z8c`dAGsIM;Be3b_ z=#>ze27w)H%%E89^L4oJxwyP`xG|G8r4b@oldTWFmh+dlzqz2n}wFEnsX>)_8XxkAlB}i(`^QkM zMsVxhhjG^<6DZZ=q#EkA+uPePK0cxAXAbUsZI9>}9M!A>9W><=1^-#vZOgAjFcQT*4?KW{0|V&oUxHwS z3VfcVY5_yAY9fxdb}B=fNsHfH%}S7D*?L_F!;;0ztnD-Japs_Ea2>zc_TYvuWOFjv zVXrZnPGNFv6t5gUiex$|Wz*+h+^OCp`}W$v)rRc8-~0aeh_FTt5e7Cgu^G_$`fY7( zN+`MSG9VX?yQ#MST4bkJiv#QWnN*>^K+tgh*pA`7-o|9zOyt=u~=lJ~-PvG8r z?sZ9njWC;QVBAoJdR>PS4`;3s_E3qC@zC^|0j3dQ6&MdDq5%G$=wPjyn(EB-i~>IU z_4LW`J%9FOMOtOsg1nsw5uFOIzT)+G-6h)vk8?PfEj&$1#N&DnjdW^HGFfnNzgPX# zrLp8m^WuDd@@Xg>L;@U1gw&;|){vc^#Sd=175n!ckh`g-BnnKJLgESVcbiZ@TMn_9 zk^=GrNX{ikfUm>#%0!co%}eFb5*PU-aKF@QXl=>pxmjQ^amvkR?dEYzH6GXJ=H6#p zhsgu)JNF?I4_;vtzBB$Ahdr3Uv0X!6kLOEdsna5bMvgvPB5UZ4wdKgckRZK_0Y;jv zh&dY6@TnOJrcJ8#>kHYYUx87Inh8L&t>7l5EZ1|q zJBNUCZ+mB5Yvua!Lq7munm<>)@d8|V#pSveBrKAL9`^&2nQ>u zlgQ;J1jL+Xa52z8A6(o9!qK|AJ|G#Z)N>ZH1qKgpU2lM41{4ZwK`J~l2uF~J@y#=< zHpyZ-7;>SPN$82P`r-3hGN7QQQ;MA~is|scclrZ9Y4I4mk{0?&SSy1`lD&QYocIdj#X|=-Ke6Pzu4G|%v#Qq*tlOm{=>zK}#FgQGc6Q{>fEC-RVQ@|yPN`q3q zY$?z#l!VF<$YExWj`OeHO^lzHftN5nZ|2DO6l(PlGOY=O>Q!_khVf_DwV+y_Y#PLf ze5Fh8%!2Aw#9CT$&%=ZG?$3`R+sNqJ=nUhclH+Cu!=s~3qMK{KHM4TRaI8L}iIg3T z%E}!~Y>=_FhS-bb6oR!CtqNKI+%2CUTOYQ`{IuPN5R|qC#YY z6)Gi{4R@c5Xk#;i9lNYg!sFKFaT5(wbDbGMAjjxLb0( zt5>eZk`+s|PFTIs?NSw#yFYfwyE8<6M*nB8j%kTZ)1A*xwdlLkzp%U1jG(;NJRBz` zX7H;!e}$vRj#<_1?)sdY5&rO}g{I?%m$J`6-1h(sFU)+S~&AyQ^_ z%>&ccB3nazP7)ZEi0QM}^;$geeH)GM+4v&X@7DV(+LQ(#C&Vfo(t9GZ#wiUJjx6$g zg2d0P`|FSn66N0i?rU@%dwLe2zpq~$6&6v`(=(WwB@*g%S6pn7Vk6gsS6_4so4OI< zPz-BMK-;!)=T+0$)OI{jh2KB1 z1BH^Imqcn(Eo?PJ(UEDDOaR9>r84Z~ubZE9p3JrtQF9}fN)B8C zDXZcQWtzh0AZd;_-9MR5PgCNW*Q07qa44`TFS8LI=WEWxnXZnO*to@`sLfG9j%#u8 znq{?FQ9BD&-aA333?Ox!IyItE$EoQO@|*+-kX24%VG5;6Ly#I7%(37sKJdpY5N(WU zk*SB}Jtt~qS4GkpF@T%@Yd`LMl%q}wBcv)pv(IalLO`g6&pdtA>;s(ozw;Ek7$jIt zFhk~_`DwY?RYBx9CT4-(di^#|NxSj4UKGOTKC)iYx_18XzFShJj9o-l+cXBjm5?um zQLXR*H-aQhsFc_dnQ{tr^ZS!liIAZl#>wFV3guRe*Egbj>2|zw>?rQK^G>|w&DWx< zZ;{0u?N4eMs&88lhlG61tGU9^a@vK;d*Xd0y~VI%7MH}KNl zgV?ukKSB))T$~W$=b9Uxa*(5@T-c79Q<39!m!vWUhDf3#2clw!*7D^`u=ClS_|jLt zsH&4Lf8xM6LZXXue&t)jIGo(92&yC_uQ`o zOI4c_SmN4~TcE2hB=?pEBWynlihEMgsn}c zzV)PSbk)dmCbDLSoe?{Et?1(U{`b61?Ct)60kpNYAt*y1r;r(=qo%DnL&)sfy25c@ zg5{?}Y;4*RIvd@TfEBIfb486`fAwo$$H~*9dJI1cgSfvQUO>qz#5s)${@FW4`oQiF z5+ zQNX5GyzYX7thLX*bATL32$Qe7uQb~OA%ik7)U|b3-(ge42)SPWRB1ld{ zU=I1TxF^1wi&IRt(urh~gT-qoZjfuETHDDJz$+N7kw_=e zl4h%uM0RTp`&iBEz=Yf%`hK6-dZ+uOp`F&pCwgh9liwFY68`SPiyMFP#x6Yc)D)I4 z=|wtO#ZQ0nDn4`LI{oVH_Z`Q%Ti4^69WUbb7p=pu@869#T)YVnKK(Kl^)JT-TQj)* z&gbxFA37I5zU_G#C{0bx;N$PR0Dtoj_bE87UE7We&RLFAgE?$m+lf@1J$WFVFbI^R zFtLbhW3WX~ql75QGxHBIz8eb=RAuvl-TLoy$pUA%xv1EVFl2yLUdRlJY-w1}o}+*s zg$Ov?UNLp8-!W;)2)%!DU%Z$<>V}` zbn}%VlR3^xB`-gPdYzK1d?6#`S+9thGUxlPmrprizu1XRgrh0cb=c8>$O2lmIEwGx zdKZ3jPZ}W)yGP z-(;mBo`vL_ZBzSsZjK~|>REj4uQgl56$zFW#N4MfV*IkE!CCd>A zIR#9T&ys1hw5B!B?Co;Be+M@kKNq3=CQK+28D*q>Q1o@fmNOU z&^O^9lYi#Fdw80UXZwUG71jNGh0DnS8x6HXSrwEML9r<%yC(|DWD-TfHoojU5cE5h zs*+MB89w+^jE%_v*Y%=>3-O7Me*hirZGz6#=coCTGc_`l(Ai3BKiDBKIx&G#fs;uQ zIkWC~;Q&TwN<&+b%VK|&#m9eytI zL&&|5gQKRTY&6y%$UHoFElnL3Xi25D);N|(goru`+LO)zjQwX_Gon^Zq9|?5kx2RK z@Vc=*Xo(aLIo=nwFO)2pXATPjKQ+RGf@@H}H{>Zxfh@5YW-yVWxy3 zyGM$Q4n4NBb8h_65=3t-;O>jEtXucND zX}{Kq7&F$B!$CL7*=!jPKkB^i!duvkUT=Eil)+rhBs**1G z*JOov!jucMwbU%JV~n+SL{ns{(J&<8BUkn{Zu-!2oH#Rs`yU#^4ewlyFZ{!k`0{5j zL!+9*w|=+_*IjcyHmnNc=AS%=Vl{+!T(b@*7({Y$TzPQ^?tb71Hf|h1S0;+RFK2Oj ztb|lNfG3|mh|hoSotT+8j4yn1CvN`xtMRRyAHaLxu?Gl;kU(Qu{|El7a|H@jY9D=_)V6Y~+YE z>gtiR-$qGkj;ArGu&?i()cnTc=ZpkGh&RsQ_HVrbttn>BCPXv`3Dpq_upLoET|y+f zVs9R7J&I@djN|Zl8{T~7>#=_0 zW=n>GL8Mz+(U$2zG#M8`s^Nm2IfELiVHz9u-KJM8U@#!M*Pt zGhK%;(iv*Q&s8|h0Opb|C6L~ez>Tg^VUq7($j8hqMn^{F6GElAeFqLI;p0J1l*#LM zxa|55pi=p%I2fI;%eBMy2rEMC$up40RXO^kh)E9*a`s_;a?8i?+VJrjy>tkHuc{T` zrS8Z6lXK>yqG%$~)EJP&Y%qxF=~?vk_G0;p#rV^YeLx2+5e-i|C4tP)kBHVc$Mhy9 zr!YB@$0LtFk6^k7$!Nt8O{z?#y(hQ=NDRf4r z@X2d8;>%z7bQ9&&9@T8WB|?r1D2|X4cqw=q%EB*iJ564UzPxUOYgO={{95zmL`~#K zcOa?ujW_~sqDt}2mh%xDzh#La`9X+T?)T9?f0ECtV=p< zy;{q~)}ieo8y)m$pP>UDQS~ht|DA=Ng?ldzZ~VDRxg^r}``&#GHg8;KoDNTjmZpL6 zUp%=|?KW3*`b2@nPnqqkS_20T9>vL_Axq@NkFod8bwFXc)(j2I;z*~==STiQ^4&2K zzoBGyeMAp%srP#)Dr1BXx4uzE=nzj^2t?AcGN zX45SAn@?SgMr{&@&j4Tj)(-sR7cN0dCW!yMV?S!;JoeI(BE0d zKYsTyyz8y&WR1IUUrAna0yD49G-e^ z0)<8g-ngAT%wZcZnP;i1!=l+2GIE^<2s}I0EODzyCAdLYW!n6(+|s<;oepKudeGp( zEk6ayJ=@+i#;(gY-0RDrgQKA?1GRpXhnbpTv^iJnVMbPhe%yqrZd?>ja%4_RK-nDA zOG6R@gyPi*F_%Uf-8cZ)-k+DAbQZz}9r6D=5+{F?J@#+|fBB8y;rXMTniFp>bV(7@ zoibuF#3W^sEJ|j-*9}lGCHco%H2m@-dzuaA=5(LmWNm3KWES3h?!Nwh44xir8gv<4 zYDri$1iXGr2w%K$10#?S5?*ib#0k)$kVZK?NgCIRxy*e5jets2M(RVgU`-j=TRUXjo_xw+@vaq*J|OS1?cSQ*9H_pw$^Y}UtP?6 z-!D{B>XJnHjnDy4Ft!CVPY`6U`&W0~jYgI4i&d}%6)L>(z+16m8P31xGK`L%k=*XF zqet-TyY9m5*dX3?;W8W>n!@hGd2w-M%2Tc3|9;`KNTsPCz}E%ZIyzi{(bjhfvmpdB zjA8q&ToDvKIW>;Sk#V^tzI^BirY0wF;NUAbXWLfL{`~aG(o={zU;V`=RLv*oTjC6~Ok1BKKs6Lf zb^P+~`_VD52FJ&Ocy#{=O5qNa5l79r!CE}Aww2nQF3A#V<@iY&`z&PuubA;{}(`~sT_ z;>F@Y?D+>)I$0v3V#Fy#avl1EgFh1=fXPoZfRBFg-5BWU7bk~BhJmMs)bh|!66y|4 zXP#?CgNhrjNn7JY!3+kqCS$1-vN<~K*3fXIVm=Saq)K2N zDaEewAF7zz;mX9qrfKG;0h~Sp$+3|jZoKimYKIyh%Rnnlj)+hlG&y&7V2dotnBr^- zcs$w+YR; zbIv6S{`y$V&;er!QlpCVDa(B5j;*{-3dZd9@{Mw4Kzd4bj;;_I*T3kZ{QY-d#iu{A z8JR=@4?OlN-gMb&)M{be^0OCl^_3g((_cJ^Ws4W%_dAC1Pk;Mb-2AW4;B%kYfN%WE zbNJW|TV-o}=lw&Noyy_bH?PHyfBrPS@MjmHUYi1HVf^BrQy3kc#V0i-6kz8;-M0;pcvI`<@l=17|zy~vCSC3^z@Xnaat&k zjg5)qMtNdCm(2xg1RXka#_{)mz6k3VCyeZ)n`1N8MmY8Gog3AwnKC9&g7RrB>C9|q1PMu*MIrC)-YWn88rPET)Ec3ZNIn& z@!oZKc;_Ha*Lu)MP;Y`kJPeAVs}n3^^cwvm~cr21ZdP)Xlc zzj8CiXQy48(Gm$23l7=yV~eWNod*SD4&N{LjGT7sb*x^!8Y3ekl1%5n(e06Yj3{7d zd%G(F4Q-gyL9ox>v{&|Oj2>l018;ich1k4dtr39j)M%myLJ%BT*7F8D_fZIDleh@% z+;s?J9EEQ>a#DlEjGbsC#qrsMMtK8BB%*3@QA36j{@#_;Pd4ehTA7}AGdHEAqFBq- z5<$iqB_)j-F1+L#1YW*lOGAfLojoirY76)V&+`Vl!!ZE-;I`**=tvFU`qE{nSEqHD zDT52K*X0f^9fA}SYS6e3W8+oywwAGT*BP|;bYaEfR($hZ#22)eN3d1`iJj zyNL|<-a|nWXVQoz+YBysY;@ZM+!!WrYzcz5+I3nC&bC-2NLSSwd(;-Bn}E~v_&IsA zFDCQ2A$3NB{YkbeqfsHVm;Fa(bbMWIJ|+m(lk`xSHxrs`x6EA&H;|#e*TLfj{KdCN zP^>b8HTFDF3|1C|VhIcL`gk3Ak*WwksZ=!0ci(=gkuOoRBubmx9U{`*cbn0}Xk3hA z;}d9WZ&%BK5H^E5gPcLARB8k+-5kW{KfGLlhW}1BJpVIo3||==qQbyp3VJ-i;>}S@ ziYWzxy!Y0YF!(NjscZp9PqGhc#w^830SAxf@!dO4qXrt1MR5IF--52*9(~5X{%-X2 z^r3IzQfU@YVUwR$%9d>DR7y&e#i7yoo6R?CR-Mdoxm4Ox;r-_v|IwpIapL${7IGf0xN?J{p)(2%(Yp7xUk^r`>7{Hy6okk;`K{6UMYhp3ZOGw6}xagAC zVBvyA7#khNj-4+cmn%wVVbzia=wGx9Ptio@-0e22U#%cFHG|gnHazjvbAo&)rzS8l zF@-g&SK-vjlTBR|OKfeuagB-u=PcVvGSrwJJq%py$sl~I;%v>Z$8BU-K9=n)c?z)i zUMT7CS9^j76zz#YGHzb#mi)Q+DO9No2ZbE)v1$pW)8b2Xb#i4myJV+s2L!>LoSC< zEQ%$I2k@y+d{mCT)00zJuy8=hD~raabbupR%d;zBm9!t%Gd!2@f!QmoW#r&`c;gJt@OI1oaMc2L{VzJdk+dgB z3N=KfveiJH0h~6N2xEGNQjK*^Ar*ANk z9muR=qcK8Mb9&r_!(=V0ir;KOnd!%3U78%wn3Dz;NTT6=GeHa9;5qe2eZnS@(f&+a z+>$Bd8ah!GReyGEOdrA_6~5#QaBe%LsfSX27`5t*jgO)#$1)STF?i7WNk)wH3*8bX zdsS=e`|sArz4xgR+uBJ_4;yygEdir`XI&5tt3AjXU1dAIh#xbSZB)H&0Q(zy7d3$S+W zS{&SW5Np@1$I!?ydipHU;QgMQoKQs{rn6_Iid%km8)Eb=P>`}~z-u9R-F@*;*|K3X zo_>A@(yzPMYejgRf6@+M`O=MW2<9x%ynq6(b7C)`Ryu(hjKp`)h{Pe1zF4dd9nT4^2@~4u3Jaza}s;GN#|*wdM8B=d*&CnIKtWW=WWm0v>42+korJ zCuS;iXo}@5s(o_C_wkOmzZK`7vsDH`!2neOS-{Zafew-uH|;;SFWsoS&IccPWd2q| z)ftd6KA31{NV+SOkY^(3bt%;3b!w0v$~VJ6Q!-_OKyD7z9!ZvFJRy=`NNE^f{_3|e z%ZUZAo#5JkGPM#S-h`FyAXe97j@-@>(UFl+EL*lj@s3IF@bECQ`5gND2gEaB%R@+p zn_BP*uO-Dqbj_E>TF$;mvf|)FAG#jBogHdp+5z2=o{!0cN6_H9afp#`hZrL1#g$mb zh4HK3+^^3pmMJ?QD8q7z{(ZcKiNqKyG* zM8)v|oUN!>^MX~Jnw*W`n*tjpe(R>9#swr*16@NS9QsVm4m)R{;iP{}$;#h&K9}km zNuKf`@uWiAz@CX}eS7uxT)*B%?0-fmw`nr;c#^Xq(TajrA zqpiIgu{Z@_cu=N*Pz8;OX!A-YRPFO~IAWbCJI)dN)U%agixbsxbLc`vbQqEg!G0<| zAgZVqPN}WH1+A8b7GcF5x<>Rep(NK1(ZZVh&%<^GFVbN#jL-kmF6f+S8tm?#IG467*S$MC6-FGY7x5kLBm z5{Ax1B@|>q-Rx?;HaV|9txXy9xS`7;X<6$ksF6U9##ZowtK<0N*S1@`g;{ysWf=a!L0|$p?XHKM{R1L^>`j($RgUG-&c>cvb zLPAK$GVzx>+S)s9WUNA0Qi_-un_iZ)DOSFOrP+695UV!f=O)S3Ndy-wgvyPX&kF96 z&0DbZz#b&qyObo`J#>9xdIZ#H{AG#4%B73(`b*EovB7cNfB)lXPuB6)%a-6*j~qe` z?M)O&GSY+us}*#2cd0U;ogpJUEMJKAYu2ht-TC59Y~Oyq2(G#83=SQ98QU+s0RMIS z?O4#aKzs1{=XYS`sujr2%veIKYdgPnVh5N%G`S{xYeB|A6!J;L72MV1j>q-cNl2t+ zu&;=Dka;#eEwdS%xsQ3s`Gmv=O&${bEaWH{3~#8HOU-Svg08TRbfsWitKv&vyh+K& zkz=QE+e3$OJhTCY0NWUZ`pvveekD%JfS;2IgCz-85!0W+I82sEy8m;@jWNt^wOe(r zu|vkiD(_(p$d4j;>H#E*Clsr=e@O5%W2Kx9d?r?sWsVzZ)7FbQw0dO4u4O_hh8%?y z+EBI$2y1!SsG&y)_@3Bnr-U?LORYd2P*Kxru*n7+y)KrE_`+X*8hzc}LJ*i7YmD3V zV|niqG1q>T-hdJ9be;V)jB7LUUh^JOWQvnbe2;wW%=9$Ut!+wRq;RRRML%xr4@4%V zoQ|O7Hhmt7HZkMKj;5CpQXC~#dwOIR-~ZvyP$=aUQ)~jpDqtqfzEEl&-mV2W|1h@p zXF&xl*TU4~I66CR?=z9+XW_je;=>kgCetFsz$0M{jcNfkxpJQU5x^f^eJM6=SnFyx z=bJ!PUN>q z>BhX-+Tyh!!jy=bMYg+L&U)NCJnM+3qNor8BZOAUA(@C`dU9N|=WTQ;t4|>nE10R)2Wy#1v!)bKrF^`hs^yb4=TDm&Nj zA``q&&f}R~Q@HECmoYYzMy^ESNdO0y8DuLmkTrMIIPHFrp zpP#|__$($Sr;Q+)$sp63M5ZN$))w0o!LTu^O|ZzutL*Z-dv}goPs;DT59*@UEMlM?SI?)e-}-p&1;n;$pr2 zy7%C|2mc$nYynqZb2a|+)}LA*lS!O|0#(b?_^L{A8WQKW;+B7Z0B`-{P5ALo4`Ao+ zE^Rd3Ax#vxu`ZVtbAvPB%Y)v@!HOV6jsRti8x6emH4Ab5W!&)OUziyb6F`kXaf4Z2 zruK+>dttUiIO3@cZQcyD1r6ToVkwWKCrEruN^om3Uqh)_!*3oLN4@6_IC$h39f#a%C8+qP|jyJu&n@Z$3?VB7Zd zaL2Fi#LDF>6u-XSVrn^Ae#*j;~(HQQ>$Z$0m8;d0vJ`ANV*P z=CepZV8d&L0GV^D=>ck zuRo2KUmnCSpPRyPa0Tj-7Hc2ye;f^FW$Gk_jW^-u@Et+TB-O=>*V+=pf8<4kW=|u$ z>M9h(sWiCJA4uXDaRiU%Q;ibpE--Xuzil^X~3 z#SO1HV=dcWyf%W)0|ET^uOGqlFYZE-qp%LS_1X~g+cR?o zlO=qfeCpe^rXtG3guXtL8sp~mw2U z$*)=>{QN959O~+UZ!2yMrJ_Jrp&Y;ikNi%O_9LUi80hQQeLVW= zt5~;jql(xT7A@p6(SJy-3rpnL`b^V^Pqy4F*yewBPq;J$bN)D`C$k#pVu`Sy{J8Lv zs}OkI1)Cb|+Xg6GOel^z;1&9WSJ2u{*n}jT64I#_WlvlPrrs4+pN*T7H`+{y%7V)) zxe2tjC6S1QQOQptk)T3i7~O3V^mQk(cyTYf+T)<8T{ytr6PfXrrHbsMEZ+LejKd~Y z!4D>?qO}_|-oYNVN&0g0@_^Ov2B}8?3{M5|vpb%{&_o;~lN1t4%T|-YZZ=m&EEvY$ z{l#VkFo`I+7n`oZe?5E()j+GzJZfU-C<_G9+tVY7*5Q#6 zFxjUV)Yh%rGzGDD|6Xj}v_%Ihk%Y$|dkk;7`bzxQf8DOJ)p#O_eS3CmdV-0eAMxaM z@$7rTxV-k%(O`1Qee7X)ZUqK$_K&?pw0JGzYS_%bxEEyk&(l8Ozxj3v_bZbF!lxuK z(%gv$iUhcvtTXRHUfcvrbfszvsNYT$gZcnWIzRY<58~hNKaSb-29z5SG$Nc>G66Q* zA51D8^y^0FNHA^UancoV94OBHhXRP5{0&;N2Z0SA#%Phq6j30;*kte(EYGOcM1{B8fchT)d=a%V{IZsHnB-EgHqHt_2@S2tQ zTAa8Lr^qI9i2Se>na@#w!WAU4g(sSH%(U#jiu$Iq9#Bj4e;#@Uy{+V)*tO*~>Fh9LHX_}bOsmAxVsX9}W1^jvd?QIZL&n)U zO*EZ!4cRqM5L4l_1+FB|O+ol1#dBaRNw8$_qSs!7z_ukU`8OFf9P`qLN8TJ6Ki|tP)825X3Hz1cQ;1nFO-ad5n*ZV&THY$QQF3P2;+( zh!|2vI!>rChjb#2OiK*a(m2}FF{Bd}baX_paw$bUfR={f?jv$jNqa%|*G}=%lSFO_=#rkSt^(8rzOO|#+H!qPSVKS-!Ly2it z#U@&069W=Z(zp<-7A9oIpeMR;YIqcbXC`prdFzqlwWwwhBpl7LK5Z^P$zj>75C!*T zoK7zl8j?}fHJ{v#OxHq8$%DRI(zHugEJ3Ed3y=T)QB04HqrIa|Nt1+iG}~;XHD$r| z25$W5W?XQ79;x^!p4^efsueLTTrh#%dxr5(->zY3Bxcs!LL4gMI9O@zNO|0l9Dj^N z)L#}vtGV+Ax;lHXWMLaV`Ia);5>72r8)l9erL@r9XHAi4exDfu4-0249ibB%mCqQ| zSm{?WowZ&pul3+)9pfW;OlRJVjoaUVuYC0@MmTe0Vf_4*Qm&9Y#6Se6K=RB%Z^=%z_7d#4HMU(D^n3t1u%#&FTDmE)DzdJV@A27w^USUT~dx zQ6>e$&QA5~i7Mz2sY9~D66;c1Bj%h@ZOXQ3Dw)ibZ92JV#T=!)pLN(O0LpXa`0B<;V2|D|hpjyo#NC!#B0isb8bpsmV zI104{Zom7tcxA}7HBR1-NOi{aO=Lo3)jnT`hd-x(xbK-v>5$Xdn=@&Or?i)7O2ov# ziZJRR&qJLlcSMdiF>zr)Okz#iGK=Ia^!OCRHSf?DQx+vg8#Bd3_B8wWNm$JW)#CXL5kp z7UlXQ%EAPMWKMp5lJbTJr|`p{+=gPMsASKtH41>u&dg%T;)Qe4=x%DFNl$Rdfmc!V z?LhvVhq38_SgVW$1HZ_p(Nq^bS14aiQ$Hf5OztIQ#e|Z?O5nziyc=mEFClWE9G}Ov zq7B_-GU?@*?a&sg!s{oFTokw6`#erh6tJwlj3|rdYE38-iMsv$y@^0#f^j-PK30)eW1LfKfBGcBCtO@(uX)`cA@IV_ z&uv5_RYap11Vd!VHc+mHkuO#;HB-P;E{bB6Pn3|qz^S2W3=U0THdjZk$YPTu7u&Gv z`$?IPgd=9kEsk8nv8MuhdU{Z*6m-!k1Yx~D+rT+W`36{V#N~X~(b0xjEP#BDtYI$N z8m1=Bpra*@RE#7#?_5SkYz3o}MKo$bY+c)p?VB@LyCQ`~DXYVXnY%ocls!4Z8w^gJ zovmYNls$K5YDwI2?@>h33w5~kb#-Cr%t?$-&!AQku3p#^0`BZB|4?pCXy91 zeG*?{Hoi7GI*xP;HNTAs%Rt5eK+cK5q7}5aGXrK-Lw|=f(k+C@2T`pTaOhAsiY1cR z*fV9HuA!=12O(MO&PLoUoDE{;>$1{eg0p$kR)j)z+;CY5%Lhs(JxugMP-YzzS7htR zATVbR=Bgt0*&Tn?RX>FE$YUU5J&1gPa>9fZ!#FWmL|^X$JUhAtU42V1ICKV&KJu{B z!!TWp>8UYvwZ@UFn!yyINbv=9Edn_I!V9oy(IQobOiWu_J8=I4_X-B&o)Ki{OuKj; z8T>Md1g_q=0l$3wNffnV=R~&{V0k^2R7g$Dl0NbiSo!yKb>PZ3U4av)j^Oa#=W+SD z9r)g__92pDAKB!0S-mY?x>O@;L_HWdyE;0te#0hobamm?S6;!I)oZlw2zCGO|NI8; zeD~XN`|ZC{3y9=O>tn`*3VIej-;)&rX*ZK^Ej=Fe?d=^Fd^ zaXNSgP!C0IS9o1f001BWNklki~)GV<*&t+Z+wFxafGME z9r7b^j_j;A=tiiWI1wL9wM>3Vk(GN`DvD;}CmjGm+UA|3d!>Wa`5(Abx_S6Gt8_u^ zZpwfy2D#!^OoWZ=lJP`@*HT%D57DB1yI;jU4?Kif7Bp%NhEOaOP%0T;i`BOACM@~) z2?~EUH=*Fhyxo|q>V^HLP1P zfNkqnDuLFHAu8)ock$tvoJrRsD%5z#u4CA9Y8ppQ&!9COLw~A*fmY+DaLR|eLmc-d z!qL&)iMEbT6{4Pu?KN#Y!p6x4q6kFyx!-*8=C8M|h3>JThSnx^1&Z^HFmXO!(|Jh3 zW8dE_=ORN!LI^f!pUOiSnrqbvhZtm*eX1A4O%_RNY>0{1_*51%xgw^sRb-3IeB+oc z)G;(Ri{ar}kPla?gjG!j!%GHb!nVdNQe@c%gSvU$JzZKr zl|sQJfyq9vRuB(1u%thRb2enKWpx_$$`tCgy!^M#JIF~S+YCSxdNZ=55tf)J3=U`Y z*kw!lFg6{*fkT5B8=pqLTt~6gKwXTwrpI0B@2^CCaA8(jqB7HrYDPB&vsrT^Z`u17D?ZHEW6-8Wavi767C^=C>sb*G=Jdju&dD0mZ23Adc4I&BrccN5Gc)dil_4t{5SXEmLwxisC398Wn zL{c4Eo8$*^SkAy`PQFACu2+x|i5QUcoQ#dI(QF`Iy>DA`NPf81F*}SG}$zOu|EKLoh)vTbtL*DDxoY zzw__@(9>FXj+sgZ9IWnz-Sjv&vdGct8{YR$Y}mL)B1W1BaP1c3Z22)`KN)3cq8TJ< zoKtF?i|HC3?J#a?eR7Yh60SF8hr3mi-%-uERXyrN4$u zzHBm%@y6OcvW9ogj3#4jdJN@y1XGDMoYh0kwXxzXmK#+hA~h`N%%H2YMN>q4yhe2q z!c4x3lS328R)Xei+z28Sub?{yoV}9Meidn{@Eo9+5!dka)HGI{wNevUY~gS(@f>D? zHfJBewkW4!Vrn}O`C(CLtp;1GHu>SyfL+VM7=PC4Hxj7r6l)un@!Hp4i@;;wTgMc~ zu{}MDm4}?OPt|x1M;C2&*?K!h1`-omY!@CVRQw{rgff{{{n6?)B(ar<&G2B zLn2I_ZgYDxyXQGQ13U2MRHkf!&$&1%n-W|JBIS_ag?50~)vH!VU(+A?Rt4b!tlEErfJVW?BX>`eisKt^`dBcoZhCC10I7#l0- zCa01>CPQ~HI_cH$>Tm;%a0aD(5vg=i)dQ~|ZHP@4wjs&XRLbX9unWulE7rQR18q4QOcZUE5+w|3ZTV@CY? zH(rCoM-O0q_Xys1Wjh+Jmtdy$TePKK!EE6ygwkJ8vd7ILr3;yQQRFF%TJ9hkgFiaN@*qlg$<>)cMzo{q9E; zD_FVWENt7hMS)SufXS4|gNI+;uQ_)TA;%{t6;v4LZKDC1XaqNY@>BTgKmMb^+(y*U z8}vcSFUKT%`0B-5wM~V(_Kr>)oeI!3H6>019a06=Is)&q<;(T>@ren+mu+nsY}$hih0q9|k5gP?Hz zys+o4)=k~~FQl2_COmB9js!Uhsu59xt}m~JCqVk-(5l_Js#mQdCr7NQlVA-u-0&W3 zTyvIMz(ixccE2u#)J(lrfjjiwgpS6P1$Wx`quJcsY`>;2=DFfFlLqR+EVw^%KV~UU(H)+L*teWGW6+`c~qxlqKdfQ3tz z2?eI3CG}@WQk@gBfCVMlF$GE5alE;`8gwwj`apCu-Ta){mj=l&oRvl<}~P zTBCwXFS`zbd%m@{!4X9%E{2^ouErKEWAu=mpIw$Zg0eGHrnAJ=sznj%q!VC)SXsE_ zq-^YiP)msH^l%VS!o_@^P?Yi#>gUKcG899uP)8wOL$;JhcD5oWITvF~GJ&4%3{tV2 zw86^`q9RGp5CcCdX<4o<0y_{a3v}HU`6&3z)6~4AVh9ozqsXLMP^t!HXfi!RC$W+= z0b((-qp7Q1MzvN#B+5RN^$2s>G7h~uf%djmTyW8PWp$&Y)HI*MY`%s{k#2-FbhgGY zl?~y@i7AXs7L;&M5iuPr;kDn_b(6uhKD(OZe;Ir zvGsKKBAcDTSu0nef1npVJzZG7bcMuVsPX^eo)>Xya2UDltS%^nI@RWQpV&ub_Rn4) zHw&*1N8$Kq!m+$1B&coLbhg;K`}XffYyBwx;$3}+v~0q3_ylGq9!4bAi@s$)LAAyp z;16(HdxSb8l}S{NeiNYp=h6L|v~gNh8r2$RvLvidW8>=e__qf`SiAXrjZZSr@p(?2 zIfXrY_TcoX6E;#PMahU&&P;S`HFS3MVC~v<=;`XRdG%UFyo57nhH&cSVN5!55uxpa z2M?I9f}6zQHN5eoAH@&;<3AB{K~lsee*n3lsV%}@b&Mper~=3Z+t0!N1Fzud@sp~k zTQjXf&-mGRxSTkC0}td2&1a*#ryGN(Pf7if2@lbzJ8t_0 z-g51=__rVYn-HO8%a%*PXz!jq8V~jdkhP1rwh29oPOIz6QA^%iU)7e1WmW&4km{8b z1%W$*Cdmf7Ly_0j_vXE8pb&z1!lprpQ#b=D3;2d&`1VI6VlI)w1R4z)Ac+(x-v=Ta z5oFuWL8WCig7G#q=*c3O7l>5`@s3Ld@UCkvK%<;xvr&&Xr&>cAoQ|B`703HfY;)(E z9U_h-+%&^+ii2|QV`5s;KAN4)H{vlb^wpF~J3iFU4wj=$nZS}ms9K5vrj zDlDE%D@FVOmt@(!FcC7r>>`{s(7#{+?|B1-}cF2L#w(;vwNuWa`w0FFJ zjg#TlUeRL$@^|U$=`jrj$thc3+y+9u@}ivuMn15(YtvYM?A^hR^DL2B0CJs`WDZB7 zyt#i8^(Nt&pLt|-68GNwFlJN;2K95UUGv7VGe!b_YF~RxXI~(?xZ!jSxCVKT__{oo ze0A*+13rf#Wo{{mM`qV17wo`Hs2BC15pzA)g`!X7C94sEYc|w(&};y^Mo&E;ul|h8Ma@t9S{ERem_nDjFLfMY&$rTzexJP%vkfeCg}21gqdZdtSiFeNW*#pWBLfvJ;U7%ki84 z{t;SR;<)7M@1llYf0Qa#kB*L@x4R3WKmo-=-$pDjZpe^h6#E0ZR0?2hvM$&z)3XMT zyxfh2OV{XrinXortrCir3QnCG)QBKi%rsx}5HNdt%a*Oef&~L2a#0SMv+Ha%Jp0Vk z$Ym!nIWw(zXa`&fue^K+XU?3_Yq09&0l@^^q|dE7^+Ykxxc2h1tfHg>7z*ILZClab z-;RNS#rX9-_hE7(E7U?2A%eOO!vsP8!#N?zZG1>s1bI$povf{+(C7k_NDIQ{FOaJki-BX!AJ;YAd*LK^2AeMl6AF?HXP` zYLkewL^QXUSKEfwIQbbf(`+{d@yk2@7ZYx}j))$Ku(A#JLUsO7x9r3fuKsg-)m%&R z{r~~7x8tPs=MsY^SA?G-7{yGeAGrWIIVJ(GLPE%?NiFLoIfcanSXwhCpd@K&aRdyi zBDW?HsiP$VWRelAT^PZ-#VO3@@@k)$P!rD%L+**BbDwb%j)Yfo)qDcxi(&2&aXxTe>%_Rw31Tq6rnrF{t#hU%Dpl?SE^4Yo)BZ>X+b&Z9~ja?{} zHG-q+MQ_(jaXNRx=ExM?;rQ&v()Y@Z8d-EY1`P1=WX5`YpukEEljD;Zo0u|&e1n@k zra$*~rO}olF_iyq6|(JIzliN~2|jYkiw|lZUfXkc3V-{95xJu=W9C6XSd#wpGqcke zSg;Hq`uGQN@2~GhcUuQuclm4Zi`#yIM<07mRTit}OD?_;Pd@pyg0M8wgApuQwh#k- zUD&;AA7Zf-RN2A)rB<51`IGfKZ z;A>LC^{xd)&hs76IMqBO7FFT0m5oay;>}lIiHk4203Dq@ccmCoUx@DhUW^V6>Do=t%-|Qd-;SQ%UaVNM6h}@TM>?5CGM!RU z@XEn`nvn3C_6j(Ta78$mzt1(xsUP*rBer*aHS7~lRs19=ahxy2e?5R=PY$BwNeCoan=7cqM|Fh3HEZ z@tx0IjTm^~5JIlal^96#7Og3#Z#|Bq5rtv-}O{{~i zgr}Z-7I*&o9-$Td@&TKNytmF)1xOv2A}iafk{^$t@HtITD69n0SN#&8l6Q)!-4bC@ z+-zBbcfa>~ymmv6A-8%_*D~=E^8T=Qyag9&75Dz&&t^?4o>453bZEmIA#g6)wS(V| z1ZOno%&pwza%jUJgfBY}Ts+|QW6@TYtTR;?vreGNkVj50%*^C){Nxaxc=9=vYKBy{ zw6r#-5bXLo#MsAv|GwNi^oPE^wvCo?SDd>*Z3HI$YKb_PP#ZNi!ZyXJ zIyyRqgo+?7|3O1fd<%^GlJS6?1hyWSjQGUT?^nA`_PKq5thM9UG}}LFJsKMGn%BJr zfnWR`+YJtmQZ>row*y*M#7YG0kTUmBBQP=h^9g_j6%&!MYwfI!CBMn>Ju?L{Aqkh{ zIU1q$lUQ-^yXn?T{YzQ5nIrkpKMST-O-s~5+yajRc-YWgG?WBM2N`Y3hDuS$dkY%d5S!;q>^0H+s zud1b_LCK5XCEf(^FZ}8@~kk4U}e&A>C96=rK7VO%T_GJ>CUfD3_>h(uV9b1)GcmFgZ4^1K^TNFTt)|yKvJ@pT#Y={6MV}9xk)lDV#id zRK0Txv{Y0ylP|U;%+!F{YalG5!YUrJIKs`z!D;pGUjLXRj60WBf{Xv z`S@ouk($LcO`I5mlu$&ZvG1jgi9+zTNoe$17koY@DEVp(=sO217k1#wH(rGhO4_3) z8&8su?OOq@oTtRAeoK7)yMIK_W96EyUe(x4U z-Sx7GA*JO@F@nUhSnQ+i%u=+Fvj!;r60mR>=bty$X67da-+^P`HP(Q(O~zwp8V96EYL zq~@fQ2T88?Zk_JNc+QXe9R5Ox;OfM*% zNu`Qds%`Qt6p~@aeVU*NlAurGI>+`+6wa*0$r}hLLCD0S=xK}M>}7E*8%RrpipZv} z>AW+S=osH4Cts;C=d{SZ6&czC;+Qzjd(wP4jVISmFUnc0+O;~eqR`*oS4L4kH7yqkl> zcgW19$cbA7S`<$8kegDZ4K5l7p@kv?sD(QbsB?6Yu7j*{*p>*OQJHWOt9;M=H{P78 zy{55Sj144ihOzkd%<{u94u@`zT+|HKv_#A1=M5tG|Hyg|FuUtAd;Hvf@7%dlGkqq# zCyBrZXrVo5p)9B;8x6~tMSl6zt)pH^aK!NX@jdiTMQR1Qf{WWr-I zox5lu9(wTCs7@r2FBwzXpJN8!;h|w$jrDGF4iXeWGs>|DB#=_y*nvA*3+bE+2_|aW=O@3!KCie036o70`Ob+Z@&EDu zFvwftv^hF?2hs;&*C>a-u)HJuc!)pGdu#E;cJ%qZzJTEGBGSS8M>V|K+8XC)kk)Hh z@e#t2742eVEGP!D1I;OZcHjZ+*c zTBw4A7!4X`VMRU@y;1)DYu}Xep!^2{A$68qm-b1R>)9mnY9Bw7L4tDDnY0ldT}RHs zX>4><%AX{Aj!%s1`?U8@J%g^z$keSuZCxw2EQ{i=E^I=XGi7ten`W$=NZKr9VHTPo z-h%sVDpDLDglE-DI$PkML1ZoF+j;gRPhU{^ulwS`3QXUuTMSb_>(B%n0dQrxpz({L zaFZG_t01ia$B!SEYvwCE_Mp4BUkQ!qn25`Ml;?7RiWQOZtn>CNjD{S0;_1wKq^+|$ z0l#1j>2ea|fjR&&l(;r3TOgC+=0W1Umh?3Xl!%chx!M?TO1nZ{!_*qGoJL|WEu^`P zR+|W;E)hjXT^O6sAY5z`%~U<+AM%I9QDLFyG(h5`CB_pk4&k;(N45GVCA44w^)SoRVV52TT3cH6uulm(D`Uaj`G|yy(l75Fn!w2D zAX3%!c>88tj`3NQEV=_93s_64LJvJAMSN;&+_^0pU8~^Yv z?0W5WG&VM%aSmbjIEoX;Q0e|5A|V!{Gi$u;s1Ki{-$M*fz8ORzwh*gUtwFxb^J=6; zpVasu*xWFLRH|BTq2v}2W@UhBY-|E|`I*4zvPNaSXSY3r$x8sep3_v1HEYho{6&j!;>b}fTR|R%&H0~t z;xU=n?Av=#@0}`=$4(r@U|+wita-n9?fBkFXf?tc3A`o;Od_T)0NUHzHCo}%@N0f# zz(j8HwpI}FHMAN@i)a-c5fx!ve^%2Giz)E4`0xpc>s<`MJY$SKUK4?T=bx%XQgMJm zQ=J@VsN5Dvko}#*`i-0L{&!!dqMl?>zfB<$wnGwF32SHEI}%QBa?G;Ob)!!`b8d$2 zcxd&$74ePZSB(# ztAVi+hD(hIM5`Stzz-cG1ZBp68Y!@Ob{UlqXS)wO7@Cb7}h)P>Ht%_SlTy#HR6k{k-5kJ>V^+o~yn^Lvm=WHcxdB{nF& zNDyk~5Gb8NXRtSYP24e{K8qElwgRu57yve3a1{dEpMA74bb1)0!>2LEIVwparL-i0 z11QM0h(<$U5N*h7mQGizP$-XZkR1WLVS`9QA^zPo&jaB9BjL^z2HA}f!myEnRZP}_ z8-!zDa5luAIOC+56|BhSBpa1Mfip~Fv`v(t-THLC@cDs zAZAu^vUpZGm`5T`$ftlxE{*ZA0h9}A6f&o^(h?425e!TsSf;`r18NZg$yyV6aOPQJ z8$06`6f8+Z+)Lh1Pjq|=*97Y48HKax1>WZu0|w^M){_j_W&Ob zN=8@3tI*WkY_D0Sj(G#tY}th0-glRvZeGh&jqP<8iY79{zccs@4O2;H#mUBiA%CmHB?)lX(wSL)9RmRsox?G7m*1i-y19#xj z-;LsvpL+;j`{obusgHdMhmRb>(xr=qip*)8gHUM_xg-CKXmH9&wc42)pD5r&ZxQv4 z9k}PYFuE2jN2-=vAg)V|vI7Pt()>9Su;IMDx+-PT*qWc`<%_@sM;?c|yhK7t=b`)W zkvutf_WAHKK-ug%fFp+w>WpWm(r5?s_)qu^$DJ{b^h@RjV!)+Z8`qnA3>_os0tGXH;(#r zJ{lS@JUpy|g3{A0Vm!~mBNoPqC}RD(jd<5zyv;15sbepl52yb!J#H{mQi_DGP>?OO z$iI#tJZtPQyHM~2!}JKyZ9*7aOQeLzN?zCDr5AVN*N^;Ob95Fzyr=Atqp^f3oH_+X z{!S?lIyA*6F5gtKFyJ%B0-VZhQxj!0Zg?*y!mVhiZ$c$RnS4qbXK?ey^|*Td9Cf6Y zygjmM5VI1#OAfv;@X6g!!EmrV7=uFlyofbTs6!Wp%p>1fB^S zLsEUUXgUqf)XQ{JsOn2RK7_&HAt|NWnJ4;U8YaB{JnxKUS?Jd=XSoNy4sA;hbZxZ6>W^Tr%K|+X!z-FubL0))~k2o*YoYh)(t0rx?o+AZa zOmY)=@v1ICvGxq)D8^F&cE7n>WViHWTG|LT$tuj7J6CWRlWc2CI|9K14jwonc=p1J zx8Q~CJ7hw%bkPC~j}772(YLhk{f>8BgPNM8nLD|)9THyU;>Bt_zyd4>6f-F2vlt&e zh5Y1xgmQb$EmNBf6fG*EIu&=_vnNJc5#-nROb#}T@mv8P{fAvB1xVJ5NsObWI;B9I zE0xgM-XVb^1}8&=!loHsE{jdu+kFC^?QKqf!rlO9`o~Y4#JqV+FgZ1%Lt4n^Fg!A9 z)jyr?Tg}ccQ4|}Dx7!TR_xuo2bWxQA+p&?1Wx@oV&#(t#c1QT zf>V7N^bZ4bT9@Ka2U@Ub=@KPDNs9*~XsB;g*G7@1P}Jnd*$ME0;(I4)kkz>S4Y=Ov zP!StZl<@p>PpiA7aS>4n76mL4$Uq+-9Y(&8MWt9lEC{SA2k~YkjOSi^UGlQzd+;@x zKs;&IlZu$+xk14Wornhm1(OKNTqaVUFY}d%ASP+nC>k2;(b?50j)pH1m?T-`j*JhB zU%?gQNGyzJ{`3^Cy!;B>_Vb_X+2)+T`{Y~5W~ao-V6gIQj6U)DnLh=eNStDlXQJjP zh2%UI3=&(T8Pm9_HuCdG8P0Warm}~G&V1cH- zBB9cYDDl5d)zi94zXGZ)o!VNAjZUBxO(M1CdPM5yqf+LXsK$7J?xBM*60 zxOGHlwXE*naXQS=myWFzP~!@78p9+4lkrcZyFd`Xy7N92)zr{n_bWx+LRkd`f47iA zzmCsX@0vtm*Fv|0IBV^h7#SYKmQCmAS*08=pAT*Cg?W7Z!N~35~^h&UL1|b0)VMBpydwfiP+k5mZGASURs7@7g>cli7?C zKds)i4dsZvRG#E@@$R1#sN#Akuavk`awfJjV`CcTFpdv{Dz@potF1sc29kb-(}(eA zb~eXN=mkZioOXj9cSB}{Bs~B8^A$d9OqzB$1NtQf)7bopZ^8#zuzGf9fbEMuspsItWxUh=&UR=W^6c5RgFK{Su-f zu40tbNwW&0{{i_5>O^93gaTwKb3(v3W}U18RK=Ll#%-X!8o3bsR=$ogtF7a6n-=b( z>F`psl`d`+=wOu|OklFS0L5}#H$RqYLcA)aeb;!h(afU)0i-i|k^HFa*VJ5(H{aZg zmX=oZ^!6ZCQ-hO7PvBH{KdySmMflxgPbpDu*|G&omoA+qiE-WV;!7{a_U$hsmoK2M zwi^AtgSg`IOE8(4LS1b=g2e$$?fKuvXmGbRQGn%so( z*>AmsT_@t$vSFjD?ve2+>nJoYb6gL>yJfMyd0-^gA?aGv+Go%dV?CeOwH_QE!P1p$ zaO(IWq>@R!AHuBs-tO*GO3Dl{T*ukCel@1XCJ>4zaNyuETzKIXSiNRF9)9F*9N4o* z-7@!v-*a9aF5ldQTS$ z0h5Ig-Wu&hHnIrIRxZ=IweHne-z*53)Y!eL2z64@43IQ4OC(czxVg8Tr?Ms!b|@_O z$YTfhNi4oRNoVPh z>WR0`f|jF@T;3piR{2sQEy#$A1;nXSJ;ufY8eJt(-JqAYvf*fmWS^vD69dCEJp7-0AA{T8T8 zz~9Yc!Q32etRfzZcm#1%sB^|oB$_d?lUznkjbJz|Qlc*iyk0&FCh{{p5s?K1M;LyU zl);dN1JNlaU;dqil(;dJ8Ykh;DL`_wgqsn6|97{bx;kz$-6{lW*yIAZBaa$S!Kns% zLYgGgy*k}YYPC3M<4~>cX?|_o4CBCC=cNq?C+SPXU}S6p-}vUgD2aG9PjS@ARGZYb zaX8oklFu*=i93?Gb(IwqiEu?b5Ls~zYMVL{B+)ez##pwjB0+(j0zH)?Za6oFzr2`! z6TBY|Znvk%Abz>a&WsOyp)jrQ?~=QZ|0)(7FGHwQL62V=5j-T`Z4Jd}u3bk;PQn zMhScm@wiDXleEe6!v;oTRPG$f_==lCG*2v)Ff=lRrY1U98rjnPCyaALfixBivZ0<` z8qONOnB25)mhCM2v6RV9yK`PCW6OnCBk;=0J1Vxm!z#<>kotwXiJYsLVGjSH9)KWg zx09;}(@=l&NRLMJAuO3>4UT5swY3NnR+4ORQ9cNA72{SNIB&^gYN8**y#wg&J%sew z1WJW8f*?_lSE&-y%&JrhAz!Q@Qq_P^jM@i{ zh_aiCq(m6Z=gFtYV|;8%21~q-1APNH(cL2{&r&IfO`A7hd~zK7_8rIG*LP#}nP+0t zrga#6<3CUrA2Nte*OUJ0oUapIFcJ+>0NNPG!kl%RSEh=qNDxoG+>d|0ldE`~gNBSm zMr4NQg=z#tAUI322b$NC#g%Dh_<#J|*=&)mpx}xeJ8waurIHX6Ce-dzy;|p@@Kih& z!iTPVAMU;H*SdBWU-S+nQYk$5?Bh6j;<(u{C*#<%yc*YE)rMgGI^2uD{!*=I66DpMf##g$dga~ z0heETIevQk?MTLx@_g94cb5t-1}Js0LGz{e9jsP@D?oLs8Y5i8n-(bp+S=Nb$o+VU ziH?7Wyik==h)H@%MIE~$BYcrDpH;_06u{t8BfeR)Vp|!EAxsv0FGLSKB+GyEnz688 z;lsG&*CORTk~c4aPk-iP=xS+J5@p+k?nb2R&qe3lMQ*1ZNEa#?&v8^r5Y3u5{!@!l{NjrnkqVRhVZ=(m>0rW4 zR>bqn38A8bo9A6P6vf80Hb$HUr8wRH8B&Ass%8oYkG#wj3(nEi6;wVU`QpIy7ra)6 zZE%>j2cNM6`wrpBKRv4=lN$mZ&2w&&^GQ4Qs5s_}Lz zm|}{$^;CXs^95J3NO+|}7PsVIMc^{{lrX&yURu+UqLfvEVq-g}Ex)VDqQdV%i;e1L z9bPZmNIGV!q&bP(|K&m9w@N9?tr#-+nHf=3>}#4N<VfzlMCR6rq@!_Yt<1_w@I za(oEo{HPw1Xre4uGrO!XITRsVD+~s?*T5l)^Y)g(3AqwR)?|{ApalQUQHWL}Sq#|w z)k=t7$88-1*p(2joW%-Oz_B$aNx?EHR9N9fP^LR!k>t&!Is!UCmV?{{r*C@#k*XS` zYMK!W#}J5AE1-^3+dh^+acU3pCmu$a1k>s55Yy$hwWAUeaiF%^I2sgFl1UP))Mx}d z4~*iLAM{D1fyD$@TV=uQG|*Woc!G~7it_$yZAQT~WIG{lrABj0_ut;@fxnmLB2(HH zFo|rMlZ=jy>A_pKb{S%^DjYm~9Oqwn8LFyl@a$8+$LW4D>k~q++8Qdj<+@H(rIuqX zc^T^GH0VCu`foSm(>GONWVis7y7A&`1zdN-6Vk}c559)j=)Ll<;GdE4B95I3A{|_a z-MvY%|6AL;WU^)RIg0d@M9^bl$WaHA4DGm$;1)%F{T!sH2&tQuuSkYbs#_-T>W-I? znH-m%`q=oG+3h;^@QJsMX-$tT<=);NDrVsA8_&lB&pm-?IH91oYSk*d@x~qns0dy5 zl-SG?+=Nc-f#o=X_dw=R<+8eZ&K&t{wYD}R!_~AzHBxo8O1LBA6M80Eo7=E;%O-Sm z%@eVd1VdX}jNzGW+puEU68!OrClRPn!ZnHg2lmLgCz(p={!&4*CY4m-H#$yR_>go$ zs^Yc+M(CI0McE{VBDn%AvUpus4EUnW zldbrE___Tx5lI=)=Vj4kT^Pq6Twk@(13PZ=OU~P}8JAwVRRNePs($;yHXUXNi+(f9 z3I{_Pd^2OCc(?jDJ;gUJgN&CPkHlbdD|93?Orl|-q(YMKf7k9eaNmQEPB&osUJhGj znQd~-rpw|O{_ON9HBGd&6p)ukYT4zOs$Gkg_PK(viEgnu>7U@b?F`({F(zL-8Z2Q$ zO9uaR(<&8@-XV56A-m7xH#CUMsz~sX%i=Wotu1Rwy|%xt3(hWczKcd@c8{!u`{*8WQc*c?bNCxtK!Ts?)~4} z(9=JFN-l?BxQuuxfk?EBriNcu`C8SSez;8`%O^e+2LF$mp(n(6;+1BY?z50A#e2r$i(Mqwz(}SdTC-x=Li7!c z;JgbimbCG%sPE@PBm4JK^9{b&Ikjtdi-SYE!qaMD_lTSRM;&gI+65JTtyrBiP zLlIOK&BdQy+=-#Vw4Miv-*APHh8r%q_yEkHCkWpa?bQ9Blz#n;MKtHHt5z&mz#vb9 z&^+}TGE-A35;ku-7xNb`(m15Oqg}zDHp|a%e*qVse?IQI`yQRsNHB(;-ea2k^2};n z1Uj!yptHRldEQ6a0NW}TlRLXJer6wNpFxU}+$Yisov^YT$ zT1j%s@?wy{R7pi5e~$m~bDElCae6et-^G|h^nibFk}P(w2wX%GW_wETER)&2aQ*^( z-~;bA5*N`y*CGDDMS@45%pRFR-kc(*XY86{$#}!)R-s{jkcst}%gDJH9zp^~V^yyix&0!ORj zI6ay*YPs9Oux&A(9ozp;RMNQd+!(IeI(LRY;SzwvgA{X&-S0OXynMaa#?kroMUdkT z%s#Vf0=*x=v=APD$QfZdIeayhZVl25&Wylo94Zz}MUC(jlS&mK2zTB6Tbv#lMqh6) z8X9Vms;xq$;0DPR7Eja;h~Toz&Qtg7IUd#t+voDh*tUioGD@{vt@heFtncQTQ#dj+ zrAk|Il-7Z_!q)%iDBchaHgq;>vLb?w2G3BU%80gneZCJSdkIFV0J5ze=2!Jx;Mq0= z*Tz{yuerTKgF2!J9BK2pqE}FMT1SIpEROm8LFH#nR>fuFCmC&rb{UE?Lt^yz&Wb*- zbuvTL74NNLHVDkKTQ0g9ft@>d>b)sxiF$1?z0|*|Oqq@cj%z5=dUh*&3|>qiWFJfT zLvs$NgU#(ySG`jWO+NIR;W^?UbpSl6$-PlKZ0_{<%10Hlxv|X&vTmoP~_(2H62$2E zm?V!`TwG4xLyN}?ex3^)<;uNZv+=N)oJniaIgFhTB zqrYcAjvTxn%a@!+I&d@QcAbGrVG8L(-$ODqDGte=L%kTyH=!Tr%69s~^Uu@zR3e#F zr>mXw@exc;7;(_LKZ+#9WGcorQj*;`$E>QV)_Z4Qh%q1p%h>kJlgOke)g>z7rPJ84 z<3)2VO(u1HSv)k=hf$LnMRGWXWh>U>?iXK0b*f&ZJ056W8wMaI>#mTh`2YYQ07*na zRBWF1-%f2*T@BsfDsn93y&fGI#j2IdbCnYSfSjnXJO_@R)cn%}q_% zylE2_E?FYuskw9KODlv)d&kaKuzt;2-2ccUD5MGHSK-aqUlW;H3`lOg8`2}M6JTZ8!C8ciNp2W)d zZ>_dj*UYb}+f*#FLdYjcopC-dZin5_MJL?m_U=W}ccVWRQ+%%^vr>%f+uy!biJj;q zKNHWFxC=%4!bGIf=^bks2g$ctuyi4YBC9b_wF;qFjqHTufikkiGDgWkpokK`*C%43 zHBJ^EHfn7MPvYNiT8^efNd`qTh=LWP{u!`nVTog!Xy{uxze4DWB9EZVCcjPdH5?Mb z&e>wN>FKy?csd#S*lnnbLFQZ$F6D|i+B1UfJKn?x|Kbw#^mOCITYb3muDc}@&+(;X zsi`^Q?$5j4d8H5rqFaXkm;j&e$bD1e$4rWYVdvo@$z&Qu@l4yOK}CW4JI^@dCHq!x1Bn_6U@Tth6&S1ARxs>Mh@F}z6VpUiOl8iI zRwVOma;LKosL4uN0bzUsgH`!q7~pv2OaQ~i68zmBlCpqehw#9`*YL|beu+ZXDr!Cx z+9xg*kg9FMnlskol1nZ|EMX2=9J3JOl(15{WNvFtO^k$0-VB;wHOy(mu_JpVdC40~ zhpgPxm?~p#eZ(U{WYZ&<8b6JEI-?3VM!rBGgG3~ZsyIJ4Z$KGwq8M(}VIvq5iz=0J zh=+{?#T)KN3H-b|lx~k%BO`V0tSl>HsdsiXpstE$FQc}eLpWEk7_}M_xa{Uvk!omH zP~!iy`JAmmaqd1N0%gy#C-(6kc*$LZ>aAiHpF!Io#${koR#)zKlHKkxzu!nmwtG81 zIjOU>YV|rax3=NffgL!0>?o>gThTFh9*!T}jq}e;;o=Qd2sT`ZhR(G}rfP-yu;Iv3 zk*rk4doK$VS%@eDVBIRjUxsX+HL1ZMGPvhW$eHvZRJc$a1G`-Q9lca>X z)1TAo*@`7qShgU6y|0g8L(5tC&F-DZi}MjsN1%HYjSFpKqSC|4ftYr-L(-KXOvQk~ zbJo(-plin!)z~;@Huz1-r96x>n3l}Vwcn@E5_Zz#g z_1sOk^MU&@F*GJ_%F)C7k>q-;OAta7a<;X=d(LNsqZj&quxKI~&x%YN5pcfBVqn^Z zkez9JiA&xYl_&VWlq zw$j(xm9WZ~FztX#ZO>LY&{v=PIZC3P=KVPN$4J3zjUxO*h<# zuikMCnVK$CMWSNIPh@h)&;nhJhD-7;Zpw_0RmmdIzXOZvL-^6xuM@}12#P9a zW)UQV%MbDRa&?GaTwFDP|Ml;+i2* z6Rr)vd7v9RkB#HlvBUV<=dML|d=Lv4EX4L#-^4F}aR+Yx#E0>~Lyse?b4bLyfOlVW zmCg$rQWXhmHr*(LgW`fI+Oj!4YT8$??W6|FC` z@nCZkql|o&jS2l`koDX%#jaxeEW)TnyVS-9F6Y_z;$e_u}tg(6y-u|BVVad{Yy4afi zIx!5{v?{5Y;+rK-v#=Ell!>muu3$pfBw0oHbV?ffG-%?SJ)553z6z+G#`P4=))?6M z-qNE(f}qnAQ>d*=p;AmEn;u7?LVfpf1+{Wv0^vZx$!YRI=kMj-D@~^OpfT85ablX= zJoMBvuxoS1vQAXTM-U89)QM208RQW1K0T7hd%toFwe_tt-523^hfeTN@^kv4&U7X$ zi1O=F+lwb`SJ}Z?|K<)7RK@3i)z&osRJabht;^muc#rxhnWwsDIAil8Y=Z85}3s4;S72Q zgBU2Eg_EOkbai#0v!lzIh?z7v@9`*Yony2^rVoLwB}#yV>r;XlL+b3j7Y4h>XgG@D zks%BX_2G#>`~fFVoN!8>7C3pmd{@TcxaFKK?B90?6H`fi`IDc(cfa@V$i@;Fofwy# zGT#TUhmC%0ZI{=LXbTewiH|AK$+xBM$ZI4uP-$Da~zTI*<-=MKSU-y zs=(*_^x&}MsD)OtXpuFteUH~;U<~5C-J^`$ei#}WHr<6}3fElo4y-w2xnh)vXcWwG zb7z}Tn^=@_6ii7^2oDIRLWB_C`f1tv2;QV`iU8s!*k5o;M zid+FV&AagGkv!Kz3nC&C8gY<_0*e9?5REG&j#AXdZQ>*lg>rrf9!(LURkr2kKVr(j zrgUk|v={3$-id8sIiDk^*s0P=63fPOnaxj7%wl}jW&?9nQGBGq!D00EoW%N#=4?y; z6p=v|0>+gHSexqZg=SQ zOGR+AZjcv=h8wDeT}8zQ!?eMaLk!5nl{g$2z0(C3di5$nv04-OeC! z&KRRgIGXJgXc5iiKO+=DQsGZ;`%fG_d_w#PUJNC*LIG{93vt7TZ$ND$;XN`&Eg@Rf z$4-&!MP`pFt#F5mSbtXH&vby|L1dRDcs&3Ga|V_E{s9rv_>f?DGLB8Ui)$hd572yb6| zXm9HPoBExvzKqU>I6n5ic}RxSA`-h^)1H*zopCNJz zY@8C-*I9@e7sI-EAFzsfLnCAd3_~nA>S%1Jmy#t5U{Bogq)vX8>Bf{uqv8QKOp=B^ zl2bt;s%R8Tm#)CI*S<@Tt{hukfgtfKM>4Y&NH=b9n>-|b5hk`|W<`iS6J`v>?k>mu zdKb?uAvh9PnfEBCf{8or{Mp(2=BROiMK?s*>JISUc4?ZmZfOL*VK zOPp(|C3TSy9V)0I*G&e*kx?u()OO~%w(l2;;$@$w3k!!Hc-;f@dTq+1X!BFe75nG}4=n}_hk|K|o7#Pp4cr0!_ zuI9j(-Ql$#^}?XyyJK9N6jwWkU2ho%vD@n zrc``)_X#XtvC`0osPTAeYf@Gp36-273hSG^ftiz0_h^#7eR^ybRI^|z#rAa}3E%qK zKUCJAb2jGA?-Ki-yaX@4!0O%?34WZwB*=YcO3{jNAymMiXI^M+IOs;rTr723ZcZ|7 z4B`ZpX1;E0dk+_>A{O*-r{y4_9*j|A}aQ;*}xKRzij3XvZPF%^qwsB6K; zKJjVP)+Y>A5NXgVKOQE2CKVifI5d{9zl+(=8zaMvBzk+h1*h6dXGLTzUITwksQdq` zJAb8(g{pX5QoLgm!?@?JyHN^65vqjosZW0##ZnHhyz&y>+;c$JW9ya+uwvCxY~TL8 zB!@|udD~T2V%4gZvRK~!!Zv9wY+QdfmabSN*7^4B+b}UQi8I!$L0d}-bBfQQwZ4E< zd>ruznY+#kmmN|Vn8+6Jj?W!JImmUwusXY{WD+&0I@97$8ySqSGJ_(!YJRTa;UUeV zo9Y|U)Y^a}hmPriVY23#u!`7N&Ay)Dm@^YA?~uzMJiT^$1pi-$~R0^j@YzhI!R*KPb*5j7iX z=JOyJTu2PBGYLl~%v2a1!7U&A7{2nOA0iqIsW@Wc%RO+GFJ#~IwP-=z(qcBS3Q}R~ z;8l!f4OyUlurF>WCQQnh;z^@pqZl6_MN4ZN&e^aLOO`D|Z(kqg&z*1LT?pY+&vCTW zMzMR}AsjiS&wn+~I{^EDe>@its>$oIw0g-Mi!gUHUsvJ&(R zidWI97LyU*KhYZg5%D=3R`Mh=Ap|ZO)z9+ZHgXA@c0epPEz9iXp8acieu7jOQz;b5 zj<1w3Igv&z9+BGQM{l@Z>Wm?-O_RjPGsR-X5xRWAVub_YX!Ckt8^Pj(<4UuFcB+`Z zD|Yio_rTz2`z_=|VG zO=nk~Z7hsmJ@gVDJJF2ca&lU|QsWR8r;USPQubCP*>;0ZU=nn6a?x|^O8D#ZlGwPa z*+`>K4%#CEX3#gY>YL}_SnmWLczPE;|G|s#=%03?v7s7g%x}dVcixQ~Kk|Om)zsjDUq6b;i4lDC zhU*YdR->c69l!a_qsZmP^t!zE-W8Gemc>5fo{hr&xZ1|s?7n%gRn!tea78RpTXGgy zBrw7IZ3w%v=Gy5;EmY4nQmaF7Tr+LFOyl8Md@=h#uPSLv0DgR94S?r(`0H#%g4=Xp zfsoB1m(QTDe+ZfEBv!3F)AC^uNLF(km^373nhgEtqXu7G``BgZkt<~QIy$>V6AGrw~T`fAq<{-!J)})L1hZo7T9s*he6PuLmZP!_Gm5P?X{5wF2{~ja5lVW7Q_X8i00^aV|U&Av`KO^n(mCMe=RqwnMk3aq!96NkmE1{b< zU4-@P=c5zPprav+WP*r>BrOek|HIpmsnnsmx(1*okyFVk2`m zMq@`_ld4jJB*Z>{UY9ftc;ZcD_?T`Q_GienYOpt5VtkXPya%xOxZ`0Z5 zV(E$%=)12I-M3 zH67%5aKyqfh|_Q2_j{u$B?33D;dRXwa+sRTpsv0~f%i*a{2L^ys5EN!)Esds2`~}6 zduDOYMr=y2Ixpt7sC{+U85{EH?!P3{xgP1IkDd69MCAy5XEDY(`Bd7tUf~da^rN4O zgll{tu|TZQu0-(uYp=mY=bht598RG!62{1Q2LF7|A-pj)$E~N&ATfNeJ^`7Sm?dmK zCb7?BBsBWal*-P6 zOqa-tgW1KGM`)OdS#W$U@x7&Go*5Y;slma5V?o$t@1@cvoy z>yOrCbL?P(Va6{pUXG0#_{SA36=2H+Z$segH=k8`ZC@GrasmiNQJZSUc^7TP%GGBg z#kpa@{K`F9kx!5%5}Q$Zbum+9q#%#8Vx49Nn-ZR?7pJk{t0TYdz=zLoOL(Z2!P@T} zvx1rqKDv2fRZr=uQQZ37@1cL7->s=Z^P0NaCR};t)mVGh8M@F?uVV6Iu|U0aw{Px| z1fd(wg4GHIu5i%>kO6R9D1sprhKP`{Z=_9=b*3s9=Z@T8Cxk|lT)vn?JVa)zRkJLT z$eL$jv)MEE(z$NNPM)1@0>KE~yC|SS9f-8{@ayUtkgTF85%s*&*#6=Uv^2G0-MTYS znLLC=$>&j@DrjYsou)sqzDS72>+roh`tazBqiAnkhBG8ejsaHEp1jlTQRyDA|oQH#N$5iCznBZS&AO&?^!h$208qSDtx} z+#5CHEauVI*MsJ!26T1Jw>cXjJ5o%wjWB6vDH2i9MjrsaFBZZ48d=gD*JKJAJo?CQ zv48I#>yCWzb>uY#2o^DF+bH~ENDPU6{(RH6m4S#I?w4-*I0l}15)XABN2t0+e3s@p zb(%$U#gX0Q=>by_?4T!z=F=7+XcNq$k_vM4isu-CXOID&=+m+#OI37H9kI2o74zCV zvFZG+8bNe*&68gQ<%;|JyHTHrU@)D<og8{E%|$R513Rb z7{#Awb3!98zDeFQzCX={U7_KhW4#W?fYF#)4vWKJqD7zm^rz6?Rxk7*5lJ8^ z`VEHJDuccYGjQ0N3C~aP^J0gQy0t;4A5dn|NFR#4I7{S*aFc~7LUoFxPGHZQ`|-@S zm$Z8?GPvV;-2BOpVa=IKy+^$x9|sKXj>YhkJD8jQ<5RU;w}P(iQ~EHeR&^=eY<5R~s?h*;+e}f{FpBHt8FQ*)X|Jczj;e z1#^{;9F4LON_kFrzKJ9rI?;<2ix!|5jN|v)Uc(zF#;~w4i1%H-32z=fjc0f6!xtVuQCQG&ZaZy>FGmVO*Oja&9}t>k%nWaPS&VtH9Z7}D9z&1 z_(H@NI6V923i{_`iRrknu}BG9D5f;EZCz!mSdRz)Fo>7-0X>6c&(|Xmiek}{#klB_ zOR!+!0x3QD`Kk3}_GTo0p<;pa)EVOle=%n&EQ9&IA(M&>yLMLDxIcnpT(7Sx#}ONO zIQV-Q(C809A&%Q`|1sX&wGWvbo%l?5o}K&IXP<}5uDI9=gjpm>GoSVdf(3Q1dwO*% zt2*iTK+S}(gq-sEtR-*>$K=)JdABSEg4cKL!oI!x#5!NLYy~!+y$)~gc^%I_`yvY2 z5=XE^wIy)N;us=fTPDwVCAxvXzOUPz*{Nf;Nin! zWYhYWT_BSU6HrZx9eh|Sjn%o=(N+B>Y7#^QY*jKqZTdh?MHF=r!r?mfj|cFsPd$a! zu4Pzz*4f%SCbN~A4P@;qpu3qgJ5)V1PI*%uGdqd`Ns|>Ne{wC@vF2pL10^s14EO#S zp#5&LiVu-)Y?DBQMt2=4Q!BT`P!P+PF2RQNXJgOaH{}VzO1`eH7H6(rj^4i0*!BAB zy6-DjEWv_>OVx=C4~-$7Ae0!vl9gu}d$?S|*yxDJe)KblMB?iHWg1hkb)w1f3EhiS zs&?9}NQAg3MV74d85%x~TYqpXq729yr8x$>nB;o;d&0C~vOc`nFLNFkb;mu-%&jO#L zIyMMY;S7bep4#2rEy5+|p}c-xw}7jaOvZ%t&63@A+-2v@^Tm04!HlfbnY&Sxo+Ua< zPE4A+rk5br1`byp(?Y9ktHjQfPe>}@om8_o6yunTKf~)Y!6Kw4r6P3wS!?l*w_k>6 zD5?3DnAn`z^J_c_&=Q36AYjkqy$Bq_pjapaqMXo1-W#s1PK-}V z*ojTU#AFU5!(({pk>BeXqK^tyW7>*jTJuQW|SWPs z$}I_d1Yx#_l%WQGHQSRoT^C#;iPiipxP>#3E#jqJhfv$lid_f#FfulX%`4k6IW~-S z>(}F+-@k~fE;s{g7B5iAGd4Dbd+vJxH{EzG;*kXMr6O+q-uLnOFWl_p-$U5@`YVVh zC`?sx$N;U#X>=5w);jTdhG*L3{5jThsDUdK$UX2QRMQ7CWQOA*8(qvAGrE$D*HmP3 z_q{|*{3@nU9d|Emy5Nnj$O$PUNWUG%-s$GU3N~>zG)|@PTOMg@vy6>kWN-}Y*Po>Z z&%dsUgz6eQH!5n)9@~D^jHZd@JMX1o#erXEcb<`fumAuc07*naRBJD~htmZhiv)5K zrk>v*aEX2g`WtV+`~~wxY$EJIJ$Nsq!2`u4 zs`=@xr0-!56Y6m6NjJ0B#n+l7{TFN{NFUNURC$L%z8C*O*ef+?_u}ruj1)vwrNbU zc>W4p{jMvpd)H39@Z3w120df-T3q$cE0o0k_s%<|2*^(HuWr0aa-#R%^D7iGB?O~k zT>HKcqNTMC4cTYVRCNN$7{@`TQ(*w4KwG~Lya~WCm>`%$s(vnR`ohog%F!An&i0N@ z&5Fsq<^nJaBX)-D$QaNVfEnz3k}%alLe_+NsiZiHLXO;&F)UiVNPZP{b#)Hc2=;NYQy z_|>m|iddLRY%`2tZB{tl4PIgvs#B9wx@I!Qaz%roYg8qrCPzf@AB(5u^B18r702-S z6#8;Gjh_Yw2b7SgA;Cn+u>#jbnM^jUTO)LU$%9-4IxYId$n)!0ciAnqb$04p4v&nW zqqPlvgF`sgb4vR6WVllGGntI(*-;P-1+==k@vO5X1v@%2gj5w*1+5UD?wHAiU|}LX z2aaRnx_&I!_+CZma%z(-s`gwUtp@UpIYD{TPB{6P_WC zAow*;TGX@Z#(lHbBKf^M3nXq5VeqJe1y|cHA_Cdj)`6RDybg&3_uvUTGYMG3!e?Ga zZ*HgDI!H$}a|(SXuA~JSoiVNRx-~m{)EHY#42Us<|FA$9ADdM7M^uRSCPTxg@f?12 z&%=l$;v$HB{U84hO-*&KbDw!8481XQ#b)MJ_~iqC#9ePBQA)IG2(8%anD9QaX^ECA z>fSqH7Dvd(1y8I)F^e^+Q~2l4T!@h5-t9SLRQ9TShQN9qe^ZmRZr2KLeR>~X9Rbp= zt8uzC`V|6NMmn2A|G*d?eeNJmk4|E$kdwnsDpbPKxpNRtgmB>4Ao|BLxct0zxa8c` zdL70fuASd=@55NPW*L?ceJBR-#V>sow|wCfn7?qL&g&C@d>k!pjpCeG;x|z(BOkgk zm=I`t26zp<9I^^S6<@aX;QyPSPy8CK$ooRdHp9H-z)XMZ&>Zm-)Sp{Hz@*IXUiw15 zEB^oU4`y>a{F$c#U9Lcj^^9WeiQ^}+_N+Bhf0Y!0BlgSrF_v(K$~+scIM6*Zf-1Fs zM4;5DLk38CH{PYyzm~@S%*z_v5J|WSf$a8k5T_ zu;5WZVDV7V4Y7IrvXGCaGj~l@1)c7>NZD?j&SRqpUsgP)HYY_y_E|#yu z2akW}b>RA4UthlxglDz;BGTJ^i@Q)L;?hemMpI*>`#vK#l5|*8YaR-jY+mCUt=QF> zRW=Vx{hSUYYwF#@P}Vgj)mLA`a9=N`Cdb8V;7FjYwMDPpM%1BLL^4^e z*Y`RFYz(xvCu`@lx;1iySlsX#q=*xLKZ{Mjvds4=--Muvt?~QGWuOR-*GS;+)R-Zi zo-Php4DdDh$7Zgf>4JdIvnMv{EY#QQvwJZn8~K>vk~kEx1U~VJ8&MVYYKpG#^I~RB zlHAnzykxWUuW{>c3};Hj4szC}i6aL}%Z0MJ*^EX&L@`(-P;HS;l}*iaRK!qPnes9J z{Xci=>)-#6e?u~1qXJK0v*(wMi8r1y^DkcaLOG1z?;ON!&y1lMuoX;plha+V3JY=C zrwg#@!a(EP8C?Wzid4!77cklt-K7#vO{!RsT;$R`tlv>0m@{QKkahIC# zF85$5)?-A9+3IP$iK@4B@yuP4RSY{cyVxeW;a5{EVw5nInZ*D6(AyxOuHu z3?*o|;*t;5F4-lJWJlr}w-aLdZgj?8Kq@?pRFc<<8V?*3m^MC3jWr(2L<{ww$L&NC35|q$=Y%bLL?F{P|klqc(-+)9Q|BGDPJ* z(-+{wKrQ!0%h$*ZhV$S;KC6OcPD2wq+B?*x6Mgb?Sr!8k*;2DxwDAHrQ|J=-?6yDQ zkB>j*%*!0)8?*$@V8SHi&xS8}rblYi4_i>05(^hDlE#Dfh`7BFuab|#wO3q@-#qpR z(&4C*Fv+wmeth5v2SVDmAtc*3G=$}g7a9YdtBKBYo<$fNgucE${jPGcjMk2J89Xr= z(PeV!q9r)@oQ)V98I>EP0tKHlqCvp`;?*hq_B#2>BM+xP{Lo z|C@yni;+yFeAm5YyT`PIvFkU}!1poP)lQ>@Llw`X$ zE@V6w)Yy&%hrCG?JB=)7972Pp{S4a>18bl{#WdD84&ghWyZ|A-r)i|Xi7Pp^MgLw^ zV7T>1jhh`3sNW;?L^g_LlMpUcFqO{Y*=?`j=)e$84RXvvsr8&8&s;wzq7ca9qu0L+ zV?(2OY5O)@^NuU!q2pfbw(?8Ef)BZhlvAvcTUq(@LYsqA%k4D zAY^WGY668~2Hhumv2oKT_ts3%j!iY=f!7!D1*4s+KSyu<*A(NOg|?a+dK1A4Q8i8u zVYf3x%BEIeF4Feq{!=~o$T7uq0H-(eCa$`>pd_zzFWpP)y8G8i)6a!6`Mgi=~V`=vIHY+uUpkBr}?Zd0|61h z*ikVsYSvu|DA=(};Cr7+Ph$W6J=pft^C*-mShsE?&b#njjEoH9_MiP6u}BpzxZonJ z+pt=%IW%+{zqsQLtXs1YSHJx#j4_D@=^A(%@v3Tcb$047a($9yJyxJhw8kK}jgo3= z<7e_JCQ7+Hssks{8G8lQ(E(`*P{py#wJ2DjW?c`19sM7;(!>4g5C%u`xbdscVYEmcQ(!K z65ESsL7+fI&8l!nusY#sbxF>vUh_S&)YH@~C~E}ZzlXt(0bKh2at$ruJ@0!zhK5Fr z2C4r~f@cv+SFTmT!gG^Jj|(nsYiZNxV3HxC!#@mKB+T)Bkqk=iiu4i!CA|2`3)ueb zwrR^>p-*zj3!<;LU){3Kw0p?ynXraRDxB=3Tbj^VUvJkSPX)bRP&t zhFs<`Arvo{m08pfq4e=_w6(P2$dSWnZEe$Qu!!ROp^y>_2j4mIIrjw?i)W52IDTQl z=*6Ubp{XK15Y*>o<6!SCrr&4s@RT68*Q4naiv*6kB%2+Jnft8N=&Z2uJcfB)UAXMh z3&a6oml+NchBmof76}GBlhDWl-~L+yb53HK9lA$uym*-OE@a_LErg5`1>YBoA%1?o zHaktm7mnyCu$E0{alu6wxR_#N3jar4AfH{uC{O;T%sCN3OLk=GKla4S`2Mp6%rak6cWK3p zPi#69B&$1J5yoatV%XrY;3JWFe0&Ob-0^E1J5HzDEI#+ezd=V^6T%3IcswvPi2Vl+ zp}8T2pD#%~{c0$uHO*syVv3cbJm@>g-= zb=M-1sz>*!qZk_-R&%y=$y~G$>1IrKL{}f%eXRF<179%k^7**wIUdYiBttWnPK>8< zs;3V_!-Fc0tKu;%U%pH+;^BvXBU3o$A`*Y83&UrME1R`-bwVD99{FO>&S*u?yIek} z_-_*%qg=OQh~rSP`5qk|Q{%pT)k;THwSrGPutZ|I5b|fq^B|10?V3i%Q}82HZZZfl z;TX-K68bqAlu_fzP%Xzv*jN$S&CTyoVUlNJWu?k*rB62HiCI8o5DeF2B%Q=JzrP(P zMp7uE3PCy=hQerTpNmg@?vv_D@+J1QEQK|Zb_6cYs+=XUTZ`f$W>WMDbo`*IR;74o zihYiQiT=Lh_~DQKOY<%Z0$i&jtQ5mdH+>G_uz3d9Yq(jEJQPf2Rqu;Qj9rJ;GtJ?R z7t*T>rqfm!Fo^m0!obWRz(B-@g2lq4kNy_JL+qHN_~3Q#M^#k>x83$r6Z;87aKlYE zAeF2_*@Zn#}emR#9;M1S^xZdygzyI&r0tm-y@%4ZBir)8gFFcJu{_bf#+iTaI zi)*iYH(uKQEFOO7QIyMheB$P>VE)1u^qo9`IvmEDt{$YKqX-6V4aW|E!QugWag=S_ zK^=uU=Q4GNkW97XEC2E&p4?SJth!zuI)getA4el^?A@bl&TGq}gb*^B_cgUC!Poou zA4X4K4;C$0D1sol1Pd1}oR-ez;pcmxEG?0fq0!TpfZ6d^xIRfffQ^V`Wf~5mwW&pk zmDiqRQI0}ZuU?6R`}ShvhO<%M*d)1b&NwNy!{k_9*ML;b90ewxv4Q@RLTTo8&eJvn zVac+_5&;#Qd?1+s1Xpt$P*a1u@BM{{r%}iBWw4bfkaP~X_ipQGJWs)piNDY=C>F2A z#TQ+qq<;LZBRUsEVEDPYK3H2k4v`K-`1o`cR#5=f&G5KC28iDyyB(@s8a@P5Qb82m@i zm+P*4Lh_sda*s&x^2Ar#RF4dgn3^J+1-?d(#Th%;k~klH&z@iNf%m=#b@eF~k3=wh zcg~eg(@qGXASXT3u<+||Mq(uDU`4d8M{+&aws)w!%8eLa7i#HKyMiP${(ho59DNW~ zD3pp=yY?*k$au+TohgwZEkRiWWwUG(d9uwCpXjI>iBJst`il7MfA2v!QYEKRA-`Iy z^#9BxbfIt#S)&`A>SU?|t zs~6Ew9$)^--=MC(MX`q{*U1y7uw>~16!R7I^pE12_U${UW|*U;d2>6^*VBtk#?Bs}QS#O1&7EtUy0GyRtjTek z3%QI6d_KdB2`uJ#cCwiXjcZPw?8DacHY+YjtkB8fb7k8j?S9lCj*u%LeC#p~g85kp zofgdCkds;DOe};|N$z|GqF7Y*OMob1j z3jlhXvy1gfgIz^57QolP{*TB_Wu2p&>2Mo^Gk|N}^+9xWG>DiX?E~jAL5S53gX1(% zK}~ZaCZoK&7zRD@60sAo8FoM`ellNiB2Elqe4p%MsAZ7P+jzkQW`Ie~c&p+_CF}Iw zxN$KlZG>I&QrNI*lfkNzHsSQ6KN_%D_G=;rv)!w+KL8wZq_Z~4;Ss>}WI zmp+4dq5;`V1-Ja|-(umyPW;Dr{|O&_+cKQHVhr)nX@rBO^hYBp?d59DYKOuYutvVr z{q$~?;TQ^mHhkhMk6<9zF1cfo79E+7a5k%AZ@Wsdo&^i$V`yYVwxtY+&2t*CV8H^@ zV~E9cz`cB~VDSps`h5}r;o2Tae1iW7dB+nvPrL_2X_5)rV+X`@(0*{KBx9j`ZVKzy zZNTa?*I;a7$|~;(cGhuJ*Uv#TUabN|qXv@V$OBloP=y2E6AL8XGyYybc91|%K9AdP zzYV8Oyd?lx9^H1$fQB_P!_H{D`fDCV-pD>5v#)90|(Siceb|)PA9DH4Uw39 z?dRCxOrX7UuI8pfz&hHnWWi!=+PVb;eSK(aZ`Y<0R|3=Nab%|^&^2!f{{Cx!hf1F7 zz_#6DHoQ5EO^!)tf+L{w&fBWzPz7H$V_i}RPR#}tLk%f( zfk-H&>0W5vRQmD;RrjAZ(kM9u{Cr-Sk^f(vo#1x5?s2|qVof$4BR8c^MF)`vJ~KS* zOwcsnnm>OYdU{S7k0_f%O)`PYF1=9uc%#)L2;_Fbag^dTF3!XWtxK=8dw_uTDwwuQT|M<>Qh@Vq9<=1Bl2PQPz zWUv@!-#0iqf&Y2@FrGdZLlNX1312f+9XC3hUTxHrmh5>)NObn&68#c(5kSz9)S@VA zJ@Vf^eg@{$nCqyJ<=F;LWj8wJ`7KsdEHTEj5Hg!^;JKIgV1Hi`JqLE8u{MkkUi&^Y zG}MWER9{!4f|8?%7q`EHr=EQV&2ySiU0sFcE0&@*Rfm?AW_7f6^>vD;EZDVO5U;|m zxBdw4f6tW~#T-4_hu=Q_Yut3>jT+BV@_pxy9T*)O*8eBEw|v=RogZ@^Ch5@phBOLx z0&Sk~J>6vsayL0}zi!X*Bu}%%u?l(A)z&G-oa{cSXQaNN?*DT29blH1<@M*bxn+8< z+skY(u$5(D7o;gj5tRV85Thm<6Jv}-jhgyTj13!6VCOcncbb) zo!)0|zyIf)_xtXQndez{nYnYz@ArN0_rB*n=e$A=S-epBb^Lgz&asioUWd11=iQpV%Dr##(OLTku4By%%g;o zdA4-bW||?>baG1bi17o=yuXVH21HPF!@<1F*$@cL*|uZ>z-Dq1CUkeNdSQ~s#DRKgX249qxJi7)$c0VPBYSsDs3f6t1}|dD%dIbkY?^G_EM~Q~ z;L>f|(a~{M2WM4Xi|0^@L`sB#m0Nv7y(2x@tag2FH!hWMD+{t8{`d#zK7B^Xp-i7B zF-+1Mk0ZhoQ|gZ+Kj zRNsiz+qdKAPd>5_`~_>VFcIK= z7V?+R>-BgD@cQ#UFjlD5l+9q>x(l&r;as62Z13^fMx#U{<4!W?CR{Qxp}|hrAJPtv zCLm8qX3o%$iSaRwz@{9U2@8p^HMR93^okIiE1;&j#!c9DJ_e5M?un2-saKEKc~eXy z3#N4N2?FC3@8?s`?8MJs9zi$eA*;RYR76S&T;*sq_u}MUweA={`8UaLJV|91 z<&Z^vXas+LWg{+L)hN=f!O-TLp)tlXO0!l2(KZgKV#{xMcnpD(QhfDa?n3?Cc2u{{ z!MX)i*zwronB=(diV6?`s;VeQPv0QUba!A``$Am#j?1LLIePqvX5++T_Kzt%U9nqr(PQ~QoBLlbQ_c+NSRVuM4+W<=8bU&Ez@EjwTz^u}FpX~lIUUGeN zt@`uQ;=LX2J{B{{U{cF9%d?03lly~vh5Ld@3JaeL)~(a}F-Ha7Qk&f)Vz7!aJDsg% z`D-LTPUxviH}wc z%$N*j?@}LDPJL6ma#i7HHG5^@Y=#YGnSP4B&4RUU5urFUMF z$)F;_j{DHOKqLV1tfM~v?frZ4>jxr1Ik^A;AOJ~3K~#TZJz;(9qwVbIz*A2@i=|7K;l`V;7mtCJ&avaiFn88`wPd(x zxbV8W&!M@r7jsHpMkF+((bNQ0462--dv65`4?qVq`O1zck@T|Od?kobq!N82G2Hdj zxA9gdt&-#Fc~+E{fwRjA+p#jEuAbMCGY=R9_w7HRLxO$7xpU^axe5g(NkfB!B3Uws zaD$Mu!C=bdVd;`3IC$ug?)w}X{y1`#XJPZOudAt6ONmvssZwn8aAjpRuD<$elvdOf zS=&9m=Rm^G!UgS!$IHYS;Fq8D#tM|{itqKI2k%37ceh|kuE9(`Zzf2bZ%+ntkkE4m zrHKms=|?|?Df$@XNx~Y($&OCMN+KvNE7Rl7o;{;Ol#)^=93!KnIz-hAlnr!N?v7V1 zT8z>;v+>~Lk7I0nRBKIUNRbj9hCRLHmJp(!P(|Bu`ivYe7cW|%LznMg?CU(y2lExs z?1W4f4ULUDoCf;)(bC$2#fz3;>m^%p^vGefw$2hd;pJXuPaVSArStGNU;PgxVr5D~ zS>E%dNeXHMq(WMQM8eMXoL8%g$rL|-XJ@C{86sRc-xb2G z9(CdGdTVDU39Ze|s{Yve*|2^c8td!Sen^zYrGg*_f`tHiCN>J&5<$WJgk}BA0`gyy zlln70GKS>Tgm@G*{$d-esksehoVgJQX}!r~K#BRZoxJaR+Z0`o{E?__YA-`Gr{Ql8 zC-ZN;uUHh1JnBiywgXa zq%exB7Z>oc8`mPMK~&B;F>8gQwFT*%Xb3{@zz|wn=cvMd?DsF?#aExh+Ra+H`i{sFtLpa~lD<2RJuxo8?5utT_Y68bkoJ6!FjMis11r&!IA4VHPt2)kDECY@6)4?K8iJKRw)@3cOek8k>3t2Tt2y1=Ox289|M~KluFsGkjW{c)M<2eoyFWab5LE)R;vwPo0$-Jbd>AFa};Ju zn5|ay65nZG4Hp`%mFf(*e5=KXuJ*o&_*}aEIs`^v+Ey@#+O(Z?W@FaEl)>OxE?Dnm z<^85fhOmrA2az+I5HuL3G$)Lnp)ekMc@U32--AM^5`}ya={!(d+k!RgFTgvlyg~*< zl(&_|OLeFaL6B=3C-setsI?J|265+|cdEA?g3bK)%=T=K{Y_T=3`#*XHMZh!KKFTK zG91^O(&FLInJ}v_M9holKfFlMEKSO->>^Z7pcr}?=d2`AO8u`sYyKa(1Xb32n~hs zf!l6ZfI8K23NOC+l6mHbWBAy|Kcb5J2jBmJd#*S>^Vgq}?*510|Gr@50Og3 ziIpQI|9TrP#J+b+OB2dU%ap7zkzw^q6Q8Q;Y8`mIhlIaxxZx%oIB)=c1O0NxeCw_K zj=c>uH8zTY%)`3AuFiRen;Dl3U&5S&5tZ?bxp~^5$bPeVvlm42*>usxXl!mlPfwrb zRxnB9;lpH44wBNv)7f%d+u?y<-H(wWb7!Lw5d$loEm?gj3wH&nfur?#z zG}(Ji5bjT>F*GgyXZ zZ_Zr2^V(~%|ImI-g|vxxR#EKRvkP0+ufP}o=|7N&R~DxtTECenACwdxIdViY*yYQX zDnXEuS4D-AJRZ_%sxsUx4+~OWR?4>9IO^)^b$AnUrSwrq9a~8Z;)T4DT_%D|ps3Pd zb!Wa1dCj*VGBClyn86oA*PUMj8vkvcw}iGtcXF_V_D7-8~f7VPHlofi9?6COu(-6zIu95i36yrK#X zjZKIp%C(=Zt}~M@#!JsLP;7OFl$XyM0%+`WUm1E7!4x%4uBO}}fI=vYmv)`RH=pds zNUj=L0|uOXqOCpu<&$tp^qjQO5Cms}}HRHdlm5BB_!?SX&+mmN{ao1hn!|c{(C5y5O&rD+dh3lM=pHG0?%oxsy z$fQwSS&CTHd|=FHCxZENXJhv4R{M-j`sWRj1kJ1EX#@5+V*b_LyUzFK@@5H{V2MWsQ(9o+FGw zY)#NhgrARoA~f4-Z(pK;R4VsKz<2fneDCJ@VJ*&??W&o`fmiPM#B;`yutLTu2t62} zgw}Brn8XN47<*~EB?+1!W>O&jZEXiXhowr=no7MHj=VdVGYI7K`1W02le=Cp z7{MJM{!=u!HDPG97cal~687&qsMjY9tk)|9@vdv%gZ1lI7-UJMKs1JwGP9Kat?|Il z7hrsB%!bcQO`*BDMG!w>Zax_w&uor<3A#Z%q$IuLf}|3Il0$QxBsq=&f<0(q7KE#q zX}gN5rl!tZ-ohp5?K!W1H#9V>562tID&*jy!>B5+#O(R=(AZF~c@RIn=f6=~U5D-4 zug1bf^DsEnkN^Ds_mtFZ+p+;ST^vG1$tjd@v~-A4J!g<1hd?r(sW9+%pKgq-2vK&( za)H>t*|#!e@019~kIIWp#~`Z}a|`#LnlR#3h^8;_Ki2FVluvg&9%p}3u89W%g&A5ZE-GC-ll`^?A)dLf>a6W^0VHn#M zhw#C7T_99V{s+m7K06OyN)pd>bz|P_**1X|Mza0NKYkta7Bu6g>)(x?drsolk35Y9 zix*>lTNSpiTZv3^Leo)4hld?ekEkyvZQ7xjO_{~_-u*}LFaP#6%$?gJMaHbQ`8d{b z2+P|SpuD_BRlJe%Y!ILh&P*E3O?7Brya;dY-zQEOiQ@cZNxait-w@7%thm(Wb)|$hAtLr>7qS{X^oF zR#uogZhV{ry+Tr0<+5yBQF&)=K09YyNke5#^ z{olp4;*tuVMEC?kEhJ|Pt(-uEo}A9W*;^Na0bG2^)oeFh&eOsMf#g|bQcLO#j0KqQA2_TaQI;3FBi# z49srUru*eF#`Pn3FpAl&b8zi-Hz+WLOH8}Z@yldm(>3nQ=`%Jhaw@G}Ev2l(BLmj9 z(pX`xb(7K=>XA`W_3;l}k9pPOICStO9Pf!@!HP?jjPL+dqK&XxF^@m96W!+raHhK( z*Ilt4RgJYMWD1x}PGH9iyRENIqOYoJ!o6IB8C-G2JLFTq=cuo1KwE1YF1_qBtP+@#^zW;ayj5#uxtSJ0i~VVB}%Rb;$#LJ>4KHK?t^YsNMQ_ZmmF6S8Kd%+ExmlktVc1z$TkH7Vq>zM%yzt#to1 z{k^v@Hpti7sfO9o_0L)WR=u+QXFX@9UkVk$M1u~!H`3!kV0vG7@OuNu%I=L zP>vj-1|4EtV}k?znjp*jHaIw}*(=Fp9^d-T_p!8nF5Y?dl|lgDI@*EfcD{{?WF9M5 zF2bT&tysTuAri45hM8C+fXAPI1EVPtg+p4yLj%KjX2+A75L=aqqN#ZnIyz74(7$NY zM%`~CWSe?U_mzGP*)-mL?Ynf{M@ENm;`lK+YU(`7*~DDFPbvxMtzag3(+-?0h8ZU; zapS$GTEU2=g2!Gsg0b;2xsmqt4Pnll z78y5j^m%VTjp;&Iv|zp=`OZs-=bWB@Mk2+;)whxKKAjJQAqSRxsz*>9OlJSKc@ow= zFwT}mU#UJ^>zDslk}$UO%7QM8sY)e%v^C|;IIKUx1i`r-6y+mMId05aX(*>nI;Q86 zJEEh5N;o6^NJkcry)cC5_f8>)nB&++k*KP{1s80<=8HCAa%uqIyX%MO?d=w)f!P*^ z0C7R;{p2#zD2vSHk`ulke&DOGydG;WTy7*ACw-&jN(T%~+QLLY)5ub3EL*-(8Ko9h zh6n=5a%Qtih?zn9bmwtA^YqKQHf0rMxMa%)42_K7wOxA!lTwSla>YVD|Je8xPM$n1 zICT>ts1lQs9z1+lj(^N<%Sy|2$vBhZ@X;fPMa!^g{wytYLRPsv30HIuvuc|VF@y)6>_)6^8Ma^jPI)GL;~U>V)+KvvW3Y0jbEkCP$fL5n!u7r@bpQ|&r^-R& z#RGY*1;Q8_=)&?s${(s_GG@RN=3poW2ycOEEu7i2XJPZYRk&cqe4IY~1oj>3!HaM8 z;)1m+arSIC#_18k!-4lJ7*fJTXuP$d4($tPVd;ux=o=WqZ+`oPY`(2pvLJ2;C1gHD zy*Ae~k%Pv@CZS@NUG@$ovH5&JJ{C+`JI{8Y^XLIwbNM=a;UB-P@x>xV#^TOpu~Y~D z3opJb)Q5-myg9Rl)X6rQ^3&=n42_Ihua|Qq+G;4j3h7f{zt{4c$-*;oLiYBH(9YSX+2{wu7%4`To!K z4dAhz-T3+Ilb8xtIF64aG!`c_+N4N7gVJ*l402#%Fg>X^K=;>N7LfqsOb)qp5{1!D z1Sb2id{Gnr;)B;eR6*#j6KAI2ryHleA$UObRkX$|%t zJBJrv-HTiyjE3fV4{^f%#>ICi`?g}Z)r z7P%maX4Li5#Kt;hRn zE%VcO;4w-2_

-z$%tWL4zw+tkj0LD#S)6oAQD3rb$hLeDaCMaP;sAR8*AW!gXsz zqM`Z6>9bT90IOFmM@w^^4%|l{dj`QUgHQq6wq1l+EQBYYd{!+028AtKH=>@}_T(g9 zdSy2zrjoi|x88E2-ox%)dt}@}!r2FIztvdvot=1V?|vOlH{SFf5otP3pG0}~D7LN$ zpd>Vg5S0zCIw5Ld!G>&pMlMz_)?QGOz`mx)N(SQ-VG!Ku#-0icb<_7uK50Rct%y*( z3U3}7!^6*>#oj|xh*vk85+g#(W7AOccSP_BhtSc{DZTm7DS!`P!#b-Y>3u#V&V`a@1BIa-a2$$jYePej= z>0Z2kg5!^we3)-L&6~up;OqeoFRHClRm_%;5+k-YjPGMrl`K2Rt9DaN355pi_xZQj z!2svA%IF{W`)2uDLj39@tujMrdjcmQ+Sny_~DG9^i+B&6mDHn^lDW`Do99_Rb|Rn@%X^2@Mr!D2Ktwb+!&{$3nC zum@LMx(;9Xhp%CBDvy{Og2Uj(L%8$IX}k8h0ybQDp`@BLiIKgsBS;CRuc~w-#PfED za^$wtXN!D?g47n|4>0M|G)z@@SrN7f)mK$j7kwyZ_ECB0bNVCiftcP*6mmHs4}5QY zpIk3~bhMXnng4|m(%A0dy7F^Jcq;4n9U+qIOsx>jp|L9JvTa*%(Wdo!pIu#N1X0)3 z*B~AvDV2R~Gif7~&E&#Rhz#oLThQ1v%Zd`m|0y!*9lyW_VM79nn3>*#^?*H{%%qXt zr@;~kLn5Ywy~S#?VCSp>Cg)*v_YUEam(SoAZzhormuvkMXD=8o=MD>NpOT_3u9B^I z?ITUxJ&qu0=9A?$9_JOl4Jd9`okTL0|uX$t zq*E3#hR_+`iH}oZ771#!xaX{~0Amu*YsCZHBR^bYri9@iBf5$d$e0^8%VTj$G)>bWi86AyD4QXg&X6I!UlKXNnn< zOX^=*jFv$8k} zq=;YKsPr)4-+W)zTh1dMN#Jvz|0)m|lP#!{TMlWGj@POZCKs9#w{D|?2{$*hI?Ak! z5Jgy$jO;8X$H$PI9Kqnwux`ZA(14zca?8HHA<1kAUD;H$0J_fiNz32V+?izXH6hX31x^2Ij5ke#qQzEAgepJElk;PIsK^%g_>QVBwam<@z(m>y%=DpUC6(^xx*__2c{>6M0^5&rE z`;k1@r1a&;awY|l1WujL;ejW6v188wQfXGc)~n^3qC+B~Zo=ArZK?|5CUkv3X~kK! zJ5w7aqceuuD1j2Gj7cr~iD|77GaJgvYa>C9L^OiY@d>e?KYYveh(`+;pGcv*m!9nO zTnJ)lcvL;mL^O(%r@L_Ge7~U+G~LnqwlU{~KzZGCP-QZB=R2>_H5eEe6l0%!0?Hrx zI~zA_#7*yguVlHoKml*QvIFZ^FT%I){uw4FIaeg1&&T&l$ehz2$xvs|TCseYt__1t zNj!=auTwB2w?#HdCMHrSuPl{{g$J+*Wh59&9va4EYEmRH9mv5jCZ;Au#HA?`_YV(e zPcGzo@rZ#G5Sc7S#;qkmk{e}z{OlUAR#72-gX!`Oaqvc2{JB>(@Nrr@>9pEjyg&Sm zT;Se>#@3HjO*|?7@{=D!X<1xw@<4wtMo0Q}jX3?4P_?@C-kLa2KwIlPR94j$O^28q z>2o+^9v{OD72u(5Xn{|DZ7QzKZ_pYN5@-jGEBhTZ?Dr-QFoVnOd@vq^^_&Yh-#>!i zztW9+c1<81uCR8ae@S1Fy8Ug*0TTgl$7?a0$pio7(_=tp0>NAoq09(w+_n%~SI*Nb zQmMe}KzSfPBiAAmI3ioTp5A0jZBp5Ehwzum((`Qbi?|iqI_0=`iBJZ$O(S7c`BrY^(@iIda zmMpPEU2WB69(V})K3kX#n zI&c(IsVOX9JQr+}g!ljeAOJ~3K~&3Ur%)d5LNuI5G?casRtXj}VOCh=B{0AcSupfK z-U@Pg^V1GF3Ef$&I7Gq2pA4Fzuy=K|9vu-R#yl!Af+cl${J9Q1y?Yc#I>+QB83;y1 zwv;M25XAN?uEgPeZ((?ha{y)xr=j%KY3praTadB&>xL$fL7h)0(NZyiyZ&|sf}s&- z`eA$&4c(cMFlYmCJ-KRsJX4JyJ#Yfg?mmxPph^b~4{Ro;e$CDdAiRI9OxR9gJBk11 zP4%)o-b+@JbWJm>UaO|qW2YRHNe`ccZLTS@_$w;$#-2Tzk1%Iei<1FUSuutQwLXaU zSVCZE21iLVc{fO!*Gof?G@#1(4m#lS1r1zdRYGRJhHCZp%ITB$h;lL}D7W8sJ65h< zjfWn%7uR0433va`uaL{x5Gr18CNPws5msd~wsOS^?GvebNI)#%%3x&_F$k99r8SD1 zR>=tkRgbVxbwVktP55*}L5KvFP$eCVa^fo2JNGj!;@M*B?mjQu zXNw;k8*dJci~~X+oGmk-ldr?%!K;|~Gr2`_mV#?<`NK?AZ-}S>m_TR0PY&0=>nbc; zwn%$}afU?&ZN&-2MK$tHJK0`Sx2} zv+B^J2v#jx)n`Gxcqlo2p1$jTUsN$Vyt?@4`3=4O!+7-N4&1*dgNXvC12T@f_n`gd z{Gge!XsDb-@0K7083S@Cq{fj;Pa=?=LS=XYfBm7$(NI<*(k9m*KZi*H-3WL$|H24= zb`Uzf&@}u_!~q37`NXq$?bTiK(YWTSE78*0gmf~i1M=6u`<+?|DNYAw-(S_et@Gs6 zI2JEnq@vCaI9Bw)#tj=Bnb|Cb*;W>r5e2mYue{=N-5<$cX>%>5O&VuTcjLYX@7Hs@ z?}p28<<(beARceR;1Eg5NqL|UHRSv7xt5R5RN#$|nsSHyH%r#M^w*MF8DS|#PA4ZO z&*$72&g20G2S?C(wi^TeBY5XkmtfYMS;n1n35eE&?6*CCV0whLPFltYTDChRVY-l? z=E2xHqI;+PZqfRiOPA|FdDToFZk_Cyz7wh4YYOg)G}! zXXz;5!}nk`WzjNU%UAhPa)N_JT+)R#XD=g`*hDJ9$ogGk8)1C)KTly#2eW?L6h6DR z+4Iwc8y{5MPSQf4bcxCe28^+>5nU`g9^UzPU((@7shP>3jD^iZmvR#xdMj72RSSbz zDEr@pd;9<)R=|`zof6m+SFL7&&_Md$MNtZ!tK65;r#o_f!;4A(-n!JeWc(!MW;r#KSb_;J=NR5DxLs;rB=gv-U$+ z2dVYbt*2Wu! z&&Yem#E6^)X7)_bl+Xlu=#+>w7Ll_h4`5mp7j&5C@<}u%Ch@($TZT|!MC3&q^J~Zz z+hV>KY0Gn(4Xora5J4bZKrT>?@Bi`uUU*{)Q-w0*g@9Ql=X=Q>u4J2sFg;royyo2W zgrep9uKpoW0|rT(5yC%Kr8q(_ne?HcjCEgC)K; zodk(!G3m8^WW945&G56ZC1(B)Hr4dvty{IH*qWoP?^H(zI!<*8_T*uygFl}~U2Pqj z8!Pbs>#o2L?s)*&Tu2@u+k7k&2(OUf}TF}ac02h zPdrgg&*MyirdtvAR+vPMPNea~&ZD^ZjU+}h6-pFnh-4v_*TUKaUd4cX+Svd3Gz#en zfG9$09P{dexbvgeATvd)bmg&3A%waX+dPge$oJFDz?ut| zi7(?_TYY;$Z6UY5J*uEKnOihGzl0{ZwuUdlrnv^@)8Qq!e%!bc8`p*+!CgnPTBU|8 zY`Nr01O}eHxIhLw4{Kwy6Dnp;(JY$n05GUiZ%V9PgQIgf!u(93jrr>rpx_h(e)WeA zchb5SECXf2p-NkWazgm}J)L;|V8SvSheRk)^R;~Y!crae=h-K<)E!C^xY1cjvCqkD ztFpWnAN$0o5DHoEM*}s;(4g!|3y2k80;|`qQP#>YbHic_!+uU;(&*3-jvRj*FTC&? zO5<^?TCrS*=Ikj)sJ)6!6n zMGM;0KYV-NA+fyqQCgZC(9&3o6CI~<>pYx|lZ3 zBI5+e^tC>mXE+xb*_2iaf;aTv^AzMTFOs91#V&Z2S-4Ca#J^xqabPro@BjA;INle* zz%YBZVZnY~$})9ass zR7V7{J;{lAZOuT*tfk3hX5t;R!CDRVI?QIznWweOQO)z_&&Am@r*Z7qNgcWj`Ly4|rK9Yp%*P^P9;B*Bldh`eN{a=jZWj$HT;YPCf^#eSUtj!~KLuPtsz0 zLc9c$8Xd%JgTUxS$@ZXeO^66eZB%5dn>{xVFtsBlCQY^+i=(Qh3Rhfq37&c8c^OP` zuaO7E!y-nrr9_!Q;*4AQ3~s*p2DG-3jqZm*8D~c1IjukAWckD1C*Pic=v@`10&_Y= z`+VlcXO*5uWL=SD3$X|r`$NF9<+TqyuSlUWFMa*5pV*Dx?#rTUstlwc>dQ&kt^XcC zKnVg-tTYO#3Gol|ll|DZr~-G~d?|7%N~{B_s5NkFd<+pLZ6YU|N{ELP?=ek*cptb1 zn56Md@vvd>CiRI+B*}SD?U~7=5X|9x?*R7fIe?w7yow~}VPsQ|BuvCEtK^mYk%&L1 zLaHUrq$;1s#TQ@X&?K|Kmi#H zp`a$f^4zMes+2_f#PO48YimS2Q7ThHP6hU}gZ#R;BiF49FEns#+qVQapM`ByYg1H8~UEQu)u>l7$lNVV$%YHzWreGJag`HEe21X zaGAN#0wrTsUE1c?+)!Oq5f)kLNn+{R3`z#9f5S1xfAwz%aHyw3@VMrG>&+YVmC3S_ zvgC#ECqIOIyv0+uNG=?_~=P+js`2KIkQ{znGPL3Dl23{u8Z3jqQ0&Y zukU$F{`3r{^X4zYnl&r6Ngsarx0>{r&rag9it{Rh&@;p69}8ptvgK%Q zn57h#Mo>1f#3ZP!f|cZ=fZ?HGRr*xLa1HX%u|qGQHNp)_uK-^~oH^UA`_7R3}#GZih~py8{4!3d8oFvHH%kp z?AQsx#hqeW=nSM=Uy znR|e?)%1IyES85VAzlVKq9<$Sm(jNjEc;{JQ1K;bc)IeOMh+~H zD_Jbs=~}hx69Yp6Y>ikl;vegO*AWqUZ%Rt=_>SGUf9D`NGj&P~Z8EC$$=OCOjf9X) zPav2cMRfhiGvZx8*lExnpG=xPH`;@1$4vHxE9OG%Y-m{xvS^l z_&veaFyAY`PX$M@3FQ}rEsNqFo;uB1=A>ISCLFk zj#)J#Z}u$4Mu&0gRHu@GvIK)4Np3XBVWpB4Jg3)mJ`J*0C3q9CN`f232uR$_ruvWv zH*HTPFrGAQ9sXdcHSPKFETWtp|Qje-ky}ePw?! zhj_$DQEXetd`a-C@hfc4GyAmTlyg5UK=5yAQUpPmyBVv|FiK*T$Q9yvZEq)j@$fzj zrYbNvUO=oQCgwX2=x`u~`tlsU_xG0}kn1)iOGCLh8Pprq%+U5aA9`abn-_xQpSrdV z5mvJ6(*=Y6RK4-ojaJ~f*GKTZ`wrpUPy%Z%+@P_`y!U;515#x0(B)@l+vHsDIUTG# z^m!4;P!{8viL#S3k+jIm!{F81H=s&`ha!9)L1X5{lI}kHs8TjaGp5Kmd-8jzX5mu=TA{u zQ7R;YL53AN<*5oJ4%%1mc5)JNR)ipjC!xUTJr#tgq%%r}Y^tgmEfG2JaIdVViBvH0 zb5)h!haRrB&u8sGuVAnik+l!FNBMnnGJN8|O18AT+{qA=dhbFZI9~!Z!I>zI(e?XV zN(;fzEMi#cMnR<5nnPCW=_bssdGs2)^O8^vgU6t;cYzn>l1|=y17x5Mba1@9l`tGdxK&b z6F*+1+J<_OIEmV7=8a?dbD!`!bG`6j<=Sj)Xu`hz`%zv|Efmzob5FDXS&$X7tm0$3 zUmOldJ`9Pw>3kNEP*i4S2M?dXgAY7}{(*CHGh8r#ff1dBCJ+sZVauk?CS6xMiG`|N zNjdmtGq_~yR%A0tIs2xjLipx)zKd`nDeGaiXmSO-|Gih@>Z`8SwdM8USaW{vsTA9y zjLAkCBt&G)R#{fAvF&9VSZ21&v3NvAYkb^H{(_+%#$ho6ZbHZ| z5gIQ+_iZen2zb{;f1vwh#P2u#zw_g;rQjs)E?Fp|3hptC(OwnA=kz`#LYoS}MVDTM zz|jYm6$qt~*yl4o%~7X05@l^cTBfp}8?m|5tW|^7$1^)izqypYS+C2PF|o2{#_ct% zq^*eaP)Nz7gB2hpmmmM~D`;Q602|kZalCT~$4`u6(Yy*=e^V)*dvOH!-cJczCA!ac zBb~A5XC-DMZXMyG0Kqj3+DjI-OCm_qmsrAF4f)wvF-=X3W5ud9QY7$;qh0xSDTkEe z!7-+3lJj3b`muNc>2w}9-+Ud|xBJ~APa>H%Sn%q1Y(a#Cr$QdDys`_UV`)Lon>Vl3 z?KykyJodbKKsLr3*RL`8jfS;_aK48FeacZ9H}fi1i9|~T>AT@iK9%GF9F6imm_2MX zY!c8|XDq7H;3R@tHNd(UR-WkJ|vT~7X_YwZH6p1{F% zx~Mjzz*lApta42R!jTFb?J2?M|Mh9~jB!1cWQY(;qOxYy#!>W}7gqR#!wr>P1LbZh7 z8AxraUrtE`ZK(;7bJ!3SG2tP3Xf;k@z`+Yx*k31QYuIq63PkxP; zPXXQeT0}#f6*7PlWz(QwR2e@Tth)*($a zfNq*;&UdgWiQ}UaN(!o~>M$_SgZ}QNp%T&>GnA4>fUtH|_TYKEdt!f=)b7*O5LSr+N z{t%8FKZBp$^Ap74l--+W43mV-8`t0?A9x?)rSyDBV{Br=4E2=wv9)eoY2M#cot^T~ z@fA3)HxGFh37qS~WKt~yS48{d&m&$UC5B8D;@e0}G#KAm04pi@17oCVB*`E2n%&?J zdp+Jb3Nu?29#QZKxkn;=i-PB;$kJYY;|b+1f!%z`6$tG8So&`UzsWJ79n`4u=9qVO7k={NpKH$i zHP>8&SV>ThdoR7ZTeG<5&S}HyHvU&YvD8kquc z$uH`uae3ocl@Mj5Fb*McMo#!0r&br>5w zjzh2g8i|r5qTv+cB_zA#Q5L8AApo{sWzQQ8g6kp_CaKIOkTLn->&kmU!Hmh0BVVyj z^xpEW6JW8n1mU15SxAs6fPuzAWFa%jl9n1KfhCEOoDMCoJb%O71$`#%d)YeI9b#aK zl{2W3RW>JelA~a5pLPIxLabvcyY*}EuO%0GGP?t;M48=(Fr2K%NAG+PgXt!uGgN0> zWox$(LU;GsB9v`IgkqXLNJWAMCOOER2>=5OtA9!W4<9}%geBv~G_PL0+U6oumWw+; zBuQ-QTt++%+6j9{L_QY}M{k~LyFx+FOLc~?hMGC#_vc+iE5eOaS;E z_%r^S?@@mF&c~j~hyOPp!$g9Ep9Ik|L3LzNdk+rLb9|IyiSMQ_dlI4&1)(=tEMBw_ z%}q__;!1R_ki*}7;nPA}$z8Cienz14W=e*-x~fXCb2@pDcdvV)qAbm|bfJLg%E%F~dYg{`uSggI&iaF;OT-Ae%%P2C<}p?}wZY7B05e z=gw-zrVSfpht76ZO?{oI&Qcki>F!dSlSEcYa>*ANQHRPn_t%{SVxu@!&+DIk-(~j7$o5edC`{-`J!*Nb))p|1{eX zQZbqL0?oEaI%ccIlemqPOJ`G>gBe*??I4+rSpq6fkI13MZSpMwejXM8M1+k5Y{i*R zs>OryYtx}!zRe(BfirLN$eT}e{qGn5-;o;m|I<7Mu0!LC_=Hnux`rmhFZ4a~C1OfjNZ6QZ#AFiYziZ zGANkLOrW4XEM-BXWBr(#%qRdeh&!-dpO1l@TbuAB5eYgm@{nV7$(F{klO3q5sYTnY zCPP{BIlQ@dKgPz>n%398piNaJ35%Vl&m)>BLHoS||@IQFylqx{lJKuKe`<1yq z_Qcal42W?2*(d&7F!Z5A2Q=Q78ui+mI(+&sK7rwpQGD~R?}_}zh5faE`FG^mzE)v8%89UMP(_~1>`Gmq_vrC&?%A&o4yM~61)VGi2=!N;wCsUjnuP2 zlWW=_Qq$X7b;hZkmNWAEtR9q5>b{u=eJ~i40hLf6KG5cU78kCV_IaAu7;(>>%%%yj zBF>UMPV4ZZ9MZTA8l>Z8X+`YTR0A{-BZT1H3y&H*M0PL#0H01IUdSA0_E8f`;l+y!V=oxbM*yP~Efu+qYeg z&wlPRSh;is4j(>VV0E|2-mme6BNRXx*JCzAg`6CJ;XO8Ek8b zq!B6Wq!ejvY}EIeJg}Oi8zrT0j2ArA{O2+UOKUR}Wd^>_ueC9a`FoUs2S$5)J8J4` zOn)DsAAcMlz2jC9X!%926vjP!0!s+&H9cD4q=>Eq;azHd8^U`h*kR(5gQAX%vO`1OO2;_SIDBmUY|m0dUOmD&2b<3k_7 zvE#@2I{ecB03ZNKL_t*1*?9(=Hmz5}XC`PRI`9~S*v{g88|)v_o^EbwQVe90C>mwX z?2GyM%Bo8A_4Z-^u|xQikNznhdGH}kza1W?n#5)!cv+{B2!V%x_YB^6<0Y*z7LY^{ zxaa50pN*r(j$;0tIT~ih#KaNF%tO9Y&=+E>44! z!kQ)Ww2F`G)(-80_)Xq?$r8Ok@NjQZewy#SUjTY}5BZFkyL8!)qG&00ih zY%@A4xg%#T&R^m&N=^sluLws zg+NXOi~%7Qjo?gI4@yhR z(Y|P*+6y$Q=^N<7efQswippyI`6oYx7^}L`QT*#a|1%QN3jEopKaRO=tqPz&y88#{ zIMa<(atfdL7{6bMeY<{x%y<{d<0RWLVGPIyl{}S5i1x^o!txMHNvXn3#{^GiO<@`j znH1059IcWPU&QqVdCTcuXW_>(YQp^*S52itAR@AAfom&Z?0Azly7}+UbG$H4;%!8oG}VzVYGs#UR=gfG;Wbr!uTcX=~)Fik*dJA z{(B#G>`5XJDOZr8Ga}_srVr1F2+RB8HzhZDEM`cLdboiws%omSZ{I--kB*sN1%QV7 z2H7VwQT48YWK!p{4l;GbKEKhKpcvOCfJ)j2mzHYa64zyOLp@e6UxZvZj8n%t@!U%< zW5b3Gcw_hLs>Dd*I&$Qg4oto`?idDoau256;<#3c09l}lOQAqgX+{YF-9imIE|ube z2ZvSnh9(#+ZKKWkUVZYzk<^?WGk@lZk~R_3#uM{>_}49x z!~y{&5JV;Typ)=f$jRW%Lxt_59MxF9PwL1BNP-hkP9I+vVjcSR=2_I=w67H?)8FwS?u zEKMvy@Mdsa7mQ_+TNgN2glp5twd76Ew2S6$FTM0ClAO$`wrU!S7q??c`y!+=Q|RvM zlhf-5ZoLJ8Ku#@Bw%oj_5buwdv9evNgr7*#xJ}OGdZ$#h>ue7W9zKBPmPRa`H(%G8 z>y^ryn(Atu4@B9xzF5H<$&m>&{Xp1@2w>Oi`|!-uPsu59WMlwKmMm8bZ1&vQ=dNys8@^HpewVQHG)EW2Fc>IaqsQ`*a%N3)zXN^1jF6at~VT>ZEg=u^QxD_AbTz(9FRNOB(yDPlq)vWhXesf5soVM)65Lz7KP6hWr8 z_nS8p50Qjq24b34zLDo%JCE-?G=yxH!77hy-dT_O`V##3f6k-7Z(KIIJP&xCZLWQl z0&0C@Bi?!4Ran_R8$I3K3VJj>dj5soc=6>oF*Y@Yo8NakR;*}8As4{hdGm|IcL*j#5nWeL#2_ecT<(ptKN>$&* zUK(SkNd~Po5jOWuCI^D{Ia;*?1(m_1BV-)}O z@G0biRdP0+Gk2a6V;*MY7HB$VHm8ZEgqa&o}OM^GbYH3=Py7y zn-Ot|32ZuPL|_I`?MKIC_6MZbWBUvh2Oau6?o1g30Gj)=T2Qui>qqa0Bl_ilP>Hm7#V_>?8?O!)YGG@RmE z;&ZXu<3a6R5Pb`Rk7rB5t3;SE_?ChHY(!6dW#yq_CIjp}^Y{5$d@P@XNd>RB{~dmx zh=}JxSm3n-IW?6=d3C*Rxsp^jBfY(M?HEAjj-Xzl5Ji2=ZF{`-|ZL?;hsgHhS?!&F`&SqnozOjC(xs%W#3YVHP$=a)af5AVO_eb#DnB!8iqGlntw)_~S169u)O7+)=> z`($t?lHm7+S{5@A28RUrWV_hLa0#W~1O7S9D%v;{w3C>p` zXa+eXZ$_Mpqdd=rup1GR1V|%mF|nXdnQ@O9FOx~yM(2b?sD;JgrwNY?j9fxNXaRf!4MYAohL;Lwc?b~@$)fY`oQ4X$KD``Ffw8FSb`o6Su+JoC3W~trBYbj zz6d*>eNIU=?*jw$!Uc=a+jkDtvNyK_kACrlhlw7L?3i}r&$;i)$Yv*Foup%jppoyx zeUXU8rQTrMg@=^q28ht+43c<&@O3>mi0{K67Mc?2&7z#WGCwQ#gP#;h$s_kX69fLu zB!JJ!-{t4@3C7H-i|>sIgGhu^Q>d+KK#oXfQKDzitcTzgKxfJgEM!@+qQQsiC&-Ec3O{hR1^7qU8@6)|4jhCt&WmfdOc2SIrY??(KiLfvQ3Xu!; zr{z-VWYAm(@4NX%q$Y_9G4bQH&R7v~B9Yu|hanyYQ5Bzr$)|$vF-5mhdP!t;9Xy%W zD_V#k7{XzRs8l19YiYz=d*4DC<;fyVnYV?%#vD`s&tLrv7A#z19J~TK5o}FU*38d1A)_yH zW2R_!rh$8gn#DMhJs3pK`Cbt>&Fsyhhv%dCgPN~btl*38vsUzY;-X&z{*d=cfd4%{ zmw#TyVXx5fRg5yUrIez!O(f&U;pj9h)Eq)P!%n0I@cpvlBpLDFQ<6Y(v?y;pd$8ux zII0`Maj29i$}A?B!^kiRH#yYSROx*)&~i=#KmX!|3zR4rT9LtXFYJ^&Z1Y9yQBjtV z8{|tb?$Tknd|5l%+ZU_ye)!=>&6z7&f?MAEUer`q;TzxlCQ{ju{2EvpZr-#3wbhmQ z(wDzNXH|qtN^r|9AHv!Tmf_pq{0|Hb^lE6(20&2JEmm*VzYKY+H@CYh@I=iT2zcA^vWo1+M%M-VG1psJK^VI;Y- zv&5bxQ6|b7IV-}lQ5smW>L8o~E|(WBBK6I2o@seFp5{H3Jm>9+LsCvzC@tp-5cY{C}E# zEnBh-Cpu2)wU@Rp5#yRDf>#l=w6v(I=lfH|?yeKt4qT(=V#ov8;Br>O^c7$miwC@H zj>l|zr};dX?}Pb{5Slib9iLkk)y_l3OB$J6_}LtMEl*NZl}a=wmC}AAbj#2?8VY^cZ8SH8oIYiC=5d)wM2whj&PVo@MjqvI*@;F1DOa%nT= z6UTu31-9qhtOf1^pDZ$QPo|Pe5^dzV@sh?TQ~3R3&tT8q*X8NJLeHayh6K1Ntp$ir zAw#u7K}27kXMEjNt5%7G*msWZj&4e)0f%~TA_$Tse#7N>?@c!XY=4pgm&svlg6K;U z6JwJY9~)B=&6u9c2_1~EnKXAI6ud8FFdE|lviGLB{p5OS?~9UcYj|5 zw~E?2{O#vHud%4?&wb?fTUjfhzM&O=d*^4B;C=Z^cOpbiKuHuI{rD$QS5<~bpLhg2 zUwBC;cYQ-GZhQZAcj)D>ZQ?65Wp`IW6WLd5=RtFJdUps44D|jMWTQdD3QBjjisb4mi zL=Cf}u~xv427PY^n^&^QBJwr`U7k zaxmt70|(GdG1)ZJBr(Cco=B+5WCUH(xP{a6I82BKn}Q^J=<%4=v460M~r$Q11U?3vDrKi6~uxLYFgYgGkYl|%sDiY|6&)48OC+y2a zfWf}5t_BkmNhP)-HM-!>zbW@3635TVi_O48>+)zkUX(L>0wIGnA5Uo+6a1N+0{n~|*8do;9+Yt$!RL=R4%K8LBSjSQ#B8RH(~4htI|2KPVskP=YFB^q;S9D5?J z`@@*TgSo1zQtd1jRz-N+B>_AfiI5Pnz4@ja^-h?Wh>YqgUbY>Wun@iA{o}o&)Yg1q zAXF_z-vgS^No{1GMQcoZm58H_9OuutPxvKtQ$8OSb2)yV6LVjG?F|_pQ7TCv6hE0* zsGpoky@{WjSnP@kUdL_Qwxj!e4@L(1jkHeZT~^>T%!K$nE0)d0XFmOBD68O{5WC%@ zqvM!LGeJlSLEx+(CPYNuydQ~g0r-mDb2ogVIWuAKC;%Vp5dyVsos3cI-hJ`0{C}=* zf1vy1p_mj1t+f^E6N4g`##ur8-%+B%GuHVw@OS<%s^Q|IdXw-nTMv9eLaR&)TvbRkL2xq(W(5(>N{B89W#CYnAWE1xXe>im3IP%y#ZAz- zUJ@U<@kv5_8&n_bpzga%e#@98po-VC-BzZ!$Kt}!&FU4Xf2t-@#Ck^(Aa=kZ7o(QM@j@A zv$AMvsJD&4peY3iuNzHfXxD4kqcmRTT>n@do9}-#M(ue-y-aRKn;BrveGI~6#B(!I zW`xg;69*DD7kQ8$>KZRKX-a z)Erk;vJJs3*$^rIn?Y9yLCBHp@cpW zOhRoewjmQF)ADvOStRk#1&spdKv;{*Fy!g!kv5#%d=~8RFcTjk30$^CcRUN_ddupE znRkO}q0NMRBAvkPf4d8lXtoiz?3d;;YL77i5VwHbo=8}8JA6NqRY`9TCql9cw4mwX zS!>@-&#AXc&#a*tfcd*-qC&D7JrsZy%U3E``-!EEjSVQTsKKcdM;)n@QZ17>(jHu@ z0`_U$7+f7n&fb;@Cb<$k+@sFvl);&Mi))KK2Ge|J#K&NO*Ca=}+mX@ko=exlO|JCG z1rq`uR{r2;fMdn$?UTJn0@pJka`uC{ZvB_4Syzd92-WipxEJect58}-*(R^4-8=JY z@je+gi^j_o?GD?QC*Bsvq&qJTgVXKjwr+^RhEY{rgrl~$IzBrz=+J-c<39M(d4f={L!s{q`p2APOdBdE?q~N zWbktd;UID(l4c&U7}xsrJOe&nZ4lQ7XE8_BfDIJm*%1-KYXFV$Z%F)PB5efS0`?z1 ziN_y%REAhx$|98U~pKJ_Oe`Njd-oF zq5Tg0`@jDk=FVQ=5}N>~CdV;4KB+0Se4iR%#!0>t<0wziU6${|p2rFwbA7Zgo3p_q z&>!GNK%SlqYHN4;kXL)r=Oi!NO<(1ICE!4JHa3P{&zfSab~-rnAGU=TQOEt z%($~zNy4FnZx(csg22f`2hrQH4_zJmkSG~JB*;X8W-2y6+bTqEO0wSR4CO68sqrM- zm=m+!w;%X;5gpx3Z7+`_DNR1+uF_VB4g@eflEG6u$MDE&DU7C!NJR+>dw$HEt81As z%vNArcj1LtvTVN1vZp2N=!j&1r%s&3<4^3642l=}T=#he==!EMeD<@S*Jm-!wJj_L zSZ;#Ro$FA*?~9rzJ-#K zQrvROdypuNE92k!$}5#(A}AnT6hQ^W{;GWMtAZj3qJT81(s7rCEo@_ZPw!^W4u>&ULPHNKEt4a6x_q-Mw8XDk#L*c*>Dh&D(*>gSqihwC~-F zecM-}W#=jshSLZ~awv|n%O{c1NQs37Ody5^5UrB26iJW*O(xwhMQ-E)=XlGBNtvCs zCS!VkL;*x(60*SWjUbfAwLF*<2l6Jzq^ zS|$z;`I0+eHnEeC^Au>0 zP%suX3ss1J(AV2%+5qnS7q($TvW+T;YN)^EePlGJ#Y@o*}hDWDP>op@85G+Or20WoBbNRd~sF zz)UQH^|LfI3!#6oAJeL*p`^4%!QOXi69t9~s+JsV#y|0E!nx6Avnmud7Mp69J~_JJ z*{qvBeWLLwE)3&)-@OgvNh(&-=OSU=10+eSa5d7Hofx<3`yW~f9yXQ=soR!dp|o{- zn^4%Uo?bLGG&o(0NlRfCYw_U$tXsDc+js7iXUKxNl-wq=YlwjcYk>f2YHBe^?G0BP zd+v^Dc`!ES$&K^M%fE=>c*0i1orZ!sRgD&m$j&p#|Cwl&m-;nDQ?dA60m=l$6Xzue;YcLyj0obWlYH{ei?w%3?f8RM_6n zF~=T@f@n-WD!n}&O7!C?Dw*2&S`Du&{0xx*F1z$xoO{l>&i0umV&fPZ8bD7E5oW%w z`TOYm<+s6~YtN|0G0vFHkF6AowVrQ^KE z;1qOb>d3!vB>$w{f{DvunNWN!r5;kvIt9R`y2tgm|6t;i57Co(>qPt}a zB7r`!(#=hfKHOR4OQx4>Oq1$0raNyeJLjPI4I~jV;i#yfWwD@nn;)5J5aq)N!8;OB zCXM#)QGB#HfIq$1hD=@zacUHdr*PqaU4ReXeGgsTeS(2Vo+-#DGuxoh6Hhz=J-yxN z>g>X*)vK_5`#yEkgnY^VZfuy1OD?@cog_O<7ARbwWOU091<hY58Pj~ ze-i#)dF3^|*MpZFgsSRtk;yi0T#uEjHtKMnbm9qUo-rNUwr<5+Z@sT|$9Z#S;j~ju z&;z!0>n3em5K^wKo`x&0yi9V>zy0kaQjH|4a{KMKqO7zCfBeH^*s^(tx}M{XJ073= z{8GI6*2{SMnU`frTh}lf_uqS$R3x`;*@Pee_-9C`v-t8?Z^T(=pMb&XmaV4%03ZNK zL_t)(K|J-;U-9Ack8$2b7vsz`jz>5@f@ncLp85OpddM!i@FEE$(O_iP&YhAxU9$K9 zR8^I0b{Z=#QDGG>h#*G8A|e`D6R?R74XUW}vvl6R%-9e%Z&-$|U28DdzYoPxZgCj8 zRKW8=;Rv0NoW>JeDh!h-D`blD%iL-(6EKk;Nn{l2V%EgkgisN|vty2w49IdlQ-{x) zGgTsazRaAA23nr%NP;29TMYE_5z)>z=cep7O#WJu;clzJ5{AK|6O3{#QrL!x0=NF( zwk49uga}qL5Yt+38u4@iF1Tqe5U$c0pG*c^QOn38mO2Hd8IqIEf}s~&RWn@&zvgE< z%og}W{7a?X{FB_!tj^H91q(2N2i!CiJLq%1M#z_=wS^d$6>c|N_ z^S>GV*!9zoz_yKSZA;@Ub?JuE@Xyk3VBsPH+PGeus*SegkSCuK-_c4xf`QsG-x4q52&|k(59o60V!*62mmGAU@c}$XAkSv-Rh8B9+%Ra|J5*Y!WE@p1k}tma!ilrY0JT6$zrW@E z_J&maK7J<8JK%*CDcy~oy;g>#`?*~tIcaOs_`azc>fhJYTtwcE@rNc?Kc9T!@7UM6 z+X_1O9Qwk*^bU+W#B1rdV=5{tF@M2Aw72(QXs{FUI9F3s=iehg1bmUe-&s)c z*|1{SI0^sx@5c3-{Cj^+eDb$VFDpNM;ih{uWlKUT#Z%1AeB-0-iYaQ1Q)Qp|8bT5_ zZdjF55Rls=)ODIgv#mO1#>cQ@!^h}q*@(WjEr^7M5y@u-oYlIdNNXhM=bht z9HyQ^Mmw@K)$GWEGPpVaf-|w=!{umeYnL_e8*jXWs+w9Qx2DFKIP%D&FukEk@R(ii zJng#*)=G{@H-G_45Y8_UIq}uk-jqt-QAZt(Su>gtE{Ni>Km8G#H|@ZZB?sg4mwZmU zzmGorf3afKCKScWaMxXTqq(6@rX*C)TfcsT#tt{%@+~YrXg=P5_g(zKx7hpF{nh9Cdv2f9v7=SEI=OhOu zlOZI^F%Q3t+6+wG5iGsoJ&XkAiZp9xQ?|m%qK@biKMO|=OeR8hWPU{C$vj5=iHPG8-1htYfwgSWU1BwjKpI0GUU6)ZeCGGlSz z#g)98q({P79I;5?Xv0ILTs5l{ufx_d`8(g6myWiTLJFG2wWYzri|8evNAB#iXgcEP z<81xaW<|E{>i7qK@N5eQUbM&pzS5+(cV?$39T-bm-oeqI9U2cYIg>lVM(Na(kH9fU z9U=p)XtYRLEK<|d9NP-NiK0`V!JCtL;iGXO6REK*I=egZ{=e3tdRnbMBaTZSrf)dEWY>;93k-YYvr2yI?lhtz=O$Ri`SA#oAHQwh4|2!p2WGV&A^K=5gajG<>Fw$Y^MwT!-~+Lug5TeLV(;Mld|oBZDVi zgO1J?<3CMtMHH=?9I{A0e(?P}QC(f=}&JlzBf!t@#7${!03av0L$FmQ&=WI!GfyFW48U9eB5bLiE|LuABJEE-CeDC>MwsoS$Q?CzWPda z+U)M$dFv%Cdw;c*`L4hIYr4N5y#G%;^7|)HSX_wfZn#0{NpE)tzJA>eNM%!Ko-r4{ z_{A?Uk{HBiFFfB4T3$YW`RiXR3GhB&e);7H@IeiQ@ZgVsisGUIeEl2OVSH=^&2=%H zaMThEc5Oj0Hy|UKaG2bL9Eu8QkDNhqA!m_U&BJ((f=(Koafx3`$Wo&P5*~F%Ji*ac zDrF!gK_*MWwqavq5$P|GAj@J@qX+&u>3zl26mJ_tBS`j*5yH%F9VI4PeE}7NjzHB9?h#5=o^D0!9YQ z(=#X-QGznYRu|EAY)osuTwfz(ErM7<1Wiq|P*KHotDFe0L&Jj_T@=SkP*PGRjRr|5 zBZu;eGAw)VeI;%N3$G5Rq+C)w0TuJLI6h+l@_YfZ<4I)H`k^CSvcQt7X(lb*2cB~q zD_9Z3K*sKwBNXn}GkEj+JE7A%!WR1X+WhMz;7mVUM+mPy4vzdGjl2d*Qu z&W;tJy&jX)qJ;}}F0=`i&C1sO?6Zy)@W4?Fi-Xazl#(0oftn7-!uLEF{-<$i2yxS< zm~Mzk9B{xQ{Piy{WBumsIO51dWwZR^3oqFF3$<5`jnUw!38 z6=Y2CB#M&Q%CQHf!pRBXs7PE1&eXLvW2=MwAokvjfXkSD!MRJtF<~R5bxxnCM3@Y# zJLmWFxov4}#X$cM)~wxtJ-c_Ra4IV)#mP%AM?tO!4YgG$fAEhL>~O#+w?xWsvkz0F`wXqi8^XTXHh`QFxT z%i(v=?!_p|9IMuJ!ug<$jK&cw=8k#{qsbvq43hJ8gC)c2Zs-t3LZDTy)(KQq*T~ml z!^YKkUDV9(xd`2GL>LH5}!O1^sC)p}qVsGoT9DG}0g*&sf%^mG&z zh4JBv)!4pmw+f-9OV34lSuyfMVeHts6R*DUwzT4}z1Fx0qoWD@>t8F;(b0`7ueuu3 zr&XaSR*0^y9&~o~pssGZB&eAf_`q%3wjGr<(@a*sZYNZ$dnHM2d~8&mC|U4i z>qZMB=Kb+XJg^1P0{ryB`!O^)f@6+97Ka{wxKii?_uq%zJ6kY+;e34a z=9?sEJ=D7wFZ|^fs3;AK>`0O$i-2gDa5fQyfVc}p9QbgPuV5?IhB`@~LvDtI=Pbc- zQ^H7SZoa2N!d4i0zU;xbooh*lQ`u4fPHqOpgD7o1)zpXGFrDt4ov#`w!-=vPV_X}l ziPzCAo2|um7Oh(8CFClz6TI-@HlVl|p-2r5KX@*}(G<>H`V@wT%O;8ds%3grNs{p- z>cwuCpFz6sHox??%DlHk;6yN@-bEmQ`STZvFxS`DgZ_bjJrlLnHF8MgHPd#Evq>ge zuzKZ6+tT3*FQ^6?omeH~2#7ot{>}g|oF#sg zj3nMX*``a2qsR&n(_3+T3P*IKt^{L?#xCheWk%0o;8|snNmJ(JDm6Ehii)C`IctW9 z%mYKCxb|zeV(EoT(cjanb#L04>lEgI{r2BqjSNMzNNA=%&4!KZFukrp=qNu2V%*!E-eic+?NAh@t=-3_NpM^qX zP27!RsB|(deHkXz-kxp@4h^8Qs~g+5@73p{>^>#LhedcKxt8OG4AR+@6dYBMy0b3? zg)6_~DIB(VKYZods}PPjpAi6EeFH-3JSWDl>iQ9fDO{SAvd-3oiszKERlxquBN!|S zt+=vch0i_FmZ^kXkGhE4;E)0T`W|(#;@6^#+APN!WW`y8ld)<*S?vERpiv?CPRf3=XVGFkRgax-} zGgj@ArOyLS*qsk754d$=MtrQUt`SFoq8~hj9G`enNr>N*OG_emdR-Gfd&y^Y4TcAM z@yH{8R6^ix?Yw!j6a;qc`V{|qf3=8XGiNkn;i9=19`45n|5~NhLUz|@opy?nTq>Ey zb1%K3J!K~2E5CTDKHKAuJ)xO*I9!Oc&s&Pa4>>>&`qR(8prWX-^AYS`%qak9l!eZ1LA_Twzc4AKmV(av4fkVkC?TY%wyIn~hC1^MaLE(}NwN|zNsW!5tgHgj zLX*Fh2$hxRW|bWYVT4_igKw!fA*IN01OtQpVnVAc;fyv&GSM(PI(A^^x_6L_cOeoc zJD(1NSrmndLUG(codp)Erj|&tC6hTG*Omz3Ppw_@{4q!n9v4@Eq0Cf6#dQ%$Y6}0w z6}~Dgg4AB%9ya&)gBq`C?>j@CeUs4TFV$pD&qI=`+{kfu=r%&I*m=Jto;Lr5NO;qw@@xTPY?w?3nGBsv4#z{-W{Fzmi)5P5O z8zGaBszLjHmOG)sIEfLt0B_xxX}*x~YupqoIIKJ5nWCo4%$d!ot*J$Pcu>#LjHWtV zu=I43WG6#i+ay%)v(-JV<7ymbn*oxq9;fiym>fNei=&t^V}@-+$Ydym3op6`v8oa@ zH_nvOCs6^$vwf{?7#kfybyW>!%xKmY!eEV&Lnk>*o3f1WpluF zaf-e1{P@^u^L0asY&?+0MHehZkvo6vc8Qpj#c2DU!JnUa7NL?E=xg1Cw$`1fZ>&R0 zTZ{Y+7~h9eg*fQUo3QQOUrWukG*%?FQ5F^_9D5v2IrSvd!ZX0mpJd`P5OaWit{QKZn_)vo)>0+!GH1T-&{ zDT5#0|7}!P*6BKMA~YNyL05Y_3JZx|WfkMRn3Ro+O!QBSE6xwZl0H>%N$R$-zU5FO zYBI4~!QfG=fX@E^2mW`PIfit2$512Idc6Z*ND0@N*shqmW@*H3KO*tGA8UdprN8~C z$T$g~uFLtAA-f4ot_GV(l2ybCN?oQ@K=7M+n03=MqcdpHk^$Ex<5>OPYryb2c{rcyK$Gh>BFMZXLWT+57{`t?))Kr7<)Cj(Go;7ddr49!72aO?$7?wC%+pa)7?M^6tzX$G)lRQNcUzlaNfizSQS|o> zA`)d*&ml~LP9TE~tKY=FEgt~c1ftCUn^Qf^mlzKd2Vb+Mdb%WwO(VfZAbxgi`*to+J0hbG;2x@V z^{?W=#BQW3M(t~@NF+aC;ez=%;D7^EOfzuLnbm}I&pAo#_sK5N$f>pl$+br7TrI}Z z6Cj1Y{vPbNXrca{pI;4+AniO{_QmT_R#mO!M?M0tBgL|M$wle!$EO=NDyFaiWehAW zE0KoE=1rS)22AnMv|4x#N$RE}=+N+hVyu#koPbU6P6eyhUDLSgipv%IG%9f%02X79 z{q=dIWBXyKeJ9d`TUG3Hjg{IRLQnz$EL?IFcI<3J=dSfC0!pZ++rPoe%`K zc{IhJ!8ZW5sbqybV=jwnzggln5qu)|2!K!eQ-Akg<2f8tivy2DaJ_VbcjLB*OjXfF znjW3-MS`xeRB8h_o}7d=Yd+4YGA0DcL#g0o6*~(HR^!HaHU%pNK&yIa<2eb5@=!7% z*zP#t;v6y~16cL$Ul9p(Ae`&d{5eSNeg$%l8~Al5qZ}=uxlm9Yj$E|(5gZX^jMAJ^ zfOE6=;UIqa+imC@FB6-aqBH!(c^SKQen=7lPd@QD3=j93_k*jfjG3J>u^tJJP09g#Qx5W*<71H1QD5wW-+1Yruzwx)3aN=%B{p zzyxXt8yBE7W^Q&&QmnwKgjZHlZj#5mVF;i&R;I*3!H>qKS%?n|V3bzc6S?^>u~pNccX7$43}K`Us$qakplfdUq8Ne+ub^V$DVi`PCNZfR8_?A z^{-!tS4*Isuy+FDw0$F1K|f=%V}@YA3C zNW`eMYnS8x?>&HUr~pOPwfN;ve<%mSFMs(e-TVA-6puXeu#y;)`DK@U!S(%E~u8hE2QExch%L;OeUuW83!K>c(rP z)!+|*_%l9P^NDu2d442iEdnQrx)#uxgt%^4Ra2?X%> zIEEaSK0l#-$~-eZaQ(8Jgt*aBN%LJ<$AuwXuAkqyP+*-(CR`VyWTDKy3zC~<6N(&2W#jdPL4-o1O#)zOLG{sD}PC2Td4 z*IYU(%xQV(?%Ast!PsXVwT&`)%@@p_jdPZsih~X~$npkl1iCu$-TQus8*jP>!GLiw zRJ2SnRPv*M$)s(HiGGacbvn%5);Mb{y!gA$_Y_g2sf8=A<0N0h#xH(*#FH2&2##(n z;R_Qr$&MW9IX}LU&~5PW4Ph2<=D z|JiX7f_3J}fgB=H5?X9sO|FR~b)-gB5RAv$vFDT5k)PX*P~MP&nMw3=m*1e`NHBwN zK^76NSw;%QX&^C!geDTHjJ@fFa|-apEA4n=O%fR@?(zQ|Q=IHo67&-Besp%Vh~?`a zG=2`7z2sr}hb#5xin3D7pFdj<7s)VGt1Bul!$lWggrXv@8(F9G*kgajF-IMP#Y^^6 zbcrVh5g%f*V4|Y)B-h)DZ+LC(bbYRLmUG(z zDGKsC3#qwY7}e~M``&$n1M;y~mo!L7lh9#I%8b-6AX>sAtE8md-1>?N&FrKgg3X(@ z$vKiYeDnI#jY6SoHpwpQ^rPOvMh5{01UjW-7(;m^ddwlZ|^qBum8~ zA?*y`2mMMc*$7soP?O3#-ZdI)WigbB;DVc%WBRlResJ$0c*NhVcxQA7Y3^ciqtG3)LaNTe_-E)k0k zV~+DW5N;Mnz{xR_49TQIy$}`@qsdX@tZ;;o9McS#Nr*Fc@?toepoRx^O!zxjK{mTZ@EPDJh~vuIni?fS15!_FaH{X(I}z?6hhmran=91__HSc zJQl}?%U0+kan!&9fS=poTCW^;ZkAcQhS@|{nD@enlj;rgOu{M#rxU&OuQ zl0uwv(rFs+S}~W0hko-r>}&5paS;_Aqu9QEyW5V*DMye4!Fxw;40$Tve}jCAWZD{^ zxwB_$!-D98HfF|>sH&{Qop;{uiWZSd^qzh4^=N`mkW)DT$~!VViZhA@;E zGW&DqFlyx09D4h@oeaF)cRmY--cTTE97h~>Ag;geYmQuOV~o4*z7MzFa)YynJx zj?ILFqNVmpPJ(SOOpXAY1-agXjmLd~;Bys=g{cLA7w_@~^;ASb#m9f>efWaJ|LzL{ zo}>RP67)6BgF|QE>6)lW_+a@vh9qb;C8DZVl9+DZ&llsHnvkY-vbG}GC`dY%rDKQk z1_`p7QsIc1&JdbSp}e#R>y|x*+`tMHgpw2MR({8m%8Nyj0LshQJ=zXxFcUx^pA{3G z@v@r58O#^L-u5DV?{{mF%CA7UupA5LEJS_d44iV>@#yR8L~F|qw6%7iy`vq047WC{ zyIj9^JqF@dIa3q9ar!j0x3y#Y?%g{4(P%!7Kjuh{FnW9YuwunJlbp@Z#|<~$AV83OI(p6WYs4!2J`V&t)Ej#4Tf9`Xb*;p?($G6{p z2k(CHF^)XuIDGZmtJIm*PMeNDKlUW1)z8H2+0!v^?gBK{O;dv6LtGFmM1N-wI=g$& z*jT6gH9DR}Q6z-+j!qO6$3(;=sgmM0)9PxlcTXEiV!5@Mt*^zPIoiqQ$ z*r-MZ4Gr}YQQ||)wLIDymz5L=Ze%c^Fcb^7_|O1`hvFzHt&lDTNvE92a^_B6g=DTr z6N2dT!{!i3M*oKOYxTbqPdZKA5Q~q|5tDpnM;OSCVa4)ykQ&&6@!?LCl%!Es6hfF| zD^}b2G$f;s1Yt%BMw#vc3r_9T2iVCl;CquP`)?*`6{SKLj1(z<36dL~i>btm zsh=lOltED}P;G`xsFL>R`2{59jUqEXqRw9(2p_h*JY00+n-~quLad+<>#2E0_?TnTytdXx)S;ziFX|f_Gzt-cQN9dR_lt@j!Ool<3N{l&G03^7t*t{r z0gE5rLk1!nUkMp?;xtxCO`?r{)Zq8e%`MN?KgE%92CR!p#~=IDosPUErkIKJ}b zOHf-~?ut^A!j&X$D^~Y7c*ziL^v;kdw%c$2Ksw+Cg>Q+_sm9z z?}xFHIs%0GO#sVe$a!C9%$kF-kvMkk-m5rKTufAnrd%c3O5=GdEC}I_JMR)w%%;vp zE;Rp&s8IFZDU`M67L6C{V-Y5|#`rLX1`_D%Y8Q!zv$q>0=0pQjp+uPeD@W%5& zG{GYRe0|=>h5OCIowwaY2^4dW&1KNj+pBFEA?;cLHBv9nl=)Rmy3_Kyiflb0>u^=gh#scMy$4@b){e;NyS2h9$ECSUi`rOkeJrG; zvZ@~UKk$7a5;xp%i-ev+p(vhs_V1X{Sb<4M??Kttc!z5lrx$0ZK@ok|&e|+L0s%0q|zW45j_;A&yxaR6hgcOK-5(#0b ze-N?Km`GFnTF#%TW~ljYDvg%5c0KTv_hoQll}>RbzCP#Dd?@&L?msp#|P0OtXi>5yZUCzWF}1B@|{7JoDwE=7J((DMq=b^mzI=DZrr-dpoF-{G2rhk zYB^@0m=U``+jb~cVJ!qB5>e1+!e(J0Npxh@QL^J^QsUoPRjtE}04 zTXAKfCMDxaV4_Msty>r{3wWHlOX`DHx!gDT*lTSMd`G~My#^0WN z9;-L3M1Nm5ZoTzZ{QT#?)OEH(Cy3@5&Dckk%!+cfwzisQ$7sS#+8mrdfBqb7-nSMW`@Uem2SdJcl;6S(fhonu2tY}7{{ z3Q3**Op#jP^nKhGhGeg$ENiR?akfOPj$p~5MZ7{L1-n24mwv^b8f@p{F}>#Hp9z%rj0lNKJm^0mKsnI)I%m z?dTooGN?Y8R3V}Y40%ZBh?W=$j`LTdDqaKJ3w5wU<{XwC99ICD`111$ZACAS+yjmo zf{2fd$_JhSik%KS+jZ;KV&}dtoOkXy>LQtVI@)&Q@yGs(y80%OcIxV;VPs?g-~8t7 zg6Z}@-~jyK{vTrP`n5QC@qzfvIp^u-Rn*qwPmex|?D!bI_=PWED4s+%kj3}z|1lOW zoQ=|wC_a1fB^d1MK_IUfPd)!M%8K&vKM(ycUViy?E-&H86VAnLw|q(6^{qGGgRPy+iq zN`xEBT>2cE`I8()p)bEqX+~u}aT)>DB*e8&>55V+hFG`Zq@T5#$t@PM#O41854UwE zaNQ4EkjX0$YOr9=0zCKpOR|>bSt^OyW&yP?jz0P*6(A$=QS9EmTQhfd7ECB4r|oNP zHMo*om%?HZO`DsVQCU@M-HY2mU>Cz~pCV1%^r1$9cm@axNhppMI=>4G`r$BFAk9{r zMVfbX zCHVe5cc8Dgdy>GW@dZ?j4Gawm!f&W=km4xOJKiV7OA}OaJR8Eurc^tg%;C|$yeOe4 z3aL>dp4WrLf{iWAr-qwHL=>84%|JRiCc&iDt3ScqxpVdGF}|sz&kt)1r8T~+d4n)s zaWpVAOrm#AWK2HS?A}SLJnNiOwNA`r^^+g}0{hxpF>7Wsw(r;_B~d=#y?y=o&gbTeEb9Z>;Goe6H_boX#Ym~nqZO$)z< z|MSf)(F7G`4pH(2Ac=`2w}0!7uVem#`BDw#59X%CNWzL+5&4bB?`-L<==2HP|9K*z zI|xAI4p&$(_foruukG`v|GtUy=<=#BY7JSjk^EGxgb5_f>wioURPqE`o)eA}{YHl` zGMEz?1fvDCWe?$?gAYYu*|HCEzVasg#{jLs9H!D5A7Tp}ex~amE(QRtJ59{*j2OhP z|D!_*&ZW4(6jE zk1%4s`E}>GB@sk~n!mXqhT~%x8VO=7TZXMIr8xG2+kl`!lp?x_e3M3Egp$H(?A);h zPe1)Eh6fXn;Ab@=>?V7uD-HS|f1|9t`Kca_B z0h-p;CB^CvDNsa4c9M!Gfq;xiI9ugY&qL2DmRtZ97woV{ z(J~YI)1Uqq>p$6!R62=!?z>kcGD7ZO`|9;_LYp~vK5o0^M$PuGzWmF`q!ZdP|DQiT zj$C?74susqaTVHITX~7`tsnddhb~@(Km7jp=3S30&OYa2jZL^2@zTpL;t!AfL5J<| z<4?m?U$_``)2eXsg%@Esk-+SE`{C|8Z&P-g7wF^NBU;{bv;KWD?|lj_lPrmePO(>G1%beD-xyVNB7aE+;+*J9PeHEM;6`f?T(5y$UXp zIBE6V+uN^u$fAPXG(U^9RfJgPYkbCgpu#Slwx*#ZhL1m5jZ;rQNn2cng~d4VpoJ)j zRiL+j1b_S6IOX3na|XFhWgGTJJ#9AlaymVfw6Q-qI2 z9E%`wD!6eoJUoVYd_ZTA@rK3ANPHNnv2moNePReEUyp?-CDu7|^@dVD2av}@Uc%R| zyGF%;lrpn9T~i8ON#IEWPOgKW!kw5zsr>1(0#nVX8`m?*b6hj={7sSj)@!Fxc0t`4OWqeaMT8 zqJrMIV_sW4g!7KCLP=p#!a=h1p{BV=J2}LnSrivUY#oVv@Od;jNn#wuNM_10UUocY z?0>xc0C?zmb$MV^VRQWlz<0lM2YR{)h2~ISSBu8!)o5$)z{agRjo}pt;^@N<5!}nU z^z!8&Syi7G#^Hw?h){k2n>O#%?k%?vPC4x)G}YIktfT}RH*LhS50*=Ok53yK*^a(gNpjH9r zw&WJ{_Vp=g&;~d$l0@C~8WAFUdwSJjkN_8n=A)=Eg3+;Yl$Mx8E7zrXHuvt{i|I`b z*u85H8tUuSkrFy4iLIo#6xl!sWo0pRceW!rNpCuP@I6iU@~EAr~p} z@Mn^fKy-l}7GIx8h)92VcWltgCo6{49=>wPiS@M}r9luf;yLd_>bkNd>vcTyxtBP7@S z2(Vm zqmk>nHEXpxOb1AQj}TmuVQFVhO@=hKY}<~VyY`^Dv0jDOvBw;V-kyFWGfA9w>KXX< z-S?xqx(Ivr>_dKj5VL13!06bBh=Sxi-F5rT_}||?j%<)#KM~!xnN5w@wqutO*~e2x zM$e_if#9Z1d0D9nN%CN(O{>KKM_0u$G&R)YGv{515DQGL-J9d6jfYI*fVqU{U&2sX zl3z`XiiKl}!c_5L3=SvMyioCUG(Cm@n^cY*GTc;4p|7`7InY)p?fH>DN;Zr7`f0fR zmh1F>R6GQLzTQE7u5szB*j9x9{2`LG$(XQWA1NA!sRN{XxlWF?gt2_i8TL_9ke z`<-+h#>S0$;VUh_-_78`3-H>jFJaZnHJCGJE~eE~qPMpl+qZ4U%C(!M*S&Dw9IZPt zuo0g6bkjCU8sQ{^lKMY^cUF&peIyKlniC$*HHFjSDY48_`HU zwr<&hKRog{Mn=c+m9Ksk#~yo_ilC>SdIr08?!iHe55+|noud`Ax@pzmT=KaWUdJh? zo{YJ(n-GZ*f&@A`J0#6Z`BJjOi(>|FF~Nyon9QIcN~NxGkqMdX?bZ8^!N9^oS!=tZ|i<#XxCE znLJ3IeBvp2lSu2nAfhhQ%$P|2BzGW!C5Ig9^zse;v_f zRt|$JJ2&%OG5rJvY{m%Qdm9H))4=#hUWkc7o*ggw2886TL$<&tQY$-a2u6{{Y;I8Y$eirB(T`(>*+PaGJ1NrvBX3bLtX!H zK5o0~0nC^^&p2Z#A9KmWu?-X!SSGn0)V*qJZ$nFKo4V(M!Z5z{rE4)T7)NPw33_@v zuw&Z}Z9wr15H(_vKxCn;tOP^DBUry-y%PReXPt@4atdY*p`*J4|L1~BaO<7734P*c z3^!1>5 z#tdm*5Lwv0XAkDinT5G?=HRr`>B#6DC1v0Qj3g4$3$bkt>bIms7AMNaXN0jjF`7Uo zna04-0ODg~7$GlVbQGiGV>FXNl1+&-W$Nu|6H>r?#$wA>WUXl8HU0j5x1+JX-fXmU zEbihM9i!-&S!DYJJ(bMwbES#|Z{X!d@jlt}xnnNydDiD+6&P$#+_UUa1wRtgsKB{( ziihOR|9_4kbS|Cqqu+Fxx(dk=3yUH?H$*dodG;*v=O48AUk+rZT3BlFdk*XHjzwXCK#qf>2zK6A5y9tjNL)u$!R$v9XN@M)FWT^HNmII1pKR zCWKA4R@J-P^Hrs7%y||<>2wlZot-ko*|&EG1_%4JzNiOHpWk3Ic25i{^ibfMQ96~8 z8yl}vd3lK`b-9J>-MjWGVbYb4b2jo9o_+Qi`8v>Gwp;GB;9FFTYp(q&mMq>M&p-DZ-g)a?b=wWi z^YP8wZxX>~>((u}`>y-MduV7{fP3z}L)sKS`u+0}uc1 z32`V+JNtB;|Cv)XGI-|cm$7^2F3ef55a%yF1@U-NgwwY6R=oD+2beQwHcmMDFwNv> zSxsj;@4uH!PFd-G^2sNtsjS4b`g$}p%+%Rq!N-*FlTlX^jpVR<(=xR0 zT8ZrFZj?pIULHp@Vx5z=AZSn~6Do=`nHnh9L8g`Q(k-r zOVUa*0nSX#7MUuHot>jftPel86Hoq=8FmVX001BWNkl-coXC+tL*0ygVxw7;2BSQ~c^4VY#<>z7GC91_jk7F;Ns5Kr?tT3&A8!r-R zATiLcjpr=zy>LXvB835nMI8$d7AO2&P;ZD^EeYuvcnt(~H2Gn%{~7T8e3*%YiGkmv z(Tm%LAe_o^ilBYxrpfPNgF^V4F^Fgxw;<@5LVkiIYaN+u>bOCKMrkHEU~!7rlC8OV z;+btC@CgB!w?u ze=CkT_Bivo;E2NQ(~Ev9)2NKLnOJo28DK%Udd+I%Ze_CamSCKXsTyS*K;vI<;% z)g>s%i(==#eIkx`_4Of|pRcZ-Nu57;G?|cyU2}5-K3cI##pU#Ab-FIQ_w2>IIdd?r zt_~Mn^j~gOn+Tp;J(k*KV4_JKb1|Oxoy8{OIc4z4^NEiPVPwn-?a{=DMy_0k^m-MN zsqX1?R_ul#+IEoX{_y@@bitXp;QVt>eZCOz4YeD{ErtfL{dsNqY9UBu{_UN?UD51^zU_HGFg-q7YcT&EY4ub+!z+kD?uR%YWZfq z!HS$D>Cq(TPhk{QEW+XET!)cF3c-BS#pVFCKuf>c9s?OkL=1R7sA%sr$Vz)e2ZVm* zU7a21@9#o?Z?E7{J2*yAVL)QRp^iWbd<>3Ub+Imj*TAG`DV7luw8mUP2$cbo*TA#L zIlf?$;K578hfrExq3YXUt)LYx0|S^nXC6w5i$rjvFU5)vKESTFHtfG}Kb&#;nVP4O zHT>|y4{Md^vdgZJ!yBFEKHahg4}AaUlIH#LbvK})sTMODrsL{MuMqDbT3Ut&9(+K| z|HmHr6F&a%BSHV?EWH@#e&#gn*t`|L`OW_z6v!gKs2o4}+5LiRNs_wki`PnCyRfJd z5B~UjLQ)=l@F!^9*MeLygln(8PKZlsX%YVRx2N&)ORvhr>U$49fbsZp^WW(1 z?!ko@UxKEFI*cbrrT3tqo*dJ;+PY)Al=RpE@zPLisA)zcjy~#G6=?L~V4=$E8jF?c zUh(Yk@7O(g$2Bqaqft~>mI0XrT6TVfo$KC4QJ@d8B7Qv+D)km<7fy75GhlWRBtSa* zY0mnQK`6`sZo*D}`$m7Ju7VyyV-Oqp&4LWoIrG9X6{Vx&HI`FT}d~U+p79dR7 zRNo*D0zC$(jsLsf|4!1m+$QPorJ`aJ@*^Q6;-eZR@NBD~&jO1NIdnqmSO|xMubGVb z{7HyOi7X#Gwr)XpPq*0R?5ufai3D&nfXRe&Xa;<8FKlbc+d2m)wj9)HIC2$Rl(;4jGR`!1%ESyQsQum zfJ9M6f_AdsXPo3}We~gX{ORuGQ z#!Trm?AWnI5Q$9ugx&eXUsIwY3#Rj==(`pI(A*-F-7kipddU!w?iwl^!>F zb~eR!eB7*rIv73)cE%w%CAB+9Qt zx0sx^Z~RAgYNp+7 z36tH3R-#1EU;$wBOnxZBk;XBwxfqcNcJmB|zyIAs8aIq4#}%aHtIp8^*GAmKsh>x- zrPhDUWQK(U9THjHoN?yym_K_O`n&fic_kA@M4|dz{hR|Zd(q*vFw%U80g)XLZyEwKqwLM50lgbkfNRejEuA`C%|P_JmWgc=16(0Qhg0U3wXcOUiM|$*1DnbI%b0_@(sSEpEL77sUBj`oshxuZINs3=X zP6Dr)JsVay$S5cnRM6*rA#}~J<2_-*=V#^lr^_W*6xqe{z3@!<%_@E^$0W9{XUcjs zq?2^B<5uu%`Llft;d|S@bBA~kyng&3Ok(v7jap~bTA_R^d|))LlP3fin&3M+evwyY z2&(BJE~%_llbD?q%%q`fYA7!UBtTuEn9tT$vw{F>r50|gd_8arToO$z+N{-;Hv(DB% z+q`8L_UvJi-!IMx;~nF=nU#@5Z0p2)COJ;-?CiwQ(16P!Rs_>|m9CP^HQJtO>%i<; zjkxlvYut6UB<#h^h;Rsv9JBjDZV!tA76II5pk@up(L{7vJSN9XuY^bg3DCABXGyWE zt4;UPJ45QeIaSU4a1i%=`)16VIZM}>4KL3CuLH-5*6>c6b@BB?o_EN!oghP8I5y-p z@CyNcv&KeUem!^MXgYq88--1b#-^UnNj`*+1HL%n?|#$Je;z(F8u?RWCO@L>5g`u_ z6_;TZpiy>U&FYVHEC$5%bR-s;_vD8}mJ`$>vm9GZ6pK^LZ{r(CD%m|SOd1LVyKgEOgW5w$3_8Ol?jGq}}+p*X(byp->Q??+5i z1!1$iHNqGnTW(OW;4o`p2Ga;PB0{DGz|YLzy_+AQUBZ5R*x9}F=X1~5)`U!Ne=Ieo zt%$bPR#lGP>w-U*W0y*4g`6R$2o-uv-%2*~!!AA|keSLTVsz+%uG zENLLcXJt&>0YBsJ=}jTOuoSocWGz~Tss)p>v*vp%E-IDeH-jDTA&Fbml^|i1ft&Z) zbA8C{ud1y>V^fog70y+;#?Ld!>+BT+^^CH!%+JTF6)TV!8I|HzDnT*X`7HUZ2VN5vXDq6= zZrdhCKQ|;O;k@L)MR;%7$Ed2T7Lifimmp={$9$<;8Uf9c+EjEwDws|@iPwtvPMumX zPb#b5z2^=ThRw~;BL%)AwCSyVKfi}RgU>5FX>G<(5_$?xL0>C_paA~y+BNH_ zE*Wcxcv3Wpzn*{LAK0^dhnhjY530D5Pr%V3H^eC7MzgHBvl`_>YtFTf4LCtZe^xT!GtG&j<;JP*zo; z_a;eZS6y1Y=6vHlVMNv778?i9&I)}r6*WLKGyeF%Su+=F!nV5XT#DysG3+U60pZ zdkxJ^GqmBvZk?zD&m@aV#>!p0w<{^nnLXER##Ka^&y8`pOhUY}qCyC1CY=^X~!WU7%8i+NFp)xm@FU_L7KbrtyTcWy_txL7}r|4u?@a?FY|GkoIe zJxAU~B=yguooPe5c+L1+`!&v~g~GoVrjwcrp2RqnALI)UzE{77$?q4^GDQ~6-jG8N&YnPzPR1&Yh{yN@#<1HDFm;$P;7qTFb6fBjw0zp())?(J|IXLU= zGc?QQYqCmbMbDjDel9Uhr-(C=z_f1NCzv;Hfr12Yyx>v?llp2)n-@vi5mTQ&H6gC# zp*kKmku66#`k-CN|X`H?B0^RsG>pK2IDl)4&9U>$+EXX z+KgNR=;=AvY16_5%N# zfrZ^W31vKk9#xRPgX0qjNej|giJc&Sj@dx-=gLYt!UV!+++=YX5*S!n^s#8IC@Xg> zo;LyOpX_vP);BZ)ivd~^UfQPpR;kN z4uzzjJ^9f#D15QN&*jf8V}_AnJx9WxVSR2X0jBZod+yf=aozgOdfgLFIt_zE)VL^? zoH55Jyiy{ICe1^{wjxwcDxvbT%S&Ty%n`Ez0Z?y}k|NBRIa_wj)SO^L5i2T^Uc=GH9D#ZBs7y(Ykc}&dk`WD1L7UF1 zxRhVW__zuYJyTTH9UarCi)fi&6*WFXR*9afie5O6qX5Q##u1kgow%BfOv3p=-1qHo zVtQk}xkct+^7Qe9Gwd1%!48Xywz_Lbj*Wo~g`>+bkqSd|{{N5!KNj%fO2&!#kCDO@ zeu768{MSt#h5OA0zNXLwr?^;FUZwcYyzOnQMYp2>p|oqVIR1na5m@=ra_J-(quHup zZ@Z~LRmu5bLM(q?bY2t>v-2ccMeJP7^!?_>_`?T&sPz~_7)(-=Z-`<;+)JNc--wI; zYpM2689>D&aD{~F&a37z_*KLlgVlIA_&x|BQFz7RLQ|dM1LL7qgY~TJ;X&lsz(Y!! zCx_TYromw(3J_=*t&|} z5>a)JfDR`g9?6Kh%G7R{?=mO%vPE=};SvjlC<+S;P+46iDc-8;O3l5ctFI1;*FI}& zOd?TwVp~*7dqgc*5b*lbfX0k}%&>);@Vt-QPbN`>>~fNvczyf&1~eVjT?Ye4-T9a!!d_eU`7qk3dc`Yl!~b6W_Y#| zX*R@c!pL0+=aDo>z74yFu=f1ni5V6k`&zIf(m_I;|xhi;y3op%DOSAA@j>oh=e#76)6QIc(GuRby& z=$4Q*&o0j^gRLx_v!>9;qE)MX;(b^GBm!dGB{R)p(dUJf_%(dC^nAMH&Fe;KZaRA^ zkV{>XCPG;iwH!0}xWdoR4XD1vj(J00)8`yoDFwGOq@rlFsE@{y=eD<(_cT2q;{0?wq7O)QDO79X?# zx7~gd+V<{qW_1(5fRT~iFB>vg;+K3hRS#X4@1F@FgW|pNt8HZQ(klQi31Ki0NrgAoytRdXNNt%p%4}=TBvTnyR#eI7~r+y=GI+z z-G*4qI9Wd5@SgMhaYbLbhsvEP-ls7YpL}-zA6@SOW$9I&Y42NgE9cx*)wx@(P72+U zkOY#D2o^udMg$v75VFBG7-O3-|BMF&*w}-^*fTcC0psyMPJ_q(xI3Ko`2+GDI4fdUDO0|gTj zSC<_m2py)?u~>|;v2zX%X@{gGHAx$r6u269y#0;wk{7>Fwv=N}IfNhppkTB) z^AU1cf%hbmYeGR3BqWkywbURT4XY^TU^xd38U0!3$~ednrzOuMsqQ@gix97k|EsML zKdZgHCy|}$igH<yH4(C=R&X1?%e22%los3DqPelzoCMg)O^o$+S%}CVI2myk z4hZ#Zshes3I?v9~rE)ATmt>GtTT5(w)=aEvWRjPbVt8m+1D!0%x+Lk|;mt$pjVCkg z>FrTFr|OtYpHx;yZ#d*Lh)`A`Ba<)DL!Sml5rD9t+*%7CWKPC{($Cp5r^NqYqnof`whMd&n;w zi&Bi^$DfMv3!~B8+N$HfSxBo;6TZuz5$eh_K6U@xmK==WlCfm>bl-|$DQ}ZT%}vQ0?IoY9;JP6(HY*o zc|Yh3)T%sm^UW_cp{mLSFmjL~M|F5;z*UXb`3Fb7pE@y!9_+xlZ#j%a03`EzN{+OlS1B!O;>%z8N}NA;K@)7xj*iF3`B9x)-p}ja z@Kc&NNw7XJFi_=)pbJ4l#re^6Q`*@jWVPmXXL=*7f1MfNZYNy*{dAtpscd3Sk274I zms-%+l0=h^9eXw|J9t2W{@4Hg8y)`ulox&y=cAug$j4(;^8>XuDkyp%dwGGVZs&<;~I2)mydQc6webB_}J8=Z$_~ zKOv&Czl0iqjFu2eT96;W-|xF^o&W$K07*naRInE83D$`h4EiI4IJJ!O-sWbfVs2qx zh+b}GaiVMg)Z5b#bT>B`Kb5=+`tU#uFj=F_hz8c0o7gvf6Dv`A46YLDP4k zXHbKXMr+hIG{?t3`d_pemll?_c|^KN}04U08?JA8vk0<*)!ub zF~KzvFR@mMviXq`9y|t&D3E_kquM50n>(Vrt1H3H6?H`LO5kj8xcDKXUsiq8@HifY zC>Do_gO}m2DT-W%@tK$&*8!jlfuUXyEVpmp5f?68RMv)sGbIcVmYM04?pyX9E6QM_0CmIAysFK{5B-T)o8DojaT2YDK6jJ62*eElI(cJflw); ztSOIZE+9P9PzTabiP}1x1xjtisO4BKbi_M9`h!@j8;q{bJ_S>fSFLd!9}yaNH@LLI zGhh9@>t);sc=^#NUb-w2H-~dcCTZtg8xKG9K#Y%%=^b)T_jY=x zJUY7EhL`KKgl5{Wb0|Hct6vZz(B0c5?uj~#v{n^ma@a3AATse+S@jw+=ZFV6;HNW! zc1(zJI2b#o`4}1=i1)wum*V7^Gx6!q{;BHk{HXL(Qzzxp+g|&MxakGgYA=2Fd-utH z@Lok^RwctYeT zZ?3MzQ%9eYh}PZ%`y}N)a(X1rUlmut=1e#6#d5=inow75FgP(-C>g9IU+uuB5x+ zo(dOZ6Xy0N33{YR4OrgB-DrVom{P)Xc_Irf@p6E!{^$=s8z)X5mspV|=|w~<2tw4x zZ~f+nqp=>?ks&m7%C3B)DErOJDY8K|#f$n87RpDSIJ1G%W7ECZ)=bwk`zrZr>i8~l( zGTGMVHbt2AO%0v~SIhJ|PvWEg*4x`H!;X=`Xn_Xcpddz3uRL?+tXR!Dh$~DdbkI39 zGpV*kM2R?*V-F?LXF3XaQ@N$Uq{`$;i2jMEf)f(L`5@NIHc$cyM3*<6U>f&|qKuw@-W`VZvss zGg_B_vZf7`$r|g$1%Obhtd@Pdx*RthYL7jGi?Men;zSx3#T%*~6N zqBEN6_~LhzN(zp+7o6Zj58N+#YYYLu4_d^T$}MBOL)(EhttERExpaam_Ke9^bjk2c zp+0)gcCjsBJ=hxrXOzfj&o$CekPZaKxvs{USvHI~bKWO`gwBJ;3m2935nR%?$GZhd zV~rRjWyZbN72&pl{sEC*fyTLik`n?6{+kRABHN~cenG$}lG5cM2dF84BsS}44EBNb z>gZ^V+irVxTz&ObGVB+|F2s?0e-Mv7b~IWVJ<^){Ab_aQ2_w?7Q5ViiXLEDZH`m4R z;AZJkSfq;QCYUtA(`C>+6UQx-Pd#;1&(3$jqdIkNG{!GZ#Qpa_6mty3gR7NvT5f*P zi=(BfRhrqeFW-o?AS4_5#0;4my)zm671~ih#POXA^z@fzo3A3X=N!U$C2Zv z%+wgoZLKjdV1$4%^>kD~j23}>em?eHx>qp%&9~ebeZ8C9^1R{xv{%!d3H%9bO2A5c zqbB^Opo8`{osu_tYKsJOcQz*p5#6^n=CUQD^g%Yqz@-;Pa z$L+6)*Sz{C^nN)f1Qv{Or-RQrBTk~F;gZn4e6DhqPZIn8hYnOx0440XT=k=^k=3L` zqEZep@{er4x)L*i9ljIuU^=3st<#f96VjmXq0Cg{j>hh8I65XFU%LN_DBO47wx=A7A*w7h`IQnz26zE4jA5F8=ec zeL!-c%oydcP=i%pc9Ul}Sj~})&F~MA7myJSE(ayKWh8Iv%y8#`VUWlGc`1kzDSGG7 zAee!A+!8h0vLupaKq~H|Cz#;}qGU^BlUo;2dn=Wrz+8j5saRaZVI#V+B$%Fs=l3x{ z)U@bRcCR^PPG66DALDWf0+^^qw+L;Z1S}efoU|l>B4u>yDG{{D$=5fzf0hGGTd8XO zNwY#CSF}FW)hm-DT4gX4rHO$}1JT{psbG&0uoAGDo3XJ@gHaq5kS$t}#M9KQjHk9t zI2BRRAy*sZ>YBA1W|!3F#d~G*!{TOr#fool6{8vB%u_+8M8W<*VZd58fY_9oQeoj~`bS2y!qs zcEM1YYVDrvh$E8%VtN;}dZB$!u)t?wE+a!tFtU61&iLa`{f{_uN$FBynE+ltXzPj+iAg#TxRfvKg<4H11^&8oTM zH|pz9Mnr^VElQP|_}^b&jr)%^sus)d5uj(DkPy6NEry1-#U*<#6$-=NP`x}6;?#$o z+CRAgo`H3`|NbAUgvL8>Y-~{=4Z^m(#GjdH$~AJUG3Wqoa|%5ZG9ZW-Y4l>fIw3Ob z%f5lrG06a(g$2vIQm(9nkV#Np6rX}MBXD#e;rGWsId542NL@?7_hjjH<|9xuhDV?_ z>0+&Z=h>$nyXLBe%}pq|}te6A+4(sk z5>~G?KO@(moq6KySF8LakU{R7pnqs+ST>eGi*w5wlEo7wsAQYS!JJLXA58A$yL|>d zfQxqyI>~#!?6S*MrhMYbqj7=6YkVSBR+g20Q*s&}-W-k1EphJ5Sp^1MqpP6O(behM6zoau!IVYoYy_=`9!v$&hA%>-%=Q|;!Z0ZajyQ7c zj}e57BEW59f3dF-b~6FKpyydyoYOTmYFU#O)eEmqvD*5z`1J4nR`m4uCmw<|8kRsS zK>TPG*1#+yA1>XPP;9X^J9O?_og}IJx6#R~ERj2e(mV&AUnTBTTJ(N)GU{ukDYWu$ zKC21_NY-20qNlfC=a8wvIY=<7T&DzY+tw{cI|!iH)?)jPOQZ1QWA|57|C8h5PQAg1 z+N8ywq)vG-WxImJlU6(6xmChTE&$gACM1?VB01k#A^1+9gjY^@Yj*t22SvlLKRPHhKSXMnu5ZCHj%uLQ{ zlS0J9LG#=hV&a)N{1_jM1OE=J?9LJH1ri{eE1?gRY;b=CYWj`Q(9#%9^-VE2FsSkb z>W&x|&0jCpYIcR?cTJw8b&}y=U2Pq%3n$Ve_sfrJ(##`BSrdkzV1}VnLWUCT%1n9K z>o?zWOPm=wt4+?IA!-C{3CkM8*wO}4;_p+iBNAhMHDe{iZEa~c9J$6ot0@_zzx>NT ziQ~^4*TFZ7JxxDNfiZ^!Vk>6=!I@b&DGPH(Cm??E9%40S7Z#&#bvoYm%B`_`xDxG6 zSQ?2FT)OAd z7#QB7Kp3N#A@>ZA($PW5hP7d@Kk(pvx_22s0%{yyO+`q9_*pRNQ^wV-ZUhVS$dro<3f4g>x;omG1@ewW zAWoVmY$(^BZP0S*g!c)_mbSe-^Fb|LI&TZgYzY!_+a>o3c{G<**&FPg_I9RAn#?C- z9EE7X@o8G6iPBka+MFw&sf=W>*EH}awe~4@OV39lF+DRAlan)X>8_#p@mIVgcI>)D zXYJy|c&x5f;vc^7zv95<*D8?!ImxA2P(SwPxzW*h_Sgw!cMm^)R0LF!#`6q_`uezh z|G^j<8j>@{wy@U(iPI*TA^BATK}vG8db>o7jo_L*pSxC!$gz$jIG)`>3DL}aP`

    bqx*i(1Z6YL1=GkiJCgTzgfa!aA~mbYFA|c z)YU~_Ur(GlGotw@8ueU=*s^7t$cX&|9r3(tu8XFo_C#hjM@2I;;4Q6q&>JX)%1;R~ zpe!!cMLFv=X}>tTFY9;YTT+>UG6V->u|!#$M8?P%C1%=UGbe!|R&bNB&q`uzBYy4u z?}|f*u1s?M*q*sqB;kb-G6A+7I9VVC>zuKc4r3>y%7qQbY|h^GCja zcSQ(7B1*aTVSRS8RjElaf>egfva>*DY(Q#y7#{xq&;R`Yi*J7O-{mMWoT72E%M0`QWm@f5oTE#4C;f* zTIl1Y9HMRz2SFGy0xwVnUIKN_{+?bTEvax~Be}F7)B$*y%m@fihI(esQmkZtsZ3B) zUsTx!$HM!_1X2_u^&TW2TdPd2uC6H-7YHWEHbRgq*&-RHodi&u@0$RCEOWK68Y_&b zo`+CWit({AJumayK^m%pG`vePxfTpJbLyLvJ+TCoFI3kqBzTPh?dbsVT+W(nWb|1u zp5@rd<60ZYP}g2}tvVnGnbl4=Jr$!D#w0UMX4=!k^vnerLDrA=4m;QIxC2QX5=Myo zo1UJGJMX+R)<8ZqI@J=!7%-t#l-4Am#84;K-kY1-Vs2(a?-&$??3ZiJFE2{N02s5a zX)WIUhD&4bj)rJ&H32r4oY(`D7T||;wAV*n4dpei%k^vG{6s_i!QV~9)N-%6JhU~g ztlx)u0&ai3_IcMwBXGY+vFm#j!-4T!b%G42bkW?T zGsiol%toM5sI99SaNZk;fikT$8w2J#zt8UwC;+1gerFgRoQ$NbX{AXBYrZynxvA04 z%Gb9p1o|kHOV}quOO_cyO#ov?Kla3k2u|Cb7=pEz*1IqG9QVnyW&5GECUah}+TWJp z9@W-&Y}>APjYR$8QaOHj-&dl&V^Bm^bqHuah|4HFqKgW-s5CRFhK{*a5&39tr<)l{a zlyYh6#Hq7!{JCdTwqQ*_fx5eUV`yl5%*{>4V~;)@gM&lr66x#diSHiye#}lzDJb8) zd%M=~(MKLn0nKHhwnC>9Bl;Y8HMfy?&9j_td2ZgF_hl~ADTjyj0G z>`OQY5^_Rekun4GcM?ayL4wNa0@yXrj$uzKVTgjzPIX!-paGrC zB^9@6n@c6tnMfN*g&8f7|4Z*y|1SL?b6R*7 zC&M07os-O*D1#VyNZESgjNNxph#s=v%bxp4MO zbaeN{%UIp6I3lSFKK0Zy z@rh6T_gG$L7}Eyvj#4SM4{nNgy!&0z-PaqH6%SxhkNheGE|)h5AJ~{ccrI@krUiBu z6F;f2(MBiDh7?s{tcendc6pHyAM*&&-fn7={$54;($#j#qT~YHMI@TKG+;6FqPB0@A%j5>lu20_x$e#m4;0Ee z6iKjYZhpp6s0;H(3=$^<*j~??qTsrQIt67oWN(~x7z?AHA?W-(8=p%M@ce=q@`+8( zbBUx`6)W+;Ae<3K9Pt`+8)&<-!`7%#l|UGc=-L*C43Zhy9M3>@=Qbph8{r0Mo(2Q8 z7y`7os8QQV_)|d=!3&u%EtmWE?-wzOd!yI>ip#H12JzVAPsa4jtTG`EYJQJ~7k&6M zO2t7%-WsFy>%Z}ls9~}wH=LX-P9+Cbnx>f6lJ`UR4Otq3Js4f~FF^>C`#PB5H!%eTbdZ3Rs$<=`@1Q!qM#b|CDs5G`_wHPP3(7ITZmSX%3h|N6%#qFih8 zp4i@yZPUOt){Qkpx%1HBtKfa9$bnkU-ZCo4pY!fE z-Y@5eeX4fFbS4=fM~OGm)41=X}SbQ_YK3Bo_Ok*h{LBw#^RAj9Mdq3fz%pMqcpHp{rGNo0uGnW8ywHczT=Lz<;~hdoH5 z0dI-*-?L|r&gR*(=Vg~68`BkY=*r8Zv#Z;gj*^P?5z20f1Zjp`>yZFFJKxK_s;sNP z!sJGwajD|~;{7UR3I1Mfi`WZ<^*|H6w^#!ZQP2e;5QuR}ArZp6_aMxr58wI0IJkem zcvpzY5qwInneSa$l@DdTSxY#3+LK8J8hc@$Uw*_i_oP^#^iI~h6Wl_ZI0?yvuYV`M zw>~X3BMw3hSJ$GuyHC6|N=kQs>qs0wekNY``d7!M!5(RjJoD6(+Ak>KUVYW`to>3Z zz%E8ZTTc}3`OeoXklQl62$V_-M{dnvK{)zkH&zq0yfFtwEfqDj@mnANop|>6@mMP_ zskQ;E&EitC?r8Oax#@*3h+A*H)#Z!SLa8iBI@yk1al$g%X*4FpMH$C507wd163#(r zhuP<80$<8XSJ6TcI?<3=!!AFtaWNFR9WguVtS$z+p@=h$nay<~K9`}9mbP}aN=j8y zY*jP3El^_km49cg*c@c!YZV6D^vYp!Uy@<2tA8*q$h+(3XopYNy;;&rC2Ma4im}A)_J-dJ z)ZTM1IKi4U2Phe}w#2E^BMLn7p~$uMETW<^+HxuS2L`lPXXhs4Pe1p$D6FyGp1XjP zG(pMbDoJQ#4Ac`3n!@Bp0!1>(MU{OZld(5jTUugxXh`*O_7G$~-bGhaIc|GVPaNFc z5M3QLF+Ek1F=zTDHe+qAUK3G4wCZZsVt#oo9(<-8U%HpQjW&n_L)9CTQNeMr_H>lo zbn`8G9t8-AT$}5f8Kq+%@f;Yxd%pW^IZj}BwNR!}&H8LDWF_-aa@MXat=1d`-jM=X zgu9X^3JwLnkODAqi(E3v1WML|`{LYZG(en+q8Ffm8% zEo~;;PEE?L%`bY)b+#ew2T#RZA2LSCh5+g5XP%4AgM+bi*HGO0(pxmlOCms^om2C% zJUm-dt;lK6*M(PSI=9HQ>RYH$&<&c zK@wUX2M=5sJsmybE1fzs5*Nls^vl%Q9hmFZR z1paPKzJ!i5+byA~r6nPjd0)V1n4Fq0TBmLVcL=C&Kwa$R_{DeK9yi~3ljMx?Pt^5k zk%wnQaN;wON(0qtVkYaC)+on$EHgGO+vNg;#troYuJ7bIwObdgx1sJHmHr*nXgX#3 z9;12qLbz$0jGD7|R5EupV5L%yhaWs5!e&=jPaMAb`SI*i$Kuh4kH(8$dSmqV_QcTE ztx@>Fk-IBw0N48%zwGE(Sr({35_Qp&q{(DJL+I7BQs4Xbcj8Yz_m@$r0Qumw>BGe7 zu4t+pKTC5K_}IREXWVhe?SeWLD5y)pj7rA#5?P_I4P-C1$z>Qh6aokd z8M#y-G$|QU-Umb|>UBDNDJ!t5gx6BsiG=t#o3R7T&#Cs>WYCqNmP$e%o;!6qb;D4i zS?_XC3$1t%uB}sQIDh_Z{Ka4VS(KK%SNLwhc`3l;+?butK161k_e!vpL|W87XEir| z2+HU#q053j0dWt9%6B3p)7(%SLmg9b-GS!VwXH*KqpdB4XpjnMNnIGUmMtztjEq&{ zpYL0Wu~}LP(Y|1Sl+`&wVysu@xAZd z?b1RTlTOe`;KsAGx3%cqG2xGAg}4cC#e~*M6dODRwW-0n9K8En69=va#^o%sH+gQp z!<|nna=zTh%&gl9GkniF5+LM#l!I0F+QuL@BP#qZdq6>7at!^weF_!^Huc9ivmm5@ zVU{{;>oTBqC2-_!_q6y|wJfDpXxDu?k6aJ(GM!EC;+dE20a#PL;B9QeK>twOeDh6K zDx?&e5;`RZiPHsYfUSdrv3Y1yb&4my!~64)Eh7scG1^}m5goBwS<_@jWb3DtVe_u) zWADBL(bCi|d2+;*KuqC98AVu<5MM@T2p$Pc7}pJIvw72?CR!eS>S>k!kaR{r0hPtg zTL+`3cfd|i64d1FwtFH3R;)pj&!jYN#L=RRkVZg@1n(r1V9_o9Ci?QbE@@MiTGBNj zv3rj>paoq7#Zfu3?Br7ufm1mRbG`S{-SM7Z{F&(LY}dO%eC*=*bSx~*%NFQ;CEtmS zksr%;$5O=A38MLf8R1;-RWP!i%Mo1H3DkOt0uGQnQ;eGB0KR|Ipw?T%){+JZwu7~J zzLCwX*7QViu!i zuxQwpgRa9Q0U*zD01~2o@Z%r(M4THtrxp;wjnZ5wN(h7RQ5j&-P!N#}LM*qx{cRHP z;AP>g=`n>c!bTuSU=akBsL!7`$tqA)T*kXj|A`DPS*Y7}%={;_@xY{dcTuG1Do2vJ zRwQ>TqLHUH<{$oE0TP)-b+oH4s!f+m7&6L>(Hac@%uHOIn%3G-gA_!bvI5;V62L7jI@kn1pZ?UR zH1PuhYD!H~W}GI<5#XdDVlot^6*)KUUuv~UqL}+YzBr4Vc4$YbgCR@F4ja%1A~=#_YQhFW1Kz8Jns6zSTkyU zC0=;*i?j}8T$#2Ij;2GTF;1L35j}kav9h!j z`}S^*8*jWJcJJD)vE*cN%qTz?p|r9PXHH$z`~c1~!7o9Y=K#3WbL_e2WV{)L%yV*1 z_U+vohYwvA-~awY@%B639PJ%_@%g{_tJpj|B;*9;L_~|&7nz@+Sukm8D9B1iS#!{% z&nNLJ&MoVx@?!-u^TPskoEFS(s2m|7 zDYqfw+=W7ec&7hWX@&qu313MigH=k{ltLAZt_eX}T`N@y{gj4f-g9CZm3ZGT|7=|Q zyld>AY72U|{4XQoN?N61mJk8El4`qYP7LLzT#&B@64`fTl)>c*CtJ#e^JLP57O5O9 zt)rqkWYliXyGS!RjCfJPpNrWUCLYg5cTZ1Te&v<1G`}QJ;LONq?AW?RzHDH4TNEDn z!S|$-pam15!;zBfh8|$yp-;|cTrYI3^q>FvtMR3O`ll$ZK$0``p9iy0Z|C4k0WC%U z*$IOhy!Lgs#qjX3;869F;wZ|}sub}`aB02UBsEltBr4r!&iL~+`Cj$O%LuxfDnp=A z&tCS7^lXgC^8MsYIy*Q0xyWm-KdU7^@c^_BM50W_rD#Pv*Ajidf}@m$Cx|FQHNdOC!xj^h8xbhiR8)}_SNQtTB352x{Vw9n;mJMB}_9GF8mpr6Od#nIQqcsj(aY)XL zHB&ooLZ}>EtVUBa-2^%?GI-zp?%fKATxwVmSq*X$MvQh$l>yY{gVQQWxJ*iy@N??w zg#?KVsje702WEqbjWRyzY>E3eXwkfxUU`2LZHe4qj8&pg_~*Kz|Q5jp!l^7ODML=M^brCv9BSL4r#W zMtYOnc;c^VN-!N|44xt&iq!Q$kih&0B`a>BoL`vL8F#tCNRC_tt(N6-yyd5UB5u9) zW_4eAP*SKfg|n8GZq*K*MD6s;nc$ynmdXuPLSynFg6`LO7#7A`S9lcyp41!j8oB+u zEb+p={!K}#a^1hHYo%0*XPK~UA;>I?V2>6_dSgxxBU!mBDlXS;| z>+0MA_km$vcW8cNIm_nXfvndZ6`L%zKc)5A*oK({0!bsMdcPfHYT-)lb((UhsgmwE zkP)se=sv5FViG};W1QoJIpF%3gA+Zpx;rMWHk*#F{dOONM(p= z!{^e1Njs2q&|t832F5${Gz44o{YlwRFrf6~4U8zDN&5CKHOw0tudCNV)Lew5r*3|V z$!p3=^Y5kW=6fNF5p2pRU)mCzn&PRapNgsJ8GW}(O6mu9-3_84+1L|LJP}{}x35M$ z5PB2yIot=$wIF?RFvrF(TBiU(lq8fwO;}2N#8xqA;`o{ z*2TZ@#uRJ^J$F;=EsCTw)jzg^wgS_uVpiJFPBEur@ z+)9hDxiQpAv%rx^cu7kiXPe7?Dluv9g82|a9TRUNpRKhD?Rst{LvMwEMwufh2eVM> z{k}y+%PpA+QSq8vqrp>4o3&@147uAzfoeis){U>vgzEZyo*+0OVtMay&uEaaw^=XV z6=wv8PY?&$@8qeG*tE(0{rv;&@uHhw5LfI!sJ&TNtcj^CL+xIC!#MiPyLFsY3^X<`tRi@zYQf@k-rlZDp8wQ^h-JC~AV^P+O8 zT5b2`LbSBk#Rq@o=i>^3_hg?5vc{8mR7OWtrgILHq>$Gq6)Q{6D z#HVD>Np$XJ(ETJ13eOA*wrOxkU6l=!4vEWl7D%g! z=ihK+6dwGc2Ru=8qV2_!vW2K1ah%{!)v&erb|4s$&;PH#iF=P6iPaS}@Y#U0mpSX= zaN-Ps3T;@t0J(2{lKo0Sm7$wT+tgW2#-Fbv6nG4WaqQ*S>B? zl8_~cNjV!;peP|2mvcD2>@}Q;%SxGu)+mk***6SfkcsRpIR`kz%m+}L>g=4JhuSOk zS=MK6KD7~xL$I#j0hX66i=N76{C$?3=Dza)p?vRozxw^mTa-o|5C=gZo7u)VSXhy$6M?sbz8VDw zxkXyq6&t!}$kZpNW@2`B!7YcSQuGaU#0@XFKKAY25d(dF+E0jumDaFROR9;VA01U| zDs9mSnW32=rl5 z^JD)lwr|;@0ZKamAec!%f|@@q(A>AR5!PG22@)tL5YV4Ids@hViHz)fzf z&9u4dimU9@Q<7(nnAIAyf}xU-WK-pw6WYUi5~OSz?2CcEeg&uX4c2%tx@gofD;Ek) zAP7nPn>^_f1Pml5OEvRPY^u8#91zRts~mwBFprG2QJ2G-%W5PH>VjBxry34(eEfpX zfI6PM-_4i8;afcJw%cAAFMH_?(cd>zEz9Evk+s)+iDa`Cq^3?PCsXzSa`?GROsbrT zGnEh&C3ET8bRSf2B=N?KJ#b!%F)%nNQnXR6buI&IIdSo#1g-QuS@WSeT^0Vu>9f9g%q-Q7{m6j^W}91IEz!NxU8@E^sTsB2j~L?wYFyu!0& zM!23!8^m>Io(qwW>^M#O%Zun%Fbsk|pR#rJtBTW*>S+ZaDje@R(J&j<^|D1p8Bz{Z zRC`PVY9u|~*dS)SV7kD5n z;ZNlu)GM1cv}qnemr^-q=ce^{z{R|aj0Q2{);yd#qhlCRYQ-I$BI)st5RSp~X`_!x4pVWqD*0SfRQ1-cW??H8Tuo!%oQ8L#Y z`7;e!Qs8W^0kc%jojsk1pNJ-TPY6bbpU~)%2C~eofjBK2eCJGz7tRuS@s2Zz*3M|Qrnn$>DoVtjJK zWrL>1Xzgf|W`fIR1tD}}lQZ$5JAXayxZ_Q+fA4a^+Y>5P?1 zP5j>PeKH36dZb;!{y2YrRBfbWs424;+Y|zCN{VlEq5dkaqVCWlHT)-sSvU%+1ckID%`^Y$zB(=M4^y@!t!!Nt?nkd|R zW!B2bh}5SEgh0E?GRobZy;3{P+6Ruly!ko6*I#>0Tzl zNKjL9hE@qw+hEFyol$uxi6PPi6Q}SCsZM9X>skV;W9QH114)ShauAR&1~@U+C5)8X z8?&Ud9c5<1CX!Af%4jo+Z(!XAJ6P-GL$*>-<9VSQNTFuJf;1?|;4ma6sDE|QudW}R@t-%rT@7^CU{PO`YDbBF?iBl({v|JX% z&9eb*^Euw6J< z-cc?ga7NIZa0#d`uDI$NY2SO@cxJ`{XEWe{D7VgX9v^)0ftZ~}n%l^kRoDpRI6p@C z$jFyUi`t9m=ko&zm-~gE0Yb>0G&IYRgwwG0KbC=t(=TT@xPOddmL!`(&& zIRy5K190yFceEs8ETw?@G?PNDlr3q5w1*Gzdx&buu893!6n7w#5Eam1pO_HHgh(by zqVv&63*xd`!t!;q1I**a?Px5BL~p(nA_)jV9aIYQzBKY+S!+30+Ww05l2HaJK}?KR zyUvcLc+HQ$OzMI#`WspxCXz^T#>sX|BBVkdCC~yXV`hdsi72V?YKrmx|MKA&yEqe{ z`J>+hUW;9q?2lv59Mx#+XOBIjmdk6eyGD}Pr_Y>=zxu1ci-EyS8okVZ<;?Z>4VVK{ zSB%vXC5Cm;I0AHrs4dXyJB=JY%AL+|DS=r`%JV1kd!p>Z^@fJGM0bx%C8)V(J(=v- z)X6iy5EsYJ$JF#x%*@S+G}znSp#Y(+6%HE+LNbXPTmF&~uYv_-%#hC>iJHpfCA4qcdOkjJp{g{@_q&tL0(QEuawU4Y z+u~Q={mwXe**>*RJF2L}_{A}a&*e@echjX|PH9xM&oJmgRv7(JB7OFm4h|BDU&ylc zQFtfp(}7JxQG*11N+ML|NmF&toj)Jjw{4NUI0Yd4Vq+N!%#z>F=Yne;yyEI8eCO`3 zihPMEk>SrZL0!DuBAkL0J0cp=Ca1lr7*8C1G8&qi zqnRFl0G>4Pg^L4sp;3R?{{3;oO*hEs(JClqzIrpdQOC1BI>fd_S`)K=eV|1(B1;dL z7gH!gYTuJ~L6(b7bg;8_}(l9Sr_fjKFnIzA|dxC_SvjvO^->too>pv>D|f%3m+>xb-nVCs_=K{^-%CtJ4W{(84tzedLiia?kfnAWhDP zAbgS_VwL**tetIRqp~{gk!*GM&K=?yfLs8LkB*KifYH9FxD4U!#4WjkoEH~VM@4Ry zU`5Zm=25Wpf>ZkNfj5ExQiPGn(zz0xDj;3FtN=yw%xPpU8BInM=xxvAd(o0V^t|ge ze9I*ye+Q9}GQm`DCsXA+2r$0+&2Q*ATytg&aSmMlPS`Ih=hYM7t!SEKW_E*IA?V~T zA9o=5Oc~kANR`jcdRr{Ula2#+qlONtC%;K;m!8F9Ed;~44(4&<8SUe{eZNN9I@qvtOuNZ^P2w0;2ttlVy?Ho&|m%9U7HUQiHVIM#@jplHoB zad3>#40h3jc|rr0&@;e!X8neI&#VvJEBK-(PM*@hBldS!M@LZVf7j2yMZ~sE{XKyU z55smCisl+V4h<=GlRSldwY8?v+v{ZD>Di_D)en3qwr?MbPyWw8i0|L`KwN*#;W%~j zl-A&>r;o+yGiTz;EA~f6XHR_jU%nboJaN<o&=t5}RaO`CgYZEMJ`ihKb1wo_?%g79_?>r8&tW2qL*TbZ~FH;U`}m`}Xg5 z*Or3VwHQ4==I;Xu;fC`BN0qPF^LhCXmF9nRV3QU*q4C1~12h5pg z_G4TDBx&>JVUI6ozi-f9P~bt>kUJPt>4NJiNciK=e6peup@|%bMgb%tX|a>};{1We z8G5u_icfy}Pvhugk40l6;wy$otTk@27vOp>DEPIuHlBO#Il)|RWpimj-4Yyx)`qzH z(BU|E#UT*|x!IPs4jEINDiWZ47bt}Q0ky!vRY>9!S;ss%dtQKl))zQOhk1crdN5p* zGiGh}3InOg@Y7eMXUl7}6ZMi-42H zgKBDh%0&1s)=*g{lPJaJHTr`355I3@$7?U?YGt5CQZhl4Rvh+XE(KsHa{%R1fJucK zu`9!Gw!1YhY$y$7ud`{T2fqOZ%y4(U2A|K8wPM{SA*5uX@LH)?}ZGM%P~DS6F1%T5*bdBb5j7tb+n!v zAomPke&d_}E@#K&Qt>B}=79An)&mQ&kLIQZ1>lnEF0Z)FSt_C{(Nyo2KTrquBta7I z9ReK24+BmxPr!s-KqZlE3jrr*cXTG8@Yf!b(})`pRHoL>mDOlzZ_%X2MzlYQb%}rA zfKKZHlCbDOLPJBFg;EMJL%3;)?yB{Dn$LRH2RL)~tR|DP*K;Ql2$J^22E?yg7DI<+ zVNP8Ez|Xm)z~?h^z%_C*z&l0;9=YI=^B1DDxEz~?hvMv+voSn0DCy_-y!-7!s=C_S zqqd<=1V#8OD994#Gf@v)EoR@67Ni1Cgf8>8NvS_o=O(bLtL+L{X*62;oE z$ClB))MxpRBWE=)yJ(d~&K0?feJzyDw?%+E=q0UMx_RJwQ01+{XV z6J;xG(eU6V5fmveWb$Yx-pWaC7-+5Qz}cG z4uU;tDda#Rp$+;@N)<^=FRO|=SYYlB!c5EBccl^vwG{<>piVrav`ZAxyUdEwrIY1l z|IaP4d)H2t@qI2=Vr=w65_)nHsm_iX_F--o#m;*OR3;##xVLJ%^-hEuJ4x_RtU`2B zu4!?XkHK@J=A6s%ix*>Pa7goH%2PoN*D8V8 zFao7}d~>SBBr;!?H%@nyvMtL>XMu?f(`vC&iNa3K*(XyYwa7`;O0Ab_@ANPoPu?@j zR5enO6TKDu0=#GVH??r4IucN&xE6x1J;l+G5YE0%5GW!pg0djtr6`>5mpp9B2F*Mr z3v^vDqaayiia%2zK?_<#qsU=dg4)WHiTK5sURsutGNby=H5A5mZRQ4K!46Od`d@S? zXh+lNX?nt)o#(a8jw-{(8G%r3FlB07UrcTscFNcYM){%BKrOVX-O#0vLbP{wD?nUa zn2BOtg9xo$mxIgUd+5Oj;s^KMD>xW52Zug2JuSi;dyngLPo93c90&I8jjIk_rF9)0 z8#75N8GTJ1EGF!bhPNt0JKz67?!Gw~K-PS5FQ~&rXoP>@f%HtqaT!}Ty z<8mJa13V9+Qv?iTJd`kW?KC4n+<_#{*3#T4K9Up=Yt7}6oH^Y}NivuF;29vUGI0Tz5{zT z4~F0mQ6z$n!GV4a?o#JSN=PVwAqa$n@LtdDeycHZ=A5(|cJ0_I{y}qds{)QQr_aXr z9Xpj!f{cl*D&*0nM}C+=)7IXiiL&*LO;INzI8d zURV;e(ttzkAWq+C8fX${<&N85A2-}^U2GbJe`CIov?j(bDi~&6I0vk=8n>(EahyEf zBWc~F`ilaPg!*J(qe-nROzG{4p1%GRDCYnxt)1kl*P^StJ&jl3QZ8xa5<`{Xm^&|0 zj6m|LAmNvP`4=maRTa_5Mvr=>*z-kaD^k7C5vbS1u9GL9i|+0ok)M`VmKDXx;Y!HG zP;_HMOH55q>i2<|IH(*(7?TjWT3ec;wG9GSDf)W)qJ;>%SRWm&Z4#v5(Dd~58J4MW z4QFT*%u$o)VCm*VYz4&BW4>lXp~eLd2$;eI9Emv983_Dcu2Y37V{c68`{vhP0p;SVc%KKjIC z%HmF+9f@X@V;1G8fI?lC#5gy*~37)a{V?FgZZbyptqn%ro;@ zPd}Vi7L2n184&qWn(z)j4c~jhDGn1Z03(I>9o#2lftGgtesAmtj+1nTvgTA1|rc^4l2>+*~_Gay&! zteAubGv_tI_Ty1mN^;#t(yhzDlr{2GxsPo6jv#kxYg z;SH~g>FN1s=ey2BNJZSp8VYuLPONxWh>W$iBX4bl6m+H&g~EzUpS(YhRO$CCHT7ri) zl^xm7_{Z__^YTj>9m@npzRSc~m*UuW*rNCT(mUet;RDgt*(cw@^;uhVBtSMRsV&oG z;7n3?JX8%(<%g42L@rUJfPz4t$J)GgYbraeD?AeF)D~*v)X5XEW9Rm&w0=fC#hX$~ zy4#*fymW#^MlVExI&DPkzw&St-uuhHP+_sDRq+y85L%ItLY8RHlG)Byv}0buYCQPR z57hhY=*E)Ag4~)LH7o^j4Il_cUbeNO5**|M znj_m>;}xQj1}mu#I1O9LWd^q`t&iA-5lyh6Lz(6(WC$ALtpKoCADcD}$e81h_%nh9 z0*}ipq z3~$-yy_Pj4l5W(RRipX%UHqN*Ia4u4sltRpJ}FT(;`%N(10&iOmOlfTPzPe6K@u1Fgrs)yVwWe)6XPgh&K?JaK*qS4piWBKDE z(@Mup7*A*<@9D(x6Bd}F>{nM8t!*t1s1sq3uCCi}f3L~)dc%b)=3Er8ZgF}pwWLnMl& z@~%}|FTH#yUi*eO#(UrKe(6+Xn<85xv@&U((7iyQoLV4x7Ok&zTnNV81wk2zjuM`G zBibocA`QNiI^)_(ES1(`d~8I)rS^l6F57OSeojvLZ#(^(Xl-tc54`W^;=ttxR9122 zzaj*8?Bck|m8t74J8yNgrS3J^wnR+Kh%{@Pe|V;$!Oa@*r{Zqf^vq%{g6>-roOX_G>e>?l!ljhwu2`d z)=D1Q(JNU=v$P}Ji)-AczR{cu*UCL&8-oF}TMBQDASCTtPwL$)CegH7LL2H$4wP)N z=_-CnLl;<&2u& z$?qli{pSDyqslc1NS1Jn%G4c&lQ|F^*dV#nhJ7?PITe5Qr+;E;YM95W2RDfs4&+R~ zISwEBZ=luYhL-r~uYXJ#utj4sUk zCToph+O~6hw6%8meIbm~)Tn-Yy|1LvFAhtt^{=kRJ>UDToC5cUGb0GlB*WR9;Mpg{fp@|)BQegJ(-sO!!aidUWQE3zj8JkAQlpgJxGgfHfh}>zJKwAS ze#_f_I<7f zf+hr!R$(JCSq}gX0eg>NJ0pIqhems=<*q~D#ou*y^wxXa}p1^4K!pjl!fENdqbr3CZK ziOXjgN3Ze_WLvE2DUJXlQK`K$C#M82N{DNUF*7|DlM|CklgFh;4_We=5b+p(Q3@Qm zmrHhUi?`qY`ndAI6}BY`Y)dgSI~!AztElK7!^ENGg-WofrVyu2o{h(zcuZ|RNao_q z*`$)TP5stnHir96-rBZht7=Me{%Y|->bFC4#(|`=su{ckoP&%*q|B!ll{{VyQJe`M z8Me>QVB$}$6b5tVnh&5eA4BO(2jp|^jQ)FC!853T4gI$g|&j(({Kv#iMS6q0%#Vv)z|k*@L**& zOqJzn$w)xsSbufspwyZA@%jFY`b|tuBqsct_AS~I^hjq8hKSI#rKTAf5Kp;5f+AWN zH5Pi#B2_pAt}ir;PLbtOY}zy!qZdYP>{I<&dr2r)C7N0+$(*}ANJi*>$+{qg8m|ip z%EllqzyEAgREkW~CpmZgJu_JtHnn}nc8NyunZd!q6kJ7o_(Sj40H*eqrr5D#yO0ER z6rjI>U8&0A)@Y0}=Zt&d`N*7YAM8}Q<|qH~&*Py-jz$zCKKOz6#LYL|5@U4M=v)?6 zDth$MC!&9_H?|B9MoU{~{L;JsQ|#EiJa~y8s9tl!&A$kGTXPo17e{_zQ`@rZskfF3oeW=8b+Y^A{4aTlP5#Flkmq zX*JG`oO0oP13{mA%!ENHA`-Bt5d~c7`WGCE*Z;&TWA~+(RAGG1@YLj_0#R`j7$Pr1 z^m=fxF-WMQtgJ(!9F4{1*t~UHRRckOlG11rNMfK|Z*P~JQC?$oHF$p{elCkt;@FeV z#OMC}uj9<IVU6Vp7IbffsE>6X_zyI%1c*nbbrb4tV=#gI*83S2bL;W?7LCCUc z8AL!Rv0bfoy()un?(A7*a7^}+lTPY~*(sAT7{Y9f9$38#3(Be?_I0#(%E&_Wfd~W7 z0dkz-wX}gm0;3huOy?ZYO4+ZfQk9@;MWr4aDmHr2Frp@bRn;WjmZnTP%^S$7Ynm&N zI0AeRvZc9x&c?%76AY+EmYAljd_G9ItxI*C)B%BmKEEzbQ5iZqi}p@DB9%i4fJ>3xeaUg}!sfgLaaQ zMaao>-9D+F)rqVF%sVqTt2RH@PC;Ulw1xSNz))9LyWoAY64l39|J8B~Y#NA#x!IUN zS+QgUhif~dZq&p;vK!!bCgz!gK~zZFlc!rEgq2Z}zyJGxjK?2)LfsdjdFp?z6r{XJ z2CH{nTdUf$Wn3%q?)Ut1w0E?|DvmMDhge*kkJHDW6H+iTGAd^$G^kh`M~-~Y{m~Lv zu~(d-kaRI$vLiS!yTD0esG&x!=*zv+?+&kESjIL+)F)Y!Td!amoTk z5}Zj~3C8(SCLkl?*{}vKQ?b;P*&zyttU#GYL{qN}?<-u$+A z#^EdX$K1@KbW~2CqJ^?g!8Geexmo-pTF+4eMWcklY(*x)w&;9;erDbb?*Oja<(FMq zEj8rs2vki)fUHiX)tj`lN}VO@(n_;&(u=MJ0dmxdAWCUWb^p}OK*>#{>a_lzk>Ui7 zJtd{xtQVl5VqG>rCumtkSmlN^_ebv{1={PXjh?{*?}Juk$#y5SoPaE=01F|>Q)W|# z2)p}@Z+vasbp5qL1M>t*O1D!C%}N8Ma$6+dCBz^RC|RE@$83&X#OC2`;$P+9L1g)) zygNBDA+%m9zNvJr`ardnlmTfGvorJY&98nd{^}pTBoui2jvYd+>|-M?JFp{u?bkjU zg;%`%$28yxhekxpK~kN9{%H(D61>65(x1(y<|SoPoyc!;#vXxd*u{!l7!}nHbL5yZ zdB*C}Hi^Ro#;>idkIwE+aTAm=h)o}=pXR!gy8?j83>&j>9!qN$Zf>{JftA8mjWS~D zUxL|D9ITY(DCcKj`8q3SgDW#r?Z;4=2reoPC56E>nNJ%@@%Q>cm3U5iKpm``}?%{ z&z?P}IzF{YzIWu@IjwWf?1*N%y1T`H06w0cpO4jL*9s{QP_F9i>QRs)Qr=3*xY z*uFE4KJ`p$^>qvB!w)~8teE;dYmOnvj+^rVsdiF>i7a%JOI)A^M!@`jI71Bk$-U(` zQ!+ub;*BaWRgu7(cakSt=Bb~V&yp1@_1$X`H^1n`a-O-4o;e^cX|z?vT12cXSK`@Y zPsiL0lQJn^8E2*2h(31h$J8#RTD)LkhH;tC(Jm<8Yf2{rfvEK_3>y=S`FSu@Mwd88 zd_D*0yhoMdQgAOwxvnmzXQ!2jaMt92%WidK9dZ%?5&)c!9m#@Q?X9S0jz_U**=q#S zxCh{Tk63o_jx!)oW^aM$skKt5%ThGAw7P30wRUpmn7nv#;-Z7}GA#6E1xf6IJX<0s z6bh&p5&<(M8QDfnPEM<}aNni7c5bM@IbQ$zpNzJSwkQ_Lu^Ap# zu_l&EC84$D)dY)6WiNy#>>g{&KyV2ktDQ7S?|0iKK}7Ph{2)3n3|kW_Ai^1kUoZY*@+re5otILVd9;Fx|mc8 zlDQ^ZK>KoE-+&bt;Wi|Rb`dmFhgWuba%L%L$XtND|5SplI>^jPFp{hQF?BNJ1QOR$ zMbJ{oMu zE9Vs!CDM!s1t}gj$2C9r{&&XS-Fu>UQ-2y;ZIa~q^A}=eZCS~c=h@^wd_8hC5XhXh z?%qDP5UZitfo1;Oxsh|RW$WguNRmtAE~{jfUb21s&{K~ejZb~%&th)H9H;Kyo;ZB? za2!8zB04+T;;nCgUEF-bOQZ10SH8Hiw7e2UYDh>i3ietb&&vkmA}j_64~U*@g3JS_ zh3sS&o8fb+U8kWER$_yt=lT>kC+Su)6RDZGbwst$x}r81-(A<(pp1--#DUBQ#qhEN z0@Z{QQG~1(HgroXOmPPiX6L$Nfd$}2@#4C>VQkNcSuCykdLLvqGoN9&2b)84%!N{z zTanfDSah>k%>s3gZ-R7EE1fpxh89bZ5k<{w7)b&XcP}WqOLcC^ASBsdqwCI0eJ}`y z$UK__@hM26WwX|r0J#j|K*Y6kvVm;0v+*Q2$h!7qV`TV{if9W2IqK@{QppITs`_DF zQ9ANc+*?_Tk&&}{Rw>IRsbi_eEtlj}sMkUEQ)!{LHqM?ot&EHe0HcAp4Q;dt7x6v) z-97Q#$rHMN%1zHa{gikSXaw*c5q1IAW0+IULS3>btEFygX0oc)!LwTiyl6E)dgm(< zdoJClHaQQTqNEg2*H9Z*9lkp5z3)Et`C}mG<`?3j2kwvM6>HQZDwMMg)`B)%_NRv` zF+0GMM_rF*&EU>Bz-51{2EL(vOVbnQW>rUDK!B;GRqB0W);C)BJ{!+W_R9m99JChV zy64|eg%dd!on5T8OJ*96tpQkR^ma{cJo?CklE8KO#>{UA-;FY?1TUN&32i}2>*`jm zUu|BR-?ApcE+|zN+~Uk|R=6H(&KhK)ED z8hKB=S9L~EKA}dN1}A|I5aGD&l6Xgnut*@m9tAPLu3#*4a>IR+v~czad{`s)75f$v zDDTH;U^zP5JL24hQ6WH_9m=J7m>g^7gv4dJjAHT~*)HYM#pvjmf`Lme*&QcOol0w7 zj-kz49XvMF#hc#v6R~y67S(>YZryI8Fn0G z4M-}xQXBvD#jnLb{mWOSq<7m-yefY3^{#|^*9E{sZ5g_vZT3b7mjO6Z! zjRd@nrPZo~PT6`&a@Q6A^sV+gIYZ{%f+*z@hPo+INjndU`;pQ_CJ?3!TRSRi-6#+t z05PhSh3;}!Rwhoai#R#>hqTD`S&LIAp0iGYI+DCcNEo#T6RAAI{P|f3tl#&mKO6gZ z?}7fNC;q>T>wLx7r~$>t42(qt9<7`*mVkL&Ff&sTBW~1PYl>_3@y9~$??25A71}y;9`Kd4AJh?K@u*fQnB2T7Ch3pO52SE~8!wm1^06C{RPYK0S7DHXX zu`%vFa*v33s?Doyld_jPDA>=Wnd~o5=ydIv`-VHjbK%qp0NJM*A>^~%7i%Pxs;;R0 z%X1T$!AoG>Op~e$)1(=K~qyK zBK(6x>qe`^?Q_@+p%Dc7X=Vs#iy0QqhP@6MxsV`R8b+6$3*=o&8k8h**5+W@dL((> zRZ>Yh59^tBtujI!&+gs3M+4J?B2b{a>9j5{K^O36`jrXdSBgLJvuvZc~ECu zT&C5|6IGRUua)DOXP=AK_I7cZAP=I%n7eCo_Q<=q^CQ0<$4{S=Eql+qe>M&sxSzZ)+B3L`M^X0B3Jtys;3B{BUULrQr zi2)MgK*3W(DPgK!pXBEA+H!uKd^s@^!7lgeXNM+u-Yt*Zi!^8w`Otx*%YV6CE2KJc zZ}P|hIY&hnNqaygu9`GxDt*5iV@wuwZNj4n^0Y~nDkKQV&_kmb3JxG-CNu*ZFflcj zP-~Z{gn*=H!?$GAf^}if;Jdc%9EhL4TV)u?`n=nGksLnO6G=GLJ6Y`M0~=MaQ4LD9hj zhl6W7keJnXv(Q2TQcIsFJDR-cEYrd+B5&5i&2ayHs>(=AMUiPTWI3oH;{*-B0P}-Z zg-J6eLSg`NK#jkMaJpoEsJW?2q@f{tdV7S-XlkCsPWYTV0|*GHFZTBgh~UP-lmnQU z5ObVNQ5pvXQ#zz;LXYTk&M+eHnghagIVO9`zyZ&9cEoeXj*A~bZBznMWGM}GDlsfB z%!>pxG&mfi=g-ITvX%P?N^zcxOLK94buqQ!Zr z@n?gXxeGbt&if#f=QtI-ANKajvL&l|Hwsh}dZ#Xz#H0tA;T>{+pbxcm4RSUaZP0#J zmS-ZXNKY8zG}Ma#_VGs_3OE=zB2Wx>;<(M1fSL2jpJBlG64uHA(yEjx;S|u?s$ok_ zjWQzKclB8s8nt&3Y69J9ptdg=WAkG)$R_ovYfYt!x2Axev%ntbzUZLPxuoow?x(u1 z#Tl{<$j~&&1_(zU1JCnt2(o%8B}HoCl%m*!1jZM}E=F%pj{;YI*#F9YH|Sgl#Uxly zdKTG{ai5&iYRNE>xCvtO`{3NoOwDR-cJ17)Ax{(IW0d{oFZ_c{1X|@EP%svU+0DXGjv!>{|sN3Sd?} ztE8qjre~*Oa)L>;=F5o#L48MpP@ZYT`F0V4|F2Pr?0Huoj<>)4^)WmI@eqCve^ZQ8 zr%t$|D~*iK{#0l}p(c7LGqj`mV*BOm*yoZ24h|xyu8A5J z^Y~v2=}=PeLGy;D{6H3q{U6=j&|2<9P7PEKl*{a>=) z1jzFAs_wk+<-V_#S^LuauB|0m0@N~6Ye9L< zdmIEd2F73;d%$87UQXS-J1|UcQOnIrqLyW-_89JF{NC_y2$Y z@4L&n=blTTLoYDzNtQm066fTMvTb??Sf}>xZk)UGuDEsMhS;>&57xbiesmhFq9woE z603fBbv4#jnfkb*)~o7*VBKpTJoi)?qt~hxuYcX+%8~`&$>38rwd}Bh)@CEFJbx)x z*H*d%&8iL#gB{~c)=NQ-Opm<>B0vy5IXUIMl_W==DbJ0}mVHWKR2h*9FUeq5nJPNc z?*}fISW;IMsU@SUV0PallJC9mK@IW|N+Ut1mYy@E0cEMMw=+010@037eEd&U%HZD# zm^?ROSI(aDiqMj#bpR;h>0BaS)FR+pw~!bkfKk~T84?-ly~N-w`1XT>=v?X+f*$frfYqswoKxX-GcC${OX2 zmd>G#F@Y9bgc@lMlHrmgP%gnQT@tg?Ga~pAlrdS-B?k)txr}wt>&|r-8MFcc_LDeT z8APa@H(=z1AaYehlp1mB^cg+>%P%~y!04X)?$bGSV$z5o{-F@{? zn{z|@`jo*!1itV7`^C5M{DDk-lE7U7LutBHS)1qFb?7Atd`Lj9S{5s45HB&g5(TT< zfoB&(^>1eDqdLx#xOjL5PG&RNA80haP-+Jx-h+i$$j+1`KT{;zt$5)Qj@_kaeWlMU zKSQ!pNC2fZ0#{T=U-9xs<8QzAu{d?|XiQ9w#n#rEw0p#f%OqByiwN+cwqH0O=4@mu zWD+A0B|`zZNQw#(bUF6F5X7+o+dG!|$DT@)XlPh1{hY6FeeVZiY+^1ReBhoSk3#3; zo4)Ct@%ZcC5RI?@`mgISp$Y*IB6gVU7y>puhZ$&I`qbhjAiL>I!ny%wsCte(h7BXc zxJ@GlypNgKj`SHELVJzKW?ZNgqpX~zj3^H(oewp~1kcoH{9kB4#o2$DThRQj#>peOQ6Ba1yj(7VM7bf=Bm;GBOM=&Iq!pI0)Q> zROzT4yFCgs!E2cb!0Q%ouPU>v9(qa^5bhRl-_rgf5GW{|_q=f78O>u?hT4g^a_w5o z%*=K(M(ZBrl)4P~xc&+h>bmZ{<4zfG3;vi$hm)ezK<3Kxdj7eKv9h|X*OB3~ZzTGZ z@N3ltK~ZqB=zsA1S(qq-FMxgv%R{>fG(@!StTyJlw=Jo}I=mk-W<&BWrmJzdjU-nxG#HcSmk-L)5)>+f^%z?Oi z?Ye})D5G@ER8uL9u}_X4 zKcT-thlA1+W0a2}N|rG9NB;5m$KH;WUord^OLBs+y2^CK6!*z%B8XgAxNSwzCc)lt z3{Q-!^Q@3eHUXdg2Y>wW__bgAEd|4mJ@!@cZQu4D4V{{snTi`%uSHK^GmaiT5>rzU zX?J34YcD?hqdyrNJF77{3QD=IQXqSVWQ{#Qpujp>`^L|g0D|9vQq_LptUma_LtPz^ zV&0dt6`3&4YuQ5)w-X5{yH~-o{LG=@TQ%VBZwM}>CV})+iu+a59y3U(%v@_!cE0!! zO7b-JOy{(+ZvBm3ljR7|gd8XBvIqOZB?*GTy_UH&J*gifB4}p&#u1Fv5#)h#!P^_` zABq+wl}0nZ{e9mU58d~G)|7HRYe&M0U%{5%|G>iv{X(zDOTXFvaB{MjFWI!1;@gs6YVcYJfa z^Bdn4jjw;l*LB3VpG-ye#?Mf^^M#MN8k(sfGdVYz&1rWJE2- zM8E)du}4{GWl;2MGpbbWlG(#rt$@;!)&L9`@z5z@_YYXwGOWjN$Emsa>!&Y7{{W7~ z6YNTI*wLP$Eert;l+2aP17pPD5Q&ZYGuNdId_Zekq^gp7t=@f%mPmokMpui!B1l25 zNknAx8!2!NP4Y82Op0;@K~B}HML^nf+mT6GZl4jUtN0i>5s*z*#?P!;lZjk|ryUGZ zs3m0Ub!1be0Riip>mZ0CNFyLoxhP>&YS^wL?+S4c)GlXZ(pHghI8gjtb0D}^{vQMG z4hNTsDEsKp$#DB{P-0*m4^S0D-(?ggC#J+yXQMkq*ox(4q;E&#%GDbp4U!G>%*-?K zJ~1lfK7Ls07FD`ost@-gEF#jPsO7iZ=%&kEG;hR{>z{gyj)|V2}rmu_z+zG zXreH3pkjx+WtZomRzVDEI+ALa<-OT^9+Y)3rId`8&lXvZ?0VQ;Jp_8}Ti*MnFMEa7 zrZQ*MY?Dk^e1WR%t7B(tD?a%b|6S`(Upwz@nAqhhpkaP?Hv*qk=eq{O_)M_J2qNZ= z%mwUy$c8v69G>@UNM#ij$+fjDl~X_&*<%XqwMUKEY;2evuIY{~N`lrXDLA^mQ@T`# zNqD3*vovtxMap&A&^#m7jrA)BPOzmmzT!0HIA1zp2om_)>ZvyYxEWi!TQSscE(_-t zn}IBI**ldn#nte1)B1fOReUznCiOgedt-j?sIKjWD=%oc4&6Ry&fby8YsA~%`gpwb z#SePVMkh|6KBGXDAyx|u?${BMkd6-{e*XLg1-3l9{@#9Z6Zir2u8yR0L;g^3k zKK1F(Y5l(YyWba&ef6v3+O=z1>(i%CYT(ntttFu=FI>GDfAX(Xn^OcNX7m8mX`=WdH z>=xgDW%juiLZ^(zRiIXxzPlOnZ=}-bflg)5>u0(C2hxJVwkz+;w@P zf^hzwWUD%GAOk9y*xZUMS6|RMLRGl5Aj%h1E3J4Q5~8vKtIi0z9J1e?_`wf-K<(;~ z7b|JqT;GTXA9_G%adU&F0rYKB)GhjAZG9OJU-_J2a-}eaGC9_}(A-{%E}Q>mKh2 zepN&!RS8FmsSNhdUk0(A9F42O1|Q!ckwpqIr=n zF}SHozy<^*fuzL(Lq;qec=d26G+K;Tk(^|d4NF=X(i1I-^pvfofRY~=3SiXn`R;Mo z=0$jdnWJx)UbyDsJ*f7VEiK$L>&M|^qhSzv&tjz40V8Tvh64mlFZdRv1FI&Qcx6!( z8|{Osg#6y9gj>@LaiT+RF(VPbb_`FmHqN3f3WU?Gz@Z$yv#yTH4b+R-D{cve+-KsK zBjg%j1bLMWU2Q(BC0ZNXGORGVQAC8mM(IKmA4f*y+$+1Q_D`Gx*%lj!&(hEyWQYe* z_#4t81YzJg5x}TC6(I++aEmdnn{w(Bl1b8OAyBM80ZNUp=+T$`Cxu4STv~BUw^mlS6Yb<)8&bfi>s4t8Ed-%(E3+JjuM+2?oto`(tqt zRF27jxjIm=f!qrSY)vm@WG_MF)f?C1%C##RrHo^s=7(e9`u_2cez!C?cyA{3agSUd z4r+zLW!bXkjMn8Fv=^9J!@gy|fx>}$5$L9RiepMK;+F*Pw3 zvmhza6RT@G@#IrqiYGq%WIXwW&&TZaRM4i)8nbseqZ`aG$x@Wi#hgs3-wh3GpNe;) z;Zl^$w&IaT9x<`JI|f<$^CAHnA@#nMS}ln{4RuO+W~p5&ad-AE=s$H5YM<-bRw+XN zX9TTE5LND0sYZWmGIsG2^qEPlW?z#O>A5fpAW5&XgPMxV-}!o~tdSq-k}LCI=#WW% z-qmYJx|^@S1&K$MXH=ZK9tIc=bvuh((ogl^U~pPbeDDXpTd%3I$lQ@5Y8k)y>~rxO zzy2TNB`H9I*UU;M%sqjz919(l=qx(A6_bvm)JdNW?Q@F%gl@Y(q9 zpST($sF_VoC{uBUzpJ_?&I?vMH-T}r{x$XI zT?G&rGt~U3eb>QLFSRxR56vo39DEyJcUDv#661g&kkf;Rl4QZHgbmr)70@Wc%MuC) z0@bzBldt|;pmiofihZA13HQlp)Ed?4Y|+^=*Iz_7HWW@;od~ebMUZsevsm94U{C|r zzF=r8Nt*vqWtFOD)nq{Rt*E3?UgZF?~ds?Nogj7VP7^Z>&6;TR~D%fG(ZRhLr<3EkTnBOHQQ3Uw61?0TAU#dj`x&kO_n8! zDbC-)2{0t*jCX2!DsCf#nq)SduTU1PkGnwl;+_dMAZ8Kt@oyMW!=bczqK3B~r%#@g z6fnjb;q!sPq-0BE%(Ye8?_y&l2~^QQ+JQ z&X7O^qdv%NjJ1sz7#`HbI7G4Fa&XNAa$FDBrVfv_RdtM(+(A2 z*Ce?ti(R?=oc1}QS2$N8T2e&yC|^(%1@OT5eS`X3-jB@0lEe-iO`Nheh@JXgzzZnE ztF-LhFTar)jfcGvSnyc{>CAW#nK(5Sq+3D21QAdrKL;aqPCZ_|SN;2P>dAViWfvQ; z3qK^K*9*SpdO3@%r_nzvSh5$mC;klqxNW4>S^*I4wv8|$QV?}(KYrv#J|LbB!5L-OlP6CK?SbQ1Q>Ks&%ul>5a8z1_ikBEbC{Mga>xu5&rVrQ=tE6W=q5&wtZ z`klCV@w_xMP=#DwTURn+bkqV~*mtkF*O5Ko6yUQ6kL`MkcEiTQNz)fpA? z6;2XKB-Pc`0}3@4-}Qdan4z6`e*T!-;d$nLjp(4IvEPZ66{f0=#224@Dn9m?pNR(^ zyeHoBy1(tVeNC+1i$DFNe;2(yo8k@awg+Ocv83N9Q z44!4~jJTYa$~Uc6AWS0ZS&asDt&zWF13>~M*rL5o1C!c@z_~}&b&;pd@A~@vR>6S!gJ*;;1n$*i_EU)PH+wh{^(GkzRNYJo9NJxHJ)vi2RH+z z=b)g2`_6lT^d$msb&4DkP%5~X_i?GlL|B#3#C-R8Ciuf18Hw=Om_K?fE?>PSyEHK} zruJuLyJ}l)#C`Xij=%e!Z%`W^Er=&ioDi~F0S(T*h}D%vW4xb!`pYIRW&p%Gu&?;i zxy!b6&KF%kKk&hSqO|2|$#)`{W_x%AdPOo;a@c*niIb>z%0^_+ zVbgX{=1|=qZHjdKs*Z|yNx)#~W8r)ogmMpV~YR&^_2LpYVGE2aT)F zC=lnTsCm%S>iBoH0H#O?zpIIU99p7oYBvNjo}{*(LztZ1DpRYhD@UGAAYin;C1yDH z!`iA>7+;cYH?Aq0;a!flvTnomIX9utlNvFUI5i)LgAxMoql^^@G{>$MX$3zjM>#&? z?tt-$gj1bmIZNu%P>%`5-$Iyc?W<1ewn(ebk@=A6SAVnY@C6QLjiDbJqJzHfQzWA%ySC@2vq0L^+R&lAa8;9(p#^pb(h7&^wk!#ApWJj6ZD<2EIt$*G*#09rx4HFOpc;hLG5i?y{Cmnbqr2I^Hp zl3Wv>A7~Ym`INc$SvZS*YZ7V*#-|g9J;d)S^B3Bcs1Jljl?754foo+gMF`D3Q8jS2 zjHY6#N`yJ{q1zcTJQOR-tGXAERraU5YtUM;`Xu%M8&er9O0q9{@r#rY;gCQ0ecu*8 z^K<_;qG?Tt;wk;ehrcTZvwMWLK_>PglRPp!6l<$%DYI@p7{m0O$#y*V+@-GSC+j&f zI;y`ZG{xv6x))n<`Q}o5W}D;&rcmRlMsP-x>Y=LvBk1!D)K$ zu&3_4<7`(_paP=`S`@@qK$8KIJN_J``g^@Z*iRQVslS!@Ql}jczvQc;@%q<2*1=dK zl!Mn&?WDg?Gs)?rrrf}XFRiX9b3h12BZX(D)dHt%LXaE!{BHN-|0yq!@jIj5>yj9i zrER+14k99sNm()nd3{Yr8^Z(ZQa#tBqg}SG9iFd;!wzK4XQ^J4grmy%K`5lcmWNjx zC0mGO2&fZhA3YCWv%_=h7!HSQM|GjpiC0-df+22qBx5CzGRdw4MqDH2vrJAS@M)`^ zNaLCzNeRX!TkGv+)D@{JCX}KbDqc0C+)QGzx5aEVM5T7pRCScdP%7U+JjKAkIQdfo8<)F+#UBSs^USKTolyGz74)~EPFIxDGsT0xk~SdB(}@{^y?Af@$n$^r;}?ONYKnJ1I`%nvDupL2Qj z>Q#|C2_V(tEMb~`3GFb*2LpHg`ql3KWF5#r`68P(EZ>PEbJKBqVOi>L1l|M;oP`Z( zHbAsH822vaNcc^tq-I;B_zDDKls0zEYr!!SsID$k4mqNE1$EDrL014kP^k=mdrKuK z0z`G9WY+|*TU%LCMh;r4Gb^5u_a8r3NtL!W&N;Paku?>l4eBhJ=$JCu*|)DcbVS^L z|NSb(qV@j`Z@V-8-EVz9hDT@Z#yxS8OpT8Ra_#^);I_*|G{)WfncmC^t z4amGC8ax~93&HOA*o2%MHFl4F#~y(W_r=R!{t8c+TwIh|-z#4EX!P~eB-)x|W5;20;}sf}h#%?*1{d;1Zv? z6RAv~B!QO0OD|kdlAuyNrBTfQGN~MULC~PGp$PvZnQpmP3$+FpLNX^UiPZ5ipDp+`<)#eP6?4Pz+-i7S@p_-bxbA$vOE%7MDz#&F$+N&1I|d9 z?uKZO30-?JJ2NHcW5~(9-BOq11TjevP6Nu0Y7uN5$S*^TW5&0zrgjVtji~Lg>Sb(N z4Tw5KK(c*M_|*=D z0hO$7GPQ-YXy}Qj(eXM@*>WvU!NK;H+P}!|lo3cK*xeUo>SU3I$K4LfziCn`6T5Gm6bxggV3i*ZU{MT#`ySTEH5vbNW>W0su%K^ zIb(uhOUh6i)WXg1M~DaXh0RSi%fXN|Yu3(GF6rRhJrjUIItao*b_HEPdb!Xb)`YbZ z+LLN!WVd_{!Gi0p^xDtH(lUZf2>A315fY)ZrzbxD`OgbMU>_2kj*pEgi=zc?cx24k z>&~v~eIN{!!+8F*^NEBg5iZw73x=-YP3-++$Bt_3H2wTsBhSma6rf6w7tJtNz>(b` zD$R%-Xz?CR@6*U@qeTP>HJ(=vo4RE(letDCC5De5c*yNfCb=3Ne&qL@CA1qL(`_>g0OOnR zEbFb&)gUHRE=~}y z<-KIn^2gb@9o4@rFD=KNcitTjKm3qIw01oW zwKybp)<#sy5p$lVcUEI&WFRgyMx!Zvza5*aD=|4U72}g*vAkk+PD*dfODl2Z`qg;V zy?4ZsfuXq2hTv#4TW3!kH+RJ8Ix{#|86Y!gW%t>^VEqM_*uhI72~~n3AmRG^`gx8i ztmM2pIV9QbkT84&4JINVngE=6N-gBnXY3#HI=MG-N@ni2s~ zKUkF@2tZH)-QJ4+;kg*U`!z8|0_$Aztgcg% zopOlC7TFZkqew;7awiAbCudBQuUb9OJ}p9G*ivgVlV4+n>Fv&g#NooZa5yEooLQZu zHK`Hpdh(h_L3_xIn74?#Bxwg!z%V7mGz(jF`{uJY$vu#{k^wrKw-hw@#DQW{^K-ZC zz~s1uyy@5WFdk2l<8M%MyLt15$2iNtRO_O9smbs_U}_kO24t~T)KVuW)D8tfiP|;& z>S{HrF|mT|_bjEF-5ijz6#N{TQ-Q9d1%|CnhF&e{zAVE7aUaSMo z{Px0PtV>V{NR)XK5Vm%@@VzrZbT&->)ZmhYez`}2KOD=*_^7fSGCB>8A#+t7eqZgC zVj*)~bb_pJ3Jn?@@@#>V$4{iDJe?U#KwDKn2}w_eU;CN>*w880#QTWhzXR)=4h0V} zB1pp-DqE9utfx4tB{Su8OEW{d{F|FGhw7z7XnJC0#ciFeFI@-(ry>FO`cSj4iaSFv zao0Wf*|=mq9YcVjamR|w6K;F8L^-|JpZTj##nkkqkb|#0`;|C4e^k%k!IV1%*aJ6i zEX3*4r&X&Y>&E0T7z`3A?Z+5T_7c|tOgcL|XX2^q#~o`dGgBQrN$XK_kw7BZ7a$^>kHO&q z4IZNuq4q~gbbEVRcc5AY3^4XLHpCI)A#u)m-HP}jmVn3JVJj4XCC8!oELGO2EK)

    F{&r^U8(NpVY?@W8UW$tC#pZr3?%>fF?hnj`(%XE{cr9caX%GpKOWX0D zn@u^)m>}aZT#L}EIw^6}KHi_R2Lyr_WYI?0vGaANlV(iKjVAn85ohG<>c+lVUYO7Y zEmE+(r35bUN*{u2c(L_r`%dkn$nN1}A98jrE_`vOb;X?>`6-iaG_4*&a$Lak?Y`&J z=o0(RihpfUJR!eDI`gHdtQ0ljtIL)1EJgA?Aa|#x(ur=K@|>v(ixP2$BxRdug!G`$ zI+sIz!^6;w$_ySSh^6pUW8EQn^1HA52Q1t?p`G&-FVp4V3)uoNDei(;UxLH?ta$tW z=bQ4JJY6v@D=HnydyF3wGy#Z&YP_mcND2Nd3`Z*H?? zW16N5m#}9DaiHP|7OS0wiEiLfb=U)rJ(6@Bd&|B#W7H41pVIdJVIx82!w;B?dH#R| z)WuYcb%H(yNV|R?BbiXL2|ubbjymQIMahFeS_#c*M1BnP&Rfd*o^` zSYRu#y2gEI-QbWx!)*q#CfsMhFA#t3Lokx3)Y6rC->IZ&-{-j+1&;lJ1Pl#bfZ{PL zd(=t6@$vT{27M+u0+(RTTUcc9jUvh3X`j4)PqoJ$qG{>rIy*+Q`e)NBY2BDrwrouh zC=x1&c~|C%iZRe!!iWUuN0+Ua%kAqJY+KJSt^0jQfPks*!vw88MA2-T=fj-@#TmA* z&V8}QgO{vygr^K~n&)MSS&u1@dn|?r*uuUg)F1A5w;*`8-)oI<6nq6u_fR;GQwfK7 z{5E{|)Gizs-JRPW1&M2506%j792xacm#$#Y!6P650P?cicoZi1+)|~p@mLoHEUcaL z+@CyD6x~Y;o6-^t?s#Q1WMt(zI_QV%SkaA7{NRgF$VY&U)Mw_p0nj%%j1zo>%ns;H z9}n<<{E_{g-XEdM>GQW;4yeC*7Jo^XW_ z4Bs?m>fC?CqYUZzYeKOQ1$B=ppEf6=yw{rv-?t*9`nQSR%PzYrVg!k&)1%l&3;@3} zNt|6Y*5U3vUAC!woV8J+0A5PFh&bLJQ2}s25eW4mrkBt|Vt2Dx$7g#8JKHY*-5=AZ z%G6uk2O->x>gElyk_<06pM(`(?5{4^mF>i0{eXmuQDmRSxJq5jvfD=YDRY(UrNcQ1 z`n5&v6R&zZr_5owho5G%nYe;yG=&o198FclPGNd8Jmx-f#R18h?}sz z8APT?N7a1>ao*#~37rTizOqBmAT?Z=1wEC~y2jIZhlM#_l_k4SorneQs7So&pNg4Yxdo( zE@<-J!LVfWO4j+VeP-bA(tSwyIdvzsy(l1BKkIzIOOPTG>wugm_4FGN}X0gx}oeZSw+Vz8@Z;BK0u| z1ZW{3ZxR1}f{4v+SCtm5lGJ8Z`z-)0`0oKP#-7_>s&x{F>q-CxgzHTcRIxhWg9`$F z+BV^$12)zOe;Tf3!V8m?9p64u*NWJmQSkey};Cf}Z5*a~d!!e|qY2Z0OWhUoHP%D*Q+GtwK)h5KLVbZFMA zP?P9cnbTA-gFo;zB|pxbL!|LO9G8|}cp*06T*q9Ve`_k=oUeGlxARF$u(kCAL?o_1^5hy+^MLx;fE{8n zzo0-Qv=YWvbW)(q{Dop=G8^2YV3vJ(fXio1B|g=oyht%Lt^aNyY2O*>kWo5G$CF{7 zM|gg`mOuZmhIBrw#28y76Na+f2cyy8F zo+*!EL~Rf{l?DD0n}6m0mpf~wqESgNLU}vR?4HsACn#_GvW`nS1H%1Ld#?@@=V9(P_ogCVyw&wL-%k`OhJ?(>@cVClBZEocU>p}buW zavWi4fK4TK6w!~ZtIZkN;a+_81|t3s`-AEJyPP3^5^`75FRtP>tCx^VL;W5k-UsA) z-=&tMNa~%?A}Zw`a~IA&=}t*g+^l-4hYpfAhdWq)_$>mvalLOJ{VnQ|dXG?A@F6pA zpHLK=5Su|_zgQd^s_k~j`7Xd$ef~N#Q3Tz{jyvX_x;TeO^VgKxV|>MWyX-3^L?zPx z__ty|;m}Z?J1I!LS1assMQgmvwS}o#f4}_UeS#+GA*+M!@Tgy!F25$s&x;lvwnVe6 zq;!pg_Uk7S?>oC*H16#r%2zWGXDdiYkM`)4@gFwxH4d+ZuNZ-r>*MX2!aiOuH3`&E z;Wt%{B?;!4hjHl0%l!hU6+}F1AsL12nmi46iH&}fykx46JUHVcVO?6y*fZ0*KImlk z4WGw7shiAgEa``R>eOPadar35osSGT)3f=0zSeU5T9@11xbM4jqP_RLWY1_`7x#4t z;Y0W}PnEnbd2FThhlo8s|0PrIWG8=`SOx$@0cmFDd{G?egzJkxD(5o<~ZXVqBi7dXa zf)-dcHEg0M#pwL-Y}m{((CVRyNRl5an8neS9WsG>V;IVEm^G@MU7~gxah!N3Q|sB5 ztMP169LJEPx*C<5Z$8fLw}SCUm%Pm(A1PkJurPA-gB`Tzm~YIbXbqellD)INIkH|%j2h&?kb0{yWM z4Yrf}ZJo{<7i^FL2CK7)jwM^t&`0w#|8^5qU1NN-x**(hxkyx-wy!N_L*`yaimpRY zg=zEKtA=aVev8Y7Z_7o#Wi>UAds%O$XZG<$yn3Xdn37aXQjsvW-(OmUH%5Ek;t(@M zOar^TL1fDIFJg_9Ntf)*JcSFP$UU&r4`5ZYy%;u9@QW97{;&8T#stv9I692_*9l_K z-0IzB09(e;hvPN9BzN^>TpVcO7&%koA+h56I=eZ5>6=J^8Zibtr2wc&$S*9~GI?z6 zM1{468af2!Q0!G2-Z|c*4?xu4_ZjTq%}d8FeY^?w4Ms+Vf!<3%aM`$zFZ6M-`%eqe-`=y(W#o-Du9soIPl65)%@8l_=k&R+%5MMM z>pU=?^50;M?Sy9$C}=!Dby7${l=)G7=i=?Ut*8AK*mick%RfUTqPZB3_s`v{Pq{zr z^Kv>=X9j7M51Fuy5CZ3QesI&l-QTRMv4{*0^3C>4>Jr{w4U8h&2lD8BitIi0yhC74 zT!J9nhPzD*7B>;3a>f zwu_3XJLE}RlZ)Z-xiCC_e1}Al7wDetX12k~uw$ojx#@Xh6h+--{*; z`KYDtaw^ih;yS13D`Yh$4q)sBx=tR_`Kze_@WanXsl+@Nufx=W+;WeAOmO?REWYST zJ!@nf-mMnK;IPE|ffs|f{@mzq`07Dx(WqebH2+Vys$Rag+n+VSpIQxG2W!bRoy?17 z9>aAa;}Z7OeD<4gtHk(G<+FQkQMS+zdi4aC9$vHG?6=IQYwv*w(Il+cv|_?PyWZD{ zeu3Fzk^W8<+dJQ6+~aCUsEpU#>_3NgmFV;#9oTX7% zx|RTG9j9#B*WO7wckxZs0(?(qK1C!{))M7eyOr;&)?5$Y=*-^B&vSAwfL~^C{4wvJ z!?Hg7U0z$=IyUN(^NhoZ{5V)|1l_-@wXlE<%cs^8y2`X{^Tx5oZAbB{*t9GI5?voB zBx5Q#2c*U>a+y;%!4kdWRPVJK`NeD>_VV(p;z@u7QJe5qLloQ zgv>=8Plc#no0fve#?`$E^ zgEkACpy6Bg>c7=0LT`sbD5;_w_H&L+#y^Ln_64A0e8w-sbZZmhx-c~u?zll8(kruK zOrelwfUDlBR6O{1(D6tBY`?)5wrd~6YiDX|=*QLI{7@yXa`o#-TmphW(Q5qi344ZW zsDnSt6C#mD7*6V=&PDR_tia>)4jKHH z(C!LA5hJGeAn~s`H*c%#Bt2ZXG|m2T{-xPBxZG3f^XoF=fvQA2lDx3A_3c21k5hXu7U#MU^1>OXTnq2UmWQP-^8?4p-WQVTPKZxV{&7Xa-Y-S2H(Vkpwd2*)pOzVJ$Vng>32OHcs)V& z)diaKw5`1F{sttxKkl2$0v4n-pg?_VF%FfszqzM<9No%$Uv>~O*~grZf(8Cj%5)~l zMUiV{0t?&~))3_l$*DbRUpL&6u_8!M@y5O-IdO7lvRZKTFG{@z+I@UdsE4tHISaNC zd?&>UVI>1K+cIHUC)eGlx{)$!o%c3s%5@oKuV;=kTLSU}Z^@d2K?M5&VZgqd>HU19 zjOV-Km7ETWth&bPn%o_F$eUkK7y9p;6;CrE#Kyfy)HR2&M<|xwc=@bW?3{1LQA2|# z!)4ni$Cs<9B3Not^ncY^VsZN4)7}25bDqtmH@V5{nRBlKMm|FuI^VA2NS0`=Y(7j- zag%pkfHVesDkTb6e!1{(39(WcIXeGX#)M2&`wTZIE5Jz$>yynm7a;2PH4v}TGm`y4 zx2D7IuLtEl`h!@FCt?m{rhPwP%;7W@Cb}x0nMaiHghY- zT*s^NBz!&60SCqVu6H$%)jZa<`?KT;HHS(ej&g?MMRrLH^KcNJ>B;1wy1nefiz<{) zPIvlWDA~6pflr*O+qk=lNg^B&dbs17!cd?s{P7RxFnAZvdbLs$ri@?A1kWs{xnq16 zjep$<$#E#e>)E|Dc2*si5uwJuBW|5BRc9p`BqMiRDgCm)>og9^g2!#U9*l;mVQP(}7{7VAk(ZNWh|i z-QH1kuFEJBcowwkgs~0N%pz|8NbR}`$lA|)uF{RxSJrIxI`GvR_1YbhTQ5{G?jD|8 zqo?uQZx(2QcR~Dq8Rz;2DgpXeEEey>O(I(U9icBmt2%nWa)~@qc|43EVYFH#<=^3p zrq{D%mnbi8FG+q{*YhFs#4vQ^?R)a>_7;BnmsS!Vh;xYUNf|~!gc5VpV)=EW@6!uR z|2dsnd0z$5OQo3$3nP$B`t?7vWlzt*3x<+h%wu+d)T>3kisyjjK~k@(!=4v=%iqYL z=;0TVrqMm1lm}$M=a41eNHm)C66k7pa4J->ECABnvwfZU(;iKPo*5d#^1Vfbf7&H7 zArBPoX^^aszFLuh7y;$pPeL@#ZAk(NIL6py*MXV)gyobObr*%VmAz&L8Bp_VYv~A| zmMFU3+WOr!Ze^W_G!}NZHQ17$j*o;82$T^x?u)yu=yyl~zuTp87g%kw#e2yl`p@=h zL2|0-ZN}Cf@cJ1sT@G(yVM~{VsdxC=&b}+0hx}xIrT1Zbw(V8W!cXa?kXbXz`)mD4 z)^{O%CKh~ZUCJvy4p%HUZpW>Iz?gW z$<@t=jKr?yHx{3B$RNjqpOy?2^4Xxlkruf3r~|Hi7F@S9hS1Gr>8Jj&fkl2I>WH{q z%B{OWtpu>Vlpw$7b%c!0bAsYj`z5P<Kk&3rwya^d*xrp2xypP!OE=G>V|zMN?tem5s=!{UvNjB>$_7b>q)U=-w;P!BEk z&*f{scG?BeM*0y~u>%*GGp_HNdmae+@_2zqDIa@VX6nrLB5JR&2~dsp9mgy0QQI<_ z(*?Jg_pVf6n95ax?iP#wC|(C2)NjU4;_Cx}<^HA{N3hr*^ImE9tMUy9rnPnaCrPfp z>VVhBRxpq>g%6ibNV>7~yv z=Pv$WL6?kj`T9|Ar9!GdJD&Y!vnk^JaAD#Bk2)lyKI!|i)qAXzGn63=I`$p-G{H;W zx0R$Hfl3PJw+btZ<1c|1Jid!ce1Wi}g5@0m_0EZ1KCEx30|hHJPh2Hl?!whg-1gr1 zn&IOOi8MgFUCLxvGIQ{pN}ZQ;;1KatoT>16VI$>kXT9Xz0YT@l(4A3XsJn1x5ncQ- zOft`J)R?osx67uxVLoa?6qjH+eEC~Z-%h*&EOC0Sek?Vw-hFA=6|!*r?-#Hh92L=| zygb5}Q(k!QHf$o8SI;7uWAK0Wc>ECk_fJ4An0bH6h=1_;op&!~%P%1ma^2WGXAdUb zZJwn~eE6%8vb$!Cq{=ob!ygEYSpH%xv+w{h_4IgdGV$)I>Kv;=-R zpoL5C%XffR&EcaCg>frlhq$zlCzS>7YcD9p;580zfb!`#l3lK5c8`y?WlM2n{yv8{ zp?o-JCLk>yZJSTiNuL%gHj>pPfXhe1^Rq3IAjM5=(;enT`FChO4a%jU=6rtbjm-Kc|D)+>pu4nx|7_ePi?>$ z?I-A~%fV(23S6a8@Zu9_xCpq=0c_mPbr*rdLN(aWBT?@a1_N^M!g5;FGd$FLW=~{o zRX3J6l*bY_q~sYj-TegDUT-Uz2C&tJ&o}Y?Tf*cAXaO=kTo_GWm*Xlfhj7P4+}ulF z2K%Zja2?3R$_7O{8-xQo|Qrme}2zIzBFV@{@xG=zi7knM!u7CE`owEO3!&Dl{2a8 zKkp!bTGTSnq!<`MsgkFhBUU?bF}wL)qd+s9)hj&Z9gKw_M?E0-HnLzdTXaN*uWK(n_qL3&gvd}MwRawLcPv0Ise*( z7mi$v_fz|RQm7{4uYFU+5+HUc0r8dgDqKxYqhC!x;h@}OY77b{{(+M3W2wiR{L$=$ znauDU;NC0oyDwrd7dDpc{&4;38+c|L1Ral({6=7#7q~#YunENh3u;( zEy49k7G^Fht4PqZ*KmfKV7d2>AMJFymgmzVjQs#hHJpJyJ+rRp_Daj+vZCvr_!bYG z=pILz;tSDvvfZK}X(|Al%|vjPvU5}cErAWNyuqIzG7jXciN_G`9CD=Z+``rN#U8SmMMM3G<9$RQCU-VzJG@_%pz_j(wz5}?@ zOS%Wa8uTaz%2+5+f|D4QO&uC^+NBeYW6idlaDs&jI4X2L^BYlRA6SnA zkbhZ4>g9N1{t<~QlzC0vJ*;~AZUT7wi468_U>HIKodYY&Wtw4@k7+U_KW7@9k6k>^ z)F&siLy!gQ&$BMp3*NE!(thzw$z6p{Og+4x!*JJmJC&ojFaw0e_x%2~wHGpjs)yuK z0X4DD360SWt*O0qc+P*+qewi#zZW_C3eSWCC-tz)zwmmVg-Iiw2^rD#H@8f5c}J=E zHs#|Br1Qqb+wFI&h$&R;5Q(H$&R`NKDoyws^l0~E2R)U;zp-Q!Es1F1k$`LiIV$rz zWn}*AFNDY8Ra!iK7aMT~#=hslMG@)2|Dk0@J%{srbl@RYEk4WhyEi`MC&95Az2Foe z5b2^@h#?A6iT-@el!T2HKG44zFhGQ2@fr{E%z>;P*u}saJ7FB`&2PeUmqXcTsL#p! z379eEm$2c6^1lw!0My&%-|H(+`rntN*H!J3o;*i|&$d_#S6aE8N}dXDbwj0wb%1ob z6-UCJz;zg01vmea=YS6m-}ICJ0!e+oXxE-MLew5#Gu$T7W3G#LyXpnrGsRyh8D4($ z`%r!0n3S9w7lBJkA@P{4tHxAD_?xHgTi(B1oG~DP4iPXB$2()Jr~dT2J>Ed+@XfRE z{okC@*7*f_OmM{70{NzfgpN6+nj;bH$#Ef!D#f>SVGeM?Jx#K+e&aKy6=tX2!#LpZ z^ypYAvuPY4{JEjeeE+_pN3a@o4zqU;N+EZ(tD!5ke?jr0cU46cTF6`sFDQ%@xDT8= zxHD7ExLT#6b(J|{9$0F93j!su9}}L}YrqHAy~yQ8g*jiROoIoi=34oBx4QKAg~$YO zmZ1*kpY}Vq8B7m{;|T1k%tOZW?A%@qcHn;QGj@775+nHhkG(el<6&SbZtszFi}lY3 zLv`vJ9_ge1=%CiI0fLL8;)VO{PiEB+qD4HK+4bXFU?c!2kH^{m=S}Z>npg=YX-}mO zX#hBd4Kbz-k!s&J966OAHjLcw`$oRI7oxb~Q&Vie|A2VMjc_&T)mVvrQ$1#X(cX1n zu_HZ}B>{=f@i@a0DEy7Bf^~5u1Lg>|U}2L6ja4#;sLC&wx|kf4L6q&jujBi2c4Eb2 z%X-Gk;L>epOFFFacAleR{`q#w7Lk6>rs>|2#?<@?X*P%EW$Ohn4o?;LM!J0{ ze4tSV{Szks+X%oz&rXL9K)4`=j72Ce}5KI+T9341EEG+NJIwZo%FeKn|U zyhD&lk9`Nq1oBx~|BSsCNKAVNYwb&LM{TWc4=k& zKp*m^ho9Qzk3S)7o&M^a7D!%1_dm2B#plv%MD_QC+t zw>>6|`&WnE1u*^4NjMQFeL9^u?Zw@qyn7>*Dvz^E*z&^_PF4~Vkr!}~+H}hGhUW&k zbU=XpJx}w@E43H(I0(ks5zny)#n$Pii`*2!yk4+SD+#a?`_AiHEKl_MY;Zd*~XC$j@=;G}wcH#Hos#zqUDHm;zcal%fG#RNTRo$`POVyqV;)nh1S-5lT zZ*9056By?jhKtIW%r2p>I4YJbX<#D>?#Dk^aF?hlHX1p5#h}E$m3CV5;m%JE;CWc) zBK1ENr1Y&IP((65jFV*sZ9Yxk zqje@T?09kRR0_Yp9}`))kg3W&o@%Rtc$@jRKC@H+@7Q-)Pr&cP^zb8YD4z zXPjg8)85llc!K()gR@@wtu_PEP7&Es`F;#CamM#Sy|;yA`&rqtG=rp@bM|#sI-G8V ze17%*R?Nf@3$xb)U(-F8)w_8ttm)dtQ34~;2SkhJZmxGO+@WEpjx_xnff}st>f*lUd z4TAjq9TbH!_X}5h;R3E4Qn&9LLhSbmG7-+9BKTo{)-;F?@)Z%T(jFc5W4FH}@wf^n z>GD1AqiKAT9cj~hTwhlH9)`UWG^=3B?VG2TqGw{%_<{xR=1g);&Tan1OsB3Yk9tmI zm%()pICwWYl_?|bck=qcUtKtQWx0=`5B0<4U}Y2*IT7v5L;r=TB%W~3%-4&uFh5@e zsE%EYsGDdJNMR?ftz#*anfgltQ4U)eW}IAYM)`~PdTXEeXBOUrpt?^(i&GJZ$0s5! zL?Qa8JG|1Q!{dTL`gzW|@=h-|seiWTQv;5KwuudOa|nhbn}|7KAmP)FA!wjS&G|L( z4JpB9U5Kfq%R& z{nCNJd$4*Ag3mBM&`N50&ZdeS@&tD%{>bV3WV(wynb=TLNsFR7JUGHTo^b6H4(!Y1 zw404gNfX_AdRsr`M(-DTwlBwJQ}LkMi((&ClFAO0C4LdCB;A||0VTJ+zT%I442z2py7Y1NGS12pRgCuP zqfcWGF2|nqs$d$=gRo*KdHe%5S?O!Y#VTyk5ho@k z4{{}yPC6;^xG$i8tjG#ro+kpaa(ldb<2v6&hG6$KWg37wuHx0HB4iQ{>YAhMrU>^{V=Nd4g za60>xVo?@mE>x1fO91vlqB><6OAy}=TuQ`mZtRJD=^O2B|7BZ#kfCGK2@pk?EsW2{ zn~BA*5El{_v}RS?tZqi@ENCV{N_>5exZo<;Jmj*U=SkxjbI#;2fJn%MzWw!v4l2+?|&fY8* zss%t$A_wWGOc?X1jH#8_CR@dF5ST}&eT4~+|VH?;|!QL zVP5^m`BI5QSEp+bHt*@#fbj1tJQMlo0K!glwrWX-YrW?BxDX9debz4w{k)~u(s`BF-}4nRG`ww@K2`Ve`rsx2 z4}WRbT4(9yK;~OGjH6U^)+frXF%*Qj@gX|1 zlIEm4TOJ&1KCbWH5x(=y`;r%j$cLXdp`=-l}x3|ssHvxwPS z%N(Dud}a3!^eG42A67W-*Go@LM{(~^l2=^AN!B1YqP5?$ay3CT`}ssb($Pq!UAT6C zej~WMlC{c|!OdOv`2!^F`8=zzBI?N~gF!)o6H&H{-Q_c7ATfxw!>*s(&kW1pJ%MQ< z)}hCeAgts?*M14+QAFMTWC9~ zjohTs0s*6xYzBcLxhJF}r~VV>A&|`EL^zn2AM{J5?{rnIPjg~fRLmp`*5ciQ&q0J4 z1RJwLp%6;)sz1I8AuE4eJzVl^?<%vW(aHiY2dz^O==8wz5%7uKq|i@77xX={M5Fx- z8?M|hgm1{{TG#p zvhqBt#9>P;I40U|7fOwCccN` zD)lE@o%N!!g@BuJR~8|STKgsqG+KF>9D#UCtvrGFvcj0ExL zV=#Z>*OAl_ea|ERO-7EQXyVviuPMnH#?&)q&bz^lF8gx{7{dCxdicmsF2wL8-$%_N z^Z=LBpovJC&id?nwh0I7T}vhF7f z3hkc^Q5}XQ6)m$0u^2jn9s;<2Hl_P&oUU$rTsjtDm8+J)9y)4?;o^U4(l*m`NA9tZ zor1B0=Nf)(53gCF4mVdaG;xz<%dxU_Z~91b8^^hpK~Jg*l4BarXYJFle3DA{MskDK zN|jwax_IT=&yV3{*utVaq&k1CM6=><@#)T_?%5mIeUOKE9T)=;(YtWD{&Vv6OS907 z8tUBlb6WW|%Igx|G(*~8+fhFs4h$b|#OICz!57lwTdT6@-}JYRkxsYQ2}R~CJu&CH z=-|56xXk zik7Lmjuk=LvW>rWVwnO44K?iZGw-$H$IT!TOb2+5PHc+uk#agTH`cmNo@>}lb>Z=l zm+ms2((ysmx!UvZIDfzCG%Ll(SLFRVrlVbcz0jVFpj^)hR~F&%o*h+JZ-gVUh&@2@ z_9Z3Xn`2YH={@kCMe1@9l0cELl_V&(!V%$CPEqR~b1~8buHZ&_TkaZG_8mOt1GZ{750T9s!oZfO7Xe4eqmld0kIjvSdSl z;G&{(t)I%;Qx>I1$-~zC0yG;eZXaOxFq$DoB$BVHFyQ`i-Hs2?GcR{u51zoq$&G#g z`HlU?GDP_oQoh|@j~o=sB~m%L4(o-usKpWu$c>?cyDKP4HLXPiq-;*&6}b}yiyxaj z&z`gaw`+zruZi6ks%+QdvQKMha_qtA=-t%q_*V{RKQ)CEj^&u*vu%VS+2%y~wlmmg zUn^1bq;jJ2+&WrZF*tatd#%IbVM6Yps`tP-P2u!5L2`rxHim>0_Orfpv$Yr+>p?(?7^R4q8>r1 z8W+qFpmz?nl9hdI=D`e`30d>fjLy0w7LUe$X&tQBdnML#RNwwP&28tl<{HoRi2w;NDC^j_WJg|vJ{qC`tTd*VBC5di{7x=Gz!_JH+%8Oz~>!pkMbE=XrF_ms7=u=hqw%xOjIE#R=hB$&8qVm2y97#b+?4 z=WCrMeslrOnYnPGrJw&OfdqSgBLl!xTz?7JmuPD}gM))9{(J8CyU!#&m?=O6k;>*!S|G7{0ZQ0;<@l`;&uB0g$y+%@`g&zlwq5wJ5XzU9i z{1XqIlcIUN-9PD+y$?j#0=Md%WG)B?e>mpUUO}$pk9zrNYlpAXOb;I&Z-}R_%>>n5 z;*-mJak@(J7d11%7v-CTH|AvbOp~syG!id`6x`PhCu2)VG0%qm&?XEj>0;W)0|ak1 z=x=xj^9o;FyvQJ>V2TFt1Jh0H`|-Aclplq&I?Q1Ozzy~tQr*a0NV*}Elkh(t*jE(& z_f$oF+<(vesKSrVe$&AmYour=sKINyukwlH&KA79$x+-F+30R<`|!BF$yW3CmXY*{ zCm-g$_*CT(LL@aq-B4ADM-q36zBjhw2Mee3>%Ike2_P5sf~3{=B{_>$Du$2qNQ4;w zcy=;wQ#mi?Z8NTyxKhRa(*a_hF4O^yyb-%WZS}OpBD>$;eh`No^ky*MenVY0`uf^W zBHgZ`kqshyrsT!o%U=OL%3yZ$NvigC&NDbZUGLP~hORp&7CScP(eY6=gmyxE(NoMp~gfs#~=$2(uz=;v&t$ z{VF<gmW={R+pY{{8_sSkw-=K>FAD|lm-p;7$oNkg=^{pRxT zQZvM!NMDcD&u?g5XUtuMi9O&(4it0BW?W%Q)N#@|&qnS;dy4yd!N&)I3xeR3;Z($3 z?a>Rl6Tx>MlKs(+^y`_Au!rxQN(uS#`vHM%ze=aaZ*^XxmP5;UEPQ7;z+E}w_N{}0 z|2^kKWzmm#cPl=~R2_4wSlgNT^+E6Fx(A#pQm-TmetJif7~{$tKmv%E%($%C030rG z6wq-qp6cizlJDvF`hL63Phge!gtn1$%2=3!>j>@2Gbg$CpF$cddDGkHumC zZfAj{)Y>ypkG*!{j7N;rnI;tr7Z|uz+Df^`%1=3dw&^nL!T9#$_Xdxz3Rsf?ra{2Zp> zsCO)}_&L#G2NX~wL?=JwX)}`pgrAG#Hix@}mSi4>eMRJ-TE^NSI6CUjEKgzc zQ{jB3=ErEv7mE0ZELL%8F6$a5+JpBbg4+WQi*Q=@CL%4dkJ%mwmy$!(6!L7rLRB9z zOb_zkd?Rd^^{V82T)0Zu6US{zArysQBuv2&w@G>xhYfjT=BXVYzwPdrQi}?x;A)PitbZTFdzFe%;Nzes5Qt${e>z6+cpLA(7KVG))$MtO_#HhTx}x7e1of4 zi%@<(QO)$#Wc8`s;}|4|_vb2s^H9}Q)t00Gf!#oPdy#Nk`>niS%L`m%*Ua|yG{?SH z!n&%!bDXa^(ZrMw3Jnjqww3J*9cGF|ao@+ixIR2}q+jh^%vcAM#{sl?uB7OYACg@W zT3H_2d%?t)nwwC@*Wa60V=>NJx9he5!oGM(G`kX#u>RSf_7zXL)Y1ujb~^l9#%1Xf zfU*cqqPYQeltNby|-oy z)?y#zoqok8!wA41KlcPFlsrN}FEh!?DwyHy>xg+QQJ%CMtHXJoPflo1w)$sNDK>x% z?H6BBptUHh{i@23*zgW;_-Nqnqd}Pl&+dcN06%e`!Kp}CAs~};+3%H=aZk+nY@fBC z3m~lOn0_-aJ}*0-PVuxcDC9raSb%dtFTEbYpgg(ipeBXvu_rkKlH%H^sq*HYW99D< z%sIpvNhDOz^&|PYUCHdtF79z+Peru6q*ufQ3c>HM*(1S>UX#)f0z@oIAL6KYsOW7D z=_Vd=^KBD}J;VXtPS~70@ZeBO4@o61?n{_4(7E&8)?sOGzgOo?VFGlR_VV+1|6I|| z5BnDca~@wr??3Y|jfofgsrFGZYv?Cj2=L6`^~9W0ax`?hg6a8u|0`UN)e%*ts*MH| zk;`}VM;2O~p^sgNnzP4gdVlpVz&%zoiR)ew(C_e1B*^$uJWxylJqJgrt7m>WISp4E z3kRRQ@~V4%okM$s3%n= zoXll|{L8Y_93PM3boFx(%+t&~<9uV&y!UnilRo{pP=Xy0H#EC&D!~Fs3q1~{>~3G! zwZU2>P#_Csxv#_PsT+Ox!0IED7k^)dL<77c@{0x#YBC~eo%^HE zAGl%gNyc$KI>q$+{pHgm6O;)1P?#RrEa66%X+3S@&4pOzZph%-$ z0%iL$e~1#*{mETZyma?iu5a2G9Vno5RUf$>RAac%$@te~?{kG+W+WxhVSQ)s*El!k z<2Tk0;Eq>|T;=G&MEA*l4BXAZ7DFhq37Hn4%P|2frl(QMAO=E+4kD3fc181QTZ;BY zFy-s0^Mso??LK;Nn4Zb5TL;sy7(}z_mN!Bjx&pnA>oeFZLoEB_f#u0yPs@vyG3tnk z=}DN0NAaRdao;zLFv|?$!n|)CB={@I_)L@dyP`8Eu^+@ksrle8N%!&i5JtT`m!d{^ zhKqOBF0FwaL5=o@4f+f1h6lZtDn4CdA8*?zT8Ur)K!H4b3Qq1YG~*gC;_{{Dabu|X zx9{AkSa-5q3h&l09DTSCMEl8Wm!&Q|=%MUKZgd^Sq>K1dRqgzs6;3VXF3f`tm1MoZ z8lSGs7m3MUDVs?A^*zNNA-%tiz~?Krmh2aT;KL7;$>>ie#2ySZO1zLmiCszkm;~W^ zu~>M9#7lhs)1Qv4A;}&WBaKcU=R=k^1}7pOBmd+U^`Y{dIq$y^=Ly%$yHO?=e&0d~ zLFDK`>D^_zXZbdT12*H|#vc%Ik5vo@-zg@TgI}X!u;>w^CqjR>z8_1m5i=OZ|Q`0B1%M2Z0yA`w2DP zkD?EKxC{uYPk*jOdKZh!z2I~T*Jb~dpD>mY<2{6jpeNKWbFCZ*;HnZCI9RalnH$p~ znUUaC6ZMbB60Iq)psaa65_suMv$J5~Y^9c-pv2AOhWFPpe#kEsOd9|7-WRX$9$e+> zd}a4MJchvy7Zer<9Wm549pjnn$WFn&lVQPBKr%nMO=cATW!T>z9P9LP(vF}G)V>H) zm|;(@DyZs3JrtXQenje@qpIa=hOAFW52X6RWZ!+W?m_!7A1}jrWot(SNpI z+HzceOJO(OGKSd)r}R!Ra_`^754lg}?)?j${Yd>#KS0LyX#I=*#2}< zm08CO?(b1Q$43lB9QR}mhuVb0ya((ZDU}1COrTwX@^V!^Dj}?DQS==LV{uqIRkBQr z6TC)qFszm!8QOalzb~RHJY=8~D6>zs2wg;~?=yLT9c4XLoMNt+9(zJJJSg&OpYBcb z%Z_ssZimPA05Q&HA+yU+PIG2h845fHZSK;K2Z!yAKVf5lx8}Fz=ZYKf18`yfK?B4T zL)(fD;g?MY=53VEihP!@aeNK2?tN!vs9%W^fz{B&kJ;eqP5(Td^!;f|YmdFkfN;wC zt>^nlLlh_?eV=9vn@o5!x~j5%)Kk!vkc@B6a^t|{ZW`dpLw5T_u^JVkl@>OJd$yo4 zGg$d%HL95Gs*q{7PC}bn$}H&R2NZHyrIwcXn6=5~V-=A6m4$yxP&=uNXMn4v0}` zarxev0mVMTtqULik3#dfeKlTW*MVA;It?@nhFtp~gc|!S!cG9c7AANw&f(VQ^(sLs zq$qJxzZKi?SGuUljcPxv} zGW~cUE<=j%E(yb}Bd`9%BMCI`|4hI*5*qj3?iQ*9Rs9k=`vR+ARJxQ1WxmFJ()Z$1 zLriZkesvYBrqY`OHq5I~;Ra#7&)YmgyMwn|-PX#PM&=qo5@TB3JzXdK1wIxT=rEd| z3y)sA&JIxU$70wV)0ly6%yIgPDEITNxM~|lnIvmas+Ya1 zb}~M%>&=ai%!m;LJQ$dVDNRSs@piDw2RED^Cjn1fA6)}Pa@RlnPYb_3x!yaA%6u}I zRyZ7?0|tH3YmeQIbSbdHW*YQN2byGyToH;x^JJkPoIg_u+}ukIt(=gEjP~iRGJKT3 z<{G~C1Zcm*)N_1KG6J%K@d6L-{T8%3M>5AT8ZhUjE9~8m%PM8YODNv##sKcE#!oy` zErwm{b#?`>&LdLVwrOAQ`RTpJA-1va+o5p$&N`)!9Y7B-t_lO@eA$?^SEb`~3h(^| zfHY%~8YudV+tp4`BR$0V!2S+Df({*)@A+?sI+<7dM?Bj1#z9R`jL{3(b*UB+RdP4RG5tq&EGHj{Mn>hyFXAG?37(u50lB-8lP zvmR;$92i6I%oB;O9SA zv}Tupx|#Lw)9|wLJKiJQOX$2KQ?EYR`SRJ~??{cyr;$D``8wU7Y&L27^|@dEnr17D zZrp4|X}37U?;yO&Vgd=Wq~OM1H!b1w8Xjver;l68ou8}vc@M_IqBy!9J{uYk+Taps zweWg}O^EX1x&cCn_{|zvHR-Sd+uaub1ZvV!^}FG#{7(Bcu#llh%4=?it{xbo@B|wg zGKXLQ?>n1$C{nLbuZQV#krY6&M9waR3gE_`{`vj~QovA7*uLiv%YSJbUc;-+?df@T zcF)ND4$s}zavh23E*t?wygg{rz|(5QB>JukD`gTonUI9l^HR*T-$&o|ekIHx30!8H zJMGy?9qb=TOpd3(1zy-<*@;A&#xpqq&O4#hA(+>Zo{*0jZC?t8r)MGzYzZ=RKeqS) z@j*+w^0jniBAEO_yC>ZC(*W-cX3BIZ^v7L<{L*px4^FkOtk|o1C%tHph)R?oo{7W$ z2$|Y!yO$83`R;Ec(JqvLg2bAF`-^=(WJu7vidP)1&DlgW<;UQjKc&V`;|ymj0se8% zo57p>>QpJ8z%u3ua+r`?NJ;cG%_z&oSUE*oMZiK6>$3AJHuS7xO z8ZKTsd5-o)U03lt3_c|N;rmW4zJJ^FS|8NbAR-ylK&eNh~aDh0;ho$>rIxGekq6oGfXK^a<0omtG@F|1VZ zD74;^C+|4;Rjt;`=}egG0e4(4)ic!E$mGye_9~Sj<_>G=hlqWd+2juDNBCD*f6f{Q zIud)|qgfZV&VWog=m^n^RBpQ(wHX^kx=~bjUr+EMA z`{OnJnYtOIEwZWvpF6X9!!deK0ce;VJk8uKi0{uOuG+T>$T`Tjb>Hs1;tf8UQUlv` zbDkNY;RV0EG`#52k0-VQgu<~VLFwKj>Ld>?yLK%xt&*`~$m$@~1fhGTJg{;up8frD2;-p5eiQ`|=76OHL! zPyNrSVR%zTOI_c7?X-+#p?pz=6@V|RTVse>{^YyuBIkP+ghRC_`xo!xc^Dg9XFaAI`xG@?WgQT<6K2y(XY{Bt#E5(d)B{ffncR{#CoKDfYm5?!pHV;obCKh z-grgOPA&|Ux$*w&68CsA4q0&j6rISXwYMwTE4HD8JJ5ppVk7-&DET8MLL-LXt6lz- zDR}P@nensJVtI5)*^!3rAs+fek9eO*t)*B5EFxs7lfxFs9IsGLJAvm)=8qwQ9h3anqAbR1T+>fh^?JZ}S?`^AeY zW4HR~=UEh&^|BMGw5|jzaeHQFDWR;^LX)9%Kw`KA^w&~mdTyos}5M@W3hn2h^a-= z)9_Y)f0|hBEN`RwYv~)7XbJ16G@1Q|p%xli0>e<~%4z;*E5TW@bA`Q*O6#ZWu^FeJ zVfV(jvbw&qoV0hTr%`=3-gfOl5WvXxwFsW5fpR538QBvCxr8YEH+UE-?jHW>=Ohg? zQnBqbdrI#Z^~|@pxgre})O+k`=vtpgVCFj-i3Ps$->AwuJ&D~Y$Aoe@f@YH zF28aWS!8PGa4@FW7KG)e**%;dW=$U`Z-T{w2vHgxF#q>_N^lEf#k&m6S`{y-Zp_6!C^00yKmw5NOX9~0}-UlsA>WZDvy}f?Z zjm{$op!}rqm>&uDRsf>TfR6EXKM-PmTTse+nzZL+1b6&+=S^dLl1!Vwh2-~+waY1% zK)E%V%CJW8(`w~I4vlWC*Eb(63&5-9Dk?|FqE70Q^5MS7l{g6{osNWHQee7fJts&u z_8kx>u=jDXuknNCX3$$)PFUomk{Zsx?}-T~PqDsxNHV?~dKOYRneZonE}Fn@`fAr< zuq_ck1GjN}OycwWs}I5XQ){H|%&NK%c>G+*W$>bV+miatFCS{F z=?nBd>?JO1oP5l~bZv#KSlaye^TyHaL?7RAeA?hnN5s0pReKLu?IN+QUczYi2d(o+GL zoAV6f^6A|T@IS)i{5+^vWrP^pXX{w(&=lWPtX{cl=kB_y&7Njr6IZ76`3}I6v~mXX z#be=>HiV_RIR&a6=u^X^lm&1L?>Fk(vNNEm!@>1GAeGr!Sc0N5Okymu0R%`2`IxLh(4y=S8c{`DLT9X z1QH?tVTwhF6<-;`d+t3Dvy&EMk4j`fvE=)6qSmHiwf(yn+q2lyQGT$>Jh5HUpWfj5 zL5Yip%CwJR(Rt1AQFV#be(oVY?*jtx>xJG8k0fVv-S77C_PZarX4H7U@Nw`$<3W2= z@x(kxRjPxBwR3|i^-~$rbA8zSwxB$E)IZdu;NZN6)vEdlS^oYo(1P;O8ch&n73p-X z(d}1s`T30H3FZ~Y;QV^B^3BnHi@md2mHR+-f`0{I6Q81vBw9;lTs`)0wvLE5~4L$+!!b#0jv!gA6QglH#25IdQx#*>ig5B3j=< z0Q>C=pb=}OQ$(Pm73gJfu&%`5p)HQ@uXdR=hf&BYkLzxpus-FkmT#O-NqGFh@XGzM8#z zNt(P9EUM*&8?g*h!IkOh$kO{p0nWm|zuNi3NXde{g&tq=_7%G=X(@v9LM-fe1Dk>x z-f04rG_a~~%|H|Gdp3g_Ss~K8=qeg#Ril$V{h@R@-(##z8Ri*{EQwV)8*Q>QS zr#BDb?rV>ZozOpIfY`@05p)+v;|X1l`I!&B`U5)hj%iom7x?~SL$Q_+%@1DDp}*qM z_rdqMIcgvS!07*xbY^RcDq9eKC6M_N1XM&pK&CrD=1C9`dHN2jztj74bvYwsu3Q=M zN2#WJVFN6u5hCNv6~*kRN^lfr%Fgqd_QN-wI!2)O%WJ+-+a%xz`)`YTSw_sr6mg%Q z+?~h;Q9OUdQgIa~?3|%J!(<$f$LJ8aT64-adcdn|T4(A{=+%gEYeJ1b;LU?p5tcdY z&DH07eaicLL_8I9`YIyUcWFKS`PTNeEHnT4gh@24+VwstW_B^p6voswypnnKuD339OUHyhW;PRb77E0T3e1PL-u+CmHaCfEn< zKZ~|vTYsNADemQ+6Y*KE9*B*nUx`eFp=fIDhb=aOA50-2@m$BIIdXe(;xZMPr?s1(!}pOGdd5F)`R~VYP);vHxv#%Y%vC184{<@VGdmyM z8?FIKIRt7d3W24~#0rDU6B2<8H#AzuLZY^$ z#GyKkm0@dKDFy2ZB0P(7ohd54mtDc6u`2sX@`4Ou#NVyv@z7J(#|-meHUS#EYgnZ7 z1QW^lUV7~#5(7_$@90<@x>$(xxcc}`2L84|#g7{;@N$&{ggH5iWs*q{GEZu6BIE?{WqiV#lc#1=%KEAFV_~Vt-ThL%Q$h zj8ur1!tezd+r^zvC={Z52oVvYBB?&(tT+A540XW;1efl>mDvZ+_M)88g;;NI*BPZF z^4uReBAju{OF1Lv_GoiMR7?xHol;o)H!vj8M9#Wy3}OH1_L4-@_?Kqv)6^Xf0wmeI zNk5$mEEiy9*Gxf2pEBSc%Racfrh@~!(C)(hj{6{2WoX*br9I;X)WTJ4xpc;=j=GALsoIkKJUM+5M*gQ zRdO;`ej3tG>b}vfvefT^ip?eIdO%+&@EAi^1rlMb&aFibh-||8X}@YN6;5UZBDJ5l zcgZj(m52{c6=QDd6M2t_?+*;E40jQa_e#0hpoSe7N2~n&w`D|k4Cv;}f@nlRn0jmo z7lw`vecBQqbx(+a=n*#W!=zt`wcP*C zO5ydG3m2nni~Vo`DU1*qiwJS;=x?KY+4rZ1-%n|j$sI0-fcVUf@p-(y;d+$ zeaV}W4ECK?YqI4`4{&*_rkFSFwhs=sd8#HFr>+F`1RI47lcV>P3Cp4&&g!Ce!gK4D z8%Ak$98V2>P9JQ!*Z-_zL0By#rc1*T5{c-OkItVHVwM*K{was>064yb{q()%z&t*V zzK_x?d)&5%PQF#xnXkJp5x-2Q#IA+7cWwqf^g;Y^c+Th-q|-`PoqnodKdsE*XY0a@ zJl@hwg*dPIdFd>9pJ`wd+%Vl9ST^2|-fhM(a7jAMsCi?sJ`Iql+OEIP{fkw@b|6{# zf<=$|QDrY66w}zEs6hkap5{|vnY0kj^~Z;~V^Wa$a7xpCjg0$?H2D(*;(NKCpO$1( z&zu+W9MhFXq@as5f@Sd}t$RHc)2^T$NlQEU$yJDs#uN0uhFi>i_|ek4zXst+86PWb zIZ%@;*fbhsy1hN`y^YwU++#73OQ9K3PQqn11MHxKEK1?7*a?ZmF4ZP+=ECQG!3suI zw?(=KFXgHd(3kFpSm% zil+TKB@j~b72-gt6nCFgs{E1Pq&RgzO<=rp?Ee-oec($!Go;&@Rz?QJ>^_h7DQ(0U zF3eJ0_n}fk}@NFVXP%?A8cg-IW@1zQ>Kl!=Bc)vt;oUm(N7z*oKoQUyeHM} zB}^DIgnl{dv;*N%^7`8g^xulciUkZo!piLXF&gHrN=K}G|Hz-6SW?V-GW_@Q~4Ha(0S0@PyI-Hg#|aklwE zBOI*%=<{)M4;iNaeNJHZXK?w>_XvGJ4xZZC8BzpK@Am|X@ApFddaf3clxwJIGjZ0v z%+ziXE}#W+qxUvmxmBK#S%5GwF8G7Nyo=)D(d*OsN-&Q6Wm!f`5?lL?fa8Db{3V%Y zOU58gn*o2agIPw~UI`EG$nL4_`zOXAwG*ViWX!c>B|d~+@D9gnbC)bT;shex4G7iG zO%MDzK1BMaFGh{%z^#)OH;!UN0osB@60)Q1RrvGsh`xv$)*1x?Pe2l0gNa40-l0>9 zkmxV(01@x8!8?M-pkd1XwpRf$0J*_Z_z&4TCBlQeASrR~P8LU6YSuig=y7Hj(Qu@& zC64J6kNCXv)i_%jLTN5kQ=(1I6dSHJHSx}8Vq{uyV(qCfg?uu&s-y~xvT8HN880** zSa-Ku!Yx}}P4n@Igx+fsq)&97G`H)L^zeQ7Q$i)V36BPT{fzypf81Rd4kTgSep`CBZ@FeB0u16tx2L~LZ!Y2wa_RNhMZeJY zV)0kW@n5H6dp*aPov{%xcj9p$ffE?gG+y)^FmxB68y1ZR9C zjs?j*WwqwD`H#J*nV#@l(o*PSu>>eOB41?=wk=d*jIE7D=sxLc(GJ};Mf&M^{{{#A z_Y%K;ob+WeCp!~BEwczsx5@J8CwW{Q4iHUuuV-p)oe`w4Pe%R2<1Yr@l|&W`l9qOQYQ<-O2lGSUrwC`o1@0nMN&w=e$LS zROV*bMtJ^lC1zdKwDzF^1{4ZHsqNt$!-R2{(h$87zdvn`GLlqbZMr*|3Fr=y*6t6` z_zxWSxlXhmON2V;tyxCD1?kKPRUm!da0bW#5(5kqtmR`v1qHRV8$`Auo?1|hrSzL% z=9DCq(t2;15_Y7*@(xzcoaTqRf_|hgoX;QeW44fU`JSc|`KHo8LI2ZlI@xt^W zpcD>k21)hT;Bm%{9(ioh=g+Ash}+2C_8DJLPmy!4v-2}6D^+;!?HKljWw664x2^Mw zC#5#mXM=S)c^eFRq!L$xb4F& zbksROTfc9ZQPv+7!5lUQ=0A-VdxT0*&)-VHG_rXg{)%UOz-+7PK#}=R$;$BsB7hfc zSZujJhhYvJ;ZRui3z)7@z7Lgs)J1!f@r;DdcYkM8UBj1uwYyjLW`<`|Kyju7z2c|sWu)wCg z-r_bPb9O)=DPJVUR3qi_DK3<(Bf08?6kFsd>yPy5o4Dr!7rPWsahu1j& z&c7lL#j3hQf-gb`PF*jkF)VXHMu9OA-(VjX+OLiDULv`Bi!&n|N?jc-O0aA2eQa;y z5p*jr-=9NT&B^{bn>X0vqQvNCU|0~%-H6us8OTK9?-M?Ol)ZmsPk|O(1Ln(k@keIN zY3}4}q#grY5-O9u<9+$|eDCd#^v)KhkNkw#M~267qxu;JWJq=>)skkPu$ita?^=96 zyZp62L@bZkil0R5*z^6d?}-;WNnC@AamfRTV=7B4enZoa`8I~kS!e25ILu!+d3^-r zOXcqj)F#T$wJOOjIO`?Um&mG;)_HX)5<|B1ZcZo2*w05k_)OGF??4i@{B?_HKe%?& zZl`l7I3^2Xno=y&>(0L)BOSBn9-7|Fk$=PU1%mvVZrVK22~JSK_m%-lScC%%xNANP zDUJbZLU0Xl86v39KP_@DWzp@G`4AwWty4w;NgEbOfQUoYD|dV#oCsJ5gcAL}`Bmuu z)J8Sf#|Cq|1bx`o{xV-zNqtP~+t+WW&(DKg*^hq%FK;3Zs zuD%%d;K;zptLe#5Fd4rVgn2meK>AWEg`KDalzN5^F9%s9p3q`Hq=)iTzG1tUpYHz+ z>Da5bB!V1>3ETfhpYBIg7jEzb7yusSeg|WMCu<1w#0{XX4=2w13B_v@*~slU(i#35 zzxp3Cy_SXqJiPTCj(va+s~R>)Rj=-(E9NgcymX?F0lr7DZ}I^8>@S^78b2Iq%jfoW zi3t5nt(HB1aGV~?kD-ezwE#4IiQ}80n^n)eb*E0{)L3z*kcHy3XKmvV3m+-hw>kT_ z;rCPW&-e0#yh}wO?Ra{0m~IV31MuN?cnI1RNdmqE#z(lsZ34Sz9>zizd8?TfNW#G) zX!z`Bu&A{hD2~zxc5GKe&QYhBS!$>HZQ9nh91iyL(zTZZH;xy(79sEJ7`A4aFtZA9@2 z5g8E~bs`18P_~cyPwEO^Mtw~~b)G(ys#srxrhook5~vj}GVWP8lE(bFvvzuz%ciI3 zboa+~D1VZVtU$sRVUn(#v*>zWcRLVxV7ii5%ybfXfy|VDdfDkB>wj=<+!D1rX`eiQbi{=#*O*d%DCM~91a|Bz*1 z!H}H9{W#Rq`_#D%`3N8zHQVI24s&#@r&)}G@$)kR{Y5iQT`7Rb*MI~Pp7Qj13vp7$ zA|G$t$SC(Rjq%2g_cjaggL-Y`HtzgjmOz>ol0JS5n=qUhv z27u|s2*zt11rqvTl~!vfLt(FZ@tCNi?`sF;K<&PJ>Ek}BTd({E8?p~KIro$sRKHt< z8c)(5c;!P7e(IB`+7h9jTZ7pLj@fyDRoF@&-{@?`CDbXBWuKhCl&>v#4CDVQrm!!o zMZ)lt|4!UKI){h9{ga175cm3t^H^#Qg4}%DzhDajLDwm)@z|17-+~`t+vlvVI+)5u z8D5Y&RS#F<^z@EG3`s34kT{~BwAD4SC#iq zFQks7LQ|hJ^A&0C_h;Uw1d^}AZuirvoTPUGu{b=xgCv1gw8-aGQWgT^kbK{(Oiw%m zW4eJ7ciJo1sOYo7=leWxRN@>54B*I{^`hLUbhwMQpx#g+oO@eTfGnMBa}-GR{S&hh zg3cr6EZBwP%UyJ<<+MZ%4|?`?r?_GS5Cto~7ZioA+RWtM$#`FZ=&j0hH&=@Qb z=S8`c}#FmoZ zWtl3ClICi#)A+b0h4)oo%aDjgEbymq(GA!?3`m6fo+;E+o}NfGSK9gt_VyTzyfQ(W z%iYo4>=eG(KMQ+C@GryzYFL6_?o`U&+@$aEOBgBtRv)e}y(7;*bj4~9f;XbxFV;u2 zrS4h2GBKM=V|_ZziFV%)`fKT9aozguaXcfnz<%L(F(mg2PfJ_Gy{rBT%$f4r7YgT( zMQBBUrz^V4D?)zBeyky4(PNnniY}=zKuEXi7#?`AGcUR>yMM0hp)o3h;PQa)!k0Gg z<`UI}8WBfybQ8U_Ta5-Nwvc+vLojfeW8jZ@UmY%KoV@pz?OuBI=j_&OIwN}htD_R2 zx@!PokR^EF_jlJBM=6JBNYVEXrrPO!(frp3S*92O)u;CBFt%Sm+3^4p4epPekZl>! zBdxYYfq)B9C(U@fR4IaXp3C7l1|`?#Pvx?Y>?I^lDnm(4Ljw%l2x59VWym1mtuM@9 z&X^c*_I#L{pS%dDF_$+jjqb&7RhcS)7K>mhzRYAwQSyg(PkzK3>Ll6Z8Fk4qwST@z633O3XDf%F7B>Ct^Mq906hSj}HgY zVy|CHx=CXt=H<}ecoOYUd08Z+;mGJ&RoLxtZl7E)9stbaXtHxGB_&UoO}==uJK}5Ay|f@BPbq8xq;Q zX>ncT?TX^+oVFp+rlpawop6l0ed#6*h^sx8*Fx{TCzGIU*B8r?#i%t!0xH&*5nvCo z0&Mwyj@1^QU47GA_8=2Ehq&=@=+h9tyMO2w<`hI12+ZvjewAo5a-KEFRllt9d(vM; zx)<{|uAAE$h&D~L$~GMnAIzR4t~ovaaA?LCCsERXL$u&{w~ehp>xSJ9taextWCKLV ztrNXY#6AW&GB%c4>ggBeW*y%NtPnup6z-hc(BnP^-ivti+LP`+&82Fzaw+b6{gu4m z>>Vwya4+#}uovzMxGm5H_T;sH2+QkXaK`&_>Mou>?xQ`^Hy(X~gf?v3R$U0M>q~xr0w}g6%h&7|Hv= z2Wjcuy}%KnHo-c~gYt&<>^z>5o|h$rIVW?DeZKaA|0!^#BmWkAkKcVjJ6aJh*|igd zbP?TI;08|h!Uja8CvPZB`iSKBi(t+31JTZU7+;SIlap{;mL)~dFXj|fpP&elk?6h? znS&w(SwO-NEXys2-m6@pKuj5Bx*f5dgN-M=<^pv*p7R>K6%vKOH}=uuKDuWyKnMY@ z#%o4x;l_H$;t{_*pYryR8JE(21S%Nd8EGF~bqi!W+D)UlRZFVjo(zy+3%!>rz&aeIb#$Gj!Dmq~n9BJZ zpz!4xuP&8`!+BvSWkhy(8b&v4rqGAeNh)ab99^jV3tDZw*}ndr(v!$g^Faoh<=l+4 zhkP{?4M7P3hwtQL-2{)`KZqqW+T+;WN4MSL zM{{p`8FGWs$w)O_2rJABs13gT=ATZ%u(hZNgv#w$2Z z!|P=JQ)vaG4xt)Hq-`=0OK2>x1 zI^FL>M|1n^)F8t#vmhWRewR-w>c8S?{pFT%p0bd}dXh;>*)gaveu}W*;fGH^!c#!P zg%Mm9WT-O7*t`-Pl`o`&NYDV_p>WL{9TzYh)i1HKN7WCt)EW1-fo(~y+rO7pqF)|J zhw_2je=W0ZvA(unYE$3rbR;<<1>EvtgYvahT3}b@@*&J`Fw9o}as52}rp5F5gKgUg zkqAku&4(T8uLn;T2|BixdI(7ODac9^38CqrxXIg(4jI|uPWNjq1-92^!4EIJqdY-o z=H+8pho8M>+UG60Bb)Qv^1Zpld***M2PWu#16rve4Ww@6vAQ_#-WxcbxLXzqXD4c* z*>RZRvNmNKj>4(Z3j{9UQNGM8*R_I!#jzOqNlL&EojMH(8OLePG}3Yttk~ zfhckdNDd+s5X^L<5I&TJd7vyWwz5*K4T#R@Xa1_#zWKy8E_D`nMZSwJ+t-FU!l>9V z(NiM2T;Rf(P%?ZrxzOVErJ=4?+xkqObXtS*>NzH)t$g^8Q4Z(kS>FFPYqak^LKAy) zK!Ut`+*8iEp@*X$FhW7(!Xx+WFTC7 z{c>gMoIzOuz0=i|E8+An+T++I*X-khz2)5gi8n0)0T`bVNy!CMEP#RG=RCkM48E8v zMmsp@{JqdQb+)b_K`hD%`JP*LPR{02e`7+H)-2r*QsuthHzSr^*ZbCe?7$%p)6$3h zPJfwo?sGr0Q4V4g$vggOP+t40gf}Hqs^oJIlHRTBnDhaHRwm`Qiy_gMXL60MX9rmj z!yg`jK^r-guN3;-qGR{(ywI&L=(-TsW73j3^`xG<_kK~0?Sb@v?-EcEU=arb=?$n{ z)OnxxNNVDs*3?xd9^7||npK{JnKR#gy?ieVOOZ)PI@?dw^r(m+so&Ga(BbHOF4_AG zIO>vlHaVm!A)SYU8`r^au1~S`0|UF83b}qd5hWb)y?x^k5KKDr-JjwTaLD|gBWvF~ z*>iPNGy~W9S#D7UnETu*?#fKGH4ek0bzesZGcErGbY!cR&#I)^>Ej>H`^TexUe_I2 z^1iI$=gN~FsVg9{MLkA6I{ zU9CIMB)R`az{&CZede*o$X&C29*}G>3qW0?TCWC~`$eE2Kjxu-NHcXQdPGTo0Tv3L zFq3)}H!Iuyvr5f9CPBA2d2te0f~^+E%Dh6_zMPVwIezD%QQ(HpDW(?=+Qo&tE{!8< zx_+AP`J8=!>F17GOO2AfU{qXPRH%a+RgNrV4`GlRD)s;_ax&L&L}3qiklx?JebDdx zDLgo*D}u7+`gZy03lPZJXRnSVhj@OSPr&~PB2Kx*vbb^)6t1`mtv1BtCO zeJP*Fao~{fD$6Q|H{#Lz(ve>EdWizL>cRMIZts!jbjxpDjn`jwu-}i}s~rg7xX32x zIz5O0x5K6)Db`QEgU{fHuh;L}^}c-ke9s2}7{_D^`_~!^!m*mTC-psbL`UU!w`Jh` zzu4DK>kGFl>4rlzz5J}$jTFY>5$dIvO8qDXbrJ~h+-q;=aQZ`C{xbc7gvT!-A(w0o zh75_T#L4mjO-ZxLsz>(0kw0r7S}|}yNNkdIa1z$rkF|BIS2@|+4aoYDN^K{ zq%lF#29i;r#zV@xWwc`A&iacr%#Yp09baFruwP#sePwkiu1-3u>amJ7-AWG-j%c(@ zeS4!-st2~D3Z#SyzCq+@-)$rP8SY22J7wvnPYYi1Fk~3+&MgWT1pM6=fS{p*{5Ub- zgX#oi4yTbdeb>@;@N+dmuK8LWd+AR2hGZGRkyn<@DuR)VNs~C%4@(XWV=n$S7g+FM zU6I9>U2g7`J9n$d0NRL^>Ef_Fz6bmAd)4x#vx(Z*A<~K7>|;};H^0BL_cG1bC?%%X z<)P*<$GyKN`3x#}FVN~E!1D<=>O)O3i-CJTihPnhbeTfy!VB09?Y8n2WM@-`str%a z9%1LEw6C$0EnR^s_1()l8Fr1U+ITFaCWqRHN_H!}Qn8Gu`6;p!A880tw62!j!)m@- znfDBl@@7q0e{@iX*Y`Ol7P;XS6=D6s${n3t~^3PK`e^nM)c=JiCtOK~dSl2b~wGjik6vzgKa z!sW7+f;h68^TxtNEj)*0)~i?|GJCkYKe@zO1i$Zm*yP}8`0iubTNT0hHT+a)groxe-We^>5{yp(j=BF}Kv+p8OiemFs-j;mPO&OyXq z<^=upO)-9J*msvUcOmPM<5}t-H6-8cI4IYr?jEfD8aZFi{;<7iS#kTPdH4{blEZI> zTdJh2`uh-lfixi@sZBo{Ek(pWAn~(*5D)iWlHyw(-RK5#8Y_7xg6H#&C`D6qDV%|A z-rW;}p#-bSO@GY3cE8HIDPQ&bQ>_bEX1*yjpUsvg7g!_Az7Fb)LTgJLl?Y0%dzhyT z`I6!hQ$5eG0V|~a;q;i(NaC|ugLrx+Gu0P)mmW1*jz zu*vl3K$E%LmJZXkdNh+r~A% z=F=Zu-LDIQ53N2KNWPDuD@EqjCB1WT3goIY+m-EwKo=*9_CEHEq>8#y=UpYzAbig%#eRqV2q}uZVF%o1& zu6{=EwFq)i8UG=6`$>jBo!jIRwx0Caz_}_hV3khbb~dKX@z{^~4C~+dAjnE$%EEmY z3roYvXX`8sVY>6b^H%SxA*B~S$nEO}SXGzUyEv06u?i6+vkZO2{-E-9Im=zo^cHcB z(CXUcgGLz*b3QK*fmriI-2fsc5eFbWR(8NyC<%uWJ!0_AKXoko4^le1vV{s#Or5T30pU+{&zvU9QOp2Qy7*F=A>+-{7%b3&>@FdZ(~qA9?*`Un%T3 z?pIHP%1>1?Vr}(MIPuxNjJ17Kj*gTTQZb@(kHl&d&XicH*ZRL-dk3W+h@KQeN^&ZgUbad-UDsVLARcg{fv;IUiy z`Zf1g&E7sU-9S+>nP$hg`n1ir-h`i4M&ACK8s% zLS^?r07z>f8o(=x3pBiV3Sw>NBJY5)Jd7nqK!kk~O=p+)ddO}bf7HP`e?r=Mc@)v; z#_?|+fsFbv-~DVolE!O0=vf&bP6wTdgAaZQ`Ul!?Z^Is|OR!%+UhM)w50AQ%o;Zf$ zU*&TAQ#x(j^(HM}wc-%3@pRc+>TCJ?d?)cN&5aqjfV;T&;l~V51Pw@t%z4@ma)tRX z_D<=80G7$ZU3jM3+fx> zwLiijD!e|GdB=&Ux1Qm{^m{Ol2lsaD)n;Q~4_+M-je(%guz8c{MrgzcM@`v;2Lk@6yr_?Tm0>pSpmSyJ%nCLFmIp zjYt@COGpS%lJVbt0=V1O65oM|&;K&%h}+F)^`N7pMIMe+!8;kH$v_42k%vhVaFS-K z&q4mhd97ZeZFYrlLst-M5Ol88Hl7##8f6F8WfiW=FW?FVeyf$Hgv8i6#z&Fkb9v(N z(o$ufOIeVnc2V7ZOrYZw=Zh+&Fi3xjp#S?d8ViqVAaaE2($|AAPOwxJ}p%j4y}E|6Y%Q9^M`yLJp%Wp4Mk! z_1hp#!ZAH)vdxL+cdgiZfNIjirb4mL=)u>RJL6)|0OnVB>u4aFUM{fnM!&37 z#?U9 zEiEJyyd}8FUC@B`2jXVQlhPzv_=jSsm*Tv6uk(-i+F#atz~DDR^UG`{WfD_E-bj*}f)| z4}#p-s{jHeRG<_O_k_si8DYg-EOl9Pm}JMKXtUj0J5st-<%~Wr?$0CQ`NPr9ZJmqd z>NWh>eF4)Wmr+)YfThChtSTY6e4w&@T!qg4D9E4SU;EF-daF@pP*D;bUQzMTGbkR^ z?tOjTN$zmVE^zR4R9xNM;URDQg5}^?wedb!1Z!4v3aX7X>ebxa4Y}CHs16U9PY?7- zJdPHLo&$7!4UZVz*#;c|JAakVT7N z=ZTO`86PQ+b6*g7jyQ$fxUcE+cgR-cS$8YP{5*3xk^6}{0bRg$KYWMkjQ{RH=;^fl zvfhl}e_u9p0wMg5BhW!Xrw#I0k34Dq%y+Z|O=0LgcI}IYu)YrIY2K!6KNHa%Na{L` zS~l5BiBA?{pjGoLJdbP4U+TuE92UQMg~fL;nJBf}>wEgsh_)S;xsG)F`RDlO`Dpr- z2h+p{CHk(Z&Sl&47DZ5szu4tIJr+}1OKyIro0D!|zBiuxW6R|Hfne>mTAVmNGC=6=v(5)nmVp_cVaVO0j#kI85z7Yt{&jN3?akH{7t(jL zIvVE(8O5hRc+k$w1qXDWDATd(WsHBxr3suz7ZNLg3EZYi9~6n?U!V=_H;`c6m7F(F z+n{n&uaBVteE<(X`v?E)DM@Cb1`J_p9}FMg(}CmxXg>jR@eJ@{GnqCs-Td6iL*gl z+Jv%-LX`T6D{;JFlyVtL@x9qcHZeug+wPy|F{luMo2dsz?7nM! zQ9+aZd?0q>ZdhJRylsJFk_L4Nqc=ZQ7~3SJ>9^xPs4)W^)hQRgr4k-ijJq~X+j>r6 zr$t?ESOFj)eEETiQog7_<`qOM6UXKjX;UNiw^P4;bQ9z|lTaZNcTsq#d>Foe&qJcF zxk!Ev#dPLr0u}M!68m{O#mFg96M@^LsrR;D&dI>C&fnK* zco(Ftw}<|aCj8NcCpXI0YT+&uyTM*%B1ji?5nDjPi|M~7A52xeneODkrHY*|DY13(FDnjr zUfD&`AwJJcq?;mll=& z2sFhD>?=OT001gd-FrjLlN@}1YJXzP-Of>9qr`vRqkI*An%pUu+lxuA^Y<$7nd|Z9 zQSfy%QA!6Q45PdF4U&4>s^9qM{gVJd!&fH!Nw}sYcIjzcqx;Lfh2giAGcDYf%a3^l zn~ZR){bZJW{uLbhUkxH#F9jp)%oZY0)O?wv$0*MGx%Q}JCsoMS97S-39O`&+m8`v1 zSDjUC+%7(Y+C$gb6sW7Hm~<4>teiVbSifd;x9}=Y>)@9u@ft$%jc6jI+GW{q_q?BWz~n*z;+h)ulMwTgm4oy7{*Rkhk-&zN&eJHCr>|tz2W> zGd{*0o7qv&QN?FJfqu#hm^Rj;UH9Al-Z#&QL{vwiYGbSm3+eJn23_g`rqELy6@c!> zWr4Fwdd%?vv~HD2XJPvmjLpg4Dm@;6$6GERYf++m^l{r(3uAGwRMl!FOwzj;A)RNx zM$3OH;{vspat(u3=kc}=KQTX{hRgO%QfGtZolSYK~&uFE~9mvUAS@4DHX1J>8bz#=F^R zVuNLUO;2D<4cQ1lX zS2nC3fr`a_MkLy<%~+092|@(|AH9%d%zOSgVIWbX6=5gD{#@P_om#6ru*aG7`EC5& zspPQb+3UA%SH=;4Ytk+K3TxAi?xUW2q(XWSZlwjj0XB&g1AqnP(vlfA51lmLpOWMI zGSyA1zr}$Oa`iw~&!2O?5(3_waXkGA&)qJ&7j+JS#DOuh#{yYd@wQ*7^=gRr{+0h_;e82{2Cnu0XUxr^cUeyoyzO-(mj7aT5A#cf>{MS71 zMQHvFG!fr3Km#Eo1pCJZAszp}Psf-RrmSX9Wb_I1Avs-|@V9LDqxT-%wK#D?V4pYs z@fif--L4rj!ALs&V7)jS)EgZyq**4`$@qaUrDYZfDTHuMfnv*@A5Fa8$jQZh%KdG* z5rJKeFD8)sjhW4MbFj?st-8^6J!k3*`_ulwj zf8wV(FD9C-Zgy+;EBcfWl|x|WMJuK50>ic!BY8CUMUq|(5FHMd+tTzdpqQ^6FaJg4 zd%QC4O1{so$_Y;Buk^EiNl_(gnGJ*=LhN|JLA8)P(T_^oTP9REkW$pUM8vyJ<1BL1R+^@$urftoHpEz#rnjal+c0 zarh%)OERCtU%$vQ>?`c^)i4XbTGd_+V(nT5UX>ZmLx z86)|5n8rReJx`67;T58mAik9zJWu57Gd&Ll5I@63hzxWFOWxXG2?L1|?Gz4igfN~R z(FXLcm0XGGqwRbS>08Z7c(z*$z1JY;`TjYSN&@$RJH95 zp{}i`#x_#^MI%L z93a{~xexq!LCfspjM)R})=(lnqVBFAeS`H{-BC6en#T4DH#%RuR}A+Ah6ELGq@i7C zX3S!cgj_=#(NRFwl(tRG7() z{d4R3R6N-=WZHQa|0aI6(0HVTLI?&-%AlJ^hbk|F0qB{JHI4cDoXqYP9Iv7KhJ+F^ z63KYa&1Rosn&1MozV3N7*Jsu1JJairV1xksg#0l`Qc(Eoj_oDqJfqDbmeHJB&W)wri~Of;#TGVvg!P+R)apk``X;Y?2_A@f?&QY{Tv3?g zDKnqeyWkR(dBlh8kC*A+MY1UiT+5=ixadi+NsYQ9HvcvBQ0$(RVaYNosnzKz- zD6e#(gvyr(mn^fU{dzc$b=2OE??Nks>TFbXjLf{?5>_Vv1Ma) z07{A6a_+YTKX%=kB!Z8&dTaepCN~yHLBXwFD4bNX*JZdXzgmEbMp}Y;w{5GZSxFx~ zOO+CG)$XUhc@))QpUH;+z_wCDor}c1@nHp*%sUWHzQ0KhWJz5;#`X)}7JyH1AZE9i zMK5lz4z&3DlnkTn+X>Y)W5=O^_|J-EpIjSqOg)`_%_xPsY*IqZA=3mET zMdCA?vJ_M`iu+}h_5f+%@2$Mhg$Vm5ikO3Y`hE3pxQ}8Hk3L}0;51kF83?Y=drAQ4 z(GwQ*gxC$gNH^cT$#-`Hzf#;UHl)Nl_utE`FLJ>D#*sl{wQOsbEhQffFweM4Yh&g5 zu+O1Jf?YQ`veQsMpbc>o-g0$GZ&7yHGwvl2eNKfP-u7>LpG46+LA|%fMlLm$ArFdeQ|;e>~j+Kx=UDiT=rnr!^}&WgCDNn_ zI{n99*qqZjo4vD!)Fbk1S3v~2l-_2GLN>AQQgo~ru1;J|x8Q9Bx24G zX^a`<^FChdD_~R4I;Ru*vOVI!zT7iSe1ut&a#coNFv>&c4t?=a?>EKu@Xum$0BHtr zxbO=r+Ak&E7w+HF`=%Oi<2|%0Q}o@mDAp~!_X%&n`*kiBcBYtCI2(X@QdGkqE^!95 zDxk^E12*$aOs~^>o*sW)?HE*PHu!KXaGgrz++J1j^F&E-n?x(K9vK!7436@7UY+x8 zTz<6pe%>FJAC=Y`*#W}(pSjg8td_Z5Za5}+Y4w7p z^)fyFM44;#t7!YojifGR!_a*>$BTpza6GIpYVWDVTR0j}cJ)vBY2V-ry4@703-7BC zonS^n63dM~VN#R~s4&evq)okR8U}gQDd+Z)?I?aptA5+Ch>(Gle`&Z!db4!mA4}KO zt|$^j{}MscBSA!Rkf3iw0YwlH&|klYJNvCWGxw^9&|O_!bpiyO?o&APr|H~?mqE<; z3w%2Xht;;7S8CXy>((yu2i^T85Nj~PFQ&cpi=l3BHgkdnvO0B<566gRL&fi;cA-%&Hw2SYB zw^)XwWUE?H_{8@stDA0lf@ykk1 z`2iA@`i5R1o>h-aZoT&<%RfTlbB+;(kmyOLf8hU!HHZ(O*Fid2?N_L4P{^pv~AW3BO%rxRj)HV4wpeD<& z_oquGQF^G|UI*r!PltV*q%J)r*xp|G;Gf=%#?r@B)n&-U;`FDUSZ3nq zL+z7(eSApNbxy%*Zp+pD1h9mzhlj-_6t08hB15~u=&0k`BWAVqq_cd0is2o0@Z5fxQ zY`)hvuh06sJvhg6!Mojuxl95*v!HZ20`Rd_!m*(?ueZB11^frHa%yUpR|E(jBU;tq zw6JRIabkth791pTyqb~b3ZQr^?S0YB!y}J&*aDPv^ z(4S6Fpn}B=bIlHYd*FE<`eOO-_Wj(rMP1q?-EQhWmjKacUeR%ip%OyuNg9Ly1u&Ao z1~AnOI8Q9gtqxV*JmzxN>0&&->xvfliRvhG`36u7?-(HJZ>$YSwU9km9N4k9q+@c^ zb)o5czx;RvkIA!XL%Tm2+jus``Kgq(5_0v8Bv7LGLj9{((mJ0Sd3|ml`t(;ztzvlT z>dgSS^+^iJYKpY_X`7(Q^w&BOIJZgU)z^je@X)g)+29FQw(Q0P2af>ndOuO=^vsXH z;4XjK;>J{DyXPcgQvBi%WyPF-_Y{zLUDpI_ivxgNKg>V!3WKo0rmpP#F;R+FEA3AeuA$0Z)kFpfv72{gZW6VSB~F@1ADt9@YX^rsWhE0dw!8D8MmkV643TF zRV*-sWd9;`=lxDgk1)Ex!+x>TZT9IY%@gja*LZz_BuT;!zt6Zi;k z{2ftKWZpl2fCT>VDSpj!vZm`9V6Y@{xkkXafeCsSe}mgAF2BXO{$Bm|zUaSa!iT8Y z3s2pV8K@$!IN)JIoK!!$hmIzPad_U^@q92{u*NBp1mskkBcp5hW^($O*~343DqZ{~ z-9>BKW*A>6kz)Kwip2ZH!u~xk8TnoUv5qRyT5jy&QQ2ZIeoFLU_V}H+r)ggqPUnE# z*VY4Y0l0eW0`}L(uGn&E=GYzok}Pe#;uZI~|D>CVI18fNt?BKW_H>Q~?a{iHe;Wim zbCD-_))=Mp(=!(u44acRL~^QL?$>gXyM_Ngd^Mzju3*YU7`;@I1_F?vV@a80Y%O06Qf#;8F_&(O) z_n%Dv?%SNVPwBXOnUi{9z&aTYHm){{e!Js`4OUN5y(kMLZ`>9x2&t>UjLBi(4D{Rv zlt9SWz35zSzmhq~xr1BoO~T?V_(#(k^gonEi^gr&TfP>iXD+F_9Ob5tD z?^XjUjH}Kz@^(BKd2Y#w09WoPyEw`!yU_{Pe^5OY>cy zXl!6GK5e+mh8Up|QyJc0Av(*bkmUu8Rt_bAZ(sqn%+gdeL~D*iB$uCi8-AkrSG|(w z0;|}j)qjj||G;%Xn&7++p(uGziSu`!rulH=Zh!o!u7y3iCsf5P|D#$S-+N#h_HP0) z?=+m|wi4XmAZ+JPq?IiCD`1d|Vdo#(F%!H-+wTOmG2hHopi+US>1Z_X+3ocWs^Hkr z`?7}Lw(V_1nM>UW{K0?EN7!;|S{~rP_m(#G_RxMlJfuoK6+YAlGG>S*(iz^J-xjiK zpDF=trG)4Db9;x%>|o={UJjHFn07-E^m5DjA=w0RqGa3ojNx`C%!>@}a`Rqgq;@B+ zuU`O?Lr9l3qkcM|5QPu;sBim&+71tUpjc?64IHWvyg66FPNd_|{;Nf#4W+}B5L5}z z>*EZUHBIp@w=PqTyncXbf`B8b@Rb;b*b01j6#iydxRJ|p(Idcb_G{Mj=uXLHu6>Uv8 zqyW8}bo|KXs&^#xCx0F))aUubJj2IHu6}W@Dj(Lh_OB^z^r=HPR?F7?W>nX!l8t?J zF75Prta~5yEuI7p9CgEqUN0(Ce&(~0^KNNKrtBN}%ZHVZKfWqx$Oq#?0jOd#06V@= zYhlZM-yaSM?L^<;IUKlR>0}M}UAo(As-kqb?Kp9%XyW&v#a0ik3r&2zqq4&Sqmo{B zzo&P7>jACgd+4OgLArUYJ4ah`_$BQ_nIUz#%HFZxG&?yH?Q47UYlp9ciiirEun$)P zSo{+2WjqE`^48t>!ys`oWg_Z|d;@jpc?=TaQ(Y&Ut|}IoxB9Zn1j1jmD7Yg4xW^@F z_K;*p$}k^8vo$|LuCPV)0(Wp9a4d2q6$-St%@q6sPcY7q!@|Oh-%k1)eL&a;} z#^QYvs8n%#Bl?*VRy(zmqG5x0Dk(m@I~_hxPA!dm0~?AV4?M^=R6k*MkQ2*8=2|@z z362)*Vd?Dn=6je3BSfvj^~n)EmVMP4yLL&Ba<_OX12{>=5?kJ`Ewtd{2J%t5r$vnDadPv5a#MWeDbdqd$jdybNt3Lpf!}#Y(3(6YqJM zF01j16|WO{{s!?&#wd8k6ZZs&1U;S3L{bokTr;p!x_)7_jUd(1czO${t3WE0DVA9Pk997h7)*6FQ(yv#-YO-rYLCs`p>tU{Q69Su;S8q9+coZyVE&)mz z1>({Q+4r&Zg6`!?9L(5=sh4&A*yU1=Z~Y7c`@W}aNlF&sy^{65@~+hL^djAc-D?IS z#3F9)k9yu}SCM;YJnJBplc`4P<#JPv^3bibHbB>6?LmUIy7~GM_16VHTD{Popn!=J zRw*3m6aXwsKAl$x~FxsNLUal>UYpKkL$_D}d}nqEe)kVlymOIn#r zLX9HP@9RUH{Dd}^%?+<^fBKPy+x7)E0+d}+do+bGHeNN~8~1fn0Wsk|b}F#@j;6)` zzuN~oA}TE7Wrn}A;(a|j3P3OIrWE{l54^V(wbcq|0&SvnbmizVZbJl@!pCKm_et>Q zVo$xT1JCR+f$-5s{KW?*jJw5r_3fF9saXb#DYzRNslnwJ0wHwMUc~xhvyfO(eut-j z0@m}l!JI@q%&k2{y;LsnSAi2WB$&n)Om3#QUTrxMMbOX z=%!ZGK?YN(xnxs$t9~cyER2n|S7wGOc&j7re6$An&%XGZQd9udjpqPjJ5yHgSvP2v z0Tra*3TT)4*?Ezgw{y_Y-gHyRAV5yDHN1P7_JX~DN~^8jJ1ayTZ=Ac?mhK!QkGtJ)XQkl>gCh&j&F`WY zfnpro>HSpo*B+Sm(a?%;8w$UNLX25Og``=9u9v312WVoZWIc-|^@ zs2hw~=pv=d2K)1#ybHR>duXg9=c1@@`}+;Yt1({Cj?zvSBO1GRUNEn4DsAXOxav^S zKDrT0!36y=ADG~NsXs8QyjoT{HK$Bt{YCXQavLgmVO>De=`!s_oBOw(hB*<&?CM49 z`SsPdyEQSDz6U=|SqIn)l8r0djK}16^U_ut5bftQz=opVzpd2JUottSZh~cZ$g1f3 zzQ)Bni6FgC-%iNaB;#Z~SsV^~5#7G#&>Q4fMXfYm(ITj$O<)0K>x#X=%C)wuww?-OgZ3zG%Fp^49m3mX25f^P7!*GCLH8BR zY9h|AaNf2{V?(G30wu&Me{~d_vC9c~vfTqgnatbw;8Ob?;mXHBG_`2uimL_>L6pEm zcT6`1;o=UU;(>DP1F> zb1uwfMjKEs-_SJCp57Nv`WH-a>3r6lc_#Mlp^wUaf6;1-^!aJQ^n%xFUmZR%wC4jT zw&5je(uspaSo-=RB72xrIswmILxGWIv~PFOIADA?>_zZekd<#;>R(mp;^D`;fy%b@ zgy4gi$tn40sZdzopuh283vW%qD|z(GB(fcHNOk!zkx^kyb`qlVd*}|Ai7nD{eoG@X z4a-}rL^gZ18EnGzPtEG(J&;Fn5$Dy>!BWp2WNF=DJOqKsq;Sw3ul0F9rQQPIx;o6o zk+MWE;`pj%93WpWOCY|ks#B~MaSYu{Jd$w-I|o!8Z}EH#?yI=3p8hI&clHjY8KAuK zTf&aad)Q=axDkXSz!izy@3aC~GkjpOeZ1nwRK071lHxlg0OK6Bo7`6dHZ0K*GCEY% zc*?P4(+!LIp*&~FA1A=C<-{tr53G#N6ZMGOv&=Q{Y(9LdBZ9Zo7c3xn^|R=)Sw3uV zPiryer7qN9K$V?; zG`8xK?8PVC#F0}t*oJ=`87_Y#KDs_Wj`q=1_^*cD9`~3=uIFg`1)JtNA^reB7Td$F zmfBY-wamz8Ja>J&dnV!B0nPPXNX=^1^%S%xpwm{fFyrl} zjCJ~IXD81SjBjaYic0yb8eYon@PQFxHMl%XC!l5~P~Bm>ytG{iVXyM5vXD8Dnv#A= zx+iFHzkWibeJ7oy(IK2`n|;L9kEkKyF|QmqJLxm~l=kOywO=O&Urut5f_FOc`}cgO z?1l-WzFwc(eh&K9Q6TLEZw5c$u^29E4g=3o z;pltU8_ylxwvOb_jFtRv8Y`2`OWtI?t!HThSN}5RzqxyOJ_a)pMQ+}wU8+;O`bGVr zyg#AEcz7J&naEO@j4v@NOtKu0FS2;j+|nI2xM&*!;oipYu-Z4PmE@zHND8PZKPBFy zAMDibQHaw6PWA1cp;d>#xeu_eA9ach-oZUyLkPs(MNt4h-rHJZRVy zDs;rH{5C;-{y}En2%5RiEL=V8XSKRHa-u?->`m7@hIrp4z6HgwTK9s-m5}qiEYdc9 z@sN{ToWWc@=$p^NlCySzai|YfH?L&Ov1Qoi1uz*O64;nMix8MieW-B$tSFD%y0^vlK zi_-Xd`K%qJYv#Yf%bEwR5g>zEQrg~xQIR~__mz9*WV~_4qA)O=9g5HF4v?DWpv2c$ zH3>+)#hp7YIqjn~;jL{t^!VcL>He+oo9<}8aV!Hc7hi8J#)izTos2SxW?BXDm-t0# ztRq)6Tx^`!Z~hcYzwGSrFZf|QTKM5Ov9d`I+eu`9DMQncmHzt8<9o% zw3-LNo^E-*RWH5MSM_M>(XsJdr6UnDr5Z%?i$I?ak5i(4`28Z?leXgU_Z##}7e;x` zF>l$A01>+@9iRhR)~!p2B5n`4pc{hC^dCrTR`}s%wa-r#0ZW9INZG4?U>9c4 zUY0Kf?p8OG)`aCX1s4YgBkIpJWdHoV12#W^HAJUqQQgWzLS64Ub+O0(BC7!1l-e^2 zzw0flgzm2a2v@L66)J>Ag);h4acn*0@WG^dWJP}ltADw9B?{5H@~>tZU`;Cf$`dS?>P-j|Si>V-=~Tx+kNp0_otOCTj5ty4d+?%%KMwL1 z={gPKbf0Y~m%}@kNM5}0U43hY4y-aM!y21^{wQVjYXQQFMc;nNCHJIBl}NEtx!+Iv#XB6R8@gY>BPg)*PzdJEn!iEvJ0pdcIHb& z@7<*%`Bp>^In@CNeHdUESPM^E!Y5>>l}nf4WivbxS&O#rDI)W_L1FYxOVu8NdsJ{AWb8AZt2S%zJ9Mpw89J%kV!u5V0LGX7E=oWh_?2SrJF&C6_;=;@*8vx@%={kY^L?Kf z3ZyiyT6RWd)ffSQbSFii9xHsGV@7%25P8*c{at&w5@x%jWMI4tEbEEKX6=mp#4zD% zw+e@&QC%+(W>3v#g&O-w{YXSsPX_7igA&-Ytp1fAS@cv&WEbnPZl?^SK~baTndWct zO-`@-eK>Z{E6wkz;qQKc3GS zwsnV1P;71Yk(v88H@;}flN5J-m=*E~^$RFVemNWW1FBW5FB})V zG63p@9|P12m&av%9#D3bAV9FUBfKdKC8(T?Ju=|b|)F*(^bA`Y4)`k>9^g`Lm(tS>C%~40EpiE2m6)Nr6V^E0z20tDDTfFXid7 z1>&LKF$-sX%n8kR8+cai-Zs*9#M4Rqp3KLk!8F z*dv*KId76!>*wO}Iaa0LJEEg38%N;?o`vBfbqx|~@w@+XNel-u)t*24U0-KqVYVPF z49;2eYNWZ#8P26S`)9v=T*>srou-JJo^&mmfp7Nk+>Ed=Ew_~M*nNB$R9c{NeLC|e z<|l>BMqUH-S+*0bw3Q!Av&5;iNmjlC;&Fs+w=D93@TI*A30VwJV!y5cN7A>sO6K8R zH@n84wA4ZrHQEa$Km$_On3}5VoU)m*2yOrL*=vKGF zc+K}TQGt3lBd1bbX$BnG%GcZg+#pftv_obZZ=%wV)~B!DZMQ_bp+0^69e${Uo&>1k zlGLk1ilvqX97rMVRGhl)(^BS%QI+u8LS(!;yv}>Ps{FV8_zb9OUyOjfHy&)#ZQCQWlffOT69TsS#sXNfmuB;0J?G+BM-M*jZi{|A$_)I$wacD-JTT zMbfgI?}f-dptfF}LiP0yz2)L1B(;ZsXiF~dk<;O7dDw^lgJG- zvCuYC=odT6)Rx1!3+?sr#XMaU6n<;`gOVbbdT3fgF>YJM$n76C2TOa>u8Tp+i+KE^ zg|Kzy57-4Q%kE$1Ebd=?9YS}>nYGp3m5A$$KmUT~T@+ydeiw-d+(O{l+9N#*6=x$V+S06l$$I(CS zOX#M;!uB1714?B#za_gIo2}-X{OHgUlJ8l6(oxNLFdW8v%+Fv-q@uxE3JqbV3m{O& zM10}SH+a@|zUUmkLK3>43C#M-7=ED?Wo2r=%*lZTMI48y;Vkc*lm3vQjMt7WmG)@8 zpAUvE7oP+t^nNSzKI#ZJAr64796tz+%xrl2(M<&QDbi;4F~EyV-uqS9UshJk0xRLd#-C4vI7!;6Z>;PT|K|2_YnNLIkbLo83@;7 z?FfT(Y{`J&Dj*94_7bi<#7IR1bi4`hXMH|`rue$a;_afwUU)px<(=%L(>^Dz+Z5

    rIccg?dtk^8F}G~PiA^&k219k0o2S{}-Wil$ zl&Qj|_uoWoqGT;pZVk^p_v`N-^)sJ}B;QRSz6SeOxl$3S=cj4q>*uw!rTu_r`Iw8O z9p)l<&8^vvvBgU#-bl{n(TT0HdtXDcDTB*k_+1T~)qQ+jM#KMV!6URxwkG|Sja|*m z*U*ou5%(3<`A$PxB2Cn~FVK=WoGEAfokBlo;Y#|r2Gdrbxt9;9=*8ccQN0H3F`&@Z z<;;q3#L~Q|a1s%DR{LnnVGXm*Ih7aoMEUuquL}ALe_CpE7~)Q<4`4DOHSuPSiz9Hu zUdPKj*BKKOa==fRQxueOA`jstBX!oOr+2-anGg8P(N~Hn$Xve9a9sswRr}1)WIA0Z z@4R%mt$Kh%vCf%tS974O%0Jz&niFI9=b@7*ZB*>()9)oK19V8*+`@ld~=OS(Cl?k40 zK*Fbw7&D9Muh|>57JoJ15}jb@tlq(|0byl&0S1bl$y7Y1w{b>GfZ9h5d3i=xfEF$P zL==1C_8gs0el+*_mmS*M4%4WH_vsL&?2*5~_Q6LegR`AceQe>114ekM^v7O$q`yU2 zUY~TIJ-X$}I3Cpc@9}%AMe#i~RJkGGs4!^>Ei78h2Nd|tczCyXeQgcw2UGdoaFLmw zs9Qeb&CEA{U-u0G;bV%chJJ8C|FWFu5W`TNO&?aH8v&9K72fiyZ~F3p7cT^|Y#_tc zIEwb_jc$i?_MK~$3d9s3LT

    #pSZYc@iQs?Xdw_JY@7^x&*Rc>F1!VI1L!c4@3ebFs zS+1Kr9bSHybTxivXYJ+kCbFf*?W455rH7H_zWCkVW<>U718pHl*7Gd2xYjOP2={i$ zmt3TvKzBpac3OTl(tdW2fwy^V$wc|qOOa9xgIzGyAKeZAm-0QxlEKIj&!v*;w1>>oE54gcE#)y(`4C z{n&QHLbZ+-jMtsfDB_o#+pL3K&gNNT_}2>4iXe75_;B8eFq0=4xKH>>UZFULb{hPq4*-PK zgTrN~37FFTGSILgKS3k>V}s|VYC>!~EPNUGt%c}-DmtO^TM2({7X)+l?Wr`7Aidb< z#|fg=oOkbPA+f!xJz3vlw#oj-_p<>toeN%0O)%Iqm`bdlG6KY&HKfr#F!0E}Vto2}8m4vCU6Cnx%Ot-zI^+{&F}Ksc0?O58!Amk$ z=lC&;A7f&S@K>q;(S9HK2ZU39(*l9m#$3oqc`0Xrp57YJ`|A_xQJL||-Z^`e9LQ=; zPMdz9^mLtrt9?0ZLRl*9SjgAKfLEvRI^Ir)eUARxKM!DObRRhYnAfGc%nKbwhfLkl z%zMpazX*1AlAuWT?6VWSoinq!$Hg+2N-d7*&v-BA%m`M+9`k28x%Ab)1j^_6eYoJC zj1imJ-UmT!&l2$XdS&2v2x5Dj_$6S|$#+5PpVRp`h|bVMlJPO0;KK$Fi6QP-Vyz{v zV5oN#Kkw?F=<4gtH%~T73W2%(9aKU+x=Z2LcGX@G9NdqL-_wU9{_#RxVF~4sYudWn zW{utx7Ew#=yFU2)GWj!cMd|Y@?RV3%PTu{Vpz)0#a2)lDol|V1_KJ6@H~C4j3p@XG z(4d6L`8`IVvvM?F(lu1ieZnl$n{Rqy-~F_?bfq}+dW8%{zh`-(OaZqnxSGDNP$zL6 zz=3||P%Or|kKN=tfyQ-EMO`dz%AmCzl8kxRJc^=iS0osu@L){*PJQ!)`e zG&qR*$-T@H0vYBY+?03;ao*K?ZJZKz9Sr`agkb25PKhjx2!59oLd9do84(>1} zF!OBxzK+x^1^OFOMaHR=JfUOE2Eyd0FpG*J)LPdUK>z&hl}o>iv9D|?Z+4{BjDK4} zUAt2yamT)x)`V?ewr)S0*v?a&x*iQcw)xtn+2DXiM8rwVLxkw>$*hr2!sd)-aoW)A z^UEBTq=LREhd(1o*HnK$kFNmLTJn{={8}v>B_<0$95S z+BBqiP3~mDT~W)nd!1+bWP0-%2|B-!uhnvW9QC~zbwf4TQ~LpuQLgJu+Aum-pK5!A z%cRE}1PsBgxa1f@{z>mGZ?5_c0+BFQkCyY$cFF7fo8cz8xPx7gnQ0ITRl@xtAyLb_ z9l2mR+*e&cE@&l7s@odx^AqBdcAxRbRWE=swa5%M0Wy5)6(SDpk9wN9;L-T3x(LxX zDRIptl@RV{3bN>`A&v#jJ=lHn=HILI$(3x{2NYU09;DW+edtf{%3;&;&noTv3%n#} zRp%i3GJI>Itg&FSzE^GvL>u+}d#`A3m2Fr<&FFQqV7j!C4s@7#2PjFE0h487{|uws z`?pmN8MY(UQxW|Y4o=6GRiQ}I+207gqY1Dwv1dED8SdK%&uj+Gk(IHD6}oEOdoP(d zZ|V7Yi8QB3AIDFQfC(beP@e<209d5iZwL#IE0cR+GciIoezT ztjo`ZQ+Zc6@*%hP`^P&0(h&!Q*xEF!5vMFNC{y+Q zRy-j-F+o)u?b_l{mBSU6R#Hal_;M&eVQw{0yb1g6Y2mg7kAXQK#Kd6#&UO=S#%D_wPw?&Up`X*mEx6 zXb1!$rkx~B>_A9Pm@7_{H-r}*@De=2Ylr5CGN?A8%S}n1Zc2Kxhf7sMHH}W_o=*%T zw&K;Oedbt(v4D2;nBjxUt+y{*NSLf=U9w$o4uo{ky!3Kd3f1zyK{mlkQD2uXLNB{Se$C()YLb2T;V;d2@IXR z@?%?O<88>8Ry&rea^^uRzLeI8FD!MHv4>rFa36S;;qox~pbnavml{(+J!vY;gv#pN z=Mv4+u7cm~qwDnByeDdQP!!IwXB{EUu}>)5Cid`f{?uy}kw{7rYVe2O4ovx16{mdn z0xRL^Y}Swz03hjhI^QJRE%Zmy7joh^xTb#cbpiIiNnlFfPSMwrRSh#!0rwaiy#0RkygFhm0%7ZOP0q( z5an#4-lfJj9}`GD_brks39JcD_z@Xv5Is85-5Zn}XnF_fHM$E!FvXjpB1xp#EXw>J zv{IeI``FJ{l+*SPXpY3}A zZvCDQD|c+#_UUy*z-_jHOq%z_c9!?!Dq!CkpW5dkcJRW&3;+knZnHE0x@K@#rhY-* z{ljw$*f#JvDBg1aa$7)Tl9@rj3xvkw3@n-m9iM&EawoGkzxDx@FJ<&ek5ho%5VMMF zfn^~0edt%^q|;bj+*S}S&MkJ)@KmEQd@R@l>GR?Zji<6{&ZCI(4zZ=cL7$eesmYTc zeCs>Co!7ngDAEF9D5N0mUZKK5c*3g;wDlXFL>u`C6l_1^>5;Dc?Zktllqkcuff8i& zpyNF_ng*AT)A7D%b@OuYr|$7fc@1tMw=FHI#CZ_H$MxSYKuHdd;ccZ?|S zAHm1Rb(+7M#a`D2A!G)W;j5Y7DK@|2VS8E#qL4k9OnrFn@ho;+L-i^5!b`>mN{o*l zn^8^7c&9D$3BBixoPZmhM!rfR5}aMG$jem6oHqv=jWW0GUzf{4GqO$^%T5KrC7$R& zcHw#;7Oytz_IJTsBq3m?>I@-YGrQOxBLp?;P*2e6ei!K9Ei|03emcP}qp(@csrO;5 z%H5zF@e%y;czV4Q-}gdcp-}v{W^*kLAw;kYiOVnx{5NAPX8~f6Lf&PCeMko^a?% zfvDb*8@a=lSLkLKLK(ttX`KYL_9O!BBW=Q_1*~J}aVh+0Q?CgEx}gl~sg_6Wb^j2@ zftiaL9-Fgy`PPYR*WV-2%8WKZ3_xD8sALm%2B>cVO0N)u8VQ#4&0BH zMk2e~TibT8OS2`BJ3m<(Y@_%R(;lu1<1&VFJ>M2-r0&ECV-%_whQt|uro-d&-0mxz z)G2VyNMrHXDI#EIv|m154ysSSag9+E60q>oW#DlQEe?m%Q~bG|`$(JL$-KeC0LYuk zRO;KPeS5x=`rpWTUr|k#%DsCq#R@(?+^lgj%K$4sL`F9FT@UF*9u1dq+{UT))OKANZPj-%Q;qs@HbUcguXV7b6#>@StlsUzX( z3X;9bar&j7AK(i-(8L`PYe09cN++e&h9hTM?OnUFZMR<%;i#;eC-{v%sBi4E31|r` zaJrU0XX6A2_Q9jHV(GsQG7X%n{QHSB_bwWQSiZZSwFa?58rpG<($`QkpvviYO`^OX z>;8)Eu}}U?EM)_M6&eD9>|T4iTn;GBouX*Z0)L3}L6t@r6_5lIfE5cKy|a&)eY<+t z7aGPPlB?~%mT09DSXgCKyT|FzD&F>ht;%C5s6t#{<$6NJ23p_wqnr{eHRwMadd<(; z9-ZRX)~7Lz;bFI^vygOQw(R}^{J|NH4+6OfRR$-{xFltJ`1}sq+X1@utU!fS4x4`Y zt6+Q&mhpORBKd?upW<2W^h5YIa$nqrVC?rOrk=aY@~Onn@75Nn$HwgKpjzIp>j>`s zwpcd!d}j63WGY*nN^Q;cz+S+zwjM~H)pz{M&=bbL99Ng$r%jh(5){hG&Hd`*O2o2$ zG1z_U@$#a`ZIG`NF!{yLW~yz%l@M$RQANc{%;B#C5qP~?2Tq#^@4do$?|>!_M3S$v zWJ&fp36YbvK-)=R4iKkYc?`#+5+t{zAI{D=j-k7emwU#Y=_N~o+WvHOak~@aoor_Q zXnYsSg#q1goKsz)*r)VI#owpF;`vc8e7;;AUgykA4Wr4^g7W+nocg7SHrY?~pq0tFi2)pwO#^ z)R0B>nC0n!)19IuC+JhNk3~QS_y+WGXj>@X{#te+d)#kAl*AFgoMo4rPjQDv{4A~Y z59>U|ZV)iB@siRFQ*Rkmw5mTMYD4v{VJ$QbFW&F!kMr#VM`bpN`+YmxG2~l0lcxCg zHqGBD8a_*iTLDLnVv1lBjP)2|sDmH0mvhI?D^pdZHdfoe|(n*k)@L|`s6Zzen zwTUBr-{#bIVnYCfrL=_gcy0Id>i4KM_S#eX*^($Bf;UU>>wDvA$IqN7WxFioEt-RIlN>^a`nsJWO0|Q zjGy7yf6Oye@W!POKsPjJV&;E;EYb_T?Q>W=qX8M88|wL8Pa+qiddc(WS-pX@5C3c! zt>Z-w+BMkhjL%*i`B&J#;oV1qkrcpii3D$lOqI_FTh>B&c|`e?PL{{rg$+udD1y_E zUt{{;ifeD?h|>?7uN_z;?;Za-Vt7lB^NHliW5%0r_65NeIox}U9%nmq zEf*{q4hL4)Yz;2vlHZhCpKeo1NSj@apE z-3p_tCjE%~9>RQ`coB9B>Q4Sr;I6)a;u_cPkf1Wy1$^fx&Y}|GDSV%uch`*w=oU!N z@rI_E%9*-xl+erj#{7mr{inSp>s*34ed?LO=;a1(+*F}rEsj%0;iTvlW zIqN6lvLp@7c16;lgrbc`uQvK4gZ;}xZ*i{U{l!x76y<@)u$9-4!Xxt)y>91aY+tDX zG1Dp$9)DT~_-@)Llg0z#by?uP&p>}f{P=q~7FG^aEN~|mo4d8pB1a8E)V%#ZNn^6@ z@u_f@+VmXi%IOQ1%8Rnk4=5NY`-6971xnj^k4&4tt86oDV~p|#(nah<=OF+~`Q@>O z*3}l+0z>O;{g4vk@ZL{lP-bxiX;%NobOby+_s%>)nw zViD+BDU;0@t#MIc4(!n`ToQ|vMGDa_?Q|>+8lD6oKC(f#wGvgR);Uiyw7&7o#HVdj zkqmv_=XiN;-0V31a%FE5d6OW4P8Wqual~3o-@_f36`e{wmKt#(@tl~%8 zA9W$!=GQ0OZdOT~!%`t58rkFfcvtjyaclOamw^3c-cZOMJe9t#?r?f8edQOLdfLN| zpeK0)nxDTkcpsQ%-wszE3#izX=QOQCzxXJfCg;&c!{npvr7DAK{j}$mCK&GIDO_Gx zsA}<0Y#br9BD6yBx_cLa%3l&RSc{osbP!(tl-Al$JzXIcuJ1R7Go<|p&mmRSZE{NPuw zL+b)J;apcp97uE$d%=r<>##i%5^TLgk}i^tD@s>>o{slUSc!s!&F(Q(y`xL4f4IGP z?3+gUn(Fc~V5>bz&*7GC!+J3fw>2f7c~Itb3qAMdoE{#~l*VUX-??YH z&&7J(=VJCY5!&rzNF~e*O{F5~5W={Q~Udi)oMG2k);F zAiEoRPE;nml;u`qEQ{;$l{xETAqI0qm;&-`kdk+4x-Y*fwE+r#j4K>8>%ut2aW0_4s?m-h%T(O-O^L$uY^_{NZyh&f>oD z4KSO=C|hE_yCvVxhwg?tuJQee$>EvSs2j>+vmQ-r8?UG3?x%!psG=BFZpM|Vwl84c zv8{5gNVjOZvGwg#@gXg><^f33v4&`F)a9*TyLC9d#n(P$n3?cwIcz8M%^nM^C31E@ zH=U!3(jqAHgI$#*;h*Q*a1E^6(_fnhEVIQ52EmN_G0Y-5mmDeRDIKs@FR8}qazzY) z^MG7rB@i?J$WHfT-!WD2@;t5rHbWVVsJYaCunAH3$&35gn;jy zT=|(U3(GaH?@wQsqm)2_q#FO;BOgDxH-BbHP;A2_`DTQW)F_ID_xTr#D=D0$oyGuSu)jV>l-9E!@yL zyDH-N-D9ZPi&GAV%La^B?vK~RumdTQt(p{9;!_L$&(a}23Q(w59yqk^ffp?HsjRM4 zggA@3jC7vep5D`Oom@ zVz|_o{LHLq$45Zfl6L>JALQ6YRE>B?yqMd*V2UvX(`5V!)kqT^)Mrn_UzE(7PZGZ` z+QYsnhRz-0$Fu!W@EO68aNc`9Cf&@#bLB{Z5y zUQ%CyCXJf^%chdKO=AN2S+zc>NE%oPuJH{-Iod?pr!TL3p;%JEn)Y0UZHfF7GOu5~ z$o!ErPc<0#Ua>TmJ#+i5---5BJJ{jqGg;F>10_}Rxqoe*5&>0Ml{S?-{_;w;-(&o+ z3E?E4>pl&8TZW9r_phQ+NE{+?uhnT&lh4BS9R$FbVt$HqLLnX@ES=5Xqsz(JuS>x-a(8`tJoKk>%E z{z1>K;lAd%(^haKo=3^i(Cj>7O%c;Yux>IC(6%ll2OI?D+d{kUqbVa}Py*WvFx|gG zkvebIj{-~%E_fV~Mt?O@WwDrjG(##r_o(~@^J{y4U^H+Y7KxD)=2bU}_BIvtOWO0a z_`nOmi$Zs6j^kgIYJRh+p<`c(J@54gFF?~{pO4i*5)W4G2~c!IyN929nQq95jtvSD z!r2R;t=Lyd1EW)o-?e|lD|49dW%ip^LAS^NuQdB7-j^{#n+{pWGP9Oo{|*8kA6?sc zQ()FlF*yJ|#xJvlepv4DHEeG7t^H7KL68x6&w4-2A zpvgYO6BW}f5!J(dWWB7kuh~QtMjnGx#`P3EkHX9A{&+QYy|H>&Y9AioqbQ8;FYOdQ zlX?u9+r}p7fBpoJP!aYtq01-G`ytCePm&rN78Nsk70QoK6qBOUDdXzNJd z?r=`EN}y$t29vk|GFTbmZwkNe->WpvyDNKerRwZ@C8T>j4BeJuXqYa-a3bz&8b8SGwmg3<7cY z{Nz^W{w05>3^d?7KER}HvYsK_#7BS~XmCSQe7lm6Gkae{ZT}b!pG;*T@{Yc*iqG|U z3Mpeb6McQX9R$su@#;1<^(}ZSkpcrsn9{Can~}D=c~(%@R1aTxyYdhD$AR?8C&OVZ zRQd7#ZggV@YZuPe|!2t;KUOf@<; z9izybkkvojukq}}6w}|px@!dO2OM-%!Z{W)VbmwM8SF!L6D!j7A3{Vt_6PD}e$TCY zkc0H@_or-L9XF3M#a2oup;NG4$>8O^o6p%lO2Zj}+l7t1ZjXfTAfJiazUUldbCxiu zf#JXvxPjY#r^h;x6fX?5LAB8dCg{Fde6>;$AsHv0PV}D&{RD8qmcdZ z6n;mt$y>@d&3(zl4}V;4nSEr-$Ltvp2NlN}>Ny}lk>_z)Ke3$w!7_Kf6~sq}a@-jJ+maU`}{s*3QslgVGNni3os($NsZeIt2+pZD33 z|8k!n#*?7kB!&E4!}FtBh02RV^$OFU)r2iI`1TA)nF>P{9P<@rE{&&e{1V}FRY7fW z1x`Ze+4As(He+E>GWL*KUnN7u$Q6|jTN4i#8pJTrYC*!|AlwDalc|jAtjV{1n}Qi_ z;=*9;t2>8P9f?MejB2pq3;-b7iafkHYcJK~!<90{3sDk0kRQUpk>`QI{shG8!e|h``pmqO_ zI4`bBQ^J=o^5LobnwWm@yH6bV`Ui4?steFC9DRSA-}mEtSS=69YcIc86-~nELxL0g z{QRErpv59gL}IbdPHHaJ78TuwEeWme2PJN*yibxZE$s>0*4@}+SN45E8~F*!B&{(N z$7>)}3@1fsAHwE%hHrz1Huv^-&zU3T40(|hhE8(yAhqd!ulMj})GeXc#n-RvCpd1< z`$HB7u=GY5hI#y={w^c-JFz?7ite!Q3D1E4Ggm3<&^b5z@VgTyNwwN$dH#M40$ed3 zn=OSF7`bl!9EKJr50?n!0ByIi5_g2k*OLGRRBJUEzU@nz5nD zmGr(~HxE+Q?mS>~uXZHoIc56yE?cnV%OjC4<+|^p)uG$ol`3e*_Q{+OJ>o8wM={^U z*KCUpW((*H(W1!j^GsbL`+PksvG}kWFokjGAyqv5A$%T?ggZi51NAni3U+9WoI@B7 z_1o^fgguC*{b`?i5xUeM9xz`8~yk`gGmZQJyOHuXXIqh_r6oQnBi5u2oiS;TjCw8!3& z;pNxC$H}y)q4!WJpP`(W;02hfimWy7bF_el@Q;ZOS@Avm@TQwzgzxzz&-$PbkBhO za|}_E@#UhF{f!Oj9M@O(F+Qa5KgVZA&e1vJwPkQp3?-lviI zA%#32_3lS_J8S<8C1I@vTaU8}|J%H_A~rpDfeb~B7vCxmW33_9d73ym^dUmBj~PDR zzaNW2gE8L2!*TgE)B#U0&}@V{GAgCN!?A%_CK2)eKKz&9>gO(T-V?(O&>#gW#wTo~ zsqm7}W}*7%!S;r8hrih#fkL-P5+U2zxZ?TYLsB164@u5q+5E_Onm|K)!z*caaWp8isNpE&C zzTcpY-s9zK)W9Xg&|iZ=V4k=iXZi**q_<^!C+Hsn$H&`=t2WcGb<^YQG^T5&MEYE) zKRmV4ics}6RMKBJI>0b~D(3lBd%qkpjAA+Kw#CEVSBEZN5qG1I5$hlh~LG4E^Ptr z(SS(a&u4Yh7N`pyMynJE2ey7{&pGLKIR^V?6`{RR~1!D{iYJl;lw9>d-1rQFNvJ%`?{CzyBB-Dbg% z!u&-PYXq3)X{=*q*@sYnR!qvy8&$W;NrrUnz7=Na*)Hz&YbYH*LoNvy1t1eupAY2Q zljqcRLxE9?dRgs=Q=Y0FL=LoTns3FBHF8too^Cfw>^QKw`{y}bB93UZ!)i*ghAO@* zTryj}@$YB(M5+X?007C*UxSfr9sBTPh1vc2Yb$s1OC~?&-hJCXyEV%R1LXZX3&td% zoIjuMS0925cmiN~bUnnGab2IZbaRn`K!Spx%9739!Gs<@!Ij-t9z+!=LZy0W%nE86 zoc*@DoOAUE;0iNDIu&r?YH>LQ?S9l70DGOnm3xZ!Ac4C~0D|7DvClPSK$jz}(8Dny zR`w}Xx0_>SU)fKn+*!@5PCtDl9}Nxq`ANxL2ZDejG7Na`i7s)6?)sKVzZ7BAq6k*R zvFn9XwtmviYn_4M=VZ@Sh$HKGV^5W!KUdI_^XYsAHjWPAKz!LagH2+rs7-^Y05JC6 zq+eg4P2dLiE`y0{o4oerV+Na~Ond$!`_IFmnLBUQ+`S-w<>10KGD_W7 zdBhScQaKnimHGXsq+1=Bz_1|!RlxP{RKJN+$P8$6kP*F{Gxkr5V}G}uyc75^IL^;H zzjMj2v$?(r+3n@VDwoQ>AQFmkLz55>iD90uqOOTWd~I=|g1qr3mL z`rQYlTncHA>imnR$0H;!uENd!d54?de&(mM$EdHD%A)v(zkL|h0>n4bYWevwZt<6B zUgya^DC6bg-3?e$q8~OKZnC#!MmDQIVC>+u7G~k)_$~n~JM1CQjp?4+1=$xp{CE}B z*fCMm-@(0fDYk7KAbXxATQ}!WGIuR5!6G*+F8fkUc!l3x1P0Z04-B`P^hWUzTf{tm z6K}nZQVYy-p9Fp1-l}<0zR>JpRe1DK>I;nRI%FT` zVs;l8w^jBygW&q2Q3uR5QR}rMAL#y#C3%zlg|9PRS=q}~K0}d;3R~)uA>Gsz7EV+3 zHDp$442h$Pb$l$$t@>r|{k=f%FSIP@3cWJ&I@zh?4T}>eEN&m%lVj?``YfEH$cVc( zbz5QmgNSNF9UZ;om956>wa?2Gg(DF2nb+m$wIFQ_wCEl}p|O+86A!{K;iR#3PoJW{ zAD3z5aa5N*_IHx<`uW90>OXd!J@I_G14@crq^r${`LMirt#4QEw7YhRWadx3u;)Q? z?PK>!^Hx_9Z^#ad9Jd@fCmxfWzIj3iHQA!{JVbQ&)=Xvu#3i$?gk@$LB?d{61Zg&7 zzQE9GyK8i?0BLqqvw(|b#3WF(t+4g7M)pT@CUb*(=ikRw48taK=attU^|#CYyVT94 zv>D4q><*40j`6K`4r;C3kKXj8+oGKxlXC>4_LCpb8e8KNE}EfM7jyFKZUw_S+UPI{(Rgss|{P2F-L+0 zZ>){d-5@PE7JlmL^P`#ikuCOCfhl-Xrj_2%+~pa4a_NB!I)!$PSJ_Ng0~uviI% zYkzbPP#NBD56x8mBgTpm`ckrIKrj*n^riSg66-TEB*gaCWncL=I>{b2v!>KTGMnGn z%=nOh0hHQ#w6c$nPH(ilff66e%Az>GhgHB=C}bZce(T#oM*BzjRa3twRGy(H2cH`+ z0cqw@)s{>201Qsp@JmswFVXn~kcD9BDEP;7@D@Vn#|bD8eVGj`ei+y5-#tWbqW0uF zrAnq)GCUD&3LGaEV^N*SBbX%J0A9j#Pga9zGFHLCud3wg+{jV7onjwGMEe!GeW43( z00jVimKLx$Io!odz!4nHJnT=ck_l@<;1Ne@+FW~d`CH}-d z{YUaVl>D7}xAY8}P_Qew$Z=C$b`1|vx?Ewg7a2PW?R5l&^3fIP%0__(a65j#!I;^( z5Y@iVVsDU5;hb37)vxsiy-35{Gog!{_0C~UsWE1bET3((a0*rR6b zB~%5xRPna&+533;iC@a5f|;y5S~ueIb7{zs%bhEnpE`Yc9LwKyeAx^2X~}3ZIWjC|vK;gPZ9L3kDD~_y@ck)vRqDVPYNqw|~pk_!V>O zd5hos;Hj%$^C*RmTtKyP4~77^9NxAxr^|9Z!ms&zFSKLvB=XlUIH$t=eI~ie)bTfi zO{;Mx`*n&bZJ*W^U`U@=_JkBOS=+Q}(1Ul-K%f>0R5p({mroat@p}hXUS%8gNyBTRK9AXxmu`(9Uw&xhBuC4@tzw zJ3M%p2Qm%%I-knL--6kC7i9RzhR-Y37@uj~)}Y8+2W zCu2GS?eHF}?^V7IBM56#!izD9~m zdp(6S|!3^$VSq1Tc;im>!%^gh?G=u8#UdPr487h5OtyvyW`R zW;KaR@*0`psR)Vg`7u}5x&$pnGFXfN0991J7li0oY6A*XdwPtsdT+x$%%E<4v+o3sJdFGO*lnGbd#?HP2FmbA4P@t{ z!vU4AwvbDH-x5|H2X=*&-dBTvn$DihhE%N6Y|V#KI%tQ>`|890=gc)ADcoN9<@oSW zws^37$5XySIv2Opsx{aHNB@FW{VPQMoegIE`-yIZdrQ5bYp2iql{WmA!9v;*-miT> z!4bcG(V*^Kz27aQDE1}l65)RZX5Mb=AzC-Wd#<~%l1K~(re>g_g7*;h65u1swcc@1 z8>@Ri;t_tE=Wlv!Kb{1Eq(1%LWGHL!`pyR>r zKj96~ncq>0=rvx(Tx0VA75^0$Qq1;h=ns2aR(Y(#6ABQ0X0b9{qNsi9_{8Ng9@a6- zL+eMpgR#$~-E2qq8G;>rP%UlSOee*%?W5~U*FCNfRm9XzDL%j`a1XQu5;!9c-?{lB zu?WD&@y<|4+LTqw4=)nXa3w}=rH5+pHJBF-;Jny8f67b_r;G-wHzc18c5gVS_h#Fl zS{aTKe{e7s(R-u zcRi0en@tbc1{3GVQLATqT%=K#u}I1`9Zyj;ZoqHg^ZZ`Z73uKjF%ghGeBOzD*J$?< z`9gL9l{Ug_f5PBat}+AP6j)`kue9U#u8+)RSfzn=T&B;uq+?-)x|hYCpSUPmSRI>l zU^bLu$Lm|--J+98Y>x7t5}d12uMIjUfDP(E z*Q~Wn*rgY|36sRVio3w5kuQ#bRKVaO9mOzpsrm)MIqKG-xRP8B16>ZUjW4-a1Y(vc z?uc|P)gsT32*|!2A*$k6wm`-E<%}e&q5FN=`!nVFdDl3Xk7fA1wyMa#ne#aMD{O2~ zPQu^@9bd8dschWF0cHK>MA6myu_)&`v!1OLb>kpu>n)N9py*T=ZS++aU}AY23DO|^b;!}NyZ z2b`mT|Dz)U#(uAOAASH!j@)S)_KE%)F?ql!PSaOory5ij8L-eYr?yyNRQHx`j4Ieu@z>A5=* z2BaOv2;9;Ou77xW!Rg{fJ#kyvHvzK{sQ!F(>j^Co5$b9qy}0`#^mtoHZmO*8a&nMQ zpMc1S=c$moTelcqeGX8VdaF%Pd`WwDZMh#HISS46s%De@ftaa9pgUL>h0`i4@u;h% z%Wn4<&<1qMDY<(Z-iO=eNIr2eb2512^2m)sE=`xA@Y3x`c5XYM$*ToZ=%dL&+&7R%(*z*?ItB-e~$JY zAes>a%VA`jPI2iXMZ;v10gBRt+<#n!bJWb^d1R&cO$2o(zbW1-6ZB`ZiVA3BKfDkb zj4?8>6e~4;2yHq^dd>u)V^X-g!M>heQ&yB-X#eRz4Yy9bkAe&o8%QQd)qffPp|i7DqCz}9`_cstZ@hW@q;)%ALKS6 z_}4qjIr}<%eAiYy8sqzICdK$f=qkqrbux}4SADK2i>>LByD?I}2gweX2Mi~LGc!X? zxKkQ@wlicq0Dx@wi~Lk29r))S0$_m=w@?k!E9ljmcN%Oj+$WE7hH69_GO#6nT&0D% zyF~>TC*cZr;w$M)m4A{^Mf;S#{XX!w#C;t~+S)fMZHzN;O3wEQg7uDW%FGxrD9b>< z$??VWNDw*cFz)^GjdbIvhGRL=QUZO9e$7TxfsVa4qjn&7(+{QrZ#^=y=e|o{4`f5T~Wjy;TR!y(}- zs>rB&)U?>RG_C$gB;e)@Z95%vv4OoBZRhlu1}I%wE80KW$tkwT{x)xG^Y7J+B=p4T zl{7r1M5=d=nY{OOT>H4K_9wqBkR zS>ffkV^}iTbQvE<_CgANpn-hO4NY-)BQO@>l9Zx!EBHF3}ksl(^Jc<;*vRIKOMl;w40pRca}{< z8h1{6$Fey042PxN6-7=98gI8;>-s@IN!5sLtZl_yFVN&*qBiUfl?Tsj5lWkyCH zT5JGu|Fa1|P((W?`x($rWh~!-A~LH#h1(2VdbDxJv;CU6%as%4=2ynMZ?(8bA-E_6 zo+4@zQ4kWo)E)gsV@cQ4#8ei8jt5Jv9TvVM?AaT>-7#dDCtr{s>8K&^>G~S-$gUmn2;dAw7z zgVNOV^a?=2+n>3L5}f2iW27bk7yN5Pgy*{1^otJzS^yNbD6wTI<4Z~4G=2gf@Lqm@ zp+<>{<%>e64WpxVcT(1Y5R3NAG~X;H!BFr zVbl11XmXFwKC~{MJ=jm*dNsaC4l{j~pek9$NsX0rK=dlO~A2ABbWl zdwf-~Pho4={H;%2rE#AyV33w)V zjNJtM!(eTrHB5oS_IeDe&o0kPrM+&}BqIKgab6g!E7?!bD%6nUy z?;s2NtpaVW-$HDl9gbGa+3>WN0)FBw91&Q_pXTW<)rD^w67C;Sel5Sn2m2I?%F(cV z-T;jHEei?ovlVVx>jE7atRr&|;nBL!RGtmI&#)=I@_GJNI8kV80K097`_2gsSvg{k za`w(ee!Gq^v8hjyGnwt8?#r%DI*@qsj(_+i6>2+ zMQ?rEgw0!UpVk#Co6J$?aeIXo|Fa4UEWEFM-G0erTVT)P*D&Mtz)gY6!;Lu%UkEVW z_Vw_>JP!(WV~OwgiV?CuvrArZihiJ<-wB|n_1I-G%@^Awp$2?wy!xpqxsB zjo;%8yBmu<9-7u$(m@S;I40seOZ#{lM6BQTmf4p*9Z-=s)gOVG0k0+8(#N~{){qs~ zo!2SmMwLB3bsUdO0YeQw4rFlJpYeRZICBb755aYa$3rkb`@uR-e2)o4hCn=uu<Mm05}XyVbh8{}{y8=ntiJtW?^#Zdx`*GnD(U&{JMQZ-$25!M$Oi za%*<42Zp9{Ae^h>q)R{Lpv*3@{bCZu1Q@g_&wabX5Eg+WD0G{9W>V!SSxfgQv-iPQ zTYi+^sU>~m>N^~8Q=ibOWh1_s+iDJpm%?t<1oS{VbJd8bc3W-~(&~FQZUDT$ll%P%# z_lj9Jb|Ss}ecRW*reS1??|paH`909)Z)|LHQH=$4sWc z@st@fj5SSDYO@Zn30_w!n?EW9%N3xuK0#obvNhC<4UlaT4l-8cxf><`OB8@^

    JP6P&3lSpc0GL|=d(|KyyJljBmmx@0HYDZE}@MSvb>6RDs1#U2Q~8u zDc3g#H*2GTWW=kUyJ%BPDo!QbCD*-h6^IB!z1ZgYl6+7%Ms8(#d{4!k+pV8tk|; z)_#d$EPlTPHIU!8pFfRf+Uko)c71xd?1%g$7>a-`GhPKG{CaWbH=o&VOD(b?P>n8n zCDUFwf;|j2auG3RPk33Bn0A|~)pvk{L))%^le{vVy|myGFpkvilPOm?clz8JJ(k{i zt{fb@R9eBRARoT;vd`a36ot#)U@kA;j_a zu{+TwoD2Bc%}fG{KTqpWI6;P^A#D^NM$ulLjIn}4reGzM>CC(+-uMEnUO|vt%#c-b zPv{s4q&g{gECFX^esU%yF{!4|wSJGP?zTU$Nr2Fk6KaoFwRL|?zWJuYqaDA)hAfQt z0u;sLTotWDO0}5NfQ`+^`aVCZrv*%t2$8n-e9e<5S0otrqM+2n6eZXT)?S3<8Y#r4 z-ksvri5Zeg`oudR$rqFLabc!?KY}3f$6CQ!!K-B9q-Mx-`0IV%EK?nLVE7t-`DNeK z^q_bq7;Ojf4HX+BRR?sB{=uM+vXp&)c^n(;_GQj}PxYBloyb=9J~@)e9V`(|Q)SVTKM+ z(07-?ywQ-(7|&(k4LZE#vJ_Ghnf&3+_Zv$5->tB}rR9x8PZll1?pd_);qG$1%tziDNfl|E`-N26^JKNGR(h@Jv`};lB65=-%Flw4v}p!Kjg}{(Rr| zeT=j2TG?d9<1+NoPVutcEA_USp4optRjk&#n2z+~NtGu@s5u4jTG3V2Swpu|NwURt@P zzO9Gyyj?r`+RcifoW{ zHbz?z+wlQ@M9coHsETYpjoIlMS2(@ewK2G@ED2HqSZAGFEhBO4&wG=Y-`25NQMW9bY=KDWBBr_i+ zbk&1+7{z1Nk3b3fQvTf+)`s|sTs)W@Oh%S-dz{A4!1-`g?Dw%JI$5(t*X7X@kuqN& zhtko*>RM-(9Z2C@Dr7Z)L3r@|;$ZK7?VK6CIU{njvHY^W9bAgm7QoN@KH%OB4^1;} z?wyzQiArhl8{Iil7&M~)aJN1(YIezfgMQAE6Kr3hGHxci3==Hl0#80{fFhmC*_A7P zHjMUgLA(N1Mkr8cM-iPL#&Bzp*||6O1)NV~WyZb-56J7x8Gyijn|;`pW7;M#?b5{X zX_$(?2*)3Q-dF0*gCo-44$>zb#7uedW&lK%$f)RQ4EMG#^^(oGiI;#$JcP$$Au~JH zaK_P2|EeAoD2M1!J?=9etQg=wpi_%dr(Bf+ylTN@mjm)*LAelrySre|yqM^^FECT+ zf8e4j+o@a~(=PW=`BAKN9>-yuy{ zv392P3Q})PZZn5{xvDn#3IwyQzb?h9?s8zlH`pHo6$|1AySyleIb=+)0v(c*m2u#@ zA3^Sh2M-?0N;0=&hFDIJ)P@Z5V3_Qg_YSl?Uz_B`roRp#^mFJ*jE>vQ_V zKVbDkKh5*>Vi>ti^O=(FkL7c-o!I+0#raKr7O{iKWQRoW2v3&B>vkx-2fJWnmf^Cu zmjXGZuBhepW7fn<-m$>#S;h_$5Y=Jd{keme!>|K?8?KF4M53o&sxtDlH)?ny&`D3j zzbFJ@+|dvVFRB_AQ+#{x;qm$AWWmS};Wg&RFr_F~SkIKj7S2@cpKuYVQ~ppTV zXB~Rtp2xLTa%kKs07c*!aQ|U>4$HsjPx!NU5yQ&-*+Y&i`@>MCv#O#@e`B2yg^7<< zfUK~W?dlI_Pr1G?SL#|w&qMTzj?;_khk9RHvE)!vbSOx5X$v(F$*14ravkE%Kq&u?|o$XQ!wbAzWQngx$0x(rM>)}Hu7Pp-AL^R)%^AP=7~Rm z&F^J#&PsrHGaMn>pze=l)0wB8ESqyorgok?y}mD4Lz5fv9ir(KYb$*Q3Q2>edY?e~ z^H65X(;WBrB0WoP`sMq4HACOW9h34uJ{&A5HA$Mr!m8qyXkt5tj{s2ncNhx3dpKWD z{Sn@6r%)ofPhoM1V+`S=;Et!@`fYOQ_H_2u3TWs4B@jPX41-^<5D<*P43rgL7n~b2 zeX@nEhFRzGC)M$V3k%v~BU}sH?X$Z9g%H;p{Mh7u!q?0m1{-QpJyHk)e~zDDZ@tU( zwoi#17Q-uBGkvif6e)sUFRo!mE-m*baF%;HbZMB_x#TwF)HDZ;bl_lfVeCWj`skv- zNq(O2VDwAdaBuS+FL4F8-tIhkKFb&om0C1R@WTj|3&E?3l;qS4TZyoz^Dwhy2tE%G74N}`%=KNz% z5bMQBeh-%WrpP4Nt)lkX;okGxI?kNqmivy4SMUQtvsQ6!4{kYCAVH*)kHk@cGL^3G zU)A*aWtuykKqz77y=KNvK@43>YZs=IlRPQ4;AXT!_x;w#Nqq4)yu2@1mup~Z4*1!> zCrotDg!OQb>GMX^?Afk~b)Orw4(QL~?A-`t&`f$hc^7jSd388b$B0*eM##(Qw{?Z1 zC(Q~`tYP;~yt7Dg?$B+1I=fOLoU=~rdJ$q0T^v}PjH}Q7ggs+~CFp*~=Wkh{ZP_L# zMmOk**`R7jzz4;J`!^z0a2KC{g1~r3{X0L!(SPTsH#r|$z5bb$@*s=elzbo))|T@D z@#UCj?_KVfBs(?S)~p7iDX-KrIVkn{yN<)UAo&dd^s@+h_b_VpTWZmI`{r0Y0yy({ ziXHj;^+xT|gsE&o``|BYFTV;`GjF-r7o{p<;5$X&7W0=!%|`;}V6=alezr)TvdB|~ z$cyyQYzPRR1oq4Z5#bb2e3mvEaxrIRKF~8wm1utVFVs%XOkcFy! z%J2HmD9=A9m3mfJh6l36waNqe^2PY~bBR?e@oAI!JIwFlujQ*k}!Ma!6XzudzFD(5}_SmSiiq=`SE`4m#mkUmkaX` z^m2ry(>{HL93|0@WhH#-&lwlKD+~Vr?oMnF0Y306C+lghMaGz%AiN=WdYP%>q4VLb zQYN#0ywV`Nek3bGH+edC+VlIKs~OZgxmbwgRDRC~w?(!02nQrR`Fb|@k(LX99rZip z$m(&s$&xftn?Eq{6`x2m>zNJyX%Nn>Io|Tituc*Lvjak~RHzaSr5C5A4cNah9w!d;S%iB1JNR&>QfkBYrAd7Hm$!u=tv4C zxE$lsmvzBi?Oz12WPG5?A7F*w_d&lSSeNZusv(s1{p3`3OVI!m4^GIj3wDCzN67B> zjQAN(6!IV_@8%vG{`TQE7InF=d!S)G{;^dqTAZf6aJ!@MN=*z zu4IM`Ik?vo{3)(*a`tnLh-7tUy+ut;80tbO+|5@>1`b6`MvepeFkfHJMy=Wdm2m&)YQwupImfz z8J6T$(y+p+D^Vy29$cg!H%>;SK2();M!qj5%gHiFuU@7eLSu02+VkLDbx9O657HwA zT`y7|iC3~+0F-(FTSbCt_c%|F_|Y`f>;6p$4jxIO9pNd&_V$pna8?UVsDe40sCa!q#s-iF1zJNj-SARuUuH9P*@J_@xHD5L=FOgf<(Sq+>eG|q( zL1Y|Ej?^z1?2;bpGc13IKSQlg=?f9;A<6Y~U)~uF-W{u76xPqoYSvh2WQ2E^l_O%0 zT4N*LOM+u>qJ6pY_r3H2e+DLY-t0Ds0Wf;RI}7e zbBQ%>UPPA|FigNazraMyLO?4v>P0{V5M+g4$W)VM(+K|O+!MWt4^(_Jp{wdIM z16St!xtOf{ zYx@Q62QUp^e2Ies4jW2;Aa5pzJt*z#8ETs+`w^eCU8G$^SyxQ=$P_w^v@qI~ls^V0 z`9Mi4u)7uxDD3-{+uyOTw?f}p05TmQt&kq2^9-bYlEcSJZwGrk&i65eN5)T7fDS1y zW-E3tpMi!fM7e)#4g~5O_+s~*C?PQ7w3ztnk_U>u)xQ${C6BboRjaL(!oAu zhFcGzAiko9^rMF8wgxSqoW*xP_K^uUd7gX|+ij@XH9F}hUO#=F$SOWo?(Z4oGs{f~ zyAn{+VV=UrV$R88k5C@?Jt9VHRmiZ<5@}L75h~#K@=btMSvCNU#2@=Ju18ybG4=Pjuz*!wJRXFS#Cxe4eLc0gvUq~DyTSu*8y%&9zkkbq;D7{XOSzD~*!1oH zNV={?MU^G`OAcm{Vev}J7;EZ6A0ba)m1AT$@~h!=T7=bVy_W< z@TJ%D>6hM;tB3TLf1bFf^2;vQ^PIPP#;L<9Jq{j6QCpOP{ocTd!^;#mHls9F@8ffw zUUp*rj_%iUfR^|y-8<;oub$c7%_EOeeL>9;1OD&p2tUXBOaEwUkMM8sc87g*ZuU14 zkwBvq9n!ZxYFsmdKITW#%KeQ6O=qulpW*nkm$1-{mLrH#LgL$I{P0Yp^La_wdylN+ zSz}L-xSKQ+*c{zrMJMFp6+vGDpF}{qUw6R65&fsDnd|p+!^g>eb9(m?I9X)h56L)b zwARS?am&w{-1MAL6K2cs{b?R9wj22B;n$s#{Zc=qgn}J;@!dY!Md*)ZE1xZk=v)S9 zHn%X6x!17h2#jsSryrdnI~RZyspi)V!3vHOE|1r2?BYiBM>HG4uof z(wwYlFw(YQkKAZd7VCaUh>HD!udj<=z0V4m$6qTA^0d8n)+Odmf8OUZf8lk%%b&Ea zc!p7qF$^D12#1?;0Z$8u%pknxArd%CRTHzbY=S7^D;9Nn^tOk9W=9?4O5x54{*Cr4 zwus}te8h%hz}8+`p%SQ=ip~d*Q=+{!Ulu7E=F~08q0G;xg7w>jXEG!wg!Nk)P%sPl zsRXzOZ=C@Et@7Vmg^CeqCOCvTL#LMc4ExWm$;B~$4(7=2F0@Kzhpx3*R%yn4L&^$a z*}kZIhP_ta+Z6G-SUnx2>kSnhUXLm?>xb>C{D5xF-4D!`f3+OFAmyX1S$l|oDS0=( z9dV@6WxLY*ti?gm#_Lxr;7Q1NA?3zB6nqjT+`GM$wKS6q2@vn-P&W2`-d>;S+I{>p zI_g*j)vFI&dGspeY9&Q#EMTBU%D0<7NH7LH-Y$0(d{C*+zx~6B+5Gj`4}jHHN*IXj zm$Lk+ex=i{DB9l3eCC@|U+fbtg@D5}o>B_Z7?LQhfJc zIj6pUddmx6`yiH_J&`rfw@+GgKQL;;wc2i7s7BP?7#?pIP4;8`#Lh~9JXTlUo=;M{ zyy4Ks0B)ByQ|R0v>mA!Vk5cWQmX^Ks4e)q1b+k^K>w9!mW4AmtS~eI>LeO{n`gbB< zDElAR2E{h3;1ixLK63Z1g7;DXz#}WmZMdDtNPhVtPB?N;->Ut$>z3UT`qX9tqI`ZzzxP8t>&E9QU zH0(Xm0gVo5qLePT!n}T8i<2_7#q5`<{D4gEJi5mL+6L2Vi2Z-P3=R{Ik(lk8)J3dJkZ*Zy|f&XmD2NG#;@zxasVL{>t%K z9AQQ9Fjg9JP13?Uiug>HOS&g}a5U_(C>4gSC|hBC)BZaW{PAJ!V*&=stc49FYzg;u zs=ht}^EP7|pbX&#LNDIlp$u*N@TD(^VH!IMM2sK?0$?)bLMktXi|T@4I}cV{Abc|G zzj}n8UfuD``>AUiOE1dkH3Wz2&;Ay6TSC=@5mwmHJ)Nmt$HcBBnS0M3sVD(k8gZwc(0{Wzd4p(P!bwy$JfuUsq?}ule`R3~B4?lOg^6l4~Hb_fDL? zCo=azd;jIv`220WR8W3MRrjD{dh znwy&ES7*04OVn)DE(B@GTw6T%)cbU9bQ%iuLGk-Q0$cTSiOVWHahN_oT^<9l_g<$Q z(8@h`#2HrkTmMd;lV28?z&3x7GcOgTq5lI_W6u@ZOm`x}Tsvw3S{oZ#J{xZ?3Dz^2 zTa6F{M0{M2H|@RfSM7CJYM)K08;T4>Z;m&JBho7x(8uCku+DbJ024mSw~^6~CE$Az z)Y6rLuj}u2J1$E-e>CFd{7#k0-FmUjV$M9br}piU-k*xHKx0F<ijm z?8DeI=4HRpSC1g=Yj?j2?nJKcvoO+mj`p+zqG<^TfmhY`V?ZUz%0dZ6IJ5x6OsikZ z(9zm2szqoWRZ9d6VxX2b-G185fEngKS5*?~WQWw_TX(YIT03@FKZW)8umH>36ZX^E zG7o?$UO$*8U!TtUx(fYcgqo`V;uX+cxjwpd{zH~m2pS_-o>jS_?B@_O!! zA`pZ^wFiFDx=$?6Y{!!@-=aeS=Vj5l!*j-1CG#bnBb`XqjgWWbJZR}2 z6yj>%Z~tD#n=$WBg59ew%FGEnG8D)L;?P)(Wvfqc31;iD&!yl3eB_Oume>4c^z_DX znjEpP@t(18;R7!eb@+hK_IY`wb#NBz!^)k%+?*!+41gTy-68u?QDv;90d((^3crB( zy(Yy693n<~N4yVQtdg03Gi1qumQ{;SMR7uS5Ti)`X!qiHwZGh}x2VuRHIRJs<8|Z$ zdupf}82*?a&S&Om(a4>JE!xf2P(QdYi|ne+vhUc`>jHIwy4Ajv%p-^Syreh%%A0V} zf^>67SJ3V$_jul^OJ1&d`@L|jdIq!Hx;J!87)){$vRBueU&%RJAA|8CZ`kNZoNPt( zvF)H7qxH^ue%)CmKqw6XhwZ&*f_0QBU5yD4(UT-gNh{YKF1zJSb>H?90fkhThX5*~@~S)*~R^Zl!O;6U9!QJwA?no4=1i z$t~}h-OOfVrw$(c=N;Z78S-wga;qN1W{tLVJ#t2IiEl3RUGIHXpP~l(e0HJs9!yH5 zz@MH*B=QX~p5>nHK=IH!lRjxn&5<~2Mm8cw8Vn>jOtHEUq1pGuo;}lfP{=CkAsOGf=n_S6slX z7~z7s`W_YVH*$M3YUyh!^zrd2-@9*RRv@qSy!{}o^xa)u_$__^65x`8g4(M>nj_vg zGPRE;Sw#}Iqk?*?uU_W8by^(tubPr;6Ei|7rUP|$Z)3Ti;Ln=TRyH#@=~?@25?5^B z`L4FsO@t8sR95?1)Kqrcq8#4`aMA^qsp4+Y9gD~3W5Fv_(H32onS(5v(3d0p1(>w= zlPod3or?{Icxvq{oms8ujNsF);K(}1qu!)ybiV@yqUd{&`X0v@4`Y=sDjyD~Fc4f$ zfKPVprtwE6n()qw2>28)y(-}IEte_eLjJ*D%58gF-$K8+FYCEy&H$+4g7Do}^B-R}fci3i)1P;8`Ihhf zdK0VbjDmOi%(v2seJ$Y}NR=xIRQgUIukGSMIDVnCfs9ya0eV2X#Y2*^Lah?gnfpf{ zkD>(Af|Eh>ik!cCXZn1^*r{GUM?x3eJW1(tL`cSt*9sOsGx!bx? zq9uU{y}C>9Id78Nr!RAOF=pX^)Ui-Gmn(0-=X2;Se2&vi$(7z%M|IjhxFF%igOHiv zo!FeXF5(!ZmX}m=I-*A}^a$&%8ENwVqL%#h-->HgVXd268$Fo|v#Kb$n07cQ$ygkM z>#6LIaBdl`_zNbcL$B7kuKmKw))*@L2WNDy@7jFGXu8AEI=+2JPkBi&YWrkv@FLb= z&u99F`;H7+b{#QeKpqze6u z_~A?Ok?ZcmS2k_JytkLHBE7nC#ENBpB6RnX9^wISR6`SE3=fF>yB|3KTu{Z3AniN5 zuf2X#!JR?ZN+8WUez6G8esj?UBUU({QN3fUZ{KTh23aoZ`T-BxuulnZTc!h1i8xkB z)HWNUs@ua2xWp5E-kKFN+(z8PmR zxmTV}8qXUPc%BLFn5J#P@>D}}RplLFwmv~V!P|~aA1b|3*4xt|p(T5sRIva=r z1gnr``c3+uF<0i|N!e%%e2}6ZLD`Q3>UL;e!|J2Gssyv6F?s*%8=-&yzK-Y)z4;I= z(x6sKU0CwVA$!FZmx&8}7Fd3Y^h*V1caPp{*`Cum47KP_B#k$60o@)&XO{HmFgHd zqObI=*p=>if_n=ZJeKUI#T*@`-vjkNBHOlyzOa-*ZcS}JC$YPVCMcY@U|wj_dL}Ri zmZ+Hm)$cMtt^20F6KLW^+fAp)26sUi566PE^wT>HyuQBLk$Q2ChwSFbhazQBtoMh? zxP+@?*S=SLzdwexE`O zTrg}jijDj;xL(RO$^ayw-Y+WRG;fW&76YF|wl4apW}56&)_~F4)T2}U8pL>oDBN3K z96TcBn(&DD{~N;-J~*!2EIm3e{0K&jACvN>5SDKmvW(gLesNjX==P2A-dIxF$>szY zP5$lqPywfTa2VAeSKj+mCB;#HKkrHD8lj^8x@lHQCx-Ea!YVpeiR6DA>UgNm?4PpD zyrIdulG1wX^70KG-531JHM3{4UY=@jV?V)nd<|6!JuvEJpLY~De`-f4Ejk+OdT&T= zn@9%*lCTZZ{4BR{R&P)OvI0u+uTXS^RS(bJpnO%uGwe7z6`C#T8!5JiB8_JolXGL% zU~2#_NE`03530+v!BPHly{NT>)385id@<&Dlv`QTbo?vKo6JK|S-V4lu>4As8dd;n zeu0%7z_A4)$}EUSh$o}hSG^PKeKkHrEx_knKUsZ;k_If6o<_y&*9s?g`NE6+vz0Tj zf=dfZETb(+g|Yil>q5IZ_ z0adC;sk)$km>(yI+*WCs4D+D8qPo`4_b*2Y8_eX%+rD<~+cHDDzw}!MZfbxA%*AZI zi~<-E&mO1)-G1V!Jb3|g8?qsIATQ^Ixm^WwLa4znMD=>ry-ezoccEx_*EkJ5O?YBY zQ*Ctp1Jt2y>F~SgUT+oWxwuond$Ae=!8Suawv|@j@$vzjedzN^m7N6}I0MV!7xfnP zxr+Xva5T1Q#P9Mp0cOSLhUjY43QmzPGM1`k14gD|1#yWFTP zhiTE>iA&T6qIfnA+vCBV2R$u*O?w}?kKR>~*yvtAA_jq>u->HX(mcea_W|T_j{Q2H%oE=_)>nt3405iLjiH997yvckWA`z=^h17lT}~r*k*B*a zrJk_*_E$41G!D=4qo#NHoR2YTf*&!&w0F4J;1QmLcpV*)HEL)I;IVrrL78`z8dwq)%kI7 zAyJ?uUKd}ee4$WWnn}+Nx4CXU&#ZbR-yky-oBnZ`)Ipz!9?E)-m@^vA2@7MR4MN(< z4Q7!je-!*Q+`dQCxOSA|c*p&cLTQ}y>?J^ptgZ%#A3fi^ZD8}a$uFj~ymTFE=tD;c z?1FlI-%3>(KfkN&=Vz*Uo=TYa-U^-OLx$AvPOyKor2Da7?{t40lJm{tI`gW(tIJ*4 zr=U3L(w_Fv5BJn`KC`b@6|!1kIs^*-K?GU-3R6>vybsSG4f_LIb)}K}(L_^tD~g}# z6ojhO@AOhKin2bV_j{;-sHl*wbxN@chQeIhjqpDe)n-oSZtRIh^A}zTf}<> z(ZPS$FS`8ve*SEgLo_^04ux~9gvW)v0SbR5UlZ0rLFldzQj)H#vR2;*C2g>Xm>v_m zYYg(yU9nAQ;1kdxRft>HJzQH%RqC@xN>PNzllaZd^IShp7mB^gVA@&az`mfW_m=N9 zTZ76%@F~y+=3*cQ3FH2k^O58_ZJZ{&Y{xh1gz*6)`;_@Q?J_-lD^KkK|9U@SxClr? zjo=1OmW4@^9rlDO)4FNfualPxcN-hS0v-vUt$w1eOMP_s2G8}Lg{Y=xlEZMd`vVpW z_1(lllD`GKtbs3pxHGi3O|t@wZM8Z;w@({89vaM zT=M4)eyqg+71;T1<^C(s{cPXEJA51?h#lW1$hFPkF1=d;Gmih zBYE}Pvz|zp2%Yxf_x*kECsfU!DI|Ev))b;<%&A?5RO3nK{CTSRL~||dotIUGzs8-r z)>ik0LEe%8HbAie!QYcc*078&G)G*nuYx@vR(fY+d8j!^9JX9*t&FfZpb~Ki0 zxbJ2lczW3fN&d-oXdfm@f8pZZKGkD8gK?H)gE8F6NAyS@S7GX{~H7>;72ZZy*RR zS4*}|hpU?hc7G}RS493w&`6ET;o#-m_i|IBO&QJREhJv8B-0bwg71QcFpxmSx^Qbj z8L+y)e&ySbgfrRzF8qahWL6k&0#)Hi69_8Wozq4o<8JMd@-|uREhPN(T7AwC{~E}H z_crm$^Q2!oa@;Jw`}lw&_}cFjW!Ri-o<+wRirukzZ(l7vANJMcb?Z{v1bP6ixr+=F zD5>?_aQIz=bLL5|)@~vUrUv-IUCGmr3Zn5x5+)CIpt{ASO*;hbQ~4w>l`UrXMj;ts6f-mK%1DB2zp8DrFe&_bDKsMrc1egd=+t z!oux&RRV}E%$bzuelRY2c!>DKcKe6`&)Z#*a=hvw~8 zMC;t$KbW}u)w)OesaaNo@O@yy0`vC^gIfV(763f#<@WgQwSW_xHq?ed4ZeIQT-w!b zBDa7jAFa|-o}`akv7Vxl-h;$qmixVdzjCrdL@ayn8RughY{Ch09Y2ezc>F%K(csI% z5w4}poo??4{*b5S;z>hFU9E6E>==y>-zYx3eK}~`1RD~~sIQ8C2P7bE!^!`C20825 z@27$z`>?RLlWzM{!8ktU$tRo>pbwvTZ92s|BUAgid-+g^S|h`02*=~Lr|TXn%)-U` zpt+>;aBLH9F>EZMPgqmKBNR;^a=yOdmI6m9j=`Syfl;b^_Vyd&{%X%RXP1N-Yffb^ zGV`F0d#;c;=Mmmzjj8_JkZ&PfP-kNQY6lq!PQA$wICCnl;jjodFcze@U$wNDyPN{yM|1Ue3yI3XutMM{kQwmAnT3)<#Afh`!(GaO~c z?-?m^aNk2cd(W0(p|L%4tp5ED&GjBi4H%dQ_^-#Z|Ce6G?e`-Z15w-PwP#H7mKmc&NaFn)9zPLKJ2d;~I5*;*wC8~kn$EVH6n)Rf>%wkuDrV$of*2Jc9~Cp zb?VH7P}O#byW~EOs^xvy{(a;!DCFEFb;dW|MFp7%HRXdsl9~5 zlioK`mzV271QJ#{Zg5ntgqM_EbDEEE>Lbt59GRDjz-u%2i_Yq{DVqeKazF2t2s}Jh zJ};RqOfa&%jS}mWAMr%RF}?B-j?2mUgO%N$}Wnjs)Gg7G|gK2 z>C8FtD1F^Qo&Zl$4$_bR*-(W5z4`@uj`6MuIov0xJEIrB?Kkw52WJLsT7n7TZzZSA z8j3$SIz#bEq>d2V`I8ddGV>uA(4hulspZ!aIJK7kv2gPU;p6oL$XGuO(HwpX@AO4M zW?U9M2^3zqxNscyr6L)+uO&aeD)FszdF(-h~F-Or;i z=wMCS0sLG0ePGr47tU6DCR3cn;k@qLI3Z5rmcQ30ikx9JwBrMXyl(d}yAs-6zKyh5 z$uxegj`t4(n(h@#PVuD8skoWEYfEjGib*NnMeq!sBTp1}vO;=$gfrPTnxG$X|X+s44XQ-o9_kCy}oCB!lU)sqmG-gphy zezZx_8_15#d3^2h&?QqA=TLeru4mAMPH>Sfy<|VbLD(k+AIFbJjq7iphaM6-Pj+AEF+=<7 zqe#tsRG%OtCr7#|#H9Vfi=I4H{Yg^qv6vb6J)6(o!LF>s<0}B#3ul;Z9%}lf`wBUY zet5scclHL)?ij@Z_936;)(M%6Yl^7xdv#W|_KtHI&o`}ss2x?wm~+dY7nxO{5MaT% zSKsQH!hqRDNVch_Ik=R3C7s$O#=sG=mi7dbyJ9^Wn>dP8rf#I)>C=gWUj#CN13d2T z?Frh(piBfiO!GNB z$J{5mNqC+0Sd$a+)xFOPA}F8IAUi*jlaNXFCAo-NQ?9&2;Tfl8|03mW4es*qJ{!cT zLJit-_nCM;%CubBguYg{S_M=ld8YzqHTo21el1Wc5CEqV>u@Kp};CyMs1gbw{k}^Y3=FKxr61 z-O+rE#_gnRaNtO}KPB0{WO2z(qIz!1Cj^PaZvDf{&=-`u`EL9y>R}{qBwkhtj1R`d zc0h+`iWpUjhoO@-8f1B97qQ?yDw8WYAIto?QfJ`RUg<-T@B2h==7!r7mVG|KjJZdk z!)=j1!9L6H7y2lhm&nc6{0XMsK*GuPMHff4LYdkFZF(SsuU4w&1iJFV=L@5>^QEJ?q`PH)UR;Ru0Woed7~qVMhH9g$O)ZncLVaRMaxGNd8_ z;7t^>5H&{tRQGir;_T$XIGyKT^~ztDF^$VMf|?<sh*C=RJemqulGLQqPfg)2CG(qre-; zlM7~g=!s_r%o%u1Coe#*8TDosz4yb8C9pTWB8DXT!4bw@^#+Wq?5C=vzzniWH3OA|2$%U8koQFiZM%(bA|QH|0B<@2N`k z5;h}NR@IUFc<<4Yi-P`1&`Hx>v2WnRL!&$7{WL-)D%ju|VxK}J(Y|uQ1iHG*9+M(k z8<<gr>_L6J;st$h_bdbhY}7mb?cr4`aeB8RY^3$;>~D&8-95I}U^cKJy54Gt z;o(wFUUs=OO3L+T+94B51aYT(9~4Tjim(Xg>%YCfD1| znw-Z%UcpN|p9Eg4PaUzZjC&Y$IvM03v|)%0)J#0sm;()p@ew4X$IpK1*IFoVQI3UB zXzVF18J~wtL|LSlB1rjwyceX2obLtsN&-3#@u4xGW6VVTBkjYqtq6f1D?@s#-6M<* zqUUaA4K@OktxEN}z))0Y#)%WYTmm;G9RKAxr&)&hLFcZ-fh-;>B7CDE`gD}q^b5-{ z=Wr>%uYNv!m3^hZJ0onx6c;9>Ne7CbLxDi|Y+Nel}&*~JNaNXaO z4Tn|tqw_&PFm&erI9r4BlAkq_W#KgH_CRkx|4bpGVfjbM;h)<=D$f~qE35v2e@nIp zIP~YXZra36+Yk?(^PsYA5wncfv7 zrNQBWe%_@mgmLQ;B*~mRt7pkp{T4>fvzv<4u=%GB1&dx3_S+`QMzBH>m-Vx{zYH~* zUIj5C4=@n}iv8tYnk6k)t*q|R%e@PVNpR6OQ|-Pfv7P_rd!{2m3sZQd@0PwYk#^vt zY{n_@?f-swW%|6Cn0q7!c~cB>25c%8pi{BG{>;fP?iouH`maNX@2Pr!9ek#e7h3&d zdzY@)>-u=P>-Wl?KGaPZ!(}vZ%zd{#m+6r_{-XDm>*WD0E=ceHp!c^VAD*UGiMd># zn{cLx>INiWk_qIkbDY!Fq4~>x?-b|2YDVODIrO`Q0y3ZPOHQ7Lu*8$!9(nC4d0Djb zFyGt@0oj-D)8kB6P70b!N*QP$MG4Y{v~D2K>gPW`#ib_AeL-SIR|dWsA9Q;Wup_Q$ zQp(_w;`7brT-n&C^9Q^vDmU?yUZX$4NPqjY%XmurV*YZ*U|CZcIv4{Uz73t$I zRq*X02AzLH5w3v2PMhLWcg^<8U!@Nh1@8n!r+`V{*Wn3W)0=bBp`e%!>XG^Qau(`w z&UB7v5PJ@UuL%WPa`_Z)k@fr!X4J&ZsbGCb`zP}Fu@ApPe)=d($^TYZb3FhJTtRGVs|bO*|QE-;i-s=4~(d ztd-PV{cOXtZUo&wuS%C7!{G?wH~2W4 zNXndbU^9eL=m^9QZd$bSRfp|>s-uj<3sgON8(h|hR#ARm>mWBunVPHYV5({pn+pU5^g15t$Tqn z|339ee?$`tDSs&P&ahMaIi$rN>Znnms2&hu?*kICY;}!>e28 z2Cb-;T=nu)l3;a&zgv`U68dFBV4A%5ob$YPT7qL;?C%+ED7f^q8^E1rhBXvUpbSb{ zY+E7s$N(7PA9psVs5ZDag|r`D@Z!)?XaKZbaY z;Rbq*td+PeT5LK?Oiz9hs{z^{t?64N{6&tF-+eUb-+`=eLAMcBuFPhtr_@|fgz{d~ zZe+znw)sx7Ir)-$|1U0jdq!0mr*etHNUzJjkN8mS7k-Dpz26SdD{_y* zx6-W1gh=ot?m63SA^~c+z$T5TAyW%4-{kht33A$AnE)NEFG!AOJ}VwRBIbv%WAL=_ zU>=EV3b`fGnd;boJ$oFBYMg6Md@p*kZ$c6#Yk%%6bj)a?e~A?P2(PKO^E;7z{^?|x z{+A?&hE=jVKwB~_(nB&!qOZJF`zY#Hl%I{Eoz3Ze6=+;h!D(YNhPUjvxw-3G##fC{ z;up%SX&+!F<$YsQ~yhkrg|iM zZz&+uBQUW(wWo2iFJfWBG1Vz3+)n;g09K7_?Zte-<%0n$>uE!(t1a#I7QGe?%xY>8 zd%J?%*1n{)L6&}Bh2GA)J0#CmU2-^@Z#b)WPYxe{3ZX%ab&WS1UR`4Acn3Zk$;?%$ zX5|JOqV%U){{>OdBzs>^1{U*A6xn!-4l({Ihvu7k^#?d@Z?m!oWS`S3uV3W1u+{Ef zK?v{AlO1Q3*f$#P9+mtobYy5Q=e!o&u|@e&sg=*wyM&Wj%iGD|Uz|t&UP~HEY7|;C zNx-Vy!v|m_JnltUAuzkEhbW9G?|$!nU0M~!^e+f$=y;=9;moLb=$Q#74-@E2|^Z@*eCM~hMiFC=*n zb$8Xxg4A7pC#{@(tWK$j+l6h*r2~n++$8(@w7Ru z?><>@hgMX4gi$pnoX9^Gwo_s`n_R5~3MO&d32XL4UgG^gSL8x*WmgG3R^&)FO;S=(a-J!W*H;mkQzL@0o~( z%ue!Q@b1(`M8cIP$|g$v=Adu~=}ivb476q-(tI%XP02y7l9D{#9*6YLtJ(Mt?me z8Wr%q`oJ7We`(oWeuR5b5!rX2C#NwT%=#jjKM>SD`FIwDZwOvKaW;?dWv2JLThmIE zI9lX~jq8Ke7XJw^TiV;)5LK)UB#Z|Mzkv>p95<{Q@`+VVto>*x*vdZG?+*9mW9nWo z3gMhDt&^7n0)z zVWo{egFFgcGJ=Quqv?uxUy&Ym+Pl13GW_-8#stWn-|#KZU2r8~ z1a9|2#j2mGe1~j|#cZ8&vLh(9Jm@iD#vc>@K|jFTGe;{xE7`g;nHo-GqQ;xN)`l(C zGei%Lq4Dgs#{!(yMp`F~r3z{_GHxXgvC8NbR|g>cuU=#q>6iR z1cj2g(tpN6E@eTVOL{Ok^+1WP&av|{j>i{t@{hrK2gBMv&4pA4eh8_7lVBrOy@U{X z2dI_A_fY&<@e!BPvXsDc;uPkPo=?y3+@guw-yhAxs;TB+%N0rHQFAI>@$3uW>aq*7dWk) z515$3VZXiFDR-{DWqc}6QRCG|IkhX>>yLOGZV)61A=*$KUZ>Mct++68Lf}2C+$*6A z;aq@RUdthV-?t!mJ85y!l9Wg>mG%?}D-s)l;iGcu1cp+T7S+O^;UYm%%CfKhBk`(B zSlVHz2*uHgXNk$pu}KcNQ(5xX9;c`4CaO}}BF>Wey;<~cMQ>RL*zmYvIxm*G+|R#! z(mr9Y41aa}Bm5#~3_(PNAJf4dw)-Uvl+YUp5bVbsg_R2LD9_`dHz9s8EhWTLoK4{y zGAmxy;qJ&mz~$>M!dEefSsWe%krHW&FrKHH5FkRQ;Hs_gJ9^K^7!s1}@ zi4T}@s;>CBn$M{9!Bn+xXz$mk?kKRm-y@^MnA^Pta&`6N8YrsfJDQO)FzRpawuK;% zUUSmCG=5_#bdutbKCn9y3PlTbiHx+WsY4ESz2*{*0LZEXw0gp0efCg8sh1V9(dpF< zAwxJW(R*JH|1!?|L3{p^m-1VRQ->`FH4=<^1!wRj_J5U&;G3exE2>){EvL3gj(KgY zMh|Z#*>s7@G$tZ>J=Jg04JpW%w(lR)9|kAU zC*wZ7tRMsLwt)U_xTeSa1jzXfl{!ggIk>F-=GuZ55bEQCOK^yfGK3Q!KEz`yFfWkKGFD!NH5yf&ti5}7 zIbZh`@%wBjP_hbHZ?K_7r6Fon&__YwZ-nXGC#f(qW#*;y{c=h%#h!GR55;Ii@E0xE zagpxUA2u3-au@K!)vIyb^AC*hy9W~r9cS~428bx^m$K-(iN%5V>Gw(C{0Y-JOJk1*X`uWShCZ6 z%00ou>y|Df5^{N{;b7g1ur1b4l3q@+a>tVziX&ha5f#>{r0Y4;zW>5Kv(ILyc{o|+ z$l>q)G6$a+5d5A!QeEl9EtMseldO4@C z#;qp(2)g95kxP+Q;V~C^?r{f8b-bj5$81-~Ex$yWefB0FK;1ml-81Y>sUSU7`_eUB zjr~01Aeg4%!k?9gFN%-zj*f!O=nE{aSAMXAllux?4PQF*X4iY@VQ&EX0e&IqcSe#N z&%$WW+nD`+HsZ+z=#OvuJdgXj{4#`%>7~PT)*8xi_42E<%TsXZ!}5WU^yTabPv=a0a|GGr*tYnL3%p`VWxY?lSzM09lIAgW z(N#)|uAXjdFb|y1dv5h(l!p;bLmxyTPgwOi@PKv6`WCy;=FKa%6)2FsYz-UA@L8aQ zQ+N?UNBFKi%CL7;4vo0EY5>&rkvmUtHVLoH9t-Dd)`P%ayL3w*KgW<)uiQDB=HC{E9HZO-zFkBXOqn?83EAXB+ z?u`{zWn59v3~nii3_0rPff^hTGM7Ofu>3-dW?&K>CEuQk*_K)$tNnu|tSuJ2v2uFS z`!h^}6|z<<1&{{Q0iiT!XOu$*NgsIc(pe2W@qVy|jU&wZ>qDeIFsK6#@Mw4pC-I%Q z+T`^K+85O4Zwl&RGu$l>o)}5l&wZ<~P{X$x%(X|NMATTmR6&})zq4WNVX-926`K5a z+ezeZZjJ&&;^pDu+>aa3j28r8!62v}|KQI-80(Is2K(vl5;#}7Z*l8*CGqe6!Gs)A z4A&gj5vAk-2kkw(J-cU@94Iqgn8$gcCq|lwsAhl6+&=boI`K&5XTUasfk%zso25ku zaI88^h*kLH4^cqQv!9BoPedCwg)i6%>_=?HFHE6XO|TMs3lme@$Hv#&i{yegNW#&0 zG;>DWlWPaw-_6|j0=h79+3UBzUD|hqXhA5#d+y`8` zgXL6|Cx>fseSTuNoKCwk=$`(exYjV2rTY_~dh0hv621(($384tycO#6Ov|bHbd6(D zq3UlU@XHS-X=B?hzNdKC?-4r6qZJW@LZIG~*PgRi4e_A?Kzd~*^xMoSjz6jw&d{H4>=HfDKCSdPeZaiY zBR^eowAL>*+!iUHyzX^KMn*g+S`>+bYn_C{5OxYn-lOt!zKiLxzd_fdD<=ucOj!tu z5>;Rr@sn%W0j4h>emCZjjv{-1jDQCWA(AiHE%j%AIX!NUK34)Uy~un&R5cU3fuwLc z+(g1aR`C*A#^!tgEY{~S%+X09paCg*WxL3H)YF@rIZ)a=K?-h3z}?#50($0c^I}=I zQ)akl?S8z#whPVbZ^t|0i@qK1e)iR)ZEg8mH_nNa)2w;NJ;PpV#Ud`4hYyMo%Ac>^ z5f8h!<5rCR>n9|~+SrFPST>zoJU#qadycfMR!doA>*Q5LQjjGfWk_wk z`&7wU3cP^dV^UGP&MxM`KBd1f29RQODsgP_L+G2)*dPleXcnZwv~Gyv(m%1{t_{)!Bc#nf+?=csqMD~Gj zr?5E{AK!hD4}Dei?+DftpTcpjEn9w2OSq2*ntbeC7hbO3or$T&%dIl!55Ze)Zx4R0 z@>GY@yA~Dx)aT|Y`n*qAZ-tZLHlf=Qdp;uV$*m#12=96x>Vw8D4WSI5y#p^00oVCO z3OilE*I= z=}x*foER4}n4Y6&LBLo?v1OKtNc7`j1Myfj!gGbD`5GhA3HeEXM?}#!41gQ(^N2yf zL90$8zwXE!z!oENe~>|&7GO;&-JR!zxykQ~fUn%@s zUm#C*gT>$_Nv4(rMD#-Cn7_12~~<6y*atjo-JG{Y0sBtPM6*zWU`HHx`HEmJwWld zwdGIygY*V_u?k8Cb`Ws?Di(J=DDA8>JHQO0>I;@Bo<8O(saJ31 z&`cnp-9unP zmbZ>|;30vQH!r0{icSOMMOnk>eDKlbJ;Iv)%^-`x>JhUE*93b;({+}*4ccg`e-1^b z`gk+Y(d)eDroB=b8qh~H_8+Mbsw}juJ4$a_=B+E#I$hy$oHXe}&clQ&1b*A6Z533! z@Xg_;a!~eRJ(u43gjE7$uWW9<&HZHwuzpn(qR2PBf48qrKQ1?+#{`|)r+9svml=Ry zp7G1x1enYmngL{p3Cfe>^%&xq8boW_&%3O!lm56=N`C9@D=g(jJzSL>oUtBAN=9PI z#F{VZK54F@cAOZ|MvwQy`+i`#RU!4iA4-B6PdOo|@o1?%{O9OM z5%j$xhldu^BV^|UyGGmAMdAWiQEPb~R0b{Yiu$!}YOn3kYr_>B6bDdEl=ye}=t{tO z7)#N5fC%d{e(83Q-Q}eZ5<4$%@BZ@jOZKHKAGjl3K!+vZA(pOXZ)j{|76=s|{q1s! z{EU4}c?2)vEjYq@QiB=ARnPA=b(7IxDc%J*Hljsn|3uMUeNoPjJ5|()`QCW$b&sI9 zhLp{#weS|me<~FsLo?^~%zOQd%Tf4TQgPXx!K8siHpO-I!-p-NX1m>L9@xg9OG0;* zNR?$068eZDiR;Co4R(}#77#gK$JeU?Epd}+7h_t3l2O=`*pW>mPY;rk%Rf3e@>ZVF za8D`tAO`sCOCGZsc<~V5rusOk+R`{9#wnb>2*L+y=3gy?(V^odQaYACBkCX}m?P4axe`mHBuOZm$;Uo4yT+ zm3LO!4~DYe-Z1GsaA-8%tfJ<@@x2>P(JRG!V=4Md1eD2e1asIFg*>wN4hi2YukJA6 zDUlESP2{#7p5^&`;)^Yp<+7LDe69hD%@P#H_RrP6&D8nWhoxIw015Y{hn;49#eMbe zB(m6tOg%B^RF6)2n}<*YU9ta5t+aYl>HNk?V5EJ%a66Adtv{g%lUI#TTUMb(vR3sD z!fVvbj-QJkY}`_3_diXu^B3(N=(kYGaz1FYdqJ417M3LP@5Db5ZT#y`WJPSKX-GeZ zM7JRb@@Fo&sxlifP!Q?XzMi&}y>s_zP0RQP{L7MDWnGnK`<0%`&z8Os;O_n> z5}{u7m(hE~vr0yD}zn|pu zL=uu>#pAm=x#@c^zz|(=Ng;QPWF@69&`2Kl30toQ5YHS<0*X@Q#TNg<72g({JY37poJ}qQl)S$5oInCR>-iyd zudf#6@24*ouexRr%3!XczX!wk(?Sa9sHNeOk9|D3^UciQ8jad%hGQlZT>BVEBlc5v zX1Kk5&r-kLP%QwyJ4*!RGhIKpt#^Y7HNG>>qmww8yP6$OA#HUURhWToa-n(O-1qy& z&;FryW9)&Wb(P&vKZ$PWo|V|deF+}kq$4mFpk}d`GhczB=f97U#~%B0(GuqtR5Bc2S+}X_hw%eLAo6$60nH$r1g34Ek><^Uvq}B^xTS zn1@dnuE~SiG(m^C%QC+X&&f_!a`{vVZ0sjTQUl`XKE5yos4`u7cprcoi+9G{($U+; zvEE3Sm z+c)pu{Sjts(Uj1oU+4_69UUum<;18R!50|=26c=8Y z+efyc3J8Dk(T3KP+P`(So(fEdgRQ_ zqz)B8sOVR2gqyYBwF|e&XXD;76Ll2}+Rp_Ja(AHsjPteLc4DnYM|D{sI1L*N~S!|jfO~~8=qVFBY!FZ>NP@Z8X~!RW#P={ zc3g1iIheBYr07Re$XpPPN~2R}{RSON@@5&q zPVW`rO3{Ax*;yzLQ)j@W7yV{IU-jgWURgC0w&96kL66#jPJDRb?ZOi?!HJ z^1L*1bvq#Q+Gi^~CA`4s`a+%NL&$*@BO{#A81_L_w)Pn)ViE3{0q&+YQe9}ROh|_5#Jn)6TWM}Cu~vVJ z$%^b@+WW^Ot!VN8Y)(HGtlc{i{=~5y$1whiwYJ##AE_R6jMzCoF(-|xX8V1jj}2$hhHi_1M=238zj%cWrr_j%lT`I7%K z(!m|@Q}g9;SC?c}4t*F6;&1@@9-xNqL-Zq_pe-_1T+O%g^DJ;F`3iIN-r1XSBiBmBBUj1p_?lr79l5?45hW;F2eO~L}Ni9{nc?NB)u1UJ^ z`iVj3#coh#5AKmWu~}hjR4hr1W>by@X`uL_4S9=@)^^yMlXq&*xP9 z_6ZvIm5vbyt>(=6a!=2!qMY7g{wU|vImA;1C>KT#T+dagVerG`DRPecTWc;(gQz+^ zHVem98d*QA03DnOvRBmwh-AJ-UODk_++@QuFdvSfPkkNhF_;~_uS>5lMKRp5$+E!} z^==+1-iEuv_413-{S94Jy1vsy?T*Q{z41!XSm6+#qK8t7Id8m~6&+GZAhESk*)h0P5t|r`un44F3F?`ThV_7TD*$U zuL?;;<)M+;ds^kh*uUPI1aAV4g6CVitHm;!|DMl+A^+ur23P*vYsY?@Yfr!u?dtID zL(kVlof#Q?IgtU+t{X_0WM|GYzkXnoFn4 zYjMqzVX(I|?ZM+zi3loqQymY3pPB$5a`!a9J{a1`|J)~CAYCtp+moK%T8KjjD!>8)5n+)fA;Yr9Wf@Pg$I!w2TbD|zq;gUgBIm* zeMUD5*t^S$2xBr?LUKR+Uk-kp_gfNE>H7q}{V*+0_NRVR7o0x0SJDf=?&+~KnmqGd zUsuUW&AmZYBdb6s55Epk6Ii3F_Q0ptl6Dg4Iz13I7TlCQn*Hd{LA0k+m*o3C${)CN zp!vc8aP=S&CAz`A*=;1#9X^2Oo$Lb|pe@THT~_~N@LFRuT>u;ooc`hvEo{+N>sa#6 zgFYUg-ctOS55tWpGJv)~`^PjLjwQ9q(e;+<%~TYo4=X(#y$4J z1|f5ph|EX#x$nT-2I51((*VbTaiZJ9EKIm?;o}gf*MeRa zZW&wNQ0+$Ht`*t{jS7}Updy5KTdi)KD(gpY-5AUfAM92tM|(gPAX(GYH&Q0y{Ut!L zNI5QF@u&pM;g$W6sYzp}nUy4*(OyBhukd&RJmijMQ=D7^nLIel=D1I|XZEbpC@lNTY7v>3E%1SI?h1lE@|&W2<)f zReLnjysP6i)!Ig*G1T5r3id_be7>5O9QITg>Bx@pj{`ahh#&FX6N96aDxKL)^Wl)A=)ASvD*NcCd{g)(+z=AS z-dwaDUf>3N{CrUetbyYCq4x=T&**2IBojUlY0R#xO80el4GL=(E}`uVz_(M$H}O8H z#Fwk^-7qEH*#nibfZ^(|f*#VwfFa%PL8sYStd!6O37Lu_v4@MUwKjS{;#OD|1a9Al z+lL#pq&Qk~KR6_wAbIo+CZWXv+oK6fL)E;T-@nvYtq+ z7z^$*e+|hd5nyW&Yw=-f;MK z*XA9rqW&4-55`%??{YYQom;eLFdE;PXMO@8EE-5NJPHlr1o^oKHaF9!tkFL{Kn7JpJhc6xKm?)Z5qg@?###KHiNtwEMNW z$BlKRg3+0%{9YX*H_NvsH^x2OYiwLf?ZywM*F*oler5O((hM#wb;^tzU}xlkPwswQ zA7gudU<%d_+OXJuvfs~PZ2R-*1W+^(8EuCdj95Pca?8Pfhu0S zqw+?fIYG<$T^{gF#!rmFs*>j|W<{v)F7VdD!ZIy2H}ny%fv`b~@c>Knw125_^(q1{ zf=mxAj5_V9Wjx&;vzGcNb~LtYqyA5Bpy?q)B>Ke z-uBqW;N&id1YbAaJJd|Ol}xrW9fh&xRw|>}FNJGKEEiG;Gc&?ooYkYk=WDF0+3wKg z;OBACj+Rao{R^xFYUN5%JS*=~U0}l9DuI7yxde{uYVx;UHXF(<`>N_*s;d<30c4Rf z&JnnUq+jJ@G;Hb8KhZ_c2cYsZM|T)F^n1oIJXEc{f_AbrjhZGyE7m0wdlixB&+7RQ z`^!Hxt!l0#x1iJ}dBzK2V#f9NnSs+QYap5!mV3plr(_wWJ45@vLcEDXUXNxHeO?25 z8-xtp7&Si<;=~L;?&f~&+evx6xSK)W(za{z2|Kp?42d;Yvyb<>@O? zP|!}DC+^>aLe?u53*YBYr&ISfwbVxoT13h3w%|Irm2E9A<=S%WWWdWK9s7pciIz!i z%F8{_sSc+Tf3N*@BmAR54(6$vjanRU_#O3(R5Xfw7PqTh{M!?utt0#b?FpBpo~I{# zuKe1uhTNSEyL;!TGm?Pt?zi{6K40r9Sx?jK4nU>fJ-Sahc2=C~m=e0Nk?EIcc4(P6wy*Qfivpa!2ibnELulV24u?qfg0j>di)xSO=q zAVTU|df_~!ALxx^kDCLI%+^1gIEI!a{kUhaxr=kZFADpje`^aQHvPEkOaz{%deeRv zRDdzfN=(Zy$;-!qzx5+5gy9(`n-bxv4}-+HL1cVYvLgu z=B)63y$|@dCm}FJ0gpdriuXLE=j%T0JPwV`cG`h@Lc=I2ouP`pqgP;)2BTkpX$yqE z<}2`?iy&0$N(L^yDs#^A$WUUlCrZ5Pur1td{JPuHip`JTApL$3Vx$=rU_=3NRpZNh zbEH?fFMVj7|jkBw)U3 z1TYBuiTVT|4@0}T?&IK_`9rD}+#&l2 zzRIt=J-z*eKW(6jnvuBaips^q}|)E1D~cv&Hvxot>{zzlGP3Uq0~# zkVU+Z_s(KTr5jhJ@EZYLSuPF|Ec{@}64}NNTff`ut=#sRg|>)kq85E$WvkNoj4ve6 zG$5o3R2ioV5RPcArkDYt6wmG{5Y36}i90-{ARRB2dv_C#oz@XUU3;fqs1oKr?C{*n zn2L996CN&B0B!2tn&LwbaRl}l$m*}etm=2(hmSRmEZ;Ov7ap&hT>|K;?SoXpG33NK; zai5H)1qBu!+MedmsG1Zp*=c@~!wWK05&ES4*~zKC8LETjPMSnzPH($;j&_AD<;6bJ zFqf<8!+w$cQlYQ^~bKMIzzs3{7IVew0>Ui%50`Ta;P8o z&tdR4@oaQDDJ0e^1&4CTE;BlTvgMclv7JaPRad0oy$-80ag3>GB|nV8pMqN;#fyMr zTrY_jdFzpZ=tlXq1G@^l5MyT#7Mev_|g{7z@}?fypLjPAMhLAWy!3>h1- z@5P1l$U7RiJ0OYm>rvjpQs8Zd@P9i~U7E0$3}48cDo*-$4nNWi)4iD$A-hABllL!+ zfM&OS<`}#Y0+QH%mCvH3pY!>1DG5)QFxzPH0Xr$au_P{4zggDW?_uq#J`R6Kdc`dG zK{^t43(@H#4q;-2%5$#^nK&f$^gw3@e-#8>c#JOxRS2%I&W3w~_bu0hsCl|OCf?ul z5}kON@*G|2XL}y*xmsoGmfnPE^Qx?l^JB2qo46$VEq_G;HWJrmGE{QEvo{)3IbcMqH^=2Uk{2<470|`>k5bSdN4#jNE(>dH-`Cgj>BpBm z32vxu`{XA0Sjse{C5DL|+|X-%k@mS{mgS2Z7*%+(?=tsj>)*9n1Y1+OnQBR8pK~9V z#HgIQKUl0Ec24ZxU&|tg@eDwZ9lsC&RAKeS)FrVyEmBLMFhU>iN{9Dnr8t&sDk>8J zq|{4&a@f%h5)q*L7bb?mmrUk8j3Dk@i3Qr+5m%bU>A%;Pz(w>_G>hyL#gUuloAZ4+ zVHG@&rH1$yPm}|z{Dm4s33X{N)8(Y*p5m!{NKaa%)Hf>Z`*xf`t{Rq)pb7^eZ<-=oMX$S z7yNo;|Mbq}oycRj&M%z0u_`Ew593rdz$#8>CHq8qWfGw$J~ni5*aD?w7E{tku+$^n z!51L`*zvbJ9_xRY#1C8^Zmy(t`-uzhFFh#GnJHm_ZvWu-$2Y0${2_mN?|aR-eAy%Y z$}BNY9GNrU=3EicXZ2-06TONIAkL{_KU9ZFiFunl?^%+(`kG!tc7Ir2#f7|NJfoeT zJsO7b*vIS7mu?mA_|7ifm5Ya8NSq8aS`OvHzQWleye|Q}2A6n!@2HL67`puq zO;L7mqBxOHBGGM_3LTzyC+{ENAOsb9@X`p&cJ^6|^%ycZbw;WKh#z(fJ$CtVg3X{dD}Ke7+7a_E9f_?_`VcjokCcORR%7 z+sWzR08$hEiPrhA^AX2<+}(A4Qt)K1?3XT?Z`A?$^j-6!vip6H8mC15g7>H2ioI~f z1OzJYXOC=;+mGiL&-~LGV^iO~tB*By?2A33EGF2b^dJR$*OS2GZY3@>_6cz?1G-ko zk@?epO* zr(BaVYDZ8)b^sr85&RD_wA=VutjrePOvUUE9pQ{{Q21+&T6=rqm_c|xVnM(LfrR=P zTohzsjUJ|Pe=yifSjK5X!(7Ad{HBZZyoM0#Qi*{uy% znjGMZy54@ebvJ(QE%~~Pq{S)|GF`kV>!}FiL4p_h(Zqh~?C8Z{zma=QwP3V)GK2Aj z-#?HL#7!$kATKE4kWuuvZWNO912fPF->cY}dXlI3dB3C;n#UVFZ_%=q6}C8Bmt#~M=d~DDc)A9gnJ78C-ys^b z?liQ5tL$_{EO@O2HCwd@FxXVG*i*4J>UsM1xw`BZ1vYt4An4@m%sxg*Kf)5@y+O^O z4YNwN)xlO7jq9&kB?)2c%SPKdEr1pPl6+GgpBw>OGuS%wZ~BNtt>~0^S6-z z=NS41iG7J~UD%zxF9%6FXsTCY{599Th}Zvq3bsmcfKv%yPo=fyt6FzYNBkb`eTZC# zJ#JgO;@igB5ja>Md%P7g;C2nRQNEr3{ObBB(S^}R%ov*t$tTY%mUd|yqsyGlVMWZh z?ZA=(DG(@ZA3P-85FG@xonA=@i>v#g(!&orvWHFO(X>a~_sbEM%k*6LjWV1%tUVp5 z9)J;Za{R5!$J<2SwSH!8I1N*a(^u}l4#*=xX2F(ioaU~pMby4G`MTgM{krzt~2%p za|pkGMlgrb$%<Q;Dku2%&}8^6?utLJq1JkuP)3)te&RYIuR8q18Dg za7{7oJJr7SFtV=81N$8PAM*mH3&OUJZ++~M;u1-G_HJz0^j_$fM*3j4%#KC_-85bnW&%KON_gRjbF z?!)qA5(!Ki4VvuUwRokj2>$Ti6qclGpWQ_Ex4ruN>6ZY+dclL8*8QGm z=~A%|gxx*=afLs+Jc8QXs^%UuoMyUuKX;|@F5uXe-UHwj-0H{PZu{Kw5fPiZ|+__NONxX(bwOUqtLIGLeo_*~q!is6c1P9tvxs<~e8# z8kj3}xO~m^D3g1>1V%S{Er}P^?IVb|Z^}#iqic@c$v!b~%uI2`q;>k7=JcS(``MvO zYHU0T)7kTfo~d7Fchjj|*K>YzhnJvVyoXlV`cve(N+njy7H(?HRk#kox?Qn137)Bw zv~XKxgA9SsS>yF!GeBg5K=2fa7pfNEF!_Ew!Nojf>bY9Jf;wu3GI8ikJO4Ohb-G(l zRSPHYD{#SZoxqb)#3LS^K6mbu=Y&q zpht#y+ZNN7`iVl{kymnk8j!Rb6grw;lV^Vh;%7B>3~$?Se(&DufM$C2vxhz#UMsPm z2WzHB>A9%=J@{DPpD#09>UEWmey*@G$VNHEZv*=udYOlNKm@^Z zXR`f9Q@Z9pdDUALQ9p9oI~RWmq5v||DUMrxL+KVvyf&;KC`V-a4Rep?t&|MO=(z#4 zV{(CF^)NTLJ~YsWvF9qO!xE(Lf(}I!r}{gdCh)iKsI9#^lbo4_ni7q(AQMk@SL90L@>n%ZURJOGZzQyWN*g29B0R?6mQzTid}_K^MRZ3!v0YYwwKC^D zed39_7a%u6gFv^i)@_QYI_|(=dmPBmM@Z^VtOY932k#YZ^(m7*LXC(=H`#Tjt$cNq zO@9yiE~Ou!={{;7W!)RQkBsCBm%>N$z1DHZJ$kTDN_8wKi1JPn?nzDle4ZuIq{Bcz zh0jl(w=5zq=9S&+RFM^)uw(lYP})DXnMrj%w$;|v8QbYH?TOhwCu&Ah+otgWCy9F^ zgoPu0rv8HR8u1)0FCQD}x^A+@J+7-|H)PSCJt_ed1(D~BG^ki-o{E3@EW)!cx$&`b zq|3nqdD4ChZ&|8Z-h_Ko3sP5x)-VQayP^?niH9{?EGkI1 zmknU$=Yh5i{+kGv_zEn&JQN`$k(Ea;qR~3l7tD!GU-wJLR35t|dfrXo43OIJVZsaV zp75^WP>upb1hT;CQ<3N-2fmVTTQ1;t*)fKFxdF|y(Ab4mDlKHaKezmpwKm-7gMXq)~mTReZ=cgV(xOzd`PE~z8_2khIMsBPRChFBrn*^IJV%PJj(a$ z^SnWXFha9DgYX-n890bck<9p3tkIMCJyd9KK(8$1J4((^{=TqTS)l04+9|iP%oR_^ zeipAgwoKVAMV&>5&wg6I_ta`1;rQY9)Kcn>dem?tV4R}EoeyEw7j(KFOSa)#`(0-< zOAy#3M{E2Un?*khqR%Hvs>oh~t{PL+4kx0@I{)IOv`5Ae0d~`MwQez(Du+;_k%{hzgGxD-4<= z-R9P_ym>drxRs|53Vzw;%3aF+_J7s>JE!+7=i9o|VjcWVdmf(U1eanQGOni8ZY2G5 ztlPgVS^YCehP02JJZHcDpzmg96Z5+Ct~7P-;XX&g`n;Um-zFB7j>??R+iz$q_Va7= zBF>H#d#VekaG%bVDa$XZ<&iazL$w8Gcqeccpa1a$^<b26X^k=?{4Z=p z_zX@tiTb4U=P}>2A%86loWcOpc3t#mm!@ELXRZXlt$S2;anhN4gwV|MK9FvAY$M^~ zYoFIy>qb%xTZsCbeta8+a1D6`?vHnWyIu2_t4(e^=sxxw1ZRrq*B6P)GgDBSs;ms< zj9dBBy-5G6&z;%5e?+)itJ$)|`7uupC^2RUZJ!Y|}`(|=8o3DrG!bYjz+|Tx2 z-v<}5yB6AP5oHEPf7T5cs1#bFlzy&hk2ko=XA+=Mlq<2rJin%&FmTZtJ*})Fg|cXF zH!L6MgRhT~_Ym!-xv|_Qc4`w|1#HtU{>S{$K|gXAmPQ+h*;8|?^C6?wV*(QvQ}M>4T6_Vu!r=ZqM%5-pp=&vAeq zzzb*^xH(zEbcnOcm$UL9f`=`C_o%pV+%g!(JyY2H`yHLH#nd=ebpoJv#L#h9Dx`&} z>6@SOkq2rYTa6IHpfFAfUk$#KM;DtfAip&Sp;7NA{jR3B7aRk@4Bsa1mYYE|o);YU zhlPGT?;tL%w)~>Va}FletnpWLe4Hi|XMT`Q?~BzD2CD_PlP9Wfaw4a#8TYMDX)i^- zZ}BvJfvt5l_47>vO}Sq840+mHC$xWGHWS66i&0KsU=cW$RYC^2OCgicL|xBMQtX%E2I zbgSXUX9^~AY^KRY(y)%g(!Lh*@4FM9;`aqF$V+#)BqN{P#`d-K9UP;CuNPi%=IUjs z$SSneaFnPH#nOBn5qygV3QB;LX3t5N4+Y^zY*X}aRZ-ChBz%Qm^^J^@WK9?ZHbD24 zQ0map=VzDh8ITa4gV%;d-6OO5)PhEDr;7oDL4B9;Ma&}#gYx^xe=}wC4JR<@>Fm5!?HIH7_fU4r%b@x>adsaWw62XX5b7o_2R-DdgZ>x#UX{EXMDij|CPtZf_WXgiJg`6`dw96KwkiQA? zPCdC%T~Vd>AOrikBsh-ta7f-IiBi1OxE=Mq7kx+rg7^qL&WqoCE_EUC?zX1BChqig zq(iBucH*7$hZsM|@A;kkEz8^v{@eBy3T_oDNu@$+f@FKTs^DwtkLP$d-8a01;Nty) z4MP)`Y(&C2#IFVB!qQuRx3}5q-cmJ=>YleRJhdkDQ!GLT#V9D0vCwVCHLU5kYbQ}$__(eR)RCa&?x!;C5JC>>(s0Oenmyw9ZHym;V z*xFX?@E~~xlx``kn6T?RAX`N?d33W#e@0vsbTJ`fM5kay;V;+(N!-gmaX{zo^Rz17 zUYChFC=i_5Odejymq^rU)WuHV(3ARLkv$9tLiqAmDDz|ozIr6`$w;jCIMgz&eUygt zJ1Vp1H)6TJjqB4ly1%B!6glS=ULDcYm0p@y{aema!$Q zYnsW{{P#0VufF0PK>irq{2-LX@(`1Zx$bXCdi&DeTw?{Ei1gXJpmufgkWS)J{Mw_u zk!b-lKNS}3pve6k;;VX#nfJkN`mKWge2Cq}=J%=pu%OiuFESTPZTHLZiT5e7{CVdD zQ<8p_*a9t}nYcgdm}CiV4y(A?JAazrc0AQ13PdV+%`@bem*|sLF$>zx zr|5!UXRR~g6NC7nfgh~N$c=MfY;ef%SMg?=BZ&hVhMrY@Uw^cGdk2q6(WND@pCBJJ zG?V{XXLqO5_50=oio1?Qg+0y8d~=f+T;|`N>Q96H>aDZhw5#tYWCJKNNbSFazWibE zmF<1M!Bn+3@9;=DN}yr!-&%e3U2-Gg26_P-`!QPXv#}qSAN9f)rmd_`VwL2qeHvKO zFmEIeEZl|)?cSPyCxLbL;$p%oz9;f_h;>hc^WgVFjg7iz#ex08sv+`ty!~B=s=XHb z2Uk!D!e4t>^IHvhT$Iq{Pt)TYoZoKjjQRPBkJ-|8q2C>hTeO#Kf=lrL*_l)*OYAZ< zALC2xH5gtG^XRaOjsLsq+<7buSjZ?{4X1Jb6-U+|Y&e51-^lE9^pP8aK0v3WX&K9A zlZn&7Vs(Y>)9WMjn8Cih-X0e6L>?x8yxL1yQy(*wd+A2Z%Vhtgb|$hHz9>m27xjnN zcV1>!ar{Y>lss@|Ut-Bl(XHk!hV@EYz74p0W5RV=agmTC1|^W#`jfn%srp&;`ZYXLfp#WIyJ0|3}O%JMHiSmW?5GY{L@qMZ;J4n(CXi}JvZ3B<*1k_R9WxhvoRy^ap@ zEIohzEU@S*3{EJ2Hxw%@z(@z@W)B=zhr6j8 zC^IyAXI+v0Q{-q{Hk|d{jfgT|Tpzz~m=eO9bI?&>lhmS^8hL?xlA<)X0XUMD_hXPN6QuA}%Q=w7;Cr3uyzmr9^ZYnCi&ufJa z-sgb0gB`eEFcr`W_~oiZb>a>9YtcUyZ+S5XUl1Fw0>c?@z1(R`NYZBet~ zT=q|E&tb1rC%z))95&-E$@~&608g9QY*Qe#ePF%m=#ewW?Q$dbsWQA0gmA6o&t2WW zz=EdbXJaVmb_QSnlOEiQw7gqdiv&T9a)_pyB%hMkk6%g2wgDgu2m!C7{Og0~_Q6bq zQ}>0m5BQZTt?ff}fh`!er-H&c+uAvo} zNg>bIS5!M_%8#X0$UZI~hR^rKlZ-psM@$$Z!Oi(?V1#UmCN8FYhl<;a1m_Cq-H>Bg1RE^r{+S0`>2)6|ChgN53(DXI^||lGg&o^80-$ z%nL0$e?}JiUL0d*6}#T`cSz}gYuI(aBl~?){ciM$*w_z~q^hmCRS$~ebTZioWhtZ( zKYV`GEsuJ`^guAL4W+=0wG8S_5U#>WR`gQ4?cZ?X^Ns__E$AFQvSoo!n9#OiRmZa- zKc?k!`uQDf5?D9Dzy!W7s94{GQ4hXE`UYUykz?c`Vr0inaaK!fJx}4Cf>i=SX8Kyf z_$`}1eDQvydT3KoWpdodf?%M{_Vj1VSN-j7dr&e8zQ=rusngEnC3smXaZl^#U@PnO zZX-7sz0hIGn~R&jO8hK4#mxG#6-%>7ejFcsMmAGp^eFF+Gc2hzdgO@PIfFGT-e)T2 z>-j1?H~J1|Z@Rz07Za_~fI#PGbawqh@7g-Ce7ckY1!(u@3PgK7!B~8&pWC>0myx;t zUXilMSKi$3qv!X4s>Vx2e@3=)UoHP7`%T{+Kj73~pcVT~&cQ`fRRmE8tK9F^sDDZe z3?C7RS)otS$}Zk;JjP?%-hK*%9LwPt!(1X(op#J#ugo7d!QWSIm6#ZLA*}ngdu{(n zx~?rnfgt)zN|Z-HQF4^@h6E9m9F(u$%j`L`JG(Q82;J4yRW~RfT}3_U(*|?@AkGls z159TFPq?&wx(PQZvVXkGMO^n?-t~B;Ta`W)ExIDHK+M*Lf*3b_?JG=TuD4&%0T?Gh zD{uqsQkT;7b-^Mf%+KqmsnbL1ufK}jkovc)7sSQmSFHB$Qnbt>X_(DIWK*MgGs!`( zZ%pWZ!cYgGP^|Y{WG`RJ-JE%FCRmphRtNI5#N({~%zifdXO1-Kd~wSI5Zvf9S+EX_ ztj&0|a3_+dcH54C5%Sl^74(kc=M$kkR*q}BfG$pZs0~}n+~rNb8}~|oOqH*Vw%`K| zm#~Waqs}@p&;7wEqel)SM)EnL!uOE6WqioMe17dhoS~cS-j76Qsca?C{`dKMNb>uS zER0g`e)D}B&D2-3=WnL``fT`AF-SB$T_8gf0w2klWIPi1O&ssg==u}C!H#|$nHQ3{2 z;l6F_V1|iIvKqs`v(~%il+D(NhJqs1&-N$shSa3cxoM1Zw}-}yGf!O^jM*+3B0Um! zg*j#=05-zRT+QL6k|;oNOr&+Ab@r7hL8VMkmPWmrQOr+kMx0&Ag}v- zyoB}(7m$ZmIm;C+pq2&_v0ScGzmk_C&DWo5O>0jQXUoRmPSY^?arC{RBOKH6+JMyu zR31l=`X65-a&LrNGswk+vX%QIUz8X<0`c?OtF##D{-5WCKi-Q1_g}c!-XUBro!yMh z@lLn*JY&-Fb}mO_>39@4p-dQ8)qqyZ5KL1xE)5CN!U$=$8zFBQYwtZS;i*~?t=59* z3DWVayv2)Oi8o%!zjx_0kg1i0O}gjb`!ext_q?hS_Iv*WkY;l`Ighjxgd8D$4+%-tw>J?@w!Q zydkpzNRwmA?@4!;P>|C9Y~T4;04Sp=X}b@_BiLWwzPvt4qsfPNZNLd|S*16`!tm?E ze9MJDCrQcnS6CGov6xi!e2gB)AA2VTQq80H8dSvF-Aq3D+~Gwef-L!%!Z1Iz@x7t}F7~Z{&zsFKFZS&`Vll*WH2CHxf{l^INNsy4l!`G*T#BSWH;J|s_j5696{)2=^p*7#1k4Hl@#+@a!YI!fp9Kl40X=Zzty zvGc5a##10y`NM{z8zYTR;Ry)PZqhfh-G_Hme#`^;9z8p4UOv=AUD;aMeo#6Rz zbC6ho7-@gn?+_j`%+~gywSnf_{h5QlUzB`TQc;S>w41i(f^rEWNKZS@$VsqEyE}@Rxzy+qZqqzC55H zj}zhx#u0=AirBR^3$)3GuL?0#n;TV&Gi7o%=%V%BV$(mqZYS9q4IeX7x<2dj0!JU1 z@YMawCXe64&?78M2qMz0)1tD;`uYoHlcKN8@nC2U7vHl%IsC1<60aya{}RsG-}+>~ zocRI*H{ARzU0M8SXcaW%=<4_&cNZlI#x}T8=LeS{o8Oo1taA<`ZM}P0V??OZde+C@ zYn#f|8O`X9*6-+O-%`Dl;RNBt-J{ICn=IrZl^@P$rkZ#$nZw0hX zVL|mf;uKT2{e9@e9--@H{eH?I6*f6C>-=OYP{2c3<8Wg~YN8%I6;0)FJT%$eV(AUi zYJKY!bolmJ;^xM1nYF$iO@Eq7dzkmD=*<3^_ZZz4i;Ek?bfoi>vX`JFvS0RHhk%|k z!=L&;obhx)4gd2~fuK_wh?W@3ACfZu)kWs5(Ehp_boFuSg+3u^dRQLF^X0CFDzL)O z`&@L(t0dy4c>^E}X*I!E(u7`!G^$4r^p{+ukY_yWfJ>PZu?yvqD)7{{e5qp zVZ{F{uW=vFe1-Il(URR6dScNSCfNS!o2LOv!BQE#gEt%tc^UJpGX2HL^zQHwfwwWZ z$JKmX$80zoy1y|XG<|1)5wqgOO%NXZ(BvbFN35IgW6ynodV08a=K5bF*)$l^ zW@p#Cn5zHMRz|4|&dqyGw3U7B40fiMFn5y?qD4G%1IWTmDxJu`AIrFY*sHXfSTOR* zOVOz}|<~m0lw6?Tk3PZ7e`(Sgz@_Cn#{z3HG zhO^rJWt=4R`JzMqsJ%GeWC0o^%zrXBm7nv;e?tF6dmZ28?;3JM-=)#s|2_Hjk{%Lnr?Z-L) zp5A#VMbbMNEtmIR8uaGyap3*y!A*lT151~uuNB_U?U}efp}?M)Uf5fo%@Do#SZ|HZ zRc_KaJipX?ko5WVVMv)P;c$I!QOhaSNcOQ^!)CPByd*b#_Q!H!cd8a8^yMCtDFj) zTt6hGf7-r4y0{W1m>*|2+=kW?1Vj;H6AK&YiJ-(o4xz4xbq@Sqi~tees~Eq1`|A@V ztm4O0Y%~%=mDj@|a1Sh>M3ct3Sx^u}ZB#_oX?lgxRk5szmjeCzEA#ly$`%rPI!7Ea z5`+u;xPS9K#J*Tn0!cRSe@==$t}qKWr+a^wbRBP{HZn_0WD*eRj%Dz0@dYk5xdV=ouymj`g0*vyRTu0}uH=pFWQjlMZ&(R*ADXxYHtQgZO2fjvC&7{F=Nrj!g!od!R` zgK6zIJ1*WpO^riE@zh)0qby8ZNOWlFKGE8JzAfW;Zj9(~QP(xR>bHc=WV!gju0B3y zFg%`~wC6;>Rt?N7_7Zql-MA-#ys>h8T>BcRx|8E-jblWQNn?!#PWtenf@dnn8t*7I z8u4gn>j1BL*bVR7s?E!okr>(YM)xl?AD5f~@AlBVb|ok%(GPH|9DtMBfj*MEXre>H z0HD@J9o!}ADY_w*k~w*U{uVGzEtz~=e~5@GkVb0d2^|J-Wc=q zV_tis2?-QD&?tzN_|+SZ&-Q87#|!i!2-O6!eLK|BR$MQwM&F=&zkdK>yYAmpHQ4TO z`}n5koPTos^kE}egxv7wIZr0{r-s$-_f%T-B|S5%bG4pon3I=Nc`(%I=cC#+d|#;q zpB@Jk>CDvHnk2mD;Ek%0%J;zWi7g55YpUDbo;X%tz)eb6U*W#c*a@_AYialE{Z=yr z`&|$+Bw}q3vvYA@w}+EMyg`F)u?9PXBvabBcbVgnI_@{p{gA{~-|wg8dle4mIGcq- z?)3?g16kFcSu{LTj3ur(Qpk2X-WG=UBV#Xzr+x$-)rz=QoUGbl>-Qm)EKD zNaIV*%d^9~85L8#E01PUF%U8WItMsN)h-Q1qe1*2x#PG*;pB>^@(8n+_8I}63r5+R zAuk^?`C>ufsqDBi7q9x^``IU(KV69usJOibElsvHLa#hY_hb=OFTf}n*BKxWL&yLU z!BiPMl>1EoPS|*hGt?}&>`Hv!r^qp=OyBoHWf`XtUM*i)HlrxhRYGNcjLi#F*5Wp? z{=Um?O8Hv&K2+t646j)cJ_J&fG8QtwuSF+Ts3}X^qYI_a=wM?i!4+wY`JR2dr+v3U zPT9q7v{XEKY&d8B(YPdMm~X0YcS>G3mIw?lBM?d+#0DwhD zy!M&dkZH3-t~m}oY(VJt3c1-*8LDSn=T7iA_R|1bLuXN(GGAIK0Gd?e z6$Qnb-?NO%2JJ^Zx|;U$bI{ze?e9@xJ9!HpjraNH`XrxIv1=S|-vhkv)44g!*Ur#m zi%pl%O7^SVXKdwX7DUQ^ABn%u1d;DA?93J!Rr2O7^HkGOYI|xfpEF>+ z@k_N3)#IRts~zi9ClC&I7|#mXoEFKy@n_h&A7R;B40k{$&3j$hZ!Ji?YxbAN&!@;7 zh5P+1O5ErGzKaMgrCPj+<`9@TyZ$G5d2(+8p1qkNVbu3gvkjYb1o~@5hjrGtNJ2}W zToi2%SJhu+-br0P@_iziV9!kB0}66$?SiaQd%-Xl8lzq;o9@2IM?WjCPp@GQ4J1gi zk&H$TWdG(~0j_!dxbDK8sn;eOXIX<-$_;$MOV6IOu~JRtni{dQtBYZ`$s(Q#ujfD? zsQfIz*Zm+ux`jNRz}>mU;S7JE{n|CL&F^{a%sawJFhBkWqWDHJ{Jti!0Mj4WM^8?} z?s+oXE^@nfr?b#G#E8>HW5T$FW3BvvyZCt@TKH;&Fk`n``L0e6B>P1rwI^$=nsA$J zp5j>uxIjMznh#~M1@V^5$CLL~6ts8o{>BxC=w)Qs#lB`vKmQNqB*e~1gq!adtu<=G z{@)cl#{04HG_dXoo>NQtIxz`{wP-oQ;tMZbKK^B2^NVXI*EIANab@oP6Hu+$KlH}p zD#mTyn;-BL#4Z9mCb=&;vmJ&YL`nA!&4BB{L-UgI_{S5k*iu)>~iS?8P&SZD(K*0{6xRKp= zIlp0VXcnQhucGBtvIIa1rv+Z$%)TEne`>o0n*wE0e$RuAk*-z_<{4b@OEB4WtM-!n#E6E^w1^yx^3Osn;BtL%G(D*eJ$izMW;mUnUqo%3w7NNO4 z=Zf_%yUn{a>hqp~7$@d=g7McSilFmff;U}fkb&6xxZzxup`3LB^ZIXJeg%KrsJFukH?6mZqn@Bqo}OjgJav;~ zyKhxy?)U6G?H6i503-XuXvYpr5404Tipft-FM(gGRO4y}ix4ewANg5;ebT~P=BQZF zDkpm(cb_88E!w}~Yqtl6nnERm|9YH{Y*C>HyG-6o9G!zEPDf>gutCtl9MEO!rks-e zqp%=3CPM{CotxUQ`tznhsoAdum)7IH0*z=&?CJP*`wbW{0{mk=^Br!G8D-}9X*~u9 z==)*J55A%>ckJLKB_zN%g*B`>I&FHV!xa!Hpn7gTvsX~6Is&wS_95d0Ad5oJ7M6GL zg?N2S4D~xInR9}nJNbosySO)~rGW908yy_fj=J}88t<#Ogy{^@L7~3ceEq~runghY z#>vq7%NoZCg6_*O7|8S%k%EyR1Vmz(dmTT-8TZR5cp-Uz*z^ zA;=HS<|{|C`aIsh<3k_5x!d|E>YU&6@%9!oQg3q13__!*1IgVrhmlM&>z!*J-!JpE z;!U2@3CfDkxxzp&7JcGA0n;}+?CZ_}67}QV1!E4ELW`rBHf$uEI=>2U=0m=%1a@_D zXyMlaWnY_=I92w=Vdp%B&S(BRpAP;J1ou;|a87drTip2sr!%^eLeVvOM0@Kgwl4RY zWUsyp~Q~!Iw55X$kTZE<$|jB3idlgO#32&m~4`YlLEJUQ1-{Z zfQTHWG7Izos}k44&0{fE4WVwuYs=@`za;Y z{D3?GSqbkFL@Hrv=BrR%_vZ?4-ji!j{T{FJ)!a|m<dtcR4TWmEsS>Sy!!-D=oYsBZ)x2G@OH2dxw9AHleh_Ci%G@FEWiPn7t@AH?| zug2pL-tpflb?T2;F?)%Pq}Q=HWs15^^VU{*dzx2L!c;xnb1u!&g42kcre3qovp8{qU z#T@!D2A+Gvz{D~?b_^x#^&=sCus$^^&xgfi!(-1TB-rj{taM+%{|<&A_;&7tc7E)+ z{662!TS;K_z@+p>`vU|_aR+C2^=hg>){7Uv9}D!vzVA69f9;14N(gO$K1xVH?06bApZt{fYqX9rwYTRgw!>PUX1R1`s_;hf*OAaFG z_P$obdvPjw$V;L0|60uD0*Fv=*@{{a#0dgh%?t;{f&GbDZDuZZ6}*GujnO5c>rx>k zAHdKOlE=u-Ls~DFj3-M8GDxNjVSwOO5OMg+`+o28>34JI( zACzTEvM!!aST3jE>Rt%zCY84z^-W&D!lE|yV=h<1X1B2n{gd=GAG;N2^Fa}$ugmaf zY_H$eed&3)SIut#DC%gPY`4|c#oMP#oO#Q2Zmh8JC1-xV8Q5CL;&tEBq_-FE;X53f z!!Lx6<$W$a%JFW9m;Pc@14O!Rz1F(>qx+F4QpyktMG7p85oAJ>hk1yqPCmWw!A5Hk z@Bbjo2vjgdrx_+<0uVWX`t zfTMufA8$`7btj4hN6f${`%(L{Sx^jErr~ix+=Ivs{xV^>_1HVBf})-S{SZB5t(U}8 z-CFd%ED|h?@zT-fp_(l3$Csgq9lco@r;4^+E!@x{Vknp=^H(vVw8aw z=iDUQDF!pD7xR{zLa@}~UshH&Bm^ot`-%2dy@tI+xrayh*>=+cxai@n4TzY0_G>?r z(VqInC-3xl`tx)NzFG5ZLX;u4P)H<=x#ROl2eg}Imrf`&kgP@$H5 zl%5c|XL#_SdeFW(sy+XuAoO8hDlLK#*sD-SyT5%x+*5(HJHoep4>v^E z&#f!M1^H&)4ze81Z-J+>y$rU!o)>rxL*~6fls@efO`W0FRsP;4PjK|= za#+bx<@)n00gsX^;mtlG5-_GV9$&=e$dKEMX>G6FivaQiNTMj&(%#SIXWcRtbV$)I1?;Vd6;M4M&C zvk2qv8YMb%sA;?T#OS85UFE#W?QM02ZGm~}cYX*eWO-1`LkFl|2y%%!FEe)}HCkNBo%bOd|wEn6NQ$ka=r-r1%9jZ}`kFy9l& z88#)P#gJATzTG5|7o(c$Chn%NBB{XbMdtMh4fFBg*O7FhR%W0kI$ zc*`e$ZaMd1QWMtT!0eb8{d&3F{ac&jBE#r26&Z!JVS{KO+f2CwRE#0QNagh0Lv=p8 z_j0;BkeTs<=$(;q^ZF?r`az2Q{K{8^(#Sh!s0HSRU-qxA^I5QUL$rf%e&N9W&Qevq zfGUkbO>_$1}xFb z5cy=aqiZ=Zg=OoFB0dO;|SI7AWl}UV*Ys6;hUaCc|%} z!&3Hh1YrmDvXF`yMOO*7bU-#yz5jXkyx&ZG_ zO#3=x??Y;Z7G-t@;LemT;>gV^B;d&2yX?1+!&HD10Yaq2GSG&7AG?XT8OJZ%!=RW7 z1UwMwF>E-NZs>OeTfylB*ctWuXlL}43oxj&c%kbF0_en+wn4;7qgyTYCsoIfwa30Q%LCM zX67rsuWD>3ER;z&fDoWGEsJ#Z6v$FW=PWTvj3*Kcx7tQV~FZ1`X5kyeBCzR-nfufgZc)9TN< z98s#4Vi?aK!PNXk_BSPXP!^{|U&D>?6O#MQvhV=Q1xi5AvGd=LABcOrn+wB0a-Yl1 zPM$VR|EeDGqmj8U_b%Se_FfO?$Bq~lR9AztY9aF% zcM$Xf?P||#`}q~UAC%Nw!VtvnJrs4TP^rytzfa$9`@_mENm>z>9zM-?2Bcnxkk)fci}mTkJxV&6 zz!zIOqn2B)5R7Z9qe7e?6)`r!(6g6HOws5^1bkB_yPSMKxVd^tjpOd@`w zDh=Dyv_({w2VAR*O(1g_a?<6WB!M&O5j2XQl-JWwQlth>a<0&HD>d?lfGSmKc5Ztr z_|?}iT7g2+A4?wW>*A}2@r$VeHx{NPmSvxgFm#@hQHwgK39f;rTyPTv zWi0}rMmz0KOtHN=O9S_d<{o5KRi@@EP=jv}jhz4mWAZWX+X%zq4Sy02%a+|65vxef4IkdqUQf}^^;{C1r-lZN*NVa!--m(9IE<1Zv`O5(dVX&`d zl%#$?#C9ahj;JVb`tee-uq5UNFWLv8!~n8$2}XGcl@8AD-eUq$mSFPv-n(@U{b0}^ zYY%(i^?I38#_0L+>QFBc`Od(L=AZ~1b?@{TTX%ZRuYR{p@T5?Y23 zr(UDJ1!R8N3;GC&Lb78hzhiZNqf1f(RP{*Z1^f}jkX8|u^Ml#5ktE-(My2kMA@mBB zr4^GJecWcbf4xpi>`i|hKZ6E=ZTl~!1cvOeTa66E?WBiC*L8|@!Yi2xl8>s=cGXdv znx*w$aGR#?fg+ZBvf%9xSN5AegQv$`lE>$C{R)OGIM-WyF}V5hl&Ppl)kG+P^ujBo zAMw$vDHo6|_WbAF6~-r{;nBmb&qZdl7@AR(uvOHS;ZaIc4YM8M&Z66hcjC@|+K_{i zPk z$$FG@w=KtsIuMSgtV{1+Ot|J$DRWT0$NuruTLT^!&bm$ad)4m?!gXXdLR`Or40A8_ zJ&^br-xA7w`iXLs09(xn7Tq5X#RD>qr1rkO4%t_`zrED`Xpi_+fK!ee1o5+d65vax zh3`>6p07!)sdM|1_bCl#5(CYqoARLE?3p%=%dJ&Sejft#aEHb-As-%s$38$d^7LN> z>EHb9KO6JXV)Okc%b-=&{yz8;RVs#mZ`pf535-uY*yop0{5_(R3?TW+4nb)=exY(n z@=Q1$d!ZZI{irPa%Td8{qu{K5*#}+$iLj#!6b8CfNAV80FZ;dCckV#&=XASyPz$+WIxqA>Y_=X?HVxsMVFA8N>&bSrVO8QT5z#BYB>V8T9%>Ts)i4}l^`q*eU3RA!%}kbi^Q)7#mjX*1yO@mi z{c-ve!VaM&r*JpLlhuB{eWhb}oF0Kf+XeZ(UYij8M8&4P8ak=BgG$osvDLOc+gJ{J zCI^_MSx!&h3?W4~{)Vu$Z)pBPB^9cG8>dEF_Y@n3oapZ3_dcKVV+bk6tNfd}w|l;zJvlIokq`*pa9A+e z8uCMn?Aj+4!9@5p#q@%_t~f7>{4n&^cFN$kY?ZJC4?#3$AM5yV;tP6V*Nm^Zx+>cw zl>6$|sds&xUCE$KTMl~jrd_Fu|D{(0XGNiTJG0%5i6!ZVK9_syq&!Id(%3hj+`?el z(7yfMf{l~Pj;j-IT=;6aq=fkya&d_*evajY#0Om4T-~Ds!8KWWzA^_Lp-4zzA8KE= ztA7=VWsk14s?1k1?!IRxC5SqRsk;yBK;LOz>nlGFD%><55c0KnAV2oK)aa^XCy74@ zb5?;j-#^}+njeqkhM0z$tPV#$RK4~ z-UiV%chfSd)nNVmmK`{MwNR|iScqHrYaWFVFg78?cq^ZWrMmp2VW`59MbStpo`ov< zi4QS<(|+BcpH`!`c9$u;sOtT$1PjTp zg#$CSp$Mv~rTQ?kV}qyXrjEmVcgI1(5p_Cziy?8}woP+3!c((=<>=#*EdQRHY-3sS zs5N(#fpmizqs}_TnptL+gp^L)XZTO>tpiD(+n;q?HYx~{+Y?PwwbPVe9K<;yIbn2I5g{?MOg ztH*rXiO#|^I$ZhU+$qedq2Tyx^)Fa6wk(shpU273V_8)WnRwu%*EzQy={#=zL?KtGj;*?I4&xH*;OHgxXJxrJK1^Gf+;UhUs4dsXu4($h3HsK~ z%&qPSR@v|J>E5BSdmp!{`O&u<$3Su@P$rO|DOI)}v-3ydmxjbWn&^*>KN+Cf#!QLm zZXJbznAP4mA-4ffgFJ-T_P?c7V56NcaKN#m;V*F@i#^yU3>mHvF>e`oRbjVImzJ&!OD z&adPiGyV7pe1kBc;D3OjYvpLpl?%fDpoXjXYQLw)@sSyb+l3?CCx5MCtcJn_Z`#@5 zOk%tZzu(uUfIMshp^1`Y-%`~|f7`?!5bK84rGWz$ZfM;-{gS>dYrReP)$)bcRhtL8 zCAs*S1pfzqs;c0&QW zQ6UIg@V7-yZwD?qqMsjUhPiZ^^LkmY{#|;DkUYp+$oz^>!Zps^A^<4S z5sxGawy;;p3z~T#ti&kx_a(vo3KO;SQ+3k;vWDhmv0`nBpP$p5Vrf4{&=vPm>-E5* zBPGP!Ni+0X=RSP-fUtJTRr%YlKMnwU{9-nl-7vzD=ZVkzO{8BslfF9ZbGs=Up69mK42uSN^5y1tD52{TM601oX++oX!!4tc>}x+e%{;1}$Mg}xvK##KgCx_y zYkpeU+yliFaf(j7gZJ706^pYX(PmpaKeOkLZ`+h)JYh)M-yy&3zr;5YIm~tMlhHT% z1;xZUDSLl&{-Al68E6qP@Z;d9`8Vkm?V0_Co|SNF?iA(HW4I4{wd19_UVFn0ep@y_ z+2%!7Lry!wIf*_2h<8Sk+o#{XQ6*T-vvys8TP+;|5tUmbyeQ7n8b3bg5 zn$M(PJ12Jd^MDOmUeCMAz+p8*s9&hpcwh9F1oenGE-a37c>vGP^+W+|0ov{yyJ$FE zV*3}ylSzQ5a+DDJ_c6)nva^#@3#LcA__@MN;V9;XF~)!(vD~wKt+zcZ#O7FPM!o%u zBK*PG+snShBSoKjn9)mm+ZCrvK)Swd_X{M zjh3^|jVAt)SI)y`7YWTfF9^(jA@pqhAWW4NFp?{ELT8Jh23Tm%Y60=%g{M(jzm4^L zK_ShK7-h(PTqcP9QjqeKbhvYFkJD2~AUF^i=@zloegiO01q#CvpkAnwK#q?7w!-=B z+1K&3Y-|xz=*TzlIe5NM2bZ@Hf^Gvv0{7&Hb$yzH;@7hmtdhcIorNQe`=k!(?Viv> z^j&n%GoA7Fp6`*#F9@F;>><@VOe8Csmycz^s#z-zGc~1*p99fOWFv#ERz)rEGt}TA zr~9od^k?Y=Z{gN+KMj}R47}0`-_9u@yw}0gPnW^=44Oy-sG5ZkZp~m&WG?>kv)4wl zeQ%m(G=Jr-Z4TS|ny1NS>Q*#x(fYzKnV+*Kl;#mFR!HK#f?*SWmnMg|C-)Gc8)eyH zbaafAeAJD*2ik`R4lnfm_cKd}7v#tLnQZUN_ecMXnhekT9WnT?Cwiu~L4?!7BUd z#UVb4&+;f0j<=5cu<2|TU7A0Z;$gqCJAKk>#|lTo8h=lsB}*rZcz&3*;j-H5UJ^TB zARq#uB}hRZvkEVPS3gc~5zK}IL7tf0$ZJ#WztHjuqnc8W6C>619TL`FW`+$@f5GO! zX;Lihg@eTFu46NXT{ndMl`Aem>#~LJv+V+)u}nX;{XKE1LdgX9`zBoby`FsXubVy? z?JC9YUNF8Mg~%lU?>QXW&RF}_x<#UA0cGJGJ2&{*6@6X2i!xW@81zMX9;m*KNpT13r=ZFriT{e zpI)f&_CHqLan;fI`kMI-L@*zvN$X1C3ZUjhr|VAF3rhG_L_BJHgYhXs zjsYDE7v0=V>lOy-gDPbL!-?p?@!`YyAn~W*1x=yFIR#(&^`zH<*FBH&y^LE)hErH$ zz`a16@}h}65ZO=D<{Bp9-}mo8|3>!9tMs9$uydx0I%f2zxYu&wrR=Z7Rz26zd8zRQ z<)?jD4T3v}^kUqaU3fH?<#XQe=vznIMQQ9rFtMw_4~kmM7*0;OG4UAb_&)egVHA({ z>7skF-x>lc*;YNH@Jp-Dq4+N1_XkZPR`#hJpu^j1*)#3WL-!>A;K3kXah4;HD}={@ z_k9h|5V)JYdLrvBxvC{^LdHjA0Ppfh&tzpUDt*&7KevWrHe8Mtp<8%t$p8VEKc7zE zo9%9MZSvf-p>~yzSpBaMhCZ@XUdh#i=FX`-<|JJj&35|GbsU57^?CgRJ}WeL>+F<)y>(JiuS7 z7rxWJvl6`PH_eIV%m+ld?Mjf)MbsqAp;B}>Ja#ELr;FF8aIdHn*ZrOuyi&b=YYA%^ zgUjK;^I)z<2-OT9go*Q8XQ4C7TwECVm0o^5tZ>7FfI|-d3{VI`zUGc4$|cqAD8`|? zBVTv*APMR)ufr=4!H^=3wA^|(nP5XUCyf%`tNwQW?hiIp7aDEe7IaR6#?%*X#!F)& zo)qn<#xNGVkw-E<#~&)B{e889CX{3Ql=(hyiiq^%bI1Nh*z|@ckNV)3=KB_7p-b94mmfD zAw9hL_k2o=dNiEe*cSo$HK6Z(WcM;2HD65_$20CH*$Z7&6hhWH<3%KpYFZuNLj}tF zbMmguX}`55uNfzT2Zs0d6`nCk9^5ECTh3eee1u*BY<4pjjm~&ZA?AT}_Y^TYK1;JW zt@lll%_ZtyZ;k8jLEI)NB%~8upkL2Lw|@7GXZLWW1_R^@_!t144P;rzVVg>L%4Auf z)%%4SN&|-hvW-iKIpQtnBZ|Ij&~rr?9`6GqRoLI}dC&g-=DgsLc$RN~(+#evpxN6n z)=mr-&{y~)h%)dT!l5Bykn~^mXtgqnJkDZ7Bn?Tw;d9$O+9c<&S7p7|(RrKu6#ui& zI&4-Et$V{sniJ*kadGB-0?I2$((r09D44MMD28eZfb3bZbqg=W(Vy&r?aIsnAIs*q zK2(7N?A7=TDT)x0WXdGz%^qQW@=P9C5t@$)h9sOaf17;jffma*i!5-Su?}acu=Qux z)8^q#&Lf12fW$6JDdtGMbB_$8IdMC(0v!&@@wYFS_VSB@`w@7sWWbgU%kpXLj=Xa} zfDf%2hsJ-BJ&waNe%gBMgK2l_m?bkNqUMsf0n19_0s*+yL)#JD&&Q(LOAaaU%XjC( zOGGW-*<7BpbRcJZ-s>5<-*1OM6TZp}kd?vCi3DXwd5}i+xn{sU7Du7#9{bJd^gOea zVAeGcXn%E(%JxQDRk}fx&!c8HJ4K236!czSv$ShJd{p#SeDH?eIUKa%!6Ep~cvpDD z@?Xn5Cg-C1XsRt<88RQ;O@XueKFoq)S)atijCV=x)>ZqgqXS+W8uLgf?b0U>_qlly zbo5G9x2wl_`kBPK6Kp{~Eb)N8x!TwE+7Zq0K)>OqzN?(NK4UtTtn*(xYkNsH zq?iWz(oxU~$$7fm9ft%_d|Ct{kuF zp0GGiNj6>p@E$bl+o=|@D9_*3*Df!t-!I>NcY`+C5OS*~TfJd#)Jq{;7mv)V*c9_L z-mGGfkJYZ}xo?F{M5E}6YKL8kP(sc$=k)WRhMJ_&?F9grVQNn1L;QkxTJTBQ%XN#Y z8{Gv%PoQu1x{~Cz=gIVW_kBvL6sMJF=b=C(_a){A)lN)!M!nbQO!nHnI*AOMNTZbz zC;E_`S5Hv2bkJM#x#`yOiZ`9*&o)(OkFrAtGK1$gYBU^K7&vsR!H-+D zJ-|_yZ%IndxjwNg!yJG+U0TNmZd7e;)+g*~HLc_xeekhbZFibK}0{-;O?28YQN~ zcMr+c9!>JjDCWpt&PDMtoNkL+EVq0DSAmta4tl%Eiucz;B0it1b+KNwlOC$4yX^W) z5Y!&`(UQpL_kdOkrFZAVT!D*j((X^Kf|ibqdxgB4ye@6nPLZznE_e1v{3zTzz8hgR+sJ%0cz0Ot$z5RR}6UHpn4@ziq#v7> zabhLly=v@9v9Bb}{MNHN1yIhky=_~e%4I_IngKi!&3yWEI1EqueQs{S$c%i@uzM*2 zs2y4L0L%o(wnudKrh)oO$vx2DnTHW3Irsz07g;81@~YrrsebABx0Vtk$@%v2)9j1= zSGArEhm;N~R^OkwQC%<{cJ%R|RgOJ#kSBUv?8~%3i6mAD0ClUHp<^fEjD5-`Ke}5J z`?T-XE^g7JDc1?C?qBu^{z#Vv`rbKItpmXGEOD#UGrCytZT#=Wh!Y%WYTp1VfS2&s z^~JTQi>0#r9h={04z};jYeMq#Tv`^sU2vSt#?=05F&(7M#k90MpR|*3gwQii0;5{_ z28hucCX>`SYyih;z@);G1EUp@V9#%&ea&>Fmjp}Oo?_Im@-$&Np_WHO%#3VvoytGJ zFxrE@-93e+C#)_m#g`ed3zY9C16H0#5?Ebu3BHftyDlGiV<_L~p?F`p1v;$`@KHd* zpudO+-`%_U`RZqIrTVfy^~WN1Wb@A8MbA-BU`>K*`7T5y4BZ`9h9*$I4>;uRM33*B zeDeABK^@jQkGpyJN78kzsmZRbR_xw0YB-wytQ&?QD-#Pt2GSU)XuP?pFM3w9q zo(>Bn6nFRP6S|1az932GQMuWGsGJEoUpv9CkEui?2N(UQ%e8r#ddiTtiUaW;6G8@@ z{A-kiJ{>GdpuFauT1r0Xt ztG>cZOW2Zj*mxImT@cy6&%IC(pagL~*5Y)jDwp;;L!<+!eu*Ur<|GlX)F z3nUhn3sD;)aLFcPX5u+)6Ib69BKvS8`Q#@dLFY-Dj+)F`L*dv9 zNYhM|GKA#s0e(x?2Y_quG0Tca7yc0368Bu38hb=XlR#>)?s7qb(~O_3`z6cyLh1bC zXAenxspp~H=V&pI1LYkD$3b)@aj)B2g;$8dQ1S7E+o-SEC7*pb-(H+M`+9!#BSogq z>%(R~B{*Kz?|gnP%ybtNT5S_vZTsfQ*HNrQSO@teOUt|d1H)#8arw#daurI{`S(ys zFg7r=lGB{TLV1AV4i9v;j}8oNK;duwmJ(R20yZj=-kaB2$!!*Q2A@3n>)XGe*?j6Q zt8NR}$)xOVBoBzQr)do3+7A>ozeYPQ3bt@459I+2DBHknFo*aqw`PT0gd_BKwFCFe zA&w*DdC)!t;byd7I}<{TO%xW zbQY20wB7OdIaykuW1psuUYq2A_k39P9Y{b+VWvu%`NCjRMGQ;-af zu=C0I?}b1rLZ)JmX=;Nk;&uhx2v0EGmJ?WZyqU?Fx_0m~@*Ta!^Qv;qBesj7bi?mt zTWe(|NsLXe@iEHR!`0Ts5lS!&T&9f9=s@g!~Y<{>?Wo zZ(kRrO@0ffc6*Ii*odTuP2l#axQY+buRg{^c7bB-3*jnJfc0-N45`DHRB(pD4MHuQ zsiCJkh_M$YM<5N#m+gCLg#3px8%y^J%`)cqT{;z7{`?q@xA2D&MPPl~nqxl8$5h;+ zO^M%wzktb2H=hH(n>(pqiHG=w8+)Z+NHO`u!UfOEHM_Ld05Ss6q`7JY$0D`j@$`D|0*6 zW>ZZ#VIBEKB3dG}X&#DvIHd7h3oJDqPTF-wuj zp9QuEJSGW&;)HTpKY52lE@70Ezd>J|&nMybRiXfpds#{ZrbP2x)vvbtgN2!H+_Xj! z?`-~XTlS}));~hiQ||1jgCZy@I>X?cx$+z;ZTw(qrG(?|!Bfj7QruFcXR%u3;~|3m zb@1G17Eg@_@X#%p8R0c<;ahrtr@vjcVjWC7G==O&5*P{y$x!WL1|N142 z=q4BsJoRTN276>kp;jC`Ma>->vwN1C%-(-De1eu~arN{XWlLZjYXl$29UM+X_s!|_ zxwTQbRp#T9JrC6oTwYTgGf|8B4*Yo>s4r=aXtxAT1KY%@@o#khbWr(Z-+R$O&*Ge0 zGzgmcxh>_AU*JKmgT9>CZPv7GuUZ{R$vRH^*8Wjrs0APA>D7GIeGw&E@_JK;Px++o zuM1LrHJyv0tJOg;xAshpmr1d>>=%J>b3DR!D6--%@RQDwckm43FxQ9Q9xh<6?=?C!9ug)IqZh|d@?>cm8YCzJ zNroMBUvJN>9wL=*H@|vizvHq`3#+fdAJ}s}k81LMUmgyM0CER(>eGv=Vvm%5%1sgF zYe`#EuvAlBr-I>bWv|9u6ZR-_?pr6$6-Li@^KoP&cGF+7=K)8*bGdLDAKi1M?-tTN z!1*PggWS#?)Jlq57 z3eB0ynyaztWP4A)tncV$^wytyj;yGRS{LZX{;tqENuP^08;|d+C68`U*Lf%8{V|s2 zEfcySrp3{Iwf5iBNkUW1j~@5?&i#)wL1nTzbz-mTXw@_EXN0m$&J%YD6_lX-cgZ@=#}B28D%)058k z(B5950*yu0rbG80|F%53AHLtU~PXar2p`O&Kr_Fhs=lBWxYSN+N zuDiqZKtj;5&g<*A4|}_SWzd@MpA{FMJtFD9T`<R6FR)K$NI*tuXUDtEs z9k+q#(|i6`jaBn~s>#c%YBYYP)?sM(tVEA6x$t+L%GU#tv{qe2h%X71i?+r;7tb$6 zjT~SxkiQ|uUq!%B_d!s}HPWxosX&)*>!S>Y;;%V8oO17F2&4l#_HBh@&g}v*@S}K- z@-1S71zN)3ECRtaf!=O=`WHM|bs0nG@gw|K4xE>3nm9Jqa*syh2)zaw6w^2|NMFbE>kbprxjAi-XO zRCOO}_!uh~d272z%Y*gzQRFKYX9;Zp59D*YPXs1DH za5ukxKq4NZ$7sBm-Y#OnLrp&Yu*-=Hj?hm&des$7k+4K1uAtl837EvVp3pxS#O%mi zO!XKncl}b6xi4|B68_?W<+kTK#5wLuXoNJ_hI!dnAp4Stf_^)YR`&Rd{?AQtF?u%Y z6U*DD*@VJc){>c#`@jm5o@4g#-hg4%VoDz+j~-~Z6i$Y`?E<42RT(-?(e9L_%mJ-; zBOfPNu|6z+8$%U3(`J#jz^QQF;hu-fpw(i`R{9%{P8yF}U1{Fq)Ej3=ZN#?PIPfC` zytXVp=^d^HFQ%Z25f_CN3xB5Y49_pR3Gz0t@{gF{QgBN$xK3W}$o!4>R&}?w(ISo*;Jgfj@_R<~;5D9UdvMR@HM} zBO$uPcxUPM4~xpStNy;tJ#qgj*caGZd1)ZZ>je@~oeq7LT36*=jmW0sYf)_OgL}K8 z(DdUXtFr7Ajj+BTzZP(?q))4xrarOUyyWw#?!U2QoPeJFehc-HWAFINOv=3N>ALQt z?f4saxk27dRrq4%w|g!d_w`TWVY3_Q+BT>7Y$oSD5{z4vt6(=z4Ag$tZ*hMSDv@aH zKu_%#?2~yPCpFx9f{X8W4@PY#Lw>TR$Cbvo=H%)dlj3mDI2>wZ+~@j84k-jle8@w{C`{MhF%^rz;;$HBq< z@JFcfKE2szNK`={2NDC;al_&9_OHN(XZvx?UIdnme2=on-VEv6^R0kZa$-91NWM;D zP{#AHE+1Lg4^fvCWwJGEt^O(Aj$;-u5{3c{zb4?|A( zZLecz{Sg@N`nyM1to=>s`H%wJrkTd~3I&13?F5P$Or!Tp-G?Up>h+e3?`2~(sIe%) zrC6s4f(Ikl$S`WVKGC~;CNHNl>YiCzEO64ff!FPI3bl)N09~HrUon_W*SGPzX+jPq zW+)7xKQn(QT3;sxF7QX2Zr4Y>m!?YTJAWUCAKX=)pFn;dPm=>K`Ncq4cdQ{cXn_(` zpY&^H7EuSky}fU-rBV3K_9?=BhFZL-hdxI!A>`LG|J&fC{*GU=$N5Cc>#K#&b)n4T zF*fIF51SXX9ZQ{g$u(6ed~m)I!71J~>-mIz?-TuK4o5jZQS?u%!8(Wi-T+w5fJKcz z8VQ+9vIRKN1WElF%6`9^yjYJEI;oT2t!?tVU3%8asITQa@yF{LW^X>Rbo9D+lj`*o zmKN!WUIbG?e89T-((?FPah(ZoDJ=GF;i6Mo?=0$90xVDLNs$SEup}wJIs>h0vg0HJ z(2or=;2A12u_GC-FxVI3n%OD?wb25!VgEqSU1aGng1*>p<>kTAdhYiKN)R`%sGM5!n3jRxa0*Ab-ia>Q9gy%v!*gMt|SYE@Kg-A z>%eOTA9ZBKk`>#Df6GQl-Pl(H+gk74uZ#asKA|iKSwWI+4;igQ{_YF&KJp(v^ZCX4 z;976>R!mq`1XbLt6cyWlFPpqx_F7=cB@0KT&3HIhZ&s#ZtbQAlxl*srH*{yX-7ac! zdU@UjQaIs5JxB9leCnS8_{4r%KF_Lp9j_?S9EewD_doJdm3R!ZulVa$^o9MCCntPD&-e?047}>7 zT)UoMMRqbzCmL5#=lx@QXZ@_43T2)ky7uX25grtcI;b z(ttrTEk2{dIbFLZ5S(1)Zq5+Xtzv%YnzYNxeL|OJCZ1l+$?jkz`ItHe?s|v)G4R5A zDh%HsR{n`$7>@e{IKmWNn4(HbSC6e& z5znG7UUmk*)EU<|yqJ_P7s3|i9x29K)}YyRAbc{Fth*NawXpFCoFXyydFC7q)+0#q z&ko+Tmw9Ow~_r~;hrGU-S4KHUz{3b($7oMbi5!`mY>?^pRf zW#MgaWJ|{R0tjR!N!9J^C#Nf(D=(R3K2+KHs3~)NDl@h{f2$1c)z9K1E`)0>hF!7# zkllNzW#J7?YW9hIX1yWHY-<8uz!;BIL`}mWeN)mawvW>86gdSogdQYGj#8K-vHgfN zJ9#&!Y`5jNRL2Al)P|dMBw2QQm6yO#?pSo(l-+AyfznEA9ev4bF5R;biUs<6N{1sL zJ4Q<408=;Y-(xB5@zNaT$USo0cp*i#hHA4%5rTuIm$yp8G@(A925~<@+MM!kW8<$6 zBj|_q<(~D&e1%rnBb$lo#8pilc{19(Zc^J{!@9^qqiIz`KH;MV{w5rAj$sVoXuJ;} zjZ=h5Y>&qe2W{h>hytdLn^K<*tUv|4C~G~f3oIHL*=N7M=wxO%M46Jf6-@yt$Ua*8 zAxn5!zVGw?%|LML)=Xf`vL}0rD+UgR-b6E}(=uS(Np;za=9f3@tMN(V`6)-hv$FEK zZsc;mCb-M}A$vLkH3@39Po>@;Z~+4}!iCtl^rD#y8ar};S8>Sb?=FnT?Yk8QD@FAY zT2YRERqw;>x3zhSbB~n!qnSQ!6~ynPsxIN{4MfJoENI?J(oY@@Bejc+x29&@7kzTL z-qyhCkASg~f@mp1a_w(!5}~h?s2mKII%rJZ-qDi-ufnCm>X+FSitktVV~l?^SoRX= z+(OaJc|O5yOoc8vXQFiMfG+OfBOu(j^5XDx!Y+p!Cl!7QP{}3FV%e+wP4&lKK75oW z{xqOuoZIZ@xb=JXED=lnvvO#3442hE4;=V=zhze@=ieuN|AG-ofgW9saW;x)y_Gj7 zWd4*CIsJHhCf0t;8C>QZf8$-y^_7j$(voSq<|m9V^|?RCU%7AM=XjZL9L#oI+0Z1jCB&5us3r22+Ud+n1{ zz@|vwv#Q(|T!O#lFOYh-xG>V|Q&{WkpM~C;2dz-t3ro72#CQF$zJvML-dI<3g;52H z8k?l#vDy?sJ5Mu^mPqgQ`ScW4Q3$+^{2tZnpxFL{p%hQ8yF*%V^Zt##1Het4dU3lK zT}0kwI0Vdm|Kk2kt}de3qCeNh-lFf3-ICKyk86|o!~W%?DwZ`hcpb^U6v*^O zxbn||+?RL=X6n7@oV7MhPLsIO&-DkKBXLCa3m;JJQ)K(ORIB}QqCScWmXif>qZz-L zRi`!G#JgL?Sw2Y|IqfZk#00RBSa2)ciRS4Vf)K4rjmqZ8|aQ?*WzP zpI+s>FhH5fUa!x+YEd2AOYixz;3UgFJQMCUSNm<9W~({_`2E)V;HtC6)ROu+0t(v# zgg}Px_VJ6(IKEH7t>d%8i^nY>j!ttO)$M67!YmCAY$|Si31JdJ7bx*@6J2!yq@{-) zR4vp!J|*KhE#)%0FIFfPhU$9r&*4Jp>Vrt$nU!+~%2;V7O5{GwG>VJ?U-s24L`0Yf zN9J4|jfo!KY1r{)kC@hNUzWeFSkCyPev#Z-P^knSO=Y-=$A`S-ojw6}?$}4gp4=x) za&QrA%^u72@DV1IYCbMIaeE!1ZsUH$Fd?>xo?S1;T z9ed)k=m2mxeqv!)S@WvWLZI0s&I7b9&R#eR_|;ratG<-33e@Xs9Qo*Xy*(h4;fk$> zYYs0rnbsirJ-!|nY=LF9IX$lix|}Wt^#bReErgGV%(4@cFY}Ydx zl(3(^Q=HNC4pEA5*WRA2E2a0VGnY>fk5e9`BBs;Pe(1I>b0U!1(u zFzUAn5NZ#%_(!84e_KF>2AZ`z5?gqkH1`wHlpUPjf_>?Ok*Yj(y>z~3T0ZJdfa=OA zK{_pg!lKK?_!-alHdPt={@4@U-Sti~UN%EMfhbA87G67@FIY3azIHO&Cp-#W&c2LB z@!J#YsT?IN#u97`joWtIvYDw5SAc+@94hlJ71dhOp}~R*1wsP`jmcW7Vbo~un|E)_ z(ltz+Jyvk6P`O(B_rTv-{RG-m^!e@DzWn(;W2sy$`&El)dU~d*RX7sR;=99Bd_3|! z>{{w$`<#XtEmz9_0m`S}e%DlvJjfruSuB2hIWIzh=_MghEerE?EdX4X0qnmrm;K{s z+^JOj1X!CZ$271?)%(32=LGIx)z2FQb|1X-lTrY~2J7S4Cu(2&qWw?5FcCaSUc=m_IF)4JiDA5ArqIh7Ty=N5v%J==&|o_iu`x_dTW7 zN#J_%x6^z3tb}LB9@8-0F?JdLvLcn*q!e>i@~?#Y%UdlVjSpu}fJ*$X-{J@+l(gUJ z8%0zkBUwZh=}+AxgG43%NAL9t>2}sVs$6dn&=h@{$%KL7t2sPRt;9anpv=dUW3c;Y zjJ40D^mG>?Kw1feaBR{3gF@wkbbg9>GK- z^PYd^AHXGi-^Q-D9~ZTqQS<}D*Rx?HcvR{0kDRX_TwvYn&D)cMUcxR--0J}?tr1sQ z02v6@G$pG0J}dBzCLGQ9(i=t8Hy*t~t)>xyp!ni{Cb1?}WF6CKS*dFPtx-7&)w=W)|-j?enB61l&`FRGtprh(KleHoHeigO9YTE1B6*f=(uG|0~?>lhejAo(g@nRASr z`L*$`Y0DqqYG;uN?A*Ke`U~HfkGy_=L3AU$oS@)48IE%Cfmj9XkD$DbMNg4gM4u`lxx0U}5 zUGZq85*}<9_+(NgPyRW}j6rNW`>rirDY=VIkUhFxz1a+a!5pAnqw1Zcchi%CpHuey zLQ5~pr9#&v)%D1^JBg3vvhNKFn~2c%=B4E1`ksCxAHT{hv+q80N}D^Xc4Kmo)UxZ- zIS$9f6Q%kMl19RUi+DPxqxTF!-o7uI6niw7kd``|J;f61goL;e2+ z&hA~i%E!Fi3T7w-Xx9fX_Nb$0xl_V;`L)ZgOHw;mQ~~9|_XFA`;KdoA`ZgHVXdIUl zW~G#eYRf2bdq0@_I+|nz9Cnww7*R4&c7A7(DebmQ(p)KpeAA>T8S` z_>rarG6-qmkD`9ER-98}m4rFx%GG`S`WhUQ^9P;2>yh3gbmktr4F$~gz_>FtSWq@) z?re~{T$cIx=6w3o--98isnhEWO8>ql58EZN&9XkQ5|B@%k}_%2+rKHo;6u49e!H&br+sz&=<5 zmy=2pH7TX27e=WA$VnH>ZK=e=)YG#>TDOyau-UuW5vlL|d5_XU^6nfu&|=>y%V+hx zc|yI%4yVsBG!98><@5H=I%{7XZELqZlOE`^R3g)I9CP_-C3Huh%lzkNn$s0(~B`=y#T2`~JHxNV-K{}jc50ZMhTqrEvVtdGuIOCrdh6?1-ur7%QX zntT2}R`L@uDdfTOhdzDHY?h7fiT%n|B{Me?VV!t=n*I~=RG-H>ZNJ|e0OF+H-$}Uf z`y+sLpM zIa!0-nOEM^usJX+lgv$UxZguOG5LtDV4%c=jg6A;x>rXl`My@c@GBZy_Ozfy(^LS< ztDWH4lwiMyI}kLNJIH^2m2lbtF$?dc?W7&p-^1GLG%S-|Ar}|Pc2R_xpao9;lsR2I08pbLWTsOFB445}#PLZ8*oNd@?SvTygdwas%4aUQ_LQRo5IV zn|WO8in(cVne_T$yN$08aP`Xs3$ZJE?YUpSZ>UwyX^i=?g-@5qP;JbD8OYWa^g&iR#0uM1n8bU^v2PQNrt zmuJl;DqQDMrTMYvD+T61>P+}D`0d-YG_PE3v3SYQb#E7Alps0ZqXDk*G1TU=>=-)n zeG9+>LV~mY)KGmg-zn9OES76Dw4_7)Wh+`olp>*~V)iF2v3&D@oOuN9|6@SkNNj-8 zy%&$_e6QytxeNeIwm9mDX3_ox?1K~CS@$t=txv~6o|H3RPW)a@a8zfop4|M9u~NU> z;4PieZulOk!dYTO?G=F-OM<_Jo6`&t!>*t?Tr{mrepmNVihB~c$@jZ+pQkfGm8bF; zj9&btUXQ(4%Ylo4zqAiFme0rKsgDz*%PWZ_EObC;!#*Et!0>2Zp>a8#S22MT?yJb~ z{w?|k&`)}MN>>=Jjq#0yN@C&VmnjHv7^X|~5n_Rf)fi&p&hFPCiT)XpTCAv}c#&Uk z68?J%))VrGhZg|?r z$^D8Kh}CR`03)1;(B-pz#gyU2)r0S(P!LN~YOxK5peXpEbYw%KnWB(faQWmhLdLPA54 zK0X+!z1Wa+ePo|R_f-3?9f0prsZ{>`?%@DJ%%QJ`&xkCh6BMEGb%u$3RMZUVu>CO+Hh;c7(wLlsVVZQgt4$+8ydeQP7xzWm z3I~A}GYX5!UQD8IDRmwDArwpn+~~^!S6}CH&W~p%gaGbw zvOi9U9t+-$^GH=hPw=u=UOG5O)&f80NlEQWM0_L#vI-{kn!lbp+XaBa;XQvE16skT z_U*Ne=Eoi1I_jQrYZhk*GlO?UQDve-UwM$dcy)mU^bV~-_m6qMUnvA_ijHLbk2gFP zE257*yT=BYu*}DQh!a)!QU1H~L1n zo4d0e)SBVD9NGSixZ9i2XHw?o!Kx|L2JWnOJn3`kUO@_haWs07kBp7?7SyrJKW2KQ zHd1AtGrYkR{()rpJsol>Q`u_P==Yg1PZxVtMQF3^2`|Ls#2lsYr2J0ga9pm=mg$I2 zLbf2X{H7hUFEF?AV?-+POlo<%J>;E@Ds3mHMJS}gL_3|lXnkGw88#iBn_u~(l%HUZ z*y;~59nNP{*?|}51JvfUqL7LB0W_fu5(5#vWvk(#D^g*cU<1O|1?1Abmu1X`=;c-> zI^h~8qozyCiSxTmC>>1a({Y!GK~d6qzm+*FZGxUPKy%p{)a5F909HZnnfbA*RoBeI zO$z80CA$}O=79Xp4~?vS;G97Ai&$vnHQQJ9TAxG0cP(coEl4j$|FIE#@eACq4;&1$ z$XKN!ZxlBdN|5e%azOR>AX?^uuy~Gk-HN@5 zTz^czB6hJ>^Kl{qzn*Ls> zUQ}WY`b1oItwg=8JJHRcXv020#(3nLn`S*W=EIjR%AQv9J6ybsSEILYJ=Px#i_@UV zTd3PCUh{!z06felT5HZBYmrVXL_TmwU5=0-WA*n3MBq=Bp6?;c?z1<0dCx7epTrP$eR38A?k4}5 zY~9`z?p5MzJBEdUMb0Vh>;>ANpIK9ES| z<R*rcGeN(H8C(D?kWZ-bXYJV;A#y%BC#+LO=#ys5NTu7hVN7Efirp=SW=* zsfd9Md*%37qBpOP>iO&?1Y@U$(!b&B)!3?a_c#BvK6r9oma07W`z6Hg%R9S}M}TWV z7oap$!@T^(Sd<3AM$@QZK*GF~TscfKNyyuKgVbumYSL5Vn=1iY7^+pCSFp>+Dx1eA zdZaLoI-i(_@U(c8fh+dvP&rjJSCV^Zun5c_Jn;)|WmH>87hlEGAg;7?fvcM0n7M8i zod1L;wGEs#{Zkk&k}B=h0MlC#C#jVE{BzQpgXt^DjkbPf7b*NIKVL(b!0}rThg;7^`I~kG;PSRM!tqwb*=UQB_$R{$Tj4d_{_nELs5@<5I8f z1H)MoFL$*4zpl+_1uBWKT1!^QItTDPwgsd-${(CT$g|=)L?- zGwXd1@dxk#f14Of@6W!AI++HL5W7&aN=~VFs~{>?N=p$}Jnw_|Io^~5{7)U(PWh;l zpfR_yO#Bfz?;{a1HRp&Km-kf7^PjG{qz{&SKI{7$DJ)4t z_}L_eCEr4Q#y4{!cWeOf?U|E=`o1G}@PM zb8deYlx}2)R@(Q3&~_MMe4FG$tUQTR)^mS2jdS4s2|uMKIiO7H^>PXk<5AsHj=(?8 z?o29i`6oWe-+u*8DxEr}HA=rcK&}*cvWjW}`f_Im^oLixdM3$rdECQ{aR3u~jp=T3 z^+-Ow1AVSf5`BON?|re&uYlU=T{&f)&er>O#yjh9*21E)Q(t&rbh=@6uHjHZa-7UR zGEG7bJ{cgqDyp-qH(&SSHG_$7F5PP2*tNVLj`K%T$7P>*3c&^&H|tPYI>QtLugE@f zXBk!n)-TVG_SKfl)$4p`B4#+fUmRo}!Wz9kROs;^8RCSF`+FZZqLR^9Y>tqwjDgoN zFS0_=@_m(NfJdnm+5h(NFiDRClU?FaPGQ6{J?f84JiysR6+>Fl2pMk5bb}H>wC|I- zRJ%O^+GW1S0o5{{+oH1|fsQ)fR`@;|7v{-A?L6FG6o^amCcIrJ!M3B5+k}0#XxH9U z6wcD?ahZa{i*-hABlj7~vC`RbCF@U+eAbhw(jV;^88beX24SgzjsXFJ%;mMW)NJnbY|WCNA+t9)Qtgd9ijmDeC$udLSuwTVB{LWR5&k^ zQ?k2tNRk-((2795cb8!P{{6D_LpB$5-jX5Xu^M`6Z#yzI48)$~$ag1NZ8ev?@mIKF&e)%PlXm#-Nh{>%bmF9cEX{xzwI zLW`Ch$%;5)y=C=263M?pV78&*)9UkaTW4A0a}IV8?b8@t0Ek%lU!DsAbDg)Vvw!~v~zYZEpVoI8B~u1*I>88R1mhU2=^=b|G04A^t${06IuMQLn|RI*0*2%&Sh zI=*eVV`i{4>EdxnRh3U)2Vn5oZKbs?b&$w@i|Lkn!ZqJ_g*^K(`GE-J7$0{MP{G^c z)3DcRb}E4s(IJ&Hi@+TJ_zBmGZ7JD%yDs}C5(Yq*yo+-s3KmsJS#iIB6U^?B{(a4&f2R(ZQ!Sw zU=C>*_V;#A(I&W&O&gpVPD&oVLKSoHB2d;f95R*x$1SSf)Ly(GY*YrzDS30 z7AZ7Ak}!i>jDKCPVv25;{3d?2eG;sT*K=ZRg%yNPI99P$yW^MI>_n{{L0~$l$3;K_ z0qqAf_n5}ToaURE_R`-}BEp+N9m*I@ZHNc|xzJ7-T>e%#L?gVDn@^eUV(e2}@7&rK zY?HDgNCD&io4)70I%FAN1LQ=GCai^vqOFJMz`jGPlHnxR+g?4eq=~8cRxR1RWAaw( z^D)oOAg_Kk9~_}9G{|*`@Q_DM@Z8p_+`iRN%nl)Snfu26xy>SzwuBMX#%WK79Po^q*hDvje z6lD$~|KVP~-F5H}X7UNWZzX^#{X|Uw)Ph=iE|jIroVT=M8ZnT^xA$2CC|=+3cO9Tg z_dTDwyBKKK@ue2C5<8ju$n78UF>`pL^}7ceH`&jqPiH&IM5F9Vrvj7^)E9AI1K71D z+i1M~hO9brvgx>9ZvApPo<|v~kuQ+ps$GmvQY2*n^{4mlV?TCe&^br;TK_;XS+l)d z;BtUl2g$zHm5UZ)RsFG=$_4pCL&*5H%WI&gSqRKkd%Q)rDz|-&ckfmJHzZlr zXyzEe$cGqyVlR60XV6+hhS7lo_bQ5f%A4ZMwhFUk=+Yzavc7mXyRV;y@$4>D%@)st z?E6knkEe#&zbZ=qF;9B?67Use)0kbmA$Oh1;?L)ed;8Q~559Dq7#TpxxzUs&@5+~} z$vAOzr6SORyQ0?Mr21GK(Aw~9bHWV`dk+2dZpw?7$xpW%aJf3|cF7~1n`r_up3 zQ;CoduKm5D^MH?ve~KdM%iJR(7=5_Hd>r8NX9Eh_;iuh`VRcUkfU;bYGD~Rwl60_d zO044jwIOnOD`R9mr~K^rHIX|&lEDQ9SJfPPTFXOndk)k+@hXa^8{h=RIdf@y)s@ zTN5`}yf*29T=$c)`GvIK;kN2y@M`(2ePVf&p62s+%jCy?pD-Z3v*(9k?pxn=RA^}J zI^+rMX`;Up>q?Qn=A2pmVbTlCy7e{L#OFnN?<*)Dv0eA))PNs=PF{W&KhT=@)~!Yp z+{IIK-h+9m=4BWQ`RgP&=sd!uKxgDcIJ;44l#lznU^LVFWWPF zoj&CWUzb#zCFU)#;7;Idm&&+_KFltA>vi!S)1s}Bp`#3f1JUJkn64Y)a`lGBg>8Q? zc(sG^Vu*LXcP%ccW5?lVT%+gW81#q$w(4J9dV=3K7Omw?SmeUoN?D`y3N@X5W8zZy zHJV2iDynY{80?%h`1l@;2a?%T+E4!?OdQ81z@Z$Ry!mn(0ZX*I3jlc-4&hcQ$4o^t z#8Yk>o#T?CsTDugyvN)$P|?n9Ne=Y^S3Re(Pw!69uQ_(o`bJ*~IoU^g{W?M>^dW@T_;BRHVzUy{xSkDXijD`^zs)l} zq!21^FQ;1u>QpO&WrUE14>{M_UX@q`bsWhro+Hj$F3*q{y^ZiZt0GBtvKh$A$6#$$ z>%!;u4)MbiVEEPQzs3$BEi=YkXC4%M{Ln)phf_!s{(-#3>(103jo7SSqDzvm=^SaT zTwW3VyawleneMzf>)jds-JIpzSGf>SYXwEqrv1RZY(rWTQ0?Ep5J~dYaZPXDm{S)~ zzwWLMQV@I3DMlXOpbbxBCi42cSI^)bs`%~XviqWU@3Si$CxQ#ss_+Il71@aMC!wRJ zP`G#K3ZLZnXOiss13O+Lih524=CpLF7(rV|TS0$B@_P}0%e11oH$}lbhy4byJiN!q zJXp*KJGy>&B0B7$VZ+asEHYdi)%NcKfjxdPCw;JSRR4l9}yXj30p){@s zxgkLsr0NxGeR)5it3@xVkQE;BIBwnK*krCiG9$*lH)_XM@=gdV=Bf5^4wd^|zp z7j9effjL(!8vV#$d#B-94$_grJHs!{BhJ6>z3PXf=U?BPkkVrGOf?^QtRob&`3mdt zqe`WRDE%F7$ZF#)Tj%U*tb0SfkXG@b605hFK(I^W5^}(w{q4te5aAuwUzX`#+Vnm) zG#peEkxhRZD`$$V1Hs=idSC6d&zm+8wkeg}r&owr-J)H9AoMuUN^Z-{Z?|kpxk9rg zfx3`eQ;qS(a01bB##5reYvq!rVaHNVWbdUDCRo~ z4{xu=tW+735tEfN<7~EGroBD^c&)^ z;RkC$d!nejq<=|sv^#Xm)W7#eXX^!ghLxrp>cWW+C!c_;a9r7eu#ZVlf&61YL)5Hj z`;Cw2puS8kN}_-!%gk)yxqewRXgJ4igSMGCCVZTB!|BU#PL!r1|F8V=}I)5Co^HO}YIO0ii)8`*2z}%sP*}jdu z-zFn=>bryAmt5pd{ysBBhD3#{fs{z)J@S(^_dcyWiR>}w`4cIHi#0BPD7!fx_E*ZW zsdscGuN5(dO|u1+hwNMKr%nKIV7%Mw7s$w2?n7J}qY8BS9{{@tf%7HFV16D=AB~|# zs~6lzq}*DTqx^>pPfrGM`_eqHm-YC{>)GXRbuLV-Axn#o&L3CJ?EBev9&bw1r_)vP z%zU=k`TY{&6&_R)3ZMEOq{%YO|g6<6!o{9ByPlGdV_4p;*rZ(7} z!rSKC8{AM`gYWwtMDC>$ts55~pJCd`qH|{tgx=u zid5T#%vz;#gpMd2#yvkF@>Edx^o(L#f#yf_`x;SdrZsOqB`N)+lP0O}Yt)^Xxt_H zNmP0{9+mwYhCcK<@bVX~ofLA>)TD|(_>ktUE9;l=7Q^NJ9H=u09O9wTZ(bEXFO=A+ zB8n_!@oH<_9*%>Gl5Q|dikpg&w~|^jih1c=6`-E4+HlC!0adw`)o6hku!kHBF1lgK z;-R>WhmQeGEpJU8CnI3Cf*J*x9!{~<9 zQDJ5me8`h;*)M0sXOcjA-M&or7{)Rgr)6<`JPsLRDq({3^L;^Ybj&Uz^F!P$*94jFt? z+NO*t3A>s*bmnTape~0pL#49>4w|!qTwjfw@f^jgellEjsS!?P0Y zeL)ib*jasWu^1BiyW$M}&R6!2tYY3i&rHsQ)<(t{>_ZubGH|Obq}OR~4`xik!+4xe zq47i;)PcC6Q&4gha{Z~G=bA5NskjZ!%)Y`1G41ZRQ$LeVl>nl~IO#aK^xo5}C;O+D zsQs7+zG8(n3#~X5>TUTUlXgQr#rXkSt%+b);F3bFCxclAIa>*sfYWnaB08lT>l;41Vf!lhUi;=l)#=5 znS0se-?qfgZ|UYddT%dp*E81JC;VQCu%ZTq3xG%$ScV14dyz zb2Qv+8>p1*%v|n-eLZf~1wEun@)%d7WyzVWaSV0?Fgr0Xa0^aA-}7zjy)Mbh^^JI2 z_aGUX5)co}Yk_*QX~CQiU&A&2Fy-|4DWA|VL!rG0Y8;ULHBt>#EnC9Z_LZ^B=a0-3 z)bkl;33DoQ3#$|VG{GAc3(kDZ_f4Zem_HQS5IBC{cWvxl5>Cu5`DyN)s4q3Tn&1B3 z5y!*#X`JMiGdo#F7pD4ntz22`_Q2C8AFR+WU<3LGcn?+P3@2dXV!|RKR##hr>S{TE z%qkI^KzL%gXQ2FMxk@495d*!IF>1C61H5nnPa8jFPZ@Qf|nVFm&4R zTbnu8n*WRV@p#i6KKY~Z)A_p!8gSg~XKY@O-o09JBW#Of4(DWf!SLdduYhal&9fo* znC@ynu6AI_uCFHAsGy`MH+AI?X4mD1px(ncR1a6$MzZUXe3#A#SUq;3y-c9@_R<&( z<(9kwR(WQ4eAddlpu00?zBN1l8GHc8Et~>Bdsn((t!pkOzQ@XyHgyAZ@Q0ssO%sXf z48zX|ar}%Gk+>i;?4h0qx5fe8 z5RYvc`<;9uoCH~gyXZ~+a!uV+1D^EaACOjR02mVcwW5}6nHPTXhhZduYh-;glb$CZ zj=!N$8PFL4Laq2Zae1$~oa54jKE1$yeENd&l1s2C`OYGDJ3g28hh1O=u9$W7rC=`v zDkbdwh*!+im+K87())&HQnm;@sUWxcBJEQuTAAQ5uX$63`H#LH`{(}PE562c<=$LT z8Q_WFTX--J^a?l&vN3OJ%hs4Cgn48?$6{)&PI^cCiVdsR^CWx2QkM(-p_OlYTSB>{ z#9NH*5nA%x(@L7QoZISM`g55Po?@lNJibH@6w7$xow@ zM+lCVuH`<9>wg*YK2Z+zSqBsHr44I+7=PX!X`{`TV)kv;d|_>m^O^c&p7Weff-CQD z$_wJbl%VoAHog88&J=VMy$B()XqCaXTdG!n#Mn{X6N3$%a=A6%(!03^4Wb)zb<7nH zT1uOo2vjBm^F*Ep*K9vo%K>EwQ{HQ9B=rjy%0(@nitC_dc(X-6bh;486w10inf&{V z-Oa=i4{p>YYy4ps2rlf1-KZi`gy8IZNwiIY38iKyiFv#H{@He;l=(f0j$HhM06WT* zH~sctGxL!!@@RX^-9L6cnriwl%V!Kf*pU#L$wlWiLJ$_nP==rdW)w$* zKI@iZ7h{8ptfs=C>xYPf-h1_1SWNfbq!qJL^zcS3b4upYjn#i;_bnOZ#OSIZZ`b*9 z%4CPkk;MNah&dy`%xILd`rkk_uAEj=XeWPQW`l*a$BdSrQH##9Rp)TD0HGFBteZ$S zsz3UTa;B!}qod`Ant%q+G)M1?07#&}@ItsCu!T{s);MEIEAsHXZ?dCT#-Ml_CJJFA zKQOR027Va0bs9eSGKDIg4<1lz``d-Ht9W*N)Dmfc{4tIcIG>H7wpHP9J(j8}SFku{ zO>5iBsUV%gP|F})C+$O=sQ}9wK0{CasXiv2O1OM8i;vu&k8=X>3RX{=i&|x zIVX2v=>TYs#nU(xjtnkntnex6wd@)yGT$7qK~uJR9&@qM_xynFaH1e!SB5Ss7%*v1 z2pqH3vfXa9p09@)bN(4gx@HUvH~ni`7BgV~IB0HP-oA9qjykj%v!*ID9D`-jJyY%5 zCA@Kw2Y0A;kex$vcS-B|W^RPmYW=xbLSyVT=l zJ@z^8Mi$%-lU3fYVESaY$Qb$hc6ttqbpUdnciLrznjnq=}CV_Yzm|!u=`EE!R%xLl9Ac4 zwe%S@;4I_5qA0FxKl9>jH6pf|U#K$#4t{Yj=BO3!2E99W@~<`X;(Zn%?fnIzB1&IC zw>zg|YVx+iUHMa;0_KmNBf~;qL4U~mG#0)6ox-g->o88XUVQs(g*{dNx>`!ejS=L1 z1?Z^q9v_~~Lw2aHFMI1b;<=;mNXt?kK`FnOZPwcLYyDm{cs;yJs{y`dxVhLJuJKPmT`CbtN!Qn zcZFvfdeX@C(O-Goplz5{uYS_j%Hiwdxq+$)S!S=^&$^8iniX=c+N1M;tLjgVuTOuP z(>eAp`;4K0hQ~9a(th8H-|ow(QVJI@`kndWqJ!budtPv1FMGrHlm!F0!B)?=$(Ijmqyw8P-_+6ig1OWc(}ImT zp^f{y1jGBdS`&d^4gQDhiwAE=O=H*Ry^!VsTz@oHV?w~+_c!nxos*2ZB`Bs(0C8@o zaV1^xy-ug!zCqj1LMZfo`yBiiyX~WNYK8u67bT?(yZH+U~o4JwD7Yblac=32laJC+}X`Yf%*C3T{kdro+ns`oX!G@ zqeuHxncBG*t@&)5y-TX)>EtQ}ixZ8Lt`-p8`x;2W^&4M^a!)~&-K)k@6kKj>%2!0Q zb+`JAcB@~2k%?fR_O7BqWktJEln%&6x2a=DW|T8g8-$oIT=V{o;v`F%IpjvwT3?-= z>*x08Hk3Ad{n)c2!<;ySeD`qRa|k&ZX*FcP^UmpVg3*BTxNB>;=W_L# zgP?7X*VIS8R~FhVF@NnQaYOT6(%T&$F`E401LJb0_`q_1*n``PLnkqcd&k324 za&LGyi9ofs{oB4E+%Bv+k7CPd7xA0g!St(#14)*Gb{d%<1>FQ&o-T7b-kVp3N*Mbr z3_b52pBWdCM`jma%55+Ml#l&T3W!H=%9)zanX#8H?5y3Z^HQ;=wtP94O1P>gVm|Fd zrucBMD1s%i^LEo8aR5_be)uZe9iGiagN^`%UM>I97T}cLj9X+pA0B{zN6`4?U*^ftC5O6hr)3VvZC7uT7$dDv96F|5g0_Osb5At9B)#kpFrL)U`^{YGX$IG0o`n~%{q?MKcOLK5 zc1wBceGmvOIo%fl1p}s;BQLp+PQ1^c;;YvI5E1X$D?}HGq(sgcl-mA%fk^VDpHt<1 z)p^|iR@x?vgEZ@Y&>SPA1a6aX&G?Vpw<4Wu3{?hvxn(@wwjEzcJdt_9tns4aBhz1` zN;Tocvebb2UO+V%c0`Yx{!TM}Na^EKOtaON;N~!c%vz(ZEIaKh_Z6~3(Gu>TLj1zb zf?6d#dzI(e{|$Z13|#4zi#4;FkznKPP?||U-{;fZywU_o-T46{-cpJ2c?nmFK{8^W zP>Tv}77fn{cdLqiP#p-gcMcAJ{d7*ipNU(xI<&{3ukK)smNSTS4UHDRSP~q$FhvP) zvQf*2_va9vT*_C?-psw;c}A;%w7-I^0%jqt48SpV3;?+3Yi*o=pLQcerV zWQ!Q#%07mmADZr>duPAy)9P+}#QIKcKj^A7^3k56A3p=nexAw13TbDbzD80 z^iTQH8Waiq5CL}dOg+P7@O_ozv(GZe`t@c(+um*PYHm*N2k@~me0}&$%<5cuIj>nV<~DxaueB#=bXz+jh-Tjm_n&!6T~c|6hL zn^W8sRGG5Ks8o%kQce-m=sP6=D{>~ z8MH0FMoLHeOBD4qc&DCZ%&*L?1ykPi-ESjV z>22pq3ljRn=;XB?VqWVArWiMA|9Y&;dl3(SZxwvFh%Yjw!wN$YG${O$_4e(+o|IZz z2X8D0W41m=A9qX5JFg#=eRdbi^hF`V=$ck_IW5{-NaOOPok)CVLcBP%X~4CR5bamT zJp=unQTi((_XsYd`qKlgM*&1cd+#2*;|$qAgRX3RLD%~&5o5Fg$SZ(U54HDtg;<|i zn7_q}@%UziBt7kkASM|heEr03*NzHRn_VN=HwklTAuT27eq$STLS_CSiv9z)ps+@- zS016EOeoQ2rp8M)l^8vi50`fvn$UOMi#Ki&h8(nJGXz{OGjhmiHSLOE}fv<_55K`u6kr zHdXQa@$#*SIV>K^&!Ae!6ev>*h;R?{Zg672lvu~-?#myfGVGWjvMbzfIl|?_S?ur3h9u?JfZhD=~ae% zfTraF#lvOtna*P`GhFGq4_x!2h&Xc>@7C^XGk8_|gw>93e?t!BaLx-LYYhNb1p0D& z^}@hq$UB0cR4zWLyI7x}+!bOsuFZaD>{&GG9P^J>5X#L zbdPAUZ0(f`GI!3eU&$-YeGl$^+I`T;{fbuF3;R2~sS-)I!US9CBNGGXN?(`Y+sGZ9 zRB8P8fkeuqIsGsm;|b)2&aN!jr`dyg{oOAY%0xxP+;<;e0B+}Npo&ErQwD9pVIv2t zl|-KgBcpv~GM)W?z^8+snHA~Z1h?M`e(=xlCoRK!>?;ZPfkV*uXDEUKtnAZ%dCd1} zII~4|(m1v_{+Ir`bK<(sSO8W53TVZL??bxJR~_yLG;g>zBp2`-xCbl)r%B=gH9!84 z>eo=T4O1C2JGCYGT)lMVD2>TUiiT_E+rz-DT|lUD%e+`8w?F%YA?NKidF}Bn*LN=w zXyjxCV(bn~y1gY~ztx}Q4s{l?v93r|bSXSMewol^BhKt3jq=@VRT2c zUcS%F6Mwi>ghYCdu6Q!N%T-7jZltlw*`~qSo9l=O`Gn6SreA}BJf*ncOo`?#$DbZ> zEA=?MY?K3C`rGjVcu$bbN?V9Sf^puD963o!ss)U!liR~STYFl(_R-Tt6j!BA+HY-} z3?dQpSV6gj!sl`Sv_Dxdk*DXUu=dE5pB{S6UNUtH-&HFy#6}m}DdW|f0rZjPk5eDL zVeS}B(yTjojL*zjdpKD|lRs6ZO$+NoK(40*Xp3tvB_wuDNIFiqdWZe(J45buG9y>S zoubfbDc>1oUrXQ$^oz#BExGzc%H-C1CRO70EbHvIf20d7-51sz3seU-OPj ze#jZt@_N=no}*`+nW38ce7VPan?x3!p@W17EQ6)4B5EI-SSs=@ z-xhATQ)jXAd)&!@Wn~q;->z#YzvJbcEs=7B;5&nimL6R9a(n z#C`*8B5RD;4u(yLt{F90kJZ!0bDARfxXq)Snk!d^zFd;G!-8$6%sy*@4y>yLFm*6G z0^OUV@>=B!O+2IckjNGG9BBD+;k4>g*mK}tkg}UMX>+as7gw@z`KmqD=(%nCk5BPZ z)SwlIDrq6oAoKare6!0L$!GT2uNAT{+Y8Cb>xVRSx42C;9Hob9U%8Im^IGPt9o5W} zIKu{(xYVEJa?97`#$9|j)ox$!Gy`sb8M=k}s=~8}4hwdb>Gs82#E+N1t-2IQC~~gv zzqD+Ae1gW){E!iJ!ad=V+-Xu(0%*I?hq#e4QpQpCxOh~)#>yQFg23l5*rK*mvviaW zUC9>KZgUM3Y}xm9Nl;wfz3w+}=r4#7=*xHXNWG%6eMcmy=R^9k{If8t{#0P&iYNX$ zV577L{wmy{M2xd&avtOXmWr+STT)&~7wj^@s>H@(bBZp6)H9NJiSACZ|^&L=Ik*VQ>2Nou8It|4`28TK=TI zceE-M80W!VuLmvap51HmQ2k#&xrUrTPBfiL!1fhPh%z<&`Pn+U>f%U81 zkqo3x){nFOTMzlt^Gl#vNK}U{I1AOSVx|YW-FyEmVJHsqwUFmUy?G)pSZtfB0gtUP z8v6rh{`1y8ABJHGpTk@KCHir9yH_NA?~oJ#N(b`?Nr@EB1oiX4U@M6>&EfH2&lFoY z%Oi`q$r0WLJ0oK)QBx(`RziPA*z`25MOt-zSMSHeW4@G_sm>=GWlW@uTD{+^=a|Vt z3a?X2tdJJZ4}8{yQ-EeLMkN;dQ+MNKLhFZ+7=ts|$i_|Y3i(6Q>fO36uUy3=e6(o`(&c$P@RE*l|kC_mt=zY=Yo+QOm zc$evv!fbum2g5!Gu{0;8mV2}P>nV;UgAY$8^t{P_a&dk@?6zPypc3~&yX7lzQ=Qch z=Aa`2Fm=298uNGC@vC`cma zr%n`}u+-k?sj`z}BfIMCnR_rK<9Li#(L=rlyhJfv{GUD}>RV?@Y(7c)H;;Qn?78GuzW8ukNOf+!H2Ol@ZFESUpa;BwIr!%J%6|yZi->CT_~-K5 zOJDn)>|#=B?9=`+ACoyyFOPsW)-MOAz4=_At8G@q@S7)T*1yPD+T(IC)Q2Fv=W}wP zU8kG&i56}H=w;aO+gIgJYbnDHbRG>$q6`M}DjuI=JuiR65i-sTG8e^alNc884?Zu# zH+`OhmGC4%Yw`Xh6|}v8IdyjeW)daHIr~V5rC(yIiJ0t5&H;C@Ac}!;wC7-KEolZ9 z3Q(crOf!FzaEYXccUH7pd8Yus1BMPHEScL^WcjLoUZ8ar`xf|WuxdKQ&-2RHCdH8P z7~83LnMl$S(eoMH#RHxNcBPT5S_?xnmH$i+B)B1NgrxuHnHneWp9)UAy{(7YI@M}) z*AWlBU<8f-_;6$TTzm%KnQ(o$``CL^lFWm$BTiFR8Q-VZdfcvlqjnB`vY zFE6zTj9fe;5a10NIAv4EE6eh3u?f+#IxUJvl z2YpgnM(G%tdt$@XmUlf4p5bkp%ID>2B$%>7w4$e;H0mT#n&?&ArD>IKlD z=7K$@xRuIbR57$*nSOldXG{9=l(~ry_(+45+9z<~h^_sD&Y8Qme-(Mm+ztcIV+Eq3 zefMahYd(1pUD!yEV0wSshMWe@QeTj)o0(1e;hqi6+eC^LQTIK9LD2h{=BYkco(c!<} zz;OT%gv)_^y5Hyd>gK;Bak~ig73W)oUX<>oW8v7>v;zdDtveE%-#=EomKM3~e!}Rj zIM`fyh94822n#%Y^LzRTBV`#7YLiU7e(2i4VDVR5b%$vMEY#~ckiGU0THRNqC@BKw zwsrEb=Lq(P^ShKJCqYxl&eq@$cRw)UH9UOBM{z-~{HgZxWLcH=CCyj4*>8$Z1fNQ=oRm%{M?h#^gy&AzPt=!fq8T>5n8 zq2atS?W6cj;gVxA5PagEyy#yqzC8EQ!<~e9)p6RWSNL1hqx9F>#yaw*xCJFe zNn#tV?}m*{>YeQi*{gxgXBw~`Sl8|E^290|M2F@MvUfz_17dE$B73b7Wam!)P=gZx zX*fP?b%w*pQ2&Y3Y-bo=Pjt7Yz_jXN2D~+7R=4UJa~C!N<+4wJuwmkHTjDcT@U+vZ z@;HCmL#EojyI9LXu0d7U_t2ryn>%_%p&8zDpDcG8-@pb20d6y8TiEsMag(N9_Jtlz zkp8}(LUotR(?_D6YFQRMM{SPkW@z<0@tWaUkU<9pJy-1?P-3?GK+K;Pq->Gn7hy$4 zw_=k=`xsepGPI~9hZY{N_hNx_zVlPTBl@6|Lomt<~cP=eN@0vOg4<;Y%bRAH&sz zutAz@Unvfje^a?NSq&YDw!3krYVt|j*NvWJz*8$-2)#1%X45^uSn)goVp766hlF;{nQb>ZxI<1{CMxU1>U2i8$fLOucv~2$^>eWmY{U*H1pHv9c z$%_bF!VQ?z=i_0VT8>0()h_;3)JuT+VzaLXdus$heW^+Av;4iO0E4)Fjuo{BVSn6% z2|nr$pOg5ve7diZy;Dbobbw8h}74_TboM&h5 zo03B#(_!C3xt3xaVj1+z9EH;3g;tkKBc<#fB_!Vu#zFmMEoFOgmNx_TaEHOjyioLb z04FE&3PwQhm+U#SdL=F^9P{u}*H$dOsqo31tZ3a&i0nsR-B6Rz7{KuI4@7|Sc8O|| z4*F(BN?e!)=%&d_HQG--WnW#gD_AbZ?K*t8C`Omb%{{vk6@iE2}y-xT!V zOEhHZZi`u;JMera?*fkioDz(4`T%!w4!h`dUkP){4Wg@z)m&(!s#=TbHj0|FC$P6e zbT0mE$EIEw>lB!3e;tkw*WDtvXSr{x{&CEe(V4<5{gs!P3x*GDV%YCxv(yVQ68HCn zZfKAz_aJGX579ZP(r1-_FHZmYMJ>fuV#EVr4;BFj2%$^;Vt@rw(~5%HzRspI82P)S zPQd#8kTj`ZGjZJC$wbG+TxM&h_4VwH4rNe}WYjoVMxj*^PvBl}|4&L|^NzONaf=DV z7PrA^D~boR#FQ>Q%RVw6ak>aTtgxe4V)?XsG&tDs(GKbB0DhiOkozOkB=+>Z)KB_w ztd0|GIUVwQtbZ&O>{oN3&E*iR2Ts{$xV%weWeVqua)>#YkqK|pDpvZ96b^_`ZspCI zb$?=v?*+CU;&+6PL!P4Lo;;;LHKE{Fi`hiEMB$H?jP0$wL&BdBPYuT)SW; z^Dde?Ty$UhSMvSFPk7p+mtwx60DJkU-y2-H4gNhDyV6;h{n8Kb z7e76#Wu|r;O}RqyREL`fg`SyXe~A9X`>hHWrNhQ&UsmSro9~PtA)()X?Z32@DXa!3 zQ|`eL1}YaM1!zXJ+v8M0zzidH*tMep6-RjV1DT`?$#Y-&zMG)xd*B#o>+|@;@z|LB zZpr-E17zF}=bxyyE`Gn-d~~FCe>LSYd_qQK#hb&hT{9})Az*&%^oNDap+PH8pg>+Q zv*R#)g+d#1>}3HVhWGCEx?a`deE0~SX*MD)^EEt5Zbg|;TszW|ZQNfcg1%=<gUE<_)~j>nf#3!U^&F?_l}YpEN2W%!5C_GHeOuIy4tGB`8P!; zIt~?4wBiP#g60qN=suOca$lv((S(&KiB+=nz8P_gzQ_VT7T8Vy^+0%MwR`1v zVB%tPv`@Ojz%$(67lw(sf0SQu^TgbY zyGm5iFdJbqe;l|WNrbW`5!1+_dPw@)ma^=omF4;Dl2N{|aBP26aC0)mi1=052+fp* zY9L7JX8D9V4*TxzG9xn=Gw&(KsMd|b=1F5lYt=1e3obA_hqm49mV$EP{?%_Z6gl~; zqMc$EO|(Xb_-XX1{O+Qq=2IB)dyok3i+GLpLW>MPp=sP0eo%S2!_~vE)?c!I37hLOc=!;2Q zrg^W1D=!Y1GJJ`1jlDc(ys+9j_<#Hy+*s_R z!o9TG){4il8}v_0?~Facqu^0X(P|5CXLok3kZ{1#Hrz!~)Ytu6HGNpdEAz3rQv$)z zYTwGCJUg*_xIi5`9pB7-y*zBO*`p8&IW`}ezmXk6aJW9nTw^^`0I|PykA7l^yEAWB z%QFL{n#{8rp)ywE^y3-#-%)bkFg^zmRDAB^_zGbGBaIvSG+mYj;up%D z{RXAL=Q$N0)*WE_*=O&>fMV}uJ>ToPpo^tkQy<;`mC;a)D0}IL>9ogvgsU0OIn#fM zY`SSy^S81Y)8wbG;P}m=&Et`=IMaQ~*|m;{Z}bWgSmjJ}$&z2aN2%|OdwcFcMso^z z&Gp;$lygC2w=DQDE%z9gsD4$ z^hYvP)~pBO2t!X!PKxs55Cx*S!Ddnio;mJ0>2n=USaSlB691AK%wpPWreHIHNopXT zK_pG4i(paM=Mx+CYs>}$@)lUTh0_vz?%JNWzS`HbxpmOw2h5ScCAX+P7EykA7LXz+ z;Zw7ldv|cLPrRz?k{tUty8;$)TBxMa&8*q}HeIvx$ow27S*7}u#25Bo$b*_>%r|gv$@rP#`VUdMU(j(B zP3zbmRinx)?s2{^|1Yv*&xiLqPf(o!B9!0w5kS$(Mm5hw{4wY6LFmwvk{VIZ9iP>P z`btVi_s#jRVFU1nJ_^vAXnTBe+LsgexnSGEe!02z@5=V&7&LmqZVo;^oeD($>^D%M z-#F!bHV9ZVWoU7tm6p{dW*yqGtGJ^W|*6`ab#3*dSSRiSFB2+De`55x7$1@cv9f_s0(&vH!N=%GvfN(&V_4UBF z1QTj^{|aNez2AW<;uoOdtFHof;we$H>%@H;xQewkAx_*=I1Cw8k8V*^O5&kI;AN3xbM#j;g;(duPusW&e z<%C&=ez1Niv2^|CFXvK@o6_+bj0U3-4A7qgS-ut=XYyJ9Nu?ejn-zLJL!)pO?vc&< zJVx?#fBDuDVP4dCvFsCFC-$75ohRp-yv?ZGuSB4d_5k4~u`ttpf6C3n(~c() zwTjE*043ORG%ki*=-Si#_0dDE)g)X|aFpI$Y|B%LP0>C#im|*Ok2AhEf5sk0cd4XK z9jt5vc{6Cf?^?Z#Pxn58>96|@2&TO5#H7iK_k|8A4dGFzw7Fr+zSXp?|3(JbE#sS7 zgby*FGa;B&IQ?rKdI?lN8EelTB8b0zYG6?EI(PeT*Xp4if}<`s+LM`ic8MMr6}C^Z z!kpl*aV#Fw!+&E_`}(}Y7PcNM%Q^B>KkH&Io%S$OCNH5OT4w~w)!<9YqWpHF#Jr}cv6N!U+OqXVl0Uc!!-I|#NP_z9r(>=C^l?GQ&9 zJaMnoJX{~-ZOK_Ue#kGu95PM$-NVn%1}r+qf`Q80$rTfQG{koc@6o5h^;9eJZ1=$* zk8&D7lJpHWp%fYL;@*O|M?eK|fy8v%!j9so+Z>%3=&`Yc!16}dQs{aE8T>X}<5!!$ z4rO+i4ywdUk9;j2^c&Xr76ppp2{VR5wn~!ogdKK9X(Q}a?w5n*HH3xUNv-F^HW&7p z>QoJLmltZmv44{)ZN1@9%y^pV>7s6?VpVI3W7b{Dg8g9X8CNF2fONQ^r)7u zk!s4lA)}4k^L7p|d;m8)y&ScpamWg4pBZbOE2d9nda!E5KOdw-R$Gg2_Hfgr`P2#F zm;6gw_&i)@kk9#QetjEewuIW#S{26jX5#tMveN!gtrl)Hy}i+7>owxHSn^pum|D8M zbn(pB3Qx;Z7r01$7JJdSL=wVy-d{Cg5&L~5uBRHNU^Hx9ib+}jm>>bWfKq+EWf#rS z1WC*IhyQ2JqF}EhV6i^Nso$4vjcD&Y8GRnm6n~}tgYyh%H#&ajnW_C_?jyrS_r348M@^4BpCd z9$`mFd-U@>mmTbv!p^YqlIoSTpE7eHEq<(@$~*rAz!y8PCI+rJK~?ue8N3sGmzT8P zimkO=5_-}O&$H1I+jnrNehVJ2OAJpnvm-~DAdbf?*Q#d69hntcMonMo8YURHxQip% zCDKOy?|?Q>mZkWm>%xCQz769WQwcztcZki!;lolN|N1e}_zGl->Sc=Z zvDVLizv&VW(2jt%{_*hhTqc{D`zV6NjV8Wo50aPud?U#v>er_}lheKB-`de9e{$G8 zhjZZ`Dft>MR#RGH4aALQzuha2Lv2BZzn9s0O}CEg^rF^zGos8UgEvUDUH%71LdizN z?WcqfgOX2wjOfu$K~8w;Gr9w4C1Qa*NdTCfEyBQvq*a zQ{Phq0Sx?A@PHJXR@#N91*Vs}Bw`qE`_iwV17&T;)U2oKar|hN@tevke~Fd`HL+;l za(wA3&m;FvT^|U_>biVk;h4f_7(ZIGK!6bM7VCntq!RiNaKIhBQAIa$k_<)Lu`pB$iHpb)0e;Cgul6=oWS8#NxzMEoykRz zE-?+7D`p!ZqqgzWKL=N$K|DMTr*%jWkgPh_?mH1+-n;Lk|D8F`TD6#yptPRJXtOW0 z#d1d{p`_z2&7Kw%r1z<9b)>c1U$cKR`*Pw(b$QS^0^Aip0_St|4@anARw3D-F>yPv&_;eYpaM}yU zwp4erQ%u@X>u-rX^M&znglmhbu6gX3Ytq%iBEr%M~6pCtpCJ67;qDY$AM;zHQ-TtWF01 zjDZgW`Czr5QO+-j^sdcs1G?_@= XFu0z(h$eDrmAGAR-}5SG+jqaJ5N|Gpab0Ga z%!!E|y{w@PG2gmLu2>D;d>>e|;BlaI|Kq=@XQXo<4jZmye|SFXj;|@R8{3+PaePWbrxJJAKc}}5R#7h zjOQTC&$@BvCodeDQ&8+#ka8A{yycYuN3s`J>i){QD?CoPJcIA-^5(@San~7SlzV=K zM-aw3-~HQi>*76da4}pHIM7{wF)wU_FR)@TAeqeEUUW+e}D*p8(9=$M@CErAPhjqxW$UD?5ddJ+0^WJe2e9B&#l! zog1$!2>AF11Lq;{rhhW4DktvPzw>^6oD^4UErB)@446Oo6DD2njNI6J6Oz2`<9ksu zV^s73>1<^0V>vfhnlJ`lw(hKpk(a_m)(75tE%(oGz1Q|7U&}U+%0N4fc%S-jjy@vn zP4;J8@QrkRzVoA7zf-r2Gz(*w@U?pH^b-OjX`GN-ZAR!d4}*Xxu8*lQeGdJ`N5AFH zTL=PDg0+SH_^V8IPtRnz4>Xl#`aSzNzWJzO3`v^U=*`n+=Pw`hn1f@1)XXm8>qWAmPyU4Cg)eD)4~j%jei& zlb1pk%B`e6#Dmk90|h4T?b3QEr0pNY`*R9^7XGpd$kL>M*`|ddjXfm6>H%#{DK!4} z{^*D5QYCt_3fZUT4vPhK$Kmd}zv0qMj)JWYc-x!8X8}R~`V#VEC@H3M^I_^=ew|=h zD~9k^XPO%t7Uv1gwlW$Q*h5~rmmMjCFgi{&Ry|ri(mV_88t#^M_v{6GqARc+CoKRx zL4u1?yI=KR4n;vrGB&WnFmuNMn7oH@)jW&-Ga89Sln}HFqGfc}3nxkK${Wf|tQ(;=&Q;r5oL~@zFfR=XV;0s6%ZP<6n&mE?dgBKDFgDai-b54>I?t95& zsxSBWiB-UQBm^V7Ml}%*qjo&J2X=UrS6>yZ!|&a6w}(Ys*q)d{9ipY_l9xYc*snsq zR*q-w62`ytU`v4zkyQJ(SOdBh77X50Z1g?tK`Zd_?%u}3o49sAJIWfkSE)677}Io= zLc!Vq?=Mvhg6?NMLP(mX!PV{IA&jLu1!2^ziD1Ysv{bTEjP0yW~ti_pU=J|SE zze>c;*~#uk<9_&pd-*z0du(NUK**evFQ$V^sIfmiAj+qx%ZB3_7YKN5-RE^5?YIBQ z$}%|v_P~t|*9dxl`0?=#J`T^I9Ki5@@!}c3kbVp{I>_Gg;-CC&MV@+Qqa=~E2S}R{ zp=J`%HA~vy^r+915>6iX-tQkhdM^dCQT$bqy}`1@FZ*+c1Ci5kmsrpDJs^o&%jRLB zykEAF>CEDTTy^q334OG`7dPCT=na)5=EBEgS}KRtf)ir6ro>a0X0p}FOmy8h#;F`{ zG^b>bbL=afq~_7Bj_8u1uDc%$%S)O^K;^f`8GZe`s~>H7h)on4j2yPZPdPDAHKlH% zp&eE}j|TwhbSq`o8wCK$_gEeSYQA|VON2T|?)XhH^Up)Bp5WB}df!)Lo)(yX()wv7 zTp{yj;ccG~T1jsJj%IzseZ^=WhKE$;vz=2A36DSH^%%R(7};D9^t8l8qeM^C)q$!= zQf^SUMx}(2fF!(p-bv~R$W}7tPUuDFoIw>WKGx)Ggp60%0yW2M<6RftjL8^g3J2Ze z?vW#1@2_Tsk6uGx#puCe2-LL=rwJ>qBB%R*oA^Q*KcYHau*doLAW;1FxpTQC%)-iP za%tu=a&_wMbNecIVchV>DUaryus%K_#e4`F5 zxT#OnMK^nQOI7pER6q>%m#7o(_lb(mA}C-QoCJD-#*>}I=w#A{W6^fuvTlT7xT&ba z@E`)MF)9~f4_8a}o5pME^!29FT5YpFr@8xmn!-e^KUX z>NwJCZDr>H{;NW3K`yGyhj;inxSvO$$8N$MxaUJ!mKB>QqbS!r8S9yF5(#vjEK}+HwiGU6MVCUy#NE(i%`=P=`>LaVQ?a-9Nm? z!8wo6M_1}9qN9|?Hd)n?H|^fUOcEOap&CUk@gIqz3BX8d+n8K2p|5MFnSOs zwcqqaCWCj5xGnXAR~DlNaJG@JsI_GDHwz55!iksp=;Djbp^HGB4IR9ooaVdYOM2`Uf zeU8ojHAh811wL~bh*-sx`K{hGDegsQ*r%tZwK_V-qn=b4(ubNuVRa@0n*ooOX&ePUlXF!8jaLspM|M$E8RbLqB{E zNme-%DVE23$F++I)^^96bKh3*=6)3`wBXBgSZ}NTzpnh(8-;VQQgQ;{i>3B|%xRPh zs|`Qe!?oP`m}x^Od))U$v#tt@fLbwn88hCbFoUB%>JwIL3}n>Td%G%&FO#1-RO{Va zLnUVd%0|2^^~)Fv<6khZGeod)?LI^8RhwTQ$xl!_zI`|y;zQ&IOC5|id)~#}s=EEA z^9QTc{R_DaAwGT!K0Qg2*bBz>y#qVx-}g$044J%W3O(AMjMwmA_+GPqAA|w zP2}D?XlUa`M=8dr3q|RTXCjvyK>H<)Awfmh3o?i`pY4133c?TJX>XI8sJ&K{PFvWT zjtSpBJE7Y2XrWs5SESAJb?{y7&Y!%oeW?Ozcfv+qm8~l#^Rn`%`;Uduo^u4<()woV znJ+f#hzWiQAO0RIN$T+_y6QCRJICV2?mJ08j{C9o9`!Q6G`f1`|0Akk9wC zv){C`ce+O}s`>nLtfrp9q99T0`SPEw)Y2lzkrKW4L}7Oe*FzN_TbmP;Vv!O z{kdYEd-Ldck`rmZl*+h74e4c(61Gw*p1zGz)i^Avv69!YryN(*vO7EMBVyWjS0M8O zqneFv-i{gLy*}4FcZpb6bRF&TaP(-#d~-5u!;P!tXA^W{2usGHzIV}b6K;w=67nUu zYv0pJr_a!6MX_?YI!uTv8U$`=jjBXVl=SyyF=DXKpZk{t1=Myd9@v`h{*o3hwgmM; zGWor@CNMPQXG-fEInyIUQ3XLDDl8jCny8pt1 z3O+AQej?cJ_vXWsBlNF(raK(cLuH;r^Qry9eI)86ASB{4(3*}0@Y4|s`(V}8kveBj z_&?WsihBYK==T1L_rW--MON&=1?>sxHd8vA~S0UP~PdudD$@~I^@(Xr`CCPCD7_ow(#-}UWGhkZxjY-B1=e5_?( zab@JFuMw!S(a{A=l?erZkC!hnC;INXr1oyMQrA7jwL8|E-{qb6*>h-%i#1muvt3&s zEA({$Q)fSwii-Q@LRmIbJal@0W&L_cQxMJ2cI~%`B!E48-j!|qZmtiq5~G#TN();N z$gH$M>dxoc6=U_Gw>+#ZS=tRxTIqur5Fr57rwC0)JS+PPiI`~0wm6)fS1O(_&1P8k z_B~()y^_a$8=5N&=40uU4qW_(zR(hsXgZVYXI%jP+RH%9vIOuUmK#I`Ak=(flImK& zjM*jIi#C*V$Nz8R*A*~}SjDpZQRa`r(66^lOs|0YEb+udAJlvgXv@F%MIN!6f;mdj zLf8Vy1upCC}85 zl#$>0Vhf9WItrdO9!E|?8An}(BD6t+q23$&t9!Kr+#ADm?Pj?8bUQV_*lOSTO_gr`6ki7aATmEQ-9C9e2u=WWqrD91riDoJrq|qB-J$yo~@&>@X1X zJes}x?5Xu_}tK|gy0PZWK~y4y~)5>0~*Im*L@#WcY~2P#W3e0{(-u*q(3xm zAEqtDIj*`YW;loYTHSFz?$_gYjepwN(a*e}vxf-t0quSpfI`TvpuF9E$tp;2cCcB)$uKQRt&p!HY}0(>~}}hk|_moc;>^U~zec z0-F6O`wla_Ar`7bLts6@lqa9aD(BGeYA_fx})p_(e-w=}K;DXP7*!8HF# z_GI4mM}h4KJi#j#IE?F%t0Jwiw3tL;&#jD7Vwr@rb!9t0t~!-VNL2Mv)^V%ZhhX6Z z|C5_9idaPkdc94U0)%XA<`3bys)205b7&Q2FRY*KwC(an=^rYO9@e%wW-AOfbz`#6 z_X|0JEsg!uAIa0esZ<}F-Ne5wS)coUk%BJ!4UyDC>sq_7 zXo$lwI7&>V9oP8WGF<~s(_nFZP8(u@9CzmX=r zNv(LJ!Vil}asX7jP9o)SOFjzy9r?R_i1)jG4=wQ7CbvX5Y8LGs2(jtaJzSi<%cq6| z?wyp4+aVfm+n24n+^Hsc0D`J)m_<9TTAUxW(0NT$&!43ZF1aQH9Ar*rjUb|PJXPBV zojg{2_ovKN3Vm+p;&k;#D9EY?F;A79XKdwaRFA@fty9|iEy{<^ooErpO#o(o*5ct; zVe3bqh)xHkgPM^ zW2M^SS%&)rE2w2UBj&Zt>@y>;=s^^F9$?F`LTL_TisCNKuA_+NhSkAZdN-nv}Q81$2zae6{^ z5mrO3iAH_WjqnOL2Zs{pn6F2qd$*1caQ^?*{O?QECc^~z)rnK&>$&n`p~lgrkuGzIWjCh#0({2 z(Hzpgb#H>vK)95Q?DG5UN11u&x^?Ej+Z5*O5Bd7lTn{kX=GN8uNJig$#`zDJUnw;J6$ zeSLQs6MpO^1o9hbZ|3O4S_COHCTYDr9jh6~K8GTK_QB6Uq$hm?;Nzco{Wlw@+<9#Z z=J{lmvm7WF)(|l07rgYV_+Rds{JL0K9S&McMdrVwJXe$|8`AK&K73cjLj zLOeT!yl>mKE{0$u-_^>aM0mP%TL0B?6~R0hKb1>rQJvuso3!haZc}ZP#DFT%|H1fyu4p|VkL380Pcwsi$ZMT`^S?i z^<1HW)-clJ1AJBVNS)@3^55JeW-a@IpW{!=Llh&sXEksZD1JtU5UldLR4@*pBgr0N z4`A?xVCUyBJYD>|yb%6$bg!)*nK$sAj!>h8Dox(ewcVGjFQLO!`e47s5B7OgUJh-Q z@0-cIE><-<|Eo~Qg`v0~DNJ8Q4i&3CvULO98OUi&ANwxop4QJW!A%XNqP6-N#j>6B zO9?ef+N1PjyjTw-tVeg@5VGFWI(#O3m&O^apU`|=iSMV*cr*!lD-W0JEu>IqxDnVt~CKCUv?h=R&}B#A5bnd5Pq2p zM5ozS8{#RD!aLy<2U_X&_-bt*;kg-%pX*i667Ec4E~fWpcQ3r9Z8WEBKH$#_%I>uHDLw0i8&s zXTD4b2sg)|#iD4WA*HV)l=d@FzgIg*0v>QT()%RS)?G=145%hp?TVP|1^rOYRE5g} z6*rN-lr)u`E*K16{F*u(R8V0?n((&&B6Edk;{2*5KI^O}-kJ(V-%D7`xec7d{Yl_p z6-4Tjgu{!jI_ZDXyVd=G-M$BxPDfj|G}D4?jgW`oNu`?=zIr z3r_1NCrDF4ZLUtb`y-nfm7yK$XJ-&paR#WCU0HZead)w4<9L1Uu7m1Lcz$75qAJ?& zdaeOu3Hx88z-f%;f~Gvd2Cah+d#{K`Z?&(+lOOgFLw);MV5URP!Rjn9XB(p5_2ca} zk^f%c>a{4kyZlRDCfRZRQk6g^Yj*{$l%sV&ID$8x^7(r3nkSvc$I~NPI|$D0V^$bA zsKNCE)X0kL$cryNfDJd8GmwzEo>cT zzZ|cpt7?Sr{YL&zqaN3yg5eCdMK&*_W!?bS{K!3VRSaxOsAb}RHfHQx4rV<>Ex&DR z-;N$l;`eV8V_VNR3r9c(lFH{ruqcL=(4%sUoD$yMDWrO$Rnb_E|Uj!`f_78K7# zWl&y42|9gc88DvW%aLR!OZ56aUN7Qlp%16~^ds{hAcJ zu$y+rNRM2?GIt-go*qQ0s770#<|ddoOkER#X7;UMzKZ@nQ&|1p;Hxq_zrqXS{Fe;f z1#gBN1xxTM*si<>qh9?W0ZaiqxP;+}P)cQDe%U_Il>8oVBH*($j~XEt^C?S&Y8N@)S!wJ}cMd~WJ;hMVJ)?D>3}S(pOuuT?)o3QMljL2W)8 z4l&@GQ=iKf5FE}HQa)67WO&ne$Lo_yHH_Bscb#Vi9sR6WaE&tV-`^__aNZeLGDf~t z%N5jk#x$Z5Ct7EUhocCa0;zBTc5s)6pXR-kAbj23R{ zYQxM^VuGpyhG6?1BZogLAQRvf(ivA)wO>fZU0mNyNme6-EPdC)l%SlLq<(~78uvXp zX=DO7uDJx-o*Kfi1_je4r4*EIrkX*2p1!T}y@@B0z;NVe-KA|nbmKObE|E;+bEUEE znQq&W@7dVdG(_(f>G-YE-+RCQuI$M&l_uMLH6Z{lqpkQE)y71~}= zm)hnNGh*{xsXV>j{Fr2hyL<5;=P`fWf@eGC*0QIWqW%3hge=-L0FUx~W%A^dE!fwk z>OQ6&lTOwiUQQ1|=~sG+tGxJ}X|{peBtiE?Ln>NF|AH32?UWftL0d<{8Kd}BzWGhQ zr+ZCMUQhYO-EcvuR-+CKQMb*uk&G|vNXPb2>ogBD0F?be-ih(OC%Z8o9K_ReEl>?; zFm3BQS8aa6)Cj4p6m1WfFfu!zReCA6)K4wUSaZcUOvWAq)YK!FIZ}G;kzDk+d@o(N z6;lPIu}tLzKL z{_Eihb^?Wj$ne%xRq$9sQAluH-Sd@WW_OREq0?RwbB7G+^$H<_u2^^23+PRZ!Oye9S&!P8s zaU}D{ObdZP9-hfpV;qR~Mj_2hHiB`;JsuRF*Y(FVsdmB0`x<`M!hai=P#$LCw4WuK z&Ntbi@A_%uY<5Mu`QKl25yF_EbD_CzSHpCDoWV%(bHp% zsc9_AbI9uF3D3=D^C6o_kz_CECkVsL4M_bzT>9Ge`Kq)54mAO^09K!(3E~>xg>=01+TVc?(5}rpz=^y2l578zOjqykZoa@&e$+Bh7x93`2J@J zw0jZZM`;A*$HV)0V|S_#nCwsX1^J#+CYaIeKc)zqTCTl>D>@KdzU3GNbFx7CEuY6B z*`MMS?YHLrot&GX=+8lYj;B|4JMj*CC$2|gUvuWP*-T~wcSH%QeebM*u9%0(y=j&I z{6`{qbXVN+(?ea=@)!R4z9^}W1g}Ti+%Whm**!LltSUf)^C+4_qs%L*5q77zB=sC6jwk0@0()2qa;XtcKf@Q}hepJiaizC)m|Gdc>`?$0{(@cGpt$!J5n$@lD z>Xg{NQI%A0F)_iD+;!q|{P_1*_(+CD_pj$07=ejc(*5sd&`~d-U9siK@cYra;4V&)s9^7if&MA7{Z>_>06Fo)@GaP8L|lURmji>A8n zd7)lE_vPX@ZXpZvQ}X$IF6-zvX*IqcKZ=9=m3nKeo>SF2`ruqD1StRWwiHxQg#Bwj z#iS;uAHYruE4$EfqO@j^IuodTHlDYHf8ngI`*q4-=%cXr-BPuGhgllt=XyJ!E#+Jo zd+2`aGcH}Isl@mvBlk!=@NQ^TYhTQ?4@R|_+vNx9D%%Tox5~#oOlLrf%J#Rlkgqcd^rlDI>7_06BbyzPbR@2!QpsEM zJYU~g7C7-P%TkF~S=v+K(;GX610={1G02aL&d<^sLi+5q&LJiW`gg`~w{+ zyS}~Uuo0Os*c+LrX;#Jcekg@4C@?Dc(HIlf!2x<0X-7UvxKb|a%F-8Y+*N*9zauGS zgP$)l86L=fa2<*b9rneyD!2x{AnK=j9|3c*S$dq{{gW3cZCz;08==MV{MP!+X(#9u z_wr1$-0QXO(rtG(^$(g^nYP8LVNCmpzyjjGO_^I?Bma3l$N}JDm{pW|J3=g^_ zxd$9mWErpZp=^6pe=-u7r-DIi7&#V-H#~BG`366~Y&dbo z4R5}Gc6j%DTx581#Otyj`6F-vVLNQKN^!W7|Y%j|9 z$0jkEgn5m)qxL=i@I&P`VXjh2@<;eOru!?dO@{P1tdaZFG2QxqSzoDSQx;HU)`yxgASKxjw9i%W`2oPuy0kQ8!GU zB60h9wFBlZ3H$Z6(LWisQnuz8)S)A4T^7bi|A;c?$^2eW{XbPQxe^OpUtAvYx1uVVXKe@&ghtkqKmN$%&Ab8u!>K1xKFO~yFv_N=gWR0_pU>iMxFJ_x zfBRbD03UjT<#Kn&1vIdUlJ*)Obk=^fXRQ9}?f85^prf6sN2kgsOswIXYd-=anfwrt zNKowU@$1lD=7$5*!IG=?K#D$>m2?CU=luB3fNS@QZQdl0#f^&nkPSH{rL)%Y0cjEW z3)Zujf)gtZamYKr%kbKdt_Tr#)@yDBzYD#BKzdONvO7WuvMfqAKkhxKz7l%ekY2|z z&>lxn@1t|Vm5-EnzHxD`llfOFcWK-M-qqDyNK%oR@{V{oF*D77d**tABb!WJ1fB?8 z->XGe!q5O`5}tYnHJNrc?weqM6&IY88*g(f4Ro7$O<)i*fVdbrN|QemSfO z`AVr>=-j*VKqU_UW(<3*^JA5L12fBYrXGMYnI{QZd3sr|Unm6!%VA;bJ0}>k;=^!^ zG!~F?v&F10w2Hy|S_y=}nLSMn%Jp<2G`lY**TjY@DN@1x3R;i5>)YnX?vt-~|el6p)x<4&)xe8Y91y7qCUxeo!O-}98rB88V2 z=c_fB*5}%tDeZP-b@kAEen?{G;}PW>w11WHa_QHjMA++b=Ehz+DORL9f(iAQy0R{FUfN7o zupS?GhoY!MToZX#98tk&Q|S2~-Jy5J;Jb&Xdzj$mzxb{%GptkyDr-DQ%+yfNC^DZv z^?JDV zs*LO?e4jtzNx6ECaBBzJLZYuA&~XD_o=h4F6NgI@4twr5nHvwm&rWU31O09 zHS&92*50%|YVzM8G(D8kEb146VAZ6#Zu(hsN;|kt0V;R+$G&f}GqZhLmIehF-cQN# ze0FK=@q7n#xyQDa$^e*sHj>Nh>J7&B(T;=3bNU5t-&@=~^pegrz`XV>ia|iB{=1(V zY|fpHgWSupFnq7=RNLVm`pY|2Li~4#jBR?*ftR6@E{)Nzgg@p;?IGMx) zApU3NMZVZ*U-0Jz-Wy*Qvmmrazk>8iJ74#lIFOtb35iAr=kJ%f@inQl2*pcr?ygBO zEYmM$=o#DEdnV_f0)%rE;wV&ziD=yZ6cC0v6hvZi%MK4@<3WF$r(^K;jDJ5n_uViP z`_{iahQA{75$-EUYFhC|cJ2YgAbw3hf?AHv6D|X&uYU1dqg;tscoEf9cfxleNPS99 zPt!|a6nD!k*|%L&N%jxYf;AfCa=lBR*w4^h&7`9s+a0A1yxNv|b;$LoHqf#q74DBC zThcxW|MS*|hM!e$2cv$PKE10*3GE|P0p zEo&=gh{kEcpU6x*r*$W+_&~k0|~x4_x$WUNv2bMq*?o_P(mZtpl8A zpXd(8BT={P$jLhI-nTuTdcTJ~i5$);B0Wsm1kA5)JA>qo5bL%hJUM=F3IYFA>Y0Djw%xz`?pjYiEZv0ytfltqo z@JbCT$U=s?@7DeN{H(8P0}|UvzHi<4*pn#W zfJiXv@oj<`+=sP*VX(kCN$^rehOhM(1PqFtRXF& zU%Hv31NaQ#=AH$a&t9-f2z7CG|(xiv?{Vw13q|wWMD-B^D_nkT&@@LWEYHTmN{h~^jEOttY zWS$#oJ-*=F>CFY#40n;5kjC0urTr_Wlo$j$ z9%af6dM?5YDszE&VH*quQMv?!zqTw5^m8jN{C+vqoYcyO4Hg=f!V4ytSD8Ya@cAnx zZnksH*}`avHv?s4@c;H0nn0x_ZT)w4SE8}EmPa@FY`n&nG)47oFN>VY&sbWkaiME6 zGbJqdqd*bg@ZhJxCB_&RMNu(|Cbfro&&0EzMKvhJJ|`FKBpMXuRoxpR%2>a7fUe40)owF zYIYx+uB{id1pR@}i~rRKe!eeidVX-qpU{!Ow$pmpv;k>3nSRyV$~~{?G@$DFiFC?7 zpMl&OID}DGBYv@Qa-1}*`{CgSO&q(s%kB##UNo2x`uGFJOp6ZcYV&4xdrCx}0poa1 z*9OBY{mKQ9;_Y<=3K}P(KMq(FxKp_4n$T0l1RuwY8 zq|jZIU)xzX@l}}5)AItJ*F0aw7t40~jVDK=46^wK!7rzgvE{X+5U*Zl0-KLx#4o@1M2X3oG6<;VIyK0+gKA0 z1yjNJ#jYGZZ=;2EJ~0O*v8nq`o`lL{DwJ77*l98sm0Gi7>s{bBOa(@pAW|EWvjW@} zJeN)h(vYY=&kcgA`wBFg{<*%E521^5w1@pA6Q40!hGQQ_i0UE*{AL$EMFvL!!!!7>ZblVUYglF;B1e z3Tqc3y($9Y78SCSaf`*~)LohYRoElSwn6{hpu(Go?mV-2_Zv`u{3k>IZodMJJu2J3 z`j>-2p5_nB`Mmf3y!~y+?>nzklI)(T(>dwb)=mTWI-VQlJqEM(6*2Js zV+Oor_B_SrC+o>y{UUG$Nx8UD)hT4~S2@zgJdd0-l$DyPp{ae2P%GS(# zP@A!idBofE1D<|-%>OPipy@`&RrMNrb?3*YtbYXA+XO4}*Z-zoydQF5zb)_SF>>B5 zx{V$WBYDBC#ha3Rbb91KtLmR9Orzc+AeC>8OnP|_xgT{Pqx+_Pm79YJMdD_gu>Q6i z;5XVHN2Sf`9=E`C{fP{st7WBgtLaYPSbM)cOl=xnB(!Zc%*mIlH#m{>3^9oL(FyoL z#SkJ?AjWmCU)AJqc>12{D!9Zj6-6-X%M42|42oYrivc|4*OE4U{p>ES-MXBlQ^iju zg6eEghIG;{TI0g3{+&@yXgdwK(!V{jf*EMqy_3$)eug^Xd0b)`|a48I5Dj?()3!|B#qxB&>2U#qp87xwPHVVJNhq@p}<9ZARH=&TUvC?OEj5=$<`I89D zj}&{{#mVKUe*-y0vj+-{lIq;!HB272T-G#uVsX`iJZ$tciu3zD_gMC*6>8z z9Ip2at4b~)m)?W#?%XX~#qbNpqIWHT8Z;SzT|dG{Ml$ z2#+_m)vEAoXEUs^<@ePNMt$7xLS#8oiHs>$idi_4ur5a~6W=$l z%kk6Z6p59hlY*|(+3SWt+r?8{x>lZX+KRc?X$2j)?IEI76FnQ0+2Ol&i_r!d!>#7%#FTt}W>%?H~A!2NmJP&91>7rX$iX z7M!`S0GDSp!{gX~QfIu81M}6!Qhe&!Hz?1P$z0^5L0MX@=(rMpyo-4bs`b~Ro${~d zV}yXvP(U9K(?Ro@)GX2~h@woiM^uz{zm(s;eGy`Iqw}O)YAy%}FtM8bZuy0Pv?-OV z$ds-+08zg8l>~vk43{6f$mjGtGUgNFjD7|@pC*2sV|a9%;g{9;smq8eo%Sb&BcJ$t z__w_GI0Ao81bF;T+D^+OV>9vx`u(&mB%$L2R2$tww5=j(ht6r)%S&clvNsEufadMN zL(FL%IXXU;XFC%uCYy?SzlaP0WFS%exWQb_!?h_>OQ!q~Fadp8EKFgRnY_IASc@dr z0bi)5{g;_NPV+0HFXty+rJv^Aj>IY?a7?rBMa)ZDzsI-8Fc?pHQxqZpn z>59Ib_zH;I3sbbWPg*73ZHuaz3OCT?xr~{sC5o)|vq#32f6BE`lqu@2wEg=rs-P)j zjk4@)Jzhxf^*rjQH(Kk^-j>I_xWRiU``q7;I{26f3|8SHa)Pd1XZz>Q=U~4;iI#*_ z{a1IJS8d2|7>Dcr?_N2Z_-dPMVSIxJis2UsXn?sCp;#s3&^r|E@nT~iU% zlB0D^Zw&pB{kb>BR}9bJO&Zfe4fl*)#ke{fKQRUJwv?e)45mi8!4G3w5z!~Y}^ZM`*u5bl~IV|yuRzUWoMK2{awZ2heD@0Pyx zQnVAZR1BfBRv{glGU4R|>_J{_1#Y2Tjr(SoJp1K>bFM6N?$`CLv=pkJo91aH9DW() zd546%&2G!07VpD_K1V8fK2@}x4W#S9lZSe4v*op!vb~D(*u2fku!+|tf_O4S*3%d3 z+0s#O7I=yPRg4+0y&GyTXMMfTm(DW~DB@C7sm(e&N2NlTbKirb)9FK?CD{I0c&~>q z!9O$C9at=>KkI@i4;`%5{a@VO*3=CL7V1 zFPE*YnF#&+x-G`X7-RnQPqztM{e2$>5m>7-##zH#@H#4gfo6ff#u!kzfA8$I4=)XTOti#DzPy;@_sj+-8bZrMa7rn2(B}nU{`w*K`Uh6mGd0#v zj$NNA456JT2s(ZD{vq$=4cy%-Y|Rbt({wlv;j%gI+bzaD#x>yPwqM5)wo@dfh4Yo+ zo^jQU=_fGTMGO<$_yWm?hd>Z$4KMz8XcI>HKItc1p}e%n`t~Z_#~Z_6#bYmNPAwe4 z*YIuY1`Y4AE9NCWjW^f~j8gHThJo0?@ilLoxrGq^4bJFQ-84<1Tz#_Selp{K=QqpT z_YwA3Hi0kV)%i6u$uap=wTtO%qF!BsMcvSv(&ud$b@tv&G48Q=@slb#66{LPsq`#& zgA4VOpD}D_zB7_pF832WXs1kn7~&431$4)Z!a4v`tY*CZ82n~R>_;0f zG;S^Fn^gf-V&uiW5)?p(Eyg#XaDIMgG}tPVRZQ{MQ1tz_#Xwl~C*QI^#uF$QL>uhg zOhPLaD66Qh9}z5jZqxMrMfoQTdJ8Xw${R0T?1Ai z*x8Vc7zal`B~@G0>wliV0e)E@zu9lr_pqGnwJJExzx_;r6?rJv+Xo=p*`3JStnJqZ z{@A~HuF%x<2I~3DGKIn%-e=))EAi9~K;tv4PxoU?j?`-u-+Fyo!=dGLfi8UeNYr2| z;8~u}G@3q7DSmvK2(sI&Ryj~5OHW1`^p7J{7-PE}xLRKVhvNvA+AZrSBJ;ZUC!`*~ zFP`J!AG03!*?v@7&@|11x>-O9O0Q|7p|8Hb1BRRigZ__X5Ah{eX?eUlNh& zQ4|D3KxTMjMnDB*{`#}YSt~d9Bq9>%uCA`ygQZYt!cvC14pzLct*ZMR_;<#)qf9`mv@L}+PgQ=7$zBgMx_pD9aUWYi>KrwjMXV_B9O|1tO%1{nnCG@^2 z;_Qy4h50~Q(OLH{Pya#4>hr|?g4;m^Cak%Qq<>^ehnLHv{0PA}f?5UdwhN5Pw8GxU z1xG<$QNGZVu1NiD&{HbTVQ^S2^3*7w@D3WoSyhrZy4+|pR-BYIz3J?USo&V^9bc?h zK`&uy7D=={TValzgl_7gdBP!^k2)3{bl!(J8_`THZF1Z*R6@z|nv>D2hdr{8m)p}> z6nDF%PYJS#xJxkcd9K}!!km;33}01Mq$$7Wg#>3Um<^NFTwqfc&Y6F)p9CVO7UN}n zT~s)OyZad5D|yN5c4wI8seS4MA{wQ_d|YMh?;q`$57O;AINsq*6i1g_YefLT@OTD2 zAC7@^!(y0=T@OduFJv}~EG?`;*YcanBzr_H{U>e#e+9Qbp!R~qK4#mqu6WYC+3kUE zB|86UkV; zML$yP7Ts24*2~t%ZN5gO+u4_vmm3hyl6)0k!4$WN*tZw2`8pfi^pKcpO{305b=+53 zSMbcA**&Q|wpjmpfhf;ud_X7ub8KL?JPnd8PjVnAz~&<{{P|}r>TYIsW*>Uk)Bd#J z%KSdCiJA{M9U`EppHTt2c0ZUU3`0P-*Bt($Ym7=7xP3V0J~fA`EQufY`ULu~cC_1` zD(x%fpR)Ez-TeIr+yZeIvk>!_F^KRF)LV_b6)^ND#I3OA{0kEsNP%v{XhBMj z-VC(9Ik+gK)Wy(^6WsFnHhrJV_sR~b0(7c4tEi}72BaJOk%~YG_~auyN-S~wn~|(n zes0N}cORgz-+BS2vle4>t&`$e%CY0X*o2#v}JB*mY7@lq*VxD|m}YT1GLQH<;> z@^!n0(>%Vt7-SE;?@|nqnzbWHd8ofPA22m&zd#-1C4Qv^a1ZZB{i=zHg{RqdM#Fyb z*)1iD&l8?_CMN|eSHs|^<)YB{F^c(b_SJ0t{-|HbBKij%-W$&EA1FosrdNQt#@}ye z!%aB>ZhWpa#}|sbH6m6o(53-+vmS9uhN3A4`)xj2zmIZ{gtPqL!5UUv$Mu5Zrbs?M zpEI`Pr$Caf)T6Xf|AOR1$Le>TVmv>Ur0IRJi47<~^%QH)L%1)!sUBVm zG(djY5@_D#(5R^G-}c3ojhZ?`^3PLaxQMN=>%v#}c1!I(fUpHHqd?B|?CEh^EpRk7 zG*}^olTj?`l+xA~=U1qX+byvg=lI0ok;L=o9zw(phsva ztnXiG4w;hxkp3a8G| z0O(R)t<&Lp5}79s>TlO8?PMl&!R|5;E7E5LM4yRrsLY8xtm&-$e7w$w9W};ZYUV}F zX#Pp(55sO49WZ6VNsR3{L??2vjhg(-hfj7XCpayYq(6b}yE0|MV7=l`TY2B-`(o$d zurYAR;3eCR+kHJed&@YMK$uUvdebangj1WPNZI_;fhd?^tu+23EP>neYgRWXH_@w{vw&=b?jg&DaWsa~+*oc`xo z=Ft^0;t_A}>VN!)Ef&nAbDe9_TM_qd(3g^=3;cg3p#@|;@D8(bNV+AAj6BWPGrDQ} zXNu2Oyga;pG)@(FA759vH{FY2bhGes9^*_d*oH@hU4A4J4Ffb-jpZ6Y@6K02MaA$3U{^Q6xEW09wCmdf zWF*JljwC+Y=^n;IVUeWuF<{nuK!fpeB6~g+B?>G{^R#CkR03wZ0pS2kpM@u)pV*I{ zS!w;KYBYK+{1<)_Gz500#IUK5TMj@m-RDpJ5mq7;<6fQKfJ8?#R5S4aAi0&#>h$?o zrxvjtzj?uy5Spww@dQZ7LhGtR@dbcfqN!cpOUrU65T&7X%yIYq@mn&l-{i+YOiwx6 zA7Hn()BEjS;HdSzguaUo54Ba>D*dS#RuufDOFKxqj3Ho|u{5lswNVe>FIvusj|Rsf zTm|z3HF)T42S9f{)eMDOaO(5|w@H0N3;%rAj|B6Y;$x$hiR9Id{R%JKbv0fPhg0vj zBs-NbU`)Ql$3F`&Zawa*!943D|5Bbe{q&2U8T_r50aR zNjyJk7=q_XHQwRM>$3(7o=6=ARv;tp`I%XmKOKko^rn=*x-kmDgtxVNz;hn%1;1qH z`JylP%k(~cKNB>Jy^J<^zlb1bSuPh5?ZaFs1nP8_X2~ zeZKUNvrwNP)-VHTM$;g5l*?jEC>ZsV*=m3dQ}$(w1noJ#_Z7L5%KIN>dYK@Yb-C!= zUT_BX;QNY{U8Uyh%gfAM& zS&KmHrm#2_=g2xB?iRm~)isI7w~g-?U!qcsPX&+UxruCYHB-ZQ->=Utt88y_Fo;&k?OcjHWb{}`% z3WRTV@TL!0-Zu*wf_Pkoz_vrH>eI5hmM|2*yX?;$!S1PeIAICVK9^6gd&G9Azy`nt z_}A-Cn6t7>%hR#TQLkT~*vSn8eLBnW)v&C;wt7wMi`g8VZ6P}DGW<0iu+n8xmZ|?@KPpcH~^NB2-5FUMaQ<4T63%u0q`Qw>1 z4suZNfLhx(<#bh0p}d2b#&?j92hrY%Ca!!zrcZ^eE0bf}@;>8a9}q(FA51tj=7EHW zw~ob#GrzGDEJgrY@T+UxTN?L$LW_rZe9^t)AIV!2ObNhP9D3|Dbl1g~DKDU_!{Yr7 z>E)emjd7`bN~0`VI9y!5sEVfcR_|xO{TTlpjq9BjyyN={eh*MCN985S#lx*&lkl0o zv%0>$v5C~{BTY|`q$R2o>pC?l2uVnc%>3hK|JRHOnmfh8+AXNXLXhCT0Qs>wraN2J z`GtUfeS#H{UnO!!kF2UAU8lAQU~1*M4X-?5upC?<6}XZ6@B=9F#IMOfK&O>{yY^Ro z&?O+d+>mBab%cZP=d6vW6F2G;q_UvD45zi)I(L=NGQA$sJf1B$EW86dL#%Hj!v&*8U!kZ^{ft0+oCBgG3KMEHXAvYq4Zd=d z_!t2$F@F^O_)6HULc&yDA=~yz_6tp3&Ayd=G*tymit<=TLa+GMI0>QMl=hh{sf)@M z7Y>f1O4O-$hkiY1yyMu2A!%48Pai6T=vhLR$jj5~9ox*vusJkvRXHZGSbX)IJUowQ zydx7!o{JkG;SHmtcMNLsd+n+f zxIlgP1aK1k4-~uN3>BIVq8Gg0Q`pRv`3v6sI-C>R(gOJq7UTEPW9Mum8!Rs z(>_~siY>f>rZuO&GOcq`;m$<@xrS;WUQG_i4~KS0YbXwr&gILv&S~&fJp)UHn5VQ( z(04$uO^zi+Y|wo1QD4wT zR-WIdOKK5;rYikpyTiUW#+ShWP4r?+ctY%9UEf|`g}a)nc^U9y8znY>It1`Bv!NUZ z5%gcYKZM?us2o<4_-Cim6!cEG-&ul2$R!Vht(chi2V%=UBXb<6T5uU@zB)qc<56%^ zlHWSB;03Sv!rmo%49jaJ82X~;xhv%8xxbnF_9LAW|c`-hQ zDWdirO1>Gd!8T5FFjhMt9hVW6qz9p&fW(5REb65@Di zfBx9gwduefSC3n*6`-4`9S+=b=~1&ikJa=3du1`qppDBMXU#dl{SYzibr;}N;yN#}d9F73W35IjsGRsGfI3{22u~11C90H|RfPW`c#p-_kiyhFj(( zSqSDq?m_F>xuypS5p&t@>L+9!Y2WkdCBDr^7kYrGuZz+!g)f_>u6GG$+1_DHMl@z_ zM+pFhrhE8NGHBnDh0lcHK)}AJwCQ{oyKIsb^3w6ByFEAXWNjbH1UC82`-^mbdDCf$ z3>(*=wvZ%C0lMu=t-Ny^~z@DI3F|X z%$S819#!Wq{mH{LUri0Ch-PAPMs*@OuIqc_=w}mfr|>=%lgE6)aY$It?T?RhsQ=h- zf9^u@dG&v>jYIE`_txW3^HwO$Wm#8#bB(XQtd6ZuNc$hYPrRFT7Z?{)wPwH^F7|aG za(a&AkGFB#(=%1=qL*;_zW&)4i6AUuK=Ew;&ijVv`-)>J9>lrGk`!4>fhfj~$ zixhCZ(S-WRz+gvRG-^F_i)hnO+=1;y1x`yAnGJ>GTru+7!5ee=UbWn1uXv1fPq&#G z8eh+OCG7=5yV$w%D%g^jJ)mvJRv~QJk|yJ|oL^RNoIY?b;Be67vbn)kiF zQKk++j- zEmsLd_Ub-czl&06Aw8=t9brdDz}5ghaYcMlzD1l6pzz})NdVs(>ePncI#R!vL;ZRW z3wIuG4tI+zRBTV&@L{LrO(&tH#n5QV<*9HEdz}nZOoZ{ZbbPuZQV=MjhzQ#zG%Kuo z=~$|;+zsIQ_i13hhWJ(-4AqP0 zqK^>N^XUrbXKlh+zQd&racmdY%bC}qGJdN^uRKob+ye5#`!AA2`O3ckf@M6Vlvo?t zfdf6y@(Ai6C9<0?%AxdRzqDc_LJ(pB$T5ND~oE=lG3^v;bU-hRYoL3ihM zlt}ul5ITfLXJ?9;8}Lae%sohlTL-B?^2Ze0qHr)f`rY0IoFh(WhtXm{S=L`c(;3kj zvRbV`x^F;WwZ9Rr!w~uv6TiV4!`V)6 zWC}5oR5Vq(n>|jKa&OwlQl%shU}wi-Umf1<*G3}12R*7Me9^ZN5DGO45)X~1Ds}7G zmlZdJYKqj`N{x0*A4~|w`#zo%;tu@}MzzKCSTfxlUcxi^(E1>xUuO??v-3yziURT@4ZQv~9pR80dPYN0@a*x%qTSbt z|AXBap-XJx581P5z4;-82-8MorlfL}8Izz7S_ui7fOWl%s8&MKV9H$S2CQAcAE1I+ zUs}@|0qu8rjOab(qiBhG*%nmx;i0R^>G!e^PPE+(g2-Gm&AV&MRZ7I8rkfrhF^yLh z=Gz`9#LcCGMq>q9)^aE_#(aoxU@n~geREtmgAq&Ib;lMqz#yF%LQvB!Z+H?ww7TwySX zpWc8iwAMC5_laNKXYFtC2^ZT zgo@K)&l?<)FllA1xvX@i{Swz(zHpC$(&|2-ma34T@f^>O-Cb0)u#eH0Auaf7r^8^8%mEbLPs6(hs30-R zk6%PMgj4%UQ%nO~8Vlnr_?i|+Xu6|*g(j5vw+{mKiN5!^O$$XGMzB(QDoA<@QMV@q zJO4yl3r%Dk9Z~L9jT01c2I6SfPmvp#tma(+;e_9wN>ZsI0s)Td`XGPrBgI;qDGkqH z_jwAlQc*;{A=g;<3=7u}~I4!VC;n57+mKB0x#~zRU$+Ws(4CMjh4w@!B_0H3H zr;bE%RkGvg(*5uAxls`v+(w=BNa}MKT5JW1n_bWebpp_Q()P6L`TacKy`Wv36y3Aq z`h514i%AUyUc3B5N@|lAu(Sr`*{Lb(<@RxrU!nY8S8@{ovV5l2(;A7Zqh&A90UwWzNI>hpR<14ob>uvl<HGn$?|LCyW9o5MGk-S4s(mSFlI zT^xYSKShs6uXr4Sx)_LvzBj&p{wDi0FDU3f59S@z?~Xs^7-`21UV55KwP>E)9YzlP z^9`VgJ6MP7CC|~Wa`HWaNPU;*k6WFEw_|n#3nNK${Cd^=D|y)DPDo8|c;6%rcU~AQ z=lrMq+`+l6W%kk5zwX3O7|otmBjS!tmY9Xt$4HZ~5+%Z)*=C(g0zAXVHmiUwEUV@t zM&NW3RMvP_cl!`ZRI^lv=|h|9!LWzfLU`ll6~%)aR1L~)>23g@Fz=-I$=RPNfbw%> zaep@1q6MEEwCqgx5Wh|}Slg0*n&>zKjs4~fnfJI~hP}7Tf5nV=tFon|mcXlv{w~P% zOWT>-=v?N#e^-`w=HBUzCFQ&+>Dhncm)V0TxAs z(=XNc^8FGZYud;30IC1qbV!|su9|XatL{xxqR>7bo0nXUB#Rx)bu_#|o*M(Y$&~cD zAB7u?Cwe2g!|E?yi65)HAnGHy8l*aYYYLnKd!&ZvRXw!kIT_dbC-d$el#l9f!jdLB z(O*Gm%M*ymTMEkCFBc!c;4k0j5I9JPtFr)N2F#L>%q;0)nv@G?Jgze_r&cH!>47R^z8Msg2`g{H%)0IMqKn3 zZa1v9uV|}B<(ckG!{cRUu0FrMdt@iOiI9{!N?rx%RjXD}$D`J+?qU}Xk*LRUDcttH zrJMReE$=5*^IRbNyDU#A^WIsU;hRgmmI>UDEzK4Cg=^me;$Q(&eJi+^lT|k^;DYo? z!3*P9DwfZd(p`esAmoIfpN|rroCQV$CiHZYQb`l`n;aeQ52KVE6onx6v?8@B(_*^4 z)HWV(!r-Gy=IcLxIN~?A24*Xl(>7}sJN#z)0xY0m46nWlVdb{E-RTL|>e)d)2Y~#| zMMD^h`eEmOH)zM~8IGeeH@I!O<3y+mm_ZZsh{U1y2$O~U5e`slZkSy&fF;7>s!6Gs@Ino3PqzG&!j ze_}5=?ri?wBmG7mPQcet*H9tMXUXS2wh3;)=ZIA@{eIGQdr52xk0JTPG9`RO>9H@q zoJ^Fr_NtIP*J82g_YD?9&xSk@e=1@lr$Xe**ORKLkIv(UFbZwxvFUU3S;)5q{Pg`T zu^TcA_+2{uVjWG64$n7vd*@H=Yj9QBXdaGL3#w4?`qeyirp_irYp@cEIYB;#GV>%* zLqc1>w1OyFa4jUJ^ps7?^i@YcvzA2zE>YKohr(^sKYw2K)`rjL=+KZc(P;YmH+EXhAKvrwZl3DcEq zF&|ESNV3qQP(4T%@xJ9PkO_W!2s1BGUzgr}&3ETwIk!(MN(7*SdqLy)>^o&X6ew+N zq`2=p!Mne4-@7!lCPZk?SR2GGrMA#MIeSQoXRIO(2mEYLc`<}FgNxYW7+HQZ&#FWm zHh@^ho{u^!dGbsRI^^b1u>?5{)f*Xw4DgBF=7y)4$wH=_LMg!JSq#qAok6r~Ptx21 z37k-@Qq-T&m*I|bvx+0AFZ-a>eX};+&-3U*iST<EC1LeFr z*mrK_ifr@hUJ;Z?;wH{|2d#_>KOOBKIWYd%J?aX0|8;f`){yu*6)-Y)#E0}A#taIK*Rdxg~ z>QHUPhbHAcIy0?q?pYGWHtsuW!bFw~`2Wg3HBH;k7Zl8G8v3E%jAURE{Mibz9rMGw zU{~K8{2$l$`zk>a!byraI#%`mkGx4X#hE&oSK7a6Eb&YJc6fUk*qz$zkO~vP68WL1 z_RM7uII<5Xg_DxiNgzMt`YjHsDv)^5K#hWfD)u{o=)Zf(=O|Y=^X51%PVos}*fM?X z=JVw#X@;AuUc;5L`jd`M6$sU#LEb`OWG$O6OW1i#pg0 zj|A#L_g|~H?^;Rk<3Nf^2w@0|&nB-T59P1t;Cz+p=Gi`)zUZcBXS>6>{8OQMYeKqM zcq|MDxkZp_8w+iuGr`i0@Hy;PFNHUIqMz9(9-^uD`N7D=Ja%$l{QAwe;Gu|vNPDJq zKJXSF%z_V~L)gxr$ylNZPmJ(WwUgo~`nw+I?R&0{-kMOKGX*|i5(t5wEXHo$Q zyr+Bv&8rY^^9-hGF6xQFn8Ke=l=^_YnfHB6 zKR;!<(M|jijmJJl_d5gshln*T<3Z+8T3ws_>E502$nTZ>IZn@IC77_cWgqmLi><#r zBb&05_;$tiTZ|Ngc0JQD`^n}76&d&tCE4P%g-sp+1EKdj=F{!l`5bFB=w_H&V*mN z{bk+0gmua38R>{Pe(Y^Z(HwuD^QuanjQAzxjmSZMGOnaXlIK13_Tm1s7x(zmJg`hN z@GGrgVR%qvaN8amI0Gd#!!fZI)_B@L9#qbkU z4RAK%kX!p1tlL7h`R0)qdG03Oh(az4`HLv)Gb;CQ>jjm%+&h#v7ZaIJwyZ$iw#kl1 zSb$R`2W$uTyb@3AK;Y&5BWhnQ9t}3&`}l*#(pPM__`xgFUKXtP^#I6<%9w4d8}{eV zZgrrQMR>fw_j~*BMfe!wAN$1#eTKwH_iy~I0{9R)r6b$;vCWLbSa$LEP`i)CB{z{b)yr(!Ov#$+&KFQq#I?? z%SyFuzlKn~kce=iqh7vDxp8ajJG$AZ3NSKt_Lomz*t{}fvsYiZsYqa5HT&7=k3w*B z{gd{D|IXTdNV^TD{u?FWu<*UBJ=FOl!u;Jiq)4B5U<-yA|91=pjwky9{^s@L(C4p^ z3HD(OaFG%>vb_K#N#7IfInRA_Vj#8nAo!{4mGi2>i=4RhkU`5sv|RnQhtb2}kO#tlb;8xt-4F%A!V}~F(7y2)s2vGG%vVs@Fk$8Xh%mW+a_3B-nkJe)! z#5l-H$@ZBYe0dH`ZZmj@ANIqOHMBGV+NL{`<1(De%Y|g@hIky2Bl;GC)n&oBRqZ zp?ECQF#e(YUQu5g~`(3LicGYV2^Uenh+lE5R(j ztAbk9dS3TXM3}aJPq`m-Xc1N}HC5P8To5Qe=?!wl8m+B!_!Y0tsfCf_q0)Y*ih03M zxTTdZ7c9L;{?eZGV|j$p+i6k0BDz58t3^9=Xz|e<06o!BNJF5o>BQyNG{r+#qSwXa z94^td(qIS$W=iH7W*llZq9B}yKUz(d3gXtSjGoIc5uW8qsYS(WvrU2bFa1h^F{Zn; zc{nTe^9V&&5;(9-ys5{yV)Qb;K(Lq#&4NsNnmv5Hu3%A`lj!eU?&(Ul2|UIb-x(N#3z)KMuh+4Rf`Qm9MXdiZ08~W zk_`?*FM3=>h)dSSwR21f%QI`1v3ie2sO`YAO#Y=3>ZS-+m(g`7ExFy}fq zv>|Oj&HQfXwT*_lecQXRiil{%A79(K=(L9ZiK+h4$UnyDub&FZf)VQ-NM>ETpR3~e zMQItw<7+jp+0d@AB4cw%mEM`DKGtn2?Z6^s$rUo0aPsqqJ9y5LMna&3R|w+iNFl3a zCgh9!;nB8&QvdIGrhbe;UF0b3!$!Ltq5WSMgHP*~a%P~Hr(=CuK@;47w^|=xQ$KTH zw7*XdDH|+er}*jcP1d34tSMNx#bwUct9EMs555qu$)k|& zw>!Q6)ql+%xn!m*1?eOD3lhc3OY5U5gxBfHRI1N4e0#EgxjAVB)IPP1?NwCJ+O)df9a!J*3@%1Nez;F#+FWvUh1geEYrj`wDjQcTfXvJXG*C4s7sd{HQ@O(w zEH?<*$qX8F`ZS9D@dVgPOf+q_Ix>=H;uv5Kiu)pyA>_R|d)JkOK?6Dli5zaEg+83->>9QPXOOepa zQ+L5jldCtHGZ942!KIa(pUzqfU%^@;Wj0_TUT3^~{n-`Uopn^9LvB1x=(Vi}j&QHH z0}Ong?w)aMo^*h@0jI$r%1@o^or2W=u3p8*6^vk*8dg9L^Da%&%wUfXh2Rql4)gF3 z)=(pY);zj)b8Wx6#y(Bwv+599MYM-@kAy%A&%b4^M!^v%U(uEGme=vCE)K%W`O>sb zJGM~Vx*rTIuMSBm-67Yz-5rC!S0~CaO7jz{b21CRhbvFc9u>Qi5xMtxiZka{-N)gh ze1b;cE?c5@_i#>E;+k?}@jJ!lnTwxi7AY)$VH5#3TSUVj0&Khxro{MsK*OV}U)1Hnuz~WGoCjzOcnYYT3;=n+ zM8uos>P?Ww1Mxbg>&58g@RD9{WDRxy{>~dzgMG|al34Z3j`YP%0hdWf6gyx1TKt z_n)dC%WiCgG~J%-^ArPMYLxVSd78c*>aQ4O{?n4HPgYZ1pmp!4F?c);|r?gzlqN>{FL0KpxTi6&_7WSGBDiC+9zVuOb6K<8(Q)LtJ8(r_5-$C9y zN{VH0c$G2Ev8NO=m$CZ04*Vu6rPzZ}SB$oBxr7{M1ix?2aUf-XQcV&gQ{LwkzHYPc z(b0H58`c#)o#FdfW)f03F~%gX6!y`hzGqh@DmTTg<Npo@v}fF z*DLjzXh}W5LzdqTarPNqKwizUMwIZJSTBgH60pprXfD{!>5$`)-2CuLiCf?vCMg%` z5{l1jr5PfOQF1>&kz;BXk2pZa!RKeYR6GLJS4hE9opaxZ=RQ|5eB;wdocY;^5AAMb z%}cf5UZZ?{QtmqB>jj+0fgSbvaGMTz`B;~=#EIVdDgU*A^fb?ZtijXszPXX#>1tx! zT_ftHVyQ{;Irim|mf}||D?}VR9Scl@HxAFv zL;(Q{2T@~w^7sSLzU1N;6cF^vbpWCM*xx;mJHE}`gH6;*{b<=qaGkY;mErJbL9*HQ z&3)7`wb#AWD_O)$K>7ItrM@DgxjOx3tVDH3w}${&_)R}oVA^~Lmp%r#(IG43+5CNj zlC}~(uSa&B?^fxIk*O1KkpFu?-#NUmTe-(`0Ca^tDx~UQsD++9xcG+V{|y_QMLwlp zuWHxJsDAkF0=#H&s@Hm$i@p3F^!GcN(sO{}Del@Z{3$UHWx&@1-2R%&(?B3;MSdMU z;{gs0%f1r@{;GJmhVe_zF_wl(11nJV%cfw2^hTp>bA2zAy~dFOcZ!d)?WrdJF}0i_ z(&zPXKE5o=uJ`@RHc7L-aQBM(ge)hvQFz#pdQ#pTw&(g7_S{noWJk7f5om5M-D=kAO%NytGBZYfq?g zYPR@nKj34m<$gdZ7r*?X_#sM7>|et0C7o^gQ2at~3nYsPI%QOVpTSn)7{2|-p4GgC zFL4C=nf!3p(l_Ta`36pds?Et`W|yox`a-M4dyfPD6TOTGS=Ak)K8#-k+a*E#bv2fI z;TG5>?uPiiL8@sl_VKBi*$=xX?H^|uUB1c&pAk4Bk)I8Rz_K5_L2*Ysu^* z-UM*NH-sVaVH0leK$sbI6xNs0vr!S0XZ5h=SBSj9-2umzZgkye)a4O@323~oi_U(r z_8POr0xP0IwN!h3pHPlFgCOhsE~+NBLA{?~czZ`^&;WyC`9|_e_UZAV6aEfw_Rm$7 z0exEiqYChzU}yH89Gn7tbFx`31F49^!!$!&uBto# z-I86TlILm~3<~1oFrWJkV$bj#TJUStf4-2G{tmfXnCyd9Td!Iao2!s`yW8xjL#n~L z*BPK)d~A|$xH68RLjN@@BG5(+1Z&6=f%Prk$@6j@zI&|av-R~kM)Ew@!1rtt#XELtpn_5^* zc7qX~R@g$t931y2iJ$fQgS?Qp85V33ii#HqS3-2CZRl(=K90(J>EOle85&j(p@Z3t z!(N7)LVT2)G~FB||D;Ty_ngiS{AI~(Jv*<$6q^%ib&`E(*AJKH6S?P}tX|QM_q~?d z^CXSw6d)_X7ARTw7aFfW2$v*dQ_{>Z^^}QTC=g=7$N#l}0ZMUVE_dY;q``1Ik zaAI8Pe&``)5hmyuaLEbkvdLvw-+;DY?T9Y0=FTKkX5Wi%eFNQ>R_=L(5SR}#xNr$= zfiR<|)al#jV5ynSJ|9;CYXbnVEsYD_(nCs;({+n}c|=N*AMNE+euPS>+^ktQ7iKZ! zN`N}(cnsp-cDR_JTd8|lcnoHi=CbInos8Tr4uCey^&s#Euf3CBB0^7>haD)`@$~>9 z1Yi~i`8t#v;=xaHD59wpXs!MZp~rBMB+zW>QOT9RkN_sJWw1Zh_hzT%4a(4h`e1n9 z9WtVCtzq3`(PZHpxM8ptFRT0D4Ppu>xy|TqfD_N})eUOr1NcPH;_v(<=BQl^^Dpne z1b>T=`9e^$9o{=Pw(AM|it+00(`KX_y>bFIFXN8PzFFw$)RW&Yc5L2u^LwvX(ru;4xnBzDr|M0ef9$0pBZRO>a3j{PkQx&LX`cszWXS5e-Kul;K1n`CoS_l^zUij%MSg@|n`h9mn)}O@(;-2VK9>Uogtg}! zFA`fWds)l-!+rvQ=5sOmeMZD>xDSj5*VNyrQ zTdb=73cZ6!f-w6VwtrwKf%iaK$KxCyQ<{0Y#ofI4WZs6Cb|MD|JP3||j@XnM+`55m z%+*P-BB7VMocm}!g{Xr+om}Tq$EX)L5nM?$;Jv{B8jJKSBN+X#{lrD~0s~Y=6cyL7 z-uR5P-OG1oFO7(k@|%mxS@@2r&#oFBt%@b zz#CTS{YcXFF>0$M{UD_j>*29CTQW&!0*Wxr+^kUkJ4SDf^OyPKYELVNEjmKM{?uVv z)4{eW5Key*1(akv|e zCKqy#>P>4Z_j+z1Cq%>!Uk>7j6Ag+%+_2t zK5^O0L`zBhv-Er{d){}A$9H<%U?~;p(f3rgz%y#G=dPzcLgQ>aG&iuyr&AGUcUyNJ z3P-jVvOLSRYmSFCqnK0Q1TFLVv<}q4@vfA59dqtfbMyOlNfWv@EmTM{BO>GMBU!&MFUCUWVQy3P!#v%+ zYE46cHHX^<8S{tl9+%VnX!r}bgG3>)iYmWf9gSo-`@Hgla7lj$O~l5O{#=?zuY!s% zNJ^@nLbpa)5k0eYMUNj1k^|LsQY4tzDO4g%vh9>5qtegS3Eq~Zxsm4KOE@F{tq*L_ zfhkfV+P&q?Uqs} zgS-kvTAc5n7x&i8>C{6$fHh*j!o;z(ECBHF6F$PQ>c>&OC+X3z#%WKm_4d^0mYp4z zy0Q12wyq)|ct_KIfYQ4q6G5F-%{j>Cm#1T-)*VoQI6?%xY4zSwAL4o3-)>GSa+{2C z0XU;A=I^~CDf%b(Qk$p2)Fe?s0~!7x{zi9GC74%ymS)p7b%UkpYWbZ_`m?V-7v99u zzywo5V+Z4ER~-N=`HtU1G0_L>qJa}>3>aq)u{XP}`}l8bt?MG{Exw!Kf+ClXmoYV~ z@y|1)`5wP9^z<09r(7_4AV@P6UxL$qVu75Hcp@xK$yP8CsnMV&wqDebRe*K!p6mXm z6I8y;3i}-MUti^&(}%Za$j;bK`o5t@`@r4!bmR{idBZ)XzJRw=?6XW#7mn^AfeqFQ zC$<;1&Wz77u*8oWilT?$LpzSV?!#KO&-ytf{~X}o6$-keSo53DoCD`r-0WsA0nC*i z6rZDl=_E5JdGR<*nd3pRZWELLM8tAx!`8>+_7)q|l!RIo_5iSEx$6Zysg@LgDYQ^i zx)!ZzNWY(1mZJk`-1eveA%i!NluBwS2?2i&Iizoc(}Sawn)D!MUD+ zl}x^)_KF1i$13aN4Ck!{n~bMYQ|JrlNNvz zZgJm%v?FrAE{9iSlhTgy2J-7GA1OhCr9Gm!0;u^ieBKd*sb5(qZl9osek^P!*B`mV zc@8+UI)8G`AJUPvbO|jVBRz-J!oVDGnD>{!pN>z=yrR1O!KfkEJ#Rws8ZypN7%4Dy zNWN_YG#FAjrhQLGw>lJHd9lCi^?l$*)SORp^7y2z*3-HNncos7&$D#^hSRV=>lQ=W z>%M;yT%4ou-B$k5J>{_VS=%f`NRD0rJdi?n)oTZ-yhS=2!z9*bMeW3gL76s zC>G-2AAmdL>6hV?tMUunl&5uG_9WLJZUS`;=rY;|*v5_6j&U@F5&8=e(Hig610{~_C zHw(gk4OXra`0%u(Qv^r5y=s^C3+=)GuJ0Ce%&ijTZ*i!W{mpWQ#*2w}d{W%zo1|tm zTFVCa@s>!cN^Z%cbQHf`%+KXSriZ_?*I(b)6lGT9XG7sl<4x_}K&o;6bqo$Hqf;|- zy3<7KM!YXl&3+#DfuWc-)SQkl{-HHf3q0HPlMK!S{r*qY$TDRf2L< zYD#$7ifaQ2u`bWN*$ZE#+W%k%Wcu+@xK0L;VaQNlBUD9zW-kECyhQSlINP%$a&qA3 z(|9&LVrH@bjr(7vqw;nL2S>b>Fy=tCcmIWN&{Ph}$8ZD`mRz~9$8aUs$8`TXdShjR zw9i=7CYq{?|8y%Tcr~)!o>*R-4=f#_pXOw&GxJDJSN?g zobTQS+s$s0CC1gI-(9rYripHt^C}}4Ayp}oQvF^YH(eEqU-Ci^<`M4Dq)1GX!p5&* z8?Up$(~Spx@_w;w73j35p+*-cF>l-|oMs9xLOCsd>a-tY2V+FMA1)sZST)~kiF{;9 zEAa{_B6~jzRM~3_zETXjh@^5K&A;hz9-7c_U!#*^84btZ#F{nyy2pF8! zypyX5jz>+=9cDKD2o-xs!0>1J4Ppvsd#pg$?g|30wA`fn08cJ${fvanAKlv;lL)$E z!yP)eY{t(MeeRnxqMzx-T2q}~i_0Cx@|R~&+mIC(uA5V`I8iSfeB=!u;Z@v@gXZD< z*TYzam6eZ3;jZB=V)Cz?!b zf+L=KyM5hlA^eZAM#@rx5(AXsz5*^)diHsE1YAiGgzT{|H%Qt)5SvCdTY-tO|0Q0X z0gx{z7et3x6a#;Cl&SR|!}VNiq4Nq88sqtr$$*@#&V@SfVa9OQ#AOn0rX3)@STrUU_hB z1mWk4A%FhVYtQcl7x4lS<38Wv3luk0ncO|L7k$GeVoZwa?*%~>N-de8taIVj)tNh~-Z-|_$J0Q6uYgc8ThwJq9;fx;#n16%{#DNkXMoMOf zDCM$!!wXZJ>RV8UqdbAkDl-Zm1+KXgCr*MBm`Lb)1QX}_ew_dMEPv+EGPg;aBMme? zAg$azl7*?8ZY)fW2U$k@{KKONR+jU!k=EEcrV9olxaK5p8KsZ*DyKrIOb4J`-S})hojdeWrV`I z%9B;MFN$DrOKodZ{R=;-lOdv8SQZbT+wBO)L|SNCQg7NKAntl|hXAo${MNXf!0uIj z|7#Z$j-dz45}ypg@FiIbwapr9_XFZE8^<&7WoSzkDkt01i=8B5*myH)b2QAO^_fm> zZbwTRDtuJKUJLV#8VLvZOi?}|G`3OJn&Nu<^nDNDS#($uToO>>hBLHArI;t&&|Z!` z8Jq|wSeeNSZ9;y)bM?BtKg9^A79H;pEhr~6^EPP@$NTmR*{0(}W*qLWbdy&s5Aw~J zSpCJvWRC50##xc~Gi_UN5%cbsBh2nX^7vPIL43@)m8z<-0`*q^fXh0b`KI;f_x!0G ztvKrQ9wuQO@ae#SZTX|0&iuxy5cG}EIwY1{Z;)4IywG4ZQT;nzFx?ll9Pg{N&l}d| zVmGF)lg~O{UJA9T3Z0eabO^<0s`;6)aEGbaaVvZ`yV762%E$CWzB@phT;TMBbdTg` z``SVaSRZb%VnCYtW2>}jW=vJ0ltT*Yz}dMe50l|Xk zyY(PEF2gB;;&zRtvb*{QeQGofJW8!)3T%RjFFYTfY4x~|=hI}up>q-h6cT*r-cYjj zaFRlDZ3lLi2jDXa;i}2&^=s4z>t{2m)w_PQo7>$#GhAsQCNn>YsP5f8t5a_?{l^ zq9-G7!7oU>0T2F7*0pbrtDY6K=z>M?98N!RvL)UpuCBAK+VX57RK{8G?u{~fo&6%z zj^oqWhCCf%UWnSp`Oi~$SQ57rtas6=?){h$-MffJ2qnI098+a=_(3^ED7Yz9wwoX^Ko4^Vs26^APeQ?$ z>h>9*EM!RCI$-27LEaaH+@OKtmA?;qwZRsVGLFtwybT)KA!jzR+DI8j>p0&ULBd@8 zN_mz+NET@u1 z^(`OZ0box*luTyo{$ms8KX$&#xhtYsf;$CS1L zXSWVfyTG{j{=VA!Iv-i8PL5$y-ys2FQ?N< zh6vev*8TlJPv|as(g)z393K>z(=oMSg}p~K$Y^A^J-|0d#2u&RhGWj;{+ZwJllAaW zr@0)eO&<;y^=_tz8nL6wbnUgJ!c+R?%b~v?pOC7OqQp`eZBbG6$Ku_?O)wcqR_C~) zZBc^fE;kO$fh^H?va%}h-?iYAxuf0gkeERQ<1O3mq+bFcHL|usK0aN)JvngHzTJm& zf$kG@9>^(N;ukSrdjXhtW#RWZ@pf=OkTSLV2Qu`*q>#Q|ZWL$E>-)&>nJg<@hgW|% z-(GvIONUbmK3I|WSD~S+KA7H8S5dE^_4c@)F^$t0z+#6vJr@P0hzfpLt-A3OwB!-o z?@kGvJAOCq&Aa6tME6i`2^ZC`-*0&j%73VyLP%;j-3hg2G(eX8iS+E;#Wl?=hV48vaSATXh; z)#(D|WcR#6I${1Tqt&U^f5w^d8b$kZc%BxgOkpPl?5b+`R;vjrmiWsF^*WEK%O|C# z=Lpnux@pc3U-`-irC;8G*-G-~13_M#doKj%^oos@@9=tjsvc?&!s}~J^3`rX?f8Og zQU7@J6*eqcj@oYSt>)0EVH<~MCr5jVcI2Spp0(?q$$lVi@S|QiN*zo=ueCam1rOR( z!J!Gjyz5$<#n=f{W6MbAr+o{TfQdx@*vpez;v6hFQ8QJ27V>QL2Gge}ja?8!9$7Sw zp44@pRPZvEk_7A+G#sE48SQ)%&J!&cZmE~*1n-p@CeO}ZyJN9ch)(7&QT-4?ig_on zU2bh9z`SVx#WMcuz66*NRhV#ByJ^hKGLB31A@=J)IiPJxQ1WQ!kiG%-Y%GLZB}Wn+ zNz?b{2-@+J;KqdRmM!V-;c45XeJn6dh5L(5zgHjvVOwlEjPpJ_tFpy5n+RtxYy~a=ZO*D zYuG|-4XU+f|J~hR4{;4yxHZ?YLhfTxwX)B>EtuBu`}tu}O_rBh)5B@%rQj@yXwnDi^g?> zdOT=!Ch|E_=m80Qpb8Ta0@JT<_-X7i|K0KKCUU=aBpUf<^`&X27wyQLcR%??q&`@S z`MA$|Lgyvx<_LR5SM$s@)E@0=dfl1}>l4(|z($vzuhq2pQEYjLyVO^x_QrwU=ZX1- z=5AVvhv5{UqFHd(e#Z?e49kv7C@0=u_pYvHeDA(EKdPY{v=MNWg$Y|XnS@lv}U@3~FQGLki?c2)SZPO#v%R@@8C;6;d$4fNxXHFQn z^l-^rIjUf1c50GW^HJw7Iy8B8KkCo*?PW=MBAgwekGaxd1*&wtz=BZa_k%hizxq!?we?N-FH?eZ2P@TJ0QbkWb z3R3HgX@NP`kMoz5%CM*_@yZ*1N?PuZH3Mv%>vPQ<(IB?8p0Zn^i=}MsT76X)Pevp8 z$Y+dd(YxsV0wXWV3H@+B8)iz^nM7)iQ}s9S>P0E`5@RJb7mX+`kZ`wCz4uzeoVVoc z%<^556e#oK{;ca5?zbDhgm-XvF1?xEVstD9Nu5Q>^8wy>8GPxujoa^!^f_T+-{-_M z`3mXmEc$gzn4yZIiw)IgK^+IA9F9|o0_7?LEMl` z0qr>nuMBJ`yfOW@T*7oe=NsgbcG&i46rsUHx?1rWKnU(OoILLb;zIS>?&_07qo=*4 z+n#tt$M!>&P#e|gsXHHA(#fy*^^~9ak51f7>e+?$s&lhT^?fVDRES(_njLj(VmIp^94A>Of?Ll}}^gOR!k-&9G z2tRN6@0uAL;Q@v0HtI}$Njt?qQ_nm!*}_x;aX{?G$!Qr?r>G2kn+2@Ax z?u^|4+CeKwRtVRFRK6y6+fE+%d2K1|=gNPGB`%I=sKJ<=?ynJDVDY9d#4!LZPT4=f z6Mn+k(D3%=6E9#_XNVWR!$qoLx{e*XGU!7Q6^DY8hnl@~wwIU7{y|HqB+Y&Ghnq5l+~C0LPk!kGQm# zl0`pzZ%qg(>B-T`9`jdH!OWT;A--ivV$?}MR2Ye@;8Q~BM?Mq*=8 zOmk}F(bi0Zf7;bzJ+S5blTI7ll@K7oM~`I-3gUb3^o+gu#B!i6jDVXeYtGBlc$3k4 zO|g$ltcCGQQLsabp!DL0`VYFdEF89IL@p?b4G}fp&GqanozWHQp3k~#Jnh_8s$Q<2 zY>>+w0~1EdFRRkhYvZ|o|AkhCjmv6Wab#q61jeftqK=G*2dL@CnKccoOde`p*sz=0* za5%S^DBC~O!<Ek;+~2MlxG}%jiC`^N&;9zF0Y4M>!HLw0gr2_VCjJ zzXzb=^orI?-a|dHr(!?vea%ES9ADR7U5f%v23@jYtHj=pHQ}97$|*;}+!wG?tLzR^ z-@isrAOiRI^Vv>7F`#tTKR84}>L>LR_z*rNblu)Se`7a67SGRQO<_3jh+P(L?XO@$Z0l`x^rHikBk%Y9rozrIN2CLa7&W()M;f0%dTGVVw(l431Dp|C zfLVK-vU10wx?U&lv0ujfHy$Xz z@pt_;D(rjlZf?x8_D4c%+6%b1>Z9rT?JY!l&wLdS3Z5&W7Rb@DMV|?a?z@`-wjZ9CGLKs}~hy zRYS6}>&af9zdJT_FT#!gz#tZYEwzU#vUz??p%p&OpEF!9J@S*{WmVPh@9NXsru*Z^ zM+JKXT+V7}d91JpaX77N4A!a??1K-fWmjcrOGc}OVQ*sbB>7*xq>6w6BC>JwQ!dXl z%hK`5whlJJ+czhKg0+FtTGLG(o<4K9vlI-u4unAq)8n^Gj zsNs*dp}b%k>}i{@_E78MVO=lYRaED>f~WK)JTHlH|D0XD$!gJoCtqBglF6w1J&=aC zG-#XGXhdIwB{dSwZ0I9d8pwoug93=M4qy#+uy1v0_g{;x-!;3By{sOV*U1C>=6vRh zt=F5avu$agrNN%R+slLa-EZ_7y!^W>5$MvyBirw;c!`veFu)5ns`ecHk2cQExA*9y ze7WfF#L?ybBu4V@7@g(!1lQQ&3AY-mhx1MlH-Y^8G#0;Onw>a z)EC&;8O1Nvq&F&92_rSt*-d10Xi#~uPjNOx&~xX_q0-7eJYp}yJB;uElt0krowD3E z%%2|JT|5_Uz$fwH9*6+6ut9whpyc40c;vy77&GP-TLOj-&n6w4Fjj@7h5+Rm9hW2* za#VT5l&}7Zg0(cxMe?{uFY~0ZBlY7A1DnKH^)`uW?0s=lvMZ5HXFrmiECRzx>wJ`! zQ}f>9!OM*lgrV1nI|H$XwwVM4kLp`m9rm?s0(lN+UX9Pm!wJ9ubIOKMEKdyS z*E+6&;2K!;)#BN)^K%`s5t{^ETqq5bJXdVd4qYupah5ka+)&|bm(i1g$m(37Bb%G)}6wPx9IIs>(+-W0#wdloz7OwS2nfcPXsT-jjOOnf3a8y5FB8U6~12>dBl6 zsP4Opzr0asgH71ovErwz=u4shT~Lw3fk#vYzOApr!zJj2;v9X(+2_8-Uk9KMXzsAm zVWMbOF#M3tiEntPBw!lcpi)h-mu81GqsT`~x|lVVmxI8z{)?uMN>dBdszymDk)QVi zj&6|B)Hne4Q*|X6@1FR1?zhJ`n0M9x0vs5Hw@FMK*Qa#FY8mPXFGJ<_Wjws-(moOl z;A0~6TT&=Fz0UIE{*(U@vZoX(QYDZJ*#ZaNa+Cv7=M1h?zrdj9;qxb2V+sQC2!mB;QRI`j({s+hK@1MV(cW>qO z40dtScbBG`_oWP(3EI*XEJsjagqd;)XARMb_2}SV)4Sp$ z5D%I4B)@i8A6agVve+37tUQI+ght8||0S+H<4*en5KTV&5woDIpNZ0M|56}06P^Jrq=be?G zs)Ygk!lIEQC@pL3(a~ZIjx4tnd(7m^zx|^~*LLr)hTQ81`>}M76;Y_pJ=jO=lsK@- zU<~^9uPGy+Rb)vVYR$*8xtnjd;LTS6{Ez_}KzF=^i;PmI-n+K`$R$pk)c4oB>5<_6 z@oB~{DN854xq2bV{6yVnghP(y%)0R~%YL1<>;iHv+Nt(s!f({_V_$$k!#h2nZ>Jv-uK# z#_iCO+_5!qx2bpRdhg-s-xvCvu@_YmA?L+Q8(qaYkE0V>9L`<$L@M*zH`$Pi7fW<5 ziEHN)MCMYJs+Hj%z3LdVu-Y{95e>Yk0RFLnmgb~i$_JeSqWrGi@K8CXX~cZ7 zydn~bxN1F%q|Rk?d~RGa12_!p57>y%MTwv~S&ItjGb%oKRO-EreZ~wf^~sf$!m#tN zE1TCh2=*G>8?ReBqc74{#^N`jwIFhf5rXaYv6ubx>Fa!t8vla%^2Z^JG`HG~#(5T_ z4_l(G>o7)-!_nOD;GXy}=6l8lq!!h2V9i{>OsD{xq7pANES|c3vQfz5RRzFOy+YeI z%i+Gq@ee6}K=pfwCY5iF3;O{rzmL{!e1@geKc zIDEwAR#InyLBvWuW|mf|6?fBk3L!}?KJNvoBPfb&vWn8hP6H`ULW0&AvuzG;bCE=i zIe=JE-%k%b(bJ-mTy>NE6HaKo_?oWM_z^jc+wYg>@jV(Bqjyb{A5h+Syh~=9&hMCs z&ne>w)O+T&Fqt>t^?G(1uH?1wJo#(quZK357NSiR^{3~JPh4Y#3kY~AXu>ToAY4A? zMQ$uX666zyf)osJ<|96|)z=xt?+$$8D+;gbULwG+tLNPbKd>$&o6ANXIcx;VabSNN z<^EDfD-Wq_Ox(!+yf+~K*;$#oi-!ABaLXV1z@;D< zbK@%#bCYW!Hxg!iJeieEdG#Wn^fkr+69vk77SdaR4>pxSA>`@xd}gHO2hBST2@`BO|=H)U}W0)|7FGTuwUULFk zJ=Q4k|>@S`EJRrz(B_40%qqc<0FT4`s$wp0i$klBR{6*0fh>h&4ac(7< zJ9U`tu?7^l^|ga?o;L5V#Gw6|3H}zq8nj;>sFnT<#N}1M>LNP0=S^`z;(G%ls&Rl5 zzOjuY$j{`$*HhoIb}OB%dqf;(g7!fdRCUdjDM76BUw!{>%JsRQDDL|EC`ov#iYM2i zwq@}KQC_npfr~aHaW)tcdQ)q0T(m^cHR+vsnZ078N89YW>)nS}?x~a8wYnc>F$ND_ zS`T6Wv4kzlq54SNFIKqcmggqx-+i(;jT5cbFO(+a&US8FZATeRG12hw=!x(!9iny|izbA@L9rt_xyD04v zFYz*nbFjJBd#T9&vz=~u%CQuM`P9GnG)#TCa_*+Ys7uc?><-OYcL1ywL5qH~#bLE6 ziJ40zIiekK5f~3$%jwaY0cpJ=L0LcODDE$fdhZ86HN1DolAiKlm)eo(+vD+}ZdY2e zk938ss04FOf^Pczg&K9bQ@uevqBnA2n+Yl4Ze73FmXyAbg5uVh`$e*AUy+ZV2F$vZep<`=l!1|+i}4I}PFf5`n5 zRpceC)w=gs4IkaD6oKdCHp_J91smyQ$<`^P^P^4fL35LbV?=CD z7ToRt*13oiXY*Fdm-ySDe86|^#QAqIjc@N>(>pr^C z9esqG@nLwu*^In_Ph=q8)h@4LAYJPcR6}s@={|>niy7wL^Z=>*%;XK5AEVdBeD5pz z*{HST0M~9mUm>@7FuuUTbmHVZ?K6a<+5IEzzC0>&5d6ObgixXXVAai(0Az z6rUve&9R?ttB_?==mhx&-OIZ%U&$v9fxV&`P_neFa%Po>wX^m2PTu<_BrNAhEES^3 zv(cVcpzNqk$Myarz02oI`og|c_*WWlMngFQo7u#hvL-}@*12F3hd%A zBU*NtY9}uDkYGyoiEJT>&x_xOARO0&@MAo{i`P-)}jnk$B0jLarLX&|i1O&^lvp@(TUp#)7q;=je z91)PX=zf`B86oZQqcXT;L?*`Xy%A2^;5SpKstgDwcq+?73N^Ezba>|S6rL2}doQ{} zEurrB)x!shAN`-y*ncH-I)_XiTGt-_RL1G@He&}IEi39^wUf;Wj_hg7$&KgbtdNgU zSdV}AA@eo8K=H4=Z$>$k33yoo9)Wzhzn8u=CR%Y`TQGVE*Nk$#D3hjQ)=<|o_l)SD zMIp8zP-2#){Psp6Oj))9Q_?!egHv|+76NWEH6}+KaZG19)uCqN!XsG1Y>?Q&k)GFwd^&vp z?wXz?GHc9~-QZK)XE*B#F7ZC?skNuGwQ8R9hDjMgj;@t8pU+_JwGFN0RtYt{kFCckCEJKupTpQ zK{+xhY*NbZ4TpMW$8o>_HMo|T2niSE7!={~KZkvM z4?4_!bo-uROP8t4pL@K6NGf650*pIkjm6ozn`LN zpf9T%qnRy}R851~)Nl=>UK|dD#e4r8wE?PpXisFX>lm3d|}`Ep@cm z1Hah^3SM1WH(jq~saKR-5%Jpw5?-{J3Mii-a_Pmnz>R^qH?PA%9-^4{o&BTM*8FSj zN15-nwND7~XwcG+%O)#c(`yP;wuhk8r|ni=Bel13xUL{Qn1*FLJW$%2Yhtam8pY6` zoc+Z6rQXZRZ}a|_r1$Oa1_=5a({{&i_c&hddwgCVBe4g=;sxcx(Dtm+7y%qd^Za!< zC-FNa;aTwbkRw%~s~T-6-NCg=P#!oYtpThOqf@!H`F=w=_OkCsCV2!Fd9TEgkDth8 z@KoSqK+4B0DnbLQNBqZ>mkT$;>7u*ZL$&%f?Rho)q)+=ia)MVDzuh1S%53{B@!yhp zUu4HVk8^a3ult2o4AM+L`4D{KQ6ioRzuz}P36+7!f2^rlDzrJ?=Xd#M@G@KW?Be~B z$`9Doz-LT{W>GfR!Fs`>L@FQbX%9ElAz_{8VpS8JAG*ocl|FqBhl6KX+Gi+^vjy2O z!XUf%yf|NSGmD?d^Yr(*v;>bmf1tuMr97{z5IsQp>=gr_{ar~t@fHl11+JUH@I=}< zl9hQ=zFV73jQNCa2#>;n$}OzUgI;cbZvIZ_qec8S^~v2?Z9?d)6nF3btE0O9xODh| z=6=_~tM`yzYuJG#>oE!H1A0h+sj%|(5GnB5mh|aQNQSLnExOoQ zm+ue$*dF5r-oo?HpVm^)(FN^%e64;RKi=9hSs4x(n`#zTkY!;Hnv-ALGoDur}uF7+DE_pmTd2@(-Uf{-rX`O&BUy=Q-0g2 z)s}6N3I$66-U;;R*!0x`+p`Z(7^z@i=X`eFCPad%_$tEvK!=A_Hfj;Qnx~Dt?z9A5 zyFJhWdB6eGE4}aQsl80>$@g!`qf0ThW9~!|@1VVAHKZ=i*?mf|%`FaAYdQ%^Edgwr zW^L+Pcwm@I7ijWXNcT-SQq9LuM=ePt_GAOfujvHupgPd>Pdi==YM=jE7*4{d`7xrC zq}fDiI)~rokd@zW^3$FXMf(rE0-_8wJ@K`X&tgQg`v9{@<2x;YM)1Y7zT!O+Tc6Tr zabOx|kP&X)23WNY{;5e=rpL+S{%kcn*{qUqZ9F)6ptV4+O2kO}P*M&BT01dT9<=7V zb`qHBPpCPXYQ5-rc6vq-g#8>seS1};Byr5tmBIb42A=K;(uEi5l7I@GMA>@yTIoUX z{Qh)UD&e>k-}LF;oL+D~`q2a}EOH{l7RT-da4Go^wkJVceW9ye{uijwnc3HDxXX_h z`?EKA*BUxBV-966BAPhTnA)3IP}h&O^Mli>mj@Fm_i&?Cj(3upC3(OXU)-=xLGeD+ z6<;$z=YD^y%dpz%_||UcyG^IAMSoLX}D)cVZL z`Te4P@8{rmrHVqxIY4j-jzJuzGSr2Z`Ht(zF*{PfGq6(c2Q}BVgUD}CPrt?TBKRKh z98p453U6F><8FJ6@@7=l?w%-W&T;6{_pn4xZi=DJchbpTEh2w!{T29`PgUn+;`r3RRERQ{N+npz+>&~V&k$AWj}lMVatb0UbP-_6LyHahk<=gx8U zLFPz3d4vINX}>RFx(sg_MU|x!uW?wTL~lJ@I72i(t$QMl^iUSt^y0S?Y8wq+KPNr4 z7mR=SnJJI3d`yQ<5Fg^aH`CvXvo7Y+{++SDc#f)pDvMA+yyOqgTs0ZI6X(p@+oQbAb@Ez{!aK*@mQZF zn!PUi%e_;l*G(Yi432(9vU z;AY9#bkZte9-6VAZk%DGxA*m>ua8-<8=4^C3OYr1qW>v*$=ma40F_murJ~|$)VF0{ zE|xWZQMU)!AO?H7VZBnHS1Iqm3H%eABHowu_(d8Ar+3HW+e0PDy`(aJ3;UU~i>$H8 z6QyqB4A@%y)@GMVL~+(&WUVIOUk7fv6>&6XC02}A<5c*N>e!>NDS6MQ>^D)yyzei+ zs`x}ctkrYYFV^2EVPaD19%)Y%PUm^r1&TMScDH2jYr3P(Xm$YoTppXd=Zeu13UMf> zUS($BZXEh+rVRrt6eZ|}4H`|L3hhHqdH9n3b9pJ6d}PN2$-O7kKmX0K00Lc;Ez{RgT1?-$!gT*F-`9MI$LjVvGJJS-wzyqV&4-&cPu~>ET?lz!)V`EP@+jWbztds3QYU4P z1HRF>I7D>I-;7gcdkEKHCeRP^@V(A4I4+|1bkl0~xC(CJ)rUD7uDtiC6Hee@@UFsfYDWkiKm%`Ks4RnU8m@CE%A z$E=Y3M0KB*b9<$a?|c28D-!bSA)(_c;%y)|bJe}s=>@WCc7g-^__O(qn{Zk+U<0cyaT0m^eCkTvUw-S!pID?xe6YdX4OYdi8bC&u zACH>8?q`P@!d$-fTYs~aq{h}9A(#ul->G zc)yG`+rtH5PDY$VPR<~iv_IbO=2m_m9!lcGk9VWO_XcQKJ*SfZFb}BRN)x0qvh`vslmNjfAvs!ic9N zWSulG#R9+riiWi;5b9$Kb3PfOllugGzkCz~A2}nhW3bT^1QZWT)hTMdujq6&S_f4E z9MqpyY9C~kmV7Ca`ApRvEXI_S zZ~cq&+AnlNO5pb`ed24V%YSM@o4;c#ZiOUCSJZ6Ao_RC6Hikc9xPCy#vWtyOYw|N= z)fMs|sn_;J946ML;YI*MA=fEp%yfYq^cHo*iCVA1lvLLTy}?<)ZgudSz!5ior$Y$? zjXJwRVlrw#BzRuF_y`@0iN79|Lhk9%0*as4^#Y{IrmuAMoQa-Pf>!xHI8)jeM1EiJ z_UBaJCD;aTiC6ZhuLN_lXCNrr|IQA_+_rYUNU>dzlh?5Ol6St}Y;pXvo`q6o1i>{p zF5z{t{Bh6|@7Cm!|5)*x2i@SL7pnO!MF#_lH0h5@bsY9|PhfISSr8*1YY4K+TeD{T ziW=b9iz*5cb?1CX?|n(a@zUcXB8Tii+ zd|EP3eQs6e=jo7=Ev^41<1}4XNL?KHN1im?+V~ksz(`W$lf~L=$ zN;E*coc8@=l?}e>vQ-`~Q`W=i3KY`|2$$jETwg#|+Dm#l0TV(uxWmqrT_$Ufj17fD zQG5SrpfurY3z{(I^`{_QVtsetNLDq~4K?oyk5UK=!h8r;fYAQSPyIA?Of7$|2>&e& zig3H+ETEyHT584P=dq&iPuW@AC;W(3dNSu+BOMy9&vQz4`ohs{$61b6sVe`f3eKoXC0$^_jLFt(OM&~&6a z%9FNVlUAP`x?evg>R{?1JXxY$dt6V+yU%f#ynvm`K;{}_vuqyYQ8wKZ9e^W05jwmMVcqEPMz1(Oth%Z4{gm1n( z>jYBRM5v%)@ldXO%@af&GEW+C|NSr#E7pRc(*4^JsLiP0=ODHWM0xXTXMpaG^QxIv zq>_}&5JnOq9)BRClRJ;^`}Xm?XY}Fzt?oyeyy29R^)umgrjv-54ne&a&(k%0u=PM`9trXvjpw-%3 za7(uciQ-f;*$TpFT9vn@0D|bU+f$qigqv z+k3lm6T$n&yl<*fN=(jsEOS^((OR1CAChE-)kg7MACSj;Wr94Uu62n6{Z+o- zRTi5(i6{$}g|~$`=44-;>J7x~4!wf7om>TeSE|3^`8}vU3O;nr)`Tt1w;p9Mfw$LJ zVr?Rr3Xh4FrsbhVCt)>pM8m=sN0+DD8|!O;rBbT2zv~AofKSyq+?UrrDUzoJiwmE@ zx1A(%4O$4NW1jtN&!+(L|8m#Ibh(1=cbhNKAoefGvq$QM(edjw4v0s)b{`_Y z%CpCg);yMn;H(F=2o*kZI*b+$&NbHT+THNwG%TiaddioE{9H4CVwFA1q}l6*K>Ff~ zp)~}p0b^zghz(yLL5Vq&X^Fu6WF~CO{}k`}=)dCZ!7^h0*3X%wv#-c~uOwT!0nMZC zn(u4ua{b%~^cXJ^jATmNgVM+XtiZr&z!Jlz4U#RF>UfItxmu+SiZA0W5?+3AjyObX z)z7lxm3keC(Ir*av$O2tGQoSM)J2aZPMN{Sc-)+uUGAg(@1M{&?(*n*kEY?SWj!o} zUqXSx8w9(W#t5$X(^wfxeikIYbq z1K`xPUQM`8wBzYMy}#-J_@Wufe_Luhz!~nh>+l5f^Zm7<)-vGrf(X*BMJY0GFOBXC zH>?1_R0@m-8=;piu#;+<^;RB8Sk|`A<;p@zddW+`XTA~lP}sxUrgbOVpYYoWGVk#G z9_}Fp+lCI4Mc|k9={>e0hEwSELN3+s_Tk=ZLhu7LoNbWy87^lz*+*8hKyg7RkIxr-{?{I*Oy6S`Gx7GP$t%i_uM+9?ggC3wK zGQ3CD=9b;l)4SPYp9)&)Ur+heFCzx_>Tz6NRJ6MOQ6~ZR42~rnZ_hh5@2|1O;ahUF zj9X%vR|u#bjjjGYB#!!PW)?N6{ZP{m;_Mk7qEbt(lP_K@j6C4`{MLL)Z25e>_GGQR zkV1@V^?|M(sR@q>f1*&ywg&T*?D@xidj-$qrNIU!r2A=S`Kjz3z|$b{)$9HPQ-BWg* z3Hww@PE+V;{u{>V&|rAq+L`Fa6%mc>eaZGnuhzD#+&(yo5{4wo=gj(HG`kWXOJ9E& z!dh#KI(m)`Y5Gbdw=2P)ff8 z`Mx+mK;#k3pBGT-=S{xdH)&TAu|N6uu=ch`;$ZkwhTX9GJjmNv04l4(ZByCvN&VRb zV#NOd+9p!@3yo3NyAtlp$bD57XeT^HVG6_U@k%%;luuAFkh~Tg<7v96Aoyf>2M^`W zR)yqc?(d)Y{f5DAWA|Y4Mxqv63ozu8z}N3*=C}GnI1qjUc}%aZf2SFlQ*pmmC(pjV zSvF%{+Vlqz2U@i?Ua&lC-Z}}~OW>7?kB{-Kl=FoW@g24*ec4cY^7At}g)^$00DK&k z(Yn=d2q}s1n%QsUNnD`f*;bv~5b(+xuc4KBAVWX&>0Ty&#+mMr!F0fh=&+Lx#?6pi zpiF$_P_lQFYJSm>; zpXh=P2Ou$d`t!7)VdOLfM{j4W_^hk;s_VJHT0mD{|hMvxp*pVJqL(2N8dOi2yEtbPAQO*`q_>n;Sdk=_Iv0k zcFoWA?ONsqLq*7y{(;p(==du?KDTBFg)^k2a4CX1SWy7rP8V0AA040hN0LeF@l90f z8~-6Lep7N5?BelM)b-~Vzpq9Iw)|RlZM(*CmW~6T7 z+k$ILL`$b+&pk+Arnva9kWGX!BgiR&=#Ti-8UIuU!ux$2tiMd<0PAh#yu=hQdjt28 znO9Hj_eifs{_$!+*)Jq_x=_rE6ZPW)R6m&SrA~+1Ae{`dR_Q^0@g_iEPq6s&>QvoH z`MZbzH1)eBpHRM9G{KDR2Q_y%F#+3)%Yjf_v$6YWhS1x0eb@%?D=sAs3b^mSLI{b& z96v0=WVlx>RTlg}JY!Y;mJKe#dy;!8@cLX{yYJumBVBRGPNHc?!|vPqJ@Gg zvhaK5rP=-XC63e!B>16AX&$tKKWe!72e_v)OdqilA<@%}otb*NuQm*!H=9WfF3kzV za09uj;xu0QJ=HUm-+{Y|>eH*a1xLH{-Q`GttV)bk(w>P>97yL1#m;BGzdH~@{&h^>90*>ko_Xm)z*cY+_;-iZcFf;wb#O>|ZT__V_&>MV zA_J-WP|0^-DBe5uR|ePZ7;KUO5t-<$Jxrf^{MNm{iOZl$aPffC@&;dLxHW;$L@ zvConBn0F16DBJn`z0T2e&fO{Bl^X$?g$*d_-FhH?a6=DLnVZ9WgPACV6w@`SeC6?# zHP~B!uEB#P&PyO3Z?*fa+~KO~8`_;;#@UVBz3h>w%^yA%G|7|eifR+x>gfB1Z2@%J2%@WGrN z5;i-yi$a++#7us&IV2Gng0O|#>uc+*-@j3WA~KG^XA}CB$_~1cQE%(~@J_RI{(gG+ zqy~dVlgEHJ-(a?drG7p#6OIu()#zz(JdI9D!NagFK4Ds>1_>{QCZ%DSV+RJC-_DMS z&Yz{$YxeACpEjF-lLAG$f~*D$tZ(wXo;XjlYyS7hvJY7qLS*DzEpY^Dk4F3pE6cxc z-zoe`r}8tTycLW$^;JP2LhaD3-jjjv80|p?zT2P?3fZVTMSS^MuHr2`vmV4iF?7-K zg1+R}V&2KOf`Jqe^PLU4v2ufG`Loe4@2Mw#iDk&?QVkuD{c2z z9eYcJ?$8{O??;eC8!GjutJS3`4P?F?TOs=vX%4-CAXwMK+u%NE`9KI%(>F@pgrEL| zmG20WqU0V4=Whk^pwFD)`tA3XV~s*3k}(p4k!ff3_962-_v~%`qL`^F*?7)l zqv$^k0~NL0X~gZw);BECa-=Z|78a-Q~iWazR~pBv2@+MY=nB$Nak0gLUu^U*+BGw=lxI&+KgEA{fG* zcp@_4<44ZoqLfTI6E3|VibJZ(H>JPqVF&*Tn>wUSS%>i#>lK*Vd=_^|NW6sxLQAM3?SZaVXQBV#)h)${8%ytGJrP{}mWz(5&xe869VHJqc|KZCM3(^A@b z1&T%AgN7Ze=|8`d8uTHM&fS+|6HhkJI!@iQmX^0sxMb0r{jAHl2kF6?#HaHc|u=sgQ447sux9ZPyzCK&N9|Spv-*m*iHC^$S&0PUkD@-e8E>P-FQ6t`aNCofNa z$f&R{oD?7GEgs6(G145Fi_VDuR!^6{iOb(%8=7Z^hI+p^S!b0#ObGOs~8BC|}^-JZ0>T61>&Wb*19&!9NKieRtfp5!7_|E&(yHO--GRK77p!4pmOxfMB zTnNGe;zKP~@(i%uKPo}+ZG_D^C%^7>qzNTEF|9lmC&qEu;JrBc8HDst`?HRvglZZ9 zp}0hE83q4+J2Y$jj-J$=l8Srx83%EX|NFE2{p}?UK`saR-CfzAu^^dJ7Glf$-zDas zFA)5c>U`HNVpWmL;Ju(MdSj7{v-HXS8fYEL-skswL`sR%GV0U=A%QnCcHZe`a^NJF z+QbGRAfC7KBZh-;%1&_4%8R=|;isn0it_vADEimiJ+vXQmthl=gI7#lgtsXUAQ(;i zwloKsM5*bVYLbt0izt<9i}Ju z4Iw1nhhL%HBM;F48C=ZhT>GnHsNxy2uQ0ud7 zSMkZ|5oL6BQ(uh=%=$s-(W9=vCd)XWD_1#_aaw6E+|w) zW{OBQ1&|1)y8{%=2Et`)onHI3u7%j))6T8_g#%9WaaL*&KIVA7&xeC@ndZ+;P{w2A zJ^;!p>7%iP;skHS%WbfuJ4`X2!b{iS#TuQ!(}Eks@!6lM>hR%EvA{=R}oU^duA2h``g3ZAV_z86`~^7O|A*c0*}2e$gD3;cmKxY zs`t%kS=uvD)m6Op{I%U2Pc+-N_}}1piDZ4yIahv_k4~c6%e!j-~aqCeXYUD4vd+NGvjA`50w%2-9AA8BS^goW5A9NQ0Ui+S8 zbBNtke$+XtO_AS2I9ZNxe6?Ku{45M7H>n#7lMHxo>G8)%WQch{6jjylKd?4l6#-rn z+(9_$7v7d8`DCr0Gm8@uP2GDLf>QN$QN3V+btgSp`kUsh`PI6aH(qg`-33;7R4E)f z_fJ(9?}uFM>tj&xsJY+i4~tn8te;MlBUoP<#_aUnK=1vIueh&ddkl5Fz?Xj2T{&bM z?$26mzTM!4lL|$ZFc@G$%SJbw8Vk@)QBh!%tGDet+`Sur_jl>hoc)!crS#`{J{8!a z_v>;l9*_8%Z;da2#O-%Liw968Qr0LJl|L8 z`>G&JC-^-f*9y(xugL1g=xn&iR;vs3uv|_qzYC@Wm|oGoeyP@BhIfjOR0h|p&y7W` zJtB<Y0yNY7|rQB@!#IoAv{nHQ=*s<0q z&gMNH$gOm|@}!83f%_F+yPx)wQ3RKln=o*Om_hGtipXnag;r|cLdV1J!hGJy_A4RM zMtcILi|OOCp3C?1w_z=Z{4w;{StvUnTvTVvou9CerAIZJs^kWRTe&&;=P@ckJl=kY zvvVK!h22zx=bHw1KBLb=J+Rk&kFNBM*Lc19He|_?RYKH!*OczoqZ)wX0VP_NE>|{m=S~?7tVAFD#Wjp zBcQn5tzvPxP->a-%m;6D16_4`tnohC+lw#5nA`&&`ms~IWE$4zLUw!|66O*&7Q~_{ zSd}*bK;7h=y|qUuf4}GC_XV7(Rj&SBA~`$Z6H+S+fAo`azcpex?8?gWw?v3D6CZ!C zmCD9q$^%d$I(@pJU+~d2Kez}4GerXoE9>f)e;%}aM!k2%dL%xT7p+9+h2m%)(^$@% zcmJA^@E3p4-T|J|SNd~`+-Z+&_j(LOGQXYl9q;`oV}zcAnS9wk-jq(n%;~G&k9Wh^ zC-;__EtA}qS$^mo9P2_zYsVe=S)n>q`R=+V)8-6T2e&i4UD%)xg#QY^h@=xV5$w}` z=bXErNpTBLoiHvTe9tFMOt;VOw&i%U)^zd^%W1lyKv(SLy=7toDWH_rS>t&f{X0>qcR9hIZN!KG6=odsx>ZQ)F- z4v=9ue7+Cf!a#99wgH73sbL=}v%lVL;8};~Sv)Gh))L++I`6AcLH1FG*4`)2`z@LJ zBSP92D>u;u+w75hdGhJ^fPV18!rS54YFXj;$#3R^C(KQ=8x{&YXc-pLn$w=<>iuvQ zRDB2*bQX6j#}}x%Cti9`|P3P7c;tvrjnrD3YV-#rk0$w1kdxl?8uRT*;wcq93Zq%hLv> zhHc-m2$Xq!IL}y-Au;6Q>o7p`$}oNgK^$hHqH`P{P_yQma~z>kzxl$-ZaMkuq*j46 z{LqK<+&;~u<@5}WD~=$j<6;K7Q&~ZMQeO7Uxm@o4FxAE{vb`Tdh&gNDB-kGgvRBHp zFj9o9{~&iO!o${Hm|J*JfCX%smzrNynA~|!1?nu;Lq#JGWiE}9MrFPmR>rH113*)o zlja;GS4TMaa7@0EOSsnJ(q6|I1z(hL9+}pUOuTIHnn&x*+NX(j@`5>~iMQ+^R==}0 zmANu1S}@-~0%tCSRt+ZPON20X)*`4JcwrZSdh6Bkx>e;RYfz`eXUi$9K2v4*R`pHHj3 zEzLln`33<84Jy}Q=HMVd=CDFSX}C^Xeuu%MuU@1_Bbiw`LY#z?{3n!Hvy^-nd!#vM zD-BY+3Qu(9wK*)2Exv<(BT!(symc|5w##@#SrpFk-~2qWe>iw_0zZZoT&p%=eM6B> zeDs?h2*;roa%l}ImU%sAtL1**-93be{arNjD71QM7))}9Ld*jq`)(a7KL--j*~Gly zVC+1$_#@9i%j}cZxm`hz|AG7|!8KrEANK1D<3b9@6EpMI;Vt%~ zpYA!A%w7rRPU2?B+%X-mv(HMV7^p=&+YHoCi^cQ_0oJSq%yC>>%i_G6t*c^g@Ag3Q zPjmC_L;n)k*Qtk^;LE{e+=71K@%Puo&dhL zxn{eumH$rUBbV69~)VQpZAFf?8!q9doblF!_a z&IU_O<8^wG>1%17Ex%AcxLwx?0Vu&9!mIj434-H&RlGBkqQFX`Ke{AjlMjdb*h~F8 z5jIF^Yt5#ym%IEYEF?TWl5iM6Dc21yy{d$IFl)5Fzz3o8XTy9L5rG1r(A-Tw@9WbO z(ph{^FVI2(gOB5yGg#P6@UgdQUwLiy)wcF(jW%GR{x;^&inZOep?*mYdi`##0e4^$W&z z-GJ%v7Hb4h@;MsqrdN7~3(vT{GWX{pT!thsDf-JIuLA#Pdk|Kfb9N`7G0Zhbn*psU$_r}Gk;DvA*!jV!cSy~&eNf-J3 z;+DXCRO`fH!4n#2`pqBccf|~$dCobySeQuyY&nH=&2|qnaKH5lmX3_S`_R^i^IJk4De(!~2$ggwk0n*QBERdHfU+Yt<+U*$rsf!M~zd*yR`*#ACzA4N+id?fm~zG`{$r@r08 zXlQa14GsKP_OS_ekHm}wOU~o#r)RIr^UqI3|6hL zP-?ZL*D-<8=KI&j%Zu!_>vMi`+TUUIQiji~?@Xz0RA8le_N_i(c)>MpxGy}Me#GMI z(!iJO+T?<=&!VFIAS5=Q*>!*y`r{WB4q-gIY;G1r%`L3lW0~?}$ino8`>Y{1d7^dY zNxrc5sedTQah^8yHANL)W^VSm+Pc;Row?sM`+Y;BUkakH3iZ!mlocraPOP<}KTymY<7^`!T~<_P=cCwU9u zFzYnJ?wz0YO(o6WpA$Vpv@qnVncH7{tM{!t>a8{&k#od7 zm4BA^yX;ZLfsJ(dVZC;VGZ~6OvHN&W-EDbY1#+kV$;JK%&g8NOQsK#e%0IQR(vu3Z z`sH(urCX=Fa2Hqfw&E5NnS`K(6qmob%h(4xVEL6wQe${tY^@T~Jh_hFDPzs5udvJn zN9xb~6zsGyp(JkBG{_qxO!|ELPvrB#dV%n687v8B`8}m5wa~o0wBmJF$c`?UEph&y0P!o- z?S9F`$aW&#%ZEml36I{Qqw9wkd$B>xTbqwoJ9o(u`XcsEd76?rCb0Y|mOZ$Ft9M2O z%vZbKZCmPnvZ9_p`uvxdv9a1eSpO9roJU)xwR2u01%=4Vg)`${C8w9uX2|(iqi?#4 zMhZ%#wE4l<$WowOrFHJtjp#Q5NR_Fi&cD-DGM<>nCfgo9u&WIy`3iH?3cwcs{vey? z`+B@H6%!RE@^%6%@VJ|}h3?W*19g0Md6kax)~X{Iy(j&8$yZmPldcsD^$$b<&Hd$& z9X0zy8ZYzK35;RI^wCtk2z!rw-uFXk>h-HRUmmJ|LB*_}L^;m<1AzR)^lbBF!;Q~0OKIi^lk^(&wT(AU@VBf+Y3u(1nJ zis$S|#+OEkhG73 zRXwHk4f07AK=E9!uZi!?_anq>#k{>~BqVqytR`N6!`#0D3a&r*^{gkv10+x{{Q&Ec z@Uq~N<%r#mVCJI0*~opr&vE?IWV48G`CWIh1iufF_lD5yq^7i@ZQEE}1&E)$@W+FA zC~0P4PcQX+dxPO;gNS4?D!ZOEkSuRmRd2tu-?QQS<1RbwRHig_@WQK=w25_S{_;1N zqJIk3D~=X@L>{4}(2_8}l@9mOJg;Hc^E~9}F&}C}z4X^Icw63OkJDQ~w~oMZJU;G+ zt}^8IKo>rfm}Dk(CY3J)urGlX$h{%bu$d#ir}c85sg6RoZm>L` zu4Gnqgm0b`To0Uq)P%m=o9EOkA~qnC4U zTxeoXP-G`dQV^bOmfn`-daDNJz;EZnRRcU|ulu;-`E&1c22nYA`s))ZhJT4FNO1H3 zmfvTOGv1mF@Vnb((Rtqumlrw5pP@$1+=M({rsf8!BaP}#n_INuwk zAUVzZ)kDI0E0}%V96uvP!A%KoD4A+0T_~VP#E`)D7kMaZXGrPK-X1EvLBo=-+2i%I zApXcMVP=_o=1->bm7&8I=t9p#G5C26+3({U+~BH3xSyr%!~)I+`w4_G=H9&q%Cp}` zmJ%WET=k>6nGQk0Hr^M7fKv9V_3QZ8&ouPe+Shcpk=pP6DDu#ZnIgE>%gd%dC$V`9 zxhp$ySA86&{afYeP;rzbhVap|{sY0A| zxx}DRSqJ>YPuiP6YTybr%W36+JEeLuMp-If2ui`+#uSk|ck_FQ3n~Vxy*Wr9o*JFZ%~6 zB{nNr*keT>E0Zel8?5^tam&2@rA`LBZfH4zN`;rAAnr;`Fq!8StAyY5!4}h;@?6v} zV0f(nTHC=Y(K!Sbiz9;~dELkDrwN@upf1`3ZcC)Xr)1Y=I@^O{R(-#iORPsKY0{Y_`%B7LMVnH0- z!=m)k{)G2Wea$JzviLpP@|?klG=MZH1Pg}If?~|19SH%Fry>RFf_DqAYS=jEVviF_ zVdG<~Z!j(Td@hp#-u3-kpH>$7cE$6PYd03c|BX$>2?X%r5&H&=Lq#oA&pBCJzptoGsscuFhDOihT7c9)`DAG*l>Pah!L`dPL|`@%?lcNhFT(gVH0E z!xLny4?Cr~8NyKA`q{A?@?Cy3PY5o?yc2Wii-VyAT-$!Y=T{>FtXY3 zGwb+DCX|VLfW4_G_z%YcfFTO%hXuceEM%b>>T3D6F3;Pt&7Vts(iaxazx7Rjm?#8M z3TkuZ)P}_Aiyl8I@1aN`8thT|yv562ZPDE5SRy?Bmc_PlkTp2d4F{O zL>90j2ts`5+<*(9QVnW!|56Qouf1JDD>UzIJ%U%JQ+^W*VFbGpcK-yy&v=J%qtZSRWgu z@V#Z_0D4@T{5ay{Z6Xw$@cV}I1c(Z1^LPeCw(lV{KplPxGwN%eD(UooY4^f}@ z*=j?$?`bIxFTgWIZqanDm5Yi%54C1(70KPq@wj~EH)v?$fnWHC-DXkn96Dm(T+)ZW`m%H2EdJd)Ho4FX*RB9*h)MeGG-0;y@pj@g z7pG(&`#rRxBqPEG!WGpsJHf2HlguW}pnE|aqb^Ym2T|rk zblidQn*#A9p^2%(5Y*K2LeH8@ka4x{0K^)>&6;*gY5qYF;A>|<~(;d@_pzLw9FaA_7qR(NOwG&u=Pt&lm$AM_gka*Okdbn?Xm2w#o@qp34x zr23G2cmxE(aHC4wK4&>gsF+6W6&R$w&ng`06K0r;!s~BekA2=hk*r`7jBmr5X8k=w z7atRyRD%K6;Gmf-8vwBK^G-pe``iZInDscOYS6JrZm&-=x(qOK0rpe>HD4U@e44{7 zAET%L`^x(Gwqm8H>`K=LbXZDdTJ8s3;?*>N)A>VY+ie9aFQ-e{GjA0&Q>$>>9yfj<=L6@AhZ`Xdp+R(m6687fW&Sx$5HG z4)I~!LrEL>f@2EKm;Eh!o16*ioL6q&{p7HqjcN<#G7Ya>*^+r!H+?mr+VsM_KjSjg$Vo}b<& z5}O{icU!oA{#2Y^I*VGbElJ~xU9|=R@Kt%hF&-~xx_=%$NHnbTKoMowDhajm3)HTu z%VVE#PrU73fO(a^=5-%Y0hKW^;YK5)&utklB6Tm83p^0PL~$LMKfA7hnJ0H448HdS z;1O}_;ag_c(~6%UEYZUyoe9uNRdi{2remotbHKJHvNcR(eKfOap*~o!L&VhE02R|XD^eiD(z4rq{LXZleGW(#haep|bNFG7?6ssM-4yGyu&9GDy8rQKHP$Bn0lEs~ zjAv4_wDhM1Pl?#l*F9&rGwme#q@plIg&Ocn#&3cfInuc@$>hfe4pi|aLW+b&XjG1g znH5XAj0t)kPgyUleNBPQe7ZksNaWmyYfjrLa_UX98YeE$KNP+cNa*Dc?(lMl;U(J( zS*oSpOsAbkBxg1VkiYwjOk|6oHU}b`$OWQt3pvLV{8vqH0sP+Xu%Z>40v@7eQ|8pq z(=W#@e?Nqcn?L9ot&fGE0rgb&i8Gx%et4$dcdt&j_pQT!DZU8OWuaz8LiQjlbzkT4 zy0g{bdU<&53&aGNl@#k<1o}(Q^nW1F4m!)=?sp?gMDIvBkT3L&Z;?epS28&rw8L8$ zW8j~xiW=ml)!O&%<-dcEld5g{ zI_5Wm&1U?B7@e-tlA+>*N|X?VeLu_m^|xVp*2@oRJ&O*LZ5eyT=-I_odgP=i1nDqj ziOY62QRYzY+Y!nMVw}1eng%&ke;Mj#U0#sYM7BoZ>=FR9$>7sakkM~ml?^x=U06a+ zX3&Lt9NoUHFTj6B`Hw(pmoDLP8&VCwL54KMfUWOtzPxV$i+yhPXL67GM?#z{0ZyK1cL}qj$c(;@jup!9a>nbeWxN#b^G4&2NraR)z{VE2;vVUaa@RizK1H` zCpSn!Ej?OwWUkBp)q5F!^A6vWc4~kdO~d?lf1b2FH6x>-lj=P(b|)8D+@Zom{Yn*E zt_-_y*n&4anG(aT(y#t=1%r1$_l-6QMBqO;yBGHx!gaa7(cahup&Hz_d>Sx~Gs# zkWbhX0`m$7&L&jm3nZ5vn9*|3_04B7Zne|Ok&5i94<-vNCf@9U1ssU=Ek(Ka1{ zred;wMRVLI>!4Sbu>5amp0J22@7EVX)>17R`*Y_YopT^!&?1(isVHGRy|3````isD z0Gd5v%KS7Y-7;t?f{f!n0@tjcTkGp0Un(O_?9TV@D?1{pt*(3Q8oK7C9;CEA$SB~j zxlw>#@PP=4A1#}tKhbx-icTm8e}Pi<_j_4goYUU(MsbqQiu-iNGlxn$gJhMw0TSfK z^*-eKST(N7a5djsbeAI5nav4mnmTwJ148Q>q&FcC;SiCYs~dzXUM!;*M}WZzdzZ8DzthpoiL4Qs=4Dj=m+Pj#9&& z*AL!E6JIt?#;SwD=kMOnOGQd^uq;)OK8&PzQ2A?O=;7|N{9`N}=ly%G?#5mu2bo-d z%@(pgr+KrdYTw}Ou0z+(}#Ce zd3YXqi!_e&5SaUzi{p7X}z|p+*txg`EpQ=rib2qoq#`O zax{4A(0ltb&6h$68mDHQOGF8`*1a5Gy zFSbk+Tog-u*x@)jF7ujcm}(8Z>y?DI8e`OmhT zi1Kf?iSpFV4yaRLZ^x+->Sg~lPoi|NUN<$?HRp2}y7SrAY`$vXD4Ea<Cn>@-CQ8q)+N z3S9M{3It~e){;g7Bzr@&Mzm?H=Zwg%Oz5&r=GUus;jRKa>S^SAfSeEsR}v=(l3kyg znA;Gp5Esf&8kfJJQ;=C$~ZL>`yh3Fv$8fVU3aQ8WGRVEnE~ zZF2k`KB7@j9s1q00J#7ura#%w*@O5YPlh<2!NkBXY9-(HFrlyqQq^5ikgw-@GanoN zN+79qmg*^(*5R8++=oh-66Ewln}qbP{$^cToZ_h|f0-voweLLNe{TLmZr} zX%!WbhMir*phAK#+@nj9_H?^-c@a1J&1?)_#(X z;1CYzPvYG{-h!~whVtyy{LJcSk7V6Ase1Lo@KEp(&?0w-$3bdA9I?r4ZLV{7z5etH zusFz?eP2)Yngo{sex&(9y{0NWk$%Zb|D-WU(vfhLUx70%_BY7Fb=M!6wg z^u~nDYHNm^D_KN0)apmHH-61sJ#klA*kL#7en9|6pfZfx&J*u3`AJ=oy3EqV+gXvi zfL{U?uB{4sE9vm!1L9VRcXmt6b*Yy39g{-1ycQI=ruFd{alCzUJIdf*+8S-HzG3*s z9+6$&Xc+xt>AJQQ#iHmhAxL_ZY$iy2lN>}c0$)Fy>RD^1+A0+kZa86w-#L~6y+1!E z?m`!H$;LnE8$@YY!<467`h8Kmc)#n(&q^xAI2puJ_*vb}7EEb&OR#JSfntvPa<_ub z@?PY(M_gnUv5kDL?!$3lC{LZ~4@WJuhv(mp)zghKu)nOd^+Ugjx zg~_sfQxu@_*BtC1ypXeo9RBMGx9(f|ts8FYaK7;yUrR{M7->0>Z|)IADNl4I7D4C) z8`=__9;h&2fL$avqWwSqc+@-{0i#yiWmx5ZIH*_CiMP&z5Z7Mr9T{m9R0{I zdRrq8W=ts8G`=}lZxK<_nDG#NT2Mq_O8{n9eIzN!oFSbD!-=$n1l!)7l#W`ub3Wo?7s{4cuMR(mP%q&{{?FWn*@N3kvzUpcsS|9n?<$>8@Dc#PBTNN_-an~9__yMi zpv<5kX4yj=oq+!FMT1?d{{$PH{Ba$3f>Ze9*2Llr(>_~v%|qt*oQp6r1CgyhQ4EcE zcy>U^?|2u}3FgCi*aTG+1C6dH0a{eV@U9dv8^_x84xId;TVF zUme_5de|q+?@dyCCB+0&rgxzJm-N<@#M-{q@n^|CO@W+`jutcC5bVH{25-5Zhfmj6 zUgt5d7UHvB2cDUD_!;jvZP^pVQjty^Qu<89oN>I~ju##j;00*u{&_65oiGHgsC?&J zDWtzd=LFqId>{Ne+$(8u${9Yf#_=ND>XDly%Fb^ToU+cH*h(m*a11SybL&di8vsIA z3_mLBNWND;<9bOXaE({Z@1c|DHqC7^SSu$njQ1!p#yR%WkY$vC-%Nc@r^6nE07`QQ zPz$}){kNO9P=R zSL6s+^-eAtQQxPqU|&3QRN0rVep&kQY^79QcMWO*T=>1Zoa|S_vF(ORjp|j-0+zwj zP_G=nG5GA$I(8R)AREK%XTSkImog z*>WYwy1X$`lv)tZ4`6ZHKnNdLTF$j?$05K2c@-CHrvYgl>SHdn#`4BY5ipA{-_BGf4V40Cw}-=hgYmdDK5Abu$(&_!(JsZ}<;9 zP2KioIv0}r%z4E8kj^Zykzl>jklv6d_En~dNic%C#*E3^TBT1_e&_~skQ*x*42{O@ zg(t~=(R|}nuY%Ntyyy8t@1mXo&mMQfVz1QWJD7vsvRQO0SUvb1lIT;Rf?<9L(2h_e z^!5dF&PqArQSwkXt+loCrmHd!!wwuiLY7m=5JLfra=f2q9S{#e$NSHnDxbX55 zTO%%??%LBU52UrHt-;WD^X(JT_v;J2f9Etw5Ips#<$+d*x4x$Po57Lm`LCcvk5Phk z^KwWGbYX@Z4%D|t?0r+}x!ztMAsU|PA0kjoXKLRZaMt(d);+@=5iD%i{_Mb4<-w@C z4!rPvQ%H*|YENhOUA(5KgN1)R2!-Vih`-N0q;+oEFG0I+CPlmmF%=i=k{`HK+~$5{`(Ctm%YUA-@cQ{2A=bcyRTAJ+Mt!{p%9qzyW6IK8EU@g-VWK2d-p5; z0@I&;Xu6Hia#Thi4)8>k;{FUPg-dyaRLmuPtRU$rsixFt^AnrrSlO)3 z-$SJSM?7QoXi+74z8xL*0zJ~{3<;2ZTw`Xe%#3k${F_qLC_)v>u|AiJ`eL8b-JMpJ9qU;3 ze{g+-k0*NgZ$ny06e<*nWzOgBkY~G&`sL;t^H&b;0VJ&rkLE*Y%0J(mnQAVOl zNU_PDfPT29FwQ*BtSK#q$|or)H+C? zpWoZI43}&kj@=xHi*l_7K!FzZtq=}a6X3d`#{%8s(LZP&0U2D2-ul55on!CDcq(6=P_!Px59r6N1lnR+NXCb8&l*qF$57Glr2uca90-*rhsY-X|&X3 zKkjFcj=pm8H8Q_f`aCXhKW>7|Oi`cL_D!uEFvpeq&?F(8>iOwZy*3%F3;7`^6MabZ z9UX+`9Ct8}!X$>Z`Tnvw43*Q7uFCZQxwLd|{6pQC+n0A2|Gz8fa0xF;+IL%PodT_@ zY*-Lg#A<|Oh>#9{cki^ePd=)CDNhguFp+;oEkIw0!VD7VJ?OfF1fI@-N2fx#UQfpZ z4F^D&DsAyaW8xe0d67V*J-^FW;j>S3*jLl@<}|P+2+YQ12~-6I?s4@#m)lSL&hWuq zk&QsdGF&*K)?&y@S%r1mm+B^jVXaF-Y!M_KR^AM|F2s`F0O zGn2hu(0E`s$0eweSu+BG4ZD@wgI8saAhe)~g%8DrdL<@#%>5W%mLLqyZ$7N1|q zD#SBMRrEjaU3n0=X-V9#UAO+VDVW?Cr!|E?A3y7?CpkxgvoIMUgrEbGF#n1?NwZ}( zG&BBasmHY)%ry6ik_{|4sQ!*x-0JTnkG!p@=z8C3K-Lb^M`t48C!#a14vO|PcWVrI z&q{F0bOoVA6X(z^;v{)Jn{Z9{c?Vo z-=}mrU$|(M=qBr#3AgCe^8MMBEH2AfrOSNgpO(l5LxgW=dwE$SK@{$lI2P>mIK8T=xj`|qU(2WvW==T%m}Kk-cwrtVI# zdc^ZS9f2&W9P|}ZK+E0vbkCphn2lG>M`*7@C0u!a=M-` z_u(~)UoTRS=yX8>cOjCN_}tqiq92p@6p>}(Byc9amgJi5kG1T~T)pc#sy0`4VIB3T z@Mq!J@9Q+`#P_jwr0O(W27&Ky*G9U%zd=E!rZseedAD)f^;=u2@Qm!UT%JM0kLuhsc^P412b{tXIp!X3_ZQkF7c!f6fu6u2&af#8UTIdW6Mf zRY3}Qx$qy5C7|}@jUt5V*>?Ao>*<@&smHkdocFJ}zDHt)8wi~M`v&@*icLewzBtTg zh2oay&i*)iTB`|;h2dBCi&YQF@^fMH7Q;xSWfK))$Z=7sS95H2`GMrXhj==~H{!?7 zoHf^JDH=>y^%XUHP4pB~zsn0gp`gghU-rwRCZW8BlXJBC6P#=7`nvB-omJnT>*)U? ze{~LhhQJ=*5n2IW5Les5fp^8uaPFJSk|sNU2~V>XGWykiurfK7;z_ZlNg zxBC4$>_ry1u+H{zTkqX-il8X_a$j`)bNuXuLR)?w7RW`>>AZB=Y9C*vKRQIzwK4x_ z+xh`|AEK4)`U9QOG&bvjP!(fINQ4H~5N>;VH`k=5v1!Ji_NO<1L7RZTb z9uKcSvC6UktL&34%Nv_th1Z9dm7J$3rvz}r>n#|*+JGO>%_up_~@SDM~q>l8m2 zFfL@2A`F}bF085KU{_#TgJnlE@YaJYH005jt*3p#4El$E_qt9&sJSy-tbiMK@gU1aNGlD zP@VJ~pJVmm&|sU>{d_RYy+l&#`IUm|A8d$H)U%m6d6oK$yWPFn`P^U8yrd1lGA&cj zp${W#g2`1kYF^_S^!pl0;s5=Vo1N9J#Vz^W;M@o5wc8@?aRAe;>MydwZFkHQG-iWu z+pK0clsHE4PPH=;I;p*ASEv6&dRa$j zIDdWR#SW2g2ZHnv-q{Jxv0P^^Fx=?s3%kPDvqhC|lRrcGeh5FNjBcDTZqRduJshk9 zs)g%hC*ETK*Pm~XS%3doX~OJhLOSyP^s$ya;QiTMJNU^~->+SDx9??Nd8UdzHq&u0 z;0jP+dGDb`@}a*H$3$DSa=;YQLJW?t%B=4B=j-F(@+P0LqihY;WqkXs!M>+wVM>P_ zgx;&J?S~>?jHS-JLwv63_6otJdkp3H;XSnYj^sBX0W!ZoQojA(gLOHdK|pE)&%0f# zUt&wB*3J!vuQ|5+>~=tfWPU&2uiz?tF6PD|5PEJBRyYt`;ue_dANw@>UO`NIky1C% z7VPlwh*hVD{J8`M45c^430gkO`%9(Gb}{zA(c=@%YQY66;|qG4z+O%=H-bhGei=%8 zzYtB(KkUFKCiX^e`O#3YuCHeeELcO#wC7G3rn!!o+c&>d0R1Ofp zX6^Waz|kwmwgaHKC5_}8IOh5&1Ia}Rps{C{8wEL?x$zFmiR=0K#T0vBl{&Aff0EGx z;UoMCHPP>J89+XQfH2FxSOtisBNe-5CN9Ii2X80%u~Ve=cmU3u3Q^ns1?>hp_U1dU zM&rTTUTp}OD18NEuC^(VkFdp9*(PfoxvNU;SXgcJJ~69?;dof7Xx;PjdhDVsf;ptW zjBV4}sa~(yAEscz^bx4;hM!Lx6;i>!2Y1^&7n=bwJ?>Yr$@@6&yD*)3^QW#mAEqVw z_N}n<92`?V7t12tyn1vY7uPcF0Dd)(H2j6tmiYpYVr z@D^&<3`&fU6WTAjoF4X7PBQR4u&FOhsMVs&ydq4f?CUyK$sCJyuAV9xhHH{)(%&f!YfUFg@^ zH-lUdbPYYiqm$$Ec$mZM{nCvGuV2L2a54| z-+s&FK}H!=QZ)M4L0?`!K=B9;!jY3n+QD zynczL+?E22zM-2IaVmdRXAfs9zo;YV)E6dvvh-Os3siP~KnV^ec}c(NBRP&Jiio{0 zw1)^beJ`&F?y|k_&=+N*{>lloxHZ)Wl(&B6ob@&Zy5Srb5z=U;pOU-ZW$Va_)xj4RkwC~oX-z z1GAMcfw2jle?H_24Bq^+*})^u?%yYD%Ij>eF~nZekBYD7vu6qK;iTX1_2RuG&SpY% z+B~h1v+S9SgJe!e25w09ElQ6|wsS8Os16531&5q6X(atS{-t)`)#O`I3_kD>|&Ln_Gm#u!Cx8zQ|jXm#{6LFn=hL?eRR0yMrz zy0HXVEaX9sPkcyHMRREK()1D#d*?x`boj@ebm-olPi1SI{;*Uw_-m(T*st~t0`bM{ zelc-WQBo++m?1^#I+t)QOIUCi#yV+mv^hZG9#~<@+z@~5Whv0GtM+>p8RW)F^4$sL z!a;d2EaOd179T?Rt!6Ppf03Ypq4|ix$R4j%EeZzE!%I#p)D zxk}YAB9jMWqL2VCP{cCw8!bWQ;6NIE*!M8EAVjlhbw|33{03G0-!e}0T|BTi#!xBa zdj=@M*^A*9dEY$ZAxT1?P@iP0U~N^j^inzgmxjc#4gDZ%p+P3bwy3;ZsP$&Q*)diC zD}Yko^wT%y0ObB9CM3i5myD7qQjvG1ABxpHBV^k`eCd~8dOwz}baKu$W)(zY@q;*N z(!yvwK9p2h>bN)PRo#k!@HS<;I3xv)3qpBmma?xuOwph7?n2AS--ns!d5D(Xq$3l~56n|aVbcCX! zjHxs~EWMVg=tN7B(=|P%{!WcxL z=kWm0TMc{wE_4|O`}MvOX2YGuuh{|%CVomf0Lab;BH9Y?Ssov*@Ri~5rRGVXRwOwB zXg2YC*&P>^Z|u|W^x-I_JN|Y1J;3|bt*q`2ec!XGs6SgE!?b2eC(s_eb*+Q_Q^=H6 zZ)keNYCFQmM)G{q{r(QdS2gaEbl+JC3Np`V?8SBc>r{SI{!cLYEk5DFwjWu8KlXHW z=>}Q>aAKAwYI7oACL`l@VUi=)?ZWDcoyNe+zwFb!+faIF5D=)OHN=-f_rQ^icFHm6 z(HTlM21_(5BrkMR(fI||l7u2%s7c(+eIZZQ^mrn(ho{xq-mz7lQpVpM|0nbB6pWJK zcGz4vx(7r996b9==~nVd2I3+@nx}IT$1_`ZKf(dYikxz$FT0cRyaWOF~?``1nFk9a$lpLBQT6gZ_M z_uTPn;)hB_hj;q9+0g@?JuGH%`KGA8c{ANBe-X1H$;r#yieLXN{6DrPB`d^j7 zJ)|TogmIqzTlyI`NIXETAYH$A&HllTgvD{L@Btv+x1++{-t3lgt8^c%PAH{Q0@lWj z^HFyW56zf7nhzN@y6xiDVb<{b#sK}oAFH-kKB!4rL`B0d@;BFcr}%Ovcv4lr_QrtK z#B9bTA`N#JA3~#nYQ>YrE}Lrsyveoqfntx~6*-q$dAKlo{N-=s`~XFf26+Ej5S~uk z(^1DBH{N3E&aAv=L)QYbw%Y|V5IL1>Oe|TDJi3wq`NeR9@;&4Bfs^Urn+kd}66z%8S0^Z>5y zvY8&5{o9ASgyrQF~Gzg7h11Pi z*!T&mYoE`OOjj`Zen3(RA2TR~l&T4sQou8@r=Ci4#mlMwbT|(2;@j&=q73fx+PJ>H zS0p)?QqD%^xp{Z5?Y0~9J>QrDT^9q+rfqtaA+f~SN~@pYfKspKMEq9adgE|Ct7Zu8 zcXw2VM-`)cXsd7?gs?Ez@Vu~R(3{M?rBLpLb>C{}yhlY==~&dKPF{J{#v{>>d^Xa* zoi`xtjy4Lcy2xr{-Tm;nx18?qG1Z@!eF`?Ks_bd?v-&OF!X+01zi>zvGJ(3i_2(xf zKX@5Mm-Z!r5-WrI_2H6xAw1{A;Ijy=>V0Vs*-M^i$HOIYmQmth(TjIEqLT#2Ow)lB zE8ed&4+77Y5e4~U(FhzLy1(r4EB?#Yr;%kZS#tBcwGz+6IRYo+u5XK2>p6Po1zJAY zF%i+7R$;CM#kw=UpM2<;EpE`+C(J3-xEsVNFvsLvEhRqsq zYV||M*^##b#O^-}aY){xj)qIyGKsK$PLRwPx{mM7kE@u zMXC%lwvz%(@}DHHEy1;qY^=4bQPIL|*l|?c2*dRCtwr+mOf~o&D%SZC2WQ7=2Qx(j zj(!Hrab`432uL-#7EK_adF&;zgo5nzobI_OhQL02`F-&nDnz-;2l6S!#3XucI;Wtz zG$-LPwae?@3+aIVk)C3|2WSY~FVP(?KBwP>6$|I^IXIc66s*C~G5u0eo>GWOrHRky z%-MFC_-l3u-$vS2iP*FkP4w?Gj@oYE$4=~cxDubYwr5GuQN#zicb4&?gt$3^CHA8V zm$s5VqRv7Grw4PyZY=Bz02B{jzr}3{IwC43RPXT$$4Di%6VJbyNL5bn2G&xg^(7(f zpx+lQQ)K4a*hvXVD%egJ&Ty-}#Ml#|({^>CLp%YD`bkmyQiS3I(YSr8HEC~{5mcGo zbFbI>@A`CrwQOLkF%38O6lnfsesW=XoI|QV*fC$=%PFV;&_ZH)vM%n+-2UxuOIs`( zT^aq-I4SF0Dr?K^6tvL&@^hB@R_7~(RvzQm;?d+Tsn7}^!w&mU?AtSZHA6F1uz>h& zakpyFd+WeiWKS`9KF1Tl5|erQ?kn+tMXO@JFB6kgI6vDWcs;3oG;nrsQ=*zVHzuLn z4$!b~PXs{m4&=@s!WR|KU~M{2Cce3Q)t1|l@*aLhWa*j=1F1c}QpiXqLm|n?fL>K> z?f&%U2R40itzr%sOJ1a&OXf#+Lf`?9Tp8hh9;3Aol*=;_Jf>G&-QoF+{J`e*eYZ^! z^;DC|ZV)d}DPn=<33UZEknuS#ZCZ9cn_Q5hm%*KXE}XC~?D<{nG5@19^N=AfjF>$q z)74FYCT<@emM>UcJlKuf%dM3lt-!pEkMMvL4MdC`E`sr^{SYo;@Ua#ux0NkkH6&o% zy;z?nXi*J4m~#y*nKVFQNRqupf^S?fUWFkW{BWL2NgF@CeO`wly-q?6J8sqvq5GRPz=hZXg6VM^VA6`o-&FN;chx@cv!M@L_ z{Jm;DRjS>uQf{Q%-kI(iz?8tbXo4*H4?|9jUD}RMlZCy=ke4QGc>s-b*gqvDW&suVr~49}0!4xT#8-q)&vWw;(7oHRuJzJ3Dv zl9`ly(zp_~(Rb_G>r6R9?Zc)H;Q292#4G$1?Gf4G{R^lZf^;Bs1<$l>(={aKuUIyj zQGR&;rMok)s&&hO+5$<>RdEbKm)#50(#IHh=0u8aJm-{;2*cD-;J0b6=s zFBsu;f0y?<*gtg!BE%Hub^ei76?03m-^{1gIsaU^=l#v|m^zgdHckVRMZ)>6*k$ahDsjV>EHZ%~yu(>4Jnv$O4V%Y(0Dh zcHAV0O*YS@r=)G^{KFk;^%OKYDUV}6E#9O9g11ShS(Js>>vw+>@0Nuwb~C&69*QO6 zRKp|m>fFUD)YgbOFdodmfFHatB_(7)?BgJLANjXE;2^WR5x|snPV4$1>Lh!<4kD5$ zJcT0ieDxa6a<3Gv8=p7(i0(;o+m+!ImTvnUd#1ca(z7q7ApY@5TuDwZY8wJyHuU%; zs~?@NAGu6Y${#45+z!X{Nxxhb|F-L-?US+vT|8Q7>(Es9dpNs?iI3dVi!Ah@>qAG> zgqQI(IFX#>TMy>f{-HlS`B6>dSznOyOw!3XU<19Q*rIqD7Sexh`FZC!(W$Q+us;3F~F*+%+xq{AaR$#pwtSlGR`xk4#6{tnN}!h8s?A z&Ysuf58zLyyR||7BRXxNC3iCLkB{QAjUsRN3KrqA6{f>aj0+t8X}b3ULH+O^Cqnrebx@l z5ynMyYMr;Azim^{vV;j>HJQT8Zhm?P(+N1_f*5F{PZ7!%(SvoC`-l7|7nQcInq40= zf}hajViOV9NBKC64|?-0C2?$6nnAJ5t~PNjR-HLnZ4Z3ny{4?AU~>x`P_5}w2O8%V zGz|%GDdp?1#ZVB`gq)-y{q`8Ro>vCJ4Hol^qh{{!e*Dn0X3n|^CqZP20wf^M%|2|V z80aVbTl)}A`Q|=BRvJ){zu%lgXWpTi%;n>gurr2)^GLEnT{RCtg|o&S%0YV`S4NGF z_^xwj#@hrkXM|T0fuH{fBl6PbnHNdHUa7EtM#cFu70!)??iLF`JH4;{M%@**PZQRY z2Jb9*$Uy|T>~wSJ@6M!Fo>&w2i5u>B{gpqO6EroV*wwMMMtsK^mCNTD1lK|e?;d^kTHPvQD8)|*6nH$s5^Q_`#K3Cc^D&A>S=1Y~gDU27ctcKsQi85?jY>h}Qo zgK{kB&tg&aP6!|_oy7igRV?h9inTAiKP!QdbEOyaEZOt%Dl{{DF4Vim!qfpOc+Qxx zVcAnGp`Q;qwE3s9^zWnx@zhGMEShH@5Q|~b!L+96eTtvZ06j4u?OQmW^wMe1>dPa} z1LNEMl&H*GznAlU0emkqt`oQXa^H?*j(H!!v(qB&jf;Wpc z9%$o=FX7OFqiaVV*Lh8g@DQQEKs8D28GhkGfo6BD-4llHK;P#E`h=MYRn7cGv*`iD zNfF%6CL6o}|0%$U;7?>HwX9@C5Nm#?-d6I4_=T%E;Sthr5;Hvm=ep!gLq5vl`32#R zWQGow#mpd+xDQCj!Ed-e_b>o$zWXICJn~#Y2gHKl!!i0@)#at6fcDxp$3a2L*n@Us z`3h9<=s0U8ieKzoG<-FUePUi`Xu=r>6S_WJ8l1`~pzcs8z;P*np5DJ9Ct2M0t$4c6 z_87l$4^sX;&i1Qd`|*ON2|{ISZP{}Jn)b}>O(_9R94cH}J{=wl)zFM{Fv#VqAUELBA@5rW6L7q+o&O znaDdo*ff;AVo^>_+SMIbrslmC6Uzcnirvtspxox2ywi*JdmH##ila}siW_%^hwf8P zaG{h=(zf*RDPJv!MhVB9li#8ss}g=5&i5vZ{V}v(FAN5p!io0xbaR6c!g=JdP0qAX z19v~QeZNuwE0QU4JJ)OWPj3g+1SzGu7@4B`M_T4LS^$Oa#R*zE!W*m|v2U;H7Ik=Sq%80FjhR(*W3V?u?313#4y&FMXLz+pvF)dB0C zM-V?}!qW2(C>R%*o7g7rO=@(-;-P$5=tN(B!^%7#L0*;Cuwtao;Bh=qw#H}XUHWIa zkoYLmvzLNql8k4?Xk%=BLh7L(rp)Ube6u&D9YV-5NV4{VWVL7R>&uhecBl?maAavG z;+g`r`65eq&X;hOZ#I*aUlgZp`*3#JJg&F!ycdYak1af4m0OfkF(QvR)?@LIiHdDm z*>Ygl2{^cLINjKL`abF!yrjN#3WCyy4?~CWc&jEYOk4nemdT^ zFLs*1i2Dq9c)?}7#|Q2&_K{Ts1Zn=!A*WsFxqGiCT9!gOdTpVrxwn#T`fnab*TIE# zVhduf3Iyq1F6=;{c!p)zr7WdEN|18|BFfXkADexZls?0o(R2H)FFK! zKz&8PCQRY+2yXc-TN+qFAYH)t+PT#g5Iusez$^Ow^9meingbVL4+oYMVt0lf%J*?W z$u(H0E)4h-3fBU55wmo|x|Yta;wI$mUKI@~AJUa$64gEZ=OihSA$NoicRg*nqQQQd zfeg+PTW=tzD8&yY&byf~*731;LSeuz`vbc#oe~KtefXjH_YKw_ z^XoF)#7{mjUF|3}tum>HyL7Kx`?$!*8SX*NUNQ+i579fy)6yr}Y`cC9^PM$5FcC7& zaJFlYm%|g)_3+yi-&bJuZD2!h1Kn}M_hY~Tec^awvlDKOVqUu%N3>C(Q{WJR#hn*{?7s2H*WGNl{nfhOR1Tyh>i zZGPxf1zLI~AdIF=`j?b<;rQ|~(9^g8&}XANh1vPiAO*Ls6Pp~8GI|0V2Or2$tTzJ2 z-pWzI$>?tGvQxKhC&`}XM}|K&`jsLG@^kN#*YeqnUMl)w7#+0Rd}yB_a2+3lIi}UO zFmwIKXh(2jS9?zBV@nOEgT=buH#fiV;7Ne$>IeI)a8G913!#_$rDF@skouwtWvJW_l>+zfb*XRBK7S*QX9 zm(VYpZA^?Gcph5iLXp~ZH2DQ|u0Km&wcus+_md#`sO|Gp0=DRqGPNm! z`CYzjIA-&%03fIaBrfjCDF#7PfD<(vNmf%T zE!PaUwYWdEt<-9ZaYZ-2-LAcVc|)h$_)QA%FYKa8S-u`36StNMA58?CccFYDwb>W? zz25-wMm!32oqWV0pRRkCStuUj74i>C!afZ3nCp<7P-5%QKK3cq&e+x-Ar1h|iHl0Z zvi&$y?xz(8`^68G*dvT96Q4JhaqcM2OxHjUrucR| z2QXgk)L?w9qbNXJ{yLKv!W9g?I4~*E-(i|vLP>aIh}pwFX#olnnMv2f4H%ItW3)Nx zxbQZV(Ocp%tQ0vofVdDN3)f4b+@!zg?EZDPN^=4?qfq;V+|uhR4rin<@KIOK z^%gBdZ7t@XO!@J>-ZfEdjs^}nRGx{IUx3a6qu$=-?{rI&i;U`fy$=5E2JNCL_n={P zO~LYi`sC}q>r^O_S#)pXE;~m9hY{Yct3h|j4_|cl2uaXKY7fP0a(Wpib3B$ZQqoqq z=odX10~$)rUeUU)C(KO97G+Ktnl>M#>+;O5we|uam1&IaeSMAo$ExGFjG3s?-4;ll zA6uU|xY?XF5{;B$XwSZV%?5Wi0wxy3x^vkUdcUp2J^Q(uRPWi^moPMad`h62j+L|6 zS=`y)_&fjY(pz-?9q-&;PHVIVYEj=E+qP4p7W?_yL?-d>3Dtfq{SJ6J4RCCZ{S!wc z#NT1Btc%hfNF@p!n*c4s6MAGq;#b(?=e~+0v6TPM$b3y4`rEnx@aa6m<3949v|lOD zV+gPh%0O}34bKOWVZs$G*&> zR!)>{adrC}pyF~>0g~I_sk{65sOC_=qvntniyZx|OM975IRwY{)qyi&-rx#a<%1KN zze%Ru%;Zb)#4%L!j473aMVH=feD5yYg8#q{aD#9{7(#9cA}XP~i9iuvu}HEezIxOb z=YiQLoMH>^{uyNMWYDa?mA6BxnH~P}F+g?J7_1aZ>)HFr?qR+i_RP)e{Y_hrg(2N4 z`6Dpon4YH*72>G-aT@wIdCcbsCG~U;`!ESLvSRXzs|#W_9Aw}%h^Nj+TbLV9KT`KKq;a9lGghocL015&V? z_$4eTek9>j@?0DoX6)s~I5f}w=JXK1K2UH8`}wD3`qakw{xte~VD^<(U1HFrXS@a8 zSSnPMoWRPZ-?$$CIN+ar!4ga>d#f_d)7D^!j$M!LGg+?EEAOdmf5FKjrv0#_Ww<2ydu@4?GWNN;054THTEn*+n zij0OSJL1@G|C!fW&kp1#rRZfG7n!2@9BQA}4p!CgJFxpFAnwe2ZWXK#>%ZlZn>D@| zz2@(~VmMdclf6OR;+6})2jBGc{qiNa_h~Gg?*hU(D!iY*`#PsMyuZglbXMb|oZllR ztr9U_=6nTvpS3GpM8Wk7vlt)@i8nD4++|ogyaZgY1akoPEWYq1j)Yr z9Bwr|*nh&E0k@YNm>LC>pm?3GG$f?B3j!6Gk#O{~-`L|P-2;J&e>|UUMA?TDJzIck zM?&129;aszD-S28FB&j(@A)njlI1!V+s4P0!YLvLc$=2rks*Jo<*E^|3Pgl3_B@m3lC5|z0jDzy~c;96L z!7dfhB3?3aDqMYkxKxvoFzFLTq*(crbF)q0MAiA4SG7)G3p@ssG&iM{(96P~1}kfrVE&^=r`(NI;$B6#sbKMVYVO z8orG14s8D~pGr^H;qG7oe``0p%D}PteXsPZ+e8D{KpW!oK*X->Q4ZOC8;VjE^Iw^+ zPQ)iC^zNfG`}#B9fGhX5*N4uxeUT>Kg-BgXtdH}dAoQGHi=(Kk0_&X)^wb|j@9}TT zN8wF;gYP)U;)#5&M$zFJo}Yf(Cr}k3Poq+OUB12SUGD%?fX#QGoYjZ^G>Mic`Pj9Q zgvX%+Vrh3xRE%W1)JLiMe%hNj`G8PXRRi_&oBf(!&O)40Ai^(S_cIcjP9(W`HMhH^ zX{8LIZI70fnTh_s=!azYRZo2W;I{ETM_LaS-J1FYi+f`q1`R(z!NSM|Hv>9g6=vck{5{IXC#9Bv{*?am)#AMM;-9I_0dqhin z5XDuw;+3obW%Tg_do+9;sbQg77TQJ8l+nPhy8gVFQUZSihQ*3`EX8}8(z$v~PM&#Pax<{fhK4aB#GCO}96Hs| z00m$k)%a<6ny}$idghUNsF)th`#0E&*0UQB-IE24Wzc{cptA0DJheCKHw4fH^-lHG zC@I>zdOAF%19j+3!hS{06ROg=V%RuQ%c7-IAaNZkA@Z8LlP<;a1swM*?(5mx`UO^~ z7`@D(P*r&+8KQFMqg@l-l`6f_wk1nTTPAsuIBmoZn>RbUc`Hp<*Tt2SjWvd{S-xqDf{E_i1T-)Y1#k~K5+=h$TAT+&9S$7 zFfE_8VBjHdmpKt40b`33v5LGc{{Cq$^X;ydO1FR>cSf=}-YA^?9o zW4eDeHA20tKDu$0M2OXeiG|ZIs+!jk3VjelIE3FL2kS*3%ZtAC$=I>T|5&=xZspi0 z{Fh7_KAMS8Wat|q$`EDh*T0wZylb6xnvl4MeeZn@<%V*Q^Jz^o78?3QITAGM9N9P@ zQu=7ItHhV*+^r67SBnXfy=EYO)TD)@2y@zwM54h`J(eV{T0Z3kBKkUS94_X^v%5k5 zy5zO-_o(oej_0#}?#u3(GaC1JGkY)uFFZ$45*;&;D4vVxe*E1(0KXou=5Ytb9Wf1P z8Oh=Q^Y-Y*8#Eu>$D?qdgOB$vqv(D%{u(DkwaG1etmLv1^+61nKe+78m?4`4Gp1f} z9*}j(MOp+B7JHs59T|4|GCv9bMB)wNNUxA(`@HN6WC_bx{w41|buur$;R)&QcqgED zbv@psn!{y{<~Cq>L8(b-gMq@~$dQV?Dcm^sF~FXz#}A0JpO)}qXRCiEFWPS}07wmc zUB%;r^U%3mK&cKExwHt9a(h-jp^*wtmE^M6S;fb0>Yi_VoN8URxHpKByWA}qVmwF5 zZ%py^xGAzt5XY6d8NW|9xSc8?>~t3?)!1@cm2k1VXAtj z{0uejA9#bfL#y%6_gZPaiLt3c=Wq}|#vG3cxb~F`vQP2L=aQfWR z=Yczepe-P^r)35U_M*`@Kb6+UDgO|QsaeH1OEPL>vBvGL9h9IVe}jQoZI6cl~xm3vnj8A|22K`PCg;# z%Kl#Zutx^1WO+Q|E8G$-Py1}9W!S%7N$-Yl{bSuGxt~C!Ya|)t_=3gMudYEGuyp%# zbbGf9?B$4MmUJbNh?P2f;R8I%WnTU;%y_cN(Y&Kyjtb0q8ueZMiMxBHCYFB{j=k)Y zt`M2{-lFsJwbsO#fKCX9hCyEFOvb)1ZX}aOf5N=bYP%kp=p1YXL8twtxoeN2&0y0R zPpzNC{qScP2z9EzMsxM)M*56QdyIsuKA-IJmqyGDgQ*rAB1n1x0O38qSLPP)NjUg~ zzCPj`vOj?pMvYQJ=lBZU9CG2KGjo<37#U{icq3o^9&agdMbfR%%1&A>6#V#7GX9Dz z!Wj!6dMqQBo-$B62(R82AYlLK&UEqen!gbI;i0qODBtZj-=S9yKOxNw^@1M+lzrQ$ z-S#f%6f{z+%|3CN0)5-^4*<4|wQkZyt4+Clr^Oe799;7FuBbruO#?}LlQ}*&{WRkC zN_8;Z(x-uI7FI`CU+1I7*Vm)G55gg%u3Y7=7KBRMcLiJHCq(`(BX7yUI@_U~&S`30(n0Iv%*dF)gZ2O!%F&mxA1$}Hq4tXq_SdB4C zNX!xzPNS993Zrt8KE6ahizBB}6=emU zu$>Zl%)y=LQ+S00`hANfCV>0t=y<2NyPXd<64aOe)|JI8V*9(-1nUhUO{Y~rv~eQv zBAyA-E=`T6?wQKhC4|7DxZ(+egwnVHsZ#r;=@hH5jHaGnWm0OZqT$UD4^Ffv+*-NAEpc z%WRjSma`l}(%9m>9obVm3LGYWsft^}%u%N?xU-tzn)Xg-+nUU&g(_YO{U*${NVY=B~>S$$)H^@IzID=-{4^%VD$Fg$3}qfhqM^!F#F^sX2zC5T*{ zKa=xUJt{CjZB~ZLi0mPw!)X0@TEDIrR7dupo0l{3*6-iEJp4d<_={yL>s_mg6=ueZ zwyj6srY{%jjJK=A%iT(R?r)UNgb(bl2uQ4KfNPX)>}&f7uOTbBsVvUHzB@>HQK6g^ z+3%iw4hr`@nXBxORP{ld-)A}OV85a4MiXF0bBqko>U0?-v3M5`=}syEzh^}5X#g%u z{9CbtKfjxoY*dJwwcF<~+_WFF$1PJbXN^IHCF~uYBuMK=^8BXvm)pLjl=8~CK6iKv2XW?Zq~H+{L`+W8d={3=W{YN&ArC~4 z`h6iUylkZH4owB$IUuGL;=b=ug|_y_t@k%k9~b=>WA$tMgPX)drg=Q%n4ZydTSV=K zB-0Xq_wkQq$6=r1f&oiMBoogw3G`6|ea-V7DXSr^uU&U{j2L@2qN@7rR?!YV5f}>8&o}dAhgoZt~4#=?vql?r*&h_0o{N61sPm?fYVut z4(?vV^Tkeok|~VwdXVxIV8E67^JzRh8|$z@1y?xJ3_R8W&V;};6lYP^Nza7bEcN1Q z&}h*Bf5;!_^bXSNnF0O4Zpl$+{MH?`kYpNfasr7Ewt)t?InC z-zL!XvLDm5_r}{##XZ*Y1zdIuHW*K=tla4A&+dhKef0)+UTcWy=KgHT-$R#-uxb+$ zZQq!u+n=6+3q?OMmS3I{)MWBsBaTANuKm*jK;n9iJ^L`qYEBJMflKo!GpFBSjv_Hw=qi!Y?0#EVxej0XP>^tSR6Z;j)>hkz) zFU;PUc&p6%7IuicrS&hRHKdd$HxTT6`L3u?nMK@6z%NzW&kQ-eOC!8#AD(?d0Sn=6 zIhMyKU`(0%Ep7saUG+}Pd3c0%)niu_(Y}{0*_3(T8L!S(>VU+bQ_~A-V-|RA+x$CO zZ5jhr9BQbo(u(sBBIBUz~UrkEzS6t|yf zE4(r#hO_F`H>gJLTMgKyHDdK_^tcAvL~gK9j^Vtk9l}7}*BZ{=ir-*e&DuRIS~}lP zmf1F0aD>D6I?FfK#%6dEXo26Nj+df6E%#$xZ>1+*>TCPof@Ku3-*13JqKc{GZYsQh3NdZK}#SA=m9#ktL*(+t=(IBDz#AB7Js_6b4X*1R5dzvL3ux zdl6*7fv@Uf)suIQ3$J^!5BY}LhMhw#$-?q|i=V@@%;yw*YHrD3SjcD(Xi^;rYmad@ zeE%apl-)jqa$>iIT95|-%DR_qo~lJz8QlmB;*funC!90#R)A%a7O=!_+C)EP@ARI3g01E0;-94USaTwoM%P6dg0Y`IHyD|bPh zk2FF~kqV5b%Mr2`WOHFYIP+4>X1N{Z`%|>xu#-MIkG<<9XAQSNzr>6!+)6&WDam~? zwgN-f8eQ7oA~t@up|fkLC=cNs`2gRah-Qz#byJPH_h&WgM28nU8&D z-G_+GcIDIkIh^VA;y8Qr%GAAmukbl!HCSbio8x2Z03?_vj|bTUTU-HA4$V$X|2TH` z1HuRHun#`Rr|C2W{G=}C#;OM{JxMyVW*kAe#Tn;iOcukn$ykcPJe_2)u?NAJc&{8V zAR@t(Zo_{2CLwoNT@$AL-Pr?J!rM@MDaz6cdekYK{Gq2Fa zGss2AwDB`Hs1!d@VRMstX0S+LyX++>a-%#LQm>y{teg&XWWcjt1mN}dfTc3NtA+n1 z3@eq(A8qAy;MO@r4fYm1t)sc-SnbBN9vp8K zdHvvM8ej^nUu-y;s&}vX4#Um$|%bdIK^x`CjIM27UI6F9v~F87 zdYCr9VzPSkv;MrY&WV{*UwY~cUqV?@@k?+Qxn!o6SiDDn^RaXppK~q2&ibTKIUKNG z8l8O4VaC}X?WZqVK>Cg3hY?og4mrOLNH6{7ocP&ElYg3>!lyCjcYU_ecsls@v&VcS z^|ss{xmVpg3LqgcT#de-;r@Ctc)iIWh>8V&>#XD?byhlKS{Rs?QaH*S938nJ!wqN}NbOeQv z>VgNg&rA|Vj*om-iRT+>T`)q^*~@6TotSjbdog#9gXKTEpV*O^m2kJRqe#-EbR=4?Sxi%wCvq zHCh!NgL9$3*F!~QiH~y+PSRb`lYH*?>-U82{i}k3ikaVn)wt^?&zg^Bs->o*cD0eu#fK0-6F9f z)@Ucfe{TyDgCBwpo`|Q|``VXED4lDyoPmogP7z7gO=Twjdg2*d5i@s&pxAga*7i&Q z#rqq+T+hpVW}NQM0&f@A=QJe7x#u2$@$h2Air79tfE?!8)`5gCo)92U%#nxsk)?Wb z?2dM5jufxg8vDKN;goc~@^8SMUe=#)tQ;d#r#IekFwF}-E`NE#CFi_Tqo|Y|@0-0} zZ(RTT=@4Mz0~%aO-OOUm!z!$VewGbiEYcUe#wg*I%$Ud}IM%?E^1NE_Pfp*5L)H)( zeBPKG5+|EYD%(K`6nkJw*6tY>LTebP+nH^Y!=kaU3{qKd>EUtE3R z*TuyO3f3fO(Q_{0vUnl^iN3tVG9yatg&k_SC>WU5hM?%w*GYC};yyx@QtXR3I(%6f zmSGfuy!u`AC?D=WYM^qD<7{jp)BVLz?4iEyFJQM~Jw(^m-$~mA(l!4J`TG?m zZ+zG1d48n3i>oGd9HNHs6Hp7;+2(NnvJ{Meq0H*&n4 zV{6W_HM6jl0m%=4LqqLpBO^4q#|4VzEn-~O7{Sa&uh&$`ro*9As)b~(H-rJuI)rj2 zbKhRRdLV^G6hKh6emU&s9wz9+m&=Q+$E7cFZ=H$`*?QXap?T&<8N6`K`}aQN3R9g_ zyZEG z^B$vM1L165R)_;|(;&o@S&z-r@Q#fe-cE7Gf6ux1I0*hsb;1`iyeXH3k_ipBbWrFrC5fJ;aJ`@`rWsyunrDQZhHm@y8wO?Ee&A#ou zz#%_}?d`t@mXyI%5@bN%_k%nN>4*Zi+ISTS+ytLasG?B$sK5n~)emmQMk!BV2=n`I z`ve+^q4+0qs(RbC_F*C9@(k+>lb|9-?l<#%@4Ds@E|@f@cuFeg9s;`DgXSgO-i31j zYWqHwX)JM90>hvtu!jYd;1TQ}^40iDohNl$@Nb(sXVJAdc+YasOM~$JkL`F9(rwgm zcv50Qd7O(Ve(#+SRj=5uzdR;sOUW7U;7^Lt;cF8M}3DcXD`V_s!N&F4@-!N?+nX%us&k+_dXKUX7sgJy?8rZ4KF< zV7!u0M$dsbIXfn(gtI%-d#r~%CmB}ba~Y35#umut;-Fn@e!iqIpIC^>Gb`(|CmZUL zdv0lCn>amcns^^i)lp-ns5BC zrQDm^0eqp~_t=zPa$TsY^Y2o0DBhFfPBU`liq_f`a=`-acF{xcUf$ah7i{opwKXn3 zA&}sik@(6Bl*015pBIRR{N;hmqZP#?7%q=+rhX-i06%f#`aUo6`Q~?Rf8rX>ha`)lY$^GYn^&@awJ^S4`Olef#%{WNn+i2;c`#~?fLSW6 za(m@z8=$MWkD-nQ_&P`0yGhvh*jt}#z@`q93#81Qio;?aU(#f0obk4>3{5@qlFWNv zTEPUa(YNs;ygdRYdDH;K2k0{p=9`U{@Nme0hO{Kx1T*h>ht1l2 z7r+u7Env=3RMAkx9ma}8n{(J=`AT0$_3CRJ8t?O}?-AY;wbzwx-FLI#6|p+T`Of;c zM>VZ>@Nl3lSk<|j$FE4LdHu&cb5nrZ6ex6Z&0F6$SA)!*lt~#PXmt3ArIkOsi(l-w zY+&XC8Gpbp`SeiDq>kdFw&aHj1MH3O&Sx1=rN@|T>!Ey+uYI^ub>oHB1S6xaR;3|d zhqxFNEUEThzn=N@&SSin9$3QdlRyRQ`Vx5njl}d1Pi|0WmEeVSmh_u1pM5;wbSUrc zM>GOb+Pp}kPv4}%F3{-n=D7Oq3;N!lEGmKx-4HqNG?ZG;f7?0sKfU_El&yY+mRPZv{_ASD2$Fq$aJ0tB6f zZEE2LSpe9@U?cnk3IQ9(Gm~ zj2+r1SUNTH`xrq4CUsAewn&`#`%Fkr6l3vePnz~<7t0c9t`Znyn-~vTgn&Wem!De+ zVpS<3C7^s_n0mp0?>r{cf%UvAGJ+%|q?fz;e#(_%E1Z2UAMcL?CC|;i@_U=qf*)F_ z{X6Y_#Fg)}o>!;Vv?u_~4=>tF_m(Z1p7`57fJ@G%YQC4sDQhk-I(6_Vn)g?Ppv?dX zx+e(xeP}-Jhm2r4dnpq!a4}a1h)|^c4#zV*4ED7NzPW#u4@ipHvwAMcKz*j<>k$6w z;o?J;G3G3ypNs1r_fr#AefnO$&tvr!;IZ0s8Ed8QaS#3q%N*BdpRG`P%O~MA(Saou zDMYF-;oE^}M=9@1nPRA-`9s)L0f^8dZ5#}2|DDK-<^hasU?<88cUo|atV&1gdQGZe zI%j{j;=pTsF3Njj;8|tQmv7o`Gp+5>g$B=h_LLOGoh9z^`6z9r(abuJ9ywO`ozai!H4SZ$b~-Py~JFB)UPE!MPY0V@Z;QuEd6SK5ciU((q7lU+1( zwi+OelWxQ#;q4V-;g$A-6@v4EQhIEN87DFRE&!BytVMfy3$NW8f?|{Q8yoo1=cN!t z@K@kql4fLFP8(l)+w{@@zACbd_K1s9nr{q}qI&NOi5IUG8HZPkb>6kD2oM&F7bj1p z2@EI;nM5Yq*=ZX5_q@yPv_eLt+yncoU+~uK2TmsG`&yE|_zr=`+I+PhX)$jU?Gw_r z6$#^cv%@V_og9sk?!?2%^pI-tqCGOrRXC-?7weMAL*0}Pghn>>Ep2l3S$&DKbb3j+ zxiGvtm#RO%mZs(E(uWAwpFTsIErw38v4>4=yMULbzZ|!ge%s-jlhb?l`ip-+sq@Bk zkLPo0{^E=B5Tl$2Q&%X%c)|gpY78M=9AX2wKpo$?e>+I&FR*JR^N1>8&e!vPPH8Io zurXz{VY%JiWp8xeQ}B1zizOegZ$Yq?+B_kvFpRppcWj!3cxOr3@#Hd&7dHDCS7N~^ z%x;EkI#S%x^G-1Y(KP^4{&0-sPrKYaQC) zV(S2x4d56jdp>4{&&-~;%KS-=l06(JZ%)(7(+5I2*Swq$mDQ^^`c}oXYrbRlZC-B^ zc4P+k^o+Q65|Ad7CKEyakWoFSoD+x{e5u$S!f4}}lx*Ma+g1@VsLMOKLNN2G*?c7? z;W!+_7YZBeK8PKYgyLN8a}D3F=D}$V-|;;fhYl(d?pA=VlnQ(;kM`NG3hB&@juITh z?g(kA&5)7dsTr?nig$G()KvOVIo3oluGO2!y)zth&i97KiiTjRv&cf}NA>!33ssK4 z&{wYYj`ih~0mu!e@}6zD@BzDQD!C_qEff7q{^RUP>?Z4NkbppCRj2-A;A8xK%i=~| zyA^IFn6GM1I%k;FfA8WAnMLVThp@eBqid#V`zk|sAr=m0%J&$5bP+Di#1z>8r~;hv z^OdoQ-D}!R`}ux6ox}r8y2|zY>xluXE(9}|w~x-jJH9*C6v2SpPQVg|F1Ujprtt>^ zJ9Piyu33%K!TzMWu3xxeKB9fxE52xe(#=Zud&p8OG&?K)u0msQ4~@#oyE@O}s=E}r zg#`BUSsG+=EA6dpUSWE0Mf}X)T|mw9Ui4c%>nYVXxq~4>>#p|)vo6CdxAu|G=mjGt z&=V>+Yj~m*MS6j>lfr86fi8at|ApUmpS$1${Y^jV)EtuUoWsToTa%I|M9{Vt=VbeY zh!xAsv!-Y}#&=mmM})=Tw^xXl29dp3x4f$&VU>HI-Jq%^5M>KC%5(T-6e7P582-kO zrtpU+6Ze5>@3ta*ZjLH^NVGK~p!`-@^ZuK;2oPwep=t5!;qwE9FHm7a@yg~ z0dHQg;pVtjd0f8nrp{8%Y<`4}r;V#he%YoZ!u#1h2V}`&dy*2xSzyfyt?SSz!sQyhS z2cLZn(BF#ca1DfPGaRl+`kRuUNmq~cx^GTW)uOMp;JN+j&|YKA0V7M#tMqt+>_ZTO z-V25yANN3l%-18u;t6*N8M-|?ujaM)N)(p*kAg)7bT#a&eAG)o3kFBz+Vcak^l$i3 z^|kgT+P}g|<_h#ate*EF^8(K`NBIQFtY&6^n|St}L5R=c=kN>v>Z0IQ2ZExf{dPQm zdGK>4A}k=4<=v=?Wr(~7@nLUzf!Gt~VEGP6e z19cr6HYz(EK(8N)&7%5|E&`S+wniQf~OzG(1k`CVvO+C!SZ)6U8f z=!VzZErR3R<>sRHU{t=PG4zny)v_>>Y!9GPyZ-##uRvr>|5+Z=W3eBAX^#;~J&o-h zxNL-(^XYRrOZl`9udl)cnz?+!CFnafTz*Jzr2?<^)7-pcjB$s zd%)WZ*sH)KB3z7$!yH`<+j#%UNZJXw7~!96j0JP^zDiHwy4n|cTG$;09Wg&N`316nN1TJ#owVZ1&J${ zIAuqo5B9pi-beJW?b-*qy~fHuK*?VT@d8W9-5==kn`NSO4uph!xxgiM;L&N~B{n!? z(OZE&+^Dx48Ep0Wn=RaW`(%4a;ys`IsUo@c&`EATp>BY0>a(}${wSuZ^c8}e#>2BJ zhc*ht)6%ywAU74Sti-Ji8_pN?j>Qc^qrH3Ul0F7nRY6Bo1;#K56A~66@sL77g{Z$J^4U+xNhq(1swP!aQ};(Ow8wVMJpI z!t41v-=Pc!r4T44pA)7yOmgq6UuK^Y-cWg*K(CU|r2(Kv@_bV40q2xisHn;ClUMNg+nt6GcrP=%~YAhwp7sOu57uqm)A3pJe&ON`9TCMqkwpH8et>9g zB+xAJt3077zc;y4<*|cy9g~o_m)bFk;`KD~&zL_8-7?$CZx0U!0BX9=5dMNc2+;lO zsqluf`wx42k0rT2hY~4!?#xsJ37Q=B8_dBdxhheL7Y8)dYSNIIB*Dphc)f5mUia*h z!#BIr-ph#;JwD|j@?Hj7TC&f8u5U)oBzOKdJPwVIW2O^oqBPRnuX=f?bzn9e2Yn@g za?O3Ffo2p=()nI|nsx@qKZ8r^n*1>j!Px(TxO_KpRi!CIfhmH2nf!w99PvJH$ZQe} zI-l09k2|a%w$AMLEZ4loFn1bk^Cp(j%Qyk+1~R3PPJMDqG)SynmIp0wrrkkAaTVM{ ztP5b!&~1G=&NuTd-u#96On&%4#U5O>A8PBa4~OK$0@1c!KFMEoyD@UzTzkW~wQ+w- zCfxyxZT5}dIV2x>ZV>8qLs+lr6Qe+<6y6uvjgU8T{?(y4`~@04WqCnRa{GX8B}XX@ z%A`}iQhZbBdg9z~0LMJ$VAHWyoD7H=VY`$iT*QI+oqr(N@pV03Ypj8q+j@?K%)Vh^ z!#yF)i7ixUaX=Lrd$~vODyzM37}VpdX6&4p#8*Q-leEixZ%Pg+?WjD2SGVYUuSWir z+;3mJVZ$0S^JC#g$^x{XB)%Enh5h3C8)s4SyA(P7Cf>ry=4Z*Szx$a*qVW7YN%=LB zr<959!B*bHM`-qu@_2RmztpAWUnbQgm)|*|t9r4nSQLtRMLH=~2%mXW15eVdb%K_EelcIhnv|Or59t zU_mU(EMKFX_{fa~)i3(FpWcuyEcvX7smQDk+j@}12zjzNmf8!PA)sjLJ%qBZJc z|ED;A(hfo$W17&Er(jB8G~z1a)U03H1}|MF z8ZtFGn5)kQFno27a7|K}Wa(D8N?nq7ymI{XXr3(5#PR1dy;5>BOeh4hd7?k>@D67l zr4n4&aV}BLa{t2hy~RAlj>;?O8g@c*AAf6-PTBODEoLb7C(KU@{t~lL#4z*mj3XWm zL0go`d3|(Tod;~vuKFT>xcqCJ&!3_c?+=yzGjWMyuD@X4i^Ye@nLu02r22Yzu( zj>M>T56F~lPzR=~=X4z-#pG&P+lYgeeG~2eaE9jnfng53vR{A%#I&77kU+|g2k#n; z-Z6xJXkXY>aCz#H8#4txLt7#XdaEN24qIsO*Rs7!3KkDNbxU-G-z!@G+%Yv?dn8iV!j%UQm&s7p#eX z&?KHlz9N3S3@Ff#Y+#`-X_`x-Y6He_N$W-TSH z|1sP4AhYgmpJN9pCuSLYoUbbzu}Ah9=x8YFOEV-M~QchZj=v4 z&e~L;JO#!D!NrN4bji~?J^ss~Zk{Rn`h=8xl~FG}wRz{JI2XW}tU#J2czMP>)KR_b z@c}pl$y{zPaaZGNy+|Q_80=% znO7XV^qKYjp%lpyJb!DTQ@(sfIKcBA zzh7M8XG=l}0yE@3!&X^=064;u<3~R4vt*@L1PR*Eov{@nZ~Pz3>^|IeNMb$%V-ya# zsp}l^acYZKat8Rxk|&2=M?w42i~D>#A4GIRDB*l}TpwHj8We$b`ml@6zp5o@KjdaD z>tc5!X>Zx}Gro8)Sw)|?WO;Yxs9IzYTXnS|{k@=v#%bwqr;I!>0iD@>580pn~~$#XXYWFK|*@{s#N&`6K7@X{mq(d~hV3?tZ4Tm8b%6OA)=B z^8&&>>2#Lhk3I%a>B;WL#2;LI^$q8)QBf=uFlOiADcCQsC*2KIbsfa3A6ee}n%_$m zU2-Fi-S_!tE}p0J=4lu9YNH8v_b&8QKc%}Pm9lPODu=L3mc-J7Q4Cw;keJ(=IEUm~ zMQ;FM1fN(J^DcJh5Z}GRRtn6$tBaqa5t(r-A5*Asp7P=x0hY@4M2swy0FPQtM*FCq zVp?IK2AvjcX75Azj~yia@_TYw3l27gcVy_UIL4Q$>gmdJAizO2qKEsJJ1;GkHe&j4 zt!*qGjr(^gj>jup;IFJ)^)#ilqtC;(B-&y*Z~pSmGynbWmq}3%YSPFs!)16E8dCL! zfgh;?3S&CG_ehCgtaRk4S5RBlmfsgLw=gF39R zdn0I$4;XVc-cdIK6?W6pPhB>l(>uwNg9aqEN8DPboMOnQJb>+G(w5)cF9V~Ie0a;Z z%l)$5OIGN{m^XQ?Q1rt`H(`Q3b;dsbtFOTjKhU5~&nb!T>#M=O=ryr-P3;C+Rp_(7 zKIJCl;p(_{Pf4h})!TN`J}L`Xn|{3%NzCj&xWoBMv#e0CrdP}^y{baMx#1u8F2Pd1 zrSij1+gw&`7eP5bLpW^TkHS~42x)Lp0FtB@E^DlHqY2WR?E@VyA^~0WN*0vhOP&um zz_%t79f0>fhh@dr8H;h*Rut|EJ{g6j~{+b9)IrTCFyJ;El$X-&t=p`;hcdy7rqmgQ_MM=Kg%XJeHx#0wR_B`jjmL zrZMUC!;XYJgDVCZt3kOQs_g!JeDKk8-iBZNhO81-Gu+{{cLN1-hB(FLN(o3@5AS_4 zP;Y?C7u$R8kcxok*^h3KK7)1TaowY=yA8Se1>R0o*yrwY{j|4!5r`|VhbM`3&pcKp z8lU=ZBYEqi7PNdzQRb-+wAf-l17@XJ51#JrtZx$$;+9Gg$#teH zQcdj426g9@dFh_227qR1{ljN)iR6zESqs0~8Dbe0!4H(V65#h=eq*)AKQq25x<@`w z7fkTH)(oS_P^4ixH9W=3sO~LU+Q)zVoqbiq6Hk8vKJR<{O2*Ly(g8%03KM0ZmQUUtSG0@JmgwR~-kL*#rW6RsQe zM%-3uuL!$eT$?Z&xgaUhn zn1cq_NXz$IyDKh0KQRXi>^!^Hs}hPDiXn?`yvNm(38)(6%%S_WzR!vHHMva!O7(_o z7QW*Ko!#5PCMAhtOucqkIh-88ERV^1p)ih5?9+30&pN5OUjOhc`%+a~2B;Q%B;$g^XTW7#5`;v#5+j(q+eAjJ4aDf$5?0&MMA&HIL5+IRb@E+PaI{+8Li! z4VvSL12TjiKUP(Gp%^R5mQqH-mTOj>`Lkr6-H+t8^0`ix*R7G5=lFM@wJ$4qoO*)7 zZeu;L&;?um_C*Y+SvM8ZriJzVvi7fm&wZnvq0IOOW#se%1ig>c&uxToRa>-A(Lg%OsT{>7>9hNU|8Dh^@6vYvVceLg>GpBH_{s2htBk>DZ4b!a+ER(ja<(h)`@-vK@b?B?!XA(Dup;0+qD%@w-fDX}bH~~0zE7sZA zm;MiL5w4p~qk&70)A3uX6HMj~=PFC0fc?<@K^kM`2N3=q=msoZnd3vYV`RnCqOUnD zlyDRfmoTSlKkj?G3J&ZQ_l=>%2OB9Y*Wb-U3{M!#_3eEq<%jeqXXQjx^tOnldzfp$ zw16v=p_0&ZL|vd_AGzoA^^X21ap%{tJYEdVTC3d8FRTSMIy0S@9;Hm+MtNAUqRZ(% zbm2>HfT3Ul-tO7{d=)WrlIda1k0PyS*=K^l!pcEq#Q2i(D#TVB!EDo>T_VMt9 zEYSDV4hsn-3j;vsDROUI054hB z45nU%Q^+^3SJc%{8D_!1P2kziLVAjeaMWS?h*LuY-z*+^7#VjcRfHj}q*H zG!n$7y7lF!vii;M8au!0);=w)5bTFJ}@ur6GLwp2xsLigQ zsJs=P3VF!-s`PDsJ4)d#&rG|~iczyGtWqy>aiX~*p2>^ds$Y1I9bExlMC={j)ORX9 zP3b-dnlQr2JHTcSi7czFLhf%CPd#KrBRSm$J^@PLN-|;xX^MFid>KfyoPcCsQ${%& zoP^@b%(^E)_X{CIFsx0LgG|HK43?CiPp7-fGE-e%4(b#ds!$%#)2@WXo?TU?Nv`DU z+T0Qn*3FEUYCC*(mgDTAn z(l>JW9`b!CBHqNIUo@O98GjTC=%Croe&J*4RT1(@22w*aOLCaIt9^3T_t6LF4dor@ z*O6xDUw+4PBmaEvwD(Ie=cxJ#zlk%n?D1MVYIijmks#Aj=b+sl zj*CZuqqX!jII$2!=2H6}sLnN16kxlG0?~ZUx)&u2R3pAV*CkC@hV*NJXEA+tvYQ;b zm3s=+Z?vHgfb)J3A=zb2PCFtaAHh59T#`HZZ#$H?nEV~Dr;Oc~co3CH%GUkMFw>ⅆsr-9H&b_0?%0@_kl?cr13^e`!qYO&L#|pCV{nb7U)bqpnTb zVMvttd6%cxOswp)M@=pVFA(mxiF?)|yZBsyd!dOiyD>14M8Ef7MyX%D10(x=2BFYS z^|3T_%D6jTzI%;n7Bux$5*Z=dN<|D!G-^)W#Qjdnsv&tV*%JRTR9;Wx=Vu`Z9}QZQ zIvA!Rp4Iel+sa9}n8XU&g#>l!pTf=Me zt}3;!4*ScY=@0ztH&FbBh3+R~Ls1qU3~gK}k)C09uebZGlvjRi;IZ-civ!2XZoZ1P z4$~);^u$7g4AT_)Yh;YDv`ym%-1gUfS5KyTAwdHj3y7}nik$m ze=ku3`D7c)DzhF-6r|=Ne8ud1qkYhm8l)%T%TgV>frBMQ_WO^d>)K9K4Wq9F(k}%; z0V^Hv=!ouoF-xzZjvS$#9j#N}%YI z+zy#h`<#4c72e@!9P3=vz})#J4154?Ys&D!TTy<3G%rdUo2p!zKNR5f+(*M6c}40} zf2EhcRtufz8evLMu2WB$Xr3bP(`~r@cvX(=36_DR{I|!02=nAkj4B0i3XELkMe4O{ z9NxT}dS9Lo5?H*(l}G2>^K<-brTn3m%>lRqyd0*oxYRvQT&3H!jvb+?olNOC|j+elPLenWO%md5#Q zXM+ML=y_NY3yh3FayW51mbWq?s#d~4W~e@y=r{4DM45S==KZFQUqCRQR|9={{qEga zpsq@@F8}yXsN8&U3oBKQK0JtW9CfowADk#oS z6Cq!BUvd%Ja;xAJcFKG>7M3=;6xS$TegB@N;&KU;PvCPi0CZLmf|a0p?WTso>-MN8 zWp>`TfmFMdbw+IF!`3;2J=n0k&&~BrJK_6@`dIVrXNv>xh#KEa8We^vpsWu`1}@l;_i# zIyCM3Lq?8MkLe~l3|1D=I|9L9>MfW=_iiNX;As?u14VW9(mv}`izzBoC=EDli_Dz~1?M}-&<9PsH^!JEO#l7b-cfMa%M4%f_?uVL=#<*`)Ve{ms z_ezvcOnmO95g^?3@PiM{x616RA^6qx?WRcZ!2g^qoh$75Je zZ{dFb&a_Lc@At#aTS-NQ@P!6FKS7oWM|u#`HMx(|R2s{`M)%^|%p&QavTU7i5aZIr zpvW0U{cN*$6?nrU#QCe%hv~2pK8V>hYZkDgHX1fazSiYYeYA+;M#K(}-)TEw;T~(2 z@(!;AL93ey8F~{sd=EilJnBbWfY?&p@yGnp)Lw=2X6XabpU1bK9zNy?FW}BcJVES5 z_=sv42EjRk;oz@_&7upbSiGV?+3I9_#CZPBOCQw7+hLsW8mpBgmTNmPSVmf*Cr=#0{V+V4*A7GolMNe8I;og-AFRXRZF?0e`7-Mx>-u;spsEmkBx&e_O#svep@mP6h6x8{w* z{Oj#+9v!)XrY#57nDB0e6VWRo^H-zv+Q#y;d%bq9_GDdOj5(HhxmkaLNqRPf>357> zDCm|MD9=2a9gFqdYjE%JfTyQ;;rqtCS-tpjQZ4Vxv{27!P-dT_s=LHY6?-w3KQp_T zgqYQbE9*3@9|5b#Had*Jg2`p1JqH~NoYB0YtEfR*1 z{7uGr>4iRy3 zHUP9OIsRPi7+mx93Y_&Gh=&}EMlUYY#)B~N0Yb-Ly`>ncg$JPO-(gkxW6j7jp}FJ4 zpluHAyDUpTh^|J$z z?%L@W@2jeyUsH42OO6MuRrrQ4YTR$qhuiIt&KN4cI{u9#-`M7tHv}GtLInPJ9k_d^ ztD&&k$Q08aC?Xc*=?llcwZ`@ev4U*ua;AV+bO$;RoeyXWM-IyUcUan=$qKVWWO(N{ zs8@7RgHLWkuaH72c2Vc*tV$!cCkD|=FQ3hnwtFi9Y!#=uJq~zhQsPd%#tVZOs@^;OD;s)mPAk1^K&#b9?v`+odx2yUkPbo>X<(aw$ zh=@elmuz(vS2&KP5W5k$RyZwWo?ZVy!whUwwUDzP1y4gDwBMIhSS<8=7AnHB@h2d& zV*=)$8FFjo#-T5OX`LSufUvoIZ@3O$N z5cS9^VxK1z4folqP<)i^%a#S(J|DQQ9XKOG_D6;zP%}eGSZ0`WVgaOpJNNsZ=yiZ9 zW4=#YGw3?087(vdpEvhaIl=F!6VvAMOLA^vPJUi6$^O(qeTS0yAC$DE7h2r@b;g)P zJMKhDe?BLdbtep>b9OrSiktJOKc_X#tV)L8ZqE+0am|GN6KiwNfxuT>=N-Rb6K-MKR>{zS1PE(gY%6;^U@iz3Ku zqV{K`p%cQHy5ES19rw{?J|9I5jWc}**(qmZxjotJqqdEL>uwGF?(}^j`w;i@I~17j zEhLoLqnfRpEIZ@-y6-<3{J6jOHgw|GQ+ZEE8(aSa?jKhHp7fSkDyVN58D_>1ORIIN z&R@e!^jQ0KsKp^P1lQVcRZ32=0*W51)?o=Dgp_13#?NqO(tP7VeOu z4dI7F`0LWr58$u7?DInQ@m=ti^Zl{5X(w;Op+#H$d)suNTMQERqJg+2K&g}yc6CU$ za2mCdDjbIczH<6vj{tru<39D_nZKWPUw3(;~~QMqGH%0L)L|MK^m4z2=-hhrVW$wfvgadhA@7 z#zJib}Ib_7*)b*{W0>aq4qzRTEi!)@Bz1CZx%>VPFQ&7&)@JV=> zCj)L_$>*$BdRyfB#hrfg(j05wc*@vpw8!PXQL}P0ZPF1(rmtV?wA-+CD zXgn%q(mnOWT$b1EnGSn64rKz0u&)W(^Y&h}W>H!f6km9bUjWnV^I-SuJ_n_)m&vU; z9;-*!)5bs^#_KVH^7h>cYU!&bsoP|PmX?|U$)H2#5Et%!o$FlNmk_>-Ntipco+Kup zP_p-ZEDF!BVP{V$_7~i$H9mRlVUGRQ^bXaVGJ?YXKKrH8oy(ozb(oyUk|JH`>ZwpD z1`1{u>A|&!nm}>Pjn`5sYf*%&_2MtBS-QO^K#70XL{*|M9Chf|px(hKzC{g@rMnPf zeHdDQ5WUH3pvVy>LvofUSZvGf@7lr@y#7LJBfhNg-+G;{+0Ed=x zBGTQX&2SPuFX0(UeB)hD@YCT(VK5WZk$@_iKWS3+uy^|z=3$grC<&8y5`?um<{aWE z=81c;a5S8)z25K`#0zO8zwnM-PNaeAG^&nLMh3#zx8i%#wr9hn$b8V$@}W&)Lx^~R zT3u#evVC{A4*`>L&EwGNZJVK!!`8XN-efwa-2fX#2jw33-R|ON%D|m98Nciv1W=UFz64L=9I=7qG{4S-HK`ckKeh<%BLtMFdUdBWA^Lv{#l$2|_7ShdJZdoMC7 zCF{3sq{5MAzpIB<2GVl7hh7-ljk+}wmr&FmD*A^XHIXy*0rn-dp=Q$-``&Pf+)pL@ zr#E>e8s1cHCwjX^%^vZj%um@vIkj*zkDczl#2QLZ+1TgB>3W7W9c|p>xdVWxOWGUh z*ZoH0y=r3{C&*`;>omBRRvA4N8br!`#;3eNvn$U^;NCxYR#BGOD&EdB<$yF--2ZvDTYX_#<4|~uV zD3R#xPLSdTc9CHsyc3@mHecCs4dA4{kj89Wu1o$ZygqAf94uHlr;N4eEPktD`h0`% zK*sK^>?ZCMxBweTeGHX7nv>k|p?;3*A6%M%SY*M)=c*s>uaj}zU}m6J9QcgCkJK{C zKEUBK_d}0F8%Buhn}zhwhajA)+|iVqc&}3aNt2MCOwfX`-ti?tno=4uqTkyG1;y$Z zS`-B==sh;^ag>#Qn{gbOgl4{-pcsMT)huxlbhuO(;im16^@HAYLvYTEgtyP-k{|gg zP0z7aoglnxO?j>DGTO}-0*=EEuLoYUbno`1+Qpr6qca)Pi&1J5$>b-64``xqNS6QL z8+dih+rguy2A%%8w0lq?F#?N(jxfE~_rAc*%v>w1{dnaCU`|>aqa@JE1L4?X9#P?P zSjp{o8}DclCwFSFl#ugtZt}Q!uNZt@^*t!w9N>iW_?)XhS+&JO2~`I9?hz*SlA&0H zqpQtBc$tU&P55G(4D($aCH(I-tl(_p`78Sxb{45at0j7v{nV4C>;o9B*6_ZAj~0sW z(KJ{tX?70p1$?7N=t=tgfy{xwgL+i5ziLe*%^S>1>Et&;CldT>9G?cPL-ltBX8@E# z_LtfCZ{yhF$OzDf1^797aFZuHVkV*p0a<+yv;u z6}1ty>z`E9{CP&7Uj&f*IaErqZD!cnH?WuTm+~?HC3V&oV>?ahw$5LHMLTwFzI(5z zV#a`0xCm!Scj~{)K9nB{^o2Pp;^9o7|Lr~ME79SMizUteIuDA-YF64``2rsvK1cY8 zfZbguU-C)Xq-szPMZ53I4KE}qB}g@XzG%=sI6?*AV1LRH+OvBu@rQUy?aQP&IF*R6Abuo6V!yL*nH)22y65|Fiq9SDHe{?U+$p ztUkXyEl!pZp6Z*0&KkNYnH@YwlsJBJ%w+Ty+jj#w0w^|OPuNozOVaTNZM$y1vYfyY zyK9L!2ZIiU8}Ov#TPKS8rnu|US4^O!-3Id3;j$St51gJJOR6BgZa#C2Hq01sX9d8@ zv3)6f)Ex6)7^rl^)0|$@K9Jb@toO?6LW|oq9c|FFVQa8@>_uO48_t%Rp$2a8+nRNB}xcBQ3x!w2A6YSox_`UhLF%(n}f`^6%VRIZw zTzReZ&#xImAPnsa>*}FHN>m+_PPdmZ{=4$~}{+vIb=y3XhWk;Q#_NQ-VAu0=jSyKTO?%xJfS8mOG`(fcPfh&S1P$Njp zk{qCbhf5TvS9?F~LCrgLb(ssEVICJR7!Re%>ypto$Xh5EL25t49xoJ67%Q5@IRo$6 zPD}A-aV@$VyG@t~L2Dpz!LOg+$?3YUvOk#q9Y=*IYMU+~4zAwq$PORPl_uM&S@!D@ z<8pA+Y0kJDd)W4Vd7O6*FWGo_&Ep*fPE`5xPkVU_+cff7akD3r|6RCreP2|rwu!@&l0xWhWB%mJh`_AGOL!V%STx-q0b z1T7xF%9}81p5D`oUl3pP{zkS%X+t)~c*BcCugAxMXHHP|%oR17@a#orfI9+AA2`yo z8zmcc^NAEv92`W2`2O}-iDfLYfs6-?AC~?CW6o59!RW6|d*vSOvn0Qsv{B?mVf`t$ zbUaIbRDVgH!6n-Klhr;Q9Ti?E1cZJS2r`Un>Y;zGdUst3HK5p!`$ZxmoX^`s4`VAI z)4V^D;qu#Ho?zs|weW}KeP=E}#Nc#3R3WTb`-FORPY;f*+OOa5P9#vO>4Amjitjx* z6Uy;<@{RpA9k%_G^x_Rbv-+o`jR~B}_4TEG``sKarUKtj>B>1Ax)xw95iARWlLslX zE%2mfk|;Ko_dx%e`OwSThHAcf``{~Kj%GMLEInYOb=sD|NuUgt>H$!bD#zTj23!aKj;qd^K}v31g}nREi&vkgjt zE{oRwvx2yk-RXNQK+)wlBH0daSC*J)j<@i@oih1xfO6CEwe(@GWEqy1ln!b6=?DyG z>~(+T3k%w>#w)kuTX6(h<4yQ(z(H)^b53G^J{HB&e04slzLOr9extq)-X2hya$WBa zRsPeLm>SsBl`PwA&u5d1q6r3lt8s#D<_alzp+X<8JjFwI`#^v80?hvi*tM5YYmU)Woo-|F>wKJ1sf`0Y(MJ`kfKl?kYt6B-eoxL!=s z8Lsb9QjYMi`A$6-%KX!&T801}KKpLd9ym4M_mkynaos~E*Z5&3#IN^gi2KH=~EFNC3<|8;JZ-LeAbz9R!Hh*>`G#gIlfN(n+Lcm$q~BCPW`J zy%V{m=-2~kfK*(UTE;TQ5TU=o+f~KXcxz{@lLkO?qbLV^{ zGhH}qpZ2!ZB_NNNlX^N#6ZMvA5M_alyt?n9XlC0|T||dUB-uPaeIAC@p)^6QF+IKu zAMnIt$DyLzcM&g$?uR!`NRR9W(6JG(n>N*Pwnh)to~hd@-owTakviv+QDN(LTHm7a zV$W}$r|lMpIe8isNJVMevlZ<;M*6L18(4CPM?PTFm^C0IhyEiBT++h-UM0NeP_dt# zujRg(yPH0iy#AoUa*L^CU(1HmL)c@b^$YV%KZDe3nUGY?c2{NC$WBF&V%#hWK>xt3 z>Q09Yh)F3yUYQWTQ;yMd8@lzi8s!p-8Tx?bTM2=uK`qAuUq7;D?a2wXv zm@_oTR6#eJNV%605%S2CnHPb|8x(p6sHfWm_qJAc#-Ppt`30@y)nK(Q72-5C)1+&~ z1_q(ANE&%+xvyi+>11Z$7bR1A7B;~?=w(Zs`SMQ@nP(}#J!E*Xu|~xlb8@xL(DrJd zUG>T_Jw;C^qd(;xYMV>%C!oRv&5b}t@$)6YLAZ^|$7EirZqF}zXKUd(e)RScT0`@y z@C56fmQJ;dfP4)ds4f*B^y7+E4LHy_lFN>`abFPX%>HTLMkGb@;A_iDO)Q{Ogq)~%I zUGoW7N}N>n?bGNSrv*A7XYpDm+(p0hup~|1j!% z5t1TF^xNv}Dk_SmWzrcoY5Q%rlj@XxZ6`V_$7MD`VS!#9cx7}i(x}w^c7akQ9%Gi` zy7N^wem>=gi|B)82cz9T*H0%t%j!+}PCviEk}96(lk9W1rMed~)0!`P-z}ws;Z*|+ z9+K%r5w*1smL%tUF9aR%hb6e44^-9|LI*vGw{1iJfSw;DeL&T1Aq7(1HH1WsaOkmC zpE`LZAN%vcm&kM0GM4XsZl*c3KOPBg8cx~of9;Z-UV!lHz+jQN2vrIw-QkbVJzzub zd8%6r-7dVcH3i>y#8JC9ld2}tt)Zjq`PopbdUz(Ee08ODvW~y|KCbicm${b;bq z@*Y3f#}Y!L?Twkcr|pE{L~flN%f}9y74tV5Ocu$^qaE}r+fwqMci=4N2sFXKOAm%7DpGCQu%vyu#Bc)wiN{1gaA_{f0PQ&IR|Zw zUK8g^az#vUPvD_4+v%JexgfF4u!FF~bIM zIA5jxPD_#(S)6-2GT}{VyF2lXm)+fDuRH!^T&EH~uE*EDEQ#R2VoBcDnr7>0C-TD& zRm3S`xa3l5a``CZL_`5QwijI4`=eP$5F6e7+L>EC`_LiEo>}#3QF1UC90o9zoPg4L z=9)K4;!k2so*j*Nc=4Yv!nJ@ZYkC`9bWp^G^_c^?lG@={=5fdFSE6&T8*EaEt_!H< zt{R+`AdhNta%M9xu#}47*uih@0ct=9JxDeux5s>X^69g3Uz4!hP6(itH`&~zL!XBr zp4?UI27El(()QY==+RalN_Fomv3~PE!SJy{3Zr-jtszUr269H+!<9)ZMQMGq`yPFo z+zx!$QijCFliaxQWtQwx?5R2@K7MLz{W!hXeJ*KeZ5n*#%I+)Ei1)(o{*w8_yRk8` zLc8?PR7P9+Hu!2QOIzGN3^o%U+=H9-r;I` z%%(d`P~iz%JI2`?CIbvt==J6E@~wqNlt**g^y`aq=zw(65`3A{AtX^zJsJ5BfWWF?K~@_og{9%C-2m}ewV-v zQN?-IVb9&aP?BGu#u0W$ksw%wu59LgvZlMH%O8@ub$N8A2ZzVH>zdrmXg>HGvh0e1 zOO2xVc<;R_8rCA!J~il@3)VNg*OCmZ{;q6f&uGpOMO`#kH>D8PI{QR`!jOZXaq8`R zpo(is9FKPFNZX79t! z8OIzbvvJH4Ef%3m)0f=Tpan#4&T%zrpE*~^{Ra*j0zwaYP+r+&-CNnC^XZR9%~bH? z1_5a$Nq(Q%#H$2QoqyyuRFM*HTSRyoZ(FD5r&p)$OmwB0KdhmHW|*eI;@_Sb3b}Da z&qfP1nOk06TAVae;ZU?MwsG2Kf}BNGXPI?>)x7KW(!~+k?%^hCf)J2yu?Oo%|1Gm4byN1Hs<>tsNLsEQD6cGP@FByDKRU4p zFYtc=>m6@O6ldO=AKx(~976-b!e8PJn$%vYDZnz-?|b^4dv+wDmbiYfNyxyp`{-km z)oq$i5y-M-EPvkT;|oA>r{@RQEqd%{j;16O_Pdd2tx(Ri@W<0tR%a2=d(sYtm+;ZX zMvW7nvV$|wPd;*)K=?Ah->i|vMq#WdDC-g|2zH0(PolJxBKjL!$*MEHyx2KD;n~N5 zFJLGX4ULTRwpt%Y49`MU!@KZz#q6T0i`=G)G1dL&@3D>Q&C*&Jo6AGTrmv zMMe@)3C#;)`_GJ`SN>R`3o@Nrw&VmxOzgu-#Ncjzdoh9csO5?)Q|i>|m)wfjweNeR z@iOv#t{Yz4!|9}b^T1n&e1~6g_IWSuGAFR@E`FAz3q*_Y`@bTqDc+gG<-&W2?m#HV zVt+a5?li9GQ9=Dosq!~S?*JL~R?}0D;5OJYMEGa!A)G!Yd5xX31Z!sP< zdpN{LJ}g&vgsLfdx~G(RmWU~y-?&(qHTT*c58>-@S*9;YQ?;hXk1L=-l9yO}I!ugR z(O8CR?A+0 z`!&?x3;25Ma~L7K4WGZ=50fhJMF?fuiPWl&UbeGiu zdb_!a%yioSXHm{_CBeXePBM0B{BZ`G~N1DxLvI2L)g;KKA%2% z6H@@5O3bSph?id*XYgGg*Ym!ThM#C_-j5!*1lCT6b8cO3;W!{b6yXIg1E9SPkIbU= zA(0G|c7PGa?#u8Oo-JVuV>;dB-zqr;YbH8X7^$L`qw=rAjCyOrtj#NYjCR@sy7TIy7*J%Ar;FNdO*4^H_$; zIvme~5Brn9<>B1i`(qfwWa{Fq^dpc8=`@1`b+jNLX)r<`-D`SZI7=lq@QV`?AXuxso$84EQGJwYDguNkQ_UX|4RYQEPU9w};= z0_OUF5tJD*T-Jxpa$6y(czu$j%Qp|%gE>3_TIkLD^^Xdp9G`jAA(Xn6`pjx6J;9gp z$CFR^_4bV9<}Y&J_(fpK%1W&53+JDYp7bbdyzItCW?g(HFiEN?OkX$}UP`eYRDZlA zl%WdF2z`>8y{&e^m~U%EKGFR;0#Oc}A`%vAo%!dOjX&K-i#6o6SA}!C*iD>{Sdzf@ z;=@v(1b??GP|%W>rV*#`Uhk>zmLq!G;?lg=I|pc7;E1RAvOkp&!!c9^?X?JP3zb<& z&XG!p`V!n6uSs3jS8I&FI&`OZx0`fdAs3iDkE%cxu)-#u>l#f^2S(l2v??pGl|N`5?QP#C)oDHL_0 z*F-)cD3Yxz>wT?v3fO5fyG`owFgpNBRcPeqcCH1MuHviNJ|utxHHAJPikE{MRn$`J@^fT zg)eMloKPEj*LxCbKGM2cyb_Pb;(U>G)!Yv1*2@VQwwF4J@(1GWAH@b56qq;6X5Kug zxZQh^xTDlARyF8Z)0-O+ESSbKC;z4Tx1N4@uPtNFHk>bM7Lh@bsQ!g9wUw2I$RsLjc69kYg z6^aw`hx#k!x__Eh?s@jHO^67@OsH;bs9SyNedxVT#6@)J->|SZQg=J1GGDyFyy7Nb zwbBUk_aUstde&}DaJt{V{TVIdbDVG_#94;u>I#0FHLvwYw7yqFHD6reb1i|p^FGAl z9#yI&Rsx?ZCmWBacs~Bx_$>XsA8h}T^`QKF&5PhCAPjFMbO1jo|?bopYj}?s@J98_Y`vVd!o5I zdWaFBu;qii?P2dRuC{M62NZ)U{DwC4;e?f;f2*KcK>szIZ(QCM!lewE=(t>OCCGst zKC={8glyPokZpqQ*e1Q zO!dPcX#I|76!a4;5IUwG3B%LZ?Y<)XR3r$&hFY%@p!`doxiq?N?N0LlB;z+$&fG@H}P%4 z`ehn_#9*}hW9rnEP#~mSaI%v449!jtj}QG#&b0jAR5OwaIN3b)SYZhJcqUeb-qd+Z z8u@|Ict7d*To1AmqEDR0k^+Y<$`F zEdT}{Z`Hau1oGvRDeqxH4Oz<_bgh)zM<7ozG8OV8`= z0u1@SI7<)dRrBP@pvf;U*z{?!eFOgR($QGW`ySEU9E?U&Z{VOEl&e9Un97*Q$6QS! zdr`>LNk_m}yg?o5qng$U{187TRM*i=)+(t;yt3hS1^DPwnD}K2Z#}h@r_dp!L zt$GXg8#l~{H0Wmd0Ib#avyIEChy2scz7|hk;DhRy?R(D_+@D?lF<>cu4^dMxfM>M* zr+Ysu>F50-3hll;Hu#Y3OLTTSSot2nI?C(A`JU`7es1^)gHZ29{f4kPM(o9qnKMtW z^$l=+vCL6=46$hj%BLpwhHHkw*`}vwWALTM5-3Uku0uW3ejoY1$U}=ktcl?LGwHH_7v9KUFJv!7v?|vS zT(l$Rk~A|VtH+@$G;ZnJNm{;AF`dBQUW`d#(CR8TPf}cY(U&fr16J z9kGw^u>KsHHuf>5hVn4In3gN}`V3zDMYGNycfCDFX+BlZSb#oAxvHr^{UHA9cB;jX zVA&bl#wlt{T+6%r?&t44)9LFE&Sr2ow2!A>y=D6{wUuo?s+Dk`$4u$Jr|JdW7JK-W zm;MauC1lxgBgN3SFTbz7oJW?=uF1IDO^MT}b#R=@gYo4~wHx!>`3;f0r);qDSW4Ha zj>0Mf^Fe%5-3;TnT)rL+dAPv8W3f{;Pa2VwE%C{IKl1afn!y)h-4NY&xCxy@0!D8M zec8`+?#)HiBsBTnij|>9wZ2o5MfaGtn z&6Bb&$S%&Fz-(mH!DQ`o&U2+sxUg8{O@Bb540`&rn&!^u`?t1;sPA8e;E2wZQ|kbY z7Mt1MNA`Ez&H>mtE*+AjYFtYqPKkhDs*pTrr+r?Q=kGvSp(_4BLixm_P_ud}XJd0- zw&kP7zDjSAn~ugR!?ElJgKGN4PVM)1$9xb~_4Y{Lx6?7z@GpG6ruZ%u1lxvXX>h-_ z^d^OAL6t%q*Czidy4B53%hli^(1w?{aV#Js6|Ah}9?!?u7H6$n@5l799Ul6o?=d}=9L?kc%8F|fC`0jP1*H@#Za8jmU%v-sq;jspTZrw&_*Jmu(;2Q z&D}%I&+GaMXllxsUD5lp{9Uv-RCzwWXH~ezZC*2ZHyC~Wb{;mm@ELE3^q#g2uJq~8 zS+r@YTFurt)nG1ssYD=dwwCsB6NGI=%saQ+|@poEHwx4-#a7b(_A>Fg!s~uN?X3TclrsalUjnzJ1-j-td%* zU39=H{}KN@B2lyDTpVty#1MRT3~7?qTko-1E*Q?AhcIjf{ia0^X1U&}j0~^?c|jXJ zi6XPZ6u4ICOkwtlbH4ei--zBbMq8)1tPo1QCa8mXc`3TKKVs_xnA-+B5bU2yZTtf2 zm37|)VYu?H4NDSnm&GsRZdIg0BlDflPTh_{Dbk{ZN?u2a^5%^x>ZMM8BqP04c<{PYe}T zRrV*Au{nQk(VQ6*|63&R#56|ee7um=^zo8JS4BbjQ%r|Fg~HOQgO^Ex!p4iAQo#lR zM9t4&7w(#*ivJDA+h5{|yuR6Q+ArZ#htoigXJ%+=Nyj7waA03JP=8T0>3o5r4W+1w zo16~R1H`rKo*sUPUyJW3i%8S$+KKfqdL1{N3#L78uxjNp%%7TS@$8_#rO^I%EDgYs zZk9bkPc0;1I2mssg{$nC)yIZo5N1<^P+w7~y28YOp%pnXlcqnuKmt%%e-9NQO)|M( zAC^Xb%v|3cbM#*4%Y8kt5#2t=Q*`-U7QkQe(g^|78Jay2(@#v}?R!f$TL8!$TUS<3 z9>hKa=u(&a3^+lN^nM>lMoGZFlc8OUUvko}t|jI{p8Niz!WaOg_>Tf9h9|@24HvC* z;W5=ZusHb8;-@(7k+*Xo8hlq){_*_9r)B+^E^O-V_|vJT?MNxf*LT3biukAG8skU~ za-TgzLHv)?S%>xIBWqCl*WEdNmIW0$0P2LoM49ObR$<`%>4KZmxS!^@nx6*W@1M`* zv_3zl;DE!>(J8x7$zzl`3O8ToPxsHe8^+N7K?jrm9oI+j<~}l$-^P6zI25n@^|?|< z9%RA^!4Za1sWvNwhaifO+M6lu6{2AYS=WooE&W z5AbY&2t;@xuEIL27rUNG8$w){!2wzI?(2MxW1Np?z7_?WfEM^GW;nJYfO;4nX%7? zWajHNNFHQ4zT@|vrRP-;ETWWVKhM1X*i^bm1$PMPDmYr}kAFUHFpv61wsW4KU|siT z0TQs2e%3DWx2F;BI1f3v!CC z6N9@vfX?3gY}dcX`6%yGY-5)8E}FwKADhX@i7+4Su{m6aGF%y=`+&8@qs-yo^Pp=- zS7Ew`fxKAvzZTwoz{YOaLKDRpO@YEP=H3c~O3Cl^Y5nPAYr3Sz_UTDE)JM7>qhr@@ z*e^x6w>j5+N6YDLYPTeP|6%Z@Ne=c+ZbmUK03LUsTtaAx%}xpHJ6PF#roH|#QpVFI zYA{F9aB`Tv+WsCik-3zq{H)s>V_spg`ntKcc=+;1Xx-G+?fVxcBE6z~)$N-H9+tTA zV?|wpZ(v;?j-GwJphvk4^y))fO+gPPBHuXuX7L=NTu>=h)XO;+mhV3~Py-7dLP1;(@f(akYtnaRKSpWo+R zJW&#VO|X;|+CwIO`90fxn5UPAYJFT%b8)ct2n1$E_u$DV8e|+siDb0n{x}C?v(U7| zBM~QB*o?S1D_`|c+4e6wXz^U%0`I)f0VJGy%8;)-2Xtf3$w?l3m(c(d7^28&%6D7nUxxX$pz^=a`aXV~3U}bb?=2ncoAT`dzBl`5 z-zzSdUElEgZhH0!gI$>_i+n8jNf8{}5ip2nuX&b2=P4gwL}~eFvE$pi$^r^T_`^%})^Y)y1_!6o`Ny>?+k#KK%TZeF(Hud*BtC)ml# z^~)OwT%t(w)1E#8$#sH_+Ba>qfllUYi_QHoG^(62M&AWdJ0 z)3e$_ui&{u(F19Tw@l;Y$?z(@$LYS&ZV^C8{yX27_IW>JU?Z%S)EJ$DO`hiM>B%QUxswxA)(&p z(3xiju@+BojDF1LA$h#&y+C)GAMNJ6+6w1X)*Lcn59!)zE5KyjBSeF)FV@oc*Q|xA zN8qt=4lb?`p!J>yV;aeG=**wBtl*%v*=EEQKaoFwO{VRkahUj4Pdf0s^+AhTg7Rk> z>(vr9TD@%KdK5|P`|H&oogUMTPWuo(7r%4GRgu5zXDde z52wui;`bj|Nz}A>^I1s*YjN9|_bU zXIRIS+J#T9!QAhG-C^n2qU%ldm|E(i%zx4IwP@AR8*fVR4Y}cZ>C-BEXu!j6Jplb+ z7_e2A-e1CDt7c*GAhA8Os3UEu@-yXYtnR_}7r4uH>kBS@aPwEWu_@_i0iVoe==zW} zy~sB}!eHVKnR26?^6Y&S?`n;L_&vNd3LH_SZl4Ixa~V9-Lq!>KX^Uab=qYwf-qOy@IA$8(-Pxl`&mx zlZrrmAM|yi6kh(>!Dm-jROsY>?pSqzFt)bt)9-0oOrkv*W_QE}J$*MshQ3&1Sqit0 zAc=}Jxc=ch*SO13TAH4DBx*C>D}G~M;ITaP*ZG)UA#OQp;7xVs>a@?IEg+^^Yi2dG z4S?NY4F`;SpBepKv26*Bz=$4L_`p_FU~_MQ!~rkZ>Ht!?&qKMphlz0_xD~XQR!{gQ zdpJT?>+soZ?$pC>$556-0+F!Q00R32FD$10Q#0jl)l=RX{2rKRb{}Q8dMi;CC&UGa z^_l#csk;X$7D~SQcAC-6kYI&%*Ls~BgONSG9F{*i*K`J3BB0Ln41t8#>dlF5Utb&2 zGEK*h9UC+lzUgv9PNF=%d+>$wmyUdzEt;;umY(_h*zT`zxF6b~8v{TMB+5)=C&q_W zG;k>%`y-e!JqWU!Psg5O3(}hdcuao@7`G>;&z;w`%)!EjLw5O%>Z~-1{izpq51m|d^KDk16BNS^ zRcu=FZRE%Fg)V$%m7b~uX?6ZF0rb&Itj~bGd zMMw19d(K@XdlzV) zsrrZ~4C%caG3&+aLa`z3p`Q>fx9;klDo<@b(`-E$6V62A+MLpd2@t^h>Aq75&zY`( zIH85&^>m}@3ahoGSN}pUGP6$_Pr&5oKGR7eH;3QPz48DTKfOJizWnytAA0!TPbF_> z{VqcLKogw9dh)X$3h-~Atw|u?uFq2s^-z{_3xN`s*)-~eIGs6CvD5EMTj63Vs=r>T zuYR zjj=ddKid;B%c!iIRHOo-_iNFsor>!L5Hi3_L@-_ilbe0B+al{zq$xZ zv4WDnuy-@`%q1AseQdmm7e-suGBi+prMarPth4Y82s=H zKdQq*&$$n;4ZU>EAnCQgkvHcO$OVM7`@?gftMmsqM<+?V!nNrX{%P0snKlkCw7sEe zvOIREF_0p2Nm|nvj+BsXI@EnjA6RQ&F5}L6UdMDy&ifQLEF<|;r5nxLA7daHXMX*> zJ;!8jmz$EIA`Ox3zq{}!Q8|V;TT=Cp=x*u$ej%|LhdS-k5;YT1L;odYs1MOvQOAII z*(}5>ro9YN92n&%8HxnIoj52iB5pWI?x;Yl@Z1D7{wF=a8xjOD|mA7|@wE|Pni$+7I9J6d#dCyK0~ zqW;&3uIrf@787`H0KmH@5iR$Mu+*D%pMyL2Qspuf`CNuyI$n?7<+^Glw{on)11jTy z*(@T@oZn%wy{m4R=BS(Ix?{K#NXHg`iPS6@!Z5Dj;z3CLeX(*c9*{Q3?wL?ej^%C5 z<8fR1Z2aw0bt>DJ+i;1YVME`&GvUu)8T|>ET&eXFY|mdfet^~7^CB^1_Iy}P6?4e< zC5lpEy~_Hp`rVJuSEE0+U{EkK8zCnAdWR)pXsUaXIUhzxh&J_jR?WKEsV*`3xP@rM z$UA6BXnarb_YVth>)M z$z(0oN5A6`GHjmBQ!lCQ`mw2n=yBKnR?WxhGjj0n2EER^PY=y{QPuYJTi8Y?`N6_) zxIKu$CAi)Vv}A*Qp6MhAPf$SNxl784`>edfh7&6_J!Qp$J)-{8J@DaJ7KtIV}Y@Pgc zFdJ$Qz04pbfc`PJ*m9Rg^64nQx!Ft}(k{`!nyH)l6C5^S#ajTEXbpXF=k+U5E@0X~ zMFx?Fx3o|4I6Th3FI9P`?NV)#^r)D}gAZ6|72obmgKzoCA=a^rOqW?>^fy8(hZz7) z`D$ryRu2$g|3G50YFq%O?#qq9dwaC9MA{LfwUGcgsVkiLPGSIYe5Qmb9=^{Mdh?2z zOvgh+*ip1R8*#1^49|iOMI~klxf5NsZ5OswI@KzJMFQS|FP?fXQcHT}2Nu}pA7a=y z_th2CI&MiXmANOSA!N@M0o^#5vPewkhF~kYcdp_lsym6IRDey`vfjYCe|wK`F@^(# z_FgX`Foi$${{c2!!6@IZybzRQ%PtPN#`~qcP2sa*;^S8WdmzeCy6or5x;y~M7c=*9 zM;&7J+&n$}Z}p@YQyse+m+J^+D-2Mkm%scjxJHHa)yR(q#+suRpCm4Z-5(aODQpAh zxxf6%+Cj-DyTpH(l_TgKNVw0fgFQz9r7B1Jrj2 zT^%l0v9k$d&Khna|0((qDs)GMJ?eW=-#?VY5m|tMnuK*ig9)(v%b1B)n-oNsE!zLP zZh1bgud+T61-PeiV^j?W!5M*^FBJW>zUVhpFF_fzr~bBJTatN=cv-un;o73lR_hI_ z!Wt?+Z2P#(t{96f=O%V|IY$HxJ?P1x@1%Fcbd!!w&-u`{R!3d))zfNG2Oc!BxhdZZ-IH11}i+& zYL&cZCI{UJYT(Q{uN%V7ni9Hx@X zhrLl|rry^E=0R!)$X}X~@uho^7^?9rUY;m!8V>GRT-hUW>cIo0bMLQ!}NAAMfd z)rK`Ne_ofOE+DqHZx#&XAaj<5u7VqUCDuQRo3yX{U~q?Wv*-CFGLWn$)AuGu(F0*z z_@3pZWZic}F#S8E*M)-)+svFL2IBMEv}~^<>n95gAE2tt7Jc)WzWj~sL0m7#RFuwr zMtD`PiQeM$tULmewPbvWDnfo8H^xMHeP;l2{1gse&AE)(@=RYJ%WpJ8hO$LDQ|R9k zZ7aKtv(a5MloV2YZAKqJUf#}3zaTVs<I#sDnjxc{0qnv*8>UQ4FAG*3U&j;GT7$l)D3VoMU4~r*6^*-$pPloStq3vN> zJ<(NirHyI3$rGK-pa=eb?KyYKV*U}>hw1Cb39cywX0?kHu1Y3Cy>_qtg-XSQCE44{ z@8|_@Fo*xvq%5*XC*UT$w#P6u_UZw z4=<%hi}hSf>`(m$K#`0#C8>q;0$+uC9h%5^la+!gWufDZ)yR?N?Mh|2xmOqD8s5)j*W6 za{tqw3iK^CxV_x%-Ng>qqI`9sMRY;v*;A5^ZZS+-ajk+JNwTGUY{DWj>prbwu^eT^ z=-$cwcRpWh<9`Ii6np5esS<#1I0!7>VDF5^&uLpvnqR^77?Xq=fL$DZmVB%N_4U4O zyZ>Hh~I-4L`{#Ic76+WjA_;R zBF#_p$5uH|Oxqe3Yem~m1B#2NGwt&%2c;~Wbue5({0boC8J#Ie@n25``$geP=p0PY z;jVRzpVh&rEmF^u$$+IIa}om@xX6=|msEOQ(2=Y-Pd%S7&v3!%=eHwmqQfcNl)^0B zP<)0x*ez@ucQrzf0Hlnm&MDj9k1i2Zv(|#&B#qF5z%SWZfmf%qmz}@qN8wY+5!%$v ze%i&#SHLp*Cg2xOF4Ll*8lH1{Waz;-{@&*+Z1%opO=z`vLhT}yt@3n+Q1fcWx?0L@K{kO_uWhcd&f zbL&d{q)q;d1QDN9E}_T6O4-~#Za_v(v5E9C2lGKn)M>xG$%D`x)7c5Z)~U!JRrs;* zv3YoYf9^hr+vapkn(A{6yEA-XUFkWh%Kgp88q5ZgxYXL~#2KcVpsk+f#UdB)lvOe?-__ufCyg>FA$Wc^TSI7+1!NlGIR6_*NA1*@@<@E zw3>UW8%k|-yH7bFi@|)80JOG$oe%n>7_9Rx!_FeVKLcxySu{({iy6%F<~QusoJji) zFPH62Nq%Hf*I!+ZBGUEdrG<)?J;z`%S6*=wy%;N;8T51 zEuqZvMPE!Ja1lWo7?w`sXE7^v9llS;<%sCT8SF~j!v);~*@sHO<^8p{^8E#M zc0(Kh7Y9 zEXI&_$8*bQ-;vNtrQsiy1pMumS$ z%b609K2LRmdQu*JFc~}wmzZ2u`$ub=&3#c=>fg(pB#)^w&j$h(hLD+NF5Y3@tmAtU zpzS7s0H;N^@nEZHAE_K+e}uhA0ACsP&s^P0=#kZ@zs0^--;waDk6?OkpAJ6SSD#(iuC;^iEiEB@%I?Rjma)xtxMf!q1$NNe zIh1~`7sTe^9?vW_5<-a!7tHaJKd~X7sDrrY3}nmKdVZ*6j!{L z7|jEO@1Y1d7T*n8f9#HIW26q`Nv4p?Zs z;WjnL%1Io$UT3|!>~rfY?i;17%t4Hd28gKsjqx}$rx^^Uxw0NVM9RM+Fd^@@=-k-R zDgFC8<9Ke^9K)*w83!ssMU@1a1)fBf>+IH+opn5&)*!G58jj~_S1_p^=DW<0yc*y+ zIdNKeK)k;}(}nFO{YuF*e9$BqRx+&i-uUvtdY|v*U0d`XRfk()pKIt+hWDH{WY#oC z+QN})8sXqp18|E!(9gBCFT3KsLK}$Gk_dS@$u)LK}34b z^L5#cdoBGb_iGS0Xz|2odhy#|Zf(DC{i7QGt0S|L=kQh`5s<9McjOY^We*;|N2|_c ziJKn{yk?dqFy(z_q6W{)_SH~kkQWr`NzsF-(_wpCup&p|>Dy2^L0Yz7H3_0NkR4T% zD92|ceze}$@}Eua2^LA`qkRdp$_O%;hyI+6d2FsL=8cvRUv{+4(bbKELsyA!`D0p1 zCq97Ro}ApA;jk-vj(a~J(Pa{}`emJm_EvC%kMvHaQCygZ$H#_02Q=T0dRvA=qGm2O zPZ@e67UeRaJ{~W-zkpCLHbzpx@qNk4>kW34mtq_9Jv3n6S*Y-}IWg1MNEm5wchL$Q z18f^zJCbwKEYY4o6R#l+LLCD_5r!xBZG$+=#D|o|)P`zat~J)$J11tlu%TO1H~x3| zR_EZ2rgfhDG&-^K_|#16Oq|pp!J4K_itIWtQZG z{^m==D=^Bg!XWyhUnJh!12lP+hSGi(REOXxzS7%ax#gbF&MRDD zC$cYx@>ABcqaAEFB|q!(Yo5;MbqkNtJl!9$xiaCR-yJd@$6+V63Wy?rT<9lwx|_W+ zQHlYVfUW`7&YsoCa{DKmWr6{`_^IzM!s+tad%(gHqz0g@*ICkHF@Vu%%~=Hl4yW<~ z2<>-D?w5knx8y6OryCTS4!QE~kIs~wIzfS1j#JU#$z{*`F3xvAy07uZH zXswvMemS}nkNanEti=5!KeQv5#gG@9A^d1|4tr>S9*-LkB5u1s@MTvY7lpv^1U)P! zPkc&3Y{PBNuNFGZ>NSx{q;dOoSX_^%Ow10ce@5vFN-o9STO{MncsTA4F>yFK3!dN) zx5&aE-3(rLIegBq3c^_D6WSi2w%@tUdqel90U@nnuvQh|Wob?)*dqOS#Y9`n5#vo* zL46;gcvqpi48;vNg#E^E!V9!!WEVi<_N$+K39&yaPgN;TNbl7^aq%{)f{zRc*9Pc*Q^=E(qm3Y2w>1%ms$@ib(pMF`%pH#!vb-3-Z*sMUL{>(G&-_f3htpTE@bTl?Yb!qBckgfMjDez2aI@S@o&e3=l)HJu3?v3xnp zx0x3EXgD)#S56*)B(@*Iuc}CFwW-z@_fA?L{XZWj3)!vjyE8kbP;+&@?wdMgD2=!F zc4hXA^>(p2Fmxw2>mZH{ar?DMs(In}D1kr0bkKY`Z}|iB6`t%rV;Wzgh{r~M06dQuMn#WP?#&rp z`aQvz)Dr)9N;vNVnxI2y{!kM7HWI;{efxRighQh;sfJ&v7zxTxE)NR+Dl#xx9qH#A z>f1QVs=^TH_JD5InjO%rTyGS-XG^<=#Qo{2HHwZ+<<88=6wQz%|< zc{3H9(aC|br7-aP+{qvGxtA5sOoKHxJgC4nH@s6}$-dDQNvoAOFpcgAp~QoPP!<); zL)aEDk>q^2#c*9C?@w5i$OWkF@?E=fKZt))cG!`rki20E?9$)Yb)U`U5Mln!c4W!Z zMZU9`e1)k?Skqii?!gBb%SKkRey!&4hAoE`ao+Z3TY#J;U=M0c$?hiw9u{#oSIaot ztUYD!5{=5sD?IDF&r4lCOd8cKR3%uk=op83zLs4) z@n`K{S+?$NC9@xh?rHf`@uNkDvH*=5zItmEsx%D3tyw_o2!o3=Z*=1Xx~qKJkIp@(YM!Lg+2g?liJUNdPn#> z+K~L1+V1NgCdE&%X+c#53Iz-{cBq9V3x-h3<>yb9D^k_*D-wHV`vn>LGVw}HB*h6& z8Hfk(PJ!q+1Pt$=sbk7o^_=LfiSeypl>3^#>9*nA~3Hy;PQepSxt!v z+Er)z<`yfLTWWX3u{^vE`-(~lh*q~FH8*DR`QeVk@Mt-h>$vNiwm7TZ4SI-|yZ<*sq zPTNms9eyW*vOjq`CP>^Q5cjOy`6%Lpxat#M?pYL*ET-9zH7Wc)cFkzK>F{B{U;aPi ze3E*jIhM=|jbmGQ?C)Dnq`~`;;f64bE_g`mk=UDg{=JR*6*=oy=Ixs$Yw^PP-Lwj+ zxUQ8rRy_<*nSi29(G_JV;ce-#=L3eFZ<;+E%tgzp)7pgl4vzbM@Evla-Jqm2y1aM! zzTf6H0iu}n*Gc>9IIaBcc5_5GJsRa>-Ae zk$K}@kKibilsiPQvssSc&!1`pI@Si`?gk73>46~)S#kLcLgsj&_Jpoh`|2H@fqKNz zIqyiM5LU>dHxwEG@aKt=D^jpLh(kMu|Dw9${qc8ALwGwKuwcX1}%LhdN`8;RHCLa>^YmcdPt+eJ?+%3U^mPDcy9t4JXjV{@t62XTZ#s%>z+n!1 zxf-^)$6X?jdU?Ilf=^@ZXD|3UvqF8YS!IXs*vLHg=(+t_YO(XuAfnMHBRLvG`e@uy zDy|w9uRO2E&pTQZ<(b^IQybHkRZ+^?em)VXepTW~TXB`>6WEqc8PM;mOLA&9D0;?_ z{arv1$eb7w;>TxjMk8-*pL2a@*b~&dga~`N@CtVFIv4|Aujx~C=tfUoTKatwn(>$Y zKqYeGX=yukQ?C0u@t>5jDjR%|9X#7JERsN+S}tY&r3y2sWm!7&jH_nHD3#q93W1{u zHw;u3zx8K95rEP;FV}uDG<>=fwO{l7HtacqAD*>Vz^=UcyFn#)6J|xJk zark;1D!9l5B%Z(jMJ=cGl>z7FdwyiZNl?_HyMW*8LFt0B_4%Y%cKk~4y5+pCKjml> z(?;(B?vZIP=myoR0i}BEBl|2A!!pPhQS6%}42}wmJ&798FHSBbfst3GGKhs+=@Pd+ z6nilTuK`G=zfm>z(JpHQaG93S4{Nc2h zDVBq*4Up6Syuu_L)!zx?Pq#QGU$p(8u-Wk|2r?m_ImLj+Y`;m=ZxEe2VQw)5&NXCc zHa)cU{UD;>3l8EV&*66sC*9w4!oRDh@9SucCFNO-uI zO|KY{g(!8c=Z+)I+4e) zV=8~`TT@)icwX3v{d20|QeCZV))SF_wWaI%R-T`3&DnFkBR7En$N3-TP9_kfads)hH3py#gf!*>FlW|nh~cy zuOFC-yyw+*zqMjrx#CZtX6_q^^FP-S81A-)l>)LxfztZ(AhrYEjp zrtyc#sm~?7lJ`l!;j#AtT{k2c9QhKdsPyNxq<8P-D24R%mx~=}{hxxZ*t^E^5OoBz z#8I`UocP0-t@-h8rC6bxHSbop!|fHO{^^!ck3a>2N%=~LuYhGP=O$SMzF?E@T=5>Z z#zMg>hiH3dNR|&qTRTfdV;1(_Hgo%w#`|soj`BY2{pySHr5w>Tc=QXb`0&boRyR-R zMspX1y-(9Uxj}r9TcIQQi+{>F@Azf8eMkmJ1Lw=G&~k;SD2u5Obg<2@s#3GwRk%}W z6r2WO@tnHIGL8;NQ5XucnF7Pn0zQx?UhkL@_Vb=CV#VBGXm*3xlGr4Jrnrs@iVwUo ziOuEW-grE4CWR%0qxm1jB;4<5B=b z?>$3wWFq}K8OFDMWFcJXmaI;oRzF;)n=E>t{cBITwL0n$*DR7X6+X)0)5c5S+){<0 zCTzprsUME@{j?S0UBA~Rck$k6Q!dHemSgDAZB=T63==&obo1PFj09cd(TfbMu6hdQ zw|SA20n{e>dk+WsSeM$FRpp#k4cfUw<;W$MOnCy7O}$j$Y)9+zMneZqYQ?a5(so5l z#C*L}1wgyxJeRPp7wL}w+BY##9yN>Uw0D%>TwV#io|nCPmiK0@3FOeA-1Y$Yuoi}h|)?~tE5Q)r88u!Cq~9=*woKlYKepV)Uu&l+`bgs? zSYrCbJ)QJH@`1YG{tTa+0Eg<$%gsf}X|#2~qrS;loz|7cf_|s+2(#hvg-Dy$LNz}% z8<+S&%Zxcb!ab5-DDU*Ev$;R?0$S;$A0gP2Ns$gzq{@7-5q#ObIFW7qaTOI9;^w=q+GqUwds8@ zs&XSkepn|(@A`Ozg6rG(VQ&%qH#eM{ewwpo{ZS4`eY6@Jj&xY&;0G86Ai7sLBG2Dz zJUetbxp5HdIK$)SF;`O3i6m&NMSBjjps6nFd`&vDXm@p0d7N8Nr zelF^(NetTC=hPNkKb#Yjg<8DHp9%pEqh(4H2t-azN=~ z8lW%qO8xZFJC*mx_olAt86OLhJSi0KYsnIezvh2o5B`}T+t?{4J$8ej?~d70=k0V@ zl&*V8XP3iC7mmO4Ey(%CEpM%{di^a{b%?)o@EhpW{Q*79JJc6JWVh^L`TO@iQ(6wi zeCXud0`pDo+ev-CC95)|MQxmC^eqxWGmp}58Kb*|AE^%K+pi;dzLFswlVS4`ODp>} zZrz@b%iF1RuWx86+5Vf{w>0#rq(jCNzAA55skaxARie`#@2OT@&;_l*C>}ubR(uCq zNWc1-kOuER9tW%XLM-G{L;A25>y}laW_rhRu=y{rTUWri(4^dF7xF*_?_JSXAe22L zJ7mw`H(d1@swZYg%0(;F++;6F7XqPJnia_{fKF8ARi!qlQ0V=cCM@x?Vng!YJPon< zKfcrB7rdN(tIZRjr^I)N4=mK(c3k`OdtdHWbW`o;Jvpes(KhT?kU_WSH=KAyz4X4z zC*h0u#FUd7Z1gRl!e6`wu%cg!8zGs;2@r^5v0qSdraL%f>u*ouFpIA7O5;7Rdhm=2 zK<_6!ZY15*KLY9o-t-LFDCREZi`}DUL);qm5)y)!U#Ap4IQ@S6Xa1yE^mk<7BctHI!Mzw@P-1>5)Wt6nWjRC)Cf>d z>gIb{`pDr^9RCe|J|3{7=kmm6{aIe^;y^6tB&nZA3m6}etUVZsW<^2snNFTpoUQc& z#Mb-5BLvBdj?)ev6Ua*Z=Yf4xB_HFWA29WYaMAnAa545^q2%7<0f|p2cEVGz{_w_- z!77d+R~V#r{oy;L8?xw>}I=9eUseE*JA! z%{o@$^MHQl)rCUXH(20!c{?%7i}N@#dRu`*0KfRX$9*3^BIR>$G*cYPB|iPmzApwO zRxc@HmKt&n8=F%TUhpf9U3rCCV|_mh!mZTq56QWp%Z>_e&+FbdvvM4mpD^hI(!TJ4 zbKi_mfOTH+7&_8Lnf(!J=MQvKdbF*5QqP_!YqRgLaKvTcSS!1qP{zsHm!w;?yl_-T z*R~~~cTMgZiSu$8lH0qta7By=0&o$6=2cO1Vy`B?el+d@0QZWawbJi90XnEC7f7}6 zs`Qy4N!!`SHr8#&{%Yi%qnGL>o zxYw7{rg_p`A+b}*;U8FuaBz2=U%P|sKyCIWv_CuKAI`l#2{W)`1nII4&7bJt$sGi^ zEx9)DMnki2qz`zk(%JLlcID@`2HD7uVM||Uf+>EA{w39rX88u`$w^p&wr?bDn4QVX z|1y~{tl+WiYNN3tv5{X;Jl&A3UU6Hd@3oRK{@eH)2aLR1PC`NkH?KZ=EIO?gQs}3^ zWJeHg(0lI?8ffLno>^GBAxM_sh^n-Q2e}0YI`UJx14|D@^?)lJa%x&LwyyEk+h-4uX?1-r)oz+#y z&MFa0S)@mePUe!X5?|G9n38QH>U|lkm+?8L224Nm6EBFD2vFVSrAbqW)$d ze}jc)eEB^m|I&&F72OT+$TQ0@iZ|4^R5Q7=!e*IzDN@Yk>kBvcSyk|rX|0xHkvYR< z^;9rli~&M!KBA5t}0z z3o}H(*f5sqyD0mOfvAA~%h-DuL9o+CSiVI0xkSf=+jraUyH^jGEIb3!c$H8T9>Z$M zT_DWd_@PN}`k>K3e>-GxPf21xs{SpEY zQy-c&=+}Npci;?e{G)(kX&;~;c$@)!zBM;}rf%$XZ#Zo}&GfILV<=aLpc8t;%l+Od z^0UqMSA9VX6-UXPdExfZC2oaK_4d&e(m(iuG27wZSrB{5t|BQ}LI~{sGWC(|5dhEp zq#trV4(y5;ebFa5nm7}`K>)yJgu>i#02?=+&mLm(u2iw@i1t!;8V7={=yb;w1z-9p z-<1#JLRtRzFm<)tzr}f?57zO3Tict5-6<8hj((pcfjfOa*VWPP{nP75)FlnKYQ(7- z@z7=;8Q^Di|CW!h4J$H+N3av1KKy}PA=rcZgL%1qoocW@{Ho9)UdQmvireua{`hqu z^r@t-!~V&jI;g0h{VFp~*QaBu2K4hQ5wpN%C~U2t(l1-OOHe}~`b=B{#fO1M-eA20 zopWfP$;JHAJa=AS`uMy89W2-%{yVf8ojmm!~I!0{?;oaXFv!G-Z|atQaZnW(*{yImbFS9Q^RfwA%#DXlv<=XyLCDmT4<$%uO2OB4!D#r%FDZ%~w zmrjb4JEQ-ezFB#1uf3rc@g0l>pyq?^nR;+=y?VLq!B2J%#zo#!rUX^$13??a3ttF} zuZE1XPv1*fT`Z4`vdmx~Sg~Krht`0oys=TaAMb=y2i+{CX@5R$sk=~zaM2%7F_#ZH zck?Unb>c}&jvu1lyLnUdSQWw7Rxbl4a_+5ur}>vw4`P1Ros0T}&tXHiA5d=J@f>Lx zDC=guz5k-d$t*ZnW2obl3RV~}KpHu&8QAedN-O9U_|=ABJ^-ijtK!dg=}1%#B;zt` zb%{HgyWBpt%+*boGE~5_+w!xVHXLn9NCVSKpZ*^yR1lv8TqO)>us`Xxz5mhcC8XF? zzbA#|@fvwD?5y`s&WB1M?>5@@=bH1d>dqaxwi&@ClTAUMCs0>+)V=0yz8;i$zPxck zL)i#1M==Ur;ryZoa?Qlq?V% z_fp!^-N_BvU+i_`ehS~;*W1i6uHL5(a`!%lhdSZ0+Y3EIU6yB8HdDB38VY{CF#GG{ z&*3ed^0cB*f%~5TM+vWVjXC;$_E}KDwBFkwGuUYmuaI>Q=S}iAWgT@OoEYiztstO4 z&Zo;+#E?vD#g`ik3<)?jA{`7+e4yU|pmPs5l0|!PJG38qIBxB*Wm1 zJP;=Eqt$;0kK(m1_hS|mszYC3ACmWw3Q{U?DUAN$gi1h?Ql8~7j4-q~+WO;;)J^`V zt5>yYV;L%+=d)j~@o3A+_7m?U?-n=b+{<6z+t&;py;2a8^@*0<|8p8zNKTdGt-ka| z4uejrFL~Lspvd-TGG3WJ4IOUs3x_jOI6bLq2*D8FFXlq^eh@BERQ^h7B;_5r=la0V zZm5#G+Ne2kRJe!7@Sb_kQ-5ouKKH7<);+?_W_j*!+Bu};_kzA6HAGi?l>aLDC$TpUc1pKq~HO#1(eAw8>7>1V%OCUPQ z+CF8#A27tBCka{YGQHYK-jRf=_p??I5UBrryys*Qyzcx;l0FZ?dam}Av^JXCFg>4M zx`>Aa79CIFEL2J$!J_J`?}|sv$TqWN8DFir@_u!IOH=ZY4p!R^>GPt@NpAEn|F%%} z`vspDV^8j7n*Tj zr6=NOufXgVHNl{KS0e}6%Me;7yul&p9k4n7rG=^Qdy$wZitGrPXeGnuhbRHj&ci<-b_A{|4-+7CLwOSud*eS&#&}6YiR>6zHS$3nUmwUq zXi+q^h#7CMkQ~^0g^FY-}y67hI5m8y2Ik!$jiT zJ=ykNLt%@n?l0SvT+Xd{yb++(zcPs5Yy&DA50?vx@=9+ryt(|GpYB7Zi~#%__c>9c zwV7H{2kP@cSgUSkD|>%j;Q?Vc@>52CXilK}(V;Om&=S~;**KHamtVB%tXG~Thmg}476d?sh(rr=QU5LL+?M%KR^b&7lk<}8E4 z=wcCHe4&SW!i>|?=5`r5T9jr4rCiV#}=*sf*fTBTJJlCOJ?=~_DGUq9H_L}@*E zxRifgKP~}>=csqqeW}CA4M%JY4jXyNYVVJcUPjaN7@g zZRoBY_5sQ7s<*=L((SVpfynl)_@n?^9I`KTWe1IZ z;M&R?Y!Q_XKo{n4_3xjC^rLj*u8?5`s_UFhjZ$v(a7lEt*4X#;-s5HH?;i9B{Kd5^ zE2ePQfu7v`bfWL|9umiVIAOyOjFo%rn`Ts0O_p_Ms3Wgq4%+mG^;Cad;{Sn$dpT=&L! z4uM^=$NQ<-QVGit8m6ce00O*wQCCJ5z>vP;M=fJ(0Dr_D0l%Ykr0DHZ>?S($@7M7! z*Z%Tl^WEqtBmrsbZR+8mM8|jUdU^^r!!>6rW1i1@S@Bb5w2s86gbti}n5bf<$iA6> zUH$S%NM12#5wL(C)t|)xSQ1$8f~<3fOGER_X9cx~u;($(VHf_CXRzXiC(T114QOq+ z%(1cyDbqK9x5^PH>pQfD1gak*QsLV0c7?bWiDxf3aXy~@;Hs1Q(he)w2=8Z^v9r#6 zaR1x+t2649@+_9u_>0bca`m(4q+Rdg_2KzE6>Utf>0#(NWLz|Sb1Du1T-d-KONVQBk~#k;9F2!zwuBGv7C?9>1luAVN+f^ zmt}R27;y3JhuN3P_%P_&#- zS5m+HAfNBX?^w&2zX*z{pSDx|O^K&>Q9i#tHU4%gkZaKpMeya}e;(Mb{hFA++gp)M zH^ovEgi+$D!$;Y(SrCi)(>lU43M(KcuBP&7T_5^7@XS#)6mc~)^f84!y}HBjeyB}z zanSM55kOs?l zx%qL_b{KsBB3-X}_nC#n>aaryzFH)J!j%xYcuw#56+OMKJA`6=A?1xlSJftAL|$!d zeKp_~mcsXy*Wq-LymN6ny)J2L&QqzL_oPz*vwr*}4$~~`KrPkRekC6j@(1Iqp1(?V zz!?!Va1TTBvIYFuO|4fxe{wmfvn`#0SGzulXy5U^-?r2*CiLJh z_wfV`Ufm=vvqdG>J%a=rGC@6_PrulCHs>PeO>RWvmHH6vQ%27W=5VtER6Pe%$rw=p zP%Fr|M=BbF6Nw)18>TP0qdn~X6yeXse%8*7uzrfPtyNrl3-ePJ0})ET`q$aIPABJ+ z7Q+3TxSg=U13ge)eIo7)kRa)QM?on zVPKF}-YaC}C$>dc*^gE_1)jI9FPw^fd zGFJ!>%M0;HHozBkfqajXRZGYTHI$?;{twyN{oT@zssCUd!YdyIt_ge8e#RB+FHZFY zGx+?4dCT@9K}kQ+dY0Hs(ZFJ^?AK#}s1!cRd%*a^w;;{WQGsvcCgbI@tF7RdT^o|d$VBR0uWZk;;$vk9o@;3Q2IXW zoZGkJbuttDfBr(L95Q8sFbYh$*JkUi+P8r$Woh`I!RfVxJ830x8Go~IWyrTZ6=svD4H|R* z-c;gBmKC|*bjKc+)XRN?ag-OJZ|N)o3tNq8nN?5sqct)NiFyO&Q%deLhJi+yWqXJe zTeR@F0_jWpf};%jZSq;&7sM5}QUmU_Y-v!7jZw;(y%8CF#b2pAYadY`r7`=sc$ihD zM0yzMyX?Tk`ly(>bU~<<_nh&WO;G)IAQWGM9$JLIDK5UlIg_!?8Zlix#9MYeu9w&E zj1(ChW~01&$1dhNkhiRR0l8ZQE7?5z5Q-nQFC_Z|!At7Nh=Qid3-P3`uA@ad8%%<9 zT#NJvh0ZVKpi?2GU%N#Gn6F-U=*xtFP0ri)o+aeA%zR&y$aI7`j;Ej=Rf>!0xn6ti z*ANM>rqy58EWXn#4S2=i_M`vSju-EyivZo7SWp8#U@&XPZ}BVMTqaq(dLZaS8f{-L7$K`46$@L&*yFOxGeb)IR_oxz z!?L?-4!8_ulDdb}evl93P2#HBYLg))dM4&KOZ>J2TDr$Jp%1|P>sChjE9NQ&sne_2 z%uprYEK<0bwR?PtBk&vO6JG-;qwtD|u3&Lg%O7mh=MXFuy3T)s|{iAm$wEco>Y z9ojUCJJ@AW5~QszqnXr@^oBkup0x7p3W*n%-5Z5BO*}K8+)5(G@<3-+1vCE;s0Akh zE{G(8xTo)T-ZadlU}S$!&A$aMEBsXGN&l5<`}FP>Q?TN@H{ich>=K%C%H^3E1Ma9_ zdG(|4XV`Hu0QR&`G%ea+OyBju20%x;q+9h^-ga=hw%2^mz~@0-qEjaM(79@|-q z8T;vCNN`)J@}dHf+URv;e7Bb)4tJ?O-w_OCF<1ALA0gV!+*SXX6XZy=ryBa?X}l-; z^qlhHB^eORZt3o%$EpcNSxx}U`o+^uI7D_*(Z+T@-Zn!V2zSDa%Vp@N7A^-Nj>PTE zl@*Yh$wt14#P8E(q)tBzOpb7)wTlUN(97w=Z`arHeqNmCG2*{OA^J(fiPQM>KhhZ2 z!n4@RC>p-i8N|I}^73QXB$l78|A6eXm*}+$sqIS?Wql4$45(;TOljfTgz#&VeZy{R zgS|ey-0V|@D_?F*Bh$Sg&fdi?a46iiYa~by5|#51f6EJJT(2_G?;l7KdiMxv#Ez=z z0cMLW1DsVW+3g*|&h3F}Xo4pi7XrO9$Za6;(Wt?MEVf>}eAb}Mm@9rdfE3&n}&a6`Gkc1Js^+y z`TqDh3>Y{#=y8v7VHPYv4^iQt0_xr0dkMR7f=ndPy$&;h#ZWLtc$InlJ;=A$_tyaw z_L>e=N?0`9t8hQ%gNQ3_-vi0s%Qd7P3XUVZuW=EZVBMfcChVL3dj^Owo$F)e^*yVW z)mehm@T7?i=Nx;|Nw4|^`Z0ZSGhqW#A|oE|`LJj#6Xv($w5Odf=%^fF0{T0<4+TIE z+_iK`5y!X7Fr(xXoXor|h`P)`7j}C-XXrr4 zhnwbzF+QR2BA{IfK@whC0qBV2F535(blw8Otv_pCN@cQVqrXc{1gCkOe z^W4)gN0AP!J(Bdz@~Z)r^AWqNn1hcboEsUeYtCGIJzn4EJ!K&tbh4FLSh~>6sjqK! zl!?X>(cujjeSEy%rvKc(2#O@qc1dd4EG{jLWp0t0YjTtsn^5Kl3t;9G@D^j3t)i3T zWZLHYg=-z_f<72OzX@N$q1kSg>H|}^RGW<1V>AWX(7x00fjT04gv)J?$|CIv*KzpD z_N_SCov46Jw=PY>$i?rrr$5U;^xg~CRR@^X|E>5U4Cq|g-A_bWxbUnHaG2QVXmcX2 z`Sl}Bk^46Ddvu<@U9=@H8eprX)S*1=Z;^GeC@B6uP9|AkE4{YQ?JnmMaD!t}CO+u47y^VFdQPMp)Sjfm2@#g)m>Vf+EwzZ5( zL?B=G(a0J1^Q5?K<}^+H^(*7u3mZF5eGqEA;n3jeHxOj-1|9E%yzW)V@9B3N)wQLKVkdhb9JJX6L?(0SJdroO2NI)BWgB`;^=hEr!Ie zQoxSA(lTgqw@Xkh^xNdoj9QsaM_q09n;xhepp~Fimd9O@0fPuU8tq-E)}y&vKB9R; zrRKmG&2z)>24ce@Qscd9^D3$t`W=@9;UwTAfHQC0B1Cblp6)^G!LfjpzaLP%Pc8Bd zXn|CG0@Yp`qza%wtP3Z@zEa^x0NQo*Otk8d7F#*!4-r@%7v_cgScd(`kn`p~8iJom zlbsaaJ8yoLAzO{}+i6l&jODu+@1p>{I0Ioo-iph(p*;>k+A^U1Y|2Ljmt05r2775I z_#Mn{H|+E3F!Ap{p)Or~)C4XtjYf;?fMrRQj^tsziOwNrkNZBO3uVR)zi%SWUSlpp zkUseLTR3e9Ld8oj`{#MNs#oDLvy=)SMBJL}=N2r*$k&}XE<;$N3YW%v$jDCEeE6#+ zCD7Mm4!^5%QU%K!>gF-p3`6mcJB#Z2bWJz%xbN@idiSq_&=47#Qsov^_1&c&;dQ%j zr%&N=*l2Y?567H|P^YrZiQadTd0r6Kuxor4zOm5DJbjCmgL{X^?EbLe7a+58^hUPC zK~UYZ=N)H~Jn%sK#iyft7GJBhKBgfU3#h!kPr`(iN-dPY`1A^oK8vNl;6R0~yS#8m z=P;N`YPQDfFb89vecin{o7v056mW7;wY{A#>Y*w90o4$N^_qeXpoGP8Jmtz=@z}On z0B6UC5~ret=4v{9@cCgI3+J^pyQ84@x-rac>AyjagGVWM+Q{N`ngy0_`B5@Ty6@7B>G}tiRW3ApZ0cs(ktfH^5X}DE-wY*>l zzfJ*pJ|!rxM@OX040}2ZHf4;tkKv)>i1B6b$yc71AzYsDOZTsbkMh_W(gAAib1_H_ z8wSD+%`sI+T9pqTSG@sKm!QMBIv<=1Sbn^kTFUlHGXl+{i`J# zZu0XyI76p@8V`e6-8_vW^md8aHSJ^6@#FL<5v+6s(5W|Mf zpuSJ-tQ*AWEtdY}-BEo99uW*p!P|6r$I;=br#*Jgos^}5GmXFZmp(=< zYwJ7XUS_8;6HC7ZTWqQoyoa9$wB4P01`R7sBjB~mGQAwj{e&a7or=HlXZ*nechbJ^ zm>0{V3OeL3D)z}+Ur553;?LVeRSP*wQ!}J^nU1dEkPXH!NDv2emUb~0_sY)l2xa#B zwSQQFI9O3U3)l7N-bvl?N^2m@Gi3p)vVk^aR`z3C-;xb00V59n()L{Lpmg%sKFYM4lD-zHqZ22>w&ENRZQeCWBIvr(0ythZuDNiTW z-gh5!W2vTQ2-P?rpJGi`*zLmYm7-l`MUQW0#Qg9=<;+eC@$k8N=d}q#O+K_`_P#7b z$$u%uvOjvCFi*qy#)ni&8-KCUeF$IQW*^T3BiN6_D8?cHjH`Sz_x$EQE}ec~K7Qz4 z$)lP!_Ncmz;YfIp0Fkz&ibiV*ntXpo25NA7$QI?S-E|=8Q$hW8#n_=Z{yqA|;~u3} zVdNLGWT`M9hWH%rOL!{FPtyKWZ~UA8#r#;0F`ZHX09*UedVVn;zWFC?&7!$b??atd z8@iyLMHOAqKR?N4jXn8ZQTl~LYYkccm5mSI%h}ro^KwLW==T*K!2kQjAb@lj#IVq# z#lz9Mb{fsdb&|8&gXv&qWZv~=eztc&`3fwL^wdt>oZOJ{QbH+E`{XXrc@eJYbVq^4hibB{HSgtk`PcaQKqNA&)MB~Cru=tbx-bfsd-M#kQF}PVS5q0L>*Uk1cfs@@uNge3wl2fXLiylJiRG> zwCuo2_$Ssys7Vy^_TGojSMbHJbhO!TZ8pPQu=ea8 zj~~yT^`NSuM`)qqF5(cggJ>lWjpi!`qHzMX8k>;c2D5R3APM`z=PSMVtB9nX2xZ*Z zm&Xtpq!PkrjonRPjJNUFo)qliPEmW7Bgvy>P$Smvwp8%Hx}RWqA*+$SnuwoNC~d=U zYo++;dD40!!ff%hf66TER$nID6c?~N*k_5VmZ|@;Ysc_UqkW2J-F#now9fx0pk2T(@B_PI;hIS7+Z1#@BlyDV_Z}(^`6f_JpW|&_s3j(PVEeG!aYVieR(1d z1$?qWp3ah*$`9tBP~`40{P}Zb6_j!3{i=^}`uXnLSL2(~74v-lVQkPs@v^9v7)U7-t_!U*th zMa%K3DnllOpGSw#nPDoa6tABbFfV1x6zlj3TNSyPTKZ{_dR%E#wbcW06m{;>OicFl z@HBE%tfO3;;ADkRj>EXwU=c{-o*cEkn{-1qN7U3ib8GvL)0H+SZN41-q+P%8Smnwi zr1!qR#rKaWz8<2$@B3AMKClZ~bO{wCTm}lHIXwB**xw-bzS{IHn0U=aZYyGpa=+sC zA%|bi4Q&n)eVL$dy#4OW#86dkaIeqdY(yZ}$2S#MK~-whz|Q(L!O=bL8~)`|n>g=r zN{W;NEFWd%0L!>X_UPKvYyABoc!hhVe9unXVG|au@ad$9@OHJa*9?eT6T=tw-cY3lk{BW}u+~)i|&d_P5eJ{T|Ko~)A#5fau=G9+4HQ$%C zvx1CBFk84I)YhfwhWV|DI< z+2ca%!IifoLu~LOgFPkT-O?vV_rE9k#J;Z+49H`5lysy~y1{THzw)Lfu-oDcq^o7% za@h9N%mWTx;#5}rN5Hj*840PyCktQtkGg|qwE>TJTu}O zUib#%i8StWAHojUJ6<|+=GX`knF?jpQ{T(I~T>dQeGJt*%_~yL@ ztj(yB=SxRTFjQRj`|LOfvaCJAfH*nW(`p3w4CpK`-TQchl)d{VSoIrP8;@M@xf|E{ zhb%AdzXuO!;JQI$>ZbB5BabGDhc~}=$|vyJId{KP?w>9kEPCI${k{6%bKq~17E8M( zN&TV`k>+>*;Oe|cb+~z zJ~t{G(085c38u%1J1oK`^H&Ew;DF~{H6pG``ARMFUqSqbUYCGqZ(K8u%0p9ZfC$g1 zJXc3(ZW|m+M!!U02EX>XhPe5y-zEONY5MKGS0NHMWxfS@K}`@%V-JH_&eF|_+V>j= z3%CUHgMQ8**dx%;sXdE{e_ zcyR3NO_n?o^ejT{0;JJIr-7dU9*jDG8{+>ZdWFmf)eVwJUc~3OCktEU6|q|G#TulP|Hf=h87Tv zkC!S__Omb}j=c{wq(0Z^bUb)ix%9hIZu8k$^7c8cwjJ!B9)OsYQwk;$#B=TWT{5TBmA%De8c7$+#p+ z1L3j*YQo9m4HG7+DSiojpC$_Z%oH6H0l|ei4ktC?jP52D}++ zzRRgGIM!Kx;H}RGrAcP9m{oXXgKq45EP0W(DO{Pbk%r^tfLlPfS2&nUkO9cJ&B60} zH{s63LcIM{-#=$E2!_00ulRmt00zBw(FK&8-|58<#(B!+zWV+|IG62<$kvZ@u`Cc+ z949G>R-LCsk^@pWfFJn6Ru>ge{6>_o{uT`RaDO_Pu#n-oHs3m*s1-#%l=vkVEIO(5 z{QDRsnyE{1@6W@tLmZqi-v%R(3*hJ*r_IoWnf!oY{k|~GfZQV2U)9Wnj;0*!YaiF< zLb?dwW1S52xR@D6(;R+i2E`$cj| z$9);ZVuDTV0^w0ySz-Qx7>5MwmU;PQany&6!jXP|QOFL;mmq%pOmhP>eDn1XXHaQo zmN{2{ca6d&r#lz5G;aT*{UhK45zCXs1x+K&oU;72`laASp??M1LN+G$yHzl*@JA5$ zt4O!Z_s1#4G>9lPX`+x+^V|D$s`ksjF5A9lCz4oX-#*Cxz?GixbHMcS$x?Wfcbd%u z+yzN+3wF=%cPtY@)M5L}j+gm_6FI=gyszU;UInx%xdqAwY|p5hfACQDw!cZ`T@}j* z+iO)l9r;N;#B7zuXe^TtLG43R4F(3zW+!DjRVSD;+^cC1M1B_sztebNo2e8_^0=o| zoPBA4x@|pD+o6CBu`AOEvSA9uITtjN3c_M7G<;p4r+%-xBlzDd5J7i^$>`|v-B-2t z;8{HjJ(2YzUjQ)fl`46P??EzJAH%G^A4(UEX!A8_?Wqd>q4$~RzUSYzOA1v1ch}3; zmZ1~C)g){F;OM=_@$-I=yqqQfJ;JT(??BEOEX0uZCF(WcvS;s@{B=mn&^t`6Z{Gz% z_~H_&Vy|>?6CA*j0f7;jmDdwZHhlnSr|B|YzfjwEECZ-(;NZ~tOc z#lICr`I$3MNur!wq{mx39FE7pJ@{^P)8t!y1fJNKF-B;9!8cAonlt>&mgXKBhtSQOo@EyOke#bo zIx{{0OyTkF?iavKmS#Ji9%>C}cAHPFO9)kF&4u=Og47r70~mWW!J3;J`T$D36t$HLRTq znNu+>!k~_TuZFH;9!4FNz`q0NJ_Cwba%lbri(

    g~M?_*y*8IhSx_Sw-7A@E4MzGZ(e(!1v4Q}>piMgs|Wq*519V!FpzIc z5~E-4+;8O7 z__mmRMynp5h7Pg>lCN-Qm9!fEjBbB}No;!f-M0I=)4fmvkl>nmwO+D?sp})!CRX9= zk!$g;pN0(Tm-yiHYlC%59F1Gw-$q&6xWgHamcVeTACl{vnJ2Qm+OWRAb@0{c@ZfW3oDeKJtPm-$2G!=rzq;OtJ_ z@4}c{^Og3cGZ~%tiFs<($J0L5+QWI~ca6vDRghb8`}noKFi$o`Ba~DXHDa@(SlAak zE&Owb*_@^mP{`{2cydjx3ABduOEh%F=?XWp;e#ngU?JTDoaS~D8!gb&P3n~&?*_J1 z!DWE%b=vT$K)~rxRY9lyG9Chv-v`92*Cj}U3vYQvk%V(VzJ;4HebU#fl)Oa(2VDSu zSnNQnIyryiXMSJKv+>xANpp?@1pe=4!;pjH^IH};V<8NF(Ck$CoNiviqk6;%1Ku~U zw;@7LbX4(4UH=d?u!GQcMTYT$_G@3)&WZMwf#O25-Yd=JtpvVx--UnIvoiVao(qG% z9ws5TbSmScKA5iYq=NLSXCo-gu34ufY7FC3LEZg*UPzRC_8u7UK$7J0NE0*DjzsP3 z^Cn!JKO~l3qB!AC%;8aU!ybW$@CCp2i|FJGbXc zFL@WlH*P{AKzQhE+mo+j_FYz3-P@(voGs3PuvfTXkvp$UYIPxZ`)dJ+=&FT5l->+z z4qkH!I;NzuMQ-^N=`?Lga+h2TyL~e~L?aN)%1s&X$1v=E;1i$IT=3uqI2pwOS5JI& zVWwO3;*p_22+*q1drLMtuu2YLf!N)T{k~!;LNKJ>7`DOL>v49BM}z6?X8BsZqJJ*) zwSrL1n_u=5>_4Yx(vyxTNBrGnBraGQwC-f!&$@jLWLZhnBZ&qzfQNIEr-roS;qwK^lWW8kQR2NZRp=+XX_XsbSJo$QU~0wfcBa6P;$xjo6g+o2m6a_9=cTHNYT&%?G*E}Hu)2kk?=KRr!yV#Zbb z)x(BQBL=9$cUJLYw}OFhs1l@QD~QHr-e<_oGY@|&sNX9VMwIyCGe5HUk*`kS3$s=f z_F9?p{>Zn33`0Y8B$Dp(mv$ds?x`8jSkbpvSxYj6pis+~()Ft%>3%uCa{p;>`YgDd zl4%=>uHR%_i0hJ0_9^|DoWKoVoWv8JKehIvrm7ZmUDvZf7?C!0zOMOw_?RCiG3Z<( zXw$6hA#$kUT8^JoLd@H*Esr*ARGK3&5bNC>w=570riAl2Ml&eS1#Ic3 zHqYQ8i`xBw1G_?8_k{%8pZYquvzKzpzCP_qt?^|asIq$5Hc9+&q5jgDXzN;}<+cQ; zd|zl_%Q!bQ%wtVY{$k-)Gvj`NImu1_Gksi7na**)(h-tY*B9z5v;(#;Y?dVf{pMue zw-k7sPA$QQz~&y?(KJ+JHw$7wE{AHa*&)r)7UW!{PU$j zJ2ur0&*kwIPeCa$=Dl`L8Q*avKI(Qi&(ALxXXAEJs_$37q|;tiG|V#^-Gt3KIP>9o z{#db{D(J7qM<^8Zlt#{%ehx3D_ia;d^q=t|r<0s^G_btI`kn+j^&i^sa7Gj$*0PsU z9)Ob=uHF+R_+1^t92PIb=I}!AgmT$X5Fiuj0j*$!4ix!M6{9@m))64BIn1sMrwb>KjzUm(+B7E=b#N{)x zlH5w@+Y~B%;@5tbma2V-48Lb^uT(c_>0>(H(Ocl3Gm{!B>BQ&y+a4T4s00}d4p#NM z`}{T5F@3%~yV-Z|p)fS1gj{rpeNeqq>1OZ`qKJhqjo={mnXT|iGpxHMPw zona4r5;c1c+N{>MbuEUrvx&yYqYra%S@d`8Z$h30<8!=y2R&yZI|;7mUmo_J_%Of2 zVJ!Nb{sGfei1AsSypYX>w&s*eLlG4G*ckq@|y3o+`A4f_T49-xRW*F7{ra*U_k9|dV_Kz2SrAEKYeU>_b zCr_q0Mh=a(y9TQpI#fccypN<#{m|N=5nn0d8P3zm|KC#C*4|_gd|_LRLP9r!BQf!y zruTK<022A9;&|b3%JB(SPi4uZCf>T+x(_Y1&{SGVR# zx)l4Xi3q6}PI?hb|LJbTE~Lt)u-?ZG-YC9VIO*z&x*`rN+$B0I*)Pr^}HE8`(s;FzF6^MHUB1)nOu zfh;^^BLT`w<-I*HAkNUBL-P+qwfK}-*}f#8%o8$nxYs4!#^Qo+QTf*6oW5>61HZ-V z_XerVD@&m0P0#R6sCeSc9sN#K-ZH%}F9S?3@jMEFz6NuFUZ!FBry|fDPcg8c!Puxo zxl!SiZ}B!f(16JpKf>Bw#EsJ^M?z*4SnzM;9d!Z^CqC$99@`;d_r`7 z#q+IjU>hBikaV4P7{He=b$}u^`&yp|rD9GJ`z-Zdq(55sb!mix)r=%#J~HG0K8=f7-!bsiv*BHS;j>y@{rb^f58m2CM5)g3ckg_%;~*6lsBf`yJi-kc{iB{- zzJB8G_|s;5f0lkGmf7lF@oQGm@v=qI@$t+_nO}pC^1WF5tPsBy(5JzJ=z=Ng#GYqpeavqkiy7|cri)B?dZ z>#H}xP#a97m!ZH~_Z9Zx3vew{?poTOdOUoeAHj5SgfZ@{3WE8Y0?tX?wv^Q0EzooK zu};HNZz1D$ePUZuliN*GPHc8DUh|yoPjYOXs=J&S?-`x=?@w*0EP1SLg!BN;=Q^*i ztG7U0ltEbhBqjvZwYx{Pvq@4FJEE5tjv=4BGLLL)8&zY zz+62XChf!CehhIDEvQY>8rfTjTHo*q0aEw*d~0ZP9Hs zz?06?bB}FfQv2+CAv^A~O~1miTcIJD^YEn{Oy0=u&u2#F=_a7!^d@k`kXEQzLT=fQ z!23{a&5(2GZ~XNs1v};beLyZw1ZeVBy1gbqfzhWTZ!q{%_I!F)2h+(Y|KK*<)oS1+ zVqUt=uMTFhnr#KbRDIK}yXdYzz<>6Yphda^~QCM|61784YO`)Za zbYacBcweIWt=wvIRda98Vek^mY70DZR^cyC&qtNtp$!ao+^n*U5kraEKC6*S`1j2R z`&s78;-5Ezj$?zTpX6B6%M@`P|OUkNT4T$LdG<-^# z%O8PjKZ^H(nuzVX(cRfDk|WP;8QmP<2=-Y^8i2NpMI#b7>wlAh_K3F}noC?kf2Ds? zvvTno{=MHWp05SWH+1dZQ1oLaIjdq!l^nT0&u(D<^b^KfQBPzC4ir792V6nL>k|2a9Cgujb%IsP>AoGd`o>@lN6Ai5NKso;1=*5hF=Fiun9Y2Oc zf$NWL_Az5pcO6z_d%V2_d8x0&qPG{KXLaz&`R%N$4B({ z$z{s5^Jk`_9_f1j=9f8$BscwP7tqau*?fi*|DAepcDCT)GbKZv76mirE-%HtWUV(2 zgI|2!N{WNwj#sHI>HaRZ{7p4t_ncPM(H<~3V9qMbE2+Z~gfO-1Og`s_I5!Q_=Y^Qf zF1h${3JzcUyQ04i@B}*ZY-wB#^?S#h&J$5+ohAF>_jVvvr{jK4UkI}GNroNJ#Km+- ztS^Z6fJS4t4Df4^6rv~hVcwd{^pu?m6%h3I%pfEpG>QFCilMHsG?^xIEgWY+wXYq6 zNR$hk&gWLl?I)MtH>R&X?E| znxPxqk|AwS`k}W15)pNum@(}?-?4aV=-bJ1ZLPl8r)ECVm8z5gsvbq_uUT&(t8_lVz z9pBB0y2x-}j0b%7%jI)#24l2c)>L?5MRnh1NiwY)!0#OMHur$9yrQ-+R zY>5juI{Vmj?mX`u@sSv#&P9}<_HOO{PI>ht>?kZ*qP;FStCJt8d4As;LH^cPe3EB^ zeU}XApN#kLzZ+8<2Ak)}Ggc>*9+!cq%dh;HgGYY(w)?9z zrEksrzW4#Mz6#c>YM3%Ru@tv-UMDOv`{t*3A`-uz-vpLG(WkYA6}2DwMDP;h#Zx+X zWH@V}bDP`WEOCwUoNa%mYTW#8J7AsrmDFTC?<*Of;nI6lN-kAZo(}=oP3gl+w!gfr zgulC-CJ}MXqsN=uZ#eT{Nn z7zNCUkdBk!uHP&rCb~@?N2exlqY5<%AkbDGNvu!L6z}FnF0Sw>obYZaq;2#3-+rR|Ija+ z@0% ztcaaN+_O19tGHdd$Jd6ge?DdJofAy`TVLNUH`w8SNj2>S&Q4XN?-c1_N1O|puzum8Hv?1QPD z9T8<+`>Io&q=alw{0(yPNL;N+1ftlxo`=CzwV(KmEy{$VxClLWb`Z9y6P>(n_#p3E znayj}uA*Q_SLSQIj}g{1+~e|<#c#nem!Ffql)%G5F~rS9NZ8st{AQbcKok2!0$$qi z$M1c3=Dz$p3@FN`kLcMV=2p*U4Rn(Ux9-|!)zUhSh#vP#YJcRHcltEuYNkBon%q+o zr1|pxoZ<5Zdlu<_s{kndSeg45IN>4uYkP`P(pdv}Jx|+c3^$~-{6lN_Jb<%TxH;w^ zq&W5K{e6nJUvgv3#vl$9Jf>C!Z)OLuJ~kM@K-QdDqZF?ONkig!;Ju=58~)`yhQVhAtgG>g#7byp*7OCeknOx0JAt z;PW>2O$5Yx#353v0zh+*Ui&yo4(FBY=qVdR>J{72*Qj23zWLY3^Jm#-131wwW*o;$ z9dY?`qGQiiy>%V%t`ke+S<{aquLR+TuyS_8P` zlgLbvbC~6D6#_jwJ17?X;d~Y6QXDcFL>md|s^j)FiZPE_nB@TigBO);7pT7*AOlp$ zeAZe)wVlW6ss@H&?5EPB7M)1BxQE<`#zMU=vuDa7E=JPPf=tVh)Uo)a>_u_7ePI=# zqN&;G>4W2=4{3@7=EzbFJ0(xO6lyKjx zw@3K=2A%OK6KrAoE($E=+8KXKdSj&B7yORaSCJqrkWy#M{B?=B1s`hD{Z@eWl3IH!@ho zj{5n$RH}-zWQDaI*GWZmddYNV(e7~&sZ)@I-|n*?xYB5NUJlEE9x&Uwn6K=}!qI1K z&T&LwI2-6{I$K1%7i5{N#fQ+6YDMckPCFG$T`MqS4V>h~DktDX1&tg2?KE}}$~VnW ztPdsT?y@Amzm|m}dPRu)!uxIJ+CDm*BoB(|KO*@HB%~`^c#~9Nb#osHAHb+|>cf0g zY^vhC1S51%mdLTyW50pYuP}LB?(M#B6~FkFPr4l5i{me1_5sBjx4~PkN@22ptr?2; zmO$~CH-hugOy-6ADO?(`CX0l?@6)3q1`YmqY)A6zk-^fU-V-=FUR$te=JKR#3%Zzm zxVn@3cb%ESdr_@@sw#mRB$2vbPNRioEJyf z?uG58JyK<)7!5`0qgM9NKmN6$9Nm!G!w+!H0Mk#C*&qz`stIa$-PE=72Uo%JoAUh=@^VoRI*96bY%aJIzevlU4Dn=L zT~x2Xl9Hd!p7TncO{I%3HqehDipIZJw6dpb#*J8(h2CDL+btT;zu38y5V1hVBmBPWPUt@N~UC_cR@) z$OS%Yz7asTH$m@T8>E^&)kwb5QwOL3UznP1mVbOft>L{6Hug60fWT6vBVt3EZGXv? zH@gZ%xMq1802qu|EynHJr=h)l7S41{HoCs{;E?`#LVmr!PtTJ(LPZJbThS)45vQAn z{DNCoio1IOey7#=Kl~IJdlM55J+atZ&&V>>ic^iUBY7jP*&1GM4jwpBty* zb=qg8bfQ7Tf~j~e{ppM~sb^i7(=j9?Y2^Dfy&cNkhuxk#D%vaakm`N&G{`lv;J{mrXV!smW!gE+g5;sBaeqGEjREm}?V(2oN7a2tK|Q(0)(olnQ}#XduVY{*QdC7{~>oV>EICDRARr%;$~MvXwFR|!2!xnds2 zkJ-BD#&r)~9t;FUGi$X1Xk2EmhCK;fNdlYv{wffUz>XR3aC%t!544pNmdSCoE5l`^ zJC*s)kKKn`8GSi)4XZ`=N!E(WxgI z;>jO)=W=?W8WC3JNf1@3KLcq-aS1UGRvy3fAVV?ymVTNn5kuh>x}bN}T|0cxxW1o7 zSL}Ll)V^c6SIvItF5)Dt7yCiD@Tdx@2*1_;Gw7xM?$bVzF1p=E&<5uxb5=LM|2|vc zOJ#-Il80)n_j!RoESdQGI%D=QC^zK1B&reS1$GfYt;XG60P7SH7r)j}ufd9_Vi|yx^8P z#gve}z3T9=4ZIP}=Tb1korMBTz9SU$6+>zcwaB?y_{-Ul$O78$!MaYZbl*Vo#asT- zXx8Op|M+%<9zLs9sU0!N?=iNkZ7KISCykDX++J!N=DaLr?SdQ$zV!W92JJf;=yKrdTbRp^x)1& z%6V~qQN|THFOs_^?Lz}t&@!gBg=y`ZTT2IuD1EKkm%CzMcjx!}^w{_GX0=w5+oQx8 zxB_9HQ@B-7NBGc)$|XU&eG#1I>c|v_ulp#9Gq@t7e}`uOL}|%pc8zjq9!PgiJ$-P6 ztV1LH9&G_B)v?0edZm>KKV?zR^D~sZC(246*F8~e-NW{7zJBB)go$x|2F5MZkNffq z-=}ODPVrj-X)!Pk%>n#R0w^+NqXd}rcuWM4Ic2CpuDJ+g|IPe zkhun-Z?{lV9h%8u{ zK;9x&!6j?DGkLT5-5E~3hsRgNS#liEdyBqFr3NJ9>>tH6`|NvqO_kmdIJ`Z>%n2=tO2u)Lz3m#%h zJ;}t~z7iC5+oB&6H+?nvi-7B~;$1&CF$fP%F_u@j2Lk`-Pz4H~*-@B}i8x+Is@0TS zWBH9CEZ!|@u8CD)_Ul8{t(ZZNlGeyJv4WHMDjb}Xg~NDWqxHTdLaI5?wk4w?V>wj? zSNQ}%)0G+HS|A_$kUG^BhQ2V{KA8(sL|&gE`i9Bl7XuMj2`4!D`<+-P>(k^TGzX36 zUvFvptK#r9DBXa3;F(Pqj+lMYJd)qXhWDzo5px(xzx0YJg3diO<<(FR(7G~|I2elO z0=g>$F1PJ=h;ASc2Xr*UX>74^S{LQ?kSPWukoX)YnG0YJ9R|FW%_d55e8?+bqd0uX!FiNhZlua5j_sY9di)#tQ>bUsOJ z8Gn-9;j4??hbYViNz1OMf{XM-x6pkF8uP-4CP;bRVfW)8E(+{?%XCDfs z0jD1HnVEoL9Hx(y#*gw@>;qRlND2;2s;f6RqV3C2XG?cCn1GM;JCoW}U7RG|XJ|ME zpKRzUa2E@Km}sM>{c;p=VZ42J`h;l$P+rS1NT{;%EjSyi)Cj-ZsdZixU;7@)2k$*u zH5|(k9HV!(n;7j^V942}PS~q!A1B2&w>dI~kE;a-iITw?ICa)qKI7wo`rKsgG9LwJ zGJ>Gkgn`0Qq`M_IzERj$UCm(KID?;k0+dQU^IdjN|Bxo{3o(4PrQOrh_~M} zM8eBAhAVZTb|+}9?t6R^pHIz$?{C_^h*QBBz29xeUqp>dqxUtc`MIDikImEzL6plS zZgDp}+kCxq_Q4^_uDa);gpMO~OY|cEZWNB;yA{RmZ(Z`tk5t(AnbBf4G|J zb~0Yw00OyyXc3E2lB_3spZd>Z2 zyA>M6Wk-kmDaM)~_AgV9rr5b~Q}8@xU8%f%w#elWw&K%uO456L2=Q#= zx5ui0#|=CzSjv)x{|RM&1cu;+*TF283A6YKnK;%Z5cRw9v0Ic1M)tC5V0Yc_{Tx1u z(hw#?v%-z-QPu@=@~GV3U=M;XW8;g$QfCXKZ4T;n+GX&MJ#}8qj>oLUkGZ28J_A7( z&h3}ajh;xb8wE+t7o*jgl;P8uYs5HY2n?vIVmdrlq8~V>az&ntXz87j!E-Ae9SY1d zuHRM(qgC!@ou-EC;l|=v>eachFNpyn+qasF$f*sRh+g@HU+NzJJCJN#9L(8{m@^eR-aF^Y+=DhT3VsT6L7-`eoq;ZRR== z8D@umT`L*<(4#g&#lvUY7(vt+H}-gRmtoi+3?W6c+U)vpe1BO<^d*M&8NLgUgYg@x z*?8&q9^?#dfDTrL|17uP?R-Vw|IBhq^n3~vh>$l57dugPt>dOM#NRXI^4~q8_)O0G z`58`LW_gg!D`Wac=TzQ2QJ+4Y`}%TPq0!?SmCLU$OO@59>y=x+JC90C-e0+*zV!jb z#22FPinXuuK4l(62P&zSpU)QpaJLPz5-rH$57P_RGuvI7l*$`21G+(Y=>RP9a)3-3 zmOwE+ac}O8_KQA}Y90B{>^#nhG%QoJ`bI{TBuhYM*mOjQWqW7W zMrHPdTYr^Yh7!&{wGXU!u{!s#IP*AUdS=te`BGfZv0dN)?%sHoj z@;PR&Y`M7m5&&ZaL0}5th!Bp^V9XvpSi*YE3sw7Idi-hw;#=qP3fc9rzXk6Y%K{f= z;r2CN`+M70LZ#VPZXJ+Kcr4+7a6Wvws&uOU@LeY*_`aIMe#-j3;J&^zjxYmJKQ;8N zAchHxmi?x#r|>HE4w=B=BfR`W(z$l421Q}`FS+FQkwnQYA$+5d`z1ub{=D`X$qISxT?h#gF_j`uzsP5ass?hV-{UR4QvNIoy$5KXVs-RB~4Pg05mXJ+8pIsA% zPWP+$rs-*20a`~k%l0zg(Y?;=}TH2zjCOpOliSMM<%q`}8GD){naHlNwul!jLW_x7eb z@-?`(w~}9Z>nRNzMq}v)VO@0_M}H&h?^L9l?(fS3MXg|5sI1D2K0xF9S&M8*uLmW4 zZzwL1Y4F;=As*>!_``65gDWVTtChWwi*)eMM`+>*eL@_bqZEO+!M|L_7S_D~1}YWv z8qsG};3DFxw19+fuqj@-k)V=)#&fTerwEXzdve5rEJXyxZ+F=;iQ_x(wkU~@1-IN) zsU!DfzU7Ad{$V()$VL8c4C>TrDpW5gG54ay-SkWhkMU$^EY#yQljT zTO89)%Cb+Ym?N8;ebabfKl{`Y7v-Gu&~8wfU*Hb6AY@vs3sN)Z`Ag0jA}iU)=4}>0 zOQh}hP#cc3Ujx*3C$z*YNd0_0ym4ELi35KJx!j|e4^194?g)F{gn5V^HL)zbpHLM3 z)rL}C*y}+PqQ~}aPy-d%GkAY!kGOUdUrxCldAutNEaehr;O_BQLafpkw-Y zLK$Ududa}Gm`ZTk`qr(0^q9gwPP)8L1I@BuCC_%Cm-q?ZPfVPzCj$a6H=oJNEwzL_ zu+>he8emaLS9>q5g2+um<1>E3z)2>}Q+Z+xIKh5SBTS*EzaojJ_s8?ctwS_%0b4v% z&8h#Bu@WZ#Hm1JRrx+2HLSGpD6@2y1FNZ8M%7=5MpjqG6$Bg%s9w%amy(4S^Sy<4O1FP3T<7qpH7x8=zW+P zim*N?G)khj@jZdr#|Y}{P4;E*l6%0>v30iM$7zB;3C_I)t-+!nQ}6)6dtt2}2wGD4 z1R(<%1V>f!P{gsUzCqJF?^Y} z;O(iO-8Eb?z|Tmx1^f}%4Bnm^)|}e7_B1;mr@o4ao7aJMRI;*@u0L{@HKQ)2da7CCUgw4(w&0CKTq{*iKy(br^t z^}Q3bP9F#~Nqo;-l=P**?;+luE}Aad!|`xZim(U25(q#mFh1qgy7&2bSeWtAbmge< zB~;%@56(JT2^1n0_ZeErpEOiq$tf`@?9N%3rI+&Uv|UxEBBxxc>mH4&iE?JimrE9$+awsmAL0>zB&pNTU&+_!19+Q#Rk zv+-iNBY)=o6ph_@=e~KJKPB^lrZ3-bc#|Fc<4q4n7_kw*OZ?Ufzx0jIz%o?79nO|} zhLY!yFjirSEDL9aZSgPI@Q0$Rx#J`x8?b=yy9M*vKAt5ATY2F~Zt0>P#51do?Zahz z@~tg@5mc^jiV`><3Lt4|H^IgZgpxYF?OoiccuUdv{1;=PBCt^;j`LkAXL8Vg1J0Ww z{`ny8;*G;x_(#I+Z5@WRn9h{)YJWudT5Y)_neVkG_Tjgd&e1hor*b*vtlx~Fjd9P< z!C1&ZYQ^6o+$}fvH&OcWUL>D(Ejd3`v47|u#zljOjHe&Ied$`!MtJ7srTChb%N^gA ze0QIG=i9&Up1@WHtgjq$pR0vauso6FAYhhi#DJ3RXUH~u>1OH#m{hKMJVwhaq4Tbs z(vN#TOeIDii8v8Qtd-6qtC4T?IVLp;B2@A`{1m4@7bG2H34hS{1^(-#5;x4e-U73l zoB1L5^%g&sn8upRuir)L$Wf79PKjIG$R&t{rTt|$P^ag>rijm5eAI5gUzJSS3}j&h zr{=h9ceP`R=;avDVNTh?=>FN|dcF??pF4aJ z`(Va|9$JDH;+R~DtAjQ|dN@CWuKILkY`u>rjEs@nWL@YL#^IC%#nFbJQ?jMQblcN# z_?JUOUiWHKjSE+N)p;PWvVV+=Hl*(M$NFJy$>R!^?_ni^4fa+x<@QxUEWvM>%&qOD zv6NQD*@7pMJv!kT&u(7b%V@RP=Z1E8kT>@Fp?@}KZ5JeDr4p+m;16%p>$F?|r(nkq zOvIl8MQyt{tNvoGnD`)kQ*+03pX>$T#07C&lihp$1V6zF9cY|T@XjTb_razN$okLm z{LR!bL-Pj6z&cw7k1tTu*-; zR`=Vf&&=TJtGk>VQ#lv;*n^Sb;03KYB`Toj^$DR@2Ka9mKg9jyD1)ABuRQ}B8-nlk zy0w4phuf6_i0E24r(8bmVdlP&z{r@mr$?is8)NVP_2fZkXp^4~2|>_c`T^$vam$(m zKwyVbW3cYzmW1D<(fGcaX&5=q8we6jkWk3-vpSFSH0z|hE`gBoXMP^KI1;)5F>Q~} z_g}`oe<$8TJr^CrDwZ`WwB<|nhIa0?X~KDrTy8JfzkoDp8~eCJRx0fxi!3e1A;~qI zK&76aRQ)tecd>tjG>KiAr|ZdT)WJV@`sxR_6MRzD_{n4qJdrap7h?8!#y*r%>q6+Ye7=*qw?d9+B}Wm8igKT83wf<7*n zP<%>{b%6ET0FNPuUN89mik;3VnQ~~g+_~b^3T=@x79YgVvQsA;LZ&D(R#iRLy+iwU zfo)N<(4T5}ZciTHt>ozd*lc_Zu$yYIW>s8recxrKitrr}_O?4Id#>I4k&i>YhcIYK z(OgHf41Y5|{U|99m{)66nj7Q**wpJZnbw=q!ieGQR0Lec5h(HL_W&lwY42$Gc$>PY1vXD;R-N z{LJ2$K}dGrkVv!k2^3PZZVv!y_C02FZ@^P(h%`FByoV}m%FW=VM;_k{K<9IRVir;z zu;MEAuk>i$H)VKd@Z4SL`uyncwe=`_hN3AaAAnPR94PuoGc-X;ZIJnB*W`arWq<5L zZD?LWoa}#kl<*H?~r(C$du-*vb$JH?*#}O4O1(vLeU#Krxw#7|loP~h2acr9 zFkvU4v$lUHOuAA?CCw!}sL)ofqhDq)rpoSvHixy64DCBRt?BEoSxmK#k1!Ya>){Ju zMTd*Uvb}AQCJ}`tnD^#<3!_Ay#v9~b@A`gK+p+>(Eve2cPy{akxK28;PwDcT6%u{f zlN-tp(%d(EMz@F=I?q^EE`d>u$V3tJY9h{$#9fEmGQFk!q}w1Xs3oN0(*b_8+9hSL zr;gyJK5P%ntuJMQ_#X3{e*L~kbOSQjJXkiA{ExW}s&dALFe!1yuC2zuNuo$DTz+Sd z4&X`5={`e*o#b$2XKct*dn8h;{*Rbiyv>VB&&u+Mt~ZT8k84`S>dE1}{D6%3d)hyi zciz%oscgA8FHbsk=xs2tXuTzFMRXO=bQ4z~C7P zIcSMKv4vOW;hICsE=#A0P-{~|&@IuYgSf4WawHeFr zIavB(JDvZsUUnJk#OWGht;pQukRQ-kn?BptY z*7CUfFl{&(Hh4U(L}{5t_IzEOXz~F&gKG0m_2=r#-;OMZDd3z@DW2K`#?)2!GvUAE zJrz()q+?VyC?yyaHPK(vYDv_uXhXBKj=PEv{}um=FOKkcdD$4CJimV*$lvz^%jNOq z$DfgT2J3 zNqm00^P6jEi*c1p2Z7q=)Fs{&CBb#N1i6Nqo*#5G_RMYCV~g;o?e=JeGa5dW;a>A2 zFeO)19DjcklC_DNZrn_kd_{u#0v$gv4p@b^q6Na1rq>IOE-)Q-sde>BfCqGG)V>Wr zBHbkXnjmcvM3ndK6UG*^mUek&-!J`yfji3nUVkM@}8;+xN9hGX%ck!~UIZsnf&`V|sQ_)^`) zC1x)RWbT^2neezlI`XaHlxah3Gfd?ePDmv?c8S)F7YE*EF#MiJQ4P@jW7MDZXxrkt zr*e$v=^*!Mmhi9l$Qyd&pZ!>pq#lsU^V|f`JQuHCc-<9_I~qDu^C_un(FHTsg}Duv zbzFXj$C6-LjxjRqyF_F;jbLJ-_nmhDHl$yl5ysf%d;C%;9PHDjz$CubpRekGekw%h z@4k*?It*_6;543;^R^oFjg*g~gns(BXd?$8hP(BJLjAe0myKCJ_O)+xHHTns?lom+ z)xqY}^mNwF>F_<^P^5lBUYEFv=>QMwh1zuOX=bN~sH(LzyI3PAk1V~KEn0(F?@>el zd~Dx!ZPHnL9n;_CeWeQHm#fOChO#kz_eguvRZuMm3jIS2G@hj_*2`X{*=ZHhA^Hkn`Ha}wf#esdc%q(h@ z?2~NLJAa}sqBLNM*_vGUF#&dlSF_U^2|`S1blVEvGoSnHG83T$pTfoTKqcJvwO!B} zPKR+{cM9^0up9OT3kAcxvBxj*!To(5_V40$ZJ6e332iBATJ z#8lRYIR7LczvEBTJ44sR4Yr4ZenE;sp)?j|+IUci$c5v*E&r^!FYbBff0}e=ejfz< zgRe!EKOLYz@2eSP5kU~2bpd3ScJ^h-zSW^A8fbjqL(z^jnl&lRJ{P)IcZW>-o(gpr z>$m5mZC{IgIcK!7-+~V-K(U%H!i^$f@BCya4@3QdT#C~r@jm5%Yeb^$v+xOoRuwJ3 zR8<=qSu_zo;!LC-NT`elNU_s;e9tVT>*$%Msry;bzdnDC4EGB^Ff3w~$?p>J7n2_! zm#svfYU=uz>V7XEPh@aY$7>=eclX!w@o8wZ6zlp2+=KTi-abV&+BC7{HzaDZD`aF2 zq>ndEVvzCYx(dU={(W>E*Phhy)u^KnexG?sD}}qSb1wt=USEhkPWF0Ywr4|bC;Z(SHQ-DK3G$E9FLW9yFVam^!IW#}l3_GJF+ns|7o=)&C#T=`_vADFm! zUMH*bFz%Y`$$>tD`36mOn>Ir_G&w0v=A=Kx!@=%6P@U_o@zI6XF+B4`A8vZ>;dGnZ{+CtbTI8XsYMmLIwsSfs zw-<3^=_qKQLpzGm_nPb)cj@tf@yz?vC>?xsN%aS!A9o0W1|1MS?54md(U%fK3@MiH z$KUUxBq!t1c5`!c%6C0?CrgYU_94G=Uj#S%ky>Q7E=M`e>TDkOl*RFQZt?_y`{m0* zJLR75)A&MX0HpC6+!kNb)n-7XWFAN6DD#7yd*hpEey{v6UN0*;()>5~i0(}Jy#_cL zFfmTw!OB;OdCa%|6t55_nJTVn7Ti(L*uXp1X|mQtOGs+@OGC8i^7~+dy_Da{nf1UK zg~KO4v3&GYk&ZQCo&sZt{j0nq=88Y@bLRPHh(H?s%aGG_k$OC%Y`ZherTwC$E-8dT zut&Z~;jO&jqWbF=jE^&jLgw7E0dacEj_!X5-;y6EXOn5#8sD8DAy|h!?|TL!==O+p zUGORbPGB%|Uq@j)6o=>YeLmgZC%|7m=R0=-aI|z_gGoT=+uTr{?L-yohEG-(mK@?> zZ1)s=0oV$iO|)b!6!2C*I*FQo%WO93G)9SpjcdAFm)B z_+z_I&Gw%}D)wnvU$k-g{0R!3FxG}E5A^GLh?e=)1@p3l;l2A{z!KUFZrd|s3OL@~ z4yu6M!9Mw7XCm%Kg)IeGWs_QdyPvu1c--p!Plx13_($gD-9V{fm8;%o`JiNnqVwPA zDhIIHDMXUQJ>y8ueQ??@rr$QFr8Y>a==jNI2G|ebs^f%h?oC*yMMNm z2HTkB?!>N`v-bo5IW|Qo9zOT%%83t@^vj}BI*(m~rM&H90-tKepxn=4@jIa0kLC;i zQ&g96F|Xg#&nC@=rphpUa@^UDuR^f+a8Xa%+wbU) zG8J|Aj~b8n{?8{_8ME{IMZe*9l!gYXaEddwqw+;7o4c>XVIV%)@ZtRy!InOfJNi(2!8@{%gsOLpjIaO&);Kj6!e zxGjT44w8k+2YZy7Ju<-mR>_VX<6_a5pgrSE^Wt;O6iz#ZCrS%rFWEgqmE&A^K&2Va zTu;0gqm^|8h{-jzo6o6R_mxqGS8V{5-vV!Y=q&urxZxVkJvghc1@9`&_YO7%sL+;> z*RSzCmQ`4D4Zh0yHzt7CdJTCaarRVneVxrR1Ok5Fr*K9_3J<)6tnVjhFl|774(OZz zThSm!{-&d22rqWN4CTV|=>~YVCQe%|BtiEDG{?GNSAgZv$38+bmZEMnFa{f!>wR;0 z|HeO?TS*)6CPwop&v||6PH=d>-uwQx#{$*}x{;EeaA?R({z;6MM-!sM;QKA++mlQz zzb*NDM2xWLo9@eZecaVw;5KGp2pJ~~LwhcYJvQ>*T>8L1B^P^Bv~phorp|`WiYL1* zhbBBOW1E3UZ%WNKD6-KTuHTtGneyYu{Nl(=2%Kq&71u@vrLBCThbTUzAVKc+F{$+& zv$ku^{i=W>#$-Rd5A6jjnO?0^LoMlRjFZb13-RaANy(~sCDEXxff}I${0rl3lZCE8 z?|8Vkh)>U+Y4d5p_9A}cqCcNou4108gL5U>@xF*lFXTZW*EY%F8Z^l^WfZ9Gu2blT zZg`Ok735pCih;Fu&_S_B3d_FLjS7BLM^;DV34g*9O)i(;u-{!RLs{n!lwZ^JwYhn* zK~~DO=VN)av;73dC=|UiB!Bo%DhV0H6nY>~jee67{T;nW52;K8Gha!3s9z&WBJIr%HRSIzE&xN;?n*H|VYm!dD=SwK!YG*<*CikzI@FH6sl8JYp2 zQyFX{yz0L+RNG0Du_@f*nyu;jZ}T(u34s$YFkLM7hmUI+D_~sUVOL$MuXYg*^hlE$ zaalwws8@85ZF65Rw(#s89klru0st*|Z7%|8bm8Ojw08m$FaEF40Ip=^`^S3Rs1;g%R(&765DO^q)MOYBZ6KIKe2LHF#kTP~xaUHk z-ozO-PjhPi60&#sb5POpXF~tf=-hty8#!%1KVXJ!;SW&ayMEAxw7K7v=DPS#{Gf*D zYP|Jt&a1FYJ7s%pgXZmX$J5JS4BTul-}_EM2oAqA2$d0#6Aq3ei^`|ZHNi(HV)&}- z1ZSIQ-wUbXhO_Eyc&v{SJm97<_IX~1i{esd=6$j0Xk{YIQ*r);+aj5L5R*GMLB4k$ ztlv1{jFrrZ{yn)T_dqlITRCnxV`Rsk&H+5$@VFbC>GELN{a~dik5l`vFm(8C&%>(m z)aoSkUWx-%J-x|I%{G8FxKm}L`ub+!<63=BuLCqIbaMdicm&<>6;5m}?DzA_H_Mb` zCzs4%p$^o;2@{W$R9Tp)8}Z>kC-&hqF&fqA>7Bh9xkDH4?GM)l<0MXRdCR5Ok4geV z_t84<5uAf>EcMT~Nad3tTnRLY#|T+vvLZy{hbEjoXL&D8jo4QQ$z3EKKNz18kz$$@ zU~YPPjacX=$lturOBGUpKqHJlVr}mlfA76LtbD;@&?T=Qoo`-9kSG)z=fupjWpbQJ z380&V3=^{dTBkK=852Dityd2fe=KQu7(o+QW=-`4&&vLM4O^7Sq-${LLHi7q6pRgsLu z)DL{bewHBt3)->d2+f$}T)^{>D!IYFCw$IG^rH+hT`_?3gds%!^CF*kTbYWk=V4`0 zXPEM&K?z%tDBr8AKA-A|Bcso@JrO!?9;V&45>Q?}Ef`H41_SI|C*I2jt{eI}P_x+oj=jO+n z+(Q?h&tLG+gx-)+l8L_cY+eQ?Qxse}o~Gp2iPOttCOt$KT78srL6zLcdak9?ocjUMIo5D2VCgPGG*1AKcJTFYR3}53w5>0*E5&|uJh!mi8 zipO8Q-<^ODVW2;sk1$!1+WU}qXO#q$=Q!|&aQa}4E{Wpz_69*MHtWDs$5Vp!L9O4+ z^P+9&Nr7gW|M|BYeeT<-u2UXWhW2Kim&J<36FnH81B$rHKDc*>^K*R0XWm^YlZt0@ zj4(zj%(Kbsd$47Wa7r>x^Pis^V4&mNCxaK+(AcL4#7uDy-d^c(N0um!{=jcSr%2>F zCO&$l492^%0Q1;heP;7Vhnp)M&okt(m7ce3e&3!0W^sn4fe8Zf2J5i2>VJjBWDm$m zJ#BUQ*A-q0_oW{Er9AD~h{~kY$2)16XC8ZZEr&0XQL|n5vGxoF{(W%czHZyvT!DGb zG7oN#du>B0Nq0J<1&%-f1YP`tJCm^aMw1NEGrP+-Btex@g94Fozewdv_QCA=ApBv@ z+q)kU3pQs6bYQC)Er%mQBBil=2c8^wBn%~nA*d$wrWa!dh0ALZ9mq`iF0fUI;?#PO zmyTe+?sr3cfGuJ)!zvyYtlN?Xbrb(7zGh+|tKr+Y`qPk(eRIkjndt?#wo;}KyV~ZL z037-8+1}Th$|mBWk!(?+F|hTaakIGB2qT^Xy(JnSA73wPe7e@?509*%(e}s85j7hQD+Zg{oH?j$>Z7tna5F13pG3Q8_i8()0vdUlc4%{sjW=j>J| zmj3v-A?}U`7GT0%|9y^MQvPO03^d&WOBTEX`?fpZ;paJd-@XSApyP>d!D$wItA6?| zM;FDJqK*CZdmPea@wg9%rxd8~A8K5(b9#>_*S&A@;gp-+{d$&P>{-E-75XK2{8R^z z_`B-Cf2~`jv4`l^Gqf)}J@fe$IjvdiL?{k@2(@0cUd7E!%66m@l(}#UZ<2M4fwJ09 zXV}9t&uV7aq28_D6~KS!)tA6<)_E_-JiP$<96l2L!h&z#^DrW1p)^~1=HLDzw#1jY zGzU3Mya6M=z13i8fAR{#)E=k28;wpKo=%!$;cOHf26=!5g2 z-P0Ee2`tLDX1%H17XlA=joLxk(Ei{al-?q*^6$u^FNJSiN@ugXy`&~*$($?lD|yX+ zOpPGSr&20k1qe41EquLL<-`D9(Y%4Y8qbWAjKAm!K|s2HHmYjN5H3I8AAC2(=-p>v zpdH8YTWiq+{g~6R-q#}>c)T*{4kZR3<+a}i`Duw}AGeUS5YUSY`Z(`Blm^T84hF|> z3vX@wk>G318&{=NGd(hi;aSl?)Q!0t7^Tn3e|068UCB^-#O0wL0E4w067#&~5D-br z33@BNYh76|`ZSZL~gkf;J?iY^y4KzRZ$|KLPJl0z|E_QBItuEN6tRvsJ9nynM}h((dW_GjOS zqYiy*8hxVb+~ZF^#DDzdO>FdozR)TfQ}(@oF5Q8)RiqZQPd_2>RYqq5Aq`jGAFh2+ zZXp;Z{m60bdPD+dUu7`~J)jtO6cnJSw%yaspw^R6dIe8YMe!u!M~&EJ5tL4eJhE|n zu4bPN!a|sD3wIDO$z@Xw+QrPT`1Um#9DsX*EQZ_K2TvV_KCHbs8c)51mhXCZ>c)c# zUV-La!tTDamg*Ei%fqkDKk{SEulbAIgCMdU6RYVb1i06aApKP4p+cBj{X}=VN_D<5 zFvq~izEy61KmqJ@G`ge@HY>YXOq6<0ZFxV1GCR~KH~bjG2jhf6E-X9ef@WXH$6cNl z6Ow+RzR1grC{SXG{?fPuzAPj@j93poeo>zR3z~?4!;=)rg4nwUdLRqAxB6!(5flB5 zA+17JH(hnOUb1A6{tEhvbTpi2In zZm?f6SOHuKVRq_t%B;XT$|@)dQhS)8%rwvu^^!iv+DZN6{z=BF`p&*cto8MG?jV-L zb2T~`%#o)3r}HX!4ELU$ekdVY7H=+>9$pq?Glx?3{6k8pA+KTSOZ3>%aWY&P%gjYC zKR<4G29^1i{GJJ`CqK7*8Z+gUTXerTs+-K7d*SSvvF!~hI5^D#7cEd(&HJY=!r3EV z1sl!Y^75%hfGUib)4o|+g_P(p#>!QfW=!flYxsKP+%N}t=Zgcj7&fiTvUuFj7H|J- z<0*1WRCmDXcuF@>`>^4cBHbtM$A7BVV-GBV3JToy{5-osaGi)q`-S#ktnUC0ZE2V9 zGd=#9Zt&T}>-7-)~EG zR@v)UZ~=<*h-2%ND#2B*kVQIi`nm+VJWBDbu zUMCj2oz;avEiJi+$Zap11k>!YYssB&A^nB>RP;WeC$ipOd`|+bp5rS`a$YkcODkw6 zlcZ?+v~->1qmkt+DP1#&u`5&(8rviEc=p$oWUB8NsZ|75A(ew#tryBaafR??WX)#>;-1;XSuj%xI{bGFdU!Xufq#A5~!NhX8<+#NfY1cv49{^JS*k%@xW0``r{0r;^Bvwn-owg zeLB|-i6^-}9}du~K2HUfKWCVx+yR&a#-8`!*biB%6j_0fa0TM*p@-DUO+&-aa$ zvXGyhe8T%-5RXhzwaI<@m41ncEI*3dEHyni!U17-c6bzJ`44=wZtYxLo4v!3j}k5# z{mIfE31&%b%B=GFBwW!rd#VE6T+-ChTWh_?yCD|vMo+O7T||!lFXlHtgrJo3INP`X zNTGT5J$ajmO!)Otzy)&vH>AJb2vAmrQ@h`TY^Xwez#N3u+Jl`}0Pl@Gx_?a07nTN^ z_ewqVCs;G8ls+kAuqJ4W&=0-vVGh^;D2#c-1taA%TIe$uO|f8uKACpOpKH2LT!$!L zDAe9(;#ydZ;E=WaG=BAQ=4Oj-v=&HfgoB(pVz0)z z+}3)T_X#s_F{Y*{`8KDIU;74xi4_bCgo7{OdXX;YT)mg#Z;xvhFtI&k(j`B$;MbK) zR~T}M`<0TXgx<=qS6Gu7&JxKn9WxMLmU{k!fTGx zr6Tpk)fLkiE6MX4+I8{`gm&i`_|$9(-gQ!@(;}3Q%|{*G)a+$HEdL3vjj*uDhxBny zX}%lB-8%d@vGKoWsqJ#cuU-q?_C%ca0w!O{6G(uq+1cMfT&l<;(TIu#h?> ze*2MU=PlB5U2HyK>W|pIIK+r8q;~n5?(=7_{m`%Tr>ypy1;)J1m2}O1yD*|%V!gSC zsf+$G;8z>G_seCCblKD6*17ra+Tn>a`OzP*Q)|%(JuM2Yr*dOf?JT>&J8u(}*hBB% zWy<&?Qmijt7I&2#sx9d`39fgvp6=fSxJ+0rnq4cbFD$3P)f$=9Dj?Y1MC+p37Y#&! zR(lkbc4GTI8t_i<2WWRmWIp1{xhL5DeVocNKIeJIUXUx}1?UIG4X_jU0bjnH-8b3` zs%&H4Uwhczy?W$-Z^jYh@q8a%XY?nX6|8?9(aC=R02XKYFrEK^RKehZ@?5Tj*kZA% zAhxZ@7MesU*4$(SGZ1o4p$caBQR2O-rYBx|LLvO<&1aOKhZ7>c)@#3aK>0*&Vz9`a zUH;m@J!b+r<|usw9KK0wx6Gl+gwlU5V0p?u3tBJ$_ahKP`U^OK7K+%K4&vQ)`EBPb z1_i)W9Q?d|G0!OCG0a*RLqlg7?CaDP?t}e>Lff=(+mmmi;luBW4?O#L_usLJw#=9E z&ChO|UF{hun4S5ze<5Afi7*}H4w*8n>^VWxR|_aGtDp6}LL1I@`F<%{jk4jBH(HS4 zJ5_GQg|`8U=~$IVb?>La@>lX4css9d1d_QOJL9$SN`p&8{~h&hwSQ=ANR0TRm^FmP z8^X9h4KY_!`svya8~$vY4k9^eaol_le?R+xf0~l@ zwnxwZ!2d3@=gX&2AlTjJ!O7SB6?sYZ zF@O6^CB8#6_6`LOowmP#q1>II0JuwLW3C+WyxF^7WR^SjW8^gU6mPD`0<#ae-#L{ctBmh|4J-b_`^-aGz zTer)VisZ8)oe;)4MQ?poS$?P4Q6xV1{$9%7{NP_4A^fnoR*sGfD%tt=Gq{R>&jt0P zt`8$>&NdF9t#8k3=TTnqyE|Fs$mjMJwCYmCy!QqE@Dv}1IruTews^wH{8|UO-Q`76 zY%z8O`0DXq|A>pIE+a*3;3nM`xA^@LgQcO6_Uh16gULWXSA0=GrbWlh>ON(bL(^gT zqE5dD#z6&MV6Q)yj=&F3sksjWvU`XQ459EQ>XSA1lG#l>HV-bVgpoF=FWTdtUe8Ry zK8D9kDw!-X7EfknF1zLxD4XKS1Ld2XPPM(fkkvMST-9m?>8)~#Brzx!49)PG2>R1Y z&8{6~RBeUgP%iiaFve>k#6^of?{jvh5>RI7+wJ08HQ~eD`PJhbeGixPrp78w2XB_( zz&T7WyXUKU)_&wQVg;Up?v(CPI?V?g(O{3;|7_+zp!7pQ=jwsG}UOP#xdPUK(r zdF-PtgFkK%(VX;OeMbNQyfc3~2FC{rQ-wVA-{W!J81Ma2j1P1DTwTd%M^CvO zWYbAoD>29UW(dQl3O0wMF+NHh@CI(L#`5oOiQbKU>%?_Mua$@1tNZo9!diuU@Qg7ymBn{k-fW zZdapW{+uVD5&0aM#pwxz16mpmzfxvGtCTW6=D1$23%O4FDyP?Kwn6qmd$$og2W7s4jl)H7TfiK4SiZoJuOJil<7cWocudG7n_P z<>ImohwJ7SGb>wa@!kxuPyjv6neui>ji0W-fOnBk59>~LE^--~X>MF*sM>hjaI2g({vhY%mpxZ%Vy&(H| z*3gtSW&(Hqs82=%0c~HjfU-Rt(KiNWeyhn>qbn^6OMOX3D6JRSmQ%9EYQhRNdb5{$ zM$qJ5roeNTW1v3k()5{2fLl+2QHqm((3w)i$M^a*^*2n0ZZZ9PAFTUFd$DK>+YVAi z+(mMa4n41%KGE{EZ2eTRjjesk_ZK$0W@c|hl7{GLIt~<(j<<_A9wg|9)$2wmiqmL zX|;T#Cg5JINE{;b;9L}St;Fm6&d5oOr=Zf&FEJPj5kz{zPyh>#xB7FcpC|LtD$&nV z;H1TS2y=;daoQ$?r3g>(8ID;~OL<(WUK67|f3Y9Gi#~rVRtW;udY0j;YtUFMm+t$( zvRnmC$b5Vc+yHKQsp3EdCy*k|kXKo%hWE!`!6gdg;)pz$c)Hw}hH{P5MjWkCL$Xh5 zntS!v1G%sCNby8*@fXUq>ks#)bZp!`iyQaSm-=x)1AShxyq78^{t=2os0M#NK1A1L ziLPvH{p(e)=uNQf2JmO*Pa6Y=QY=%7GBbI*{~j!urtgjP4@YJ>g3;xM1f_9~_4sY{ zm?zo6Vf^)W$BDS}L0Yb9;i?1Z3_=U!O&|<%VP6Au)LZBrx}Q^Sm6;fd`moPKO{LAa^yhxZ;M;PZQ+a=A@(m+pfFY7}gYJoV*y)BkpO zkW-PfDwF#l7`Tx!0gr2m5OjOk({Q|8%SW~466<#>$6A;FE>&kbh8^?^u{0kZ`xx^}2 z#ciOr+lLeGOGq%QW_?iOzL^Zu?iVq3>{^Gwi`cFmqCGZwkB0M*u0nOvhU7i*s2}&~ zVIZ?&cG2ehy~8+9MMYP#4}DZ+KQ29g_tWvo6P-kU_(W5ufDS}b%VHvG(UvV84ffFf zh1$QGD{Xa7V~4qq4`PGn-umJgP^Ag4UM*H-^V;Ck_~4Ho@S*YYpDh{a;}y(dM8J z`|~ZlpUccrBYG2jc>A+kgKRbR#xRFII=>J}C`zh7zjp*5kI;Xavku;=mcE*+@>(M~ z@EjdhTQl{JS1^m)Cwaf$VnGC#Ec`LtvAcfM;!3}kv$PT&MI5uL%y21PR#~yGar7AG z%bv4PNDVy{5s;e{>bs80R*A|mo{RfXnVDf~e;fZMiih!G`rbBREZ+@Qa_-))7DIe_Hn=O`=H=qY>wjE{hS-FA} za)*zaw2|m|jP%oV8)8iZMy`ZC*M|<+x`&RZ&3~FP{#gT+_y9+G+Cz7o2jC3inv3H+zHQ>&nuK3UCCa^9vzL&IiHe8{tfi|eoU-aaqRh8D)N2- zY5pTZ8Yfqqtav;!Dy<*Xk5z$|dGJaY0iq2NA{=}N0Q7i-tnRB$0h7tFWVnawY?-rb zfLP0?rcl4#Xxi7Cco&sw9HzDlSNx=5wjIlxEff6#(Adqjn%2F3m0cA8$$_YhV({de z6_e@Vxh|c>G^Z7v1N#t0)Smb}e`h|3jn^r1lsmT%_j`o9 z=UHFyNlM*{l>}N~^O53zR4?8e<=A8f=-FBhA{T>xXz40`zbEqPK9qiJ2#wW$_lZkx`D{!OI-)8mvt?TbvV4ui=j3 z@t`BX)a2telHD>KIl_`T3vhFH< z5|28i?C?(FDFr_n5S()Fk&jX(U5II?&BRnE~Gpw0w zs=1fijGy;I1si~ucGGerzDC(=Pgiu;R9ZeYW9okJtCr-o8mHg6mo6cv&VKJEAdlAc z=@vU5qfD=0A!H9n_Es%x=ru&wLO5KC>F5tP`#B^L>qTj%x-yiL`m@c@C|YsmK}sSO zNucLff9?bu<>q)JN7~zYVKh`dfH%OA3_h9);%-JnD?Kh|ii=U&(&W z$qFWr{D@L40ud`eh70|LQ9~Hm53Eu*h`nxw=zo55I2u!{APTb>;{I3b%b; zz=N@FWnrC0V&NI(!4^;PL(m>-^F@F=Q{j=4`L=yEl|}g%rGH-%m+32eMLw&EGO8f( zD)~x(6q*t=?!$il!R9|FS$0vd?&tlR z0yNL=fid*R%sz{UDJm5(H6ntCNuKe9c;kls+`pmI!LL}F?y;3p`uyEO(hYL*$mHdO zx8{9wvBW*7e0{gK^Wx9zF7rbXK8KN(O{4ZF?0G-bP5vI|?cMPEQg9#V&iE>scx2G5 zt)1qt;2&7MndDN~i{y-7&hBk^s_)6e`4 zh^Q3f6h@#}D-LA7_|?HRQ|$o^m9?2fIx&>O(a|}?;d%AK<%mmdKMfs3Q`r_qcnI|j zC|=@rbf!Bn)Eim~UayC>^%s6#`^7VPyom4{#0EG&2;b27jA!P~x1=k}4Ss-;8qR#( zaev#EM4cNsTMRz<4R+Nv0d*%v=J)tpqy9%xcXsjRY8S2)& z;AdFv=$-LApyYum_TdL@`l{e$5UaVnJk%N@Vo=;`>fy(%m}bHO;CXvkK`*t_Xxj*F z;?%A~1#?=fw}N+4vWrXPR`)*BW2Ezg@aDJne$ENA?(8s;KP_F6?(jGm;iq*XCuT!v zK}sKO>43@gg_VhS_xIdg$ev7?04vOGQ-f3SK5VV5H_({W zO`t69a7L@%<9(twLqiuvYClP8n>XnBP_CY^FaEZU<^}Yp&+XX-X4@#ZR3%eS(>_@_ ztV-TJbD%|)uF)6w?B>n(g{R3K*m^t$oU`jeKVH;XB#Bxw3){#f12>xHm| z{zM433;&3m$$nrO6Q7}^O4dbt5Zhh%UN-oZm47AbEzAhpJJ4KQo?ow7cs}Uv(loj8 zfXkX)XXFyyzDzXcjCm$U%UNO=i~`-AK}Ia(Pq)s!9&!Op<3f)WKoliLd`oMX{eTq2 z32O*YB4JW4Gr}|Yas`e^iXpbJmRE>%F8D4V`q|G6-1Q%}RDw}oNV(-6C(5C_EyBs8-yClufJ7~@LLN7i^Wf$sTN-4UFPcNj2cEf)saLF%GuCFHow$5A|!RH6< z;qNOgxKX7f82#}dak^E+3S(S64SQg8_J5t5cCCqIeOvqfJJ=Tk;mke8!(=(Fb#3=% zs$#5YpU#wHydkz-63peLZqI!tb5JCOZkq7H74X*Ya!xpVt*J5 zjODw@x%OHt!p3Cot$01z#Grf~+H_LPm$a89)9D*r>vD5ri_*4uw0O~cn;+u6Vv2x8 z#RpnqaSZB?ec9ZHvkdesZtmE11aV>8G~|n_FV$=5mC89duH$D~Etc754?j{>c4km~ zDIV~Eoym`^p2SFs{bf6_(F(!l^I7>7>75oj>%qRUy5LOj-qM_#mGa%CNAsI$CQ|V% zs&VqoMrU|}?n+MWmFlNkocun9mc0)F#P3)^{^`7bN&MVe&vpb`_G~uJAY93zr`=*7 z%6sbt^jy1rf9#Xddh;sh6zE8ffX36#?`G{TPO~ z@D>zN)JEG$&mvt?GybVB-&%=c^Oho8AOIigP-o$P{ym7ouwhyFLcPiFqnsC-;N{=H<>iR|je~wl>>~L{epg2GoMI&pvq85oAE@6V z(4+0#ZiD%Xm!*Y&Zd|QH#v6Js$voiP6iF>Z6&STwpq;hz`it3Ic^2g%rH*#$wo7kI z5{m8ir?A|IQ93}b+3EI3#`<%FhnJM@OHWLQ;&^x`Q>kk2BT`$ycmjA$77$Fj)&9%Q z$rSt|e9F9456+vvkacLYZ&93yhv0j&aPZF1g0gL;f3Kv)erUeMnnYPQ3Ur~?=3O+R zvv8lh7vNp+k7j>%KP9NT54xZ0-$%>9oq~YA$7qMw4*qEOUK!yyUY^%be64S$_iRfx zPuc4tmGi#yR(~qbdY>w5Msx%t8BNx%_n|&!x{9Pg@$&hF4qBz}ON`ElHA+kR4U@|0 z=*aAwg}DlJ9IQ0F{iy6k*?+5%WFl|}pdR>^CxN?U85mR9WMZAs#LnV&jKv9AsdAym zB!~Ktx;&4~3-MF;1cJ_&dA(`Ma8{7dG>C^+fUmg{fXPakk3I6_t{cRw~m zaE+|{t$;`tzHK6LlD+yphwM-_h_N^Z1gkHX_PN){-gI(vE$R3N*qVPu27hMcfjX8=nnL+{@z8NO)E^@y0s|qjNx#a}q;0i7sDC=p_&OpS zVPRNZ({olC_+uOjv0j!?TUOv?f!`RKL6Jr zV{i7pKfdky$hjQdWyQO2ZBDH{si?6UNH@r9j|U+sFA2dO_AiZhRPtxhLHrk{@Ji%~ z*ZW-=hV}%|jl>9(W;Abc*X;!GHWw9}bu{M77@uhH43KdKa0UKYfzC60U0I`avr0wk z=)6p#JJ`mr4x*2~pXpoL!DSETnQ^o}eLygJWKVtY!!%2yFRqG0w&QPEsbYd<`_CZ( z6I`G96f^`+3SP4M6Wxq?7Aw@zhtpoQ2jCA}INx&(A1re7+e3c1pz%&^nZZCCmcGdu z=4Elbb7Jr!;sb~W7tWp1+kU07lI{iPn(O{&DYD8&( zKCA+&5>q*z<%KFY(!D&t%k44n0q0EDQh<0$@|8k*fs6{&oTE!azEV5(XY&R@sb|vp zWFB&Z?81%E8XgII0DM8dF%WtQDA8*lcCix19?+-{`=j_80h$yXK|5lW-KgcHa0gj#x z|LW|In~j%n$SNJQQ>OtZ){_v+8ZHA}5`xiAQ+hbPeL-eElt4igm zFH8O|b^<;NX82a!{z$c<^$Dn^Q<3Yzt^O@q8tNhH?~%TJIQyj8KF*KpO0IxW9{m*y zR`ItVqrJP{dRG(})urlDA0JfgGv2h1^MQY=&RA!Z=3w$hnu! zKHy1@_9Pnnq{RbF_DjF!;}_lmM+OxFFM0%lx(Gfl5xW7-mi(Z&@sm#1&&h*_W%u1~ zkHUoMUjp3Dg@9?VbTvvXI<~_C5%^Q~^Cd9+Ods1}&Vv8tVHatG!<4*ykicFA_kscQ9 z`)2}s(VKCP7ZiufD*1Go<3E}7*iTM&#I%|3yc_wTX=RDr_1|h`+X3NWJoQ`Nb@<^BR^$Loj`lx`<*9(gf7fEn)i#6#Ly{E#zf; z9<+VbU_bP$c5lw~Ht=5}8{>l+-A_Jj5aSBh6SPJ{Bkm7ag=_4cT}Cgj{?;W-FzM|z zY$CE_s1KbSV#?z}3k(|h^~eu#@iWp4yEnV_Y29+~eFK#T8cZ7+%>8M!A*(OR5FvkU zvndXyV}#|4_!y+s;e3V&_h?uRG-77S)nK7a{DW0Dntk z{fcq&U_8|Z)x)H`lt^>V?rL@+Yq_QJ>-`LjEmgL)#gba_YXhjFY({Po*0zo`D?YZ5 zoasgMp$bLs`z9AyTR+3jvvbqInC){PpBf3A_O0&P=_|23ppoPu%+CFNogpR@kKbR| z8!Ls;T0IU&0Ex;qeW$$=Y!oQI`yE^P2fzhB%ZxYSSbP&l@L@V>Ms2O#Ak7+c8Sb%? zizK>4lw-D#$ZfBiB-+pM9Hy=|$dPHCKQBAO7XE3S!^Wssp|GA0LhwhIE{Nq_#6c3Y;(+lW%Q(Kk5&5Uk~n^&~NPuCA7rLwv<(`o+`P9N^TZpS9N%Qf7}j$A%icQoqzi0fcMG2Re{- z8DHhKE-h~}<_A~N1I(qLf3Doir(>TScN~P*PZ~epeNB@qXQiCA%YAer0Q0yi6TYu- zQIDE^dVS~;062Ahz2y{`kNch#h@D-WAsXJ1l+KcJTcmq-sh_#^%!1|PI|u6xB4XI6 zz=~gng6PvP$J5Y8fUqYvU;GnLgMQk4vx2=vW6a2PI=$(y)aB5dkoIRn@jbh^Dr5h8 z&!owmfl_6WVu^k6aj@R9zv1V!2cAyT1I2rO$@ifjGdI&?i3(QcOg0GzMHQRF17&W1qVt;fCo3rgf0 zc`q!%U4G9w@GJ4SmzlZ=P_QRfhOggPzq8+so#MZy%LK3=9T^{qWBA_{Gny#wLeq+? zas#c6&4&nV;uOx=8|Lou8SfazZ4(b_bXS9Cd`_OqGI+G9U|?l(A)1E|K(x?kf<{gJ@p^Xz&Klu03J-8C{+pLp2lkR!R+be`VX!m{8tO z_u+MN@mHv{xaf-Nm*I} z9J+(g07y6TZ5#&WW0SjQP{Tv^$I?Ug*hL-D1llld=2xR zOKGcL9*bt7hx!D>jihR|m%(`UErpjkQ2Xsqin`Jl0rfKc7ls01YWobg+$4h=O>c6{Yx(({qW(J( zSoYIbJmMIvN>ZF;Cb--eFBX$Mg^S$lacV#IC8Rd$Mt55DE1~jOGytt8S+7h71$L6x zFV&8xiN&*_{G{LdMi&4Dy}c83mOL2K3`1Q+2r__%+Iw-~h1D(jO$33SE|iFxkT)61 zax6{@Z4Mw69kPdV0$b-X?x`gOa0ute!9exg{%lNR^zfM8<#ed7Z8vC^W0wlt*r1zt zIz98Rq)i%EF&p>detCVncvJq(tEAs`f?O#hqZt;64>LJ0P z7Y)b-Q<~S1v)DUa0#&P3oqb+Zlh@+4?`bae2wcZ~{=rYzK6JN>>?4t04{AfVHQIIX zJ!k6-`|cC-9QSnSP&D4}i8W zUU+d`=-=ake2~wMtuB-OPXMz@L{>k$;m%)H{O#NJ_DL5^G0+pq2rvEm&9BLoveB;j z)mXf|c;!HQUQiYtgPqF0wZx1%oV(kKODVpC_$R--MhU@wO7U1LG$~UR-)=q>Z~t)W zeseT0998`$_05Fj2+^w2I!Dv!>#L&ewFhfGrNtlZ1TN0Y29$m(mhpB)-9!4geAKVD z|EEFrq~F}R7@aFeZmKAQ*atS;$X|49 zenTB~C$4h|vV(2*)w^Wur=wJwdU$tZpI12!(gyZf{!B1!@`J8RWIygV^&q}E{d-&E zI3aCKOCpC2zlp>>gah3;-RE$T?9T|@`R;i21M=8L%69nhUcGJ!=bfFUCJko261g4p zyA6e?64b%Bgc{kr(seq-%_n!M7MkteRyUoa<7|9?;A;e26FtLQQ$IN{+S4i2jK>qc z8Ujy&LNn?;uH)F73Q7i>v$r-ItIQ2dkMvX_r zr;NSm?IqRuXj#sKROes!b3A#seJ#VBpaadn!KKh(c!il00-3*Cd4$B^HMqRa%aJHa zf(p)bPk&TAg!?0|DTC4e^ieazPfzb*6G}YzyLb{dPO6_}j0n-T)oD1-3VEiX$lTf9 zOS4`r)t~RshCal(*~c+S=+5=Nk5pMfvAiMQw}9i^Ghh}DlEg##4zEK}>6d+4o3(u@ z!5rp8JNn5Y3r~LVo~S#6thtm2ZYcHUV^|sIPw~`!0`vRh-~`-r>no9x(Wbbyx)VY+ z#|_I($?aqQVj-PNRoZPM05jvk42}|7nWjbD>nWbFPfoAji~bq1%b=Y`Y7cmGKzr*p zJ${NI?MaRGYrgV$1Yu-H(0!p=eh>E!st7fP+wFUG#W1?tI*snzHn0nnLj^yAcm%w# zXWex4UqAkFhhP?ZX;US#-oJO`AW;;{0t)8!z4IRGS=RMAM8`VLAsLj6&>l(3AFr+x z+FBgUPT=5|gK`Jm^Un8tb|5eC>nR@a9`Sv{{cg#rxVgjj&pk_xQPrK_@Q# zT8hy8D1NW*?Qcn-1+XEYt;o->GNgvDw|;WDc1ly@b%ui?CP}eiDHzvypUoHVDKA+MzW=ch1Tq z-fbb3+9_rrx!lXw@N~U~(962qoe5o7#shr})aO5W416dTq}fR86fSAchmt(;jADD7 z2rz!um$*kj>#P@A(nGxbD>~qQXNHFS=3c)p0}bZHhZs>w`CjbPrLu$AxWu1$ZL7(I zn$@dcC(>~{b6irXAC|-NA6nxgEWSeokD{H7R=bNc+fX^hK{B^$hyvYu47zsX&ldnTD zoh-jS9L_v=*UmyQYi2ETp8JBQyoo6rio?`KthQ`iJY zLH53-cUHMuX|HoeNP{ZVIov*?1xUbA_+&O$zYxIRAlG4=kT+%Ud^3-1L_+QglXvOV zh1{P*%BKPRs}PQY*XUiKws#MB=q)yT^{>_|$(wUcyp*;@=JUc(07Tzlx9Zsh!P=Uy zKpJ2UjNDXID2p2C8tU`C^$Nv%sm`?!l*`G(Q3eb|W&8C?l{!SwWr;3Zw%~6jwVqXh zJkZ){Ix3SV^EawOEvT6O48c^Vhvy}-l6k5B5X@^n z?4zpqv#>dr%phyP-gln}K$p8yQ|60(w$LB3E1RTQWv|;U+ehdSM(%IwAdHUcJt~cS z=xasm3sm`rdiZUiuU?2#02xMH!iJpR{Kf2NWG9 z^Wo}m$Zr(%k#_V>{fc`wR(uSl0A*t2Sg8}b=~0(hjLY}Cwa5oMMN!+E&MNaxb8BA-&|4k6^LE!x%mPzo_y+f} zyzapYrcDeiVSdy*O^bpmB64>-d>{6dw)h1KI3o19aQD=>A-NpV8t7W!J+{~%FZ&GB zh=3K&gy4owpB)$X5Z$Qh+9B}+gmD`C(vH8``-JY?4KE#YF|2hFBaXD{Ywj*8O?~gEp_swPG)~xA;D9NoKMO zo~u2yy3;X8GKQMneU?4oqQQ762#SWwE~D}0<~Yju)7eiDOqA+g>m#2EU3ibECvDQB zMjxqtPmH;H4J*uV&1v_0`vYPq)*hd`Zzk&rA0l-ZPax}!J$@l``Nvdd?O{q2!#(ME z3}XV>;F=F*k`c}q@;h3y2Pvvx8fKJ?jc-OL4O!?|7mLF%rfNay>BfVL!LD*AOllJO z-#fSy;BQhWKu3lI$bX=Gf0_V|qJ1-k97B}1H9bi~T^Ne!qP-XXO#YY+ErdHtM#-Mj z8a>UOj%eTzh^{l-!LG;K>TC&54{sR3VI5HXVo}^?>JQHe_Zy1rE;1QeJL*atzSGy%gz18w z4-Su?A_e@*Yk~)8F%3O@pZ#U8;){I*8g^>n-uc1TzeC4y{;-hY`=Ve9zbjUSCp*Q^ z(er_`QHUt-8&l}3syVr}_0UlFXQ+$yjYt{IteFnl10;aoW&6;>gJza22#gD-CFD`qkAxrlYXWC_ z%17d{ANm5Fn2=qC^wP8dgA5&d%ucQO+F02&fI=kk{*(Vm!$hefBEsg)B6kkXYF?MFFO}VT=}$Z zi1|M3tFUSfbQ1QSOaksjDfRX{zM;Fkeh&g%6QS~V;rC^Gg4#wNZJZdZh1&Zz2UnsI z=Gsro7lHr)llIDFXPl_0t|*2b(tOi_1ga2GL|@Ko9-7zH4NAB_{x3`UHvP_nKpzL7 zqth*-nezd9ZRqz#VRL@JBFeqsJJv&_{jvgeblXW|@Diu{-&1a%&qh1bO~?8$Wy8fI~Au>-@H4kT^$>DSxGmO z(Qd*se$;=9eBkoZeaM>%>Sfm05Fd&cbQ>&3Ts38c&MvfEf6D19OubSZzBN}abr{Z9 zqEZ-S+2R8+5Tf%+cr@mHKxUADy2{ss8-m7&|MSoR0Kf?pKUxCa1%KzE7fS5*1`i#Xuz^D|`E;Ty z92WvQd)>+*J{J4gWb#LEtt0J8)BSx_RS=z3s7FP0e7U@=lEZWCn-SK|AMZms#J#*~ zf5I~E)lR>Q0|7+!R|#>l*Bh21J$`JoqLFrt zG-e;c!pigW*;!vviQ=x)!7Te;;((uR>xr)*!JmvwpHCH>nCucP#KSuVUJF_8ZJ)4g z`?O!Ry=?g4*dK?K?eLUCp~>*dORClBs$Ux-e+el%PD)6iz8^wQAry5{KI~JN25rTc zpw;ImG<;eI&XMT?oj|kQw)WH2+xg*bsp?|1E5z|LY=e5)ycJFWLYa0Vol)bP6ZFrA z$9X91VZ+3yga_KuxJsx(SvdR!}V!!QGyW8{u)QX!>PayiY;!UG3aj8=_qvnPX2%@Q7XKS_vEhqn&AE*v{!(A zx~#qKKG2}OSF8>C3rr*^)!W;tN(EJP$j=uHo@pZavUmx(xoEsnxr@{3kiPC;&K&Pn z@x4`c(q2q*UOj{MuGce4ICM~_@T+PXEpf^Ac@LB?RbiRiwf8fH>+zkPR%+GF^?5p#gxNWu4!QSdqz89teJl96ud(zsMtp3!X5%%qIEXCbcS)M(ikjbN|o~DS0lg4=dHaRdfE#y=U znzep8cZH4Q`=&uIMhe3}3=H(GV|3hQ%o?|0@d!MlVy~SPehvw(S_0WtnIcwR-qC24 zE8*f`#k^d5{Ysv1U0T~zy;4*iRhoo)&=gt&8ILrz?$08hfKEm&gafY2HXKvEMv+!d%O>08Meb zT)ZAJhD7mpD}(i$lG&*VBc5tp!+-ylzU$y7mg{ajGx4XNboh=zi-40R5qsL@0%PB$?`&RRC~AnDchP_2vV%Lm+=pi_hHjo4ri&ojOuT2s@Svyi^K2@O;7VJc zq%uFRC^m1$J%PbNo6jAN8;rzVGZRTC9EgnPvwJu2CYl}!e>?nMwn;w)C?mIB^#{`x zm27$O$35t@-w&LJup9h-Rfta*-%yQnuuvDX(%Qo0%Dh&)kocSPQs+l-uINxLIt4x2ym=J1w}sG9zLDA>i6}Mk84o7 z;)(demK?57UUUX&=)qstyMIdnDf)){;&PTw?%|^;EAfe$ing!s?AgKJ`SrX#jn!3J zB(B$Rk%Ei(W>H&yalSlo!Hj{h!E&wrMyB~L{;v*!Dn-lvA4A@FcrUl(H8X|l3~a{(|K$cK(?g~h|?#xErp63 zBg`ZekdMa60zx9~Ju{`~brG9W>%d+2Q$>XBJF#)~`E;A?&t2WJyEI;(5_rM%%ejQ` z7-^2)b{as=EXwpSvew<3B7m6CMFi~pHMGl`l_|X_to_< zsk5vkpGSt|G+$sH$LlZeo|am}H6blgR-;(j_ovdQYDZoF#Ch9yD_=?Z*6PO^)os(K zMP1p)_sSoZQtr1m&6=#X5Aome4s5lCj`X)98ww6fOt)Z#{CymE1f>xpLuRG#SdG=SH+2i?ixcg*g?DMdn^?>Q22nhc%yt9uq5`XltfPLN^Gt;cUX{cD% ztbk9aS@#RLl;78PI;9i>BcC1e0e1mYJyQ^7R_n)y=kdwt9%3F6*)gE9>2LMrcuv`e z@X56D;_T8&0+S%Rtwdoj`W0!cosWCMW%cB>B%?zf__(+t%UM5NgyDRwQXVtD=#u>X z0d3oRm*|CyqLjVN>};rGL71mQ2qBW(0pu(!i1~{X`5@{S4GHsKr+KAK%W6UTI^d1T zgf`N8n)xe?6lx(x)dFS&mzPZV_q#3k!uw$}J8xpo#ZD%xo8RsZK~p_=nfmo)sfUWP z_87FmtzDm9%p99mxi)RJ)*J&u7UN(;y#Jy({nbO+k0{%D3$L&WL{k87@G}0YH;x{$ zYRqCeAcPgSM>#np3WLAKw?s^2?wlIO=Z76S0CsR2MQCzy-S_sf^TIP1qx{K^ib}}M zI#ELWyizS5n9UJyA{g0X;2VeARSa)%xsnkwlC&FcsT-2rJS4nAV1M{Qq!ZwE_q>{N z02?oy!?Oiz9{PkBoDU#hPy+D=-Tv7e9E@C)_RPvfR5@R9}I?1l_qG+&9BZ z$8O`Wu+S6RFVO6BdoJl@w?Fr!$Q!-d>C4}8J6j-)dK7=~{sdt3+5FyV70fbEmg?fY9$TqM^(WY0KLY5h0nrT^wBwOHE;WT z>W$Bi%K7!t=RM1qh~W+Sk5;npj#RTQv}r&-|FYJh<=PMEp`1pCrDuD?=hm=ln?kg& zSE3X$v=@1sOQg99$-Pi5HD*q<2fIoI@_Zun`kUAfW($7Yu_mCZP#gz)?Sv=i>lWi- zFoMqV0rZjG3(8+ZdA~nk8O33F@|_37bHwN3!6>NvLm+MkMbhue@d6jpP+WgHE}{5o zQ<=Qcms(cr{aQeQnxbC36{#M-coE-@%NTvi6sEEOg0Ft%J5udRa`|nW9NU+}=E?iVExnfPhn zuM-zmRnO1zP$|?3asE#~J_O=vP&BO?x9}%90R%YNkMH%6>n^S;m`Te{8{KEr1JMgd zG)KcVQo;;?Hn-6&6)JAIihg4tQHm{2iXBu)AeJflWnq zIxu))ZKA(Q-@>*cmZZLRdsjE&th?WLSs4d5oAoC0CMrIKjCAS#$_4@X{@t4QgSf$ExdG18tO`P`7 zp&ZsBJKtm;_AUDim_kr18&NA_8|@h^Fz+V0&*g=-;eOud2sZE*^ooCHg5NXl>yEYP z9~%}YkaKt*T1zB*eoWw)P0X`oW&?SJE(l2g&e_2;kLS+dMV?^3QKE+8zK?1uo%}pS z^iUuefjxFoQx=Cm%@nAaz7n0+x?(%_en%vi`vc;m9HDgEjkpbrWn+nUt8Um%v6bc% zb=6fO@9G10LaeF+*#7E$1h{qGZ<8b0`%K%%->)#PV{~&Kd!{d!+8xT-r(=x{^$*G* zzyo!R@HoX=nm*IG3M^=4G!ozae6&2MKFQQ6K8sSFdV_vm9n<<02TOT=mh&&$K2K#= z1A{{S1YjlHKqlvW7(dU5{=v^rJeCOb6lE0CADuiuy?j-B*~}((RxW1f^H|xZhYSFJ zdf*Y?)0D8F`*AXNSzTp%zhCxb_>uV}O`2LGQpmg7ekAo*jI-&Awb1=zG4ulypu+V{ z?J}hh;PQt$65$`qsiGA%+IBrgRGX69^BCkRKPIiOT>P@&F9kgHf zN&3%~twRm56CY;UVghyatv`CUjdzt`i?fE-SrhVa*@u0S znU%-|tIgQ@M9xXQ+7UsoPmfAvh5I<((n%yUX=JD7Voc}x%X*yG`81b#LA@aVfL?ekKz621{<5Z%uW| zkEjPgGLyMU3^AI3T2O26uuoc{4+SYPr=uTN6k5^W>?hpvYIUFzyQ=zp-HDZ~6i&vZ zO2qF_zrBm@qhhyu?JcdC@|^a?MVSWjB#Mi$QeI?GdpQDF>ZND2^y&0k?c4p~k}$#^ z+gQ(;6%O8Gkm7(Vd6l6%%$(u!Q4i@cbS!YxlbP( z++y-XECc)w1Uy-jUuM-bV)sZDoj5&-XSB!n^-|D&qurOIb{49krJ|2%5_{3MTl?=IKb@Mr|gK9`uL7ki7yQcvZEXD-RCcqARNO!ofxh znEP|^w}z|cVGyR+{#02Tw8($%WYgm$;w;bVG zSarb|oCz{kSB-o4v2Re_-)N0cc>OvXf8Y9~%&;NYFNNz(OmRWl6%5)#O`$o#0BqHl zw0(-n)IU#F0quhJHN6kz0~R%%?EdLWJ0RJI?rAl-d4nGF+E)=|-69aNrLX!6f-bzB zj@;L7&-*<-P`_{NBNTMxl#0pu3PJ|;7P+PYZ1H^Yhb@&l=$1RSfT9=B~ef+35ZL4+z&}~X%FKB zyRjgeg6`(hfGH7b^UZ~k`LE(X;_Bg^>><8HceCHPa{>3uraGL5MEl#-$4S$hPY|qKE zyKH-57)4<*M^}?*e*jTS$0^PXfHQN6?lvLS#Ke->krdQ=4r-wzbf2a zk$4__(ovRC15WZs9co&Kq0u;Bb=b_?AW}lx&B>$57Kb-)n;p*kU=t*kz)uuFUb~5h za$KebF!tY`*T7r`cU~c2UW`JEyk76rowi*Dc*pJnZFh*KhUxCK@h3iPQ8w~0kA%n7 zJ`v2syO2WR1i+2`rTX;Ve-tMP(T8+?Qe8iL@o1rhvGHy8yY}MrGz39rRtdF(jg@G<$|SWwQn;+jyZR(w|F;S*+<$l_DxGtNrf_SfKlv#E2z)O4+-VF< zWZv0S(`S*dkam9!ZAqS%*8#*Sm1JJ7V0Qg%-}@v^BuUW@tZTohkHRCpCO`O?W)P* zZ-s-ftG&;2u}EDqo~xg?PfK3S;_rbc2&2nl{#8?V_T@}k25s<7n_u2<7Q>4Bsf^5l z^HFJrKf48%jD>no&Sj86=3+ngia&3D`6KG_GwKqMiNj0PiQ+d+itbhPV}9hXx+ucd z|K%>QZBLq#yFMga@mKr3L>V)E^F0JTfW#Q-{Wr$g4U!b{X@Ra!!NM-Pij{qQFg%Am z2;x4qdOysHIqVHXu{wfb2G%~dxas1x9ZOi&QWB511_^)VVOe?};0m+h$#HW1!oC!} z?0EtOs_FGY)8;NA_|)(OvoZhH*Rca>0h06%rN1FwD3zg^mFqs(E4%C;FywxpmaThu zO)hY{&#uxTEcM~kHh{;MW_`vbjD%dc4;}*iNj|+lM?#-&@$vTMhgo^Ddm!lQ?8v}3 z!u84rb_dX>eu^dw0_$~pJ)XuixRzI$O)ZD{CcxQA%{1Nr%tv}~*%|$74mSqqOZwbzJk3O04`AO{ieB=%VY_g!` zn?#R0H;DIUc_~2zN`&;TtZ$aASN)b8pVgUuDT?~9d)VXpg+D^?1%G{u3UIngaDvM2 zhS7rM9CO6@hJLAsJWX8o(0#TnJAeIkWMO=31AkQCHdrOl5jn!=deQi-y(xQE)isZ{ zdk8}IX2>@k_$U~7KZb4kL;FiS`8Wk9=FQx+&jS3cMxSP9Ty09uW?T9M5p$YIu6se; zP~|b9DLlC^q#DuqitiLR2rE_4JYtC_jJ+0QAKi2L*#j!1bvHRfZmp;TWMA6LKA$ig zsT0eZY2Z8rveX&yF>^tBh&)4>%%2^WcZN~`T)FALXdDw31)+Ope`SHA;~NcNE-f0% z!4Ed~BYYA$993oBbA$^31^~PGEBm$h9N_PVc&?Oi%&1F$OwRkmZnSk4#lX%p9h4GI zP1ZAWU=?LV`)?}WD%daVPunzNtcZi~v~$ofjFNllOfsEb^!G;G%gr%_Fp)+=21S-1eX*C@{KO6Rm z1PWRBJ1%cMdmD@K@=Et}pwMUg$<+RY;fIi>=t&tV-N63?_OUt;tT($7qd_GJ?#Q8| zaNV=`KF(mKQd4R93rJo}PXRZKL>=$1KWc4W!$H`qx*|hmvq}Hpz4i?t zzYu@P?x7(v?kf!p)_n~u5~8y_&-|qCHBr3&>-00sS?SsJ34{TV#6|+$mh#tDP__D& zrv345`JMls!#yYS{D?P3442*eLMc7iq*IkI0Q;Ig4w$V)?F-qX+wBoA4_bOA@F@58 z?ZU+w5{G`z+Tk0*?DAqv9;E+!fJ(A$em8Rj)ovCo(d)y7PBOMAjKLA;xtBi)HDfBe zG<98X@usZYp^KQ#exX7pU?w6RvC^MsTD|?o^36Q+xR{a5JdRj9m`53Efb#buYlXvU zIdDK&m8**xpStKN6tBD|5EOtdCi~NRnN#1Li3><;g+)`RPlbdR-|0Q^+pmTi9&X4- zMH7z!m2V%u(+jhe;>i(FS&;m=7jP{w5B62>@stjGZjBBwH*b9J{+ zem|4|bR^~GwFH073S-TArGt7h5`%JsC@htOD21e4&GxAwT_B@G=dZSj^Xjt-sJOEF zzTTUHgGd-cDI(&*NCviu`@{nK`H8Uz2cCj_eJB%?b0L2@QettPk}<26BkL-J_9w%i zQ)$vakeC5HgzODEdeYiyb>}>l3&ao?QT$aEeTY8(e1b{6>{00Nr+1*YO)XI2M6Yb4 zX9qKRvBbwCi@c{pKmM{0w+Mk3THk~#*X+Z3F7QgjVLFX$yxwg0M_;Y>8C)IY_(Fmv z%gfOeqZcXUt7(>6Z~NJH0f_X)w#Fa1`l~B=+FezP;z}UNtLs!54%lC{o+_yRAD-`?pRFd;SD&EdKtQVmtea$n+2Mn^ zH=e_^%rI^9u(zS8NP%LxS#TaNke})3XCDH38|vbJC!!aYt z_LNo9NJX$T&11KGE1YzGQ4o5FzM0V%jxvMlTH%78l&n5cBDv0Q_rUr;<*r5A=_|mu z=5e@v0@o@{=fhb+{z(r+rkd9Wq&}CVydm9C$S~_-(j~iBjw1Q~0GxH(83mFwsnf># zrwIzRAfk!aM&V`%DvfFj5HKRZ)@(wztRon3R*o5wSJ73Zi2;+hxId7V%s5TEN&ZI# z@c7j#soVJ?3WJ6Jj;EUf>jQiWn(U$b*%wtNKNnDk2*!_c<rUY*CH;_*jlFWz43z5FD%&sbiIOM8s%{bo@&TM&<0VKun~Vku-SAuPJUu8WTfwR)`F4=MQ(%gsU{y%D4Yo)5qb{=@xuqX`rA3#ca1*fwr%Rg+;aeN z+vfxPoRrJ1s)nX&v|inr$H9TAYGYQ7=F3z`=_U#&AHQDD&0XH2B`z2h!(+#aT3 zBzZ9)Zr;0{EHjtv0J+xN5?Yu{4vw3;?OP(9J#2K0~` z7c5^*oD!nfS4CN3KLq}-4bXrloWb(BZkbNv@z`x;8C?6f@U55IWY91VmJxW@_!8z6 zK9NjTm=}!fHn+44ngp&uPoPF_d7G24uOE^Dr7S}-YPbdq5cCYbhtK!QVdZ~>VZza9 zzuBLe)dUab^V|y*P&dds}tb7{J!p4=%)FH;o zJY)6^q@d>je{_|?I<5-uNqM-FL-9N)6Y#(HRU!HVQ+7~8lMeQeDNCVT_te-7hMk%y z9)y5nS7k3AWd}TXy;#t<{ja2>m|Xw*DR-Hk6uRq<(&O&7egI~ zy;G}lvGoSqfvc<$9Gd#$iRhjZOGXWj%|TnvSr!K4PuA69@@#!ez7CTKM5KH#IocMF@HPkw z{2FgqRYJNhfckL0@et3UvY%3hFRxlEiajtC1Dx4<7(bF?>cAso>-`JvRyJzdm!%#B zI3s(%KjEq0>ouNj6=Vr$KJ2M3>WHuN9-)t~XE|FRJoBP&n#0-X^X*ldfr_jk_{$!ImLAe{avqYtVo)C^&3+FhENfI?*39_`_k} zkh=Mbmt$>Sqh`2`e~XSFy@MfTgV920Bzr z?=KmH>&rDg9`$b|*O|nL{Sm3qy*%st!yzd36$?`A2|vcKf;4o$*bDi3W%u^Jzg{Tw zQoXbT^lHNJXCH^^qQq)twH$;KUG24VCAUg@_|Uc{^0+N-8i@wYrK>tFotJfK;q;d%~f* z?^vYkI8_-e+KB``4W*X3kC^t=bOVIxIL5~N$LvF^E>~R-?B{4mQg}uwZ5ZsqmK2%- zh!IV@l7f@;J?@w=q$m~@+j5_S;}_(fVW7(hay#rH2JHFcxrV2Ftsm`|n(MG3@uyQl zl%s@dGbE7C&>kBb@~S=AA}R0@2p__O$<;|dNwZ`ac#ni~fUZi-SGC@aCpm+9slI+g zCfJ(xi{>pt?AbP`h_6*xCUlgbI-+Xl%e0)Y#nHzKNV|QC1!P=R7=)8Av;HGIk5^N; zu{X{c-~h7j)#Xq)>yX*WjzPIVy&#FtN#VKm7V_^e)DraZ7asR*j;pZT zmcw*v50cm|R;zpQRSXk9g?;E9vWjr5KoQLPO)L#_io^)d{qQz|@U>DDT#H!+zMo8sTDYM8M&?^~hCWg`0 z3;z??=%ecX?yCVOUk-H|5i&*a9L z(as(>025?u!cI|^P3y8=lgHZd)Sc3X@G=X};S9gp7k9Jw`LXD$I{Ik8uVuyfld4w< zv+=L!`uL6)!ER$WF#T zZf2C6PgZoxF7Xc%_e`IpcNY8Z2}66o=j>Fp)aL#kKgI-D<$CK`{o+*|*t4uc{Aw<} z8g=;0VX*SC|vej*$*`*z;(|);p*XD#&;$pqaD& z)>G*`=i?LoBftoW97NW2hS%19Ed~k@T6_NF51&qXvbq&C&UE4lso0=Dnh z%hf1z`3vkDvA2ojD?l>))F!)`>e|=*bfB-zH4Lu8UQMvph^20u{j#4{-BGnC(NUQf zZB{iumUU|BBgwU~(&r9n%1+G0Zua+?HD37v3SvZB+oFnrsH~Gw;mYZ@o+rP{owB3X5rdanyOR{&& zfXB}9h2cKXz=L2NukZ&7`vLIdj}G$|E-Z7mj}c9d`?$}L)`%4KY-dlgyZcR+wkiqT zYT(Jv8JxWI1-iH#v*>H)FrypBm-IXjk013}1$b|}UrP$Ivw4mH3}8;a=d@mCa263A z+Oib&Pq@G~xOMi#oOFMhSMpDHzpZO)6Xr`jne-oV_U*+^(wS-&UmyS$J%h+!AJ_0z zcEmn)v#e!rAa4p1=YQBjze1|6QE&{yyMlDIH5Xx(%-<`zLVE1WEWb=hNr#qx$Io@o z+fL&1>PoMSeUwJ5F;8c{Q1<(%hCK83*5mfT8TGO=GLU|`3tsdp-`Bx z;IO*K5fbwKw}foMH)+C@-8}4hrQ}rLL+mzh@_mx}*J(Wh{qcO8kF!{mAcx`&TZhcZ ziCd2abbA`W+*My|p@H!XaBJiVjK%#N*596|y-6>7Pp{E+FV3e1VyC)z>mKd$IJAl2 zg8L``N%gV}Ek(JbrD>?KrS8y#3Do-CD_6oSTIv^w4;w-d{IRwMJ-aSj_;5|{3TY7sxxUSU5JY;AWY0Bu8R{WbQ|J(oN&O2dTUgF7$Li`fU z^=%X!JfrXdomgCdkbv&sWT}LeEZICXM?AtquFw_ZEX#FXR!9BblgUeiTEwM^pU;4f z_Fcy21?3Q}U-~_1g9=R@7{}l&`k)7#EJ!JPE}D?kLx2MTwB5Le7m9>=B8cX)Cry`rl;z5B*7?Bna+qQU0vqF)@|z)uBJ76@BToZ=AAI6J(g zMLZBfq}eC_{+GmGY)4&e!)sal?CDPrAA%Idw_115-Dv{xTdh)#9J#~36loCv=3jgZ zy)%$kA~8xpvc6Xd=7(1)MidR6$vG__aRHjB~Cx`$fRz@m(cLe;nh07 zmGx@P&?Y)U7>bpOP_dyav_e|vx8E xr!e?4|V#)iFRg;}hD>)%*Rt9F+r`V`*1- z3tuP5YRk9}rR9Yj?opMj5KG zBS+Oh1sYu6qJl0$hz0M9FW@{r$J3u1blyK_LD(OpW*2u9@5KXLMuc8W+t&F!oGwCq za5mnyppO9Y6%hWs^UJ|ZB|VS4|Gs~sA9)CsJ!F`~B(8>IF z&+=bj#-GIb3Hd?5LnbI1j|$-HcEW9EJISg$Sh_O~d<=|tB7J0SOB)n$K~V`C{VU`>0#)YQ`L*?yn$>dX^2pF$mPPtjpGOJ8{+RbIC8MJ9|+GN-1pitfUbzFbUvve=_~g!uwW?u^?(E)7t=lJ0dz$6 zEiRgu@>3U}I(XSKP|+b*MBkv7MK!pJuIUYBlyGe#;_wI~Her!K7m#@#UwQo*IC?}m za36?zD#2z6a(|_Me7;Z5AyEYK+%D);w6>7t;7^SD?=~M9=rRx?o^z4gli>XeI9*-y zDm`i^ab)V`Dxac0=dYSfw=Xr=wvmAYV*JAJhX&h4r_uilAO`w4htFy|o~7lPLW+0h zM$xezs;o2hb1d&KjaK`cfX?NyT$p;cSJS!13_Z~u3pJ7$14Pbi59v`2Z?oQdDpf81 z%BV1|#8Y9A|9t)cAqu=8W*6-OTUwRTBV{q^@?)To@QoO$C_Fn7IWT|b7-AC*4 zaECKtlMcJNr;T%BuP)i>Q>^a?=(6PT!yEgs^6<=xJf$(WQvbv;$GKugFdq4t(2WTU z@e_Gh$_9cSU%X7kDRts`?$X21DgvoAjh<>>LegN`Sn@R04g7=c6QbQ%s9MI|2uIzWqvb8gzQ`(KgYG2=5P}n&S2R2l%wef)G zADJoTi?=wu5x>vz-I3T276HejRUx1>4c*uuEnU8O%`rFwmD0#5e^lGshtrWwzp1IP zbu=KHiz!U!)3FX)&X);f7YUlF&h>F$Lz|i9b8FZy60*noy^YnI&eadwv*n-L zpLlAPLvs+wYWobSMo<<+u%XBtnqKH-&r&Pg$QfVX$3FUv-^;Tz32OnJBwWhu_e(c) zZX4DwzArJ^P@!b5`oQRSn4JMX6TQ66zf;f>YmfoHzekjvZcq4HV(Uk-BEeKW4z4Bu z!5eoUh*-Lg9^I;#dq2BXI300QzN)w8F`zOG?JEc~F)18fABw2uN8SkL9|;VT5O1ZJ zO9VH5KUN+Rf|B}8me;N}y~|ciuk2pUIZYjfe+22)oz+OUJ~|9fnf6KLhkzPiA1Eg5 z*{ma}+1Ybp4jK?L#I*4erh%=Z(zJU)`+fDl+*wNaX_iD`F5hpnT^9ED*2dB! zTiPs2g;oSeR~Ho81oYVGn@76sbqMJd{704Py5r*pMe~>hk zY1)TuINyCPK}OFd(Pb&?@btCbiMBNs^j#YnbOyUbA#;AXOf?4V;RJI-LjF|ThihTp zz3(x)KdL~975tw3?CbZ{RF}Ux_(z?UT@OY6b1o4^Lv-e|%fI)jgJ2oqOP ztz=YoA~>p6&tdWywK;_i5(W`&s~?eyvU<)yA9`X9?bFg}9M1jZ>2hs9=YU|sV{|H) z+0>u8r7BJZlQ?|T45><;FG>d8F&=j0dwQVs{r5CwK9rqrc76|Ej!G5LI-kqesa1^U z*U9C6>_j3uS|J!RP^{H5rH0=+l+?L9caEUC^t_lyD7lYq!Z0_2ZoRZU*uJL_P9n|1 z`64q~LcKF83qQkd{wvcZQk{2e+65GsbAsNeJPO1VMnoeevCu8oeJ~0#_oZA5@}rh; z;0O=Fv9mB2%2IGP{rkhZXpwLYzGR8c`&%uXZ+I7FGs$>^+he?Xw-!0(p3oXpj)D27 zQV|LG#$gw647Jb;-l^qJ$YkZ09c8f~0P501dMP`$3@Ae8dk$I41<_&?zJXMI4#FNc zyeX+(>*bUjHT-435OO=8*~Ii#qPjvYdC_1;#~slz>F+6jk6Y}gBxU8U**xZwZ1Rf zJpkIC+kECa@c8Gwa&RRu4E-cDR92Z(iRd&zm;O89O@u z0iEr!+f$TJIDEDqhJmE$utRUp}YfzI>?u;|`PYC6$KMFJ- z)LrxJlkn|ol-=FZH+pmDKEIE?Zk2PKI@3=%&7~U@ff@c1ZfRlNdbTdM_)&n>whjy# zlLFi>97)soT%q{~bQ@7?Ix8p8qa+3%Jb~h`PNOzZM--HNpLwsS2CDOUefTJ^+^s9T zxMhw7lAL%uIiP}r9jaHmX@YAvm52<1>xO+?H^Tcg?32RvY@O7zY(&@lVd9=-Cc3_dhYN8t z;pMm&goa-ElsQ`+6qG6ScG-LzD4-dIXs4LQ{t6nZ&t#7^7vBLhODg|n(!n9ruKn*>)R|l=Hxu?;2`zoaEs#d&qxQU zov7C1gny_;k}O4Bv$R_Wn1$ey_oZz3JmkZAv7W?d$Xu_4{|fJ}(d+tYE;fXrFG2PE z{FaGf`PNpGAVuEj0M+iCfq!B=EMPz;mmU-OQJUYO`U8}FnY*7#hr{K*ukZg>mXbr< za%r(B$a#J?9M|j;J?MaJMCVyGX{6VSg0DgJ(5RBTAE|8wNf()Wm=h+zYF)lH!02D7 znO@#u=q7JN7N|BzM{Dh*AKC?ap`VBNjHg~UKipFq^_>nxRr_c;fl zo&Apvx{kj%O|Cq+${<|<*>0DgTd)3kc$xPPuX~@A&(zohe?=zxQ@!G2NPqwfA|djLqe@>OgShzH1&lw#)JMq^a}IxzdYl0*t0@DvS@lDx-&x zv_QlX=SKrP9&_Q;i>yfZS)2=cTyBH-+v*Dgv7~4LhsORMSa8>FUx1N+ktH^J84n6U zm&rTOU(g~R^DWw^Y_uNre7Z$GRMdk3))NFQQt!S*kp+8>gEOErb#*W2jy-!3U z)VD52Vx(XD$`7LtZ&mEEi}F*s8(9IY^{3wXV(rl>`3JVS2{zl-8b|y7>?Q1!Ouw!Y z$no~puWzBPw*>&rs6#>fu7AXBJ^-0(IV1ai9ag<{(HZq8ICLJ zx3cU?k4**^6$u#IwMt0dp=(LK-b>x+?LKh|K-|Wxi+d)r+OR({qRhIw1GTu#N~TRq zXbf!UnC}{n;=M^W!+RQXbttd=Bk%H%_5f!S7dcEoO|WdUvXAhA>nZn1^itMld&P78 z`Lp?H52s5KO$54?pWjEhmUcOXqo&$tET1P>*)b4W!~%bP%WPCm_nnC))+NfMB^F3! z2{?`}8(+41C9e9~FH%-8o_JRMz~d6e@WatTUp?FBjo<^6q5Nx(fb z@=PT}t6p{3k5?hpJ#XDeyAQG^G&o$emYKzGZqF(>Gdy%|311n9-J{Sz8=sG1zVg%d zIK9Hof)atnBIx(0{1+!@Lh8a!XFj)N`r}~>OT-zRzF$&RoSed(i9_-H za|^Y~5F&0YvBW|n_?Lavw5hgZ4*CIfz6Z#7XG-X2LJFvKGpw`6&!;kgEynrMaze6) zwbSNXqiSALI2s8bKy4kHcn^a}ZDo8Zdj2Pc z@&zKoCYv#&vk zgF%RAL43{kL*rzzZJBaM!ade4(7qJ&x8QR?4IVNSn1oJ~%@(ELpYRJCskSNpI&$es z{%){G!PbA`rn|}yf}s4Eub~DH?R_`=hy{$?(Xk}a^i}V2;kw}E%74{{i}}Jx;1ltD zxw6CX>SdWT!U&$!^zfDP;ZY}mY>wpq0YA*ZF+#6%D0IL5)++s_2VdJ~#LJl?UXjcv zo}Q^v1ohwsuuOK3DJi-MxJG$-$1t@!CHq$9Yeo@g9xZQueV_XP@;WVD+R-Y(nvZBea^_VZkWl>U$ zT)w)(`h>|P*l#N0dqg?GXtppSEcdA~NEY!izyvM8N|3G@Vg_N+LM-CW5YrVt>GLlXl|)DnNW@DP)J14PRu24d)Ne*e0Mt6@~0 zN+1qAR>gCIMLLl+YW=b2buSX_xqopB#xlObG9SNdBy%$^|<@e0x92-rZ6A{GbzHM;I>b=-rcm5Eo^3j5n^!gIV9BJiEa z?=6ou{R4l2-=sZWv{xS~+RxVU)1MpxCZhfHgtKb8e$wTb=PyDN5e0F0VKSP60Q>6= zVM$eNKs1Bv-uL+0pA%?bn4>ThZRgY!4o$2E@4Fpq#E({;C9Ucz0^$;!ng|wK&3;~R z`p?T&-901%+ccJh$1Fb-G^TT)_9_V{HSH=nqId#MMw!axwPwrdp>Ze)p(gKV#{r(1 zEB6VVS8Xn-rc(6l%sZzwlaIo=I6)2H()S?oI0XY3uh^IR>#co)blWmA^`rQb*Xl^8 zdklpl19d=no$kw=)D0w!;J`y&rQ>v!-aLd>FM$sCcfGi%A45LZ7eFVmCsWp-&REfQ z5sWwG8hR)6NL+E@8E!m`%094iw571+nYJ7JMScqmUHCA|T8la4c7+2XbdWI;WUno! z!<{|AGwc&SC2Ef`P}%=pRnu_m_g>^l&;nt9lLSyFKa5cP8x~siZ}BSpJn=)Zz;R(* z$%$+4F)3;oS-^NF-f4?J4|yH?*E2EQ_ugvG7K%`X)=!?gmD^Z_VPG0)J{)aSUILbP zV+-?)SoW@T5KqNM2)1kWUd8h3{bDY`fn$BEHuD-aHa<7KxTGKXZSd{bDqdh?iCJTq z_XyHg?K!-g!u#WX;r7Z}YqJN8)4gto>z9aNYg>Jvb7`H{Q2795pHq-h*;6pNF$o?^ zr}#L!%kA4OVAR31CnXU7K8V zcz{Uz{UHmJf9*bvy@9dCyLK3GS$saK_wR!;?0yw})mo|S8Nxg~31aVf2JhT_k~R_- z8L;c7KiXkmM{^y(GrS_<)*8FVnmjj4`#`07Q@(^TB*T z>HB)p#qc`P_b`13FW(vAKl~w=aM`robPOJmOPPG>Qz=tlf0e>7Qa3RKU5_#jBODAL zuMoT6=qmg8B{&z+uPJTtBRg$qV}F`sZit=5ceOdb|ZrQ<{ps9+tYr6>gzSQA|0LgHKzEGk5g`xfkM{ET%PxA>aX(o zoSuv}S`PpXPK)nqe%MFJRx8spYlmRtZo&)FkPOkl0ph4<67l_;-=O6}Dv|DmHl*xc zTg3)JJf<3t`qRPvl4M9fBWs^R`w|sGiBu;4i9O z6;CWah1lDJRs9yYcYk{~`b>n22Uor-lc45+FTJ&W{9+s#ke-Lx@4bARERC0XeI{PR z$@#5U){bBe&p|muVw@x}Nmm<4{pL7BU=H==q=;yVOgCHGXMim=w%g(M6?$9oCVW9X z#@PJ^mfL0~XP6bmGOJmR_$XKJn4yKKzob{#(^k$qn$_7PRV(GF50K z-0jx2ED#-&01CIl%yE-uBMe8cmPtJAF+S7y^KzZna-Gd+mn|3JL$?P2+3ymX`c?%( zh{%1mw*zW!fV4qmsFagnfQw(#^Hxd^7T$ux`MxKW!Z8{J%X>|SeO0oQT~sX&banmr z#esPKT7o3vY33Jsg#HU*2^BM)pBa~>X~my*4fUTYXOqovFPwwuMhv6eL~k3WC7nj0 z$~~MJOM$Rm63*p)Q(G|Seb_VpdO|Jss)g!q^Sghjb@n99=ROk_4A3g4{sDRW>VR60 zb{KT(3EXE=!qIqC;}pbh_FS?o@QQIar0BCYw8Glzv}f!1(exExuBfG7){&u~vyVNO zp>rA}^=IUdmIJJIPxks)dC@lSpdt zW@4Zmb-1_y_Q3e5m%0pI{ z&CEpRD$S((nHjf0{w5^GQ&k#p2$rJZ#eh~Xbv-CT7!)NtL=YqrV<>a5)Bf|YK9yxC*#3ZbhRCy3Mz55P3` z{LMl`xndwoxi{haQ+Q{%9$@UY6Cnq7IY<2I4n#A!S4}S$0y1}kXg36Dk?mOGSGMzu zm`;#1;7czL!PDf)fjbgUW|hhMSET86p$umN0nvFE*SCu?w-F8f^>L43?9cW_a_2Ay+>4U)@^>uE@+8K!^F$g_<5^BoB% zIrl*z>AzRWM0Ha(OG^tD5Yr?lc$}(1dxUoRzRM_;zARVvcw)SG@D2`-r+a|yJ4W=L zytm=kb{1}Z+$K|fTu7i|sD{SV0%UY^CqAefnX-i}bS0g~0;9j-R(y z`se|W*Z4^ImKQiu)f6d~zvYj64r9%O}7I}i6HNZ!(!ggSvEQ6KJErAr`ab(s#R%&9` zpB-EU@F**KPfL8+%65WRyIM{c9Xak-H+{+^LgD_V=n5iGBw(CZ z8ejEXes`$0T@QkBv{m?IET1#IAIWYJbg}uHkk|=hgN*)?J147$PL{Eyf6KNg)`rfH#zP|H1YNab=3%|+8;wd7-UjB zWth4Z4#q&p3Sy>sdJD_^6d-{ic1fOQ)u1NZYe)%&n(Imr>nx-!1uLmy4FqC-_1gDB zTvFu=iF~2Le37>Z#`2?mC-&i{@gUL|k!C#7=QTD?4`|&o)qU8*do-Te*8t}|8u1B= z0-|)}a9@KfAOg;VT!|7Z)#nqkjei5nl?4Vs${=SUy>y9ZSk7Q4CvPjVTl#+FPy~?L zX&1BPLpm=Lvl3Kd(!OgwGuCClhXna#;H!O?kKC}W`&o)Q#{p=ZF)IfHHSY?{YS3sf z4=W$a57qilKpmSLIv?;gUz6V>((;4;kj)v&w=D|Uj#_^1l0c28bzYftI_Xc$rHyb? zdgkknZ@7xkXIPi>?E7I7XydJKI!+6iNbAHB46pMMJ-U3wnb^nR^uA6%|JG0sC}197 z_u-lJ3)YcHRmJD=Q3rnoeR;yxp8|M&>s5Mb*ren%oL!)JR6FC0Nv>Hh)PS&QcQX~) zJo~5mr>7Kp5gIHlHLGtrW{pmi#XW9m(%J7Ns`D(W?_~CtDITaiiF(C!@M}~M`<;D8 zI(<8;H~WG7r&Lk@xt`QC=Yyh-x63s6GY!2Gg>cc!gQD&^0q;}cI+aaBWc}UTBms1G z0k$-wse~DOToT?6)O{RE$`#<;@1^8hvKkJzfU@D@#wedN%mc!q{nFL}7S0eehi^_!V9BV(G9t|;#R>p3D98NlvJsY$JCd*I`-pLEYFBzPv zM;D>?BG(xh%df|wtoJkY4Cyi3t@<~ z#k44@UieT~6Vts%{%HGS)^J|9Iq%DZOTTbSS>p5E3!t!kKBldf&T+Hu45AKDN=Bo} zBP_gRV~Qp~n>Gm#DpsbY@eEb{8$Sjw4M5_wf}xR?7Sg}PstAugAoxlO6-8kwFT7~w z)%ckXx8{f<@qXpZt0KSy6#upf=`z=xnU^r1VyNB<%BtPXr;&3I7ER%)_fncqHIt)Wqxs+%B4W0-WX(CMpF4P4 zyxUdpf@;H~5zm|ti2;3=!=*FJ_10<7+zGM$BW2qFE(vCja4jpIazyc_v9JJ%}pZ0#ceMBS7fVizVag zpOpv~Sr1wLdC);I;x}nZ>Qx*3BPt`}`&*TdC!So<*1BWsjNIgTHgkq-$5VRZ5}fM8 z4v{6iL6wENi+2hTNHJ;4baRG3+x=zWX?hcXG`RGpQ+QLx_a^d!YX62Dqbl-p!TF3i zfSzdG>mapd^kvV6y?BKduf5KDMng_}lBd>?MO41~{u`wJSE7+m(3&0YfnQxL+J|M9QJ%tANH*Xv)$B9oTL-_P=%-Q zDJxj#q6=5SzsCHgK3h~__GFu^Cz@M8M7!*wzVgjhqLlGh%m6$tUm_N}_e6j8>;LBMB{;t%25l+qx%`NU7n!d%|8-FK07%B{NF+P*l#e06VeUhkza_q@h`2~RW?Qq1SJP6_C z)INbHfWCkIM@ni`p&74449Tg$SCZdRG*{&U#F?xqSc33feO;>U!Vd z&-8oCg6HvQoB!^`r2D3DDRv75nKFnesIystt|){q_-zk;^?f}D)7IWUrpls#CR#Tt zHvACvuj%P&-{A%qSEOzcw~l+#%MiXV9J@=E_pyL(Wu7k3`l8U(b3Mwv%dQPsGKf7M zW_`-tBGG;;cMyvU(1>W(yRa?6?60EXvmWQ%A zhx)6Qzym#AE`t@ec5{r+jcr|G1@5R@h%K+O&IRRntRacnsTBXGE4maqdrG{>JN;IQ z^e7HG(wesH(Oh}uUD7LN zh_}ey)q%8K-N2N_K<8aoVB&D<`n$b!FYTIgZvXoT5WUd{^L(AHliZyWx!4ETS9cES z@h*9v7nP`H=kjm}f&j9<7V`#na?s^xcSE0iA0XlFW=kdgj&^fiS-b@dWmx6pph(f6 zvGza}gt-TX3J0<-K2w=Fyc~~eNUtl!b|tTlAYOf6K8(ygG=jA03GbL&3FhLps0dGp z+Y=9!W*n(J88vAqYpg$ixf=Jmz)5QSC(mZ~+xc@DtmS=jnDoVDg;_OCaz|zS)xk)M z?vAT%@vgiV3vikz(jw;TdQ(ya8`@}9Chpe2dtO&-GVkQ&Xc^@j4!jZ=4wGsbP-a|b zHd(nAWbdupezzLmrYuc+@z1EGmQQE{!elEWZ<8Pe`ZUCF9|X2>jN6(W9-#BJ%v4K$ zMXg?2j1k28K1vS*o{Qz}w-NH{&)*P3mUzz@a=o-C7!w&eOy`4RdN)nNfPOSvIOsQ; zy!}QVL-wS5@VXw|3duaY_j&GK5%~jhm6ufa4%?SIdN<-5iT3w>LIpdBwu~Wuxyv-$ zDO#oefNR)Pq7L9eU&!-*Nhb$2F?peDuxqcpaOe1$YQRK4$?zKx?zd-Inw+^L)63T3 z1dU~`*l+6i&XwVKG_9wme{nhT9*0^0VzbMpz1v>(?*VVbXER-CbAdO`*PF(H+ zRtDlR|CG1oWI7|7yRal0$-s^%;{4{!2JJZyhhR0cN_al{q*hOD4mbwoK1}`N@ zuiRZ1j!V>Q?GyQjGIE8Y;RQ&}FA8GXKRsIJs=q@puJviv6S5jDdD~zwfI;p^IhjFV zkh_CNJBz+Jc^BI^>!!bsG7}s?b=%iQZLN^>qKI!cf>(H!rPY}v~U!Z;q-Gm zEiYvS)(^#V{hivAJn}*j;MjI?I=5T<-k-!Po17G8yfhyuTS3Fjtpd5PZ9Q`FCRzUV zslD@%fc$TO!TrkAV9#?r;y9B*bh}!2z}TbFRG*=a1rgcD?!MMRcjnkI`j4K@>rd#j z;Dgc{*H31AR%Md=EC`?vX@lKDf z-3!PTNj>QNve`Nj8CRE@k1VtW9V00JbW@@bHNi%n)DL|Qi_NU6^KNS=I$uH)4*gQN zfkyPrJRZcn=c%YApRUl<8lV&&S+TE~rSRp*Rrjb1 zr#G2$%0vV6tw?Xh{!sZwF2Rf)zwzTm>#>-FVCJzY5hZ2r4CP;DxkS`!q9@4ex(~cP z?(-&03Y^8g#GC&iW{+`C{nLl4Nu!W9AmYHxeY%8D55K;Ye@Ng(xgH(fmq!EsTiG&( zcanZ`z6@%9wyl>A;^E$lJJQT@e2cWWnP)aiFVgQ@p-OE&uVNIXdrBtmxfaEezMB{v zI51J%&%buRjw9YU4To1ZI8a_O3xEZFi1%_&g9xZ#74~30+2PICC#9BnH}eY6L?!<7 zuu_=x?pIXH94sV%bNxDX&`1UFK%s!+u|XbYh41;=4_+9Y=3u#91-RqE>C1kW{*Zk# zZIgFa7j|MWPT4~B|Ed2Lrh6Ueyw@UwhCSP2+pQCyg$`7Fn4eQ2qOXxG{n7oHX_SW% zxM{WEi$R|)!DT3ZD1h`L&S3xc7IRbV>vr7z*Y+{nCSStKB1NOV=|F|ZYeZlpjKiI z&H$Cu2EK!LErw^`vOhO)gTG(RN?P+11OJOFbZPe$Bz-x=Y7Gf46X6{=s@HM5pB8!l zLg*MgMrHbDcQgtf6bm|1@|9_A$t9CjRfS}ZuW>=k^cjPkRlxk?Fmt71x_@QawT+?> zh_=AgooMR5JUs0(x9`o$Vn6g|NlzG35WZy|_9{lEm&eh(Gm(HbP&fC7$Ai4MHiyQG z-k~~v&^5=8Cb(UJ_91AuJ?JpgNOK^ae$oT5a3|yQRtWx7(dmb%ulo7u0N??N&vBh< z{l+{Y#P-&E)T#P|PnXw+aLQp*@_c<+rQD#RH%_p2ZBz@Mak%)eL+j3U?BEpowD@&x zM9PkDhOnnu2Wq>?^LyIdppUH^wpNBdH>_4*Y&x_6Ks||W=_as_8BXtb)_CgI2kPa2BO2PVnh$*(-J_QOek6<7asOajy zG7?4F%~ri8QIElN=fC_YN8o_ZW_ zE1|b6w40dkEo#%oC7&!H zy|U^F*lcEgSI#mtw%R8J~;Rr;C^OBE>m`c7!v>VLY4ZyH^TjC?w*ua|?Pcz!j&Vw2AZ?i{)w`*zWuzh3$Lf-1eP zi_{EAHGT(p=~Pi+V~C@FJiGxz`viR=Q_3fm?2EH$@Yue+$i9;K0qkQpL|<>7=}U6h zFKj7}B!@n=W)HAXM}j6pHOM#i5zvsaII#Q3J~^}u(5Nt$a4UkR0K2EXG#2k*jnT<} zES*=kqDmBm{}M=k6c7{y$-y^?5=4@K{`y;-xogduIdfD@(7k(i)mOtD2-_5Ew)Zn` z4fGs%?9b(~0rYAI`4S2G!MrB#s66Xew*x%Y`|bzr$b(9siB_d81p5`Sp;9S=*E!-e z>_tVM%$*#Vm&07r8ch6$bwYGpUT8YoODo^sh5}cIsARX1*xv}_oP93pnBO2={mx1* z2Zk>!c=zMizJDk1eV~3OI6SEKB!^)JBLW2yy~$^s66Qckf7HuLVCm@V- z^UU6IU}~pANQ`>k0#s(yjTV2&%la(`!#~?5vk9Ckb%->>f65`>7j7pmGP>oBX% zNnb7lA%E^Kf6@wH-HYc|yGo>uJ3t*s&zCVLvAqa$#L2&k2&to85|@=I1TvUfh)|k* zSDQ`)Q~_uFIs+{4bz!Tb0**!QFKr6z%C@n@iNF!x8q#>u$+T^cBJJ>0j{7rdhl_&Q1y01E?iE3~6OC(vf_M6nE&atJPK5f1-KQ-1 zZ*vEqwd(EbkcIthq$`$hz`XJ7TzkH~h_9=j#;349Z0OC0bsNn`GQ_OZYAMTJj)!}f zQv_|iWpU1LetK&>>4H2H#02W-)hfMkp5M`BB#SfZE$-J@WYU7R0LueWBqGJG+ck#i zjCwb)A+o$iq-MltVIM8~2XqG^?D`e>=;nNIG^mx@=xHKQ*}0Qr8hLQ0`xl&V2afX& zD6-utc%*xec&x;=TJ!oH-7nEwo6G4*(=v`Bn!@ufvMx=o0_%dNvS7K9ehgb3(=vYt zGtwAL2b3QKOku7>0gCR-0Xv=efvWfrDpiL^FYNjuoc6LY#xH1K96|l27+)nc4j%#1 zE@pk~zZvt$%P+|;m{Ek_voE+|kE=$aw+1ONCaUL;J~M007say|O0Xk!URmFsb6n$; z!1t->RsC}1m-A+k)?>dZ-tHt3P-`x{N%R*m;l zKfk}%y{*?|gBLz7wAm_p?VS(m)$n;1>1(PY_MC@;WI+V|9g@ErAm@dkw>Q6$zd=C( zg+39Cez+6%<8+Nq;~_mELr^UD7(h|uh2d`({m*u`5U*+iwgq`CUZR+eu^c4Q(iE~e z+h^QIt`ldeJz=#Y#uv>nUO_3izK8)v*fMtd+rqvb0#1LP^6Kylu+B5u zQGnG2956)W@tL?^B1$G`i-GS(RQ+~_PVjlL$zfaQm(L zet-LrWs9e$m3cyQVPM;|48x4UJnw;}*$>HDxkMg9q~N}gen4Av|Fgey1PF~UI8WvI zfyCSGDQt2*GAK$feHB(!BS|ayZD;vwr&)Yx4>D(tY*ReH;YY`|_Ioq&27Wv>M|!K- z+u{wJ+&ZLm!(gPejfHbesiJ`ETC55|`M8}w5Uks`-z~>dOX*Jrg@ZlB6j`agvao2^ zX(3(FK$B9i_p8>>;vL+wb}d4&f22faWo1TWOIG z*&zT%#T)LROo0FN^qeuCo<9XJN>}lodh!;d*h2w*B_8X1#W9-lsd0xQ6r;O2$l`)u zWsLY!XeVnN;9HYexEBjX)ys46VFN=ZGJTxA2TK1#b@y(JC?~;0j`LWkk{vdsHzjAP zN0@Ju`6PwT=JmZ-2AcLhIr^BxR$;&51#vCWheD>^54q+rQ=8h5zvp|F3900u8SVp* z6YWd#7j*E`=mtHOfZhJq(C{^H!T5HtP4Sf8LX)|+4VPqBEvzxapEDOlE7JPxR&Sxd zQf_GQzoaOhcnlt%n#CY0gnPmSDe{(6Bx?oRl3A|tVCPzqa7mx6T4S63<(K_H7LT+c zYk%79wGb=_?+%@i`K;eIUG4@S!V0Kjj*cA~?-Q1v(gU6cETG%d^R~S1IozLk^Xy;$ zL&Z;YP=u4@5J@B5HtxAv#S2`vS$gg33~nxfxK5F%`lGrZR&u{m&2;1L?2lyj4y+;& z=lPmZ7k)P02qia`6Z4ELBsVqC`vvH*<35M->6dbXNN5rIrDtu6#`RJMFaSR!;76`D z6Mm6_YPf@lyhOJ;wn&ypZ`kaYqv>~4qb`PPd&V;qhUW(GKf1AaGPp%2Estpyu!ndZ1= z>X=lPu7HvFR&aOLjw*XRxz-Mj zdfV(Lcdj4J9Aa_gN{s@=9r!zO>{!qRb-7>*eEhGYj>L zzWDM8_lND(rHZ;h$sxSv!oj%aOZ1tkW4Cbo?0hlAO3wy+s!$pB?l-U1^zI+@BH8Ek zTIWt}Pv(cEBG~C_?n7I?U~56*d+{^~-kCeCE8&n%ZK2`%jZa5$2&TiM6~W0;)TqSneV%&vv(`veR4u1}sh9A?4M?5*(#^yATwTJ(aj31YIsh+zxeod&I`hT`~JIcdn3R`E`-m- zv&$|1P5EYru5_V?_}@-6A_tG<-bXt-*d%^nN?r9d zUNd`p<*o^prQ2yYPgE)nruWJ`CrZr?nZ4hAA81c}R1R8D@Bdy$UhF&_)yeW?iyzDQ zuj=!a%-gHE8f{(#v}fC23;InWpuAX zsj_%OO3N>8u5zw5fDg$0G)vj{>Wq|V>{w9NBv?dKG z@v%hE+nY66*~`*Ibw2uPkONCHnA{ZRCDS2Ywg8vAY&MEml3Vg^v?*3GXw( z;d;D>-+P5}-mIF;s9PPVipYMe1wWsry?;Pxd;~9YOfsrDy znrt!QicB4BTGzJX!d%mVFU-RwJQyb(CSZqv%J(Ngkp)P9J7k8$C+uhxiXl4KI^a2pZWc-p5S1yIkBA1}G71~VDXT6lpc zpSP|IAlpzWL{wlN43#Wr_fl0N<>{Pg_JUI7QWEri2_P|Uss^M(u_59I>11xEEKR7)5nYs z5AEoshjhV)K4M|ZrzthoCc)Z!sqx9t(Dr7miZl@SUVY;&GIi_|sCQ|5ywW{)0RRM3 z0Z@WmE6$K*{&SEp!Dsjo6S?@lUc8RQKkzeVf*TG9;m(9d`TOY}gjrAe;@cw^jXK`uUW)#z}s6KzDLjQ9gQ!b<6$l8_pi^^DZOJ-d0FIPSl!<@~~Q%5&^e}GB>ln z_w;gVCJ421WF@IYZnq=4O^Sg9%LKCuZ#%x``j{V47uZ4t8cjUXqEi z$*c_|?s3&aNSmC$B}kw9g3!PD5`P5G948sBAjL0oOo-FXa7}>T_9-nuA)zRzDnu&p zsU@*9I<$o5<-u*PjQLQ~pWugN!_w8cIVYOqx1hS>D`XSMp^l!QrG;~|%2svop69-z zFYi@Lu(tP{1ZgC+9&tcRg}=hTt~nGx6>4qsWKC^yD2BJ@sVf$q{l^QuZogI}i~IiO zb+Mt1pv*~oUWAdRgBuBn9*v+E+$Ck4lmO7YKc8&Z8Plg7%2lG3F6GpT_CZt?8#c2)UCFE5lT>RG~@tu}Tj((uQXlKVMPMdl58_)I^ngVF~EK-u{p`^md zqWI*5znx78YsQ!8QOEk@=%);qT&=AY{K;a{Ye4Fu7kx0N6k?}y?69AdNIN{<`e0$w z==!mp z5(&T}w#dn^{S+*kTU%(pDkH5u|J2Rzr}}}&id@@~yqGxzHg9Uz)J#yw9*n`Gj(&?Wo+o65(;DLrWU zFoj#zbgfsAQw*H^q7=v{q{ic?>Vw$(83iz%?vwp8p;GSdh4U`o=mxbiP91Uigy&!@ z?({dgMF-%S;X()Q2}qgX&=Hw^{?tADfo5s&NozgI#ZWyctA72xaBM~hSXwJ2R$Gcz zjRPr~_r94<1V5jHTxl zXG!#4!UvZ{iKL6ElT~ zN-S%@FLAcT37cQ+8iYiOq%QGZk^E`#x1Jb^44#%NE~*JA?)P(crSO&9IWEi|h-ysi zN|b=Ph3fv?+_Z_U-p0YSGkjgD3^?O32#FPdM+h3c*R7&sRDJ>C7wUIKu1|*Jhm4O@ zIRf~=277B1UxeKtoUwrm5e?;+TtFZ0k#LrgUVfm&adGZ9z0@uC9tj(8-GSAp zVQN6lPcr8@zK};tmT6S)mrK@-6Hy^O+ZEN(U+YXS)ZBf-tMIrq#`ZGo_flPi#>0KF z)cnJ7wf_FmL7nLYk8^#`3@Br*$^C5kz$&)`?#b}__Z0Z%idi|$7il2Gyn~Pp4F6ep zPQBQr5%sa3`Z`tT_;z@C%$)t&xU>S zWe;N>#Em|`sleZhCIn`g&SSrFewF=70JYt5UB$CzZ_EXsB~pgvqmyFM4bB=iV1ge^ zXJY9v=jU{z-R_&VRSDTU(yXiz%AP$JS3I&2&z-3=*S-Cc?#IQ1is0EHIGdnBafYoS zEf8^WQ6Uwj9$(>g6cf6;AR_=?>8 z(q-4UMK5^Sj@+X0Sp*>YvNngnonFfR?)Hi^2*_ifg{u}*Yx{aes^bQ0vdxywUh}H^ zTwWFW*r)xx36J~sg;Ji>U#EzH@~OuilOkR!>Jl~&cKw_mz3hF)tO$=L-{Z*@H@N%MZQ8DjQLE_{aU17Hl_$K4WcMa$S$ zrRg=L z>OQRQN?hp=@oDoq=OP^BB!DHmFZ%fOV7o8Ci%6S$-Xt@4@UnKjbhD-C!|6*t69Eb; z*uCpY)%Wk`9!W7{v=vemW>_`$@2nSIbgiUfLPa{xH$`8M@tOGI_4$0L%ZKaA@f5x) zY*1X+6>(XEdzx7FlyX47D8*EQu6_D3=o-IVc1=LaSQ@p?3TRpY(t+`aa4 zZ$Ewd;E;48bF0v)nxjO9{C_Usp7OvF&{vl`b_m0&^-=4Xeb?ubQzU~P-NWZ@O?L^J zbc6M-=WVxV2YpPCHaKoe(xF<1R^s{FzE$wt6#b48$mp& z%D(zk{|UzXhmB@GW0goZgr#8J{RHfeK@Y)!OlMMt^}}6t$#wq<@QOxznLjZ}|Kt$B*mLD&O8x)Onbb`0$>mM!iB;rp)F?v+l`g zsMuP^3&9fA&&fp_?|1EldJ5?D{lx6m1@EP7LCJ{_y>Xb@U#(c%4=L@Dg{aDhE(Pbo zaJV8h=g~iVGWQ0`nD1szcFJyXNF%u#{XfeJRsJ~AZVex$G}ok$gJqwN@W;VZnC z^!p0{F7ZqS2#;W#5@R?g#KRJ`H{>U)cwlZW5xG|m@B;Tam~EV2merZ#Olva)gdJ4K z$@xi@ew`0~?6&u=Ya~quz2^7|xQl1)!8!bCwAgY--^z-?NtN=H9-uJ6ArVnfTOAS7G z9Ftaig;i-!*+#ZlE{X4#>`2u|^?vHJr>aAw>W^>ZXUNQnQM8GV%BrWE1PsR|^j>X2 zFZ8A7S%mAh0A5OHVe>Y)IM@_HMw~_ZFpHNgnQi(5OoLJGIxlet*?BD>T#cia+n~A{ zD;X}^3t3q_EfS%Jb%+AYlMwT*dp#t5nCmPOtA`VIc%A}(nUNRE+~h9{fJvKJC2!<+ zCIPZX8^gt(k=eKXdFQB+J95{EK6U3SrouqWAN%Da8Ovn8A6Ka$>+C=xcC96c(l@Rt$9p>)65wl~ybZj3A2b4(&xLV4a?A|gBF(VWCTU#zXO*yydtb zga>CA|4@jm3jlbU&UEfPBVi_it^-(dow1km_{8WcE_>4gmiUa|zi%(2L*>m;N8261 z@937NFg_6sWY=#9+Iw*?!r#R=VxsjPuU{wBKEegt6hVp`yy>RHH5?EF{&Ul=y8k#m zATN26tx*;Mi$w$W%%?scwzFEeX%VB^{gP^FM@NxlY1b?TTmi~mT_p@)4v8+@ecz`# zTk3OZ>H2TE8-iJyUE0{kS|RBtmN$m-5n-ExG(y z3|Q%Ms;P0KM{oB-8W4UHo6S_oMwf5+9qj zzl0-|ctCn%q7sMue)>|~#*#iqs7iQ1iGVKHCjLIX>uslQ>=*SyQ1LX$`&yH(!8@FD1B534GKoE?GY4Sj1W|_8rV;%sW@Jq}O;5sJjZN!9$&9v}C zukZ01o?SxRHL!|^@=~nNnjJsM@_}=5FAQIZ)$Lbm8YLvfpbLU%Kke;CLVa*p^%4tj zuD#bEa83MnUn8HopMkyJj{H825VN2{=~8Q0{Bri!chFI%%RNyiin!6W>C(%6p3{$SoKBhzOQukI z5IYs8M$pQF(!uIhO>fi%2I4=6L2F@4wd^72)(@_5?)c=cCX!6PCB!M;0X_5g^u69) z{wn6`-elgocsR$9iqOYM6!43~PHKnD|GciF7BBaFbuKsbCg1@gq2{Ec7>Rn3;#+<; zP}nHl$y#`T9pElPqF;g>*e(T5Ide#j7eY{GwBPqNCUW7D zvN=}gCqW#Ki!J!KTX2AI6SsK?084(<^#qr=V$b&@;qP^w?yk5ZTlLeDYyiEs>SZgU zs&)P@niKGc^?7#gH4ZMKk6oRL&M)@m6?PYzj*DnBj6f1!KRC|2kd@S*py`lC6wo3y zBKpLyTADr2Nh4lI?8N+TWC=yIfp-HK(x80vkoGNR?b>wE=X>RCmBh_Rg}4dz)Ljhg zq%glTMUiTnZ+Q^mncL6n?!H^9`lC}7GTO*@L~T_Oz1GU5&^nXn<<<}UO~(xCk_!vk zJqA*xxst?k?Z)QrJlm)K)v!s9-1l3?SMyT&`W0TmI>Q~)?;h1O39E|EN(Qg&fK%kl z@0Y1n1o;r0J`5%|1uJ4)XTvs*_X+tHmkGZEwZd`anOe*vuO7%!6RuKrJGYocm6w~R zK;kJU-`!^g_gNz>$6D}>E6D-2z0w(K?b=%tq8)mp5CfM63^-a#UCD1bewc> zZNb&k@o&KY+p?}Kl^kmM`8#e|c$?V^J^ER^`}LY&n1sh;*_x(u)|l}Df{m}oRn~T6gZNDl;oMLb zQY1W+^ye*vu12ZdtDd_8X zBela(OW$@m+%Nu-E(zUmQQ?ZS;66CC-CuW#I1C2{&hf#6Sv?SSvZ#t<5|0s!uUK?@ zMV*rJ^A-szpa?Ol_o6Cn=(f8}@%BJJb{}t9Q2v>lV)~B}>Z}j@7e28a^&^4#EPG?Q z2ZsRmAF2}6MPyTZ*DP|@oSP<_^le{Z;W0@h@8Esf^kdaDX+xULlkYEb1W+A_Sx zSjkp6?F??(Sy)?ycpr7nsO966xfRB|dK9c7I&5>8w90OVs)vcKDGv~rhRf$ z{KMhN=?s6mKqK*Z69k)gM1iF$qzBqLE&zmH`aT~rpOe&d^i-R0^=r7 zm!?gI7lSIxz2op)3c{F161GWdZE&0K^e|}F3OwyKRiV?d!s_!8>ywmT`r;$(<1^?jd#u}R z3eG~g=OZymdoiH{+p$*`gnt0DB0U5JZO|7vg16y>x2Jq3(2>zT!;f#fu4Hp*tvq0u z1l<%3v7!tBAuv^A9S+{Q@t&ISeSe^8+dup7KD@+Z3!3R%B11T-+d_`dhd_VtR}~TL z6)f&@1MC0wVaD>InhwRpQE(*WpHQu>0d`MWnE5PnK0S2`WeXz^PS6@4o>@G4?!+ov%NN?RumP?`h zU3=1qrD&$5Z;F~8whe>2oxytCJ1w7dKoTb~x$o`qF%jorCLTLle{H(NQZ?2o397JX z@^Lw|<9X?@Ksr?ZOiy+L2I^|$4qNa-$Rpi_lBw?r(})nUiZ!nkWl=uQ!FMf6`r-@L zc1SrE{?dVfHi#HM=Li8o2!VX&cD0Yp+Xp)ix&Y_+f;2hNc636msn0w=QIkO(_bX1Z ze6F;cxX{%oL>Mc(-?`@JjlOVOV)=p5_P08G-jNrQ+CJ!>`x1R?5T{*FE?% zmhF92Y5$j~oqBy?Uw#~}P7C`XKM>4%`B z0x?0wxWzE4tv^eC%B;|3HgEjgZ=WCLbZ?{jRh=SNt1!I7Vi&5D9OE4G3`;W}lSF2i zfP}4M_@0l7uo-sVBIQ_p>0|r6s)E(Tl=PK4LaLUf+1?%S{NM;5Z+y95j`7o*5!}x5 zzf%!CB3S+KganvxTxEDv06f`Pj2+T>4#B$5p;(^G`)i6q>pOHmE*fdDzH-@JQ#fdb z)iJr~*COvkcuTtZ9Q6J};O_Wym4a*dNBg%^K7KyVGp2k;T4(2hMhEaB`#`cW9ttW) z!Br;0Yk}X`4ft+Tf^;C1yZHYf;eol$nDgNpe&2}Pv^fA}Or~|F0g;;;dyrOvqQC01 z5|&<@x+4*@UktrUjiDE9s`SA%*EjMEvu=HY?W@Nima7xfsv~K-F!sYrs7s;q8Hnqn zF77gk@l!z%)USwGu2ix!liq^poG}#WvQb=mvAowD{#UFT$_DA;r_nC)#LjW^gyy67 zJe)G(GS4Y7aCbPuj4HO-^Q+{`Jy%nCC<)5b@80y74_{P=`f#myb~F#jfJZK3-OCe< zfBu@OXY??M_rpXGdqe(~5oZ4M`#n6p-!hHa5N{Q^nabmqJb)Zhz6CM%12%vPd;hYh zJpcaUBrkvlTu0%3HrP)vcTRQvYLJP2zVnhilp8xEjipV9$Hla;7sYsE&fdOt-&>u4 zET9j~A;L1ou47VhShgw+acSNR$Z>Tov+K`+FZ-_u!80zxt-cOg!%r#^FMdczc;1g`P9{>`^aiIB-q;RhVzqi-&;^kUE*A~^)ll7x!)_b{^{g@WOh@^>gY&pK8h`6W*xDStn$^g{O8r(8}Yk*|AW zBs@$rw%er9?INb;s=HzZ!g`k+J~9$Kvn3mVrj`I+4$b~a)A*hgsa(t1@yO5-`Tc8S z88m>g%%#W*8ne=j-jJO4Chtc3FllyyfAPT=`dXFq=qA3_fx-5xi43!@vs1u zuY-kPVDEbe&*nZoHBPhCJ*@Q+ymaE_pEjy({qA(T5%7rery$AOmHN{^AlFVRBSJ%Z z-YHPZ<^H>Uc`iG%L<)Tyz6Q8vd34iBHY;9R?PIU?i~#s0i#4Q9GkPOHjLA;@F+5!8 zn)@TK^hj3;-)<}*<7)U4vZ(1nkuoMBk`Ft9UeN*K)mC>&+*idbOH}02$4GQ``Y#VUg0ot z4$c$152us!`uSv-ImcI6TsYx-tW)s3%HQ3j;3$QRQ*|bAa8tM0sPUG zx4j+%jKOnt);b~0U|tHRmsELQ4E;L1a+iqQL*iZ6OG-xWKEN>!a_POlJ>G#>qu#g( zPVn@6uDyyU{jvKposA~sFtfcLmE4^uZ7=Y)O!TkKtH1KL%>oi}eq%rP?!yc>?Q%bbT}g}xF^VNzdTQ5|xh6w&4oJyfKf|w%zgea^-uCUS z(kEyIFH)J$GjZ&}PjUHI30}Ad&Qx3~x}Kj;8_4j2!{+*rgP1lPBiqO)?oOdVr{Fcd zvGk?5H)K;3X{K3ZjKkeuzn=jAXk`KMXiAF^;XdDsD@)o>Whd;cf2@lHGogJBAY4D0 zT|(Uv0C9%{$a!nqZ@xlNhgS+Q$Snym!z(9lUnZoBg+kOeiw(cR9}=BJ{2GiiEjZ`( z1(~w0&|e-zian`#k^rT7D&Y-Ica@xv*0rDeGh5>GD|^$?`Sbl*9LBU#^Qps4V-^FEWqv zqEqFLSI5i#VxNy5qUe2=2^zTlQXU|9SeB1JlBKLy=wFMTlfm5G;*FBs4hP>e<~|b? zF7�C`ICu)j@gIKyWmh_~5Bz4ekMFgZ{!%r<-~=*#nGR_1*hRrP@a$0Wr$iJqWRO zpYr#%c~6^t{Jd6r6{u>X1XH9sM-HcmP#VqV0ncKIr9Q3*e|BF>?hSu)YxnJFge~BJ z#E>b;bGf}Px65hyD|kp^UYm{uNXDKR;5etru?`{2Bz16IbjGpP{&2%uR*{OE6{;GN zzkddvXd8olQgEaM3zh*J{aOCd`9k}0SsH&FT*!o|gt;q^VfOuPTB94IbRS-jtG~Zn!snk?HpmUDTEwVQIaqGt*XpmH$HWo_3&U?&A?T;1G}Z zeqzlf{u&OKCEQzC;_&srxD!AkfYfs{kHzA*;F!2E22SxuKMASZFEZ22trZ!)tFo4p zctwZ|_wI6QXn2|i<Ikj(t4G2wWi=OqmGvy9D`37Zo8PU3c08l+ku zw3~pKjrHiSNwwEK0a!Kc7p+Or>84}kSr3%|>q^)3KuqRS77!Gq8|yw*!?!GWGageo z65F3HSii+fWd@}ga;y^qsfs%_YWXED`6fdAj{ky=Cr|0i;B2cd0`KXAH>Jr>7aoJ; zyblv2w|>-9eA0m&&Wqc*tW;_qK1(>md=A$?aDmU(*1Z=NNf7#PW@NH1kT<_|KQ*LZ z^vmSK{VuX6$Knm5^bjf+ApIRT+MVyhc6v!Yl=1r(!HO z&u9Z@jf^ReHQ5UqM-C0^)e?K~r-BtHjwRzS<%I_+$9Md6YX~4kw>~;2Ikg{89@)%` zMcQ%NmZraq!-YQo8p?OM*EQWsA@${|^wXD%SW^%cE5kKRDGcQ~3s`KUv42_Uy&h0r zYh_K;*U8dgF`vpSWgM?C-RlFm!*1DRcLzsXQic9l9|+K%?(KUD$H)1{w6NC2$}Pn0 z#iqVvJ$LrO+2h)o55G;Tx1oiLTA?21&BY=@{(zB(JL6aP>H8fCUH#0!MFX{1vQofF zxFM;hO7f@n6R66{G4Zp}^D0(N^N+&rg!?Hf=8koa;Q`nfTgbLEsFHU_(}5Gz5f6M= zjm`K2&$Oe3(053)i-TS5v+r^rk9l{zb8JaIx2%ZI)Gr}?T|m{3n-%&dPPUbt*KSO< zPYdjQ_pV+f6)8M*B1pTnM&tXtHDURB4M7@Jd3ppXdN?YeTBdeHUXcNhlSJ{pU|vv5 z-&7ATk(w&6_{-%Q-hIDh&L|*6r?KTTJORV%o&Wzxj>T~dy^6kOmx}v`o(y_Zr!Z~qTgJ#xc0FZ{oXSc#*Ghv>-=?KYjL!TLz+sF zHCuBuvfPO}^GT1PYKlSs@ zKMgiNH{pn^mqV^`cCo+FW*1;evA^$>vlg0Zo#M`&UfQF(StSSlqVD-fIo;KOV0b$U}58z z%&2w-GMW6Dj`JWY*R7%1BNsb6U+UZ2iCXp? zCj>Iwf81Ojw)Z6e*1h83op%jNGOHG#Ei!cU(7Y&aw@`*^%>XY^C(9eu zax~$4jIyc7I0J;{ql<%Lws#0qsL!Ez#R8f2YH!qm1KooM0r&WvGHk3SEEHhKVnwBb zaA7q?9sQ$2qA}S{(O9Zi*1npncX+YLm#q4>{!U3Y z_i~?IXNoE6A8tY?e;-92=^Pdl*osmM!RquWow|VK*?#iC&y!~eV2O)# zOk`RC`nOS@Ngsjj5`zGPBZ8xYg?D_Pvj0XX|4*FPHcL zjXn(6&a$Ju$&jem$8~-L$jF?q12cQ}o(^A=LrtH;q5jr_9I zm4Wt+rj?iz;A|-Cyj#vElzqx7zK;wfHj3gF!DH&!)19Oc=&eI_4Q!wCG2^qkeQzX(8;V^Q1GK*TT33eYkAZZ%ati+~e1GgIj2ExU*tV2h-pTCK$KD^OR z!gw-$u=gEmC(~<()9@Mu_sExT$Rf=B75A@Sd_kfbJH&g8o#H)U=YA3_N6bEjT|Lc& z=sR+qJ~<uSz?*g?$?|6WJmFo zmgoC-Hll4q5u@G|?_puS}*W#ewuGZ==o^#qS@g;cntJ^9S>xV~o zBaeGo=kCv#XKjXb#kZ_{1_T~l2jX{!WS?6HuP4n`S&)%t+|JP5AlHs04<;G_)S%&0JvqzTw?oz4 z5O^LyQu&Br2j4dGh7xb9fk`0>_il&NYT8iIsSiRtAqw7FUB_IiJN~u)?YD^^P9nOh znOpuBctiJf84=~4HuP{oWwgenw#3ZrSAd&deR@TmkUCm|Cl53;uXCVTlU9A>*46Ie z1X|FiznIc2FZt)-nbQc>(fLyW+pjV7>>y57CZ*#~y~rQU$=iq-2z#aOD=e@4dAUN}=hjjN zTgB)7ql+dGbGd1*{mP3r^Ey~z>b;v4FJhmh(&z%fD0)A%EVT35B?3eIqJvg$N_vgj zP2j`d2j|f~_yz*_c$uBc?gOwThHnipRIp>58E zC>}^ZiFtCby+V)vn}F(txrF-fc}VZ*IXEdxK3cFw@l1>vN83HgsNm?=2HHx^*q-9A zas-a*Ju7>;O*!}E^~jx~&5`PiNQ&KHbo$kO3UrqGP1FH4Wqp)`eFiF5>>dgt#C5pS zUwY()kB3@+AWL?ySl>TKEoittWMMH4ts{oBrv{tzrIAfzR|l&qWCtjPV#b;V_wSx> z2s^*=@zOLLm@mi~EZW~q3%%~TKVQEls!Z`u{8-UhBJ5wc)Xsi;1i(BDa`C`?4`}~f z`wlDd{RP}#YpOdctrx?o*N{@+M)AY+j_<CgBiJiLORSLnj~V3D*f`3hTw(k z1dAseA80)L)&%!MY~m8yq6Lbl1-gL-b2y!Y(%3pUpHXrK1hAK0P*kzquC z2XmnEJDpI>iTM(GDO0z@5xp+)^ZPBG;4Z$8fMEJfLFC@A>+-HMN||OEopI1wl$U52 zhrKY#)!UCE1jLEE-g31t!IDI^bl>GPCh^~h<0Ig9^Oxo{3_AUeKmD4qh++Zn+nZ0*^)i0q z+oLnO=LcmEqHW0dKa$RDIaMf#qQAsEJj#rKD6_mFf(nQXg230`O>R{xF$tnFoYSYf z_u9*yL6CB|k)SsQFP(7A4y*X1s3$#K3g6^$CMK3y!QyW_QZ@{}I~qu~ekij)A0Y}w zjYUWf%dd`Byje{Jb#&XKE1<#9Ol=?KVFg{hx#i$NBudIGQn$U){{ah(yLT+5FCjfy zj$3cn^Am_$7<+YpfSqXm#?f0nx?fa>PsAbef2$7lF@5RSSc1YPGt>E1&1P>Trpj_p zrZD$=2bHk)aof`e08})GS#kvV^@_QDfsL<6BHI;g*l%n_^XRWlaSpYUt1zX|J4jkg zHqgn0q;#?z)AD8Yn0d-&0kJvRf!% zp9glM!=MiK$n}G!3~)%51IvlO8)P*N2C^P)(7tosG_agy7<$i%_L9fGq3)*-4fm_g z7*x-;F@S4a_NA`k0-)zUT~}PIO9PjR^$b^^oAh8@E9^6c_J!-Iz#XKKJ>-^0VvpDv z5TT1-`Q$9iPuj~j>Win(?z8oK-!gKd+eyCeqhAY8kT0I`rFFm*()bqk&(r*?e$75z zV<}Uc`!K{}v4thAhrov?I}vs~n^`U=s$u|hYFLx0%c(^KiUbUzO}3sz%B zy?+1M3-!b+;jM`cmIIj}9+BLwl_Qrjxuo{F^pd+b#SQOn*x?;%Pjtfvbm*0vGw)-p z*_>TwEaP)_`WV7FIMdqm)n~I6@!ykqQT9;`o8kNWJpDKesFG#y`{0L)&CEXCV zdl8)z!YPJ_O=`;JPF2nSC8+U7lrK>DqEW2Za(tpr7?rPBHn8}% zpHJ9NGiV6ADdhECUtvK>k^2ylQr$Bx$v31K3>77#%}L0~#M(DI!rkT?K9^E}@}_&L zqT;w?W+R`a^#jj0kMxG=2xq)j78E@n)_y$gvn|TpSdaX&L<^58{uYCSMGIpp^v0joM*T;6h= zfmY*SKO8qSUKcT3=;z^qu=%1Z>YMq)TREbfqKSTxSVqB#U14)P6oFV^|AAN!R~%U=vuvpv>xk+=H3&+tNvy6AQc|0$|{A8phb@$){V>}j+v8=B${PgM;Z zL^Y`T>;sy>ypiCIj0W|tP2*3{Z5jPpMu~9VG~%Q&zq!4T@JL7#`vS#Z9X`)Ah&Tr_ ze^h?sm2NMczqK>M-~`Decm%;S{!H4RDoAPFl!_Y&ZT_bAwoo^ z5RHdby-fC*Q-@w^kFcbVbqdn{@6&B{QJDC+crSK$Q!CbDE)g+*m(U* zx+vF^QOy>VGWo~WwE39r86X`4^`{>)`Ci)mXP`D(u3(Pb#qHQ497N_K zH1e9eW6faj)WTLYuj`LJ^S!w{K}q59QvywVf1D@&{oWU|m-&;=9`s$z+&o(dlve>q z1@MGtpz@$igKl!<%;6k$D#r{M*pTL%mXYwsI~$5W_w?dU=X>~uV+JVoSFz6zQ)D;9 z{f1UlN;hCFAh57olhrbCSZVA$4&@uR^#Gp*$x*%Qi$@|}j%-n6O6zes-X8}Am!3rJj?L0)9p9HB=a-+TIdFg&$#-1!FnJ%zPWtd0Li>hl;U$j!8`82pU=;{?LOsg(jUk7iH6qs zd0+Q2iwo@+yv)=w3)lE}?;GWIZ^1U{Hm@TsG%0q?J|8~*7Sh9+!43J5t3R!)%7e0wo?vZDY(Z5vN)fUFZ4Xj|?`$ zB7jJ9zpOeG$hJF<{&mlcC4KI=S6O?C?}3Qlhdp_f@*-t-2U1$YjJDb%PV}*L-pQqD z4T8paDG>uWoAGhxv!i)BwdzgK_K&H)OKBds3&0saNL^h2wISK9emr_Y{#qNz{lfAM zliJdsX$r#?+IiQ2|7&jjeup!53}X>N%V5{hqSfN%{ND56lD~FLFWL1e>Mjf#4*+GR zb?_UR^fZ(OKVQ zKeAWc3lglA-WaMh^}=7F2Ls8t_NVriyVKoRbLZr&_C6GnU^1-I_je|Xu;=~v&%@P^MLn;pXMj1k?s>KP_you&zaAcd9Ld~;Jy3qnzC>QEkxOQ~v#@;7Q0ol+R#+!^&r^42 zYOa#QT8k3bbTg&ct8!T)&fgRgJoV4bMfG_{m3v!a(hT_Ee8;h5AV=3bm}K0@ASDFS+3h5sc5 zUcgQEyF79BrF0JVJ&`BabA=mQ4G#l(h*?*X6n@}8)5|YG_dSpwen!Lh#`c_C>4wAZ@bl}iCXS!f~H{uA;joXKGd|J{`vlCI?x>- zCoXv(FW=@+Qdr93P30E{*5qb9>rC=F6YU}c`u(hV9d1($8C*EV^K(qkhxtX}xY&xq zzuc0{t-q@Bdbf`q`!F2)NszbcIU%MhTTfP4kQ`p{LJl+Q#b1{`oY=MQ0xzPjrVJ`i zW|&gIcn7@<>Mt7GxxaQK)oXinWJ3=43e=^kDzAihLUKV4!+!0W7?u0dA+25F*aCpTn+q>*Bin%5W%DH|_3a5T6{bgNii4Nq)zdeVHg7 z?bJ&UjSx`HBIeN4?DN|8g{h;!*ruO8=hGQXzvDw=DnKjH9x zlVs_S5l=!OAr(*b2tpnM7R?uzxRhM+?QP!o2?LU1fQSVI>um>yw95(Lzx=_peq{SNr`0D_d$^31OxAQsBy||wizkA&{kW}k8 z)6v4M)v0v*LeTd{Ziu!MV{h%yE{VYo=wG2kWs0&Jy3hR zVc2~6t?fI}DP>q2nOu!WeiiK1#mZ$ExV88k_3nno#@|D(FP|wpym6?smcM0VzP0dH zV7J=y+ASXkGkJBcQI7iz=Y72cwzWV*c%(q*1z85R*!T<2e>b8hFTUx5F<^g&`Duz!O4*i&Ts&eeIKeYL%r6+ zv9+)3)zNyrVC?JB*@uqV8m`s7{25vd?+-Imj#q_TQEEA&7ItA$;!J<&i`4MubSr9z zO5LM@nmIZ*DE_Ox4{&Gc-T=~_>d{w+-a!y1@}zj@Z?%=g*Q=;5d{$0Lb+KSIkX;x< zjG$`Z4F~5)e{HXNUI=tG`K1O-jL|*H0j;Rt_)>4G;%enSZhd94IWwl2F~NyamZoFd zsQ|0>9PddQ2_+W%uhXSPumFC6pM56xJLK?rKMwPiCe|rQ+kPyVeVB?bcK(-JS@iIUCgZo-iG=mMoAYr` z)A0(w7yw73ahB6vKgJzZiebD@LQMGK;fh?P#!4A)G&BF{1ixv2oME7JZOKBoUp{gJ zmgxAoG56C?zi?R0+d=Ha2YwHN5wu~#!Z&=C@6#IM4VlYH7!7;KXvR-?BV}so`p^|S z=(Qm~-0j}~hyYqbRgKU`E9|q#!9S!ge9~me8xy$cKHALPs^uL?WfS zewxjZv}l|HG?bxku|&-s>X_})TWsNxW54fhpQ$}8#n%4Vm5>TQ_7u@a{ZeLWqYa%D zLDg!1;gNeK-uEmTQg?&01QyJkRm+j-F?RUehur40Hidv&)k{C85a}>&#$UbcZWVWK z$WNSAxYyA!!o%(TCKbTEkm1q@3Qcq3J2_t7l4AP2SKhs~LKh&|8v*;o3DlzVn_;0A z+?)4MSqo(Ta?=3(t&tK?i?e+5Or@yRrG-x~w+?h472WxXFJ~=BEaacZC^6Bjacv^Z zLfZ8N8(_L`a&qi6!Bm)$phdd^7Ej+v?r**(6B2~ICEH5NJ3%VC3IdLvz%VAONde0 z=j&iod;03HJDI-QKlb|_XNUkxSAb!mQg-41j`oGkXxo_eN(@KCY@47p;@1`;ry{@T zkauJ@>zv26JQ^Bb&N6$ospa7!w|pF`XP4eg_4Ea}3oir=9KP49z0W@j0CipC8t*;M z!Jm!%B6Qoiz4E&tSW7EJ?phG3>>d;~hOW{cFoNz-9o4VC`8P*g;#72f{c=e>S7+n` z_Q&cet|EA~H1d9v#SB$T)eIQU7E}3l1r!WHQARiA?2U)(w>F=zpVs=Oq&W#VhFed{ zpYkJkW9BN~VEM2joEdrH?p6=BqVgm%c?K!=Zok@Qmt`A%i@rXX{u>~-c)|G)ZimnC z*b6@er54EkeCrUc=O%zT6^P#Z)TZVsW$2)J5s6oF)J2;XDxr+agUAfxguMh6GmvtU zyyg?ecnJ)!X(D@!xSF8yHauHuliTyy=Ml3rHh33fx(|)8qHzH&y?<`jbC1d+jY&zd zCEjWb;*@n%5#bvbfEiEcBq^Vr&e2mDQ{>WbJcc?AL_&b>G_~xU&#_|LuO~Q(Vz0jm z!e_7BPg1fS-lV9f=;wRF+#v@0a?YPPsnm^n#gF@pSb=@3Y)WMgSq*dGVBYRYl zeUYD&=KVvJ9b=D1Hd$X`g?reSEQ#Q#0(R$jruHoK4#e z)p3#ZBVW`qFJ7~w)wCkQu4UM>iXzs>eIARTUJYSgpCuq`x+7Qs`-m|e_U|E*594?$ zp3beA_rrZMJ)(XnCt_PF%Xk<>?<}vjBd&pH40M-srI)zH)k2OI?(|L@vsW~+SbCcT z_vQQan0`N*dS106;fzPTKPIp!Dtqbxn@rYpqJOJ9wVp3)~LV_=sKv**GZ$$ zeYK|D{^#>C_v0+mY7ZSm=)iX;6IYZ(q<$uf!I1l8Mq)AGZLrpp8$mGPayMzSiEeI_ z=!wSgAkoqjGa5aYJ$5sOC~1|lzS*a$`vu7b&HYF#s&odGDUmkEoR3r}v~S#t-tf`~k9t-56#vMc40;e5S9m-vZgiJ@3upT34P_^zjF=wsEC)AYUt2 z+QT7px9{O{bi$_uF#;#Pv7D)oMEMf3kF>q_xRvK28~Cv9ggF5fa*&^8wsvB6$+~@J ze!2S+1O7gJ_d7^%Gd;0~%y&TnniZ$^ezb2UtQg-|9<$HUzda?=V$IK_-*e9HL^6Yq z#A8byd(W?y9T+IK0J_DF5rK9_q&`s0dTRxItIyu0T(0uBhYsM`oswj{GzSBjiR`sN z76tR?B)#|-N$lYm)E}9_Fs!6s>ECD@*txXiD8)YRp376Z%KyT1Z(rvp)44AiLxFS- zKF;AeAd{!C%&Bl1u$T9x+-Yd$u_3MFcjbxWC@gh<{3_B@84PlqZzS~RNCM2|*+SY@ z+Xr~{8HEMT44#bULLzTO6DAD7Ba{xO%{ldm6R+Q>xcH@YzwB!ld>MNVb`Q(o+_N80 zQ^CJi1Fa-0RK{23oY_(y%h^5xpPhRa#jq$?K9%Q86zFnrM*rh}R8VXTZp6mN6wL}! z54^T{jGO5=%nw8gu<+_;UqG^PzvbX?Lt=Nk5)5~vRw#6NoTqk0_xTN$9T)m*6G#+V zHyW-r=1;Y~7S1!J_5l{blDmB%7PXdg^r-OoDSZ7=jSpr1OL-Vazxd@C_+b$D$};z- z%bzpVqmhT1TYEu#{Du?a7EKV*@iOl#5w$cQ?Wci}?u6fDL4J%-Rj3=kw1>xmKkfGk zvMUEXORB7E&)!eh(63;IrO==rTq~1`UkB#AbEQ}IhH}r>5f0AY(66yzg8%8XpF*q=kH`Aw2q~-07 z#O0e2xtFVJU;{_B1LoHtez$|mJ5-*9*9JM0%dn5~+=o)6G2tcSs-D=XBN{Pl-<<6F zVKaRw%UEBNaSF=j5RCzs@1rGmk)MA39IM}xscxZcyqGi!bI)_qHcL5ReomK{=H`#{ zHLrXY|y^c8(YOG~O4J=r~&b0!){K`Ww?bF_J8_4oG? zwS!)7D_-qOev~r+*^?0CqLkk4>l5DWIY9d(dwyqWh(A*9r(18q`Eoof$5Bjeg}={l zS@lB=F7@H(;vz-7Klz#Rx99WG@1rgwG1{e&s#u^q??O)ZPle>O8joS!7xwiv$US6h z-{^&~LQ4V~Pw~Prt(_L_Umv_I{L*1L_uB zscS+^*k=|X{*^{FC1cSc#_I7#bV?-Bz_E~Kk9DUssi;r0YB9CbExp#P+!TVi5Q zxO|x(44t@xQ*mQ)E7im4 z9iyrz(`W^Ml(RY_yGp3X4?%eM!-Z;9JdciU@D9R*I9=dMt)ZcwB9B=U7%%Tyb^#PP z%5NLV=u8_&Zy$qS9?E?CPvq|}ATM3~eON4m(kT<`ZB@4i0wigNf@`L0yy}~b>rd0D zZyF}Se(m+~7ac$SPruDSa%V70isU}%Uq5en%IIn zk`OZedIhU0+u2w{z@D4Dk0*Z%6Y9M!!pdV3p4J8>St2Y5u)Gy>>?Q0L$;A|L$L1?U?&pK0g zcqOl9dK4r_7`;6lQ&4*2WmB$ywMz2Dm5s|$El}MX5V>5u+vQ|Q&#aHDGVG0T{_k)} zm0KX>!CPH1m)h316SSwaS$=jp(ktVg6J}e|a@sHcVOA;9dRM{QZ%UX}_|@BnsPyZr zK)z3>k~?It)#P|G+0&Dfl8Z};`$7UJus+!h8Js=y4Koy6_EJ<#eV~5(koR6<5vZo{ z0d<=KxRU+oU!|nBem@Khjmr)r5VbxtWX1U?9{XAE*AE0&-=OnhK6&Yq1pbKA9|Gnw zk)-%q_F1>GE5b86&m*u0d{qUJzuic4AL0aeAjt6)Yn=D>t;QYx94jB|KH(o1Zs^0; z#C+H;B+U}qessk_6W}({PR*Crg}g=?ec*Z^g^0G&-N6; zM`hKnT~ud<$k{f$YtqBx4N<^HLH~=T1=20zV#-205psN5Iz>X+5AfsOQu2X`y{U#CCTjpd$PI78hl_(I?tX%7K-mnWp^QDJFH;-^NnD#mgc^ zXEpEYTH?sb)eoPY@*uZ^_8#h?-TC9^7>R$zzTz$ z@e3#)?w)Y-H5BzC3Xu9r`_va!Q5K$j?&>j#9FRT53uA3@h>ir&KavI1?=$gK+m*Q- z`J>G!Y$`CuW~3EVpa}=!*%#iAclcyqdiIlVx9!!r0#@MD)BV z#YpSwrqC|;b3-w_P1!}&i^Op*?-te+sN5wDKwBc-wdA?)(+#;GJdC}Vf*=*~{PC1H zJZ1OmbBQuuh2qogBdtG#DoumyTgUChtfwDESrE?+6hzG3#{i8UM^mZ!^i1 zMi_clsUIp0VUY58Oi{;pP&W**9~z{{@)5<)_wn%A#3wQ7PB`4gd42N)ce%`F7Zx+A zG{VbhIP6=|&gdY-9W33cgIl7>coXYo8>IP1oPE0)p(G{1_^CnwxDr z4T!>_&n2S*d~CGAq01)xZSZ%IjcZ`;XW_fATMh}UdtENrO?CIXts6i%@yFcuF#n4R z3iaiuHq8A#ut)ED>YZu&g+3s|v5R%4FO}mhufJCPZDl3Y6k_K~PQ6{6WBYTvVlHVj z+2`j=aeo@b0-pdB^hAKIu8A(tXdwmk8@}Pj^(-oNt70Q7z*cd5^2R~ z>H!&y4(7$OJejOI$gHln;O8hglT)U1o55(m*~^uxdsfiqQ13%~fD`s)8Cvn_*c3_V z-sL&>oHo~1X7wA@6h1PbJm@ETP+n)>oO{-#{cGIh2fyR`O$^^HE#P*J&MdT>r9^C* znwJoQaXTOB2OIe$%zM%(p+HJn|4N)BnsYyo2>T;6;Wec*+gLeF9&BQ0lKq73X(kPA zoMlrr0G3SW?K{T%KdgNQvJbO=Nbzh~gn41N&q`9&QonMG%kw7;nyx#c2TLK_V#Maj zx#urb<^YivKhUv!)${6@AvlU@Q$LVMylG>w-Ff4F+w5ut{f(uZHk}XBea+-ysJ5v= z94%E{R=@UJFSAYydIizMSiT=UG|>^K+}zJg0K7)t12^OrCEmIaH}=!&+Lp%xZ1h+q zc=ZC$qIp(=JDNNh^C3Qo0~%NH6aZ_W?t{N=%{qgT z4o5Y$ZoH1zn@1W^F-9st4;&4rD7G4E&qH3sfssg{<63=!^X~!cyh|=W#&}$;$P#t%~R}f9F9+K40FZmmG=W$dtYw(=3+YnVi{k{A|se z@Kuk^4;&bc@;z~Ryf1tnAGaqRW_?+chrNt&QQq3MWXor8S7rjy#@K(7`FDVWC0I<& z@dy17Z!>SKdnCp^@;75R&5_);#y*Y0gZ!+TSK(N%2SfV4_GB;|x^QJnsi;fOcprHS z?RH$M^;gv{Jaj$}LcR|I234)9&%5cP1S=CoZB3qz?+4d!42b;#NZD1=Yf<@&{MI6J z=1nOHArAJ)YL?u|R*(Tk0YX7h8Pm{8lnoI5$&|+g(P_3^f-+7NSq# z_3YgC0#Zoxt{-_pEV*=@zR)+wj> z{e641Vg6H1C=iE4z|q$1+b(I-VB7A(Qz2>}r=zlh(~iGAvLb#4fZ*yhv*nXbJud7i zC;NOogYEf_!MjrYzpL}}@r|v>MX_TCz8?1((4V^x1GA@t3Ly7=rtac)<-UvM5KHqt zKYb=I(CCBVtp<_p@kvh-tqecjy1BpSi_N8dP$=k?!v|@^a<}?A@1x?oULF6Q`3fLd zC6U5%yI>VG=8ZoXaq&g2o89b2=+piv5d8M?e)bdCMYievMYS(55Ag>>iBc{KuFOxE za~~@i$-5l8mReTJsO#F_7wxwBdsxqvcp0pSw?c4P3CEt#ZER0Ruw2i}XIEis&FX6@ z#;fecBi7GfIc{GcFZ>{=A-#<%ybQ zwjKO^NfL;T41tCM^%#I5@B90+oeH~)?E72FPH4doPqt2=_Iv+;hW0f|UMtkgYCxj+ zSM)sr6L8A-vx85gCK&?1x;mat{%cv-+P=W!gn)6U$p7w>_6>93nf8&gK`MNn#t9A+ z_-*Kc185U*ezcoS<$iib8;O*}?a#LkRT`rKzUKC$B@L&B-_Hu1JYVgRe@s;jBxx8o z?Jwe8$@)|g26j#F=@~wAbEn_jVJ5G7A;;@7D|Pg0GX@d*R`vu==+j?G}zJlf&f$ zQX$q!W1T*O<+%rVoNb}$`CZGxP0fIXSxARGTRzbrPK&H?LjXvtXN$jKTd-8tWq9A1n#PMr&>%)yTrt!Hl-9?Zb@EWzgRZ{hz0LFEM$+JFGwM{wBi4 zfh}KJXuzg1JoNsR_F@s{u)+%o<;im`$bgDm+Ry9p;i9!spboHD-I(0=GH^z z;Y!wiQOf(3=)cMz^1Z4T&KfCa@~AuSO$h)b&QbH(8(^)cU^d$79m9 z=|N0uc|t$9oFx&v#9Vm80f+fy(#_Nfc8;btLcs+H!zp`K=(WTy(G0uKV}yHwKDu-= zOTT%OPhL-s5CM01-A&ZA`=aeL(|)@Z6>B*Gte!C=^Nm*p^!qxt9Q>`l^eg}U8cB<9c^pFc4D{ib$# z&<*=sIXF^aCeaLa_kJ|-RljTJ!j%{DWt0tD!E0E^zLNA}XP&*@&+WKPfxI8L8of8! zWU}reC*6SL(PfV1udyw)DSK6YOy;3n1Q<9pXmYhFG^P(KTmz|m44w%Nx7J~%7Oy7p za8iEEnoq@ag_+9jJ;G;VM>B&18*q5VkCRg!4K*)c)zYAP%w@Sx?XSo{Rl|Fuf;e^Gs8=s&HL|YnY?0e=i48D5$vF749=5PkX=n{s z-Zp;}B3Tl{N;qLG-p9mv|5C)P7MbD=|ABGOE;TRAtigq@Qn^G zim!f7B-L5WQJoj`pr)(>5e)YQ{V7;kC}4KBuc=+fY5ScBHUuz*oJKhgC$W+x07&6i z*v*gpxELWlWAXgm%T{PzJoub!gOY|D@#z*Stzi0<0H^XhD@mTk7XZR$c)6!9KDR`# zO;y!J&HUB1WSjP&?MaP+NYfC45P5*DQAer!&gN^-}OWLrq8 z#pQN7@|54fjOuhEMHVQ8`Nz1Uop5yslE9-&Xkzs6iMk2g#x3_J^7L>#aRd6G_METj z{^q#$Fa}8cHiVzRx2xLUFO`Z`b2Yj`l3;pG2U0y5HVBic6W?i%O{&Mm$YCmm#GNlJ zs1aog%24Oh@>+wz6!B50hYck?_7ql89+Ry7$Y<9gRUS=J_$yADaKX>vb$sS<;M?!( z>vO9kxgO(n&p}|cU_fknE+bj+1PM;(L51?H#lIK}&dYehm(RE)ygn&|*aJeT{^iDRa`Do^3#*)3!HZ9=b(B!$`1bGcSVlU0Uq<2awmPG>&hP+Tf1+hrXS^Y;MuXNX z@^KN2sIRsYjYcZ$R0qHn?@D^b;zE&07X?cPE(F3#F6Z6m2`0R^$70})VykN64)jpI zg0W4sgRoyA@s#_Hq&*10VvA4hC0g;=c-c6+NrC(b6{LQ7I~W%G7+xQ3K|a?+cmLZ3 zcQ4poLiStcTwJkUBa>cnQ&m2oD@2`~jbuHBN8E;OrZ|%c=9Y3!U;D*fOu$VztBhj& zu2=IAeog7IoJ(;q(V0lvxYH{~Ao#+`Rjb~-V{W8yKytnJ7q(+e0PB}@UwyqChZB48 zL1R5{*g4?V(OJoheJHOGIACp2In3O0;pz2D=vWZjt*cw}5*_5d{w_& z=WAaP4Ej2))CXRH$9dYa_)s@O_yaw#Mxb>t2ot?HV9B|}zs7ofq;+_m)wi>qxz+n? z4rsJDS)i+V%+}8AE&V9NcZQ9^R0(D#-#-Scqcf}hzJtn`lBf_?za_bgEytFNV~!2B zcFu_5xqYZ}a{3^KP`aP(pLDQb&oP(j!^ee@`iYJ=>hA)zp zAMFSOXun@w^9-#Wb%j#cdqgiswDu@KU$*oSvZJs*b)-su>4HvTtoOCY`v(oXfLiza zVe#)-Zz6H5zCNSN`b4L`;@zcoI{R<_gBI3{sxIJ$fKa$;Hn#`S`1<|^H0Koc$wO14 zLQKZrBKgsxn`a-RW4aaTUk1?wv*~cSQnZHj)I0H%ultPy^Kd8{A+@ucVIx?P)V{U> zy7M#C&pN}FDt8WNq-;Yw%AqQa(79X+`A}oD55B^e=s(TN&o0{N9z~21XrQd0j3xTy zlMn^D{}TC`PV7WA$$(m>D?whbuQRd!9J?CU+w+PGsQ0A=IK{ZpB+Q725Ss=;cKEG} z@TsGz4W8w|w}%vQ!x58iD8)Wba8&no(IyB=`R37LpB%0^nw%46N38ucB_zX<=h0Y6 zo&(__lMZ!AEjuC(+`B_7wq3XpY-r01NEGSgLY=ky%i#kuYctglrJl}VPE{bZmMZ-^ z*rWNzG{g`seNvPUp-5<$hF%~^I>9KsxsI;r_w7#zb-5c}-M`eo?*_MDNa1E6S3|U; z>Ml8=Bb%2ry~)tWOV1SO%aW~fvz;7^bdRj)t7P7(t5w;lQ{B05LYybkCIT0r@_{)N z{3fTP+^GhUYqY7va_nE4p!sb>c~d@!U^EG`YSur( z&z$?4y{ey@H!7I*ulsC@ zE<4k^K^B*gKG~$luE_RTU%lpW^8n@@t%B7#t7Suxvm9Ea7Y2^Vu!bVND3ynv+bCx< zTLpf`q>K_`s5g2bLb!~27@Eog7Ub3Zh~Ys}Lx^-Aqdw_0@3Njm4X_C;&R!$(#}P|I z=vtY1=+VPq(=P1U(bu_2gi6)p$#Hmfik@b2hlBbwsnC8I$9RZipI}s)dS^uO!d)SC z%j=9*xso#;xUe{6NVM>hza!b|>aR{^dqjft+}nPpg%jijJa#)G5yrE43U5;K2I+f7 zFS^tJRq*#P@M#=hx2`GRU~0Xnf`i*h?W^GN1?Tb;SKV#X6wCa`Hb*Tzi7M*yxYDTA z>sXsOF48xB=q#mMxkf+#akQ(NFE5w<7PfC&L|}kmx`y8L;qZj|VXfe%W6?* z{rXHe0?2JI4&rEy{-{5VbFG_xA3*k*=}m--oYCInVqd<=p7wB;?@!t8FntIKlT458 z;P8)lA+&4K0^cjh8hnW5Ms|_g^8XmBbN~h;*i0&UO(-M+o1=Bueg^s#D z`L5zSoFUGOm7lIeYAJmJh8z+xI?LKaz|WtrUEJ>t!Ah$$DBmDy^du$uYdXhh7AN3AR&%n*} z{82&g5O?vw|DwTy@5}+>4xzk2Du0mmM#$>mmR9-Vtm7z)k56$@SL@7>&n%9SDq{hg zUWLBKT0&xQ14!=+c{ld=buqiwd+??K`o3#Hm*vL$v-Z56ntfn!x+Z7DRU#DsUh^mc z&`%#Q2-Z;o*`9Bg&5SqDLr+x@Pha0p@8siW2BSL;=G|gu<}1p8LlIlP%C7T`1jSz?2oYoz>5sMwf!3djC;q~1omH1z4Y&S{Kwmz3En&x|K7qr*HErX72U_Bbfr z>3f4_-Qyuu57TJSo7TTj8BrIuT$!hz-Q@i7tzogCPthIoD-dv?>A?%O|`$NB{8Vum^MmXsgKiX-noyioVH&hO(l3ZCQG|>C))mqU9CLEgE#0oAU!`g2&5& zhCfh&L8^obrjbhk^p01Ihw3hG>?wIRRoo8QuCsxQ&rxIyLIr$&x(cI?YgjASr~mV2 z_h*bb`bS%7VWKdpkMCJV1aW}1hVuDtKWkE4&V`sRWio&P0_c&N=UGR)kotGeFSEft zS^pPZ8IkuLIt~uJd|=E|A`Xa`{Qwi4m_ej}_yKl!`*a)J^b!jiP{XqR5)VLB_4}gs zjI2VqL6}O@-*fEdzY16KEH@Xiu~`AM!~VT=i;`ESZMJX$U15rWQ4w9WKgRmO0_Zk97_Z^4-;!cR^Yw1pLwVx^ zSKU^vizB{+exvOd{=-3XuPSS43)K~v(0xhsXDEcs2i}R;Yv+zsfhv#iN+P>39xtCJ zJT?n^=X^;}0pd5>X9q*DQuldpUgU((Y3=s=T^LMK_&oNx1zTYs(oYXlf98Z`akCyO z>=v%i-`9RJHrt}lTCT_*ie9f*cq%L0T0ejRDY#^w^Hy^DCx`VQVk27t7KLa=<9x_< z+=-Ig+9X|HN%WHs+--v77tM!Wko6i22Gsp65;yDBj$8paY79o=$2cNUT9n5KI*T>d zc-Qc0k={pVd_8Ijx0WhpHHK5X!}y z_I6%GbU^J|Tji}Uob!Q5cNcl>LlR_l&~;i09qc&K-LIpTLGN+QxVfm6QORM(cE{zD z*zM=|g@TK)dI9k<8yr=uT|A z4=ULpI=Yt)%T8(M7He}-Bk32GG;t4jFd@6j6H-`Vdx(@YFl5drp}K&p3{HN2?+{tm zkM!8vz~}%dNgooWdesjo85c7(kX05QfEt!3%>spV@~EUqKlA9tB>ll0fNtmYFj@8- zWmNn5^zQ=RaNB$q!m0G{{Z&y;MsiMm%hg);s92JM1JNys6Z{E`%6tz4j%zBb#_HNg zel$lVZY?;M)s8VrfpWUbk~WnV>VdADrdeZAYMd%N609+_5$92g=f>2719iNe39G&C zFbzqQs28ANIpQ>8;Es3h(Kz;=xj_GOh##r}gw}aY?jiMiPT~=uY+`)KU(`WOHTI5N z+HapDTK@InJ!UHF#YixX>{1<2o%j|$e1!O=LFt1tr{{jz6F}o;j?^M}AGLzn4xRZE zCOp80{+@pED8s6~;f~EQ(Qfkw;&`Y!>D0fw3AEK1`jNhpJEp&mJp9e}F`-pI#PWq- zxO%Zf%>s&4FUk*q)iCE}$xq0E@vy%#m0rFCHFPWU0B#)f^&`lf_cJEdH`RYucpqJP zRYaepN9P0Op2$P@JLylRB-sopF1*sug>B#kdRxRw)AEBg&stoV3NGoKb?1-Q0e#6j zh+-^RRb*ny5E*N~<$}mQSV8(=*uC>x5?X0RvCI3LpsCCXS%V9iJ9r*<;RyNpC)Ljt zd&^ub2#^FofmOl^eq^2q0qBy^L|Nz>5a4z5NUcqej`-yAV6PP3;Prat^efCaol{%1 z7{U=bp69nGLdCRFs(?+f^10TBJzo(iPyL~yb|Ycj($d~%nWKY*wYC4M#Qs*^Czw-< zH%JV1hVD|;&!r=VZR3f#8PaBNUQ>|%v=pl{Yi3JBlh?<^1>Btdr4J$TMYv~@bddgF zKpO^JlRW?zldBH^3(jB(5V7w0%9>j0Ca7@JNz7Kd5z23FslN#Q4u>O`Nqqiv$YHmj z8WVjTzLuuU!=aQMav%H+#$dEbJ--inpu3C&hYgUiQm8CCgLDpzbxnmV_>yWw1sT#a z6vSf#Qz7QSbP~fB73ekD75VZt1lgZ|&fg4fw*l2!QwK+I3Q%im5aG&a~;pzP_ zKOKBJZ5EYft(ebEdS)y;)EmZ%=cBdH5(N^wrm)%JV0P)Bs?KSc8e_$wC?-R73AtC{ zlw!WG`%Xh>)|kh(;NwV7Eumg?)MG}#N!HhY(Pa2vGYErJ2iuOE2a50-3v?POEs zX4AL`MG_JpyL*+g!^HC}_Uq*qKW?I}BPB!J4D`xF^n^u8tW^&2oMLadzliz^J zKG^r-Ek*l4ZheXsPx(Mhj2}$+EYoA2fyMuP>UNwo-zj$~NS!EDZ0p(!p6@R!rtNdY z*55}1H__hUthj?hP3IGlJ3J5MqvQIfcXDbu3iC68kq`-ydS}|>%S4iX8pG>8h8Bmz zJ$t)=jVM=m`#!j;p#G6`W?PCXK@|NZk@-}FWD>-$??d%kw{Mr#2#Amw z8F6AC#?BV@;J&Ph-0p`osif?kCCQMZmv_h$c(|&UPVIgdDqnxGPQGILo~{cmY-06T zPb=C|!8Fqg@nS)iv4Jw3Ry+q`!S_{@#}QRy|7V`J-(&q$?b1H75~wO<>f09ctYm(T zsycpqj%1nLXGW5uh4YlnO=dRokH_Y|!H`+5see}_Hj;c|($RjguSTCYKH%k&gsVDVDQP>G;a^j% z?5qTIU>3EIF~y_}MB}^70B)#z@bEUVGwyVqr)Q%k)IYA>LlE{`rq`nVd9$YlNrv|Y z))Z|t=X*9XFg?12KV4#xa5yCr@tus#*O9q59Jh`S>OI|Qv%f~)bq_MU*H^ur9LlA< zBWjpJf}wOh5{2D7AXA9n>yaD(a|8mxm99FQPiIjwA|m|xKlHX0vd ze~^XS@8n&NF9Sr|P|elwDWdzWBfa`eAL~@&Cy$ywT66fU6#O}|!eU~xW>xJ?bT=0& zy4n5asubP_*EIB^6Gh{L%ONaS#I?_|*asBz2$cQdl9e&F-*m@qyC!@1OR;;^eeWWe zVu=3`O-OR#IoicNNFpHp+e!sAT|7^QNxnAo8jF!cfA@BJL3;n;jj_IB^!d-~ecutP z^NO)gAVQjmun5{SgYqB3@B;vQ#}=Gn)hqQWr=t?s=I=U!*S!e0l%E}^BATw5>Mg|Z zz)Ws)8sVW>8 zfI!1T9p^5Q*RJb%3MPGk@njeS*QFp?_g^5S;X}j7e zel@(_&9I$cBPTua;&py(a1Huv`Nc-`hi7E@$gr<(Y=2)j=F=X{ERs8RtC5P<1Ko=x zk=Q?uWhWlR>u@oN4sRz3@fihAJME6w7SNl4aocC3$ymn2!G_%%4A$_Pzm!vTxEpH~ zT-%)XZD}rz#Hibq1}a;Z`GO927{&S zw#2XHlk&$1m*zxWQ$LqKg|k0r)6q25XpcYFp*NSOGp?uKE$Ul!uT-jUM>VG+)&nQJ zRX@`Xl|2SZw2?Mt3U`FG;;llsoSB1A-3f_zDTVj4(*=dPE0?b%lU{EOn-CYdmCvk2 z=b8_x-3d7iw3oq6i+c2+W?&UpuOq5{5d^gRZB3WosGL7U%ayPmyKEMmPc>h)LYCS-*=QHeVma2L^-!#!}oS|h40Z7WlPqIm|D>Al_NNk zhBX<|;&TI|^VHyJlH4g=pls^=m)vnpeJ&JxHvP;$^_Flg?&x?#dtX?%I#%tXNxAE{yJYy>c9@w z;>5QZb8g#&_xdye*1IXo)B71`OL`*an%Np3~xo0GENDsA9R z*RPjE$DcRIt8tpu6>MG~tW6VB6wq=-0Qwhx#r?WA=&gnT2Rq3M;}{R_b5HjKnw9~t z*WPVUrvlk%U3fqgm3km-0+sURvq%66g5-g1t)6(AQJ;r3g0}T3lzL!Y&?N5F?iDv7f(~Lo9%L(vo8O{J511*|t=iV1$jnn%i#r-ON zQ5oMpBi+9A*D@%Be(8K43jJ4gcyg0NO7ZfY&(xMNl4PxI0-1_`g649h=#5%+#u8#;z8K!Wmp_ z0_GcrV{E2t$&AWpBYi3#_lI%NP!i%gWo#UC-p^g0xiz^XNp9Zy`-d0m%NSK_dCiZu z|C5w^)YNQ|3)4J3PEmY5)zGGjrt%Q1lB=6T+_G&>%r=cO8a$5438=L-qpXz0$`%w> zu$<(OIy4rUGvrboP#owg?<4%hQpF)C`vNm9`W^AVSM0PFr`!yV*c~y2Yf!Tv_|JPk zT~x@mOhIPkiCZ6JFmOmA{@t$H>u|(#C+#x^{+pi)DS?3Wx;;JeB+SSx{^?jBw?|@7 z)bvWfpg(hA^Ru367S~X`tl#x7g5o;>lLd9~K#>K+HT>yKxE?4G`Q~B;0z4jD6 z4Co2Yi7lD7f|h(ga9K_a(+9zQ41@g4PM+P)T^Jqg$${&O289AOCh6$hf#T;i*yKRF zx{tp{jT2569x`$4_%hRXf0fkVls^^8jDO*gfMp3b`)sT7+LwHl=_Cs&`&%j_7pM~> z8KUhu1iJX3dq!u&ilFN1DuNFhVIOgAB+;Kgdgeq^z`92lb~$Osx!Nr~$7^3{hclLr zQrMl2SGW(rheIKwOY<6lbLr=s^nARnf@CKsjjeY>9PIG<|0l!OMyGRVz6R?dd(k6{?I(L~NdYdGsy-$TcGo+?Mhgg>LJ163qw9gsp)2CCY} z+ocMcMI$0oe1(+@{WfHX&*7k0uQM6$Hyo{EgvWO%1vSS1gx|x#mv!>R8wd6O;>PSq z)NL|I0{!Pnm4_5oO~ZwMro)Ax?3X)t~KV# zdGFm2?ju>ugW2D!7xl#61@jMfwC={OLaXd~zTlAjR9DoaFAGkRfPqNrZTu_LM@5OW zEA_P@T2gz`ZiaeQylcMvd*-%Y5U?+1T{y&xc55&!7iyEt*z zSP~98l|7e!eVex&C>aCv8X&=-LD`-|vJXwU0rz1kKfF*bQ-OsXUr5`XsifXccNZ{& zNq&I5UjJb#mKXJcpRXmI$tC{aY-2;rl%#uA60z3ew4#ZxB_xhmwS7|qXaD?e7fuX% zI^J)aGnFddSG%|By%5=+gD*u?J5u>fk)68ZE9#~#u0C!%vNuM<5u_NQyL0_3IgX&| zrM+vyK}AEa!>$ezh|}92?etkNT5Y*6?FP&0PkjtbaX(ypJO4GAiA-YM^7q!*%~>ri zVY@fw6;xYBKXWe_gkS-KL#_U!f>z`WPVztcx8q(ef`iJlukxL1rUK zN=RoME{D=l*>bfeB2kGDmylI>{V4Kfv>joIg}n?uTD~NYy89#Zi}?BwjGsvVi?!|k znzP|p?zl+l66QJ3>*s~UnKywBe;^5~&TuXX`uhF$Li2*F`B%yYh3*{fmGb9b!HY0& zYA-8Tw6p%%Nj1mil?=i|)V$YJn!x z1*n|oJqa%aN&ME&)s+%W;b14{Dhn-Q;EA^h_39e0(FyN;guSl%J}lJwqt-iHe@h!v8d*4Zgewg_UGGV~I^TS2hs`u4Hg>k>y$ zvvh8dOhxGpZ}Y+afmiO$`kNg!sP4zD5MGq~z0k3&-GR=^eeAAkvd=ydWOtbf4|24H zZ|*|dU`n+bw`Id&51Lrh{~YZ;Dz6SbJfu20-b$^{)vmLW`s|X-`cnD-G=)@}JUfkl z?H7_|Ib5~V7{a()CRJtXV}eYiYmMt`vO1edlYux%P$@G$LUFK^PTrd z@|OLq^p_WB%z#otz4qHr3ex;(5}?e8Nux}C=RAVjiwM|w;?Y`V-lGTa9S|D`Sr(F) zcm+R~x6I%H7W4%w)Qfb7pyYk7vvn@+3rGBJ5BoMuxT)j){%{}rDVME6`9F@lrI9c0 zSDN~OgYe?Ck6_KYe#wqklnT+kG!}p#nNX>|uqMRYGZ$6!e%*&0$s}Ua*KPXumLdv< zx!Dnzpf<=S6~+;HeLmPXT_CK)7EA8L0Rap)^GiW#b9ydaVu+8kFTjNJOi=f&Dtz;S zhSu~fmR}vf)!~ngDzx$HXi#i!rj0H=IDby>$ywnlekSJ`F6UP+YJ&SKJEGscufQsR zr#I}Q$(QECBkj|R#p@TJOtZN0-*{n9g@KesN5vC;0b^?SmBKXXrTxBmh>DkAnAP7+ z(QO!gB;tj9Xp(}UM!llDL;K*Gh~Xp49k0j&jk8#?QjKW zx}F-I2&@zDRp+ECt}W4>?iAI3!-*u%2{=+X#F2(5;PvIY{qDo-545w6aei~j69XZ2f=M(<#O%$Z+24a9McoKUegye z$R0?~GAepmbr~UH{|@iM2OuRhp3yGB1~JO@*>r=!$lN&gzW>8^vx6tV7JML5N0_VI z?I0ToyU7;?&BjIDq1patfFgL;x21@$XEi=$zeE=Re4QPsQEM^V8bA%Gxt~rE13Q7OadsslsC&J_u)p6E(iL>(PpHS6eiP zQNRYjIDIsrBdPf8;Sbdql`4Kr@UQyfAYIiX%PDVnOl>)tuhc7q!GQk!lrmRmFJy>e zC2;nQ08{tT>C8uz(8$?AVa-J*EH6k)@vd1r1}>k} zaEiX#WN_9yg*#6%&&A{2gyPQP{?z3_KW_0i%~f$Nhm?cSy3|mIr628L`F*~S?9D{) z29w5}v^!57jRnio=FWU)yM6)Twy$QM5i;7!`{5Atqh>ddYDew*9p%H9U|udAkXX<% z{QS3ySZhMR7OIj{h3D%CxGzVQQWl^k=6hl@!&_Bu`-EV6KgnD*K7ZVc^0x(PAU__@ z<)@`fp9!Mue_dPc&eaE8QZy-GS(&xNr=OlTp%J+aTLdX+~>ILep=0C=`()i6j zZyM5dg3#j)?h!7N@TyWdc^cN191K^GZ}z?&HuH&3$Ez`M5g#;j4s7FvpkJ_=JfiDR zwe3}HL3j`sh)S3Hi)~ao!VoNkAu9l{^4(AS{4Iv=^qUPjwOWy>t+PAsdr#T^%%)5D zNZgzHbS}piDrE3ck&nj+fiH*$UfSt_nYO}y%(lL6hN8W0H@|qR`$AQCpkW57YD7)c zo!0cJvx84L5TkR*gYZwcdG|avn;wJXVDpQIB_f)unT{*BZ%k#Q_h4GfDH1>ZzD~;Y zRrOEV|FlzpPcGxOKsU8?(Er**{ca9->8SJVW8K7??-U2|AafhK1XGLj zh9eEy7o%Z8bCKYcA{D)}(WRB~y(TCM4Xnw0|H~#`mq_ZwN9Qr;%RAZZ*d5x-N6fyg z2Aud~#|M27y`YtsdJCXbRUy0fu`nVIY7($P-RCx&0z5l@A3z~ z(<@QD_KE(~=)dha8<(0=_F>-7(SneKsmBT_l3-N@REt zq`#&mb^CPBEAiyM2aeO9&c_tt9Gk1M3++m~U-y1QQi|B;uqE-1HyK7$(g%QwMMGmB zR^pch?N7pnEuX`meTSuK$a4RR6SKH4VM@y{T@`Vc9}gcD3+c5suTnHA?SA3`!8*0m z&q7Q>Ij8Lz9d#jZi{ct;lAWRyG7-`{P&eT z)g27SuLHcB9U|EmjA6Tc!b=o0VD*6QhW6Qhu{7KAh^>V9m0wZRwTv;FdjHg(_lL=G>G>I-_HYlc&U7XM z$GUBjgLdVt%xSXNiaq_*|1n}RNHkI9lv7Si1e+L|+Y?rG<{>tJ@TFTH`oVbd2G4b{ zDtP>41@!v|*#(L{V5uSW=6Wr;TTk+ji}=HBJUSlC16L5Ud5Q<`{5`M1?s_6w=JX|p zXER&g=eqaP2sl^CF@_ng>GET_q!=Y77mcH2jqH%*rw<8SNREEM0&bgl3x)L;93-XF zY({i{?C*mr@Gw`ww%=vH%?-J@eY*bdjxJs|Yj|N&MU~qZH0MMbK%p-nOt4oE=GN7j zncu7ta~hmwaZ^b9l(05`hPw%@v+xS0!P5>zKhLB>nb!+APuxC`gNnhd4e0Al@s|sJH~xZMJIf@q=IEwI|te?8pzz zo=oj0h*wU0k8lGyyVd9S71pgef5J35#{1w#q+Gqd-}Jq_KS^u)0;eAo={SxX9!)_z zHEYr zL=*ceJsqV^!%2N5GxL#jj-#UEBzDw!N$2!wP$5+KRi&?jG`NjQLfh>|0@m+1jhhvb zHayk#*oVm0L+^-cS~vIGo|zPayJu!{x6jd~;oY&ul*|dlmL8uE{;bVDxQg10_0WaQ zV2}1hdCt zowbjjCx%+8hSUu~Glpwv(D16%63~+-zw7hm} zg>uRQqyqhiGL!zrU6|sP9m^)3^grnKpYyGqgy!KGZ!}E5g~U{|a73m66727fm+$^8 zN$B0X8ElxKO9mW`N2r0WB498 z(!?J$eI=i3D8i+Hg+CsBzLB)IMo5c9m1Wob1^7ie8g(FiFeaDh^AcObMuQP7PB@AH z8yi|y?Ps?b`&H4~74a_t!;t+PdXl6{$4ZhY_05I*FaWL?^!J%`)sISaKB=xR#8DuY zG0FqyFO)xFAJHElK0IP>sh;aQI;TfJui2Y!R3b3ps$4{0uRoOJohJLK^|!q8fieBO zupqt_1Y6cX&}3co_$KRwwgvZ@MlWhRa9aIWUKYrk$s=%?Pfz%uWzXUU^QgKqJX(Ew z9eSpvSUkclz1+tk58c8Df>W43l7j=I3jwx<74_iFBQPwA zc>EJ45Z!%+1r7#ZVK!dJW1$HSj|?bvRc_n(^Y$G4N1N6wR3=Q0$9T+Lc12?FnT*jJ zjVoi`p&|t;~D0)&&9Jh zX60bbP*Y1-lXes{#6Hc!t>mzreutb9cXg)3J!IjyM)rEw&?M(xKCGkq4#GAbql$0> z5s|wnOK~JOkrRHuFd6XC5ThF2}+&S?A(*WhZV^p8J*A#XMuJ(c|7ZLmK$ z9j_eIiI?(@!(pF5XK*C%euUz1{+QZ}Buxpg`q1b43{i2F*5N597emiqf_F{;XsPCF8imbd3!ZRd6GeEz*s5DxEi zC+G4ra-5F_r?ElVq(|AhPhp;BKlq{Rqt!hnY_MJEelV|hpLip6@%=5%c5M&yRX$yu z-{WT%S3i(%_0jRK0tfQMe(N@9-+-fGR@pg%d&#m5wlhX0f63DPXov*h&^L3QnUe$m zR=OQn%^i<+T)QLlsvfuOS@CRxcM5ZVf?=z;HQ`RM5>T-9IBztLo8Q?V^KFlT?uReO z3$BaSV*StDJeypL4=5BoY0<4!9(;{@NEYi9UQ9 z{C&qFwB@HLS+X&j0FrE%;pzM>>%X5o`K_P)Q#lT>yMQb|J}vn*++IIC)W{!TQD(~c z<|HSKtVJ@7ulx8g1lA7vHJAYUD%Ylu?S8~lJXyKl!Uz~_351*UGb@jB2dp}U^^ERChI8qpg zvF%u9e%j<9>8Ml9=E#%J?0g-~7tH2sSae-{m$q zRqAH|hZchJB>g9#v~($DZNb>?Pmw>zoj5Hu$v0wsCzxI}huqfg#w6IOFN24k9N8(l zgqgL+o=A+bSEZ;}PyGs70@{}UW0#0^1mOz`_`}wN3hTTfcj!fv{d$G8S$SKN)V2*1 zj=Pl_P&hCN3y+tMq56e=P{`Uy&rIKsXr1wMnIL))Wcq@USTHWxa^xCBcwBf^x%i|g z!j8_7T;`ZUB`npfv9X2-&&%(0a0vX%kg>H734dlf25&2^zeMnv#znZIQyB*nRB?I& zl^am`;da}Dt(Jq9pni->EfMbOg+5_m)EZCdyDWqb%`wV_GS16I467DN#NFmVdbiK~ zjnwN*VUK`Aaou-QvNT(GmqG8+w{!ey&W{sV)ax7$?6YVtbqARKQ`EA?H@px0L3YP3 zX3uOsx^JHmX+!5-EaIv`i0TQo2Q?GjQor^S#~SThuO~z!72VNcn!-eLd)rR&Q%?rJ zmBrbu=l2l}4gRrS;{*2TT^*(c*QGgL*!?9$@A8vbkb#U~^w`GWucqDMs4Ki3f)|U= zwBOq$248UI}^rlW;_886x+nL!D6hV(bOPHSAIbeRm z$sLx#EsX+`dl}TXpQXV6sa{y^InmrW^y_ef95kzc({1_K9!OW*JWl0lz2k!2Jw12c_9ub81r9q zHg@#E!wFsz5%0^H<*UAg_u<}m<)a$Dcua-ok;$YE^uE{m**uzlB2A280u6og87}Wu z_8!Fhx1dgNMboY0Tiol4a`YG5zP1B;)B9+;(H}4pz$nt~Sp8gC1k@@}L8tv0Ye~0J zDj1L{S0fc{@lF6e*4>^H)NfOIgeUK`c@0nVd}#sJDG}U$c}Vt{11w${7VX)ib=vB7 z?t@432^EzG9<9m4gqG>CI-L=HgeeFXlXtgM>nyg7Ua&BLQ^+rqG>5ld>UzHK<4wHT!RxDcgRZg}!R@2M z?E0}V1n&S=ROrW{uR3*1ZkUjTC;evQR?nK`8DCH--Jx>)sla-#92c*=TGlCKX%zdo zZdE`^O+p{D&=5d;kc1hN$?SzuX`|P@VtAlc_y%SLWk4mJ z2ecNO&3&Qc{XrPahg_3skU7!=_c`JSfS!L&B=)lze#;*(cDXEHUjbdm$B!dCRpNb3 zDs4DDnB>MOLBXT{js$e5_=vy$L3c-%ln>>6)lRPXG=9M=+8%GxW}s1s!C<;@i-b!T zo~zGzSBz>M@KO>DTk5|62p=Ji#%suHmg%Bo<&8#K>3V;h3I5fQR29q5VowA2+7yoX zMzD4r+p5&+vvQ(7_k0=v~rSSfB9%Dm{fb2S^k`mHo(QsMh`E^pDB-;KU!;X^y$X8ij3dNK~k z696%NKN^@VEdmuofp1FkhfI@=%vDY>LesC7Y?KG`Qf+f2SQpSIpJ~hbUp76xnTPM@ zT{TgJO~GaQHQx`n37>TeFZUVQQm#Y1)l-B*M{|EXh_QZUYFoX(CSv1S-AhzK`Wf)} zy_KJPJeKnft1wK4f+v3xvg2^VC**yIrpw1yTaPI1|~VdOU=tyd`xI}r@+K*Up!x2MWXtWcQ1Xl zFY!_&HOuz|r?q1MgH?Z`j_&;9>x693Vm@Ag)_OUup*_8Nimv5DFHE=8-OQUU?xua5 zB0>(qiUtD;{y&5|4g3viAUOExAtRkZl^}PWt@k^(v|WmENu_dT_Zjsvmg{p&OEHdN zOu=8BayU9t{sZ2Ue>`H9PNzo&^I#eha|tPz{XNlyZf`iIx-(D{cn!f@t48Q+>8LM8 zeG~(52>i`neWCrfY0(SlT6IL4V@Ut_;NPjLMfdIm5f7C?D}L9)0}!GxFvXHdP~#VY zazOOrHa!?ghJ*!9t9`=Nu9?E&Un3Yu?N_$0P^KkVT;f1@SE4r;>xz4@Vhs_V+MGTR-Xq6~ApGCnS)zGH<2V{nWqkm0{ma!(Cpq zo%rswPe9gZU6_WJ2^AP7XA7zHi@7+`;m{EmQtuBJsR_;=XW;4y-$h%j_mQlr{CC}S z_XY~dn|}YI(ESDdv-~pHD8t=9g^Yvt;#=Fwqs9<#EERHS8sw{ZqHQpqFHI{s?T}mV z0hB3_WZiVs(P53#3dVbH@yjcv<+EtM zuE(OSbPhL_aBaA4kJk2C^3zTGC8Z7+S@vr%_v&N`;j0nQyu=|uJDGN0zN6k0!za0F ze;r_1O-&e3rHiPXzO(#oq~R>>a}YH|FUAWfb%ulZ}p3q*7OT%eDKrw;}O>FxA_ckMTYGn`0j9$5PZ?k3e@Lk=BMNpt!f5H6RKBGb}d@+?OYKA30cF-Iqi0q`A$0 z%kCk~9-BLXTcRJ$?2^b27&x->(1?~=Rbeu52ROPKb`?|&|IYUyO~`K`4RZSE=iX+W z2KL~&d9`A(vOm|pZ6PT+cJu-s2uYZhY#yg3h2J;HJs~E(Y;UEx-pz@0fdE2EtD$H5 zyiYMxohZ*MYCB4B9;O66Q}j8btroY6bX%2UauO?bX8OwaYa6F7B*bn1YfOLf@kQ;+ z3isr50_0OB#Zq|LpFfW-Hr z9^4cOE^uoW;kuP3BdF;5p2_@OZ|=!`gvt2c_eYz`J|n6TRxcxZ{fD5lK!6!|17ria z`c_{ogdfLa_4Uu6nhBU$Qz~&bwuEx!rhf@Liqf`e7m+IAK}77RY3CECA#j<-$F&TnyDdkfQw2 zZV`EVGtL&HJ}AidQde)%qleANKF>tO>YUAuK%gVZBPbZ?ict6AB%Whz$3j-=Bm zN}5P~50~fL|N90?8Y}pL(M? zYsXszJ<{y{_i?M^7#_E^e|I7Wo~^yAiYzaj$@WeXG2JT9==V5=M4U@L(3Bu{WN%pY z477N$ACL~KSnmo4kTL6#;o|fd164UZhx4h~n_wkD0eX-?Pb-hjP?Y-i(Ma9wUI4{p z##)j&jle$54%#czuUSlwXQ|(R9ubNLmNt^p;C=AcK(Cnl$%!k#DyD}|D{*Zl-|pfj zamml(yKP^mhVG5d(aet{C4O5H)@!f6OI@iM*=O^srXcaQJ%kp#DRa2QfXf41YpM?oChk{NecX)HSZEos2ml1HoTM` zzw%+rY)kR6D}2ZSO(^ZH=3c_cAfQ4tBm97)yjB$%tnGI4vc9wIlyF#l{KXE@&Y0D+ zATJAC@j|sy3X|Y&Q#2vAkD>mp_38v$sKm>Kx435Z`!o(>nWeZU_088+C9S8SMeod2 zgeFQ_X6o;r!eKE7J+y(zh8a@Ow|GdNLOH%~&anj9Lx{iQQnx4dc>a9Rj_|d{eTpv9 z_wVgi=4ntr@SWstJh^{2Zt`v^N*C)055&5U;|HH#6c&Kd z^xk}j?&9m4-hVluM;U*8&8ryxsi-F1%Oh-w@2j~ZXcHW9e*D_?6fu!NJkm=AY>)yE zfwfR42+`2BP$VeV-a7PVKuUZ}LV)pthVx+dljI8^X>pOndlzLFB5@J=FWb1Cy<&Er z3)&s8m(Mo=GL?Zb;`$xE;KIVkVH06sm!)3F9&h`ylmee$I`ei!FdRLb1w8nYI^(b3 zGCcok^7r7pW)eNUSuYT7s=8$H>zfcb>4rBOnS7X!zv9l-Z%>x^IoVod&MIVFuo5v= zvKJoNF|M7K;7jHc0&?VFlteICp+^b+35J=)monRu=esMIpLHl1MLu3P^lX{UBR^%s zDrTIsab0e;&lB&oKT}Vlzkm-d*v}>{J{W8t?D;K)ABLB5c0HY7-o9P3``msr7$e@l%#W-w?X?4J^DhIp+n zC-0LU)6n;TS;wMbWXh;?^tt0oOB4qfa7ANh|rq!D0BQn1q&n#DE zTurtQ7<>+%S1uqCaaU`lmU^bxrz?Ww0}Hu*eI<>_q2oF&blJfI>gkJL9l2G1r1p2v zoNK-A9~!?*&eS)XgCzp`!$P_nfF>Q;sIXdJz4N>NMs!&P+I<=Yg?R!W<+0Q+uQUh7 z$PqGmNfb#HM@JV%eu4rfCAkcuk8)xHKY0d!H2_13&ozm<_)UH>tuK-29Ku2&7K>ETRANR=$?CmR z|K|Ga+$P;@Wr?TBn%CaD>jC!OqFF?7#PM;Pfw-yy@{?)$c9o!+#egqaDAoZA8d+;M zvKQcZc!iA)lJ|&;W7k%(U{HnB_&op(7Nb{+I4Mv^`rW5?##pAN86doq5ZH10?H6?M zuj!4vJ&&D&eZP$=y-x#M6Oq7x!I1k5>W|}VNnY=4ol11vg)?v6l+t?{v(*h)9|`Vb zAF0tq$c+4#OuiiZXzh#q7_9hsg>jy&(VrrsU;c979yR;|e|>|Zdbqv@-2L5Vw8x}U zTbkHSLd;XHhSV&Tu@d0V{p_cD5SZE2b#&x%QUa~X8X zeqXDHe%eM~=CK^t(ddvGlcSEpKCtc~x<5tW{ArBN4HHy7ziY@5W&>oy5ja~=Eq1jI z8g6UE$JTX%_zXG{SuEqKL*%a>a z<=tWIO$TOgP~&NB_shP3tVI8;lfG2Az$rg z^y9aR`35C(&e#C_@ptvnRbt}fiji;kBpn+DttL3SnFX!nkyO#dcj>dri zG@T&@-(Vg(kH%mZJ!0Q<8(Gsxruk+=@*YgoRM>^wZHIkK?U>$SLjdTmf2)7HypNV} zgjz(h-8HHYfWEZ-1ReCt8E>sIU!1qHm=XhI|4JOps$Nh@->|5E+W*W^!r-Ou8s<%FD zBKmm?QiNsWZzJCau&CV}$_=*3C;)OUVD{nAe$u_aWT*W2hsX5=w5kAu5fN~;IKHIp zVew2F-wwmY4~zGzJsflR1^~0eYDBJHo<~oVjXYaC2lcd*p{!|(9Qtu1?7q7`7zXe{ z*luyb+|sKmb*bp>fj;kia-dfC320tD1JM#s_s-I~Sc5@~Rf3auqg^z3H?o&d6+tdf zQIV9e^t!#6E`1NF8|qyE1O;~SQ9N`J_Zn>UNFkW_&n2+0j~I>kN4y}E8*Sx4aG1gQ zeq$-ZY%k2#PU})!5Kspc39XFmR#h!ijBgxYSfug?fB5|_F5xuUp6r3M(z!p#exhDY zwdgO!Xq3V^M>nhVl#a>fxoY&(11W9VChJ-p+n{g`uh6E4STx}xc1x_Fn{A(k&~HHHSC7uvoZ zRX=t&2FYifLDLE)P`b3M$?C!WkSa}n?+>ATH?KTdSY`Hgi?;~X-dZxbBaC2>5*3#= zKIXbop#6wCv=D$kN=Ju`_}X9z&i#7zQ!9OFn@w&2td+0xr8X5TT3D%nIbk0?-SVuc z!BKxm6v5w+sIii3b9vyaa<}|QNkqsnO&d=&wW-MYXb`Uw6U zT;*l$qvT7H*(UT#e4A*yd}@z1ido*;mlusJ$>hbdf&3==;&F07f4NqCfNB5tz$`!W zfGmZ?oiU?d^PQh>@gb)10KXp_00Gx^@9B5HZdFTlo`+7F+1sbc=?L{4$zQ?LyEb9? zeBXbkAGsna(TIGkDqH{EBwJc z$Xi!^s?^Z!POkrgm?G?Vx`c!Z16^s#^NSYfOcqmdRKVflI{JPa9$7mj7dStk1H|SX z>Mo2ETmI>o;GFLu+7XXt7`+b+HSvq(FOSw^pUd*wpH#N6%~$ifgS@VYZMH4PWZ?R@ z(ry&_^Z0s?JonTpk``$D40%OD0FNr<>KuHyxQ0E(9pB9yr*!5<&3*$!yX#%d?N6QG zj#tXE&#(f`oX0Pb4?l_R?=Bn=_9`d9o=dCV7S?|cP-1Hsnq^eCqUarEiU{+V&!Tt; z5fph3$WDH)#pgevX@4DeRc?7)gEsVUC#0WG8b#K}HG4RasKa~m*9Xg={SI1|9){X! z*l`cdmXp-}oqRv!0^Iu_I}!rNPq1SrpKM4}x^Oz1{6oIc_+gZw|1b$mz{?Yc zhwu&*axsSGHOb84l>hZ6XE8vHfRVN9W+x`|G6;STL2j1HPb7%xTbb8NWH`Nqd7@VX zKZSG~6+uIO(at86=TDBWxK*6&N0hFV?KueiS0bY>`~uU?Q9Z5B$Av*d0B8RKDOrJP zX5?IZUGebSvoN*JUGS~MG`>b<7fhi>&|Y5cGj5kk70 z(0OkA)3hwXHztG;NifWH$XLB(riTymUlEx7{C-R_FbT`$4a@zFA*aW{WdIzT$JM=M zRpQdp@RNOW45b4Oc~FJI4iGH}p6 z<*(}Z3xlr0^Vwc8Qq}j!BBJkHAZz$~KH%a#b>~w~3E6(~Jay1eHQ)r1$tLswlRd{k z%{`)JU40;>RN1jCsG(ndmJb1wU(&$Gf!aQF4v#M}{sBTU$?=XulF<={zr+C;*E`9L z(p-!WRa!tZZ}&TYvucwgYUF>~)Z8AVVOs}nb^nSBCJ((}sOA?qj1nnRJnFKRbU~=JIY8Y{t)4Jl}jg{#)=hOVoHkqf(YpC*fC=txj zJ+qgilHZyV&xc?dm@?}e)f)Z%G1dKR--BHRHjNm6TwUF#R-sK(g)lM!V$uk!kKd3o zECsdcR9y+(fZ>qOwd7x$JAdKxqs90IriF_uY)sW|x_-393H}#|R~yJX{ZnB#tb zm&M+wfw|>3n2fRE&%BxD_#&2fLq!TWKd6AT9f}%8z(Ki-Q0C9A4u6H7ojFfO6H4M1 zv9nYM+8=XJ)-E^o<=(VZCf!i($sgTb2+|?X1^edpoFtC6WwLS6W-k^!Q2O#gS8=<4 zi~CY^IJ^(w=_G!otMxL}Cm5@Lzy3r&hxqa7QsEAhJn8g#e)(A8>k;9U zP?5KP2dF47*XJ}2@LNz@?$WA0iSw($>L%_~Pr-vyjZ^JyCa3OoKf?xTk26Rql#1ou zouKL*MO}R->lbcsWM$=4uwtl_Abe7k*W;CD*Yo>C9OKKKK>JsII_Q^5?xas90ok&T zS#_!&((t1Hrt)w;w*}oJ@!=cPt$jT8^YkhibktMl8G0>Boj!&ru5nyf8?4STJ#QTe zcfXSX0SrydXGCOe>a}ow&cDljwU+(v?Kzt}fsg`V6AUp)R*^m8DNcWtkmtHjT5MIa zMP?(O6y6|ZTWC#MtqrcrQyUzQ^B3J`2h}|u?+23ES=mDPn~$5)8LS^GIx^k(9NzVJ zL^s(hd0f~NoKkuU$R_ahbLolbnCVtjWU0!^ym>CC7#J%>9o8fGEBeCqpm$!sJiWPnFkHy$sW~UC zck|CB4EKTw@YpeqI!m9 z+Vi5cYd^Arm+V0X-1{Vr^o&v?_oHFAa8HvNl(4+$`exx--dS5giP**1f)}t(1+T$2 zkoFWoLpepXLb;!hVmNLTNTaFpXz;P%4SP+{3z5$<{W8;K!0Mf>g_ZK+h+BA_{(j!y z@l6Qw@*|T84fG+}mfzF_JL%aV%O z7N}0|E6>94_wmCE(N(YqiX3?mZll!BoA3yP`JUwA2{v$&84s@gtNMLnyiVHE%Bh-r zbMrV^zs+HP?_%9xZ_#kw=EmKng8rD2T?{*N4i85C{9L17?2|8$Q7CnSxWujX@cZ3H zBuJ5bMa=SI4{`iG9=8l;r+i?T#8c*)3P4}SKN(|dYTi5O$25iZ%zcHM`a6#s)IwI1 z4W`i(dU||TTx%1%6H3;!jwM$Lb~yi$e#>As&mvFZ92JG`q#BeC3_v6 zDNLv9v3Paa8K<0AY2LpQ^t{ok_{>0s4>|XiKk4 znbrlfnQw4o4=bzgi$oA{-)R8wmvlF7ysbp(9@JLOxdTjD&l&?zyffuh;CqCVWN z^ySu<#9xZNrYjx=FhIu;_b{(mX7hQJ1hK~rovWF`_t;S^cr&qMtfxCH?w;nTaG@~* zD^=}-KSOzhZ#V%xDxhsBdmNo#eXN6ofJ$W!Zn=!vjdo@vec^w#3w42sTgiAMK);t^ zoIPDWW;di(Zhy)W<(b7gbIQ)&TRq#$Z>$JZ(($HQYy|0aduNa))+!9RYhu&iYhk3# zGCr>3q_`o%!)=~-8xs6*?Kd|8TyIu5OBKoj-&0~U9}rmd9niAgOY-RT`J5vA>L##p z#ELN%810r&{W{ifvK1hb(z{vavHndt-z{!dp??;(c0D&KZG6Z+wnL6StbJX9Tgb|(|sdMf<056F=XEVF_SaX zAns4&VrJ&ErvN`GpsG1|2R$R9FL3erC?)|?VAl4aK42P``f^Jgh8=HRAIkjZz~)!( z_ZVyjRqdL`r|`N9Xmn;bx(siJG6B}-^pZe=XP++e590e6YP}3L1a?Qfr`B1b_@bZB zF_vT|O_({tOD4j3MojC6X*wsw+QVB>u1i$*q3cHt;IKwWpEPE^7>3+%2Wd z*)gc|l9MOQ^c#K3#i_hqFvu@S%IvgUICx{rf!-0Lwl-|k5u!qFkG1&A^9v~Go8zF| zB6%)F;^#|J(Tpt5jjhT@y6mfz`&(w&MhjvfM63&z)H-qI|~>%qcakaITmBsgkTR4Z-yE>!5pF zz&IU#iEw}V2S2^t_xC(9IZ*K|4O&lC$3?k^It#o(@=>f@(hK$h6hBvJ$#ANvm20DapK&u~q{t8gg;oUGn1c%{opI;H+HsdNx;cbBqkOtal z;*$$JPM!cAv16dL{y1Hd;C2jKXS!{12B{Wj;rfffpViVloPb;T8cEm5)(aXQ0mY${ zn42o`EB8@d`+f_qRi929toN=mI7>6@3ta4--q7mP>{{@n1a-PU7r-d&a}wUas@|L4 z?coH|zBB4FA?vH2hMsU9rZ`u(C!^97lQ7#m#vE5FY`-^ZiQ>LReYzeGA!p@BqX-50@3B zrqH;*v?q)bvB~=icFWQEjU;MOSFPPXh`LU#r0*wWpFQk-f(_cja^lNCr2d0#1bS%O zLN@oAUs@r#X4Nd<6{(>BsCJp#O)$j;EYl3O;aSkfL}Y)q{lg6LEK}aavU7mORdG62S&Rdk4q9tJhKWZYX*| zM<|^n5&{WK0p)0R%30pHFn#Fa7Cy5zI2WSxtkdzg;$r3eI-g#Ts>SkSDB0)OH6a(1 zrXhYUEx+~m-iR;=k@aK$0{bFjPk6)B;lTCLNT2S1haUMuZz$k033n{Paa3S_-!RMq ztN0cc&yYAlE|s!~l{i*4_j{CkeHj*HCs^>*t82ciup?_H&92Nk9gOdT1!pTcUU0u~ zs*^qO-;DMP*nU#;SxVmDm@6(q!DEu`b3mmCYo(rU z4H{MUAv$WdUq(HQ8>F+_8@wy`oni4Wrc`v0t)q7G%Y#FfN!^gw+ig9kajv@KAea!9 zFGS;2p~Fb$K8RDcnI76*&!_wIuf4B$c`At9V>(D7y7){#V)h2(%|PK*{37zzHE?(Z ztn6LHM&f>ZF;J#gH0?wDN$RY5)`kAYgNk3>E|_ZV$G&hl{cRnWhqy1EYlRYth@pV1 zW^G@ohlJx6zinHf`~OD6_TR^G;pD#F;q(DuN4-h_ zmVr?VTn%SG&T$aXDahM%#tTV)v8r>A$WH_m3>lO~eqL`yzddE`y=qmg+V)Q?90-7# z>vJWQ#{!8Bd21O8#4G1P76b7>eHO2m5wFGXk-mHaslHZItGpk!fSCC|lO zcmCXq(9)-M#!(>9vPtQ{B`>T*F9-o4<7t&B`LGNR=nfa2M!wM{BGtzCZE-<&BYW#b z5%64&E$;Ra%DTxmhj;Sjkxk`iKkcK0&$}DpLj?N^_@BG?T`x>eF99C~#*7u{y2<6) z3Aa7rw4$8w44&KtBmz31_rXiLRLlDy2S>b*c)pw;$DkO&BQ#jMj*CsErOVw~%|+8ocqN2AJe2hAb=mRxE^IMmmm zGxu&)QI~?(%RkWZ(klB+6S~LG!6n0I(J+EZeXj8rrl1^y5@l~$$~w!*CYe0>tfY2e zkk=5hY1)s#8_eWP#Qg~eoq?Y3(JY({_eZ?429xV<&8K(dxZjh}HZx>q{-}blY z{e4U?Qi_Iow*KBhtW}?fnPH%m4KYNDgfw4&LxGS|{=o{`KjAS*fY@`gAbkR23tHmt z-g8g)jr^&WueA03UiK6RxA<|IO~iejS!a)cJJ@C3UhqY3%DSSt z*F~Sa$m;oRjeCe!v^+c1r>_AorPIBKA7F4kS6Gz;z=D0)@8lX}63|uOuHyRmGkj%T zQ;=oP8FuUZXb)Ef*M%4xI9i*4ray#zw}*$JdOMddGG~JESSxlRPStCUIj)mTdw_9H z8nZWVj%R`Q(Sfa&KIy0VW;ponoNIP1kHyk8BZ9jqpg1=Oa5-Mu6rB&Ibe#lNt+IW~ zDCo3GC282O$8lspzmS7(Clw)tEG;_Fz}^1v-KU@0@2ybVUr?7QaGVM9#N6LZ!(ZOj zWmV;*D^5n3yU&|3%x^i+AOU^dobEy4Gt@uDIcDrUGUiW~o>ez|+QN|!QF2Ce0U{u5 z^=p>mE*Q8@0A<|+pd;98EB?BD;DEUw&BK641M5-U9SkO1!F^#V;}G4Y5t{w-vPd)u zSF`o>nMR{^?s6}vBH2_D?h)}pdlJNAkms5U-~bUTjjhSw7ikwgI|Nx5lrK=mp2`Tb zN&7>~dQqGz4W6a(_jBVrsf8!jCGdul@Yb-Knx9u1dbC=dd$@g3DdqC9Wk?CcD0xs$ zXVZ_-8)F0Zoabov7(+Ms+xzDC*Il1k5)2An9P!$}*jEL*Y;wC~)F3CjQk`GOdC7xS zmv~or(suKFH;aSt>zfqGL%hQ5(@fqY3Vre=_pXGsEg8rPoK9z&8s^-nr;eW^NMF0| z7g$FIYuSgqCO7F*Y8Qbpwmo2$3b@0?_T{8AGb1FS|jy&7k<+DMqVL@FHk z&ih!T6D+*o^^O5vf&ifXbK~T3L)%P3drQXw`9&WFH^vdIuJvpL2gnUa=T>-o??aSStROS4VVD4NyU` z{DD=%v8+VDI=-1+fFSOIF2pZ$%;fX(W|@<+FeeqWPl+V<=g_{p1>)~K#k}`)dl+4~ zoPPbFW)NTBL-W0D&Ewp)kHcK&*Bf^0sa@%3Ld#DWlFBKLh2$8Kc7bMldz$hC%LLKh zRDihpUUU(IMeGbI+B;zEFqi79<+|{Jq%YlGOG68Y!rdVF7vf437y8MqiBgl< zM>}8RI|4V$pml8P4hKJ&AEvaDOMa1l28C=%Y!^rVbCZeTmTVW}^w8m7TG--#~jZcRDx_1+81j(oj6SgliBSFr3fet-S1FWOrjpa#BUpjzHn(Q|<0m$<3Fm|_g=-(6KQg@U&SkRjb%x`dlU<0n)W(X2)3FMo} z_q0X~8G{=6NXAQ#=b6B8c(2o0MYsUGgh$u|v|{*QS*C=D)3P>EEg7D^I*r_~$Oq;P z@#PgJa-Wf-IwG}4P$@r8ZDx>L>_UrwU&$UxuYj@6N65)H7_Ts@nBWZxy6W^oVYslmsxY)M=%R;c!^Z-NA5M{psc#p*e|U0C+y%~nHZ^_Z@3 z9d~1}0_IccA^V%MSwJBFu{H|`vx}ldSftCtifA11bpC}-?**jU)M`vsgbX~&waX*~O@olp= z!M$N#61B`86Bme^BL>uuPflLfe!d7|MfS7bP#4QWXdv>0?9m6fsXNHtH4>}bX{fJk zyj^QEC;j`1N-tqw9i_gB)rdd{9s5te;j)Jl`}rEIDDS=vQ3&z_+Bnn>?;Jcn`Z2WZ znlA6WHG=tsyq~GhSjeKHeR+9k{6oXlc!Fuh6mlo|s%rJqnvRK-Ro3LAt0mKv&voe; zP{6O(x>wz2xUWci!!StmfJ&s~DRF&B_1NtmaF<0BBh2!6I0qd2>l;|;%i&%e;oGBukX1bLxM@V@+_uX;x+}LwiFFUR7SGaV z5aWtSb+~?%O&TKBUw+sx)ccLy=F#uvLQB1?=@qknJ{QR9N(AuF(eG*phvLrhK58ID zTzt}Pe6916Wlz=&ALp0dgRzaUsoL={fJ?~%LkrZ^4yYLt5OwlWP zH%oMcE%FhczYhS_9_9UrOg$@ZL$Vj~mBY0iQ9JlBS5}kWmsc%y=93XG5IV{Gm4RlI zc;4qVlp6MEojc8+zxxr-MdBI}_B{u$?)o{4uvy;|S`vDQ5-JXWM>U3OC8H>7t>5i_ zlUPh^eF|dOH&kE5NvvLC105=YUS!D$Th(yDw3j{b}C;dd$07 zs2$tQ9xt20%qd>2dIT89{8x(rx^8>Y3}N-Jmg-$ z3+KRtl^-Ke1yIHEa$pv=Jw&yra#gY~qrui;$TxBPjM4ncijgV1QLd4U%;dLcdE;4Y zdg&@qwkFj3M?mIlVu$=IgEPp9H-s?xAp?oz%ilA1ruCk}R#l}qs&ZcXyN9zWT1j%* z^F6@6k$&*Rc)G<9Mf=a0gFFRK6w>qOFAe4{aHA!!KlA(%l3{tQZ^%)E8OetU5F?t< z9p)HPI1g-Vyo_``lQA5&CHY@=KG4&=(RXwFekFC1zxe|CPa&=!-+{XZ?qlvWCbxbj zZzxH{4C=s3t)gc|8U^OZe~byMH8ccN6;?o^L1UKSZ_y*-?+UmraY6$Lh9@W|8_ueD zU=3o+zs)DY>?H>Vo8GwVqi9D5x+;7W&t^IEE=Kg;I1RC@%xz zYp<{V)ctZ|4Nxg+Cl6goFJ>UMGu$d0_qbtVxh4F5v&D)l&^i>z{9BmWF7VFIrpwo3Z5x8jj{p;~Ez;DUnYb za?U{(W=9)XoS69>ZThp;{qP)(oo#i_8w-q;sw-B}k* z-Id-~BAFGvFUo$MIQ%l6`qMSIUEBa2F z$I+9Wp!H86#;wZU`hH|i*DG6$w?pO(-BmK(Mt^@2^I|^P@4@tx;)L1!d+3W746j?I z(;bal)i3ArXUn!#B0mqO*74&AISy|B#BRU5_LL0u+CNw=G_$;?VN1lEGKkb3^OVPR z&%Eb^tO7>@xS)MNq@Jb`TXUWD%^lF{%k%54;l+U&~zm2GlL7 zg-k(uBE09hf-<$$Q8E#zgy?z$4XBR>&_%qN`eIr%pnoqW91{WU5Pzw{)=f_Zdldjb zc`pBu^UF|B18q z``xIRpCBA!1FKJsT6oI&k=CKc5dNf+Rp5r|@0UHVM=2FSUICJeWd_;?g5#CT`EzP% z08P#t#C1p5*#WD10J60qwg*nJsI7f)giXytcKHd>D|Rli0VZgT_#l*D`yxMnrvNj< z=DpU`q+c84woe}g^nsvi<~@$EL2zn!J+uoTCP-PfajF@T=@dXz6XXnORWIyGCn3<| z$a9a+WNNAQn^S%Kx#Gh7I!c6fRDj)oOYEFVMxP5-XYtg=b$ z0atY{4*hqUr@>$D$X-F&*;FmQ@$+$aq~VS6eS;#cgK>e^iE8s@VJ zx*~Y<8!xJrOA4W)_0r#Io1&3dZFs62njy5V-Ejrtw_5`>`3HjvR~00^508&<-g=-3VfH9i z!@gv!w@8^;@ERA5ejwoCGVzxLh1xC5n{pV1trB9J(Im9V&W=(TbEAx9Df# z(groH!f=(k?NMXMUdx&+tW^6*lY2g=z5xiFVBXc`RVMq;YCq;9R!KStXPtXRQ{4CB z(rbraz*Fkye_a-8wlMAQFVCv_-}~tn>38t3rz<=7=n2HgXa7y2_aiR;{T#|H)s!$F zLa_zhIy}P9ysVXU>rn!G(Oh76=3m260dYrVLCbmJ4EkeYV2Wr zzI=Vuw>78Zy|l z&*9hp@LiRC0NBF|V9sKAqM$xK7011%2p5Sa@OZFA?agdVJ~ZpWDBr$q67633<+53e zht1mu?=2k^LU^6;Suu@12MV}Ed{!BPlF~C z6~nTyeW)Ph(|Le2lV_K~&|vz}>IYtR(=n2adcU?Splke-3Em3K7yNyNr1i`f74Ytn zg!^9)sN%klxqUd{oeH_=A~)UHmF}#6q+vJ=tA=U6C7PQ{SN`hc>h|<*;0F=chAwWk zc$B|)Tb(1vnqmDU?MstZ7_98YbSOY%03xspfzr@=CHr+@v=cVaf5W%-0yDsh?9>jQ z?+GnTAXm{!8R-^N!MN1q=RCChM+2wi=%7X~XSlfvMKHqOqB}4#6o`~q8)w?(^ZaxC z(0V(%XfE5FbTM!G=hpkWdu4U8tK~y{q?K*NONyoTuYTt6=P7P7@F?+E(pP|+z|U2F zJenL|b}k=cTCW%-qsl?O$wh|pbAp+w@@Rs6xqechO6#?6ewh?=?BUkI(!d_ekF(vu zP}%0Lv27}5znrSE|!ub_Ph4X>El)mLjzVqEV zx=Gi_{gFBCtBln5?7SZ8{_C7;YFcLgJ@T^$;Qzk2C5?ZsK6WcTD)qG)WmB*|^>}Z5 zK_3nf8SvqC&G%K9yWj3EMYJ@j2h4feuYh!^NCUa;rTfS-rRr0uj^IPQzDYIKVH8Cexg97>MJt z6XB?N=iq<$1Kn!Rs1$H8I&d)gk`L9sXg(IUM0i3=7O{1a5%^tW#E+Qb*0rE7>o>OF%+UMa|Uv$MtY4TVKLZhgC(R z7sC1kNyIs5Q8S#&d96DhR2l%ZSm1bgd2`(D^tv*g zJN}6i^SN*aG*-lL;iIhVxgANi>}l#RQKRp%#3`kE(T=qa-`<%wv=gf7Nlg80^bgHp zN+*MCZ)!3O+hgZ8jy zr9cM|2$S~LR`YOK7Rh7eUia-6*1M`@yfrGSWk~q zkIKdTdJ~vp z8T`|I!1LKPbk%sR=xvtREl%#bLZI{5D9@_0W>5KtU4H=&qx+ENzor9u+pl%}Br8sM z>`KSN`2k~({+Sv|!tOM63VhE8H)WYNq_bXzH;JDT1jVtR$?VnXeL3ICGp{^sZsj|= zJv=`Tw{zX4fRhcxSo#PIy=c_#o;xJG(*0YLd*;aEQ&$E3P2>(&6Yp>RYwcPFj)%Jc z`_tewZVg5G6@G1VWBF&pQpNAlJszEYXk<>9GxG;os;4?*sTrX?`|6;Et7%EHI-$*%qZf-p&SEPAqqp(2%eS$jr8SOuTDx?#-)Qb^ZE5NpGUY@ zyiA4(wze@x|3110Dt+?qe+wn`uyIuYDG7?9W!#wt15NwDJd^sUfjP3zN8$!7^KVb* z?E-XxMR0UWeM+yBS$k>9#D|=nW%5CqncAQ) z4x{uw!y*4@P}Y(xb*#GDDaFo<@|I#^S7fJBL+faS>1~D&GNAj+m2X^8lhIAXHRGxJ zOX4q+k>;OIXwl`f2{eW&W>1v=kdP3D!4iWd2%2a7Q-Dm0cX$NQ<5j}okr^Av9#!wt zmI_%aXapBU@PU>Dq-2i{3k|5W3&*be9~9XfuWUB3jN#pVY3$K^{)1X~e`?xe^?JX( zb+hNUxRioQU43?uPYY0~^6?~XC+BTzuTM?x7Y?>OiNSmKx{SMfhf|yL8!sM_r)LFe z%%inNbTb6aCLMc}VwD&#BAAPICV9Lz%!bdNH92^0fQBr1j&4=7zUo61U21!^u(6hY z=y6ZKl!&1|e-ZA&gU()MG44_>V_ZVc3|hjNnY|R2sdPXW#kZIKR@lWqB|u?*dcX>o z=xS}xYtkok$cK&(rl@ZO;FmimUFZ4V^-MS&d;wF|9A1yC#q`6eaG<7#Lzd#OaKX8j z=-0s83Ed7zeDRLHvUT(+f7SJayOS)_3h4-J`CVEe0Ax+-VOb@jOFjW@z#jR?zfHcM zx~Fv>`saIGKIi;^8k{T-{f5;DosP<{y~NEksE6e#I4^SxE{Em!bt1+)N=M|``yo9D zahdY!a?$BMK60+M;BIG=1f%BD>eBA-Q(CMGtx?bhl%GFPAwWq$_g8tqy@wqCOMdmc}WPBPrGX`FKck-ieBQ(^`!gxMv_RINT2_K}lMzY8d1lwEsjEY9IR=3i=&YR9TVxR~8B-dG5y?LnGQaRM)BbbyXeO2ME zWR8XuIL}QkD&GC-i5;0%c>~<#d7+;5r^_Ri;w5C$On%)l)tn(Hoo{GzM#PO*n0Kq9(KQOuu8Zkhe!CkvOfoXBuY#*C#-DGUVlpO^lhIUvatVCnbFQQKVu^J zQpYa=*zYce=ax!`qe`@y2T6ZDf-OU5{&(xZ)OxJR>2OOI8a`Z~7^yrpldc}D5hsnE z3nSfdl;+ z0mw=VkGgG=+wOhf-&AvVOsU^L1bM6cu;v(=&4GMwpJ_}s#2{SI6mxkIGsMo|fiMvk z(DfEq`BJpt1x7(G1zNv5Yu%inECt#H7a-n8&MC4gXPdmmy2h?qA1d|9c`}Y!F6^bCIiavcZSZUr~Tw4~0v_IEcjT>AHVlmdSXbQ^9Nm&&r z@5cPzT;iNuj}!K^ihrK3ysf#~;}-5o+u6nE+SKaj;}Q9$s8wz#f4*8w=+H7^F(an7grKt_*Yzt9JK6wiV6Rgym0nKZQ5<{GgFO zJwHX;)X}0AP?WK}BqDELSQMtmz$c?&cx_VN9~zPI$f^sHq;h=4dF?@j%#NcNx%a?{ z9L4_GAPrY46X|b1(Daj@IabxYd%~qZdwa0hHy|75{PBLVYU-_E@;de~$Ys^47aKEdrfAoId+! zHuKvR4k`xe$*;^u8~^EXZJiJdnIE7wfcxsS*>e78kNr>j6kPoV@+rGO$%T5aCqaI) zAO3LvzHDdGXpe~t23I@mCNS1p{rjqYhi(0kge&?0&!k(qC&1OHvU%?^DqF_vQjF== zvA@Fu9*t* z!?N~{D`)t6MuWu~_k-C7H2?SwUaXT>GFP*!ipwa)SMPD{?UQ&ke!K~;ffxtq8Ms}B z&eZoSGisfj|9IXLVo!zylrJ4)w(H8gDW{eseiTe?3n935`S42KdRB zuG$h`6Cj9wtE~eOt?a{ebbH|6@f+k%@!)*n9HMs#`f#qrMR9(t(+SH%@-o2pL_s@W zoCer8D1kkVbNI@TaV`!=BQauP6JvC&GR@Rdewz=Ss-Q7dcp~vPQCWZDt@I5@y|ITO zE6A{YDBYi{Ym`_Mg_rvMNKq2lV=)j$1Yk1AAQXM9+`T*eL9AS`lJldb&;EW6JoOFf zS#n*f^`zu8EPq&dsf$g**|PD}!$bZUZ?CjLBenn=sll(|-kOqtVto?}wLDlx1ztiS zG!xBz+UPdPXbp%`PHXprpa!aL2b$I%r(79)oxGfe@iXIS?G4l1<1tNq@PYTcU>XD7 zW1hffws``>)4-};^C{T)@jPZg#WyVKw(j{IJRc~vJr&)k9}1z@+MEOn3ABr;9M^aX zl3cIn&QFn4p*~$)9EjWHmn?%5Mjd;L!*Xmkm=SE}{ceogHk!Pz!vGaoHXH+V!QiTfFI3zEU^(Q*h7x?2m8$IY{tDD2r2vaQ(xq3;~{j_$zKP8WzxAZf7_b|cGbbhhb5|vx& ztiaST56AoY9$t>OQsv>FXorx$I3yu>lDO|Nezq_E`RqfUeAwE3XDL#Q+rTKgem7 z1>!nTI>LTgLYC~g=zx4sKe*@adu^Nu*?~i-vA^%x5K9xDUz>N?b?0cZO)$&*QtiSa zZ^C%;$Q{MPrSrFl(>V)+6!t?D>-$vAWb`$AZOUN7-aMKQ=V-z=+LL9&9kyMLu^(^l zXiC;+KEFKIwnQ36e+2cZ(1`|#tf11Di?7;OtU`rko?jn@VXl$+fQI0~ID$IdiESz| z5ZhMF(M0E3e$u`{AG$-`iqE+&8x85Y7V9N-U@Vv}Mph#kx?d91s-|+Y1@P{3uGA`s z8%gVMdu0C>A)T2jx1?KT7pdozIIqcmM%UBj9hh?am4f@t9%<4^Zw~}6)Z@`3k+(0g z{n)6^kJ^W=O2%&qrrQ@VIHxihpIxaQ?Knfz(r=I2@9Mtx{i4erf9yjdWM0MoM0b63 zMTTFlZ*(-iqpjw%`rbMu>`UAs1sJxhS`QRODFlpR{@u7* zHetLFp;j?}xA^qAGqpk5)>qF!`a7>9Rqf$|E1xo=lairIj1FEKQ4&JvNc<215BIBg z@Ug7>=n-#ctpU~3WkzBsMEoe)7oN{K`WpnHqXKmO?ZV@4P=<`!$21JlB730V#F`vi zoc0>UIL5thc4>*Oa?gO)wadY}@NA!juH~)$^V2`ho`csaoQZ#5f43nAK-a9DLYJ$4 zmM=BVGsX}l4n@(c#)3jmJ3$0gd&;r+Ed1Ag@;yOb&#=NsY(h8O0zoadU+xFyW_JGc zdK*{<{2qC-htaX>U(;h5*T0o=a`%H|e&#vTm!M%$yj=4tt^GS%7qZV=Hrav&Uh@Uz zgRl!%N`vy@tsYqCiCB+^2kXgMpJ7{ET=i=uZ zJ&+QwznFbe#@8{tuhY?m;c0g(Z2#Nuw?&?+5BeJ-ZSs1BI4oka2NyY;_FH*3SB~yz z0_|{jx)X>v?@il(jflp~)VR5f74=1}r^3VYUh@pv!ZTc2jMm~lU>3(%KvNziRqXn_ zJ;?W-D1dYxmR#Z@KCNoCj|GLRk~@(QD79Ia)*qNCx5+ZT2%xdu=__t`UGCK+=r}q> z=ms*fympT{$Z0L7*$E1Cn;^(peF$0i_kA2*nqjFS zi8CU%qTX7`oyc$J3z6`px>V}%%u366y*<=h`b{QyYX0^i;`Fe{BXPoSYF|A{_r^m0 zu7VeYk}LRpuOvEy;9ip8YVDPE&R`S47A~E8bHqAy*Ssdo=1~s~xrgCDd7rdTN4fPI z*7eJ*ki&~;{tTAG9-MIPa#Ru99xx;B8tV2f?1o)VC%__L?{nUx z68waR1^qIz1ZH=qcnL|MHJ~gT8v5*NUaF@&KMtAlnI5{OoPFvnO=bJNguN6+dVfZZ z1&xi+;o_az6~gwq{$($e5{*2$=gGTy2E-y5z3?LE+C#EeF1#8(U zyDiF%u^mP^OEfKS$7_K0?j*G|u#Y}@ms+q?>w`};%)#_()gcw~ta9|p#V~iDsBiLK zhj)8K)3dViSZOTtz8ZqS%te51+Y;LC>%8Lk3pMu{Wr^tdy#;|hm3{JjlV9^wEhLrmOnIn*Cf2zA=i|pGk(et~jK1{EP z1Q%9f_`-p=Dowp~_tt)Y%MTNu7Gg=W4M%BjokL4MHahTV!O3ZThIZYDQ}>@3D!N5! z{KVj^-@u%Mqu5NGK!2=Guo~O4nZIVQ_CS%v;E(E`#@SFUy%!7apkdEs(yQ2X}>!p!oX+&cX9MRa-8nOG&#$anGu*p8}Q1d&|8Ph24s1 zX=aP#1Y-USHVn|tk*21==@4J>#eL+@|1X5@jLB{;@df%{aYmyxv@%cd_Oh)38)YJyj8K^M=fXjE|z@>Zr87c%kp*e-qu2}l^D?b z-5Ds`9xRmeGKwx~5@(&vg!N+`Uw2=LUofs&O~dkAN;}za#R>V$X$G=nw3t=i6)m9% z>U>gV1~Mm*E`jxauX_SWYI%27J`4Fiz1=I_$0p2au{U&A+(SrSuMmnQjKq9S`vv>^ zl#=6|;FkD+Z9DZybX>n&_i)n&0h+j6P1s3fIqmUhoDV!j7{@W!EcKp$$aGtfqZc)S z+Om=N?1(#*B_BdQ7R6k8SfXqnzrCZUeDJI?#WkP|cJLe%XF-&+A0r*Tmlx%*Xgt{J z^qJOxv=KkubR(jdc6sloLB7$yt8cwq-Cb9h$tT&{@lIjHgGtZ^Th|Y{-JRcd>e0_} zR4?OePl5!u$TWXbEYjj>JixSwJ0tcX{U1RvJQ|Asu9TNZd+hmQ`8pV+&za3@%N1JB z>Wjn`?MUB`5Ot@kAiUS;M14uy4LzjsvOT#E7A2{;+S2*Vrx3Pv*9DwnBrTgJpn2_a z@3||AY`6o!x^-R+xrF=dc07>Z;Emf9ozSLmd^|GA{lekF+mEZBzsR|7&dRd;`Ks)dXsuzRzk&KtViTCo<8e7N{o!th#D1$D_ zw*_4ctF|4Tk!GHQLK$$6rPTcxwYU{v=S*8HAVb-C3iio*b>2mFyv-J^z?Z- zdR5*$Fj4cDSla+Qe5Cwv0#u7u4{BL0R=5%Sm!t!xG-~u&i;rovBL{8xpTSuO^LU9O zmU&*T`;ji+w3W&G_t+fnfUa$?qs}04z28l`AJRv>zZb?>F_nw_2Md<>(%PzfCK8OD z&a-OwCAR2Ed=}YisCWA!O^uFdNA})`@j<^mc|^M3IP~RCoaMUflrJq!S+tscuK*|y zr30PmUTYSarVB?Hp5;;4U_~U(UX)42E5KtOobj#-PFawYWXu# zG|^(6@9^PVBgt|*E*v)Ng&M;Z=Ry<{ZQNbj%NU*p;xK+$YmA-*B&qth0QM%lKfkcj z@;5!b08n{OE~l0!jG+IdU93Ye`0Bk{*~%tnW=Ov|))#pgKF zDef2d)DNzn(^3?qP=mppn{t01X-CF*OAT1291mUB>aWYNAAEh zhbsHvYr|6E+*!y$NlzohTowEd+{q+OtDk5V=5it=a|PwXB<92kYi}HZH#SH2ou4x*+x#vX9lNUq1 z8y`j#O58jKsk8vcKFmI5{YL&01ju^BPB_X6`ZfJH`*` zi3}6qN?z*cb$jcTMh}L!WqI}_xaN>_#vCt>0uPm}Jy|@({&Lg@lQA=$_Iv@4<9YP5 zur=Ci$BgDfiYU$7qcR+u6XSkiQKzT}{tgQL89nk40enS_Mk1?}eXm_I)yE=264CLC zlH&_8&HdPP&pY0Mqtv11uRdL|nyj3jl@Xo#K-<(y_kxXv6KfTPWbB=WWwPEQKN=lo zsNRHdf$wn{zdqEBXGmin)4MF^(7#QQKm^C*e*cXc#hBW$0v5WG-(+`BpI9UxUT9+8 z_|kQs4;x!;tbd8}^L$$4u$Q@~R6@ZcK=>c{i(ZD%;Zw9I@s@P!f%%{C3frSD!H2q9 z6*(Rbf`x~~^st{temoT;8WQda7SWHb%uZgG9EC{RcgKaE{PuWI#rI*ujtY-#?n1Jm z$w*GC1pCeAG6OD1$sBVD_-Y!S$jAiy`HF4j2jB*--f9TkXVzWHTBgA)+cFp)3s-hR zBH&vRH|>M=;fELA;KnmZaD@ZFI9b=LuHd{?_A%qo!|#8`2R_Xwul+zBGz^qzk;G?A z<{Urd<<=C9^p^x=Xm_8BQ!a+{ankD4<%M){aYlu_Y1g&5+V`n}uq03aK#6?fTZN2H zO65?R^{xXKTQ_c(M^E;}4kQqLD3Lg!gn&eS;^4zT(668P-?OPVpD+6>$WXq$sdIC= z#gFULqx5Bxocwj#FETxQ5PO09nCG3qIHV8sktK&R>IA+Gqx#zXgX%`xK!tei={PyHh(0t(8MDSIdz880uO zECJcW?}YEVxPbTVO510g=bZceZY6}AY9k7Q#b6vdC=7txR;6f06-pyU$oR#Q&?=6D=4)1@JCWMm}> z_(M^kUMvz`#-3%vE~ngx7ZOO)kC+{PDId5a(3j=|7q=jyP#dgpO2oo+B#7uT!L%4S z$R&Z>i*SJuBL+j}a9kxOvj&N=6aYS&Gz+h(gUF<;-EFb~aso*w!3y0Q5Q^dkS}w{YoF>0qED?(Ypw7dM zv=>ksh{^-A%S%~Q5l0R-zLb}dE1g9Y3J^gbs*Yx@evCjuVWr9}0AJM*-^N%B&@rt! zK@}45upe=-2A?K{DFXaSIvHofZlfCZSzKu_X^Ny*o>T}*ahXS2h(M@{`@%U;4JAMh z3nITl-lJ0648U0Mdy}QKh>yLE1r*Y1PC$-hO5ly=r!+EekQT{c<6=Rw0Yyb=HW2f?YYxaE zDx1Iq50E=^2AmfL;YG+Cg8NS?C`rPx3?>_osB$A|fol5EF(6`(t3{ z3)l!3XSbHz24O&93i?Dq_2m$e&7l@%Nx$2bOOo=Ckp}jSIU3BcdZR?o#tf8`6T`I% zh0t|Yvg4?NO`8F)kS>%!7#U`hK_e*$L0>ticJN~&YqRi?dzwqV3*HrOn+%OAbYiDT z1AgEFA!3z@U`K>9xGC>eI)y9)aTOj?rlTQ#&gF|KQyedNEJj5hd>jq>B;(6TqS``E zCG`lB?|>!+gO6XM32Vmdl6w5r3jS>CL2H^@CtH(q6#=aVh7$=PM8Z8^Wm(>qhoTQKL&AH z+-6P2JX)tktq23!p4A&-;ChJaF(u_snIW&04G2UU*v@dB11r)=HI+Bmb21tD#D(6u zaAYHLpg9muIXF)l*qqP>5FD#4pbwYShL~Clu`pa}kspaDSZYT_79W{XDPfr=`6v_w zmv&p23o1(z6O#>66k-O8M8reuBDBsHB1{-q@WsOpD-FhI!R z|NL9PvREMm zMgWM^3t37<1hUdP$onN!oKa!)f%$;d8=&G*LLD`6T4_9)VhM)|3iFym%;k-k5-KGO zVMoQW%&)X~L=YZ^^CH5P3ySgq%{!kk8JBRllQO41 z9OZ!Qp>@N3c{(KPEmj zqcdZa2w?eyr8vWhO9G&oWW7;$%9ByWB1RJoK_qKaM?@e$Ns0Vuf|6%I&60w4K1Gzb zk;k1Hjx(l>ey5NCiV;;PNKGk;CvQn0Vqr!R)=0dF(}CIJbb=*)NtHlo&G-~P=tKY} zLPldHt*Nk-DaErKnd4B2*rh-+*+?;%QIP>-+L6^8wPrD-_ycAd37Vuz3^?|J6uho3 zAO{mz*h>gItc~e_S7gy4ngq1h0-DEe_St~(SXB8k2Eb`h>S!2h7cmEnHj;K3{HeSd zlPRMyuhipCTJ4s!9~{;xOIjFAK~pDCpG8KiTT`@HY$ko4(MY6bg8=bChCU39)40t6 zt{xt#&IpDkexT*>`6p29Sc}F4a9QIiTNvB~TmixxD#ZOv$dPpUf+DD9K;Aeh;5Q*Q zk#`#PF#4e5RBGqEii}U=gElL02bHP$b7dM#TLABAPDdbsB%}OU6L+PR9^fVb&@f$O zgOI3zTMPkdpyUkUpnH&U8C2$=4V;!=-oTjAPO*#zaAe}N#>!uzL>Y>?y}3-xfrSM= zl`H%%dlK|Y`9VTs3ZWMD!3hG-3Z<@a78 zu2l#a8x39CAf}UP#FRL$Ri;z8H?3f4Q5NiH0zybS$23Ke%$fw!r$J?Qg0kBYu%vU) zI|a&GJ681I87gS@Cs2$^vu+e|W|UY|7h-cnI2{$59RxT5JH!#Q+5><4p zBmibgaKa7{HdY=m~y1Sk&x?T5d|S5 zQGS^N3+YtJ9fmBDJ}65Qv`k(SSRtzxRv}oFKTL$28JipI1wwmL$GyWQisD*+;bL++)>JTA`IBfQ6|iS?xLPh!!XZ#Db5f{ZD|pvL zk_A@}yHpLvyjC=B1dzYZ0f5px6JxY&QqFI&LZ}4b7~dKx18>xn46|qWWHh98rxdgYPPQq2({Tj= zGKj^~{AQ#LdBX~SOj5Fo^cjGCNMm{0W0#uvu*3_uQ%;c-RJi(lnBe%iC`dZ&dNwGx z z34)TD_!TK)_NjdsjuWIP1iiRc$_SepfQJIO)@Cs<&}=J?ln7&qsf9vA+bqCey!H25E4zrhZ8<~8O73#p$ zQOlSD;PArf88{G99G(zE^Smk<;m=&~gied7n78N&z@)^WpT-(t!j!@avPHEVA>j}W z^b^8wRML>lUl?Y&X5!e0V77cXt5;E$OA|oSi!oi)*aT1)oM7A7k#JzCCsW4 z)WX64%i}`8#KtNIP(Uu~gRc!wY6H*+BrycMGDRRSvHLlxEsaG;Fh}=FQ*Mw;fx{Z# z1W?G)F`XwEx8ok#2{t_x!@TR%i+Z$vr!7PH0%BY$u+g-d$&0cQzsv7~d=lf6$1JG~ z%|RN7fIy8O?eI)KB5bi_v)~88K^`4={dTw%fzT`wL%5AWqQXvt867Lr6jK2oY?+{_ zR}18l5J+e}ZVRVNsw}W_fbvHxkNWl2AU^;N;FKokl>V>`kt7@@jovS^gYCFO@8Rcp z0T?a(QP-MHWLcirY7)wsFeEJltSU`g^TJX|ty42jMx0SORES5ZPdfx&iNNaSuo!Aj zWdn>$YD!uQT1irrOe??)$PMH@H5h4UQSc(kDoln%OlneEgnGG^(QqEhTyQGTVuS`B zoj(RHpGhYglPfvBwq$V;DW^Q`NwU!-jZ;X_P8cApWP&z20FtsGBsdfTs0XXf2(3qC zV7DqO^2SB)xU2*}A|SP4O9~+5BfQaA3)nG z4&*S7gvFHv*+xF2;wf%+5jJVWB3w>u z5L)CuSqKdw94XP_SjbJgz<(mDamA#DL^KY>ccp_?1k|b|8`Q?-DzAgG0;WTxjM)Wo z5S+-EQdCrungnoSmjlmCl@QX#l#>5=v^KF77Aj@HP8F4L9~KayUZKHlfMmI;JIYzl~9?9`#o&LAft0u70zm9tUc?-yg`Kxaq?jX)T+JEa}1qu37B#u=d^$(1#@nHBZxVm4(c4t2?p zB`M3=VzQ7uX$OJ~0x~?c$meDJrWj;>bBJ9oHi^}UiW6D*nIT{dLZ>3?RVHY+C$B;T zUXdX#P2}{Dd=e26X#}_NJYQ0h!o|^0GAu}VMPYu)cFKwwQxKOH{F0c>oB*{K*bcbG z4zJvUl@uPKmyx-|Vi+qBPCGSHWg?W!I#^#o&7Ya|M2zOJM97wQJV=7#XwL)S)?VGD+NT5yb$d4a9kjY ztKvSW^02X-N@z66un#oPsv;ICp|i} z;7<6#8ORiKb8IfDwldCW7AGLJ#xKRt2ohI_+_}6{#)gyunFp|h@atHNK=jNzd@V$} z@Je(_?2&7W(Dtb+^5a{S_Of1*Vgh!=%xMMjG(lO538C34Obg*=J!SXl5N9^$|9>EQ z5Ui9zt`N4cCR;uL+?awW4p||{Dsf_jlX|lWD)DYjjo`(wk#<^W5LsFw6JhnZ!6IA? z5a1wOmfS4Qm~1jnDxfi?2tVVsE2UvzNUB|SwE@jq{8CfiqKR691ukoZHZlIn!M(+z z13`C^A7Ak>mhs}@H0E<=QyN{&6R`=vTU9P%IFU!Bp~^0E=%LX~7Y`YQ#h@)h zk#a1wH~DvJ|@za2XbxLqe9Z~xw<4$3<<)Yu2<~ncSRz`N8hS)2rOl$y6g{aFa2PlV&<+rp zCJspdObA?8VIBeZIpa2g{i~2n>Hq@HcvziEQsA@!oj6?*fn?2L!PKy~h%-(_*bS9A zzD);m2Wed%5P=c!7GhNKgfOAeLbPFp3aNyKMU)g6)LtwKKzp+=2hk3mu~>=;m$smd zSRn%dg7KU^henhITTV!&UY%GWym>9rz zSbIQV=0A5I7}n>NICQ!tvM7U@rO`sh4Y~M~P%8{%T+WyY)#aUDIIu#3Umz?h5ETMr zhNPgU$!>E;7?lahLoY;7Cgg3^N&PrVT3yU^gWFY*vb;tQMbxj6ktO z7zG34Fn_{KWs`t#&YC&7C=WkE3RXjfV)2v)0L4Iua5+^aU6zqxZlN+5r}K9BS{My1 z^$|*sr2Mg{DemDHK8%iYv>+ET6*7d?OL6>k1BrsdB9Ij{B* z>=~0d3H}*YHKB59g(kk(3IGZu$!FXYk|e3deU5k`E7UTUlo(`?iIPzY2EURbwAsZK z;G0hP{Wu|t5;1-gp;fs^5#{$H$V-G{8D~~s(1XV)l)o}a&H^Ye{x)^oXCT1eh*0`X z76GFKS))p+Ob6IVMrt=J#fBno4(4+l4#XYC;&a8lG#Nz!vZ)CGL$??UDcz|g|8`X( zsU0wd<|Mygq(~7R7l2bOLT62sm@YCwN6O|)6i|;hPG*!MM_5VtvcLl3+vEZI7l%VG zT)LhKX<3m{pEQ$!q=LVAGQa`zLz8f39C8Ax-VC7j(1=_YM5zEYUdx%3r)Y#z8R6m# z-Yk~R0EQ`I%xZE_1Wbc-cPuC`M4<-+o+;tcD@#c_X408;QZl9BqLjKws0fhIt0K76 z7+_dKmLHZjfk-J&q9#wG*S8Yfb+il6~t zP^^Fp5+DF|E8IF`qGSOFS}l0OXyj}`%clops1gBum(~XDu>lV#&O<k08F2+&_p|=ap(mJp+tsLgjg8|RScL6a1S=;PpM_7)s|s+ zX)P2ffG`ZdPZd&%9PHMJ0OVh&g^1GOV9c5Dh;4v93(z*Z+~YJL5kbUlS4olvS%lD{ zLT?oFCg99MnpD1Y&<|`QM5|Ecl_iZB43bzb=8~BOtVAp$K!>4lK+kMK!q`GNcwHCd zP7Gcdl@vPQrxZ!LJXQl0$h&(i}&gv{?Lh=NfB=r#Mi*!~30Gu8gDjzb1-6W36g&^YO z*B4A>_J>L;JuR_>?G`Gb0sM`_TC`>KQj?2#u8Gm zIHdDJJEudH)My2MQ5ZNLYKcma4yIgjpmdl_Zn-Sy!DB&wb2Y|8K1W&~%Emd@yAGuy z?u!B)9}8ub0+W|Sa5RJS(_bJ6v;26nL0eSOWQ#)H5_9D8em=l5S={`PE9gzmgf!&y zMS+g*$VwxHD2Sv@!hl#OiI@c@Kz;`KscT@fsKF>?9aJe(1QU5FT0}Kw9m9b)M4o1$ zglq~0ltLuvOey)(jhu6dqb2ZW4ro|E>~Un4rTh*sKnBn{l1Mq>Sc`-~bsrVbd0)z| z@?@<_8D+BSqlQe%obiEoToG{;)bL18N~WU2xW#13s|%4}E(54~E2|{Ip2cC%(^_e) z=%ynMT*`OJ$H}mck8yBJDS}2CFeFrm6><(MiJi0|l~DVrJk8%~K_OcO|0C52I3%k? zw1tit#cH{RvO{Q2n&VcNMTq1`kSJJL#=?X&xDlXF8eLG3iWFULsL}hQ{MMy(JHf6! zD_2H*7%MPaV!m7Soz-s=_-_r7_~B(wd0KjX2pT zOnJnV(ncjNJ-V$NgTUY>}A=pez zR*xBW7I=mff26`g1%4Uf6MRmnwqY(E2q6OIq@Om^1{u_};08<@bt>I45~66o3$vKR zf;>o%1=5_OWDI-kQ6*^8l86F4tRjj`Ch0Y$sVJI+9z&K%=tVATGyx(lFdB-3;4uyB zC~YeEggP+lj3%9el8#YOSw)zk-&I=4qQ7VtL24zf$ZNsRG82wttPi4ns~N7AS4ZP2 zr7jUDu_Bg`0Fng_OR|C#Bi4lwqbn`)S_C8qlg;Z$8sHttp0N z+5~IW8Z&OnBrmz;{FuW75o2B*_dpgjsSv02Qac^-5GJiu29*-rEEb9(MTx-&0rw>Y zl9D-RhQx=(5|oPJmqtDCsYnw6xovQ{7P&dfZYcP?nN%*Oge;#9#Nz-&3rB#K1ASac zi`eM5CiCDQ0J#WUE(TJk8w>I8Ek`9dBZQ+8k31%Fi$ai=$kH*1MPSRjivk?hZV~}z zD;rO^EaJ4x!&rl96>eZ@sRAZ9sW)&6QyA?sI$f1HNp`V zX;2^*#Ed}U%6StWFNt$}LM2_ur3z_4zcEQR71RI%I-^e8wOB5$RMQ~1^3pPdNmu}) zpe0ixg+julg+3Cn&HUiXQwVAWBQy-o>Y%4^`XEK2^%dcC>9ZIC?rkWEAvz+7Y*gz2 zeG*W90HG6)JNQpe$TuC~Sro!aGJ~)Ii3?x?8I!jNU0xzI`U_gnCLX#rcL^~tqLQ3Gm!E~1ez`8PRNC{LFL1QqtJSu(z^ybuJH!+M} z$R5n0h+SrKgd`wKv7$H{Fq!%DnBN_e3FF3q2REo~YP&GY?*lmLB`<=J7hT`#VK%^-^Sz}7PVHdPQj`TP0ChnRGp2-j72Sz z3HeM~zXt5<6iK--3e|RfGF^1~(_s8gne9rgIE{n2OfmF!_s(!ZsW}z*v@H(BCSquHp`l3}{vKo`DTpsm;tVgAnLQXOsEJV|S6fipA zVv^vI!n+DUNl2E0USlGR$5jy(B>^o$Tw;6IEs7enCOnr0EUvu>_bh@3l!?+HWVQsl z8GqDg%Hh#Gh9(`PMB)Sjdl8|$(5wyVc#!Gk;W$W2Xa>lZVsPgzh?0=Y63bjxA8RRy zQ3yU2hLj|%0?lsP$0?I~jwC#xh{GWYX$%FOCN4Ljex4Bq*(!{5YoQqKgzpRRv6^5+ zjmBhVH}sdXLJbmEXd^ioYtS}IK*XwcSyE7{gLJLlN1C0KgN&+7Owl2OuMM|rVU{pj zBA2#!08A>d5HS}{$90U_pCDMTiIOo+xiG><9}WYn@5bV$8LW3HqCw>r#iqy*L|;>%cs8djLdCvY0j98!B+X*S6$>7Y`o zQ)c}*1a@IO3U~;EOJ|Nd{Bohr7jh?ZIWCmWXw>11Eviq63^qPz2kM%FAPzJj9~>8@ z=4?EYj#E&Gf_IshLuhX{(=wHTXSj0FkkKG=iA_bq>H({hLWuA&cD>r8bmk)pr7xIO z%k46*sHEg1o}(o~Xjt+>qTdR;zbBf~z&P;GXu>Xsh6mOQG=R8KW)g5lFb>X`1b8VI zvKgXYE?@_@Ohl{q+dO$eLZuecUT2!f1%%R|1xyzsMxb~lZE;dvA_!r)AWMYxc7CqO z9MJBlgmg@r(1k*7g&#&DBwoD`K-=O{omv-lcr`dQ8k$h85= zmcunsctkYD$JmgYvNP^?;7uqv@E4qZ=biwv7;_Nzfr2cjGP@&L_}YN~L;H0ew~ltg z19O;!3i)0kq|O0&vb2IKcCf0cZ0p zc=}3=QNo)uL9;l&VWz>b1^yApa(PA%HYo}uD)%VZf<~>d^PdmO;9P@txd3f{T$#*2JLA|oe>2;y@v1_vcn;&eV4QYe+G0!@Ma zj@zM%BvMA9k_%enCGZ6|3c!I)85g_II9tF#SIvZ@Fne*1)S0a|Jd@HxyKKoI)7eOo zDj-r5dV~l$P=@exLIpsTLFhq1YnqWVr(l6s$q-}EQxYUoASIU=P+J}hCwwF-QhNkc zEHCi73;=No1MMvqiAPl=Q9`3eols(p$PiO99nU&&78Gk~OPT`vFItVkdklsgAh<6w z0bJt-ads@^fwYyUM7+aT(PRqp_I?RjgpTukDhBQn;C}(C`)+B-JS@N0OW_dCaGx!uHuQDh$fvQd>SE=CO2DN{k&wvs|aPX4bEe6_} zl^Nxxk|rMJzn7$v!JUl zm?je}u8Z4f2D(H%5D?*XC}VJQo;d2I<)GUz28oD?F7nSWEBT-gIT$qT*UQhB=H1DIDXm zUc@!6X+fak;!Q!WM-7Y(^pu@j!f>KaG?SP7ArBoR5;2 zK|q@i+oX2*LUDms9>hI|JhH3id{ES@vFDNIbc35U@G0T*e7B~~0L z1qm#tv2rXcmj+D*wLd~b7eb_j(Kbug9;C&7r(Ul~X7lnSZewllFtqNx#qMBqCb{OF zDue)Oi_I4e*nSNQhL8doDa&aF1wrtEoX+xsnke{<4sFNk<7c#*_!YIX-t_B3-kQC ztqbrK3iyvcsAIrwoq`Ap(hW?`W`GBz!_gDuaVHR1g?2Qa;cG)0cu8$|+KKNP>c2 zLNwYK;RsJ9~X=lcBxRIZ3PV>r@2Aw_Q>~vzib_UJho_!%=9ANW^LDv9Q#+{*s=^UTj^b;pIBxMxb|Z?~b>;(0Xoi%;aigi2f(ObdUVGAKrD@ysi_z zj4l>22an8oar5DhPnKlvr@r0%tni@Q-KI0X`s&%`p~tZ+-#@#+e7Ak)ZQssU3tZLO zcD+&YM!j}rgAbP1Jke7?ETj6(su-EyeooJ;nZa+mefn(gr12H}>KBnlla&9ysyt+F zyXKFOAzp8T(44=y2OS>Z!ol)oPQ2Z5Q^m-_At&zmK1<2Z8csEO(Q3qjq0PK=0|%AZ z-4CSo%WKY^JGbALox=HEUCL`c-@B&GzMJ=KA8JN_wsYJ!-_)RW0l)e4YsvA$daSup z{>)A;of(`&&g&*#J1eK+*P zE>->imA7BLCN#abQtP+f1ScWveUK!jtd)GW-pJEty6?Yf!h^_?e>?TQe=ohkYiAtQdOr)AW=l zuZGiy0xS2l8?^Ohi?NY5-9BN^jl-&K#p`b!FzERH(6z>i%R43_*h0U1l3P} zf85W{1`HeD>cYWWliU{v6t*?#`$1;N@b?3)x?TR@?4R{o?T{RvUdOufqqCdV1=gQG z`SV5t`tsWAaZe6zcXnyAY0mQ_ckZ>1{-Ifjji^+d^1<0|JKN&zmZ+-zl3)ABo^@aK z=gMAo&w7{k$>B`fmaW#4w@ax973z1E+&Wu6s1-SP(I=zI4jh_${`>(;Px2!N(ZO-*aYt9z z1w&r-n%3oT_R7{_gNC;KwsZelRd3XMS~}PA#}6_;4?c!FYYiLo^q2i7-`+&ibsJ^s zm-f)UgU=o!Q|mw2zU1NHg>{Ga{&sh5#f=rO4>qZdEpd(Y^!Re~u-8LcYU-#Xw@|b` zwf=a!i4$+<^3-~L^7CZ*qZ)eY-*fLiXuG7&t|!-4SG)L0_l3@{%kIsYcJ0^l$8+bp zh$c4SzlH{P4ZWIOFB|db?3Ui>{_{%V62+R+imeM(J-W7UQ|J55!)tBK9RA_>B4fkL zPutC&J=J$2R@Qw=*Hf0}J=<)`?)>Fq|GD$}6RX_&*7fg(re0U+wSDSqa?QnkNA7<7 z^w~4>H@{Es^wHaErb}OJ%naB$yta6KZYn)78_pcOb*sgWGHtFz$FFI%4c+T-tiU8{|$*wtKTm1pdg9Zzd7 zpZ5A#!jJW;zwVz;A4v{glFYy=7_LsQyl2Ge$^PeOW?tEI>%SX1sUUv$=B-;N@8@sS zemQ1Tp9QNY40v08#P#7_4sWQqFWvlwx8mViwa{~a?t3&L(7X0`o;nvNH{Chs%Eq5} zjJ0+?KDpYRrGLz>_}`oVZkfK{@Z+9y|Uoi56t7-=qfMz z_3_PCh$cUL-1n8QOXEWqcDX0dpV&&fs{NsTHCxQgHR{$8!+KqDuj=~!ilZMY_I)x% zqMF}s;Nd3mI`i&NAx}2xRna~9^1b)(A`338d=obrXB{U6`}Q4v@Y~6yj}n)y@|MV) zY1F~;z=zSz^QE=l4{w-z`c30URgYG$Xjn%7?)~HWE3!rRfma3;r?#BZd(phw!76g3 z1>OAl_`|1~YsCvEcG`s!9 zi?e8O*Pr+MeI5qukUqv{-o8?^q-^4OyipWIMk*$ z9=rbg`Le6i8_dld`E~K(TUfk#odvxw4H~#_O3St3XTBScZLiWOJ-?bgt*n{6@tWUiE{gq4gm&Wx++TMS5@~>7S(e-qf zQT>xuwrqTFm8C{uVc)5LAFDVuXKmDBNLRb{zg-zDGs-ljv`*tWawE|`qI`Epn1v(*-uhQqv5B$nHExoB{<4f+XqyGBKRW-QzP3&&nQkNc!sgd9R_`~RV zFRK3jcdlw^-OWC;r#7!}{_^?#*RNM9y{TAjOqD%d#%V5yTsrB=x`7`bIePVB=PSGR z`YStn2%6pb>s5{KUyPfRC|poit1P+L`_i_{doSF}T^jzN>hCQY?@f6}xqI{-q?=LI z;rZaBv7IWcnqu&6d=Pxzx>=Ru$M<>Op8B})7*+p`l~z?;+3mf}Z;n1W{H)8a8`ni$ z?(7Ll7xjJJe^jfOzRBxV>*T%H?3(=X^6HIie`dM2Y{jS=2YR*n@Sv*x;^D75J$lpN z)RvyV*m}!gSFiTXU-m$R*WzCk#7xSx-d#Yw%4Zq|b2;c(Mf{#k&L(4uCmX&=yZ9)Ij$fmRG^1It569g563j?`&j%zzZI6RcAF)wQ!{Rwk5ulsW9ONE zo9)DeV?Vjc?b;Os+bB1BwT~tzW4lj0Pi;87`;)fIQdb|`YyQ0DkP)G#M{kazq!nw- z7}0NklMTUxjcae3b!c1PgD<)@IDSxcgIepzb)PbjU9j5HwU!`x{rTbwi`yTQAKQ=n z{x@{9VcF)+75eqmJZ(Sj;~%>Gx+`4ay%86IxO=Y9?A*#SF?sN2N9Dr3qGT(vZ_vkG z>kgrx`x?21W*@MsoqhLS*xx6fSYNhxLqKt32gVJ~QbUhc9(Jwg&XL|_T{@`x{o2LR zWIof4=^(p%8{6U-y{Cn$NgMO?#izHNZho?U{ZH>~y*sCjnf6}i11(xrmsRn$f8M&{ zdndbu&fPIB7xo@?y0ht^GjlgG>WIABnNIkc(+3V6?aw`V(s=Jjw|4aC)U9PFcem~L z+Zh+RnlwBYe}?RTda1_!?YH91ANi-Z)r>uNA(xzae8pL&-F;-ysNbgb`{34S<_m>= zZIjg03M?a1+h<(Ybo_3^ik(_k|5N6w+JB=`6i_`~t{idmf z8(FD(%s550jFPW+Dt2DPmkm&@`*iQB$A`aeQfuzfAM3AbvhCr4Gp5fkk7?4Q&4T@7 z3O%k}8hFdR*loFSqz>%_gyC*$|8 zoqJTHk*?$2dv})#kyWoc-*pY_zvud?)QwsLT4sM3UbW}82kX|ozwnb0#=GqHK?nA~ z?AoO1G@psZl_y_~c<5`IDy{FfdhQTgvp!|>J1w}{Ws$Uh8Mq79CWe*`?X9~sd%>6+ zkAG_un0KcAqK@Zx1~*Qa@R#QG`KF8an|A*9*~(PYRCEbaug<`o!+|Z*Z;g1@gF22*|FBfMd&TQ7s`mMz{D-3peU%QBb);6mxvfo`Ztfk_Id~_~iP&}SWvv~$-RU9Q z#wn&W-P!H0HMf8CZhN%o;@3BImF87>Kk)KW?dOG_eZPP+&a=e(wQ960Z}idmKDCV} zn~0~3S9X$oy{q%vH%qRT&l%Jl>s05$SBD+RCl|VnFKcvpP}7a#)6aif@*4X#_U+Z3 zZ`S+_m}b4%O0buMffKJ5V^a4 z=O}Xf*eu%byUV|BofO)z^Ote?wQE&ZFEt!;CG)KDzb|{MdSe3ypa1p9>l$|-#A~#@ zF>if+foIdf4MT3+WLG&?wY!gwXz(IfE9Cx2YyNzqb%#IfuROeOx=r;u7Y+_Oaiw0D z@E5)Mop7R5`Oh~lO*u70;;%AUGW$Ze0ZSCbv92dh?BArz_V6|u`Qf*9$5at*OV`ml z&Q)nq+2cF@ra|3tsNTn}8vbpA?|V)8)LmJ-;CJ)4XKs9Zcyo=9k9>9Vo+MR%S97GP z+j|xrv~Y=WO<)u;`}Eu4&kr@YzoqQMCdPsN=x+t*J-ho)l{abqs=|opov-}5`OK&D zK3iA+!td?Re$lL~(a>L7er?b%GtcX{)xQ72z5ZzNWurRt4V(IRpYqp{yR)2MIlkNR z`OpW$C!MNUrS_#c8y|1HoqKui+?FZ(l&gD8Ja^@yWucl>`Z$26_ixyqp`6`EXD zEq_s~Qr~u?rxGpGOSnzz>5KhFy=QH7qxs|dyE7BgL%! zc7GR>;K>hFA`qGAFBfmVNDKYu>QTdRjzu;L*HosThLHdvpew^pFH&vdhWHX zb@$=>N){~P*_SZVw z{z7s|yRJW`kneXrC@)kAHIuf8`I^Z#bQk^OPu1K}zmhFDc}#ib?x8mOPoMb7bE97U zi7(QP66(S2mfw2PJx8?N`>_1elV6{lcYEvW;iWcbo82Bd;ri*?_w3bQ9qn`B_Zj}G z!o8Y>ZI|!=0{gGklTN}uZ~i*|cdu>eyjr7sv}i|uXuc$G_ji>lS6kE?E!Ax}@!kpZ zqaBq_clfcRc>eUEqpSV8f7j^t6<3*~$7)Z&RF&!F>VRh9`YAQf{q=`XXg)AuX6M?q zUp$$0|D(pA9%$|v@!c1j|HxhX^Y5j??UV0(_j-!ubBS|OEgg*Sy)QDIQ+J-WXg@VF zOR@IyjQTsuj(yVT^ZK(^x+YJV(y3;7jakvmZRG5X!|%@se;g4{4qSg*=hc{(Gd}6L zki7r>l#SztH~Qx2gs&$o-?4J#t<~h7r=dD2DRJbtA1$LNb>x=(bNBT^5CQ=*Qx%41`egntuuFac|`q| z{MBaVxoba-|Lq_2{FA!o4Wleu$J#TMU*OH>^yuDU(km1he1JZ4%Du9zYa?y=r*9J1 z-mE&;H+*eJt;1WgrJ98STWhV-{4j8TuetjtR#dea@o>)IJ&wUWeRG#In%lnE@YM1u z4K%%|m-%$G$)b46DekJ9CusI=U(CMuq{1SUzCB;OT^=?FLtRjMh{) z`aStUGi$m1vLslg<~M&WpY`)W(W+^VGx_Au%@bbTUub~q`YRXYvyYcu!bZ1pVZ!5;s{Y<>-@to2@fn{@eU^ASS$ZM-+2a|r zdnMmAUUKq$PoHR^{JoLw*znAOZ67uw)$RKCnm2j$hR^+fss0l9PgQaKjjde1zgM-@ z-L{_c&s^m4O&mX@NAqUr{U@)sygkyUrb|=%Rh8Y+B|^upwuXN^!WtjE{b^qNkIeth z{-hRmLD=AjT2-rutF?K4x$f}V3z&;du0@tw=))`LW8YV$wFAQM|2wl)P4nc-i+ZyU z*bY;xw`u+8P40DJ=i6>hx4T*SgVM^4+JL$J>lwlx&PKbK2lwwTb*{bUTk^d2)BLmA z>*{*xwSnKeb}Up1avy)y&#XOYUGPi)fftEiF1A*le?9245i{C$I5drDy?e_)zf|hb z_T<(2(}(yJE7(T8n=W2I{Km8<8Fondx$9rdrH!l9`v3af`fcd4QDvEb z>Nc-=a?{pN5B;$`QSEry2NnCMMpf$Dx#r=f9h%PA+ppEohKvObvxuZFHY=p|E^ z4*yu^`A-|Xv%7w>VcSS;V&ul7Z4OEPHP>luvZn5h-OT>AV_SLu-hsUXjs1657{hd4 z+2Z-2N@pvatK4=@zgcyDLwfrav;KUDP8m^mi;S$HKl^&_jNehwlcf^(_cP|#uG!u2 z-SqM_s&BYWczd~S`i=I3j<*S4p8Y?ux7)^9jq)EfJ@&zYBmSyWHccWuZO8ucRMBS4 zj;bBJmX{xOS{t~OTRruYo{N5cIBCwPVYw=2zBo6w`I*Fnt7S_@)OmG2wZU~^+NLM> zZ*1|LIUB#-tKsR>4L*ImaiciXWwvh1@K-E~}WltXa=gO(F@z{o?bNekg+t&AGVE?e&fA%)i|F^-*Z}*mW z{P)%Do8|LY$7&t)GhnRfc; z^ad7T1}Zl=c{vt$njv=_?wtlLOvY$D+(93uk-3nL=0jd92>9<*(69Sz%&ELfWk~VUT#{Y1@c7{6#<%vg!#mc=@fUxJAO5Ldu!!1= z3QQnsK*qq0AzzAl_l`S4KFXJ3H_pL=TMo$_j>&GeD z=?rRGXa?}7wc()1!UY#9yA2qn zcx2Qw#2M2KL-do_?V8PnH2VA=GE%Pb2^6LbKKGny*Q7^S>36VSDJW{~#!Oe4AXO>N zd=8Dt1v&pLi_sgjQOe~oH&Md9=jJd|akaWrzya*jVGaf=&htBou7oWqa4_q~{ytV%l(#Mk`Z(T~O~MmFpt4+4f%ELa>5@u|;! z8;c8bc<{#^J&s}}aK!Pa)O+-WE!Hbh-kxG^e(<9V}L$wfGI>IAZ6Xi;rGhoR^d3NjK@>vabgMz09c zaL`hq)#>OT_uqe?koJo&yodtt`$+zs1Idy-MW7OE8O=fkHmNG3;k~5IBjvzagunUh z0eSQLlrtVxf4JtspO4Q*K%i&#G82vi^R@&S%Zp1IGYW`U)o}CXO}y>F`|-91?{V7S z7>7`*SDUC>RYSRkQknU%yu^=m-1#CMpXHDA8K1LZ9OEmG{zv@i2mdZ|6%$I@!evg@ zC^Gx^o6{l`8WAWEY>1vG6A6uYqX^a~yL00br=?jv#=#5rGFU zg%lWIL`c!7-IMeaa&{rwwBb1C znKKfF8OPXf9%6ToX*5RMMOBB01v2gp!(oh1f9kVB^&EdvdMb0({>YF^ddLmiR^~+3 z$M=~)j6jX$%|n^!$oPa(PSM;367(5e*K&{{yJ8WH<-iFH_`SUUP_YoF5e^15%q`4g zZgxiVFL7fiN#)!sB?oM*?_y(f8?W8m#KFOq%JFhp0i`lQP!8o{LEzL3TR|y38kJtB zgQa83c;GE>!C|wF_4RFBySau&r6#d)N@IvA)EY~OB$DczAbIyil&jNR1){H~YF$ia zeH=gNVUlWdIhcY{3A9aoXs*j3$}*bQ#9%Vi9#wHo@cZNxV%vM%hbr{;2rX147-)>g z001BWNklST6)8mLBBmk!;|JnFj7X zH;GGE?!f$s^QsPDNu!O2*|zUK^&&p=jcxRcGg_-k+-Z$4(6DN>)wS0p?4w|MveCf7 z-X2b#J|mr2uhUl5L#xZwStgy&sWWG7-y?^eolR7ztLU_KZ`DdgqHE4su~d^?e%Iw` z{P4TapfqfYIpFfAoyZrb>1f{ZE{g! zrIZoy`=9(O&R;l#cieYOz(WiH0ehN`7+mT%xZbo6J;!hP`5yYcp3N=oUy@*BvyB(8 z-NdnzOITc(R#g(qsVUB6s)2it3;}I=V2)*1=(|)==NdmxaTwbWSWfe^2KFETE)AG~ zkyUynG5wUUH-ZXkcPKLLj?3pm5ELpJcrW9p)Qo9Z@pG_I^tOOB!?<5E)Fb zj-VqBPMwteQ5yGeN2(#GX&cUjE+KjidHTRc@O4sgydF~q5=X@`E}lP)cfa#N84y`& z8J<`)FzMZ?sVOV{VfkT&>3|3oY7|Icx$rOCmvkAqJihgXNAZq_zYpc9Spx)mcB7>2 zQHQ2QVHua4JPnscCl-~D74_VRGO!_?Ag4^QWGSFPvjwnX;E$;*%cD7`Zn<|+;A45}fSU>LxfJ|dfMn<*gs?U#bkkl|ea|{a$ z(_Zjz!X_Jd0}NzZwzhV$zOjYP13JS9?Y&!wG74P#D5?J4_IsmRks-FS*8*DYHYO(~ z6m2$}hl=htwzhrWlD2K=J{paA9PVujtT!em(C;0fK6MIFVFI=46msb{CbE4T@5Gq% z9wiLhixQ)n_|@)}z{(gT)2LWwlYj(al=nIa`yy0ukm)=+b|H9B?pD217>L{7(m!x- zsGQBBISLtRF9%FXX`W1bASUVvJHws@8^ZzivIILZotlec<5X2n0;wv=%}{GhVsCF# z<=rX;OcT^g5kBzF3rM?dX%Xo7?b!%K1}c%|wY&XT>*MWr9>?W7r*QK071SnYkV?2{ zj3M`7x6{W*|LE&j9iH&ioR#wx^JQ?0-nw~Bw$s46@;4HkvSgCiWRDgK-`?@i!xAl0 zdvN{wb=fioJW-Tjc6L!!IrJeryPKGuUQ$#{$4#Jq->D2AeB_)`p*gXrbdDK@Ngt(Z zS$YgUXR8zAw}1DeIDh&S{_~&zQ2{QpQ3RIS+Y~Dz!grp2319l+xADQBdM_ThLamMU z0N_k;dr)IWTg-fYjDFHbvy;QsYq!xK3~~Sc7trl= zFf~hNg{%ZCdpgblTJRv2R%P|3e;^RIAQ4KPj7puooH^(d7*JPhb)<36gph70R1)sx z;9T0q{1()&CZP6 zrIRRGTOoVzN;~0cA8MCsCcOV{)Q_dTm0_Ha$J5G0-ON_eP?_o3CF(b9W#2 zz4P6s6Nz%*wTN1cmaz?XTFJ2+LcqZ3)p|H1aYiANnDK_#za6-ES(t(H65eT8409Jrx2<-3}_kUZV`oN zy*Ylx3ibwN%+DXk%RraISZDRaqgRYo65}x+E&6a zHd<3@Z$%(HH`pF28xOgKC|0a2?&&uG6mr6iI*Q>L`>6JYt-h zsbb+^fMq#3Q(Wi0OggL~0|{esqMW*Ny2c<;uouQVtWACwnN4G>Oh**}tND2Y2TD&k zn?&sl#iIk2=S7IqA$pnzmhBm>Yyx4v&jz3KyE_=5TZnM0+eEA)lcANeg&eutAhK$7 z=FQf=Y@Gs(L5!uz5`N&pQ>sF;(rxxK;gpy@Dv2$^W-vyE_2P*++;wgOciwpk3(FUf zx(yd@jwAaN-RgS%V zxQlX?C9yRD8ait3UG^p*vv7E@i!-do${Q*!HOC3nNwJ*OwhpS+Vsf0I`?pr$0(wAi88Mqku<60DxB*uZ|*w(;~ z6=OD^sX%_O+ZKQdzK%BDN`B1`1uz_fdh^c|R(op2wFMS<7}MBmn_zU13~}x0Eo4a^ zv$R)AKQk?u;&zmwRWG17Nbv1vpF#A|-}^V2gngvqrS>MZ%nw+ZmxL9LQbbP%aU4~~ zX^Pfi3)3?*Ms36iKJt5?#Qwpq=%ztG#^TZvcD8mD!K)6RH?CYtUO7l^M0QZD*K626 zJP?BrXh9k#f&^n|)w#szW<7kWNSsmG;o+ePC0Pfb0S5<7r8YQ;A&0FB2pQA@>XQ?g zsMjP0?035=oiV3i4k!rYXy6!4?(MVGt1Y36>dK{PH{)c?0rTiCEOLMl0E5wj-jT~0 z2EMkqupo3xqhRXWAs)PZ#=pxcQUWRFLW>p8rI}HZlk()bB72g3UZxtHsN4g=6h(u| z!TQ)0tf7j=)hihYv=qIQSng9eHI!5DQ-CL$lN-S9X<~9x-7Raiioiy(#5`S5)fdcN z^0pQhmQ-R@$Qv8Q*U6rcuZX}X&Zu&A@$;${i}oCaXV&9EVlcDVE?yGfrQQuA#jv|i zi_pDJ-TMq^WAOI^cxG6Q)-y*fOTimdh;MxcLcfN=WPNNBd1g0Tp})`{y1v{?uE z?0@_$PM$oki0t_B<6=9?l`39+0@l~pvA(&5_04Sw zC`D^iBuAsjXo-eg;!?FLv^`v6q)1Im&$>)f3z4sj9iUz5by}F2U&7w@EeV>-jblJA zMr(gv-_e*@LfR*g8X#Ay;n-{$^LrgEX9WQi0=z0g^{9HoQip*N2n?4g*j=MAYS!an zzB4YIz@R4)sQOz0fPpwK{mvp)HZX-tAs1I5$Ab2S*Hm{|l@!yt*q-C>X=}Q}3^&s* zT9L^fl`0L~uQyB+XeqPPsVUo!vP*X!pT_-Xr$*_okp_t0CaT_o85(o`UCjgco}b0t zmrr5&+#Sdj%j&AgXj%+c1U&h@tN6k*Ep(z8%*@T;+=a_pQ!hUI6oyF;w{Ks=nKKu# zxxS9MxjF3aZDVg|1BF6e`CYP7?e-yZY_`M3Y6Y?ZB>@21Uj}8ID>}fzpld)T9iZRu zh+)WO86J82DLimt0nB)^v^~n3FkWd%1z@x_%(&38a>-c=tz5DaK6chEmlG88nf|ED zp#nG)&>N%Z^&?~*$t18z5Lxm8H6;bz8}(ia_M%9olB!@!W2LApNbHNP>2wq99US6? zmsW6dtF5^*R-8jJ(DT!miOq6t0iQ#GjcoAPE{UP{6p$)uk^}{^$_!l9+oFK)d-z>g zUA>Ootxeqfw)bFTeG|8DUNtaQuPW%?-rQA>3GTZz&52Rxp5${9@L4cqRSHTudc45z zs8*^t*zMrf3kO>1b!WBtp4EOAhqWrYgN`vZFTH^1!yo?5EYRMh=SE!x12R@bH;(=k z;Yk%6^1$P|a*o++uiwI_{`k){$<2cUA-YTF7SWiU$9MncMO11mv7kD1AXb47!wA@N zjaK$&2HZ-DCK?k8z!Z^szFkO+bX=7k^o&;GM6qt04K<3ziprum;2aQsZh!wkD4yT9 zxxJ-w$z#Wk381Xpz9nZ8B9y=u2<0A0v4{zvdQ|k8HRfrx*xGns&%#YkLmG@Vjfi>> zcrHJ@&J8g$Gvh2tNt=o^(cPC$qFSQ9zyvF*(dHuJ0#ZUebkedWFs7EZI`dE^pr#y7 zk%qZc7c+KJJYu27%*Z(6)N{Mzr07bz6gqS|Y%kqOVXdu0j$h@4{l51`2xW^b&&o8m z+DPgE7okwJPGUt?WaKgwBI}eHIzc89B3V?XR=a}~wQ2>Ga!JU#TrHtqpFq84YG^i= zVy?SJZAXc0kpaD8i3Tk6kQjF=WZ9F%M|o1cG|1e@Ue3y<3~G{Pi;v1;MhRqI*i;Cr z>wk0krBh1+j*mY2=V*5ZxNz|-78jQUvS?(kzVs}vzw#mqNKmG(!&5VIFy0-{N~Vl` zk;X$bNI#*EhlLrp(cr7?WBRt2wt;y4J?lG!>=>q;VQ)V?=yZkuT4qP^`K-d?ozqz-KWY84wDA%X4G?m9}tB+HeHB%#gtV9t?Gk7>KyPP=9yu26Gs_a9)6vPcu^hA8!yiBT4cu-mp);_Eo9nM1_n3o4((jsB zojG@cQfIuVyAea04bW+KWKZZXMoc4JiZj1-ekQxIV21X)S}kCCaT-7Hj<@5k3-g$) zFu)?9a;luVhCH=otk$x2^23BZS_o!s0my`jMNW~4$x*WvXI~ivneAismjQBCv#=#U z8@&yrOXIv*Nj!l9>3Cx;7&P(kq~F(bTlt_-_T63|$nt1)y4c(As06j@&OXE&-Zu^X zL2M=F4kFcU)`M#cY-kHzgiP@vH4{o9F+IzmIYORbs25umj0C8e=7oNfT9Kg7@aF7F z4|DEm`w9M8eZi$k`=YV)o(b|J3d-|1JvWKJ{`%|4XVl0@h=WcB>{JVANGf>`$=i)V3mk4A1OM=(hZjLGYYcX>B{LcO5zXuIFJFkq>mw94l&IW?*0td=X*h=w)h z=a(^4Bfv3QGtgJc&(oNzzkxL%2?o!4?pq`|YD?@*TvYx^XDj+`T=r<+F|IUGO4?Pi zAyqO05l+W*ZqK@lXmGa_>QtV5?8CVU%ic zp@O|WG{ZV#vqa%pu9D9ev<#yj07TGiZ_P799I5j;2{3df1r@y#ZCQ9{_0WY8Wmzs& zQLffdtxcjaHIG4T&A7~=kJC?l#>XD}D_p&H4G%u}fcg;3&dyGlqZ%E<;o^rD_Cz0l_EzS%y%|%W@zoeDPGL8{4!Tm zRBUmgH!@O_Dz;o#@&8B{B=F>|(G_+3m;{i;=e3>|fsV33LBR@hy>j+L6EV6%RC*|_ zWe<*2<=`SY=79mU(*c@Ug4IC>8J*D3C|)wOHaFI7)Ea)}F*`G(vESX@lKm)Z93wn@ z_X*6`jS&j>89;RC<{8t$i%A#?EYxejLzm9t@*N9UK7UaHQ46HZK60f$`o%Bf3xB-= zRv=P{YEDWuHe$C-KuSB!`(yq)l|7dejT3=^JTTn9%5>ufS>*G zhj8k|63V#>qP(Sg$|Xx3%SKTL;o`~AxiHwE&>h5GX-c4?B%zl zBV&IM)0tU1k#@A}VFFa1rXII==Ggv*`B9s@B?yayTrTohe6o+@GuB zx1RbIqTl(@zjBa}M}ZrVT{Z{?)Mj+7e&tgHq#cY;pg2dRV1Ag&Q!l=ZM?d>{6Emqp zVuBxe|9f!t>UG>$Sye-tkV{h&6jDTL9AwRYB#Y2WQ>;NZQ6d%iz z)K9_AI$$&}G@3C5kSJHm2W8rNza8c6Y4^AMfsYy$7p zNJ@=}nvoVA_0h;9M0-T9QhZY*P%fcStJ@h2)f$j78jHm`tgf!2)9aczlTlh6V|jiW zCl(1F#;ucy3}t+|`MhzGSj})C$dT@STo6|7$z9&Vm3PNz$1GP z4?PV*Lqf{ZDK#4G&QLsQvm?C_Tsi3T=4X+(Lsd>*`U-C92$PdDxc`AGXiQ9_ zQmKo@p)EC%#|%P9J3Nv$cG$tmox^e?gfA72Kx0)#B2@=Lm z-SXX`kB7B%4c}|~%kr7#>}ja&P@Lx$*ABG5VOs!m(x4%2juS zTx!-t$qc;-dN}m9T^H5eGaI4;qhv!z$)fq`2iHyzq# zc3{+0h9JZpy()N^TGj8viuZG5c%Tp;WYj%zByW&nD3n0T21+DnrH-96!G6-mUM|C7 zVyQd%F&Xtx(rcnyT{D7&o@7c74t8Z5=*p|*Jbv*0)2No1p0$djAc|I7e+O*IkQxa_ zqb$>;qs?&t**RP}H;XfO-i4`|c@LOOZ$rDZv9X3t^{i>4*B|1b)k3FZx(B_)bX>{&^#C)F8 z7*KcNV8;$uGZ87DHyyIqiB&Jqrm$Cr=9mW)4uW&HF=ddVAW`k*p|p}^NzMC@s^=v1 zHcgKKRkL;cKC&BHDWR3Pr<7T}p>rCP-gbN7b}E#IkJvmipX`9Cu9{YL$Qxn0j?52P zS+Xs>2Iq;|oO~MLYhQW+FR#UDPfv-#VM_ZvO1Kc^@jpHD1fmap=zqz0gZxmjKtbF1 zq`6>_tceGaPiXTh_+X8SlzK4AS|s zj|yZ)MKl_s2!>k&e#aipxIg12l%EG7z&`)+Z2o5 zr*0%T=W+08G_W_umxvd6EG;eL13&(L7bTTNIqvPZ{lQJx7D@=YCZBxrJNT=wd;>rD z$PZxg*aD^|r||NN&*14Nzl%zdrv}E#=kk-*@zM1dzD`GJ4ly_5&^7=C&Vh2e9>I>8 zf-#V=v2bCn*KCKqLPdVFU%{~xr%)#=r+GIibvSz?h&5MluVH&*?9r1KQUi?mjb(%O@K+cj+W9Ub?LDmvh&cao%HK*j7aW zRr)H)Oc{(6bXEuLR$C2s=v?#Y^b)ZZ1d6N#IBa#W*X+36%0zW@J@ZG}ECDMM(2>QY zu$nrhJMTJ#ww{uxzoWipfgR8@W6;E@%MYl zCo2vpJRcn}$2n)TO;%L>M(hM(s|+&xM{Ss~xI<*>|C6X`DaE&ZouEu5kSZlNp&&#}` zS59f9M7Aix@@NJgh}y2c`l=i>DW;%e4pkKs^+`-lP2tWvF5-hiwl~U6N>~# zES8-?hPbUu@Q;z<7rQON|nqi?n4 z6ppMl|4fi@93TAIpLD|!p%oc!y5j6Te?-O39mUXonMQ>Ko!+r>3&}@;K0fNvk#-e{e1kc+mvljv( zeRr6kou*ieI|3nN;O(pA$no(ucb+0r^BjeLeljI6H(A0Dz4Z)oOyN36IBIj%!dJ|s zck0V1tW2=g9H^D^+b`5`{Man6+;<l?#JxT?uTQN)F%lP6G*YVT~Tez63VS=781O6pJ!f*WR|6Y9( zi0DUcbh$WaXgzO63XC8@)cYtJGb0xw4ZhdX4%P-#O4C9Czw^5v(}6J)^$N<>Ja%_G zQme9SV(7We0j48i7q_|DS?i}A$JR@L2MB3_S~MKexWQnCv_p7s6ZEA@OWeG1Te*Hy z0b8z8PF|%j)}V`Fn4*RS8ge!H#y?xkwQq9s;_a8dH0kwf-nXO0PY_`xfvS9m?HK?6q8 z4+y}GbJC;AHb2Nn-x>Us)5|KO(imDRT4N1N_((=a4$7(Quwj*!Q1dJ+voR-PM*P-x z5BXxn=wy#RjU6)bJ-&70Ya=tHMWm({H zJLM65?=|+}_+pD{Y*Ni>+T4wS(YPUyjYkj?kK2#yvBX+18cflT8dyAW$~s??qV>bG z`1t@d`Pv&dZenM5M~z!XpqA^9fJ@+>ubXoU_s2**+&hgd(|Nou*~y?wF`bG%6SX>x ziH4#h>XIyGAOGVx<&q zWr*G5n(_33XOX<=Rk#;Rr}3EQQ0X-~^Mcht84qtt1QOcG09$bn1Ns1hHBTFc@jVJw z&3>5zegxEYhKaF3r{}78*F8%D54oK;?mey+`1-^ey19lIx0k5YVwDDN7CQAh$ux!T# zc$zS)B_d0{dm3VV>Tftp$n3YxJxeRaiYuLAO}Es#JMP&vd>t?tB={ktLYpg~kg(xb zNJSV!sWL{LmTVPM=9@fFakiI$MZpu<3#Kak>+DN~sz7}rJ4e0vmvkcz*yich>ZC!cmXD)bSR_PlpMJ!;E74f|%ujBgT z8!Cf}xEU=*#D`;i`Mc=YNA&jk8#q);~pZM^{! zolXAyb1!3US?`fe|gGo`FK(Ggv%h3);poqpvQb0gY02Nv@ymUFg5 z%{SEa$f8m^DKa!%@}s9S;Du|eC{(ICfznQh3@t}Z_53D7m}Tg++iJ_rwLqrjZTH-X zG_gt#-a5rnGWDawa9Aoe?i(QIGdgG89VQvSBc+GItArzTwc(HST?k-;2G*R19seps z?`)PK@3Dh2Ad%OhTEF!7|K7M6SDfM2?QH=-bJ{+V3bZ3M51RO+PktH?Joo?}c<_F_ z{`wozxmcyc1U~aeA4hT6MOC7qapzGBtS!1e3SNS9wg@Sl+hErYf-!TFZx$(zT$^}U zeOQK~GsqA}4IDqsGFw{%Tu&-9^Xes=iwM`QzNWV2b{2;*F$w@2yeXCApoC)?+GZQr z42L$ElV)=?V@p^UZjG1tv%9;Cg~bI$D}fEs!AD10D3eJ%J^*GJWV2d^<#sH|Rn>xZ zh?J9cU4ZFIyl;Wmh-*KoJkh>e<%wQuss>3zuPSliAeO|zw7}pH|?WME!UA$S_muxhz@gqbeu*&(ANRqd*$R5?m0gr2f$`IVLb%pJnxNZ zhT+hfC2{NQc4O=w#wyi(>$!P6cyStMPEO&%9rvKps7tIXXP`1xJE6jCh>1_NUtGXv zIxKTC6265>7HSAs5<8$Sz$yy@gT(inmWDRSQX|I1Cdje9cYfNn4i3y+>|A8`O==v< zW?!|VJXi=(v;u^L=`Tyus{NnOyY{v#qj`!U?@xi19Jc`lHhbdOF~AGyZUPOvcLs)u z{1DR!YFJI-WrZCsdwviaTa%ALGxv?P@D7JZ1)xn^>RJU=iP)&}o@|d>aK!aUof_8z zQ?g3kYp>aShjSj38lkva`m&HN=I3plS=UqQfQ)qvzFI8?3MF*fJq+B(avW;aD*9de z9os8Rb%%hP|0Y>*^VwBA{*_ha;xhjEGv7pX>B9N!?z>Owm}hqItJfMDP;GpQ2}>o3 zX*fx>N?qa>QF^Y_w!ZQffdxk#L|1CDoD9+4{T`MVzo&*u-Q+kv^2rT!+w7{<6_qAN zldV@PWn4IWMox&UBt-lnm#Nf5rDDp_a11mD$#Zp_WCDhpYpdvysnA4*u2e=HjU0zZ zXaq9Tlhe54(nZ`_U6YE{qD|K7l5GgR{>?aqCPdAHL%ic{mvH)+9ZaQ06izjfMWCah z-hq7zxJh<)cG2s#ES=$bFP7<9l<&uYj_S3|k#aNenfh^pdaY&@Y&gj=^mULkuuT=R z^TrU5U*~rj1#M{zZQ#+NNn@41HL3C%V^38OwQ}LS^2QpHToHAhCaGE^U$nLff)NXA zp>=S8cBiG(44>hB?|Q4#Zq8&lDGYmH1H>s`k518i`s2G z`|L}&>+U;L?eg4n&uKo+oja=ox(*Kx@zuxv9E0YTpV<+_iX%Bh@b7QZ&V;il0##(| z#T}aigrg~k5lE0hvbMjBy8CGkowR}zr_PMTyVBdZP*-Cw;Z+W=5hU#Gse>Xr{b{^C z;$_rtV?2@~c&~&|3Y}R+5>t>mEX%7V#PWICr>dI<#DbX zDc!*4I(aqO;eCgGCP$8GcEO~Lfq^6eh={GStu4FOL}<$^5bD4)=wMV`IPT_Y+lY~} zYkC}9b&~}ALy2E6%CM94amX^k5J?7FBIMP5t^yzk>rv0E5?4D(QYCqV81KICB$lU1 zLo=8PhZ@#jf^tq*(1^(QR|`mvoRz)$f_8DKSuVn*GW$TIjdB#xmP*~)MO>7 zR2Pscat*eLfuA4D#_M}^LI89E?_LsZJya6J{icf+`2k}*RT{4}k%>H`oM|Dfmw~5r zsO)bvj9u{4dKsYda4GifQKwlRJV@UrX4e=GrdQdZ&JM~l&dGpmO=8l<<#5Pau5kK?Of z{ki~1BE{+?c6avG=8_Z9()s9Ymcerk7BIgsr@Sy9LO?<16R>Q}PJ6Umy3tLFOuT(> zD1*GYwua6@8$H(k`cD8AmMrLzL-e(g8%E?#Iq0=oMr%o#YHi)o4&tDyt7Yg^Sw<*lrCl zQLTH&R_`(3kw-}71R8p0drOU(^qm>-1MhtZ@qndEp&5}yFLr%%P&P*%Eqj_lo6rrs z(m>&mumDYbtb)Rq&mTZ!U=GyA*~OB9vS$gNmF!yAx8P_E__N$JhyU`w`p1Y<>vBg5 z{pu^L^td*E4n9Lv&BkHW-<-R6LDcD!-~Eo({;AWa)f0pLJHGPR=h5F?_XC(hS4!7F zdzvUP10m83Lb|YKWnzvn2mzRf^4t+f7*$9ZlhEwMNTNDUpT9%rE-*s16Yc{0WKlWi z=Z)8|W6R5SgK*av7yEXj#BI#@KPI5EePT?QIeY$a4G}1Z=i+PJKifN-n44WNIyCY_ zu3SW@XVtm`syTv$3{{q^G7T!inrAs!*|XAWj8wx}8%H!YVtbrvux1P6o-PuPieWS3 ztTpHd+S&6Nea0~3xaq&6Ft2e$MbzawYOpx9+oki^?MTWPTgH3N&A z@f->!V0fJO5fOSAPXk%Du6dn)&j26CgNKT-KaZFtcB9k*f1FQ_H7nCHY;AP#L;u64 z5WVN!4`;o>z*?1()-M(m=$ZnO^Eb{9QH7Z=l~5|=P-ma*e1vMPp#h`#kY@^z&fsA{ zc4$bX6AZuh^~bTjy@SoQb(}eUQn{#=m0KEYHC6JOQd zeo#qX6RV}*CtrzT_frG8NDkX=fe_|ZL#{qJ#SvXfl;z z849(0U}&{$NSbtdJ|E*B|MK5cYiJ%2a(2cbZyLe;s5L1mQfdm306Rnvbk|`FQ;lWhQ&bG=s$(mRdzz~nT z=OIydZhoDv9@A%`wQ!)*wOJiR*t6O*9?i+Sch_HXmf@@kKR-Pjm=qii$2zFI&B>E~ zG$!mQMJ(Db%kXQz_N(d?8glKgzPhIJuaTqXV)F=;j%s~-FNu?h~rG7du= zbQ7fc22P*3sIGVvFbQP4=;|nye&hO0tgo-B-LDxAJ2*^%fdha*%ZJ>*)|C2TSOjk^ zXiaD=rFckHxWU>#*vIV5>L^J1+v}FkbacMLc{X7U8oiw1gWrD{$OcH+13^85>{LmmR5BYIR&FuP8B@2wQpRqE zX3zE@LGH2o5RcrujI+xVID6>==8qkdX3AJvR+fcI7&4aQ1MYN8Gt1H0Bf{16yb0ya zIsd9U8|!1#qeSTeQ~X={GCZg2mAtx&>XL9>^)K+X9D)_v6+75%9H7x|MiE;n^F&Zf zXP9oy`gaJ#k&)1er^a4bIippWDF06#7{%-C5?ibQkuh>i3m-Oj%~vrsCasvAbHEch zdCgHEsx%FCRUxHf5rZ*}p7(bKH0UWTwcx#byhCQ_*MCS2wG1iU7;7wGo>BdVHH z`+H-!IREOm5ulgSM=qpvQKC+Pb-NJQ4(*RLL$~d%(>>#3-AQxSG)+CUtZGl4eUZak z|H&s1z3)BWpM`w#!|v`Le*K^P5@u&654~ja`NGLWUJG#bOa+Guk08{AihAAA2x?W6c`wR5M75T-F_b&uA$P9bGGUSqcOR{ z*iu=Jfrj4~_tP)m)&W1(+SnaTWOS&`e#a24=02JS`^HE)14D56$ot-*j&7lu$jHgb z2)ppePaqrX9f){?oSK^^0vhzVCB^Ut$u_g zU%}aP7i}OViZ#kP7-Y^XDc6;oE4Y1oRRCTBJZJH2{TKrjt~&y!+LI<84Jj)zGHOX{ zRW|`_@mWa!Qx6pOrC2qWYS{iZ0L<&nC&2N63!`aFnZn3Yr5!@)W6+3bZhfu^^yFYe znvUrx?}cKei^jqkXJLCYjGJ#JfeZnJDAmC?hZHKZ7M=YIT$`ci4g%AV26bntXwIX& zAjS@b4Z&^ z4U<3&bsrWrYmIpNQw~QWb_2!MP1e~$0R(fBBY-RiZ$~?;wYbuXWb>^54bOO>Pq8_+ zv?JLTyI0OA83l^$?J%rx%r)Pq!=929^+w$cyVfPYvtvChC_I~1m+VS+=JXjo{Oauuofa2F82o;I=GekKmY0`}ZW%cNbN&))uv4R=b3^%D zR66h^NwfgeC9XfjjT<+xd%%hXGlW6o5L$_bd?0lWjoJhj78fx&If2!+HIK>-AcaWV zC|A>{^E-N-E`H?w5994`xkm=@=E_YR>>ps|)+$>2EuA4Tw>*uv-1nf+u0V!zy0Msu z!{&jiFl!G40aVT{t z=XL(kKl(M~OIDV~_domGtI7+SlQmAnj4Jc7sSY%notwk$l@&bq>~nbc_kSOXg$nA8 z5?+7pHT?BAzlu^!rMewgPDiNkI6~9QNxA6MC`c3SDsuCaGL1&}8u5`9DA1a2Y`k4E z1y*z}j53FX3eI1+Q#2#@h#b7r@ODhJr4Vmizk#*2HMHe~2neX&wuiQ3!^bI#qm7%) zn;7dBx}Iv394PP^B)C&9xIQ|OFRWQMdI|Hyyr}`^0;)sc>>xu$&XLc_=1h?&butSE z630iL2UbXpfT$Jn$eN%*XFIs(qh^WE7P^K?416U0#n1J#Oj?6Zl%h$HD^ZL^v@)YGAO*G(PrKcv0RgmM(KIpl^v)lfTrE{>x70OqfLfLQj#U*^ zr8qrIB#) z$YFSHJL1$*Mf~BxS!8(V&x}b<5J^Bw9f-GBj@fD0QM7sl4Z-xd0D#sw*%hwKAYL?$ zU?_)F1*VHM2^d<3hZx2ta+j@S`Kk7~LkA!Kdw=!gh~D+iw`EoiNQEiuTQjvR<^-{X zf)~~TW~H|u@?&{jTU6$_t)`!jTbs}i`Z1+^Ca1zklN*JT^!oJ`T)cQr`F~CbZMlkF>iT zEG#VGfd}qEW5Sv!$(Z=UW!j?5?P-F^X))je8V%_@N=e$;#lXT*z36 zKzD{H+Md=nzlizyX{%(2B0TlfD=3z$E?P8TW6y7GbN8DEYNGVQ z3oqmGC%%K9|2rR4Bsx7ciRYhx9?w4cB%*k4ysknH-m5D#H)_2-&XJGUD@MQ+Dv4e# zVdtQOUTkf0Lo*~kANQI{rC_wWqN7|MeWs9$C7eBT(R<+=lVIn5*x_GVh4l@w9wJAXIo?MQVA1dkAP&y_7*{uWIH@k#rK)O3GBPxf)(RYP+P}S2;vHKv)RXN{s9%|IXv;fD@ zOPswNmA0CF?)e@b;zj4dqnrly61vP2`*Z%kbiD_dT-S9ZT%D&U=ZFC?$bke%03=8d z0KuG;6P0XI!IEi7mPBc_>)&2`z205fvSnMrL9(cvMFmoUlthU+XXHR+3?}E)-80?2 zU)4Fcd!+S0`t$)D%yhqg@7{CIsZ*zFa%R@2JRC|_Rd0!{cnz+i$iG*mQmEv!h($3* zMMJjVq=*_75!v)!Y>Yf`J+wa}z?RkRSkY7=odH|#Q3)xrJQ2%XQ(-yq%;35vdN4LK zkFi;b9=UU@-=B0mikmmKpsO{3uI^T>T7LmjmEqYi39(5Pp-PVWlJ~_HLXgPBBFh@-8zyhd2kCY&>7C4g~it(aXAzK z)Js@Q7`FB*xd1u(J9;8wa6J<%7P~>ztAxZT$@38!k55ecXwJp;Ob!Akrvefz6p^G+ zPn=9`lA=vMJrfOveN-Pc_#!Aa@%D8Xn{sGFET9WACg$Ltxl2tcl13IG5g07*naREEk-U7x`F_9C}v zgsJRy7c>S+iHhJZGY$#~Qz^rDXFSQPa^9HL2E~C+jiShjj|BDeX`bbQ%##G#gVRDa z5JAGmPel{B>dI|CDd5nq^9_{6I_o|3Iy75MQT4@k(b9|XS>(l^*B_1&f^hgRN-iV= z%^=~n);u&qViO9-64dK3y0vE_*mM1L*syk`p&`*I_U}IdwoDC~3UI8WS%Uh^EphMO z{dnZD$MM!%-=YMzsi6VSKKm^8z4!v+m=?ru9Ds8B#6}98%;;@~fXYeqM^%ma42~m~WaG<& zg~7`E=bWsHPEBKNMIGYv22lqN0dI~;nRaPj;&CX8Q&qvsP@rfQ!a=5>(b!u@->^8_Iz>1=gyjf{^^t35>| zfk}R7&4ah0Sj5J6-G#`t*X}8DsD5oB7$RW$2McIyY(`a88XX;-ICbiDsags>#Bi8| zWG6c}qeSWUcfMBb5kgZ(4$jB<2A)Ia(z(3@l5l`Z#t9N2PPi0Bv{?6~PHNgWp^yEVl zrM6BnTdI^Z2Gu~NbUkP&-q+9ep)@VNyTH=qXrQLw5d5T2r1&&Hz&B0Ldn+jbc) zy=+UV7x?V6ht!+2R)ZyH<#kPkxh%#eCUNNKQM~-(%eeK;Z_*`_xcJO7&)~@3=aHlp zvLi4g$C^=6*^DXh5cC}M`Rq=r)t8E+cVGfJx7#-D0we8m9q`a1Cy0M%qOLxpGx#%e z6vl~S&8oFZGK~~zvfg1mh1WQB_6!Ej4+t`ru09p<{GNxOmC=tw(_ylO_m2CCre{nh z`2Fxbdo~td802`JJZRLbcJh~01Rbpm&o1me3P4rYR%51j7}doH>f%I9fV5=K9R=Vh zGLg&DJbDB<@nGDdo_+LKMCMCVnK@PE1;!4LEJ!gMaxj3VM!ID-V{CBD#LSRKZN7-M z>UuOJlc-5lppdl#hmALzoN+A|DI^-Pjny*?fh-|zGUNFi3wh}(%+i>tnB#1r4vtgf zBT8ym$zHX!2l1Fq-KZcTluWXA-klCXW_}KHxjbgGe0^X%lSk*W)#&b7i@~7*?J;Y? z&ZGCpe%!pJ3rm_~Sh1=L9ZNPMmf~Ss;W3kDTNzEg7>|f>Iuom~#%*uuSE^_1h=!T!BJdqiv+(7 zKgUR_H$yIx2d!mnBgKZGGmetS7j#1GaT;1{+y_Htm^9LRL#;2H7VxUy3J~%rv`5?= zPFCDLWuc;4LWg{IOc2?2N#ZNtc?t*nXOT7e9$da-JBE5s;*yQc*nQzr5(w=_yr{ z3@!}L43b(%K`Dxak3?LfCLu!#`~be!>9c21T~)2DkiGnnlxQ{^d0enzgNSm>FfArK z``>#o$)uTyu$m&$pdJh>Ivz~Pl-d}PcpT@?_hM*h&b>Lz@w&P3p zwPgOZXwKdiv$5ut?T40%;4#}^mghyW@0ETXYDAL=R|R)aB~9@-Mu&$mGc#Exf4Rji zv*a7E+6hF>h^AaY+wpD*i=Bw&zq&Vw_sI0GzZ0|;9jq?n8^);0Xo&@ikSK)Km{mm1 zXtQ$E`3-hpDeZ_xv7%=+Zo1_??tqjMFpj9!_2i!)h*f|HaBkx43Q;k5iv;5WeYgjKVg)kA{Fth zqPCR9kra`~ED#&3+x86q-_hBI<=x9&q{@51F0K_0bOz6Jz2}r9#8s&ox9mdHM%ORu&TZZH2|uMam0z57-7bc8kcR?*t5%@v&vtH*x|&_InVzlj88CL2NLb0 zjVM`&MKQzPcQkn zFq@?u^Nc3XYHDkds;t)1T)uKCHg3KUzxdJp*s;0|Rr&MiZjWR2`YlM;RGHnq+X!p4 z+*`|Bk36thcya%*P%{xZjt3Gw0IF*%v>z4k<5tlsPWjkfiI?ICpe5(_e8T~6LVabq zanon8*AZEk1V$G;A_;RoN2EC+!e~GZ_@}8OT1;ia%|xX{boW+T;3}~oChsB?hWT7p zJR>H&I-8hm5Y5s}H}}sF6ZyN!)SNRUeg<1&QsA`&M)6m2$mD68Go!c|`2{7$DrBWE zVT5p=kBo`@Kh-WZnoKm@wR409QTm#%oUU)t|j9Jv42NAa`A`%u-n z6vHE9Qgq~%U%6)o_V0fQ$PD9#%U0r=OS%!sXXrbKd1@&LNj1W>CQksY|AQ|fvUBHU zO4cY|5`s}sMdJctMHw{El>ts$OF&Y>uGGdo6r2*(bIWE0NvU^4l{8I8u&-n8Se%I9 zf~PO}(c{Op(0FrL0S4HIH+%EOji{=r6$-#FBQd%ZtB+hM__&Tcy%Cg|h4CC`>7QYe zFfdRe;aH!>GRaV_@^x4-Ri~@b*4{4j6t*e&dI5pZ?@6q~?5PQfO-xRpy{ifDdixuV zd39DFTY`rQ%p_$nkO^ML0jEi(ZtW<;f)V7JS zKWUJ!ZNxA)?^+1qkXxJ_c=DtJ*20EENYrx-k-GoVT|#Sw~yTtx!|Nf+Tr7joMuv zFml26g^fG$KB-kG3+bp;kuK!KAJM;=?w&}J8c}n<5NaAwG>UXVsXsFAxR_Dk;Dpv- zmau$e0g+S$(PRYarb;AJ5zI5$nw`fCZH@C0OwQ&ooy%ilh8_$?fEF2C6Hz?afsVQa zZn$U(+M8ooyS@j_9o?u%F}X@u%SVD{Om5r+O{1fRlIZAhV=Iy-l{8i)k*qMS3K1Vm zW81E&K*F69Zp-LkxkYEKB!68eperUPj9bNnib{lX4&}I__Cii$rs2Xh`3OI zV5e+EWSQ%^oN)>DbCfW|exa9iWGog?SzW2;B$A?%Vmbfx9eg%oWa2Au8ex^!JsZaJ#1ecXWx)ko67qnv$TkG+|ro)0o9*iM8#0ElMs& z6H(mx!P{LMJCC7(VJVM2_w@5x#1|7uaKQu1_DWnOH@xwM6_1JMz(vgV12aWIdL%V! zmNE?TH8Dxu{{T+NO1fro#VQi5ln!4R<^o?^w0-2+Q7$Y-G~ z`jRD7Tx9>$+lka2h+AbPG;3}SXM4}#^y#yuNfQQ3?gKIE=jKX!C5w@t@O~kw=6l!I zH=sJr-nU(&)LO}FlI6OMQHD0!;t3*CptHU*e`a!G0+;XDf$6CUoIc&F^`{DrPKe%T z=5;NlynHb#V=;NIEG%eRX)Q_6vvWvKX3!ChpgkT(ZKQ%@0=9-Vv1AtJIv6z`X=^3S zyIYHitqEI~L_!`0uwk}D?H)n@w#ox(b)j3 zUDJ-PWvh^`;mm!tnfke^qe0!~Y-wY}5xG!m-?DJXbCS(ecWayK^nDhE{Qck-YZekITpPl|EOkq0){v*{Fs5o^M^!Yx3g44)tIJXK{(>nDAF7I^=^p5@3h8RnozXFz{~l>@(DRu|21R*2U*CGt)wa z6l)}wM}nh~c~uCju(o(D{!U1|z2y)*CBnVup3`)N?*~3d^Os<9uKt7W3yU32iICL! z&xo4h1KAS^Rdn+#3yb&i3AH?{`D0XaV!)@2}7-x&T z3X027a(p2tzTBpFe;tvluikB|UcKlrhGqwovA->wQua(3-{&(;Hr1RQIX`OimCS(4(149@c9~H?l_@)OI?G@X%3vT1<28rYn8O8Ysfk%!Y_eT^U>E~bg`QB`+OKKdj!Y}kl&wP|#R1Jxv-eL-uH+E`_n$>+lsM}Z9HTvmw# zzk;)4ND{&%LO6K6CiZ^0p*tZV2vAh0-h*2tpJ^Cl3%z}-Ty5;lDt?MuRbX;r2K$cp zBbiEwc^)=iKxT#p2PBvjUXT0(E_{x(ZrQZP6B}kNxgmG6|McGTX~21c_)X40Kx3LzOhwFEtl!c>=Z7z@IpNM>@&FYV;?eR zGn1hHVGNDZkjr7Yu%K0RMP*vF@8A(UaR0Ay!KMqaZR=*#H8<*BJ@V)ivW=$sPE92R z!ZK*BH>qv4o@97qZ4kbj{7(cKSPO&}wd1o35@k}tU9vY0_s#aM^=r!Qhc&BL>#(28 z%!_PCnOPZ@?{ z$Pr9Tke}qOD3adPOXXV6WBHP$CV_so7Y)%U)-*MvJ&{IJx&rB35m8>VS~PK0^P!px zm4hKdb_;{QgO-!uQSsO{9v9Qpg-qHwK_McUwItQ5)j?4nwPY&61W z#-2B1(2`&y$7&?h6APB9LHH?CToAX6WXsuT5vRr`ka6;EC*Nu^uwKg1E6kV%xKo#occ1Ge1K zG$AtQ3n-x?pT~R;*pt_p<%pJKml^Y!fK#lA_RtzrH|5`ajzUgc_X!nk0$%7Ynw{19 zG5?PsA{Gi#d!Ev-@s=>JE+(sNk5s+@iB1tE)0sdDpZgs;l2nWF1k}8;eEZPD+6lt zy2E4O9Po4S+Qm9(z_?Ukd_lf^KGZurE6H;KL)Go74Bd9o`P@WaWx|LSK+#IgI z;c9HXaJAlp*FQBqsRciuvGFvy%?Z1;MHYIkA=^|Nj!=}7Z9>MInaQZ_Fg-J&`!+Xg z{oJ6JU^A|^=ogPemZ^M;XJ#!k=Y0ucB!P`?hqSdELRD&&fF)hlL*(Zz;)O%!bU)Ze z3BgEhka!dWef>7atV+U(NPzq})~@I}UT@C=NgC z*Ffuxgm!5kO3t1+T zSwV^=wLR}e$2bb57Kt5HWiJgQ=Z?}3gN~w3+)&c#!NPK*GNMvdRV}e1+BK70#$dt8 z7;9S=@rkk1sOcS3W&4@+n=qa-Eq4>@Dab0CQs6wwG8tAX1x!lU!%VxlUbx@MxhN+l zhF}=H3{<2nNg#s20)XS8gp13%@rDkGPeW;Da*jkib+(nGM-+g$>E;{p=%Y{AL>0$C z9r@6>UIb{0Byn+P7n<`$G~}b;>_ps2ys9QWp;L>Xlw^hkt1MqDA})&~>wK4zP9?Sh zy^_MB6-{d2x{gV}IC)qSRnn}5_zA{Iuq3d61s`?fAzvn^8X9G3aY#*q*M(2LxOkVn zmLnE|u^=bPkzyW$voly=8xj%IW`T)~@!lpP3%GvM67+N?(cN8(Wj*Uqk&Yo*QB|5i zvvl3|hSuQ%4^r!?^S>DbSYb-+ibU#kQVCj^F5<1WHZ_$tsa$KMM3EuAP~zcd#Yw!R zsiN`bMGB18hO>Tz2!SF-1-8F)7rY(96PgFPlz0~jEb%~{m*utlDHP#xOM$Hv>zE{P ze^WKrq>rr_Gz6w#NdnhAIYKTFNW&{m9uztL>ab?u{>)5H=!WJ0WwLt+3!mOe~am-|ThR9wDNmIGiuwN56OqKY3~fg;>%! zbguV6{$J0Ab=bLM7k>P`ALyF8mvv+LilsPy@F3diG8pL}#~rs_hmP8LBqMn&WN96q z$9lFKuGqP~s37l3ZNZCW%`s6{)hhUk@B2R~46comNM8Y!C z8!I+z71%E68yUpZ#H3J!z@%pDK`wNW2rju~o7t7hh09?cH(oM?(0clTv!LFolUW#a z87vvt2&4A*4Iz^y)7$t6i~k>pC;XF853hwR+p)2+5}}h1H?%p3ZuBf)ikA9nTz|tZ zp&i^TblsYsnnuDCnrzmT1`83FK6T4t_OQ$FyM+d;-0Tq4fgzvqStTIkW^e(ODuv&J z$HIh3IV8HgsRug?;9<-u$jI6=E2}bE=B-0m@y8Mey(iI;y(e@pIMt$gd5ViTPh@c5 zysw8K6-*M_0+w}mVbi)Eug=WTuv|sj850nTkjR9#Ncgu>^0LU1+NPKco(+=B;Q%d> z8^kO7kuKseMt9SM52WV z_8vG^p7QY#zyJ^*JaiBbJ^F-2c|Wju-`1{QgUP8`9N2e2&v#~KN)>{tyZ~vtZLa3} zy&tT0l8;Y`4>UK6@relq<-k)AwCP$6mVnzh;*#!e3v7O}ar}>nUZ_+*IDQVD=SMJ{ zOd(Y$;O{qXax*3hk!8`>H>hNii5YoGy8oPBn746gUYk%ZN6$XOMcmMrNO zDVcjPd`X5jh(rknwzfe)^+H=oy>3Cr1>Ahgb$H;{56Y}YFgg*wd>$L>8?h!;h1O_F zNdff}0*P0Z?Bdpxs~-xrb1B_LU{DD$P(t7hozTx#E5T)~jk~3C(MA)4v6K^H8N6i( z?#YQh17T`%5y(j(QBm!Nh=`4WtXoF=O1G*+gyX#kNxXi?TNQjKy`S&x*$6O@nZxix zRudKcJ&{f|j<(JJB#~sMYDXaubP(vq=f)ewX`WF z7Bsdpnfxf`u;5GDLs9mq+*7HF({tZ^Adea2KXC8LV8l z2A!SlIJEx-G^C3-(>sp8yyF@yZ(x$XfQ8%w*53LBM0V}E%#vYix}hSKmbecuPTJkv z7@hp}xLOu*%TL2-dD%rOKWQNi(AU%HcX>$?PMU5|$}>&6}c_nD~(>GP$gJnuCM= zTDYN-3x5x=xyDLpSmIeF|GT`D9vXaBhD{AZGb1Ec`il&= zN^!^1(9jzT&m%mOa_hoiRWYvpKCrj?)V`Cbs!ZE+^d7EEa1u$34i5;nV_=ZhfoyJb zSlP22o7eTIItx63P|bz+4~LySTo)E!JndiwTfnDF#7FD@1?9~}lDw*J%B_uXkaCUL z*rGYI5hb|ePd|=isuG#`oF-iO4CpQL(;xm2cm9_TAvd2fl3=_7FYh~60-#F=w0jmD zICuaLKl-FHcqMt>i`}qcEoP=Oc;SVYG%-V@NfTB+)xdjRT3`P8%Ll(DY1$Xr39;5)*>Q~PEL$Z;$46Ec6|5S-&ci|PQ-ClV+S^;YmnxF zlrKW+iXL#4fOwH&NkX6m+9ER2*W#%fk5tZQF(kyfD&A_49zY-`2D^5TL;6`?wrV4Y z|6)js);H1AKz1aLf(aJKBH32*Hl}3P{os>M#3BXBFd7#=N1m3<&i@jx!Fo1s{A`54 znJ6&6uz<63Q#$;uxB{XJS-frM3bZsv(ACv|)oV8)nNFyuuc`G?o37lt;`JL**pOwS zF>3KHYVYy=b>BR>5d0sK1D8M!$yFFTEX#D8hJq9uojb(%6s91;REPOCcpQkB40I`e zXjIaDRy?sLB5Y_}L_&2n)ipkht!)|PslIerYiXU?OpA%Va8zzt|mO^J)P@(urr$j&P+DKb!+ z=Rz5RH%Q%d+eOgv>NgO+1j&ef8frPK1}&?!?3&4j2t@9?U`%*}q3vPY$l}rCCj{GT zAxGl!a%gU-(;^uj9n(X(_`(a36+y$0i*Tb%de}!#R7Kd~!0b6VuknGO>+Mz2QHaDa zI4~gRGF~H-n~)R){sl8dLZW;P>xmf@7{)@0EEq?>yeWd|1{Wri5`Jzj3W;0zPxFA{ zJt7f^*RMJ6ilo@Nl@&>(5-HTyR$JB?i%a95ftfw2iWFaquA6qxI2%j&*o2vELc)@o zph{`Zho$T1!tvg>HnR?3m;Uq^y|}+uu5exChw`$sS-f!Yq>a3)3bxi$Kp`@&^I&2u z_Kdj}wqCpeZH;w?1Ui=>Jix_kF2Ln>ZI%lDPK&|e*pMt3pTPoyy{`9trJ)i0);;NR zDQzWH;@Q|?!C!sDt+%13wodD%s;WwBXli@}zx?H|@ZR^{hHP$@;ZYLJFTHrkbk#kW zg({G1oN~tZ|LV6&WZBObVwFr{>%|u<$$0+x7v)=G%A>~7sjscoD6xSL){YVa;C*rH zqcY%fBywItM@m4P6Hq>0Eq7r>-rClV)~04joHM!L>yl%Tte^y~nTFju-iNLI!)U1h ze$mu{i_Z4p>E>44-@Qz&Mz&o@GN!7WNwWtn6*mQP&H&K_>YOZ2HmwB~QG!5q$m*IJ z5nYLjac$69uS7KVNh5KIN^PZRsiI}Y&cx__?|%>O{_YQvC<1TkT7{lS6qOMxIy70u z3X1_*q{FhDwb5G2iGoaWq}O00dDeX~j|W*umkiMC`@*glQ2euTm?ixEMOXVo?5f}e)QJ!!gjJxO89u5qn@A*cuzlVfWrhKYuEpgzn zLS$hum&4HfT!}BSYefsTuBk+0a}`#tUW$g6R?{Wmp`IryXG(`ELUiC5|G=tYiyd6s z%(avV1c`PxP16LJqbgw93M*{TWH0Brp&?icegOMtwFB?kU0UXSpSC zQEb|IC2qU*wfLL=_7|9#&S2^4W$5beK<~*@ICuIK>S|N?v-e$v&Z-Pnzy5QG?Ap1# zNT`DI%j{jy&euIFcKt0-7wBv+|SRTr(Ht_N`kiSh8p7ijQ0%%=$voV34QvLjxHuWRe`+q}Rgr zH{FCE{pcqc85>nr$!s#Xa2fhxNe5962FY;n1c;v#5`<%G>uVJR#roDmu!ka28_@!P zFbw+CnJ4td^~9K<3?kDkDnnkXM{NG{pC&BPxm^3CS`&l@z!l(y&OTm_X62gCa~0Z>xHz!?&f$Oax^HW3!S=1|Op@2l!Ah{QpRl2FQ$6QF z-I+?Iu|y+&2Jt2D-+ILsJUkS*U3OKfdtx^`55lu=V;Bdiaq9_Rd)=$izGSJY2|jb) zmzl{iJoWT5c>U{NrFIVkCTEdfc;R5lciqf`0uP{wfq_AM|Lz}aw3ln22?q~}Wy`wt zd=4Bqr1fGVH`Z5I@-0Ll;BI!%2UN>+D%j$SVZJbrf&KxjD7>-@M6ktyb$QPUR8!F~ z0Uv*Utre~%s2vUVm3W#j;*ym@m6iCV;;R(rlC>sX` z2k}Smy&XUL?vHUp`%+v?2_pt+Cr^j<6cCj#HtJ`rIRHA+5=;$s8(f9avJu$o5 zHvT z!C9K%D@#cSa=f8UMz%C_rwZei@VtvrE}4lb`8X9q$LP;OL95I{3`kZYgE|!BRhY^U z4U40#r3K%)>ux;x;){qR6KHR5lfW818$?3aIW`ZvF%v0H$0u;-Th_6cZ<8~=Rz=)b zk<6br1cUpmBA&)a{^!pyxIkg6vXXFUy@sTd`%2Rvh~whjd+^~ueiwf5jj!VAXI{q2 z^{XV3HFWkIP9Av$4J~Q>+57ik_uKv+ksaGFE>hx?50Z1?>B=-_W~^tgtk1tBe`&au zW!661ui4K4wFO&MR}`c`MNno7NU_cOo1|(<4!T&x5*j)cpc_S6Ab#)05M z6Zb)txK;1`j3i5nAV_khGlYpiOioSs9=5747<(vi3RbaxYzXp!K|(mDjuZcuX5xK}Lb|o^txq55~(^ekmisX25Sb2vu-i?FHlbS5)-Ya$rzCo`MoDCt}_XJa{puqO<{rb-!S*P9v} zF+T3z4V*nrRp83qm!Tp-^vHU6nwMv#Qt~G-Xju!|N6A!$EV4gVvF4DcMKCu!a)M+C z_#sIMD2XK;F7fM!BZKMe+#H5Rr;wSM!Av%XH{bdeY~6OLJ6qZsqYuN8{rj2O8yhMWMKqP|3rUq3thYlXneHLR{VnIGa>Jr)E zAXt1aED5vZj@5i`Z*K|GU7TEmB!T`TOP6++ri+4F=kU-lDk}IKty+Hd=m4%8>PIpL z^wa?75*2u2CWW4$j?7HH-m}nEUvk*1FM##(b<*8%C)Od*U+efi6hsgu|N54 zn0^jn^n8xQa*7$*ewI?NM1B&wHlopLGgTTFp+LmMN0=>*V*DYWB1>r;NvtuBt>d6_ccOTxyksNGNVZ=Uqb#xYqb~ z!JkM|CyISZ31G=dQ$-U^%}9#3X$Quz(Oegb6vCp$MXFvZs8h39R8-Z;GM>d+bxk#n z96g5BYgVACt_kHfw!#1))lo_ zV0)r8C1K`(Jd-3hPEJ*^fc^Uh@NYjkjG1{O)rX`Yw6(*3t9W*CG@hx;H*dlJ_h)zD z+uyqv*I&66XZuER;>Z!4I(7^v4;)8xQw{EU@DW5V-n^lx>M5R3PzVWw!7SxqE!#;# zHm<_R#b8Q`);0)Gwe?1$N;Il#tBmkS_%uk^%CeKDPO~`IdlqZftU+~U61{x`C8m2_ zeLaQ-MsW7rDa$0u;7lZO(S;jy1FX_8ZE@38u--cZfb~vo(!w|Zw1KY0NAA2+s(1Sj z9YSro7Wd!xbHQtZ(F7y$(B~{TAvPmv^1dXKF-%TOV`6erqArV(1s>2`&}Lpk-*@Y| zv%kjs!Qe@~2v#^u3J4cTBqJI{M{7IM)m3)Ah+vj#i`lH~tvPzh_nw-XP&GO|HKPP6 z1mH5k%SN*7Kytna71@}OAd0%WIvGq6@!+T!vsX)q$SOCP RyBZ4`sDw|e*7V3o0 z*+?qyZCgjHvS#-0=H@8iVGQ?>5DCR_K1t{+li)hnh|=<)RpvU6CsR9%My$UiIR+6mwCX9Mi-WU}yltfgSBF#h%oVezRf`Ud-Pwr@ll z_Tv*{a^t-Drq|%gt9SU%^B_rLc5Vg-_w5xiwXMBDxe52ci!UFw7K@YHRQ-4xiTmLT z|M3;wZ#yKcGHPjQR`tae*6B0nl<+C|P@QjKK?#;dA4z7Df||jafhS~#ut|uYJ#)q? zb{TdViV-$H*Ub9$>vjEnb~f>0*M0tcAL{BFN=|+6Ie!M5W+sq~0;_7R5_q(-5et3O zx|V-lvmOg>v7XB@DAO@7rNoeTm4^V=MJ8*g$>OTT4*xt_TiQ`qS1&%z@W=={TA4KX z$fR12_B^c(Y1OGdx5u4;-Z8PheEY?iKi-R-`81NMw(XEjMkBI}4zuS%@;u25iBo7z zT7qOf22&Wd>6*Y}3S0=qEQtg8GxP&Ja1RuJLUKWr!q=ckr{W*@th~1dct80+5)R4l zV8WoB)zeS4Nq8-KKQlTD=$g)WaX5@PX^EjH)x1yk=v*<>5(6P1jy~`eeZbg~ui^sc zV=)ZO4B^JzJ!orAV)?2zbS&vnQN*>P1DD!4a&;`X^7PUYF|xvf&o!4Z*I<5@w3Aag z>7-(SV{~DCIu0UT0q0xr`59^!P^dCOW$Ve31GQ#VSXxUpByv)QBkCr4EvYVGH8hBA`Rmx$ql<<)rq>sCoDNxYNby+EXe+9zy9Gv-HQ`14Qx7`;=~ z$hyvoAvFDHoRvv{O|zivuM?8iM1e1GXHnbXWMn4>0B*2}scB4% zjAGq}bvSbDm~=&#bhX=fcQ?odA^0*dAQ**2NrsuLq$Qa5kKXX}3&CaOey)=MtIReN^o+DH!N^C3L*%+rsfwx$M~E?VamN*vF>d_ zYuFEgTrPueeB-+cDjXLKvenC$^&pv!V)w2q@gHBj%V)fU$&-x}(W@nw7sC}D8rLy=GcTs1m`H;$aw_t#i~udg4b zTCucu2uIUte6h2;goyFyWYaFUJVTP$g5YO15w@~SHe&$Wg&Wsjpy!dD&thO;0Ikg} zN)ma^fpMGYX2r(G5@) zwF`$vC!!7?2g#I<9b=pPdxe*4G^nylHlVI{uv)8~;b*5GY- z{105cZ38AJ4=X-X`-Bf^VtO3Uzwolo$_p;spx8?^mg1;SKJ+ZU`t`4&p^1d|1tlZo z+%e(eXu0_mMNwCkz@NWo6B7AZO_fPYf<$!2a03=Kfl*uAi1+=MyK#Qb2*KgY$iw{H z?mFxfYHIK4*_qByOJg&3+;|<%A3lO3hfm-=e|$UA$tZsIgL`$azI)%#5xMEctBZt~ zf?m9l(fAM<5UBW+QP#yjWg-zseC`Biq(-YK+5h1KIC=IgZoKw-433Q9$;Tg8HAM)v zxwS<;@`n!}Qet3!7v{2^76Q1K3NH9-nZ|^`?N1K9-#tpTw%6tGL zleypt3h3(U!pHyYzvAv6+>NoJ5xnKiZ^nOo^~*SX_$bneln&Js$4{x(J2pOHi&y-M zC{`@(Mr(V!W$A=kshvMJt13~9ZjC196evkbl?1{V=GkP$fDLf2WvVbX)wr48(o#Abn- zMN?xFIyyV`oOs=QA09Y7IG1#`UaOa11QESFgu$SoTqjcXQ4${vgc7KL~!Z$OYwm_-mfg1IskMZ z<)QNIGf!b;WDu`<^>wAml$Z7$MO1{jp!pHz{CRJ(_}`!WR0%F;!pD2Ie*FbN)SMId z?>lTQEl#L-0w^RvNQ#LSF$9KIpW0TgS;G5t?C3FH+s)># zU1iRZx4@OzK0b=K51rTe*}D2gnJ0iR7wWNUd=gLAH{!m=79#_DC1WgUBOkNUnx3ZT zijQhAb~wVpMD6z5ZdY9S#n0};Gw8js91FXIT4S^ z2fN_LE%3=Ls*0ARmz~J$Rh*CmcRN*b;E4f~1pc?Bx2Czkv@RqgVS-Gktk6z(x70|i zT|d!qZ964I?u)>clK`PS`T)3?REiDV^=%>umY0`xCpyVqSLqeP$8zQyVTdGiI<>Pp9P?o=PX^zUE6Om<47WnK}JAFeUBp^fOjfc$(0AG>`U);1>;7dS3& z-Zb3fL|=$*L@_;=#s~lUC&)#J=2(mt;^OF&{DNHlk@2^*?mh8j{Gj{lh6^`pRQbg5 zlX&;-x1xT27KfgA1pn*a-ym|`wY!TV5yjJ`2hJO-Am!?XGXD_VLvQ+s#&`IqX@uL@ zUSLx4O>+xHtl7904?ge&dX~3f-~MB$tfaeQJ6_(q7ioGq$oIP_vl||~8#b)Rz5|C! zVlA9<;J-1*Q2~zum%YbTt5%gVS`$u6XtS95l);3wXKnB5z(+s&5q$M40JlI$zhBqG zxcdD2rl^H;bAQVLjQapBa;;L`4aJz7DOe< zhZR-wk06vL5}x{dtSqd;&QP#~VjZr{U@nK2h0Eg94-4s^b0ZRkC;}TduGgkeZyOOT z?d-(a^SwBG?!5QkqNu5?6bqlfP*-2;giPD?{QTlPxY3vTpoId`=}KJ}`^OZ0(qSy& zsi-(2yjF403kCEn@4@Cx>#%a^Qnhm!d_y(4xF;Oc=+rp$ez4Y?3t2IUWwLhYtKGw? znS35+di(MG-h&t&8An}hty)D4P?c3_J!{jsi0GLxD73e=;s5;a|D|M(*Ucn}pXJ5p zpU2_-`*8bv-(EUI_8&M(nHrnu@J*>?gOz#&_~*}jUOpY{9Wp8AT4`_VK!i5D#R85V zenr3a=fDONwBxE8{{CKt!OXp_sy{1;|t*I;Z&?$S&H7lc> zR00Eo{ib{3lI5cJIm51|x*k_wy#rOX&3O1Xzjf}7p@4h_Az26>z!u8P?iN0~aP@>pnd@Wh<5o(99&9ukJw+z0F zaTZ|8Vl-CWTBROjekG)&5}5~~CArc)A===HfodnBtkQ_dOD9DnM7EA7eGBpwY;qu@ zgN$Q#L_(~6qk!*@g!)r@Ad9qBe4Q*-vn?eDB#`?7Xrv=Ug1885OmjhTyr-uU%U4&U zqq7B_%e&B6PX|xli=d`yZQFnp@i|zVz~YuHx?Nkq$gD-A>uR*_*?zQyh6F%^)or54 zM&$W#ypQ}hqK#7h^aLOvo+Nq)r9>94a*S2G)DRnn4h?RRZ;)d_Ya&jD8nAU4hyQxVK6QAwbwqXU2P(T}4r zn?O1_rstZBrQ|>H+eaV4p+m#l#pAHMSq z`0QsskE(PUfA^1ni~s&te}h*J9x_7?!t>f+uHhX?V8h0Bc=5%T1cNN;UXG6DdR(&e zQvAzjzkp;siH6#GRm3Y+uMq;FNrEC7rYU4Ia|$9PtT1cZvgIPY^&RiT*S`LBtX$rM zOSWH%&wu{&m>!?N==hixk$E!2(bnFg2QoM?h9o^I;vAhJS}-dGFRE}c$nxeBNg!{* zpj#sYYHA@%B!MD03wZUbuF|;7e|+Ja7@M9)RZX=PZ-D7|2=QPiQosY8e`n=NfueLO zt#;4yo_1`%WSi8riiM2GoP3{R(YO{=HGKNnXR+m?i&0zKpcaWGNftg$!*kn_Qf5ERvntXWh~og0nsJ3?9CS@r>q>8#g?#f<4st$ZHR(HNQdS{wK!*ZFK9WI@G2ufm(<)k1)93H;-%g)8gU6nFQLNxMz2Q}w^$pdcMhior z7kq1DtqeTZ-*Af<;pIvPIDFt39(w3kxbtIol#Hbg9X^IUSYDRZAD?b}u=Ap=iDM;3J0L%tDF0`njsRi|oji^djD2Z=5xDRW7`7=aj zXaAohfuH4gZ7a_8P9UAj;h(ye;at)t6BuN;_d+tmiKvN*F|Tf{ZybbfmUb`Ip1J+K zx8d7gV;jb_Ntl3hkJ+J7Ci#Yg!PNMys<*a=6$!W8auXi@$uF=qQi-Ni3Kg36i7827 z5=yRul4I}LldGV6psLa*6Fl(6YDNO6(Lf(h{CS)FT4k|T38FET!gRkcnM_fZnH6rAS}5-o9W zoCF(C&(gGqvL9=g7@?ZC#yAQ}5{h|L*T-<_C0(d%h+=t93u+qMG#zDj%vNa|SIEah zb%^`tak+9KHg58y=bucJcphPjMei$g!S0>43(BHe!E+)cN1>&l#7;?G7zMU|duU~p zS`2!Aj1z3R(t*(s0z zxl9Cq_V*893O43W0jixhzYVXu?zPB_A3#24Ee)bDwKXX`@ze|W&127Ca(EI;mM_7d z{>i(f+W4CX9>ur6^DQ(s)ag9p`9WkkBwhRfyw)|#6ZoHhv>ll_(~q!%ygaGH&+&;* z{v4;r6E+GPiF@Ky9)}OgvX-v;II?v*|>S|oHP!XLcn1NihmeFn+6&BH2a<+7+sCGf}ZeIKIfI;>v392Hen z(t(#sV#2fmp4@j5AGzaW=xk5Rn1vRvL!%=&e&mn|((s`1;Gm$uhsU;q`xng3&Z28c zCpN8IhkXA4c5S*8Ba@R@*4c{G@;0p5aT%6$wqbg17GM7Iw~(DL;y1tkB`T{)K#Aan zYp%gHH{5{lfB*Yfw`MKYZ`^=?`L}<^+~g!C#>Y*|T9XtMD9Y&YAuLoOVj$V~KHIfu z;h3x`gCmnC>t}^gC?*&@JUNMwj91{o3w!X$!;j$nz@%C$M*Oo@0zdEg__+S$eQR!L zR*+l1Vg)vBS|#0VW9D-+B~=M>S!VoAtRx@nIj%N9uIxKB8*g z;065n=l7wmu1(3_i4&*L-rk})`qQV*YVl1?Pocf79k;&e)p~zs%DhLs_Nl2E=~ax6 zjbmmmBYpoIXO0U6W!F3usKgd}=K)G&Vq@b(c~$4)jKnE7n#Jw!dOKEhciCF-s*wxT z4h>5#Ec^AUD!{Ccyo511>o4jf$_n_K-}xb$8tU=dSKs90Lgs^@`zNJB%f_Wgpx{?P zHnV_huD?aC9rn_x3QCr4fA4wx?5FqOPe1%e?$^M3cMjPc^(BH)mQS@vharnEefgV0 z#n@-;?CcbD`1s?`V(;F)SlZns#m}1BO4<6(k!XU;rA=i+RzM@E0RLJOwEsfS=$FS+K z2a%YW{!fzx-lHe$mLPhnA5)c;xO?Xwd5Mfq&tP?j_y0{)TJt)1Tan z+L?K*k5`~N8b?(ufeLbY;&G(Oof48^tpmZ@wmFnUS(Rn?O2JX1sFs)s2_>}dL`qIW z$dcQyGbE=aVKMKiYyG-WPZ)*d0jt)6{5YJMPl(^x!j@q1GZyHP!0(%IT~@j!)_w>H zfev8jY=rmH^>Yqi0zmG7s8hgD0-IQ35n~C2wIq0esWh`Bg@czwMGN!Ta&a>nThr)S zUWJaO%TZTTr{Y24RE``5PEbH7m8@t=!-d02y>GUYl8WhS!6uD|WYY(B|5edTF1jp@ zY|ntLHnv|)0-wmRB}+CXOzIP*s|CfM&gBz_{2^a z)0CG3+kLz*xd{H^GY_G2%^JM#RjW`Pn?nC^7JvDfM_?MnQ6y58c>Qf3#`|x(8Kb=; zIDPhz?&k~7@5kyjtI*QcB!0p@_uPl`edD-b;~Kp6EpNmVk3NaJzVH>q;}J~E%z*L_ zY$fxV68R%y!qL+>=JClpZ$VXT#=J6UtQ9lmSMD)B`Vak|`*CKNd<<9kbl!>4;l(s` zVskkmSG;s*N&SQiXwf*0Bg>axu?vR}?!(~l0G@j8IYh47v#S^+ndwgV);GKs>o30= zAN}CRQJu7dpFuO80vc*-@MnMi=Qwue94^^%kpe0!SS@;ungQ8D0dIcm9k^se8_tRC zIfbJ~4oKrVFn( zvL=nOfhk>SI^~2H6RPg#GPCOUvJbCbmxwPx(wKxY(*|I5!TZoZ(1+>iIWz1iW$$)? zkB*Kih*rdtc*k4bfMk;78TY_YUmD8Vjg)7>A}D=@Q7Wwg@54zRRbQ4sh&k-NQUw}6 zU|G4J>phMA$9vIxx)15f3M^gLg_9@F=$c8mA#8p1o-5GaTCc$H>)$?x=9U(0yLf}p zlQ1flqPPb)2)*aU6gRRANre16H?&o0am-U0&iNS(DAUt3LO2Hd`mk%)Wk^?;p^5-7 z&wuQZl!HJisJMHh1#=@{hQO_!eFXU7kA8;1;W6Cy2e)d1fQb{)o)Az3Uz6o4xU$^O zP$*c+BjbOgx?TD@BZFT)?XFecD&=pa`8`hKKl zX0Wlrm(hRn$Afjt5bqzxU|Sm=zGxe=3v(zeMASN&nVmyl-++*T;o(7_S=VYXUQMb} zHrbusts=S-dJV>Kq0O@RIod&Ca$!pBe9Gh0=`-l=T7sKyxdA`D=cj0>sYhgL3av8> zXh|kei6~OB7@E@6NOQ!OV|ekT?y(L`jl$ALzzN5^5Bwp%kE=j(Jy_4y&=83jsp_^p z7@TFjcJQcCUaOK`_C+jY!uO#@4_Rah;B^~mX)Kry0r7~Ej)I{0GJ3(+(b}~wVhEag z$<}+ee+zDlE|8{=Wp0qx?l6SPgrV)(2ubiUO!6kG8VlIGtrc~(2`pdIf;MpzYz&a= zMeRkk1!8)CCZKF5$gfB3Kl8g`+d;(67|FM$pTJZr@M|pbvAu3?;C6xfca22`Vq|D> zl-n*=Wm{1hrcvbap+hdO#8L{EN-j(QOX`r0JjyJ~lM|Cfk86s{_)gaDmHv*Sn8{={ zKKeKJpnd&%tZK~Sy33Ygc(jPW{_Jlt%Qkr`t-ZD7irx6{fAI;7Pvmg=$O$au$8f%X z2>0CcYs8Z=y!kD!LR(84<`<^%(#r>N{f*b-*nwmC$``+e{=r_Ps>(L)e7=ka{L(p* zuE5pTTxp3Kr^@KvL$rzrS`kRbbNJrfzrxhiv^i@Aivq0=7uIv?fT6B7Nfb~j6L}fgN5B$j;Sb5P!n4ig@wx&}3Vq<}dny3or z;L+3Av|%-}yvdq(H+^bG&cU$}y!T!2L03zyD$w)2=iIQRychzc6k?JVfHHpt8*9tru-Y z*V3i<(p_ItwMNpVyeN_hwJwH6$1E|>46i|FTqKt5hAPtzcAF?5*)O9$y)o&TY0ev5 zCY^Hjev>$P@-!wXFFl_V1aC!*^+A~caXvd0P2lZsdn2kVsVWynzRKflW^Zcup%e&$ zZo3B_Gj4(U@q*VJVURPL>)ngpPW}8?0-5<~JpA}mc;&=^DtUSoQ0|)KzPXucB}AJy zZNQez>$C|E96W|oXNOQ*oyJvrE;TI(%Q#AQs$qm|ajQTTPGIM|zktUnJzJ|T*y^!% z7B8C%G4u*8-Ej{9uQI}-4#Ls4@qrJZtGnAqktm{-Cs8$nM;?3tZ+gqCjl3BFMn+~Z zIyNO((M-9_k&PQ|Vr&Fo{`$A^`q#f!iDYwgqwezyFYLp?g9j93`TAzzE9dsoGZqRI zfrw7mT)PKPKm7zAd-NIo9M>g-1Oow)1m5S%w_j>)Fp3scrH!-0YFeHn6t;>>gp1c` z)x8l0RS7f6-nSo1fBg$ojE`ac?{N}-KUa9Paw%ft6F7U(ML4p4gIWl46n@E>QXOrj zsUb2oNwTU5yf8=;{tN|~(Q`fw7S9Rh@+sST0UA;p>V zSH12geE++5OF6Z+x&~=ZzYL6^t{6dmsuF417bjDwBErCAD3&VOFso|y%9ziKRg=&V zDTlgUFiFMiwL2+TYtGAv;5CC+cgfgbo`Q%3@?7!0|H&#Z0}APr8X;B{>4Nfh}<* zL6Y}O2O!Dn(w;Fz)F5^3wUo7>J#o-foyWG2?8zV1b!*fT5bw!VAJv*PtTm{Sa=(eA zz<+Zjf#?DeHcdBZO}I&*PheQf$y!SPaMxoPK`nM{U5)E5NTP2zg1`RU1DMWc)Z(qI zszgn51K#$B??58fiLMrs&JDSH?9nH1=ZYar5Sj(T+z;(i@o?W}HL<5DFD7xj=1Kh*>pna#0;YauUYSBn32MbK> z%2YywimCAsN+ZC&!EJS0i4%}n7L)=8D${6cX~jMF{s@uluGv$xi~>kR;<(}JYjMTR zH)41qhw0HtoIQUQ=gtmdVsz37Pg^&jwWCeyg{g{!W??Da$`3W4&x-B*vwMCBsx$VU zJ>w9M`I~d2FcVcr!-FCY&v7tYOnd zFnH7S5jb_hplTJF0)mJ;hL~ssGRmHPg_yt0VwnIC673(L3!-r@xKOz%0>hobopA7_ zl<3XQV9S=xdT(A+$n3%bR}$sHCy?U|BDH{^35=*IQ<^NY%LFqEb{9QD&b+^|Xc6~4 z@Gvsj0>(zi(AM6j_Z%6u)(fwbE{)e;y9-4s`V9nj& zmT-`5H6tP;yarZvsNijGy*#2B)HuUo6eT!4igt9(oMN zj-SVEfAD7H^BE6p<}zqWX=rN{@$|FLWB=h}*s%5jj8BeXWMl%j-+mh|zIgK@eGQ6i ztCaaw6&!PCr_Wo!2_@0 zmE*@8_Owbcw6N3$DHgG!X9cdhY8SrxwXc~|;CunKHFesTOeR_Ja2ketl}YHUZ@C$< zL`q^;Y#(rK(Wr;0pT@tErWhIm1uLh3QZTWtd+;}CWRRK~$J#|BkpCH`Fj3urqk~yO zXgKrE+c3RyHKt}Kg(PqqfyTyq)YLTixNH%J4Uw zBQZXS)>sM^u_$UtYD}h3LqVuGNsb963n7WMgWbFmxV23&)mAOZURFSq_oe9<1QkU~ zdqdwpjFf6R$GHfletM|l4Z!kPWMndlE3xtwVKR>_r$uDj7eQ8q0+T0;4<&s7^Odv% z+dvE>GrQ=Ms&Sw2DiIx(Ae4P5bd8?O5EUR#f=aMUx@)k0QyXe)^H{aA2lY+$5>(?T zq}>ohxq|v`5Ir*KeI^0!dEmM&x<@nvBwQqNeLs5uU%cy!xbVUambAGVtzulBZT^gqoSl1iD?ao4v)PO#pNx6M z1^nO}-^IE90TcalG$*(oTU@gBRB{(Bwbj_3G2Tl^tZeL^sCY)4l!`y-;85F9AlDjlN(S3@=zFi;lr`Yk`8kjT)pQi?A?C=eSN)d z0i6)c)7sLA?(U^pL^oc4BaWXufv28)44?kTe~>cZcfR#)B{AvhG-jt}N`0`w;UQJR ztbRgIn%72%huIt#I|Hz_6@slY^$`e585|j0DrIWKYvshk$cRXSgwsh9EA_zLf1LC9 zfh@Cb)k-AeF|1y*44rLl?jukhR|>={jj{zVf&gQ>7rGIq7DOIxZEZz;L%q$gmkwAP zGve11Pd<&YsSJA0_k)@dsmde<`$v@2O-znSZ0VL8u0d^8QU~D^PwvHBmK91K%`NrV zdHDq;w>0$>U4$m+m<#R{3DxddAWupI-}}G84w`VU&;n^q*!A&u!XgjwX*j4tAPxwF zRdzv=xD563wZ3%MH__46jjMKVH^U>LF1C64`+D)zvo9eTNg`7yV0dH{`CJ~WRl5C@~SJbW5+fdH}nYzwwMkadjV z^LXv+UL#xJ#)ewFw09p)oH&cYp#hO#RgJk5r#UQEsMnrIMe)n~@59*WtorBX`(X(X zzsS|$lm_n?@BJHI|2mVy7ShM;KX{OsUjq*bP82DjQyB-8*jV`-AlXi^Pm4h1wmbHJ$77v3Ffjh5`CJQo+)Y0(?-mDtwN= zxKPxzloAJ5kkvX=tIv{Jd9BDYo%{tNNq%5Di`>vK_f8=0?(U326#T#rz70Y2NJ@Te zK{$NQ`FE@Ii(qFtD|blS`<5j8{t_uUkPj`H)_!m#OEH}~T0wIqYEzNs`CxjCd@eBOEF@=1L3Q$NR&mFtwa<>m@Fb>bE6J08ZI{1Tdu z0^a_Pci`q%U5i+R2@~Jn1<_oQI1nS%?ga3wpFV)U{nV$hVbfaO2Nry6*YF+*m3Lyl zEU=SlDPKw=T8g|tp(2TAe)A+UnF;N8#veT^kEsDk5XpFv!>XY+UNrfrxwZW4Jq=-^ zpi@%DY)`-N6p4#h=(07+lDA&c<_kCDbl+J#{^&E(|FWvl9zz^a?B2N*vzaV9+M7|8 zwkZLrEM{}~*{>dv7B%01(!sodN{R@PcrkBTn(U{2EYD@IIsNm)NkQ!;L#6h?0X*+4`xM>oR37pmz1>00a9|%Z$K5`H{F58Ao)p)IRvo1L!+H zhAXeyCGu8NLmhte$U`{aJB-PRaWhF`yTLc^x^-)@bLV!v^un_^c<>d>=OdV$n38}M zD=TL7nnOnsr%#_Q5w==e+i~sHR~g}s_ut2n4Fb3Jf;}T6>si1t@}l)!jEs$GDyp-q4L4kS6^n{gw03{)f_uc8LGe* z9D!M)ZsPw)jn2p80>?&&sVC~9%Udtqs&~_cusq&%7J^@l!}}s8NT->< z%^(#-_i&H^6Aw5_Z>#lCZd)j%i%(HTJM4RwYzN+f)IA+i4z}siYY}q5_Gk{#1Si7m zdpz`*oaCs{P$*z}K7%dmo3UY44LX-JpuMXBb@eS;OS5xXwR!m=7&ld5`6%YRjFEiW zONWt9Avs@)i6Y}*m{8!_kl-6wV@mCXSa=~+I=(^TQkqo2)^4X zOQ*xR2Z1Q5={&XbT!m0dr`A5?dup^hBzeJh9dY!I#PF%Rev5oOg{?a-#qq-@@CtQG z^nA=!lR7Jf$O1m}kq=_$?wzQrsP;tDHFp95&)ZIXa23fE?!Wg}_~a))g(b^7kjt|b zo|K|7Te9T%$iF8yFEo>iyKMagAw#0W`9cI^W1~Vdc>UrVx!k@H>-`!-G3NJ_W5VKe zxhGRla}AR{fmdTvE-~yq^fDsXUcIMiP@DBZ2#uuD32a!q8oz$<2@DSoJM?9tf_$Iq zstVk2!_}A=9mV!bHX$Ch9vyGq<4?bUAOHMGEqe9+#8M|&#(qYlbt3ti;D%sQX(h0d zr6&OmIii@Dm_~merDW?dJ4f*%3+B8Ttxfg#AAj@L7#<$Sz4zWHXT06Jb|ac7V0Lm2 zEiH`-R5Ntfi^Oo|%qc@CJgC|x3%R|EamdElX7FipC8CZ5fY?J0iGfcUxc2vKW)|mr z`!G2^fm-U)JA7ACiO4V@jE#-qYmYyRM?d_2 zBohoa=CJwFt0%CUE91<$Guq4yM%1jJ)it>zjMUan3gDi5?!zZO@zdrTFM~2;Wna8- z9!CxzK)qhDBsmnu@Z~Z4h|ZIqK`39y;cH*}8lurO?z;O9t*_SBHazj*|}LkpG0@EnT+I|nb0jREr^_?co_&_$Bv!2W&gFN zms$V-AOJ~3K~#R1Cz(7s?}^$N4mt3=A4^Wn*FgU#Rkk|1Mn*CCz3-xDWgc6dEc5>? zN#OTik8D7l!Zdf^gYct|qNTMRzxWHE!P3H#kSJb1$Ef-KU0vNukQWvf(b?I7kNxzc z`0}6r8LFJzsMCxrf**UwkKy?7S5U~8Fgh}#m_c+!GSAX2Izov&bHC@N%uNkKFiLOK#dO4AVJC(-wT zR@q4NvdEIcE^_m6F_(wfs23i|AR-&N9-R`q0em9nARlAXB`LpCan5wB!i_1`AoI&7B&N||$t&MiEd@6=r->&jlTwUMlT;LZ zE2A0;AyX)zwF!9peOu7c5yQYh3wnCG5Q#GuT6HTYPsdLXY9f9Q<-%Fi`5w3-Ypldg zFfZy55a-X}916{u(3~c0V!^mcuK#KYISUU-WLx5(mZowBlde|f-*D~Zvr+Tbji;LS zg^j-2B!x$ZrG{H6iHz=@B~8lTT1}B?65n}k7Oz|`U^$b=%Wecwq~Ird=_2+ zkLMzd#J5aMB39nXz6R={D=1H9VjB9b!-Dr0n z5>QZALCIDf=Z4QA@X&+SZZLUNW1{kh=-xNb--~Cy|FWv+R5IRp6ZY=YO$oF$#|4A7 zwWjo;a`_Spr3!|xOkz2+q6grGYxtl@sIn@&V@u!?-l!~;UQi_S_q?8apL3|yz<65 z{LIHcAk{;DJ^%c1TppRg?w#9lrslwwy zP9hQC`|RmcICN;A#*`HMLt$LLI&K@)$?`I>q#+cAyY}wghkg6@Du6XNx8j@M`Zg|K zvNgy}r_9~S&JylswXGIFwTiK^ajkP|N*p?L2-DM35#OBSL8v$EM zqfgk@jrggO^3TRg;kuve9J!8d&pnF`nK^7p|9?pj>}T>7;QSI$O{K8-=tmK{^B(-_ zul~k5^Cwfc|wm{{41E67{@*L+=b!G!@4gIJ$ye-oji|I zC*QQg-i-rJ-JH_vP%8b0GJ!auYFY>fLuii0(G;c#PE0xrBA}Af@9nO^#x@b9s=bk9xHaKy zq)j-9Tm+|DNR>ho=$!bQjGv_QVF8Kji6UuLq7cpu$|z@Rd%{0w<*0IgbYwl(I^a+9 zK=;H+R_sg%iadCjASiJFXj9D?$zyA^QbvwwN4<=9-ZqHco0I72O=9DQKE#qKt8&4% zEZeOne5BT*3O%d-rEF;W%MHyIR>I^ZFi~K_V9&-+LosQmCy8lUSS!GiD{DVkOtEBP zO`waPhhjra97X7W_~R$FDrKNjN;nYnqTK_ zp;+#;Up!K+0!91-}$ zPx=NtKx}cc>gU4}gxp|JT2@7f|IFF5a+I_lyY<#MUg#Hqp$TqtxC6-R3Gl)hU}Lc` zy1RRD`pj9BiUrX4>BArVAS%@ozW()ZA`&t<|KNcGvftd$+biN^A4F+O<6pos(;$*P1s@JL-E!a>{R=_l;VgTp8;`c~G(xP+Y zW)ew?$8mFZMjL|=Q!<^B=Kn2w_ldl?bJrI1_x7PA<0Knr6hl}GiXtL*oxTs>-~({7 z!}2T>bfWSjvwAUy13Dnbrk60kFps8G63Jv-2~UCc)cL%~US9ERaIjzSZ#K(KXDVot zr>+Ok+uNojL7ME|0LmTCUZljXV{Jp5X1HzEMm6gKpjLrnh5Po4|C#lbl1;l9G`s%G zkD*Du&ha$(voF7V5*IFw;L#7hTm8w4!!)$c!9CcwYllm6yp67HLVia723n(m z2<|)jkiN%Cm;^v>z|(KOiO$Ye3=Nt@H=j4#4VG$H)y9_5+`>Hm+kgEW-ucdVpl@TJ z?ibhH6W@Lc7ltouY|O}BCd19PBegl0vGa?qs?%?tR$r29iLDSSl#Y*2qFBl|5+d%^ zJ8r*2XoEjMJbGY(+qfQT{YakHSJ;kl=la9V*REp6cb`Jn>N2+fPl$^@oI+fUv|_3h zLbzDO`TynT@cFNO!|kK8l4mB$hIR$e+S1bS+~9uNG|-24zw_;=RDx)2ZN?YB_$9P< zbYRm!2X<`Rjw@G2mE<$2TUuPi)Z_$udN-h_XM>W3(a{?X0j;j?9wd@cjE#;dabN;w z>am8b_)3ndlA+Z+dTSB%u?-psBT1q*$IOBuv_@(79#$binUsjy4|cz_K3z-4CtOzT zT8lsjfSvFS1Wc%a`zP`X_6c$)44<=EXAoxB7%Wo0IM^0jfXKuH?g4$drzhYkzGVu{lnL32q}95G3A z<2w1zwr--tS(01AV3jRLGJT>ZGNhN%mNO-j4ntTit{5p+yb+g33u^ZXAhjzrzR$H1 zL%tlxA3dAJXs!dn=1oAl2Nk4{pSpmVm;Vd;dRsAa{e~tb#BC!|qPQ5q2S5BCJn+c< z7}&U7_sH6#R$Ns~IZIwS{B)ERKXu|fe*d?A7c14QbHTOP$eXCvhjR-hWvh^B2$92&5k= zBT2^x7@I|B7940u7aN(*PA3o5co@U8UNs#M3}a&UrpQeG%R@arh#67juX|tne`Eic zhu)U0{doPg)97exmj=T5bLSN_xhQYhXZ`YR+qcPWi-$Ky6IU}CO=b8VjU`^r2#I#1 zvI4bW!q4F!44Jc(3Fbp)#my>+i--q?M+!2zWlT=Ypj0Sm;}Rwosj-l^esClzXTi4C zX8eoK{0u(#xj)C*OT!4!lqL~JI2I9?qq8NA)|MtID;8yfWd09=ywtGdf1BWmp%O;u zlxkR|s&O-Ut2?=25_|Z0hlj7>)l(OdUCAR9392>3go%oMxoj4(gdswfBm~ge)`37U zVhh=`WW_A5VbjJ=y!Da08)U^FTpMfsZa?L~`(c~}%d$lPTjx~RNFMyNcOy^YCQF~* zxG_J7AXtUqduF~Dt3ct@6kmAhHH?kT-~&JLHe|9Z_@h7mQ*7P56OTM{RM56>19>Qz z@8iX=goFgx-&?|4-}YVwekR3Cy!gIXu3SMbvy9tsXKRQ?TTu)Tk7+bmOk_gD*vHV+ltem}(r175wG%jX>I}lsAW8+tM=04iV<>7i$EXJWkGGACV9V3r z#irGH45ofK9sA+5;IIGvM5qHR;W+Z)2!5sN)c67%(Ok9yL(?dAX^appF~J%e;pFq( zvu_9Px$902OyJVxE65k~LbvED+11u5r&P8&Igv9lIf3`R@5k}_YsbZxA(@(=V{v{# z?LHEN2L=Wl%uRcAV}ToilLv|Quqo3V%N4L85JFEVfh5Iim;e)92!+tX$&g?eNs_~u z{5O0A)~1KV_fRbN)xS65vcuZ{k3S)+W|OmVPLU2BbY2g&#(1L1EtA|Wqo+VnDyx=Y zSi)lHoM|dpJHvT6c+n;&8P5d6zn_s3D<}yu;K*fFNdl`~SbcDFV~khZ;Iemy>38KTIiVLSzs&{j*p@g}%W{rcytG4At#4}=n! zT2A2dTsyAMhjD2>g6ZV~s+A%F^;OhY=g^+4V`EDcS1z1Dc6m-t!1}zrc=rq#_YNG` zg-71;2=2T00hE{=an#fq`&lc2g z(HewNDQ1+IXiA9^)@;Si&MF47_@%%a_Z!LdnjBnLxG4c}lG9qBu2^Gy7HL1WrZB2l zT;XW2wRtWKpQf17y?P2p7BOhYElum^SOm9zYMIJ`w(%@ev*2#t?AFT_o0M=+rHr#@ z&oz{{ydJw%%1&m}Rp*|h=dVMrDQnKK0?f)vM%A5UHyuNs%5k?Jxm^xhn>G(hWTsLw z!Jdin8xr)e_u(j8(dqG9K$jb3*-Wk2&(Ykn^COq$L)Ewv)*_*46?MVc5&*7^TvuCy z4}!fVE<{4aQb}~A6aMa=-MjFi_aD__dit3YxG;PjvkMDy7He;B!R~ECSXo)bop;>4igB=)5Co@-&^Sic z@d^BdgAf2$nOQPmUk&n=OC*$j`g!(7&!O?F4fH_Q*l^&hwN=1<8CQp>n@bI-GyEv1N+?a9;jT_rx6bpoqE|t++ z3!#Gvl#>o8DZ4WnM>-NmJQzfRqmwR)wBTwZoBGmxzVQW=bUKqIUvSyfSIt@rBr9?r zU&xb*Bk{1Pxlv5E7CiD$qLG}Rc;L@b#4Wt$KVa|2;@3QMlmI)fgOMNkoXk&f zxF=ZM@p~*r7?MQ9nR|wB6;H->fbx0p8R_2}Qye~CuW7^>7s`-Stz9?zNCcxH79@WP z|43|adoLlyOXpu;ZBaY3bcThJ_`_!tcq6w9!AKgD!_Oj>zk&8t4b}WI3dNj^*qWLW z=;|hlSjXv8ConTTZQ3J|h-{-(z%jw>Oyj_9y-DL z7-2)FYlWOgc?{ujcIobHByWgFwvX*XcN}tb@$y*&?!E6W`iZD|mS%U^CJp#P-jR^m zAQuvQ;S6XSXl4$-tOQ{ zgZuRS98pULJ*y8^S00vi8LY?zDPwDZ?sMaRIiY{0$FT195v3rilHP>qMs zM4SrX`4?WnFxw3ueINe&=l=w~8wc=X58vzHeHTESq8mx3BpE*T&8LxSwi)Ktd~Mwyu%Br=NNXAN}b2EpZ42adCJ=hAI-#5y7;I?|kRGIDY(f+;iuh zl60mu^`XOuRn`6H-}`Uo3Q9ZlFzwBa*hiiU?;We_`T03rubGya^B~`gZ3S{x^Q4l2wYzGo@m*ej6L2HEe}V zZv0KZmP^2eLR5Y9&!=1QW|+)u`gRy;%p-Z^{`B?s>Du&s10h-H&P-3Cw|@h^|IBeE z#Y~oL9L=gn?sv8zZoBgcUU=a}^!04O)YOd7qB)|JF5Bd1WNVXqH%1pdSC#U8+5X_? z=cE$XE?boRVzLyfRFN)L(N(U4DGn2ZNHB=ja15zv6v+^$B9bCF@+h{TyPi8^(*EEGhRyntv}<%el>_pJ~dq~D6dM5ItWWw1(VB6PmHXMv@*Jp8r*L7h$f!{rI z3yR4;w4{?5d-6B2XCp@_Ynmz`vPCQBNHng!OnU+D&u>5exEx(&=;jRB)N+mnaqQ^b zc=VH>l)9+3z8nFa%Cq{MtiOn|g|RTVg5UTLzk_;^PslhVYq~s+%TTQ#*3^wu{~ai0 z=CLyQ25RM;)-Z^T@=hUrV z{{Gnurx3WGBaj@iVRl!pm|iv?mYcIz(2_K#O+IjuG!~T$+V=1)J26DlP8%W$!N)3DyPqM?xU}tTtVnNjo z?+LvrxTzR`s13o*ONYaj<`ylAWB2aI#=Z_^u%}O4!u)apV-pjqm?{;j1m48XZCkKq z`+zN~va`TePs)OaDrTn&DKjE&pE~f=v#%lGI0*i}iBI78C1xdRvcaWN!SOMy^0fpl zjO+?Yj3gBC=WL`)CO!_@9P01JgAW|BEMCSeE(`Sp!v@pZk_YRF8KKMfr2XHuB0K}j zvI|#zt-)WeK(ip*K)~(${(HV9;#&r+BF>*bi|1cBfp@?2ZTQnae+=(=&yS(EtHYA3 zY7N&$M)2C}r;y7QRedq}B>cy9%QdZjaIK0@KKe22Ke$KCbyiNiugfdTc=CyF;?YNc zLhFbJ&c)$tC^@a(h4fx7iDRhiZe zC17xCPPbxqZbsuwd|vF^`*wkxL79xJ4QR!s^^e#DNboD0sL;6{6Q z!uqP5!-RRM(+L@IPG0eZ@~b_D;8UuMwc49PhC;My3n1Lrs+Nsf%W!4Pt#vJe6h z6gBEt)%W2h2&$4NuA@ZDXRa+jS*6WMq|&PIyLPnWfdgIW>1sk(M+(i&X(W;nL=(;C zcfn~P=RskIjLBYWiwhxfN`4agVG?1Z?(}kC!phrbdNRg;(nN{9kV#?(jpV2)21i^p zUI$wd6@>QwYM~-jU(sG*o45l_3KA(O(VkM3h%pb6>E(<8EX+2j~zQ&XB8Wb zg-xs6LBGrvy+*cIrSj@tN(7v0)>?G&nVu;t`l!x_eeT>jJ3Ji1uznOn8IbGk_$0yy zV}9slJSA8~v$>@*28K4Hqpc15ZrO*G4}Y7U zutj4cO6iPrS@wcz0g?$+;(-I&Jc=q#>}jG}*_7pMj?K79int?jt;p2IF7320$5A@frPfl}Wjj@41CltuVsBEz*P6CVK0>9lNS)9GgM8T4F2BrV#rm1VaR zTVe9FA(z8@PrQzBM-%R-m`wTK_Uo19ATA+{Y#@OD=qC(Z;O7G4FG(e4_OJ_ zapxhteEbb$Gb?!4yWWAB**Tm)e?k3X21$;9_VjJQv19k+>8GBSSXrr5kvZGVn^Q<7 zl32;EVE3LK=B%y`eqI_8pTb-qQw*%T{7Mjzl~zvKJ3ajwSOr zIu!I;6<*0xu2bUGr0@tx$bN!0`SvW?G{ z%hp!l0q(U7XzsL1trWEgfC7^TC)up=N!Q9K6S8KK&iCV#jFaA_4KLKfRON4pdM6*PUCIUzvldCv6Y2aft<8NCM_|W}3(AyP4x+#vf<``O9+7VB- z$oNmOM1_SB;<(n#qS;!NB09TvuQV0h0VcOvr?9Em=FS9iwye$UkN_nCYjX9z-D;|f z!WJ7`2NiP8i^ay=4N;KNt|M?tM%}tZs0X6>#V;&iKDrsr8*fD|(kx`IaN>{9*RqUi z)yRR23B}^7k`)%8UEST1v48EAS9DN&gj~p9wS=8}w&5TB{HF~Ou8@CV4w@Pvb!0>p zXaV5H$T+_E`9DH1%1IuJq5K{bT2}M%1Sdi&2&Hk9_d0s1%DblzQ{T2*xKS5lMuRjK+~!wKmC}_uekE z9$ti6JH@gwlVv4LF&47EqFNlQgc#VXRhR!zUuh8%w3hRAX@98d$lu{5qU~m3&fBaRfEN8K4U=Z(l`%yghjmI%N zpU1JIcVWk_9fBn}QydD|WW?i-KZU+cgPL9ta8V85f%_l8d*1gBC+@<^o14FaGjE>4 zJ$K#edU-Wmy*7?~!Oy<4`l{kDzW$fEaPEp!7U=@Xd(hX{gQbEPMz@PojThZB6!11#y_&2}z90mvWU~DGikQVWk8zdzD z{_^s&T7+yVSwdsiZ<9$T1SW5Va0q>c5L`}x<`Is?aQ_4M3kjGQnG`h7Nu@oz zx8wNnmt=~?gKh7g9XNMxSR=SpokA4!_m5dTS#xnj- zMFQ7wy^hX~4z)BQLAGK{j4U1w;?U0B$XpshU~vU)!6?$+cdPBrhGS`VYg-Zrw z?lD$seqAcENFLoxoyZH2qbv8L4i8Q?SgWBVgPl57`7>${7#p660?%9%Ju)T&iG2B5 zS%kw{iAV&mBZAq&s`ePsiXszXB3?;Oav3_nwaCdP9v()JG;Wth5 ze#e~y*t0Q?=B5~$=?{`f;Lf+cAM-coQD3>F_{eJ@a;um?!kd$2S8c5d->l0Sv#Gqu z#GCKG9{p6C#<^{3+*}BOyS~PCQ4_-Wa1>8dtRbxKkk6__>D>691r5b^UX!(mNCdQV zCtr!-pZswaD}gS=Tl&$`yHm!5+nUOle&Y*hiQ9-HpCgfM66Lv{Ncw)@{=4v>KKuJh z-*`xSWR}Rmt%ncdLm&BRB?;urlqx0N1OAMZHifcS%j?XU3wZqNk7@5yf5I1gJX@Fy zr_-EP2q6&fM$5kUBD*pVMzAf+4}_zE|k` zg@T~@A#}jnc$tY0(H+d7O$I?_tKl%toWFz$6&0O6#j^c+rIpb8%o0Nb3t zZL|J<`p@T+34V6n(?AHzG%5-ZCXBk#D(e?(Jp_Xo+Sr4K9=ffuAogR2=(5eQvRX!e zZx=rFLl5%Q}IlX3EYa7ZG^{E3J2R30~V?T2FRZLG#X$pcm7G|Pl z5S5Z|j!Q+7i^ZH_aEnuROBq z`9YpX!}nq$Uf_sytt>@F3Mx@fI$td*Dae&RxKytM16B{fm2$p*Dn5=W&Kq2RqHxpuDSmG z8-;}gpE%06CJ@$`Y?7;|#Xs#~@<6=E8(Xn5aWa1gd2Oi0VXbGPb9UwgPzm?o6aQ@q z#b5%FrZ%+n>_k1%Oi5sbMxR70MjGvQCKtR;tMDmG*NN{x|B_S^J-koYp2+plqxa$H zvA3AbyGE&3mE19=+uE-oz&X_@@a$9H#o4pxCG4hs%ICP85wC@)1Pk3%Dvd--FM^xj zg?zDu%IX|K*-6xMlbE{kCbn+hgWK=ekF5hen46r#H=lSCO-(Tj3~oTNT*L9>=aj6{ zJ=RNWtEHrvWx_9hy&4$ha{w(pX-|;mn2ejq#NAtp`8eNlC7I+sdv_t9&oa%Gm`E^U{awpANg7Kl7*kJQNrxmhYa&2Z zD|KXZ87#~%V|;vENk>ado8Vl+qZC}So+(bo$gM=ij8j8pwv>K{)gE~WOptGkUbE_s`&TVBQ;Fm?w^z#e*CQi1(bIvSudIzK z|6Q_$>lxssauC$2{N+U2&8HiD%yxr67>EYaK!)VS&W=vJ^wLXuTV5A!%lR-kS{$aE zWhjWw_704U+Eh_1r$&gj6uEBA+)7ghavLP?ql%6F8`0g~iRElYs;zUgv*wTBMssyQ zI-wgOWQ4~f6o_Nroo;;e&8W&eD_n=ht0PMlvjn1x|FR zj%p}?ntTat-Ag(bmH z-HXPac5y{TgDWiboYYn@*qpIIVhhCkVaRRMdvY|26r1ikMRVn@+7_6> z=1d+KY&>h*w-0=hLdc$?HruyvLzJ7fk~Ow-z}Wo!{Y-``Ro3@puapaeukGC)3CVLx zVqtL!*RNeuu;tI?3VAFqE()^e=i+!3?^&4gz4bbF?A$5aQTC!amZiih7{!+}Fa3?C|5=JM6(b|&6&RqkJpkvvx+A(#@_ z!IGu6>*FyAT3*TG%U}K)ZoTzZZ0K&q;834CY`r&#-AnZ-HI-n!eCd4XJxFd%;LiIW zB2I*2uI$9GfGd};;PxYXu*#`~8ZD&DxN>cxVXniq_3Sgx;)NGqQPuG9Ll0;_&~cN= zB*z;sT^-Y*H#<9{xnx#cy^NomlO|#k%&ey*xZ59k!z?ftsqGevq}|B5@<5?!4vox zE6F`5Ik6zN7-v5bvZjyT*zyy@Nlz{Q4zMC18;~)o7$R;74(3C5(HJ~8ZUIyc1)^@PRNV*#>v}D zIL-N(FtPmdwqBhBiyIb5G^4YBF9NY9)GBrK*DfGG`Ya+*CL9!FG9Co)FNL7q zJarnSVpir(w(kh-7jWdzK|J)x+p(Nsd(2v-oWNtzNsXE!$0Cbm6ml84)^fd4M2*B= zI`WDTssfOsl@+8CDQww&5G(C(L$Mx4el?50>Kv-8lZcdNFxVBA({dsi#)m)rUc^Eb zp=kn~ILf_Rz+;a;gW+q_nlkaKwtTv|tc}5YPK|LU)=*&~c+sc~?gGb--X~@lGxxF- zv1}aDxCTaWQKj$Hvv{-ES7qhHDx8%!4{P?}J(9r9!XB8H@Ki5c=t3Q5&z)W8R_K|P z#_IGf2wtpjGx(N+$diR4y1IIFjbf!cf{YegEUrn19lN$Gv-2bsjV9*v)~6-tA0b3b z;i5IaZH6vS+~5p0`^3Y;m(bbKj@Fh|UCZ`eyK!@BTquAv69NIGn$ot(>NV`xxdRc` zA7fP_X<7!yUU zsfVlAC#5-%YHr1+{O@0Ti)`Zl8>&=cCC-ei3yy&a1GUZMO+q{j}^<9nVHrYq)C5UJB<(}*DIfY zsYt()3O0Au@lSthBQ_7U<1?R~!1zL$J+8*#Xcd}yIB@gRx;)+1qL#;OUXT4qctrAs1|9-xfO2Fj|FoOX8EE>b{Fh@xZ>EiW~0LFDg z60#wN72I~)LF_+pE1rJl8BC2&H{wGfUzBz9!6SR|O<0(pMf^ zX>q&MQhIv1cPy;qeTR+{RN`cB^5$6 zXUlWyC>X%>^bFqr6Ys?5|L~98#E2Cg;bc=rl?%wO z7OAKH#bjvdyy=lv)s-ZpphCjR0tzlUq17&&8@#S11RLZOLjkv}GV zBGWhFJ{!Iy#l`#UCVpayY`kD*=B5*1q9p#HVp1U1_d0huX271{$Z)TUp=z4u$z)8U zf$I^6(XmOXviWLvJ@HN(#B8X321wMdZ`e#3bYN?=1@rCa%VQTU^mR82GW7`p29X*bf%mTJ= z+lr13CNjo%FfNI~@TyQ80g12smA`xftNAKg+u9_mA?Nur#>p~fLZ}gZBGeiSP~1hUtWpMDwT%ct>$pZpg7?XTaCCw}AAzn=`jy~=nFI8zSF zE8&+CO<1Vgp~vKie{ydbm&W?_^l9ks>B56=Ii^_h>~k+7pUH_}nMx<|wzoclFMs)~ zT5HmoDCD*0{Xxk+W&&6gjtXMy)~#C4w4tW;bTMC$^Xz)glSdAC$r6)siH1KId7!Wr z*52BtgI4hJI)_;MsCIx`pTO*xBb<#RYC!%DV~!geR=bO>2esg=MWAT~89>=6q(;=- zn3@uDn?(~`tc2X@rZ7J6021HF$!~koB#XVFp?+MsI$|S-&Jk4C#^h#QOVAJu8<{g- z0ee5+Zsg}H*DGjmYR3NEn}N&(27B5NkJ-q3DiJ_iYZKxT6L#VrTV7hlh7Ij%CD6uP zudCo0z=2!uM6$V668l-g?(~tV*HFl2QJ0uc!D4a6dir)AsGp$m%Xp0UE@l%{vQ1`^ z$CI zB$_+5CI@3Tar5L?(Al2G{K70ouZ^IivlXKwV>o=re!O=4l%c2+;;Ue2Xb@Yr4#*sk zpE%>zTwy6AB09ZASU~Xk_*NmG;A+vzPdz$?fqs1I6YoX~wO1sVX486wTn;zKr|`S~_n)9rkJuEW zoFILx*n|Z6Wi4x4*M6@!PQv|${;6lj1D8x_W7Z1Bmmh&=(6j#^(S{_n&t9tfSPpcy z`F3g!@FJOwP!iYJ&EzkLSzNB-{P0Cr*{!*&S+}mZhs4M*&)!TP2yy z#lu-=&Y0(mMfCJ^qmAldl2NwaRHamK>WOY_rwZgtW&*^U5)A^q?KP|x!?-%WjPV;| zLMZzC`$YuXxqFAM%V0R`Ir3rCt!{CCQ3{OYEA;hsD{0^@h{TMPp`t?y{Rw*!L zbKV@w@d%7h@{IUNeT1^yCfnQEG@DH?2_^unrp43Hc#J`der}o2m`#2JaqGUl*uQ_1 zjW{`VInO4xWXAXS?eNv}b4q)Rf|Ba?V@$dv%MLv0)CWb68mZMlB%xYG$Hfa6c=1`Y z*kzXMkOrC8n7p{t!#Cj({_eu!vOW*td|H)T;B-|Pjcit(8lcnA@Za~cu4;L3T@xh= z8>^jPBJfhZuO)4tLH_Tixgq%6jV_V3&*YfZvLu1s8pP@0q>!17n-)oY<7rVFwyjc%o z5h46`EUDYZ@k|k!y^EA3~G{_+VdEzaY^AN~L?UAcre zUOlP!v_3)bYu>ayh?s>jFtADMfJqn~LJ8MPhSwnpUQo@q$Gne;#mBWtD@_+kjLd|! zcwo_QL;J>&Tl5+Z=_9(}W({rKajiBa#hu22$cD!F7s*ba+a?4QW7rO$fdrZ9P8yu+ zOM4ta%q=boUYCBxI>gbMesy$rb}6A585vi5!|ye({nALbUHs!m=6&()H^nS*hB!7C z!J%7k5lNFRxAJNZ{apz($JxS+AQ84gkX{6af>Mz;hEy`D)+Lb)i$o@o%@&#b9^Aq2 zIRnu|Ok5A{TgD8Hd1~aDX9xTByiZ}oVsZ^ydP(Z54P%v7|D*yt08lqQ8Bo<4aB z9i8o(atnocJx!RM9Wy>$Ab2`kwwT3VXb4z@xZh@`r)>F6(DDQlrelR4!T)bop|7U$6t&0$Y}3@<Dwa4iksoAqAeLS+}*eQ{g^4grzGJm z4;-y4i*+;ZT%;z`84|0Qzrf6jeL4xfNSf9ld%{U}lWY;t5|%24Y6qwvNwSI8C?L1N z4s7-auU@~Q-&@Z|u)}Tb%O4(|*yyJx_&eR5Ju)hqnVD7cKy|hI?zPA?#pN+6nuVtFZp=H@0NT(QOA z6yf;r=zht**lVx9-Z0}~HA|RFL>ZCtD4r8SM|(3q_Mvy`8fWHuaCIb!>zBTY4ZXJj z)kT~i{uVkqIkPbsa(Gxf4L@X?ns#wVwxstAch1I;2Ax)zn=<4aQjpeX>+gv6q zy_zdvd}171w{F&y$Kb{Rk)PNnbHJj-G*{KDx68TmGPChIe(ERQA*DHv=@8A(^JL%5 z5gWa-oWw#@svF73&>?4{WErHZ3JhNLq(z@JXllVYUg|^ke&(0;b3eEm>^1!L@;_WG zZM0kb_YHT^<=F46bCz@pu7B;{{d+b3{Gm55)u4oO{g;Jh+hUF&{?`s$Bb2RO3({@JCFSb z_Mlb?;+gM#54ns9QJMZI;rF#!b6K^=&wA4H0m~j&|llYQ9@Lki3&vB%p(mNlrA( zF*(y!SXwP9QKqbKsl>lK%W!F57-5s2NnEZvFwoyoY$D|V03ZNKL_t)qO8w^Sf}53J zQ_%Cs3qPyP_M7UVca}AWQYPPJY~Q*S8#nf1Z1e_3#>REvaBs#VK@4=aqBR{wG(<8Z zuRVyA_zCnDsG0q?Mj@>bX=zFV0eWg!T-5ndEbD))^f?+F37e%k|K~@hr9h|&6yv!m zVT)25#GH7&IaFLOl_n-NHA_OVSp`I6HU>)gJRYatM->0#=`rN60n6b&)Wb1E;%U@F zY_~>H4@Qvg9zwjeUq#-QrW{6I`W(Vo#cD2#>6s~{lW8n2&*MWs{V9C@4?mA;DI>nm zul$F9ji;Y_5hEj4l?ZXLhv<2_{v13X~G=1o} z6w7mSICq)pFqC<09aK;eWTbw#eium25$=R!2L>bz(`JK6Mf`ZUW9LJF=R5xtYYAqttA)JtHel9nwx_1BRTG2P zs_PIw`H6QUN}-TqABL|FVs!Y=RX(-04C3UQU(n&ZeS5z?UnXn8gK(sn_XuEic2?CV zjiq=$n6&ZW=Alnv7_Vc%-*0Y8>wYr}f9;Jouxpnw^IMY5K*%66Lega5`hdv$Y?C8Y zA&jA|g@l?gvMX6te~DNWt?dbH+O%0(?)SeQXliLjFwlvc6X%5_9{cf+;>?RLBOc0t#s0+Pl!_D2qu|;h|6o00?prcThv z{I8H|Zo;icw&TJ3@6mLQov#7pGpm@Moy7OP^CDh3IqarJ%oNVd3!SEgYx$e*O#tUF zylF`SYazj2%D~)2g1gZ_ObW6E#qmfIf#_*q60kxaTo0U^#fu>c$^z%pnTcA~%VdFb zzn3muYCwk`GXH@-^E&9yw;}j_Rt6>#Q5SiV@5NpwH?t?`3GyXFSw=SoaSD!fBQ55f zmDKByjq5Y2LYa2T9M`L1HIqfvjnFZhSE9j#ky5z&Urj9uBW#-C3n4m=-icsDfq$oS zkZdwVt5l*DP03zFf_cPZO$dgQ$YrO&1}6K=Vsvvhx@yv?zSVK=>{%s6v=1hFLLn#l zxz}sDelo=~D@#UzYf5SIg4yKDFTaXC`}QhxZExwoYSDy2m~ePYUnMe5+rjI)hhP%E zgr+E$%K(*GpuYeUml6WuI#TfjT3TZw&V-}nHPq47)rl=bLlQ1xdXO&{aq84r+;RA@ zC6o;-TUSoIkx3I#sv&jaO|*Xf2~9C{#+AnwmyBkwPMs((fB- z2$&d|z)Ciw7SYX{(-oFj$d8aDSdHHri#dn{b|C#ztpy(eN8a~acQ{^!tR-Aj6X6pGTx zV3Ht^$0xH7hgH!siNCKH814gnGvOBqxvc{D`|*xge@S7#Hx{q=7k-PVeCzWYAx z*|A-Tg8w2fVsc^}kNwqmF*-hv5C;mVdg<1ZC6uluOrg6vFnozg!m$VHrr+%6Y)!#T z$$=x%Sg*pS0la{SXBczASfy{mE`p`0To&iVLq>;HzGODaQT7wvxC=Am(a}+5P&O{d zxASBbx46jxAk$KE$!o0%X82w~O>_8~@io}e_n^(`%Mbzf$&3tW5V(h7`Ox{^%6N62 zi+PAxD5AEBEPI=qk)Sm#Qz_|!o1Zy94-aRKM^cZRpHo~4_7>}O!($7iY^E>OIcvaLwP-~zhbl~8@188YZ2}b1x=O&$*o3({3(4P|3asAzkRWT@u%u=ZeX&}t# z`{5LR;xoT=>8em6lHvyY2Nh)GFebTB8xL$GPrTnzwwTPpju|F5dnl5|Pkrde5DNv6 zNVH&ld;<XAnUI7cNr!AuFrpY<6CZXDWVi0mhg>#-iA}_a5xq-7oD8A`qK~He+gX zQj3!eaynGzvswMU>yN&O)cK28{h5#8{y+cX-|}eshhO_qxdX)-aA6Uc2nBI6k;dcA zZN^nu*CLaAF!v_)A=nm(7#Bnky7o^+%8GO|CGl$i!F@P<>#dlan#Rdfr!hA(tA0IE zt<_v!ZiDOvXI5zDRYF@^y9m_YEY6^5ll3-Yuxp=+gAx=n$3)vIZYHlH&pTd#wTZZ= z^yP%bsCLMBvYzy1D4PEfY67;H}nowavhEU*KG@uu!OFg3Si zN~SK+u()UNybOfub=-F3ATC_EB(z0vziUJAzlHX?L`4;=YX?vpV)w4?(w;bT?xItl zwFFKQ$ND|HMhQCUe$=peLmETfOcLyUR&{aPt=lCbhUYzu@&sc&}>`2#ch8 z@GpPuzhZnkgW-{7oWDMW#cWQks!Dkkp;Z$0YiNsPuxqFZtBW%@@#^d7>g~q+-hT{3 z{rxtLBbrMc%S#IwzcHn8@x_&*&I={6?#oaGL(zHbE)1Wt=>{=q2?aSOy=S_bAX3am zmYmKu7br6y&+7D}Db`w`-+^hD^Kj?yTN}c9);0=dBTIapQ>V{qk(12fCm@*pX|K2u zFD^bFxO^XGpM=?2z4K;!;*m!#_&NPNwjamT>s2Yq9M{71`U~ErOv#gDbSf}8q=Cr< zVI)&f^g7tq0M+ZdG%}6i<<0Rw#l*G=Wf*!W&V+n@X%|L=@s$8~5CE5c~J;P{zBolEvWW0fYk# zqyd@iEG%R&eB}zh`lZiFAHRv}gLgiFfAn)7*EnLav}$_fVy4HCZb@mZXJN_D#RK`@ z{*TB#@dS4Lm(L>c&p!2|a@PIBb^IOfztUfD!sog+;7Y1}Bj> z9lP39_ly}T5?GB=bx-8ZB5v8YONLKO1kRp0jj^#wjeyRuBICZ1!lv2qYFn~>N24WY zXqQaJ(bu!lbn=O$Q5PT?M`n3hJS^^IdPs1+DyjF1eXgBoB3uFFR_dTVJTNZsX|^G%>r3~(dUNAgN-1osA0mzKk1FaEK(>e9XOpM zp;OeAO|(qw*t%qVb>eGI;nyp@dbC6`?`|5-bYrXl(wW5H2}O|$wF5*FV!Ny;WrA7@ zAl%%6KsePnup`agXzkk}ajpc4s9*dtLWMbbIoy~SL!HH471*-vFoJ;yCU2Za4K|v| zGl;IPzSSVT3k1-_g40dXa0Jwd_;t0exXws$bSb6&V3N?(z6qcHH@}V9r6R^|=5g-Y z9BwWw>Nmjtaw>5lQc>fm{7Br>z zKfd^Nl)br@n{=^r+twr#!iyJABXI9Mchyq~+8!H`f%BZ&kj@^NABtJH-ynqgC6C;2 z4>MAgF?_9;Vs3yY!OG3U5AR8dzW2<(^L6c^n(QU3f1(c>r>hgSpawN{x~;{*#l}VF zN88B$x_dh#f)ElynS}7@6QYDPO!j^UIy<}2($Xa9-s}J57qIf&bJ+8re+$uH z{N&%^X!?g={ZYCDqgfzR3t%J=!*6aHGHYRJ2{=(JH+;u^!@z9bAI9c30$WuIlw9{R z!cw9gL^ijAT|0N;_9KVT*4~b5*RSEq)vFjAnINl3+#@6G)s%GezgflY-Me3^sAR!2 z#_&D4mpNIqvaqP%^QK!uH=OC4;*a*N{XG9iv#wNAlPYoYe1yR2WL=vjSkE8fXS{#k z0HUF_HmwC+D?&KVm(7>4T&haAiwFGbY7q;o`37%D$b&4FX-?$|oq8Qd@4Fi(&zzNR zjU`szpTQ6cAr-*@+S*&OXU`7I&&^|)QrCH+s?JJTq)12Xbfc<<9NS^X&r&Jn@zG;@ zkxEcW(w-HCyO^-m0%2rVIsF4o9FYIyN9iR8Cy$39CT6o3o>+D~Cg&mG%#O@S)?zH} zyM=(dwUD4^k1OWZuW`?t;O7+C-3dn-={JA~MXy?V5r`zQ6xwMCk&3_yVu>^Yi56)$ zh@TLOBHgoHQtk8~>J3d`?u{?W`=wee;l?DV;M`b!FoI-L64?xORIDAubIi^LYoidA zYHn%O<@z(j3S%R*GEtbBW{bz37cY&5T3vlR@w5Np-(hj7fTe65S0-0*`Nj;gxjf3X z5^5#NH7_7i%OO-PU{hNj`?h!EufFoIY_>(XF zmBvZs1fw&bXt-->1p^qqcou>8zU^K0mQ)*tc5FqqRK~fpC!~ti;0TDB%Nb;wvE_&I z#!gMLE7Yl)EbisP>xdU)L2XjfwUC}p{J;N$V1v(3I#VgeE>de^VkN4 z1~=myk9`BlCTjzjVH6=c2b(*e2ZP9LGl=vOXCgt-5fiB41LC#B6P!&oU3ea%!En$S zD4D7txdjrND3?{8b7NVxL4HF-L5iG*7&!=tAeL-JtAHHvbrh-#TV!Woo{S)fiR zvWQ}lHo$9cUnEO%fojCZ$&QN4LAOaUP_6eULXJmP(UEN9YhZ zzc4Q!bP_TtRm#5U(W4KVrF9{XRV969Bqa32jp492n`lbP=!>H`u_#s9D#)!85^X{( z5<@n-h&NBYg0|)eKK^qb$Hty6v9EKvJcch_lbFn3{Kc2BYv%!c{8K-TbZe95)wyXn zx9`^gGihq8F`H)9!D^BHv*>U9I%=0MBmJ45$Bxhb`yZuq?jNq@?{EjWSI;j2xo{ZA zQ>}Qct4GhAUt-sL>2dvoO#`Sx)L(6~hE9c4ydxXjI0P(6EU0lTnJSC>ZrP3fd-s4S z!PP5cxIS`2-YYa)VnWUJ{NS+%bkLVej3L%S^(f=~{5%$B=A>50IMmhE;d-_4Wi*j7k+)sz!$u;F&tQp92<=2ou1Yn4T(O2isjg>} z%hTt?TFOFH+<5fM=f{z&7&4>@7dOpd%gi(u#1jYwHRZy1Mwq#S6Lg9mE@^SL)5d4x zwYq6*HS0aFCzV`y!dfKsL#{k~?$URQGf&_6QR3*&KOykV!XYs@{ui3Mws8o3E+#||7 zJbVFx^KYK4cXf5++UO|GpSz6bUwi@MVLJR~;Q4mYG&c`Z;AY)R?YNva$)ed_gK!6kuWnaq9I~ zaryEUbar-Pc5Xr30X`&eWvmC_1Vi}V8~X>bY14o>7dCBRi=7*p$-?A~Q4yVVP)4Fi zH6=u3T3lJSVBmyc_^_K(ab$Az7-uVj0gCQjT=@aSBMF3J+YpW)L@BWi$>t*{jsF1> zk+Ue2=2S_0M8peOC^MHYdBVI4=>JZ2u@J{#3KD8!(!hh1_u8Hb?~#!TckkJ&)`C1N zC`Gcmipy88Aem~y?A)A#W^35CWeaxf*ln(ZxmDcp<5hzaMtC$=>$q;X8 z>99<@TEY0(3R>DXpj0ShVQvzGg9!z&TxJEGU47`?Fo>1x0$zOXNdM#8rj-`M2)gQGx zkSPQ7cgO|9`0C≧gl2IhC=+naSDMpjp<-!k$UET3Xb{cZ4;kLE&3_*6O4}9ra0y zR@tXg7#P@yef#%eLoc;Nf*89os?zvF!IP_F|I-LgqWMuc{WPUz5cN{UQq zR&>Z#G+n@!MU3@o@OaAzZzBMY8Lqetr@xMWEg=)mu#d6E5Ez#*ut;*c3}i{Y^X?&R?Wl=+M3F2?ekWo{ z#gC#;9`+F8m|w_ZVtQWf6Q3;cbmuic{?f2o4m@L6h4A( zvAqMORYRx!#D-!SD|eU3_`a%*X&dn~6p5gBZ~*m461mtd5;p1>+Kt(<%cxfh2y(hD z*`dh>UOzbsO`V%1J57Y7JFMj`0jVVFL>tl(D5HjlRA@FD(76CbGK3}2SgAE5FnHNp26UN!2ugT9Qgd66E+T{ zfz316Jev$AgD^-!pwNn_rOvslyQ(XPoAbTjm~)*|-T(c^!%~eQM60^$-h0m3d#^Ru z48_;o~jJ21a^5Q`hLzmlh3YQyY8NDhU5J2_g|sNuY9^~q zjsE7TkN!PE%gac-` z%&p`N@pNL^ zEwR#+2W$}nL?Jw0Y}h=3Ql*Hw*+mSEjAHxNO(>W0ICA(Xrlw}J|GDE;jbUA~xD1{w z*pI~k<;zwi7{Sq`&F0hLMFa1B!)}BVAlK+8j3m+>GhfXkJ?(-h6&qId(kmvnXHhF_~!(G^LE7|owC%XNpx zB3OjK!(yUcxu{I7yg<*;2oQ>*lDJApLdV2jtjt_Mt2mE(y@+V%2%3JH5m}BzJrF_9 z&^GvdG!Lv`ymcJYhrSPAtBIx66)Y`XvKRwe1UM32nj;aZ;j_wfWocPs_=7^Y-g;?>pb8=b%#apil*tG9^sS737_;nlD@P zTcK-Z9?jeW{LKP}+FIDPxeY)4(N9oiMnocxSH1FPY?vHTvMsr9Tr-7i26LA#;j3Tz z7G{>p;?FUI$aTX#dGa_suYUPGt($M!4}T<%hky1UR#q4Ffmj{!fg}&W*q59kTg5KL zLdjyEg%J46+L+&yH7ftiO3-6w7&ePHNQwGcJ$#f6)oMC$=+H$Mt!Si$n7@uhsDkm) z4xCvXMl{ule7=NuEN)V#W(#M|oKnaNW1BfsQ)-*DF>vv)py6jor`r&XS{K_tIE2Zu zNlc6l;inHhghw8G5{2TLs%d_hXv0-T8|s z)vb%KRZ4j8J6?u``6UFyF%0*G@y}m*7`bX#9^0%$J(gLx{$@MPelCQYbFrrFY(d`+s;p@`a2R`P{-H1_p-ky4SrHy?s4;eioM& zl{LZQh0g~`G$fz0z+r*F|GvDuDpZNrW&CeG0$(VEo?rWA4E^;V{wI&57k~V};uScV zG4kxA9ew!0*rYaogPK`1n?VutQ%HU_rwL)?001BWNklg+SvZ$XMMcM0*=>K?iOv<6{Ha3*>$M9FIXp*|aQH-fDyJGA>ghR-*qw4Az=|{yAMx*Uo zGmjI|GJlldr+ACe=JYP8>T5&%b=)ldZGUi#U4X z80P0LARM(=V>d?9&;UD}+-PMtL5vTaNgn-rF!^`fuo_AmNm}GXZiN9+i5d$uEkM7o zu0wFcP!hlMjtR6Si>MUW5ccKaY4zaapFfV{+1=>q>Q+uVjV4&Z6M7#W9KwYQQ#g9` zkl-g)pIdbdSb_}6##8F)Y5R9boM<4ni-t(>xVEWPtgu-6LV@Wj1 zIsEzWyc3`N(vQ&e`*k3*a^+a(N(4x7r(=ih5=^OvAYn2Qjp$H6eg2{r{Ba4yt z_6~%8^EYXxkL26##pK6dL=yfh9`gU$_f%>C=dwT<9{l^pEjXT{IhS?ON{w~?zmzcK z139p=g(g|f01tT*`XnKA5Cpz27Qj5{3(7OfZ7N;SEya{mp-Q%Dbth5*w~vals;oSHu`s#@HlP^W zj+Qs5eGyF`Qf=+X%ugdTcMKhq`{4CqQn(q`VZEdDC4xiM1o&K)~mfDq&{k ztcATPc#x7#FVUtTb_MHj9%SJFHewESFI&XVI!=;HzZOs^#Ht<*|Dt0yHvs z;?ZX`cIfO%;ojH36!9p{qWH2NBkL}$U~ypq|L~7rLLELs6k07CH~ho@`Ect;Pd_WG z$5J^j20K5P>u2t62(DUycEo(ZxUp-jP$?te$N;S>73tXV3@~F0Ndp{>ZIF(BtvUS7 z@9#w_TE_4H#Y6b}KfDbWXQy%E^gK3COyEyGTg1`RbGYjIo6&0eQLdD<&?Hgf3|=8U zMa<1zk`jUBNPZDP;G&~MZ)Mpur-Z)(A+u!WVMXhN3sX}l(YcDQfz761Ey@hzu@FKi z;k|F!j17a9B&qpLqlKB35bk@zgVBjGoH{oRT7eD^^k8l|i}TY<2n3^e{xFmN$W;iT zqq7U6gCjV9{5gekG(*&#R*{SXS8ojBRkwFy*QO2}czO*V{_JDey=540`-Q#8t*qhV zQUFE&1`G`E#Q4^2=Co6P(rh9gx4E`+ zq1bTnH5lVg@}E)!9e;b5_r%ta=z~a%4Vu_=sX=06<&J0RT1)>B7A@wqM;Ai#W0>d& zA?T$->2kiyW!RZqgeG!TnyZ;(@$Ni86S1=U7J=gZ5J6c0D z9D*{*OuZIV!+sS z*!wos7MoELuH|+sKDWpcXsqSoQ!a{`JzXB5I=M8C%`pEv(;0c6+D67u?c5I^f~dD@ zLQs;u6Ih+QfSG5%h0$HNp`I9kFGS9i$tpv!PNar5(uEH7Vg}7aUqqm_0FH()U7Epa zc5&TtlNXstDfctpZ>nTi81(n|X{^fYNf*$S)fH^qxKU$RD#%1uY)c`XXv6sn=cMwx zX8-lrd-ZMDd-H2mIB|?j!>DSdf!S;sr_Zn8_;k)e6AGx6*Whhd&@59LSwPH_!Je&M zID6y}W-iX4v%4KVeKEZ5HFqJ(@tQm^tg$8vHamR@|NPl+AQ+<@)PrMGH$3{?@3lI{ z`tkFFC-Aw?eI5ZH<7|r}dGH`1^lb6EtaO;5X!ebSx?HU;t7(^oDg^<%d*?=S;qt@t z$)UEnE3k-v`2Tjm(_9iG_#eKqf*Y?J#m12}a02zE9~AJyVF>PN%Mn@FaF<)KA$Bo^5mBPfG~hy%mV z%5)z!GdMoeJkZHzkV~uAi%d2z6jXT&YIdD08m$|5yc&?ClCQ&kl82QXVA;5s4icF) z<_VZ|GaXN0q}>Cr80Ix~;8JinGj$d7EE38Mlxskl+zcML8rw2OvVnSqKS#Bbks(ER zb^`SHioLyE7#SMGqX(YQ+TAaT*&2V=WC`ufr6y8#tX z0zt3sfzh5xkVZ27*gqoC(T3#s?P!LQinnGl$I(RF;AVsqUC3v%h}Rc^lV6lFg3r?I z+(lH&1$Z4I?)dm5W@avGtiVY49Xoc2n_#i^wAD}Q`6YVF1DYr=_g2cl`OJ|=Gcvvb zH{NtTCO2-zvGZlT@}7Id2`g5q=BbO1u(VRbkqcRzzqqJBqftVmmW8)gK%=+{KPu=5 z6>!zoK79Ag)C?4OwcTRs)S{1q<`DICSt3{^Li_pzihH6gdg^ zzWPnA(a8zieElAH0)Bk#WB&+vtjpxX$AUmU2k>bY=o(@$1c@JxVL_}2Td*`{2r-uJd)95`IV-~GE!32 z(t~R^ci?5$#SjhT(AB|MTQZNE_|XG%_|B1pNQ1ZT-+`bXIC=U!Hf2~RB`F?J><96Kl{qMG)7@u|u8yADnB%m|wL?@W zf@32qk{r1PA}AUeSw%y@h;aNTn`75zAxu|`tF#I zMC5$AhC-Dbhq}yeSV+*Yh?_b0IUcI+>$#Z`{13{N)a<^2Jv+AH{Dq4`6s(K4b?(|u zn?aoUM;L@}$+ad&_oBUxb8E-Z(H{^J*wx*Mh_{S)y>vnWR6Gy^AtsuZ_1;8QbdqHy z5p9|r(f-H&q0!R6KX4pJE@sfx(IMMweg?ii?>FIlHWK`^ThwqrC)rtYbY*D-q^OWe zpx(s!^A`{(JH&1`BA#4_D~$47&KmDez170lHLt)5dMtg_>qE4EBSNum9Q)3P5ek-( z9=#f^?b~-?d3h0eIwv~*8$`8S8LTDKk+>Pc2R`@#^988~P(T;Y)zVWrMp}VUWy{*UdOpW|pmUi#R#)cm;QbHdnP;bQ;>Awn-GqM@Z~Rm z2|k)&IO%DuE~!jlrR|OyEbzqQEU7hi!!}q=v-7Ms>0i)5jI)nc9c}&<{N?*65ce&M zQTxwdIgXodz6R~F0)BE}2GK+UBOC6-8-MfvIhtK3PL;olgb|U6ycil8#Q4MnE?%6* z-0VD};Rr%uKCD4GF~;MGb?a!&t?DMXWO^bAOc$o6v3bh|)9p4}(pK~NWzpkrl@Vx` z&>ft@o!7-g(wUi^hc7&afBJC?M^Bu>t=I3x#-Vl`JvD{Sj&^jlx8ca?DP*%HRO&4} zcj$y3ZeA~PkJ({|V==U)Qn+yOB8sIv!odi-dOGmF|G5w8P!;WMA-(p`9zBeoJhh0k z3m*6aF-&fp#MIPT+`4ZFr!VGkX^H7~R3Ok5E{kL$A%YCq*u174=`QTqy%qoK-M@(J z@(KLi=N|?|tL!r9UC-T3u9yxSD`kTdrOa+Za2*$3qbV(%N*Mw>jR>TbBiN{k?sqj9qP~bh9UtHFLp?3udlpSp;^z`(gqq760 zUw;o;r4rJ=_(qJp$VvEbUrsPBl7#|eg#UEkwc5a4UVws*C_8kFeE1w2QQGlasapKJ zt9;;kCM@S_j zzw31xCV5e+HZ`VmeNy;3iDbeG8zQ?7g2D!XYnt6+XGa^3otn~^gYQ>L3wK`c@v4a8 zdY5-em@&;vaWo6&%iX*c3NpECd2s#KKD=yaLfnQ}JR#(TugS3@FDg5BzE6)osDeOw z6;2`2tg}dH;nUxI7F9z1Qo>n246n6aGYj$)4^AdOEnQ>r+1Tni+&D_8BTyn z1cEIOd^7=KvE&p7?zlqDp0Ya34U_kAk^Piew)OgL;9j3no(mS*F(+TN|XeW_RjY8k%VMI zP0K@f=ameE;esX6i5?5wEUbDr0+0St$6dr|B#U?7+lFExhh!oRZ#ay%f9Mb*kpxEj zV%UG(KAbu|t)CqqAI9|jGR~Zxfj<<**{K=abknVfC!%8Rnr@r&zLIQ3eW3iXg~i2X zv;|l2hL?@v$%AL{lc%V1h#(M5O76t*1b>F^j1$9s%0OtsujtX0#U-TM+8hrGgHH*W z?b~xTI-)*&>Mwo+zxAPyV6D-PdZVHa%Lrjy@C{u@jS$EtmPwXnbJ%Q*5lfzrrYJdD5Iew7XxB7}n2>Ao0X z0n&zH#8KSolvhDMxj+DOu$3GQQqP^>tyD$(dBb*E)8i~m_ zhFw0d4Lu*!bO_crp9hVJBn35>%GEsZxgQ=zlZUQrFy$0iB3F|97a%b@Vx9p3OWSl@ zwTv%PH!@^A85Oyd%?D-ml&^;9b4B^%Iv2s786`_Phz37jsZqi3?pGn>?=i(kEQR#g z^|<)-w-H=8*f1?)Q%<#2}&aULHI&(boOmhE)d5-$;@-8PyGOXuSXn&Y-Yt& zCys2FugUl83Ro0Qs%U!#(%j zjYidje5Hk4sex>+hUK*yj?Jv$_@zAZ6{=7gmRV6NpGl0p2!8()de_5`RnwXskGg=`jI{KCKEYu~ybp4)G}rNsv;77Al>(y zPj3p}yZ;P+`7Pt{a~{-)!rSqB%+>ecz6YMd*T429%rN{%P?gL+b& zCejw+eLi4qo$Zo1&CkurcG+S+{n)*04|a|A;fB3K`0~$Api%dtLOD{kDw38ttFdA< zau$D=5vnYI!bT0WT;(QZvL0?k^e?z9nFMN%@KC1P`ajCpT6p0*{cLFzGt_}Wv{vE;3Jm}=JLf2H23|h#Ly(huoiqD*Bw_xG5j6pNLt9tJ+@lHMB0ZUofe%An`=?sWvwii#Y~ygb&?$GSk9HyEGf~@ z8JpO=-a#!Kc-_s+u~01A?70@1wQ}*|9HuT@)OdjFkY9G~wBmK3$e)1(Q2k!Bo)%w& z9jWI00o2L`{O-M1A&e}7Q4*SC;)%%)UWJhnq@@6)5TLKj;8IO;7Ay0+YodNGT+hd(aWNXPho)PwD4hLg-O7D1B*P(0m> z_U)ZhNsRGCT;~_b-sAPaH z`Wbj$dizUSv2YkS-*OXT$rK(x@D$FSKZQ&#FDRckk(CiEy3USH1q0=2$ivRB)xf4r z<9Ph>=al+L$SM@1fl&gjdI<^78b12L3Ha-aX!)CX`bY(Zl~r7ORR;pzG6jb4cD@?t zGP`AK+?5XC#DP!agMae?YMuyY=9g75v!c5B)>~wt#H@6ZDEa!s!^4=LpO-rzi;BUa z9?f}7nPIawE*3g#J^9oVGFIy7?8K>4r?7kHPRodJDu2tO@S;(vBfGYQ_uP}fu8j@M zuLSYLkqTaV^9KCxUp@kV+W>CZyB*1>52w#gV|b`fQm03rd=B|S9s760@$``#YCbZ9 z&6L8B3QLh(nwwVv!T-PtoH5Jn$nA^PrA>rG5t~Cbs*1bKt*t3qn_UtKK^$3e<7B=B ze>W>>7DABBUM+KLO%<3^R`*IMlM{u+;C|eA{Rut zR6=ZS+m5X;V5P2Px26Zb{On<)izQHNlX9qGe1{%OM)x|nEHDMEmA&YNw2OV zfzmdP%i!2Db8V3AuP)u`)J1}J42Tr^=I|pF=B)jwg&=B3 z2O%RO;}AG-IPI9LK#q3IwWiV`7gw{^6&nk3JtWR0JFXKDuYlNH)PV0bm55`*^gMa$wQz(04miIz6h9sHnUU}^qVrOF;U3X{y<}+cAwWfZM z8bxH%7S`4>`kpx*IzPkTSZ^WVC{whrJEmRc5kaYk7o@?D?7R*0jV|53wv9I<);5Tv z_k9B4%1K0ex1ts4mqQ~0QM7y!Lqq*R43BNq$fV{8AX2!9^5M_R<0qeA!^u;}*O3GI z&Cr~VGVx?0sqwS<-y^}b001BWNkl*>VJx8I^hN?aF> zhnu*t(8S$udL^P%n{fI@wnAp&Rm*2i0kw_4}fO${+{Q1-P?f3lwJfHdaM_Y+>2WDn2;o#w8 zICAum7DTC3MJk;VYn6xp%F2>p>rf!9nKD-<%_h?Aam>vxI`DB2?WqpLVj-j>75v{n z8H1-ZjiaaM@$A72uHM&=iSZzOEyg8B;E!F4V)PDFt1Se)brhE#LBewkzx0QX;`~ZG zl5IUQ;@Gr#BTgMZiMhEs9qi&0kVg=WiY1>&(jhRZ;>6q(ZPBqfU~(cK`lCmWAQXxy zZkZ3(;NSovv9Q72P6ur|YG7q?4mWMB;@95Pk7o|&@K^sbBa6|NCxk+|j13!x@$y^t z;r!GbSVYsn``=C`#F^#uwxz@R4B`L_#DvC8MLGnm;BIDIM4>@Yo%>np`c8 zR!dg1lz(y-=t^15e z_`wez#A=3#c#OxcYrI1q1D)=AdwUcj#*U+24z^z(EC4Tq#`az|szG;t6w$|O0$ ziZSLr7{Kx4C$$mNmxE+#Ca8{$j7uhIY6rTDMs+}tJWIrs&$Q~_^#n)fP;oX19f*n{ zCInATgdJWY0V{Bc2mrY}7QUnrn%oF2rk-O89R%urog#rFRgO-yzU+4q^5qv@WrapK zhq#SWO*JHkNylfvnmH@7jHG8s2=@|l69xx~pe}2lSL_3KQU)zKeloIUcbY4=a9N*~ zJ873Y1`>GPO@r`qgq(^3-k|37?)ZhjmqkLY(L$-rBiQWrb+7{{SN-_pH=cnfU@5{f zD^l{O23G^U9vnaYS2I3l5vC|Gm6X+V=ib{*# z7a=S?@i}aa&C0Eio<2lzj8|b&OrF$c25AM8GCDY>()Y-Zn*6R;yd9oj|D|7UU7BCUQg#i? zi*u;Z2fD>5Va~$|fpOu~bWpjLpf0IJiD-?c7A_$x&d~{76IvPQj^oyC4ZP<~oABI; zQ|RqWp(|ZOETH}!tri)ZynuYDD6^x5W)431@beRX{PrhK$jR`!{WswF@nguWt**ya zU*<-%v|(`E(9_dvh810%BIK|j;DVK;r(PF&u)3O2o;i(sSmn~Skko%IauWQMP2s`P z>>Rq2!0-N#N&Nj+=imt>)KxQ@E1xZ3d3gcveCyp<%jS^FW-&Q7jJbtXJa^&(Q$egK zaG1U}&*MTN`~#didJLW2JxI5ul|iw4_YS9&BL$HNvh=Wz`er*ga5cm(TnW}lYe=+XWO}DFK zety=_6%rI#<+ID8RIJL`tu-4Ak$lVB-iYDhUZF|xWLyPIJkh2ij)ql48_3V0!OY_F zDze!!>Jjbr7xiR&!0ul@BIb_KJ}3oPtF(E6__glmkL0tGmH;z zyxJs@;yT&ri_a+6Jiqvi%RqH^Q_uj<=JzU~ocHaf;-->B8b{S2oj!fe zAY~^kPT4v#C}O8>oC>$&b`yPxTE6q;yU-giBNV0UWmL0s{tmuRnh24Ur(&Q^vNTgA zo$F^)W1P5{$9JEcG7km0RoeYDR=-7H+nC`puR`7}>vzGvZ%M-}EUdWVb>X?gpLef~ zp$$#==((T}ElaVy@=MQDD2##aw_vH!DR@3Lwhyt+2^{<3r;(22(Ta^|-}i=MItM66 z)iv=3uwmmi8ts0KPQF*=M&!;4Z4$QSEa&DL>px_~3+ zv$(igMO9-D*Xx5>gCs8&(dM1Uj?Oha{m^&B?MtMR2#39R#a%aI!-hdb0zuuA+i$-Y zp02L`mSS5y5D$S|16Dp{Q}UwmAR?Sjcup0YvIBUi7!1exI_Ed#Vp)bnUN0|~(V8`uyCA1a1r@B{8nGyQ|v>eVns7i-+%*usvC@y*)iLwV0ls#g;8wH2)Gz<;Z=+ z))|h5~ceez`5V}ZQS^oPoVhzUwwfckuQE+UIE%R)0J^?q#K{=o-mUyu)wu2C?3LU zTqM~e8fDxX9_}Q5@mZrRnDR+Jj~2LO=olH}ED)kpA8|hmm{Niq1==d}wagCq@`)mD z0y}kiz0^^!Hnb+xy*h`Hdzjg1!p3)+>0goB$k%npe*B&`edjdin&bO+kxey1&d7tG zjrRC1x}fYNWhvMXixKbqUAH)~eZ|sYsE|MV|`bUjQ6QBFuK`ayk z8b9dTInq)?1kAnHiX}q@^ts$Ijx!b(%5g>hj$2&0902V+w61n!@G``!HKl$qAi}r; z>ti9G4`aKo$84hu4POkNL_2yn+=$G|BIcg{GUA;>LbC(mD4PC+JZFeNaAe^1#n3mp z8I5pSe2>bhhtOXQO;Ac^3nK&lxas?Hg@RVbJ2@aJ=>j?5`?NtEUH z*?|*Ha5D|$58@p3F6mA7$ueQ04!tSIS3a;heAfw-=BIEaGH`i*?u0#EkzDAa4=$nj z%EG{Hd-eJ%gv{5(*0Rl-`K7!ILEugXgj0Oj9G=(Aj;M7MqESO%cMp2|dldR3f0E^u zb>~`=#qC%>{I0dMGlFrOLRSjmaxUl- z<8QPO5bvqwaKfyS5f?2M!RXFAuuw~*?)4!txC^QNO_+N6y9hK&&`IO*!5>MAo6z(a zQInjEboT(F=>aqYag7Ly2R?=_@0>=j+9iZM6iTE{naE={$*qfZTQ9C z{|}s)i>ca_G$jDsytRQ3{K_^YLVSo?no~Dh1Xl<<^TDLi1=GQb`1rS(@MgK~ZsM9j zMn-b6N)#gHaRcE4M^Yl~PpnCrK=LM6I6v$4Zzpo$upp7HkNN66c zJR}!q7gSh~!AuVaz8-&$#7HjK_Ea3Nyz@HDT$L8u$_Hs~#6q8_LMj#4K~JM4t`~9>T#}e;S!{U%d}0 zE+Xq)y}NEqR%|3jcU-~WV`G7UaS-Tf;B?KdxsmR?tCw>K#a#b<@A^ADe7*L287^hS zKW98ZvbKXL@OM)NDqjH_s5xk+4n>lW)u1HA<07$+l5Osxw3|1jgUOfcRg;N!giE-7 zob2}&qKT9`Y4JoHJ7}pploLV5KlgVclQxp%!9TrN!sqTgYS6u7zwKIOn-ask5i~w< z(rMky3EdB;=nx{x^Vd;1xFZ@CDJm|EoxMK3;eB@mFz`|(M;->VaXdyQx5P>hHeGWg z=9+^doO>f}NDnefI*94x52IBpY1GPQxEkt&FBr4yOw`C5K-bV#1QOk7c>}1=9Y=cR zTkv~q)N7>(L&Ge|vgI_!)_j^uhJW#Lfn#LXzQJB>-Lg#*e?GI;J(?$mGEDfs>kYKE zccT&M#MtNnDpm46cyB$JTWjFZxg4H3y^5K&s?-|*ksrkni;>}JR?z7$U`tO4^M`(f z=bm~LiF6!^Lm!dnYGk|icI6?Y;t9l){ChMlaSp&%L!JVQbMsov!^4B(6ma%7zp#LEu_zt^ z``jj2By$@c`BS#J?kfpb~M-Kp13X_wQ zI>24t04q|WJN(}A;=HPLLiC$AZZ`Oo8t`gG$^&j*{7n4)96PwIVcrwt=&%~+sDU!l z0CKsErQ6YWfl}2FjgBnjhI3sOh;&huMJ{D$j**Q!<1}Ry(Gfl)b{~RXKkk0*UD&Z{ zBicKtMTewGL^?<;WkJMi&U>QIT&*bcfdNmvpLC9-`3uKIlztXpehM|GHTJjO&%v+LrXMSEbs(hx0C@bWDC@)hKB%c7Of zy*PsM1h7MioCJQcxiGoq6+|h1S2iY=1FRBL+l~lt*KUhjGwsWGQZe93gq{h+H@k)lPBX5)|z`V#=baF?by`5^+#U9-8Zj zitdFwzAzL=1r~E2xZhEU!Plick*^nupm*DCSVFrvVcuvPVjUwiia_?#VKi%H)XOV~ zv=5-{ZxiZn**O6Olig_R83DrWQr}b${u?^$r-TZqP;kysVLB~)O+!J5LYd!(#!t@P z%JZYAzZ)YXBcOCPk&G!rLPZxx#m;z#&j|S~7v>tc{jU9}*TeGFs5XFXp@s8{RXlTY z1;?gySS|C_Ifgd;pNcwKO1EkS^hCe20r?G8?kjm1Ed=~{&Wrh_TBS%;&eebi?#0F9eZ&4{29TEECh_f z$_m$gu&i6=15P-R7o7{XtFv1-is}U(P=xSVg)`0Z`NM}WGc%2jjxLQPNY?1+XtV5k z%>)@`%{c5DPMcP&P z`;;Kb-$&CI9_EUCX5a{u@SGyf*sNqy+icW`M=TLcR-^?{t72in=8=5xxY2T?!|TcM zO*ll=ht2TZ(X4`Z^bl)z6_M58E0S+&xcA;S;O6~T3nAi0wz$Yt&Wb8urbv#Bj|m!P zE(qhJnUcoO+S%15r3cX#GNE%EbG-g-h`j#g*!t5SzEID|7xd?Tv=G!r_pzP3#f@^i zb&_X&ew)E_qhwb^5}c6&9c_;DZKYg;pEYr=?dx`!bTJt7m_OL^FHFLpUn zZgDOinDg1V<}7XSvO$p8|Biox@c`88S}LOUZc_wkFK}G`+-8A?E0Ib=kd4Hw1C`e7 zWpY3A_~6^Fg{NGEFW5x7y-S6@_GCXt4Ybnsqv`d^B#Im)_lwt}(F)-2zVI+S;iR}s zBtqLr!9_%@DC3tacXg$se9L^lY*b~w#%6}97hXf>dZ^fNiaIMgT$P7Q26Y-Vx7yAo)2?gD&FQFOcz zf-&?DZ$cxIhBpvHsIr3EGoL~#ToI3ps0z1D5i*%A+%nXQyRwbX?P_V1;PWAsj-j)= z8$&}w2>AozZ+U$IghR&3;lNg$FJDVMzEC2FLnm{1^=t2t6C{W8G~=4j0Ow{ac5kM{OXBVC+6E!`)()3MQUaTx?1duY((*P*byJdfkY z&LEpxLoT=Gm|ir{6=`DYpdXJtzlMCnPp1g@{UJf;uX@E@3QeJ0=j5r=$Yd=}m|yO^ z%AH5?eY$zx{9ZDiKu3EgI=bnE#;Vw2qm|~^YT>cR9@Fn)3fIKs23Z@sWFr1N=WDFc znWN1@si!T98@GoP&snYJHTTJ`aZVLPGTDWld#=HSnFVvi`kiJ6mnVg_4J@rtK!a=yd1fFR@HO9 zPz3WU$aW^;!Gl;uf)mU{%#=h#tH`;SIEtae8xM85h7qm`qEKAJg(-f<%i%BVm}HFN z$g9%Aaoxt!GccMlOUp&2e;jPE8g;^dyp?t@sY>M%8LFz<&Vs0U@@?|vZgTv zzsIk(_Owt2R?aLCh%OY?GKl=@Zz2BD8?pJZ`(Mz9hYp%v>Dy{BT z2Sm^|ND{2vL*Ct3T{zn10=UrW% zjXtZTvJ(x>?w-m6hT@sx!X0n&pylC7bdHC#r8JrcfEpSH8DIm{)|OV`K@OJ=YM&Du z+=8s7MG%y{lDq_yJ<|`OR4S_zRY%POOI|NLXbAh;;Y4JBXbFFog^jBwPyulTSyHHg zQ_#r&gyS5Ib^PdzH}K}$h7oLe5lwOA5O%s@JMh@J$ta35@w!6_beag>yGu(&{M(O? z$uZWDO+!kItZ)1z^KLK#r5)u4)6@S&3Kqw}ir0{+l3P?*2X2S8DcLNe!Yu~*`T2Ts zj%9X^VVX=|63<~apJzEft#*m*qf$a1d6z8A9;I7xB z6iNXeDgb-{5AbLjsh$ydqMh&rf+!vSE_zA_)UB&gbF00}vKQ^C?la70lv^ofvB`8A zLn9+-Z%bNou?iz1I@*ct^AJto7$XqY7^I_b04pVidohlhj+YDvYhf+}9GfcPxwEUd zuu?<4#dOZP;=N_Ur@*khk|2j8ISd3Z;G3WQYYYwcBiRm8H*z&h`$Z z(``aBMn;D)Kfh>s?lkmhwea(&pG7vihF~a+J$v`c{*@IfKa&#ToO#y8sq;FBNyr=> zY%>y2v#1!;u&)SD0GmK$zpEy7!}z8fQK-~0x0J(^z=0cp4)U6WUOCLq)Li z8LO9Lo%&1l}#(>H+IZ@&{hKgS_;&0FbTQ7q;y z`+%EOl_Lj-L~1f(EeMV*=&j(wcU&y_61ylLLXotPk^I^;j-Pl&oD$k=yPb{Qdn;I^ zaCU}^E;q#`*s#muM#yV7J~n}0|CM(jn_ra!C9gF{3v{^b>Fw1upqhgP0yk7T)wMHi zEs;{OQz+!5FXsJhd&jRK@v1wp@$m;Z%ppijk&= zfUVt1jk0L#{wWXEnx^%yRxr@tFGp4* zKN>tvG)~NT-$7()D%&} zypCep@k~@tDX=QY>ew}u#H+9ES6AzcF-;Q6%5kr|oG5jznEB$QK8o;cyoqN{F5>=Y zFWF37@V=QMxd*=_gIB0mTyrF|QZ}xGsaX7S#O0`)Uo1?_Gs2z);_iCTaAfS zJeki18(_V@bFJYx^9CAT_$qY_Z@UT$-hNblG3|X7crmc;4on?=3W3TJGADn4*uYLi z`gf!3jR~mt+}=5h$a9Ue>jb=t_458*C!Xr zuAVLo3=N{KtwZWF+FF}^zK#E_s3oEvK&k4%Papj`&d)63&R4$%cipxZ_iz)9b3grj+WK7#khV#^rUFk3-Htmm`vqSJO5)Ge*A~%?C!%O4}Bk=v9U3Y zb?DFE+0lWaAx1M3LgOOgLBa06DwZoV!Q1Zr4PE2Co)mN$F^)dA<5<+Hm4NFUl>V}_r`dKmOIWOcP zVq*|{a4Z|ZAsacCq8;t@zz$(_bQsIat3nM(`ryS~Sy{t#&poT(d)2;u4$&^W9%jXA zo)6Ug+)@2mxc~ql07*naR4lTYtYEke<73Jr;OC?bHRY9rKFJMu$<0@xGo8SxvzM@K z;}CNBBEJ2j$1%Bai{N~Bp6M=dE{JCj9z>}`SU-Z{;Zbz=bm{Z(;AingFN8=ufm?3A z6+?qOU~7`e(A=U@tjGs~qXv>TnOSczrv=i8!R-$qN>WlHEz%1+bv|T;VinmO#~(4X zO)gikwss!Jk3Y43Fu9)TZuM=Tphr>BZU?81O`9)gfMi2gWlHmwH@*>pkS)qsB97kf zJ`4>F>hCPf&tq|64(HFEM^{fT#>U2U|09tQxLH!qUMQ9{Urqe_Z=vm`YcclZi$%f< zsbV-#iptafk$3zLZLI2a*$p#z$=TqkE+W*;HSdN3t;_cuuahg)1upWauqMso%!QTv zk^UYJydX!T0mNf*@n~F0xHe^~aMU;exkAwll9&NgV=-aUJ@e;psL1E2O^%S3Qnjv< za1jJ|M5=?|>s6CLqOW>Hrz>VQ1hvQREdE6NGM|@Bb4Y?(k9(_ zb7dgpt6|5MF}dST&nx2=gzB2cip+x7lzL#bi(F?)&UcuqJ=ac>S!b`0!})SG{TG5gOewZ zt1H>EWve4KG&Dp9y2ldJ@|mm-FCOX>5rpTD61&2M(gE zZ&Hhlok*dW!~Dz%T$(+jMat_+U{Mjq7jR zhaEe1p}no!)F7oYW@j!bwe!sB3urd03gF=wA|8zh6(M(oc^tfNL?8Tb{6%!U;#Q14 z@!$*TjC?_V)@PAIZ8eW?+zpyaSxGB-H~N#ZcnF1DJ(c| zH+~bxfFh(h2Lky@A{vrV?7-tBBT`z;!kn+=7B~F7lzF-ctvjFRLF7sV-Qqw~X4k6N zL4j>OnjBL;Fiw)Db=4*(=g-)lVFw9E7p`}K@i?py33?j%&3ksiS6@Sb0d!F|e4OE1 zlOVFCkY*2x6*Gz=0${2J8vHcyiLXC}Mk|O~!|b)y?JL1EXhBXe&WIh_#_hO_P+NiK z7CY`9C8A|8=onwQ;~*nZ>3TV%3o9U9mtMP8e19w;xc>>{cDx*<>S#7FHn9hV@EB@d z=FBwE@1gu5`e znn$@@K)z6dr!bFw6A}F2vwws$Ck|SXpt#g(Rc!g4JGY~&qf@y93i)9Q8RuVxJO^%0 zuDU^Cst8Gbq)0k-b;oiQ0Y==+-h=%dNqWpsbv4xoIaT5};DRAC4f(gIJ+WR{63TKKR@T**0(4 zx*1O#ctRm97RF))2s?Z}m4wG0eDEi_k<42lB+oxknng5)PLNx-Zr7-T1pvv4g!EYu z5UQ6IbFnBifeHwjDmj~;TP*SY@X&4VOrxu-3#oWg-VoWmd3_sH=tYtDsFcCEbB9qX zlOXCfp95zj;o{`Nbmz8LazQwkY z`KMK$+liYInL0!krL7j$vRP-&@3@G%amh~K$%0<;Y1fs}IndnBjn`JFq?3%w1AcsB zRM0#RPc}k|JYJVSdJJ9FA=X4HokS{;5c)+ILs{rHjNoX8kXb47i#!N%4P;1WEH#%$ zK_o%@sAHbQ-_I_X#9rdXVW~H4UhB#wU8R&e<~AOJnW6DZFug-M7CNh>RYM8fpIv{w zb*};I)ZIeGRUHhb{dntb{W9Q*rBY~-IO+>oC$46J#7K`0AkooO!;xHPBqQ+EQ?r*e-c2I_{z9?mr9)AM! zMK99bThKka867?Sh{dBwrz0p7YdAf%hD@Q3nx}9VM=~Bo*iVlJqXt+*-$1ThLMBr{furlPneCO7*4wZqU(UKUw7d;8%N6|F zzkUjy$;t5+B_F)mWS*zf2~3QP>EKSKEPk16d%FJ}K73e&nX9k4R&q(+c-~+w9@!4t z;*fiw7ANIOoJ83JQ?4;t&?;^cVz?L%J%1D{nN^3iY4Vm`d-hm2t5mis%0*-J&n+zK z`y{!!auF5^ECO8SzEzkZq*6(AcXy++qYK4c7OA$hteROZvKU|i!H1bX4=j#2p5PZD zc%LsQGUkD&9;g2i65$X&{Qhe&(%*|nJce-Gk_?NrI+oW8n44Y0;&KkIKdB}D)6hSJPMtgS~Iy<^Cec_VWts)wUA#C38Om)oV*D!tY zn9vuqYIXusoFd^$*_1)1H9a%jGnr1t-&y4IKsT>QP;=w9WE|N{PBXS@xr|tpW?d0< z_w}Q#qYVp7%ko%=1Z)P%8j5qdeSiBIGEPzkN>xE>$;;H zpEo9$a*rWrh|jc81G&SRIgK0g!xK@kvvU=7+&F*Gdb@(Jz?Mq}M6NTUW4X+tqNlf8 zMK6nQcC{*`C=+jx*ls8S5m`z_ zzxBu|9KBEw(X+d=$B|T6A%5_d=h=z zu17VHLJmm;V`+GJR!aL|XC=p3wFc2F?$0GuN<|?AY}Wm?MTEkbl_b@_dM|+Pz2c9_J7o8)R0q2t`679x`!}^B>os!?d@i@#M{xj@Oa*WHYNc zb#e;RvlrIQHB`y@y@*p);8cK|t-It&E+85mU47L)xfr&$r&Wcs+BPvW5eEt2`?8p65=a6l)hamj{PX&3 zi;D{w9T~#5$w>qwG@0@v$eE@ehz5a3*d9pU6k1s}8dV%QwTRg@LX#x(m^V7F@45_8 z35re%rPnqGesNYWm`~ge<6x+2uGUm!@!v(II@$uEFTELpn4K*Du0Eff%KRGT(1(EC z1l1?}1`UijaC0M_=k>9%e2~iHi`4_z{ao@V<=SQg8#BX-=sGHz3KQu6C2R;$XT1`y{_Z8E@djwItYo33N zMXiub84a0=;c}Xw!RsPAN{esBFW0+4zP3)fy4xL=y%7|J0MPGN5zb8!r}^H39JM-b ze^l(4RM;emEM$0i6A@(NVe)X}3CNX@`>V!$mRq2;>VzM0z3}%M4}-Exo2?5GaoGOs z^jJi@?u44JJ7!EqZZx}NGfZ;GYdpw_^vQ8D;3&ZiZE$DwCY3a4v&(;QeFffm=N7bu zGa`DDCq>6pJE$3zZ5${?+gGfsXF(F+ScC|2-G@(o{b>YZX$z#f0xd9NMTlf@yq`cvXPeGgIuQp0=CR-w&%AHBTp5Mzia2_- zBX@%UT`mU;Y3|iu_}u@saf5qs@uD%Cpd*#WRaaf5!(N9^nWKZE5p=j{$!v9X#B_gR zwO1#%fG|`Al`5I{RYB!q*9ZJqSy{$~>1l_l>&lo6c8kTL=Q_CTckmv<}UzEn{wWdR+?1hfXYT7AhfopECS#nAtAzN2gqfWbCV31tZ^gkmdpOPy17b>)0R-8|1)`4zL_8P;2)px)uX4nyQ=Pe z-}9cc!`f@F{k+}JMLd@wmIhooziIPPz)yXj4e)btiw?uKrEk98( zST5P5KE6Ki#37vO&fw*BwuS!J>)E;jPnJWdEY@&crWJdr)xmR)2D&@DtWRHMOLPAG zyXU_c;f>PnrhrHXtu6)^^wXZn0lUmnnW{@>c(zuP=Ohgr3Sn@lUja8WS|cO+pqr%b zqDDgJU%pjU}gvh5S0n-us ztlHWIEjy;|BT}n>TNOm;0vyTElM}tdV@N!r6@ekzCUsh=t(1tb)v{MQ4ZNO&1yRXx z9q;&!tq9a}NTid9=owki!?kBHMbhVTr7pgdXW)m_O;N|G@d9q%Gb#DvX1TV&#F@*^u$F|s!$l=j)EhLx+#fVTcQrMzrN(+OEJddaN&n?Vj zdS)J_Wh(eumk!Ssxf%SqZ+`7M3lgMW6}CmAGvcOw{-u}eFj1qNZ*DpXjMV5jR(ela zBPT4*hfMT=hn4JmwG~azqO*$=7p>R$#ED}VIdw`Aw@5FNMor*_FL;3>^qX(FMNmgH z98(WHBk!K>F05U*Mo5LY4y7_4-t(9at8aDTO?e^@Bi01aL- z*t9X*FeKVY$i=~>Tx)97Ti>_IT=Q_#y%(4BICbiH(}0SUpMxP0Cio!{QOlOidw~ifdeS zcV`EBdpgnHkwtznkC*@RkFa!BH?9~Pf42I^|GF;#_s$0KOeBV{w079}b$giQxz^Se z)u(;X>$wBI#f{ER4mP=!pDUuDIvluW4i#{-4`^pCU?-x&a_x%rv5Bb} zVcF0Go0CBsw6-ITt9ExGMqQx{=V93BZVh|Wm}m0?xn;J2l9(5k1Jg+CdJXsQo4}JJ zL}LuiXewd4w3euckQcV#Dd=D#wW4(C35R?p3j$!8h&ma;A zAvkmq8o?xLfiN18B%c(flZq?3h+>Wtc$pLc(!ldj%_=(;mDCg z>P%o1&pI{_6P=wlr>jlpbEb$$_=~{=KYV&>POXnIW}}?fo?pfjPd<)ll-aYD1?V8p zea<<8qaWS#INCcnO)G>apLj}#b^DoHF~68Yqt?K-ZD%M8J$m98j*pyFy9!y!3`l(D z;5U;&>txY})uNe6Wt*Et>TBBIJZc_v;z5Zbs3~vcX5=t6F^T2MvZ-VR!h&q*fH@n2 z;!v)OcF-8O9XobZ z!c2S??5H66;@QVG+O(m%tB9svN8Ytt(b#d%tH8!KmQP_)soN` z@?0qVF+V@2NR{`LOs0{|B-DeQiYG*n?dtABI9NeTGJ%V){ReD+^EO0(xc9%D>9ceN z?##sysMPRhJ^ivHbe4P>F_779KrPuKWJ)#0M=Zo@lbK zIa$6JeTN|>77($_;A<>C(Q#2?bI%xJV(p^Vrpdjn-?|&4%EW@n1SQ-f&pv3Xbm0;Y>-e@3{9Y!sjv_M2%dxnS@ z>~HLQ3kK~WQvae+nnQ7HKRSZrSl?DfM{5G%ph@7{G+v@Ou3Y3hXEc46fdX55O_`We zo9XLVTHrt|>Q@M%aGf>2B%=wc+*4lEiluP|+zJ{S_}16|27yf*H#AH((n)a!i6-P# zBW8V^Bbe2n>bL^h2yUURCT^411mn3G+I)~C+NHB;oEjMwtU;3A(&9V{B@_SQ2EXF@ zS0J0t;^9a3sI`*LH4%?txl+c14?U#P2Zfb*)6_eV9BPFFjcS6>$vH4Yf)I&~cO~q^ zBfwzBBIk(BrI6kO^~D(=m_k@nGnZaE9vwx8vK5|(e~aqz$a?Ao;(KfCW|T2GcTip7#1T6NGDu&_Aq6c)|6NCG=#LL0shn!n3vkr5@It%=B(0-PZYbp-_+7t8BQ zCR@a-n4O$2*uDqzXrp3>19c@3sEQ|S13ySi}sM`i~)(21vo6q+PqD$ zjFTnp+8Ipn#cQ%Mgb}4#GiFA|mhkzxIRylE-v;Z-DN(VoTvofYMnOC8p+v=T5owDw zZ=gxj^eO@?(-RqBaXtTSYozTtFAc3=#-TU*cLg# zT3L9T5*fTf}Z8)_8|PyjxF$@vm)cwh{HuuX)OgfvOg42aZG=F5;ifiVQbG!o3| z^LNyy=(s6<0;Kn~x4b%{hrcn=b_?1nFY(!dsRFAE? ztA7~bo?hN$wJmT3>eV7D(+7ctXRsz)L0ck#u8x#S(jK`t@}`w!OdH2ZZ|mO312J@o zK9ZkdT{=b-W%A7z^+Bj{L1da8gxs&*r`bO6vxb;3SMc@!bqxaRhu1aK%BPIf$S+>J zr=zV6Jzd>`qsVM!l*LW14|VlE!rqLm`EUGSIs+mNgv~4ElAyZL)29`|EG{jeP%P+Y zpMS*_n&H0Zp~n!s z!2nw~ga)v0SrVr<4mqS+4M}*?c@z^@b#-d5J6kQHU?QrFnd3ZXW~Q6buWwcIush#V z-3abrd!Y_G&%VAPT>0xSLbXD|q4gm189)5+!x~F{@DS%gL`B9tcI<=#rOr+YKShwq zW<>~9gzN$Yi@t**P8G{V)XG#_ELvv+mEoKU8Ly22hN9p|RO@njbhKH=^#*~@m79!N z)Y!-=&3(_bbYXboRy^^@-7-#GPa3^!I_>x#CVIt#ssp5r7Qtngz7SXb#tTud6maD5 zFUcDQcV4{-i6B|EH8dg_ z#FDK@rXtwXQoxfh{wj9AYd0$2df->vn?4Kge!K>poDblq=`5~q>r^{3r;f^5RvZK? zQk|Vqj;`^V z07*naRI_`&7$Ea}wq`RJ8=q9*%rb<6m*$WuBaQJM{mc{wP^J+>ZUW(IPfoP8;=vR* zLnwp6>fT0s-2tMLKI`VsG5GLkf@Rlk1_pUzkviUZ0WRR;_xTxo8VdL%_Qw(t<*q3xWax-&X3bjL z2REFHKxQMB5k)l^MRxseq+0v&_zi!J{=q@i192s$T#G<7tH3A_PN5RYAeipA_FXqd z+rPIf2pI~sG=}2%UUW51p)FBEODcwzwxp5c9X~>CqKYtVa;W6RHIIkEnsp5Nb&rrOx|+=e3`;V5l2K!BS|p7v?RyKD25MYaefKadIgtWe2EU# z-lv`x$#HPq5C*#YaQgIV+;{)abuhfLB5#cE$)CUKWiQ2j_uY@NiHT;0Al1Hj9P8Gu z6&evsBr!5_S`Z2~t=WpFh`C|Vlo4zj%FF|ekm}<+d$Y51m>!?R+`@t!Ee#A04M!VG z-HW_}Xat#bNZH)~??m20w*0yco%Wr}treY8>fwR@ccbKQT3huFftq zAh8%yv6#lMvJR^jP0EJ4a*RO|)Jw3bbA&%7Fr%SPcIfyXY)O?URco6#4t)3~m}C<@ zNtW_|u9TK>{NxDEIAa_3@85@bERE@@QEem!AAHVPws{8FWkF%3vN%Ir!$>G54#|#l zwkyLUTGZCojzX@0FMa-6RLXhGEzDtoWg>8PL%SR0OYIA;6U#acy#I|Gapt-ugw^fB z;2|mztKyM4JoS5betTEzB=S%*eC($ypE@%YS1X-SGen4Y7_4-lJv}FtBQBBv7__h1@6p(<(H=x&u~7 zozn4fx&+qgWui#rG;Hin;-$~wR6~|fGa8Gml5)V>6-8pNv8~+_CgzybHJ}sYzu*1n zG)Cq*d~aEVJx?gKnF?~ja_oG@re|TD5_}dSMCw``^ug<9K(T6mOv6bXa|XuhpihEG zPAc99hCYb&37_vAq5UONOAd@5fW`VeyGXc0yv%bn-G+@juEbm|g?b}|YOD>NTQ5eS zl*i=LcgQ}oG%FE6^72AS1Y%j#;=QQHIxJ>%W4smgQHV-GO%2tVgD8(agu!$L@lY9w zcogj|Da2z;7FXIhrFY@m(m7a>NvI35*d##FJx|u<(rTU6F+%&wE($}qsOsojK$$cv zuyd`Zwl@uRCW)8{`n8|`Gy-RCJ)@z`?pdc2;UKAj*>G9ICejoSN~Nr&E)mn=U>(bo zDEN>x6^&vSj`YHk!Jz~Dl}(a4${Qd`FuypD%PzSLM~@!W>~^*mu35WAJ;rzc!$#eLh8#Okl_~xtXz&ElX6Ky6j~4dzG$%{sEOJB%4}U zz))8VxxzH&=H@Uro5MnmJ)=bwt3i~?bgV&CScYNkPf@fHZP+5Y0!a~C3get}&c^VD z%{shBrZQ)6;`mWKyysy-JRKeFnv`km?2^`zb^ByIhGZ&>WIEXlKB&g#htqgxPs7M- zSFNc`NQv-XNZbetC-wLBN#1yFe$Gk}4$kC3G&VKc52=t@z_Am@P^qvk7tmaJwyUzu zi9rYhK$1UGnJhT*ljQ;)(3Wf)Ui#9PVe8f{R`*m_OGT|VL{GArtT-E|PmkcUfBk9Q z>#?IJ(Am|7V1R*F$y6&F4ZQO5R=o6Lj_9p8eGRhML!bxQclABk@up#fe{}R$+oL|q z?*7hF66stK|1+9ExlzT?&|29Ul9qkTF9Su|0Iw^rJyxr#tEj!TP0$=|fp7PfVRSWX zpE)xrVdhE(IWs{&cA4kWXRkaHXKg!65W9%PE}&+hP%YQ6urQBPqod6+%O>Pwya@)n zK5OIOO%uj+SH$a=lL=_}U3)tRm@&DsP6I1o489Z+jC8Hxq zW>U={!QVG+3G3?Yrl!MUhAJW+b!}=feEp^;Pz%{LFfsF)sxNVP)kE)`ZGBd{IXsb4 z!G%Lggfh6Y1}6$zB56avR9=$&w2{8W&vM<5z7*>9*akzV&)#FJT!@4W|+uu0rAh!rO$7(p=EjcRf|0-QJEkqO8C zWB5@k%%M2`G(rncW3Yu?auhuZqO~Q1ScHjqSV1PyGEGnBcr22`RX%7)2#QFU?Gx+P z)AUgVVYWYPl(i8weObol7)A8nR%Nj=5qS&ZM{wo_kqOss{Dn_{9DyC%&SC{qYm8?l^U#;v#CqQ&HUdkz4dzi++c`;%D5&9HI926Z1OyJml}M4ikld&tb! z^9*94`d=M`J-uk_Y*$v_lPP1MwT!NoIyyTuNX6rbB?G8eiq=jO4kN)~Ca5C6)WGS9 zaZJruF*-JfVxfUTHHc!Fn>vDpC1%=544?5_gyWQ>w)+#b->Bi?`|np*2LmhyHGFyE zrceNubK-GiQ&~jfCe!L+QXLlO4Sf#O6g^N@?6l2<4wq=)NbI_)rR zd8)tVmvHdt5lK_4gp^1q5NOM`SQ`xGQ`vW$&Y-`44d&(-uzu}2yz-S-p|!20nT^wWKiw@NJ~H%6Ah&DKqugaXkpZXcM(``*y0z(o*ljk@ar1WI*0 zbM?d6{`x^gZ#?xZbCbWixAS;4jOu(9w+#&8A7*C_)^F6Ye%&VImKK$S#3LciN8kol zRxjh>#x6G+NFZP79>tMMCT?2`l92k*qaQ%|MauzmX$M>w>yfFS-7 zm1j#BpPa7b$>%5EK75aRzgVDW#nHTP2^XS7dtyUG)A6W3Z7+_9vK+( z?=;+Ije#LCY9MzUYR_NngfzOGif+aob~TeRN~$ zU1`HR0~@&H>hXR!AUm#{Rsjwe+ijhM>MoSj>2>Q@-V-%vSp{n;)PDA29(Ss1#e+opa5OVE<)kEpcA%0RZYMJ3-ZWWCJW)o)94T6m_;v_Uz3+QSAI$PS&+ndHfUkW|lod`x^xaM2?aD0*h z2D6B$qB63e`EU*%KBORtNQMFgl|jg?rD|JPs+Nf;#V}G$%>{q3X-s|l3mraOL7YRyy!ql!9{Ho)F#+%aG5-j0ED+O@C2MIU*SCH^*2`hd&7s66U7bf5JE*w65 z5a0ZVe{e*yhUS;dFD&5V3olWI`|tw~HqinFkgE5Z^cTriscfd{)O}*W?<>b5eJ2+raZkHOTgaFFz9FqEXsZvx43bxQhCza=5Kauq zjrOK3WuoKD5~>`#DVTiND!=-`#|^JqnRj8IV?tZj-N3-o*2a`P84%GalPJ!vIVm|h z1;$V~ioxOSsAM*v9LUH&Y8oc_2W@N6)w>p__TDAJCrOEwXcxlW+cl@b+EZ=HZ)s@) zm5Ha2DW5<`ykMo}5dB&NiFjCOxmp=x5ux=YpA(H@a!B;R$eC6?_an_E3GOsQ*acyf zo)xYR*G)k*JLbqwaHSl^Qmcvh+(P_pjb^9(b|8okedtdSxa4`e8x$CmvYDb!e&wdF zJ4nKa4m>y!w{jW^w-`PMvaL=k*lkdBo%%4=fuqd$ARgof+gOq_ZtH zeJjQp@>cIWdGe&zOz&Y<#kv>NI%D<;O^q{tg%31lXQ#1w(-u7S~nzhF;;VKShF^<-Q5B*#vlg_RlboZ>m?YG^CJMOq0wX(6+`HYBGunm&Rmz{|s zzWjkrs4Y*pZVOfD+z4^t;Q!cz?Qa-B^v2O=i;w)3zK{DuU8v2@DdJhjh3OISI_Wg@K0+mF zqbxHwwN19nW=SVtx(c4tg%r&W z2%;!LO+1sqwXipzi3?J^Ot;FzjsxJQS^BbyI33cKu@+eOWVLomf+#CZo(LtjYgIXI z>+T959Badt=e!6rwTxyi2)&>)Ze54&p|dgi#1GVU!uzepdJyS3TR{RplG69V@)QcA zdy%S+q9;`_Q6%mI&9dSD5d~U&UJM#E<02lFXr4&BzGH*K#VTGs)HD{vsiC5$O3KE4 z;my(hli0|g=K`8mjg^TFabb{R=gI^KZC?jq-F{#H+7}VH@OjT`_^i|}*dCaNu2|RL z=1D{y1nvYX__I7*bnKZ_3IsY1JhNYc1vexg0Bdr;^SkfHXFvBD3=glvOJ95?%7qFh z=BIIR-vQit_w9nCtxjjCgNKUvZ`^#mdG^&43g_bSVQ~TYz0uK8egE>yFT*2`Jcy~O z`R1%{5)D1{WbZ?=AK4KWjeEo3Bi#R6xx!zQ)%xtg$T+w^3u#e%l-2Zn^lJvg^vDMX z2b+IZ9nA#^{24D`WW%DuLIuK9f(+WG5iAE=YpppEgn&tS^57BuAq>k0ZIG&wns^92 zF~ZkdJxPcYD0!N-nH(~}`{6xWnWTZXY#ToD$xk7lUli$uK>;J{1eLpV-El?V`<{LR z;}fUR*4lxt?k=>pcHko){;1x&TB30WGU==gImeL}3rqOopIwM`onvTJ3ux4ca4;uv zmAe}7%&Q*7jyLupa>LlKv~ztn-28*}G{Unv{PVUQ*cS+6c+*C8J^lEWAKN*O#^k^^ zZQ5c^jw91^MWI_X(rV`;8bE{03^^3UxS3r91`jB0W{A5TOLoJ9&ZL6et4SkuL%Fzv_hL9L!u-*yX;B%GKUCd4%wjL zmVFEM~^z&0lWm+r{VT*dLE_+2AMn~j(_0_6fF4-hV5f-h+ zZlwUTdmecZVqLP1G~Sm)q1@z56Oc0UqrJSmv>#n<&qIiZD^th>D~mV9U@3gkwytE-$W?v;^4JTC3rV^L`CTuR|%6u}`AL2d5kNo`L-6UO9dezDto#AqgZW%4Qd) zksIBIcwq!Rtp&tGoXS|$TBM|sXfpgs&ISpSC&se7aY&3@X^M$V1}Vo(REzeQWe6tG zY}>aMT^qir|2bc%kk`OMma#m~!22@(K1rfx`yHQ#C>aA*`m#m?x88O=0=srSSCUnH z0}dDB2eF5qSb>9tEh{?Z*NPdC3}!umt}gbVQ);%V;Utm96u$qN zi%?yj7HP5GAYDzqZmjiSm&)%b0lBDbIv_S8uuD=zbZ-LnHoJcCek8} zEfG^?z(O>w&zxsXd!2t~tFoKyDrC|@>DtMzmCy4MJYmu+L$2=L@=1q3J8RbtxjuNR z|AjF;yg_IC_{kHxmr~JjjmpcIoSYTXXFNPl#IyEBCK;>i|NOof{k~H{cEY+PRE8mW zvs}XKUa%2e$ue5nTF?m5HW48(r9V2S5+?-LEU2K}QIJ5Tp->HvAD+iltsN(ipB9YH z&m;oMvZqgUe4@qY#vp+Sootpvb7%{><|NR0E`lXxD0fq5Q(L37fADY z@}7;$MjvP@nQWz}02uc!$>dxoBe+u&h)E?8Bv%S^=*$YS)0KLhV3#lHalL%fc=sJQ zA@KYwUeF-SN2g%|Ll$jo@I|>Iq8g!dPDbRWBcwy;Vy!g|9q>bk54o(}A~4m8*4(o*q&5Lg&F3yJ#5D zlk99lNrr6kt6v`v(=!;@zHOVe;<=d($`WZQTnnJcih@ziNNTFA0@Wp4_}tyd7Y#uu zmQ3J_?@i7X#ov5wn;lb{;ot%V3sO9+&Y*>52WEHt92#YV`Mv${*DJ^5AbXECcx1vO zj~?Zq{p9Cw*sxw59lnK;$oGAgfys#paSW=J5@x3tq(39RgnPc4X6PiI>GZTO z-M}OMkWG}dbL1yvTHp{wv{uGzuh@V@q=;;57NIE1ineR$C{@0!){*D9Vlv{X{Sb|c ze^jcLamVAcC+%9P7)!ox9 zb$Nh!1-Uo$=Ko7%<$B+9=gkQ0+_|$Mh?#X0PMjk28=zQ5MeKJH5E zWXv3Mb#-Ge--qgm9?J9xK@;|J0E<9$zn|kX4eziS*=hnOvre`$IVjGf1H66`Hho6V z-{ZZQhP%~1`QkNc^SW{Z52ckI*t=ZBnnT<}2&YC)c1%uY{<4ElKxirLA_8y;HGg@FYH2b4*0}1`;myG5vv8U7Bws-5?Gqc*|fG8 zJ6@`CfE}EW8IK`IH8&Mr2o$lpi^ga=pO+8us+V%`s!AN9MA|f{Blr^oI0SJ&&c@>s0 z5 zBLf_w)K(sHniNjMf!D#3GCw=Fyo}kYIhC18WyhJ}9%kg^_;d7B!vp{TAOJ~3K~#SK zHxow*F_|WUC$f5f!a&OhtiBw<$;B#}0l53lA0zPGUAr6l2RTX(a^kQir#&8wNN9qa zgpnc-4<{RXNym|q5o7u~k__Sf*T4AkIB9Nq0Ln4TWTd*AzR6pOrZBY$wX z5dXZiupmu>o}O;J@h$%opZdh75usyi0OONm&AR03l7c-jQ#V{)PxKC)o0^-5q&v+} z*Uws}+{BJu3hPk>{w@iE{s9=YoCR zo?qbK$A2C_lZSyp0tuk2gBGi0Mi7f8^(;R7#m}Q$SQ1>$PK_9!6^FqffUkY^8r*&7 zy<+kb7F>qHeC5#hubqus6@O!U22WPGeKxodC1^PBVZAIVMa2&7{N8)dM8oZoYFGcRjLz7~%IoLxDyt7{-pX&cfa& z9!HdAEkc(3%HHn)aNgKFHn#v7^V7ey*Wygt`XS3=QGxstwUG`k4*t z3_B>DXJXs7t#b4l<;>Dr*@%Fw-HuI6Tf1?!;+&eD6_o|uTmw2kjiYw|drpz_%uX1H z^5r%t&d*-3V8D1nz9hoW@?{d=+UI#hmOV50k7*jNk{AWtmdud2$j_LVm{v=i@1Z9b zh=yMQux342R!j$BHTxClozF#tKu2)owOoEiFV5_z(+nb+rJx##nl{);Hl@P#j$(Sz zv;>qeNwlesr;pF$(PPURfy{Mc#|nK1*OsLlmS(*8T@xXda;9+xczv`#-X?KPeTN-C zhon1Rqlky{QA7o-BTo*+AtM%G+O)&fB?W%p`zxQk30YB+6*G>5bU4UWAfb{&@XF#Q zs4IdRKI&Qn`Zt`1aL1Xb1T!wE@RLSqL(`}Pq9_;hC@sz)jwQ5*CJ>F7*cA68gE>PB z`J9ZvPI98z0F(1(utU4$bvekBn4MivP{QGS)l%6yD>-u7OHI43IaAzndK#-F`@J9V zr74z?__C6|qj9>4oLq~$?)WhRyLMWTKn6Xz2mCNbY~&R15b|b{v6L}s9bQYP&blFC zYt2yS#*BpU+Sk1n9UWaxG{kBCt1TvguYC1uII#CgBc?Eu_v1hrF~<`)bL$RFOikj- z7hZv>*#-1=cVffljaavSSi#1vKfX=%m#K*{OiqtmyJnrj7c4u}l@T)QZfk9qfYajA zy!Z;b&iOfQP;OKYt$61vn9|jyd?u~~?N9}7YH745k``(5K{BIu6BD^({CjaWgv2*o zYt7`;l&;+e0p5}Fp)?Jfs}HVrJXT&YAq>^x94A8=mCKY?2N8;L9g4tf_nC-CYF3v| z_-`a`^4YPimG@+O)jQNMI@-DBsKFGY1aI*$?y$;&~TdhG(9B3d!;V`2DMUj7VTPRWm@aT7#2H6&1vx z3=AS!ZwyhBK7tctHQaJv756@qM>xV^Eg>6;tg~eA$KO?H$kh*c=t)TG>l@JiVc>q~ zzyY+jn&?h0w}4QifOo#C2UlG&h*~v=Y9NZc?l0iOfBOs?k(AIs+J@l`n{f2_af6~= zw~zv-KnPzvc?|2*K$}&xerd1!=EE3CB=Pra*6Wt$=4WMei-nR9ze1^qsR^D9L+*IK zcuiCsC6UT^2KZ;npp*MXYH*DP*uH3T!YiZ9dCqwbJoM{ZA?0i}THfIFv(Mh)YR3)h z5OA|eCMKsbJ2R^_(0l<&n3LpOw6-%>%Q8ntbx==svuEf(+Xs%4Z+9F3eg+BMd|FR-X*E- zlociP<0dV7`$4DFoMF?b;_6G*qbqHt9*Vow1C|U?{EhwlwC1I19l7PQ){f*i-Fu~m zn;trfsXXV!nByk@i_d|uJ>QSlPUL~>XAXO1t_Bx}pTVE=_LA$xppSe5Dr)-nMIt(W zn3vf$Q@Pc?b^(jen0Zcp$=S-UR*LcCxs8`bLaen2axIJpMh+ayw!rNCg5y)vG)ll) zY13GH?n|)LU?-Y&35b^=-HI5>wFVYvCK0MGqCYl^P=LvuA-twuYpsZ~*P1C|h>ax@ z7Pxtx1hzHGW^t}ajd~tsn}egDV|?VMU1}|ChKX7oog}lB>|8tPsv@US8y9%m%nWNY zwt&^%>&`oFM&ODou4vGh$DS)-~Kipdf?#|dX^h(p(rsJ!uc2M(v(NBIU7OD&o5yA zzC&sQoSB=|L5Ri4$hF9jrI99jfB-TX9v+*_#>M64o0*wWjgdX3T->>Zc|B-vOt?u` zN31@=`o+xLHg!y;7ddy=)<}V=WWvN$3Z>4Ba0b89)xc@k6$pbC*P{gDAbF_o#@E5`B%=zb}yljnz&hWMD*MbQ8wT z*m5SO=jQN@0#*?kiKFuPl)o|2(-C9KMA-XDDcfA@vI zLT-Kz`QUbK*r>PJ&WjGI#A0YHLTZJh(L8?im|CLDaV;xQ zBg*p|yJPsnH=T(Yo#{RytS)q~sF_I;LY< zE}>A!DZ$vXWs~G(d6t`*5qF0ISVMzMNzV%a8M?4x!zK+=<8^4pjGN;?CwqEy+>P?J zt{-O1CO>Qpd;jt^Vn5E^BMS;HT=ztCrivRPr_9z7^XwctMLcbwfJz%yUR;?wK|Yw1 zKtgM47F}Ik&48W}Ft3ZwmuMjQWbC5wL53W+%8 z9nx23__Wo&J<+2s-hNu*YtsB49rQ`t3a5jeW7g&;nAnl>jMHGxOjU75`j%~QN{bet z8w%(XDE>|=owN=(7pUnO*Bi(eiu#{{Ud(0rZ0+pXcs}ACXQC8fAZC7vfqy6x)%};3 zW|74_TEf$2vmIBfSqf@OXj>+46M{`e*K^pEw3k?lvEY*37Fs8#jI2Ks)p8qD_hTc0 zZRnUoIQ8vj3}L>-C&#w_D;AR3=KIu8u*|W z=4a8-*`NgMxc>SZao1h9iqvQQz%en3 z`8h-{Ui51(Qik-*GtXdQX%3U)Q!?nR&-h_Vtr?E0wtA6ZwJ61T(t>`>ff{@-N84y9 z$e5m;#;H@M#3ShG=@A)7ei@R|&p&Xpz@L5h`WY>9h=t@gU6cZ9j9H9OgUU`3@bx-rhm&I}NU?7V(xh zy-k6aWlQGZJUr@&ncg97*|Js6E?-!}=*bbW&8Z-kZD~U)o0cGO9PZA9q5ZA9$!W1pSYspHA%*I(2^NV>o)mOgqYTR?%tq9ik;gi3=MM7G3!rc6K-(sY- z_LM+{2#yoNV77sYS>Ub*D)`nt6Y4wWHPToZ8=p9#9c@iNT4|Gu%rD@qHC6oK>o;Tb`ZOk{$~Zm|!~4JR5OVcabhNc&Sp!^5_SU3Y zgGe+Q_~^m?=uZMYiC;>5fO`rdWD7NXesC@JEH3I^lc}`M2WKzPl5wxhFU;ZC(W9<2 zAYh_3gvG;QWz2*?&0#nKULc66scG%auFej0^>n&{HiXul7Dec?Atl!{aO&t zw{PI=bI#UYTqdGO!egZ>ZWQaglao`;-{Wd{y%wK^ng)sW_p3gvanoj44bnEDn$^jM z&&*cJUzBuaZO1l{vetl&h4<&iKG!lo{u>$d>(;K3^f?E>@yM5pbXo;vo#|9Y!PNBh zG;+Bm-79T_P!^R6Oc0K1BF8D#pOKq=LL$w8a0F|+qPTo(T)RBe*1|VZNsl(pTCORY z7e=u}fh!7IIeF?@9ix-WxZ#m86pAGw(Yyx_ne&=We2NJUxm<>j*o!ElA&?d%In_wE zK{_PW_yQ!DuC$-4Baeuq)5-A9$+#l+zQ#+i83bP9-V-|M)VUUVUQV}xL4bUhlhxLB zN5WWIDqty>*Rx~E)odFOPGzy~tjmyZbV;gNF&|r66IuC1ERCZtdK%%7p^&B=X$hSi zvs1nF^QR0=G~4b28p)5lt{t`nbL&VjiixNRN|;WDyJlIbrl6GF8!t?s+iU@~@YCWe zNBC@bqOj9Bb!&6ioi`z{dGoOID?wyZCicSxY;B`suGw6Hcw9qBhBs~2CZ#@se_(vr zmt1x!)~{P9>0^}?{C-bo zFV?O<3m^E3|YtlzK+lcz_JFXXU&eLME-A4lKN5aN*-3b`fp^mSqPxofd|{Um}_c7)Whb|8kf z)_^0{F(_gH2kbo(#+yEN44bx|C(;)87T1kNl0lEp+6Z?Rmh*ayHc-p=VOu24`ypv@ zsDFTYAdVd$K_rpJRadqi>fvmjh)igQK`;)*jf z4B_yJD#}=c&-~L-AQZ#Q?5to+lO8v580$Hpl&b{=B0)LDG)*#f(zbMl^NS1Ee%3Z+ zn0y`#d>QTn!7@sAd#*~dQo;KkdsG2J zpG{T&e|nv)g)li+!`>gSFCgM{lGdK&WgeTR$dL1|a><~`O zM-U)7Bz*(x81dZ-9uejB%kH~prqZ*QT5d`;8^Xe5LE=7AQ*@HoO(LspSD#E-g0rHB zu=4!vjQZq?ak(W6D`B~{MB2QKR66Al8`@um@F*5bQjb*Wol}q{8Bjqe7DvaxRzy3t zqs*aBPTwIENnmDn9+AQbx+4q{SYq&~2YrL%I4P;{fuof!X-_T0VK+(Hcq|TO`o#n4 zRWga>o4Z<>1{2m}}r8dLnIKf4d#{mwt5R$WFY z8o`-oo{7_^Mn#zOcaT=IS?$4fe-xY z2b*=y?(Q!9@%!F}fBosb_|CuFr03!ZS^NxU&n!u8+PD=9a}!9%qj>-8H{#UkllaOH zj$xr3Ln4(`4W7J@UC-Ho?cHP8JdnrQz5rqgDpZP-ZHG3HKrAza%U*XIx(3g~@so#i z59;9-?6#uoP6TLnZU(7j9ODy{swdLedPAv6pY;X?`?^st<-sYj%QfJ?U3E3C{qm>L zo>|71{%9Cz6kSbUCexN)HpVy)>PKL0&v&_?hJ3Mx(TNDY_>F@YDP&NoyG{ybX&DOC zgj6~*^uf-PFJ73!t_7+zy8I^hCFRdIZ`$niD#DV~W*|goM`uMxDa4>wL2q&b?|b9< zc>SO6L7~p<$6CvbqtQTnFo-YCOr!gk6eRp)Hi+p!03Xh_Vg1_mdghcj_NAv36-C2g zOib8W^suUgTbvW-eXgE=;GM1C>wLOv*RGLp5BDmEnl){Zn`Fyp$^e?ds-S8oiA&4I zGS}8K&d?wot{1cMv9WQrJ+i#RV8+iy;a3I)v@5g`N)DPWz|p2-_d&Z4`qiuN81$CS zLw3me_YI*?>Cw+DkW!?5j{Q5GBZI5DL%-@O^=7jaS~A3rN!Ir5I~07gR?YWhN66IV zqyj>AiYVArDieQ1f55o75#5f`tA_spN=Jlo{L?*$F~984P1!95W*+kP^2zq|JUev8^fSH;>usR5WLiMLb>U|U z{dKC1^n21Sa2+BV)~5iH$eiVNo(O5`fmVLzSI_Y>4uAzWUNgZ5b3_X$B~2a>TVQz% zb9wVGL{1o}aW6N@${1W=ze`iYvR5NV*M zwaq)*<2q07qE5o#P+voExV~#}snuG2owbfjF1bWQo|q96hPT6OKWiL;kVZ9McG*SX z^v5Um?Zr2~`gP=sIo-&vojY;r)QE;0tz|rf=4$x-TrbGNx=b@Gmsn6; zya*rZH?O@B#HLMKC49kyO5+uYa|4-x3xg0EAZ}o0I|~c5I6X2>sh}o0;Im)9Ir(*U zsiA2Y9gDi@_+6QTe_xG2tPUDh2M+%C{P$Or9H|?j&ujn#gKGubvvVXIO5#h`U5k3n zq-@<;a|geIx4q@wkY8T9Y;W?FTm@6fCNx(uToW#;DSR&VdC9h9p>zb0ENOi8@YC z1@VFFj-e6dh*=BxXaL*WNIX9dJOlMdk$aW>A*onCZxc3Rnl zHUHAGAo|X>82Y=4c>GBc@EZ7U7X>jjy^OEi%CX%h_v_16ZH*c}J3TEv0!t46FR#0o zB8Zo(c>ll}WO_QWFrPDKc*!J`trknhdl(awrlM)KgJd@Q@aFsg7m#~HzdBGzL}OU9 zW{vbw%p);oU|m|4IrC?Y)z9}Q zvO>~jdrP}&=6u#1WzXrcMexXxddeEXimsMIY{;q;$%Cm>60Pm+YQy$+tX8q-Q7&1VHb0Lda2_49pv1}%<~vMXkZZ*fwuZ&Ik|ICT zPd;o0^{%9)B!S7`s+Ms%X5OoahelN8+VX#Lhg51{Cy4VWN(h-)hk{77tUJ^RwPm4n?Vai_H+ebT(7x&MdA(*8c%D&^~gT z$_HG&1xht3w@LY4zEr^jz>)*!PMo*%0_=bK8LU~eR#VLWS~I&%gj^_VwUS9s&wz|qCKbiTb-lQ7cou!FlTPY2 zj6DbI`11D-Bav(qDw9kn@Ya_P;U&+bZbBLNK3c>JFYea3?qIYZkwgyy^<}*I19#!X zwCzP2369z2foW}P$4g%RYJB?}e~aZ}Uj63GCI}TSmrF80oXV#|CE+PPy9)ZcyCj5i z;qxxXwg2mL$fiR0%Xe+UP;0?5LGA-Lq{meT6eRfiuEGeFS{m4YcnP)WI=uJOk4YVE z^@}Wi!nTQIs#ynDCMwj3aIGh{(Lh>u0tfAY>wj7?AD z=l6}_(B2yU{Oz0Y>i7H`;f5?prum6r>CdU83X!h@Bf3Zhf5JOa#j3IDuc+S zmm(Su8_%Gx^>?**C~+_) zK05rEb^gGN?$Q#8jD}M1UimDTMe}^i?l?9$7nI|vD|H)jZ_syC_Jw1skI5ewQ_a>d92umH|@ zWn2@MaOv2jzd%-hv8bS*+zgVA4Q*Q??lpt8hH=X%c0?jG*HN5~vXzvqlx&;`JrfQ{ zQs;=3oc+85<2G1XMyL|?Ey@*L4{acWUpjJiM{wRloUGq4y4GBPVx))G0MS$yxl{X) zsU0`u+Sy-;F*$yKFEx7f*UF8xW(zOT0z*Z;?uF|-5V6^8f@Gy7;Adqi+xvzh*o+F} z09m|Yd>Z{(3X2vHDBu+-($Gp?gKs$C@7&^xBnJQhAOJ~3K~#CijR>q?H`GwJqDYu^$RJ1AImxx9?0p4p2$Va93=7wp`r&3j<~ zeoZ0tu(x+&KDzM+kPna~v%$Ur^}chwC4(00cdn`5mP}7NT`oQeM1&9-C<@SZ@wJ) z@x6G(rAs10mdmV-Me#S^KZz$#h0xyKiC~Baw~C#cLfHG{Q&5Mp_}YV*$g!?%Z1{P0v6L%FrZbu;!tw|e>DWfaP66KYlv-15pcvPI&s}Rl zW4Ue!FMaWE;lm&OAmWh#-t*hNIA_@Uro%#@+$1|H1=3kH+h=*NR_b6o`hnwRJp6P3 z|8)1bYmqXfNKk)!yMhGnb!9X87c$O2{+fGF~S6blnwTX^2{zg*u(!_KaL<*!W5DKXyfKG`Hn}jrf z{`mPkud)>iJ}fv>o2?Td@`!+l%yIVC`$0j3-3`IX1qi z_4eHjv~O1Wh$@A=U|kaH+A0!4i%WOJCPS*H-xKW`b>xaBqNKov`X~+Hhd()txhkEy zm7u+YGDzM0glQI-?crzA-fC!SVKt zCO9E9Lm8~?nJ;lT+yr6GWj$z_0tN1`K*a-5p__2m7osUj59y)J&dp)pQ%~aD^PeM! zx_94Ry+^Y)vMS?U*%(1BBpJLM2E>d(1V0M+#Nv8iwmbPLXv_#mP$ROzgKE8_1m3d<+_90n-9ZfOU`0tH*!71c+NxcE|s@{?ac5PWIG z2L-lwEUV&6_sn&4)5=IbB6y`u?Z{VDL!*EXkr+aIon8I-^FRL}>a~&vO;L1a?^Ap5 zqaXeNljDonuxT@fhldcT7I5;^DLil2#h9KtiaUSun4ICs6UUkq4+a=rU407T%9Wgu zm*-z}5n57LYd3Dc^~b7*zUImdE<4vqNufXm@tD;lt+r~@^gIR1kQ*RZs9|z0 zfj{}{N3j%WZAR^0a+e$mo^cNFQCUj8vZuQ7;zRPn))5%eU1-v3~C z!@tf2QRFz;zCOvVbAHOvV@HKVN&qR7K{}JgsgdK#ypA3{B1fiu+Gwa0BxfHr=jF8q zd~nQXX>fW;=V-%vdv-SakZ2s8qV={bBciOY8+)wYe+F44248GDHKH^FTsmDjD9&8pyNZNz;-tcI0mbuTE!x z_KBbEYw~o&J{jSjjK?B)$&MDJBV|MrF+}6+TA;{k5Yc!-Yc9Noi6Da_=}|Ce=6yHt zwObAV5i1+n+L-evO2g+XT?rE|aV?F8m@xn_9S0-+uDC+i_0tpsvbh`FGkjJ=0qFy{ zC%89?#WEHaDYK6Hz6S5v&jR7k@VSdS zL`1=7w!*N79&q6)kgHSY%^7xa;gyuw$<+B!9(kmINQft>Ido67TL*(U8 z)P7=RMk6gaVI)Ta(BLbFGWcMSfsyg)i~~dD#qR;1M0)bAe@;TToFuPgicINV27Q?$@Q#*&LjzSrBN@Ev zRj;+ z9lzDBjK|=!oz>s>2FU-e)#=={Gne7&?~*`SnNaDoU*C%4RUDZeeEcszgVxrB0taJy zm+;#E@d|9-d^SGv(T^y5z5juqV&hO3{_Y#!!-c!f$Il;p1WzA0DpK9kPd{ZwUlOK4 z46RwKd!HO1(Hg$ts!MRu_5uQB21}+Dz(>aoT5F{6#eaMnQ_FD-4Xs0fS$?sA*5DMr zckSh<7Us|hL=XsDU|6jdq)J$<_27+vb_=G9EeJ*85=>$n?b70c+HARw3OPPycZ&WYf+f4vjYpdB0<$Vk|nOfW!8>I@o1v>1d1YZ#v@ z;=r*8KJ|~sQ2|MBW)OV$gE}z6Z0F@ncx%J6OvoGx35^^V&b_Ye#ywNk&IKhq(3K;L zy{s(*kFK6Bgo6K2KOFjo3rUKbmkZE{;>%RrGU== zfKI}_OCcmmHGHCf04Js9XQOIujJUznlt&*KIfa(?Hk3J4Z*dNzBd4r{5~RL~At^cs zj@-xnPG`>ly^aBE?(J=@Hq^`HqKrM0rl{%sCzB$E%0^W! z8L-YJt9jFwtB$RG7jRPUR`MX^@3ZM@xr%78gx|WL2a#Y6=@x^P$m>ut9X3`z_t`R0 zKMkKF%D`#14ICR?!tGDaptJM66>SM1W_nX@4z%lhn53HQ8Di0g;OoPWAwqVbo)-D33mlWQf_l4FO|9%g#Rf zPI5|C$3(nO@mgF!AVk=OOnMgXo>hWy$$7JVQ^Hx66iUR8Nxnl-ympImsEj9O{??Le zt^<9zI799;JYwksO0__K|GVF8)EkV3O)7alw}>16n{(Q0;}T zW~%w%godo|)tnV0-zuKoe*mK+Cl!r)XXwid{>JINxak>rcXo7&_06sd!8>kDG$X;K zrNw5sz)Sr~{m(gb857D4FBegv>Y-zUt4CNf!i}UtMlBb}*C2^D%*@THoWi=-i4(`0 ztZ4p@pA^aKj)x<7)7yR*fqEG?-*h7i%N2E2@V-g-Tfbpgq9?4%`F>We8HsU()me{a z8yep$x0qLO!iew}%L~nD#UTs6gkT270;1LB1RoeU&(VbU6qoz5g?qNE|7~^P!Hq$~ zvFn0M@rqZ!T-q4q5YRB~eezKpIj|px4(`XHL&s23jTmUjQb;PUGStG-0(!dpu(Y^{ zR5F3X?17I)(cjxI!?!fQh|=Wgo9)y24I(`lgybbhuzjC|R4R>QgHti#psxdWlr zH8}75i*e%E2_&i~@a<2XiF&Q5E|+?p41Tt#IkA;+2jZC_y#Ld;;-`=1k#6smK{|Qj zgfc4{CD!6;#OG$`(bwCfLz!*K3bLM_P`gF&=?~#|t>M(1%ZaeVz+e5vpW@W<$Iw!}A8-HI9*N^{lx=ou z9Pgi+#kvg8{_j*=JXi{1HrK!nZSDAJwngMRIwSHul$k~u#07Bv`RC*Q2OpI4$Svg* z3=!#I;?S&{GZ1zvuYM1E$HsCDxk)nm#iD`=B13#ua$*{&QQK5t9(7_m?t?G?TX%^%Rn%(YnG9Ao@KV{vg>of2XUF7=T?_r{ zqZ2={hhyeXelRS)$pBv{1u zXufR2aoVTGPGWI3k8*=^@+>#xJ^MrH9lA#jr0L*T)4rVGkp%zM|Bgo!cn#*n3_A3s z6^kra^c9So02B(=o<)h|FhUp_>co+ghY<^>v2*thyzDox!c&j!!7aDkE;y2#_T?{o zA-?~ETjZD~CnrQ`;`13^zYYVv{W^Gi9@~SSt~L~x@_5hdw_y!QixkYM0i`lwe$!b; zy@ZQ)_TaIDReb1+`;hJ5jO(uZTa27IjYod`A-wmsts+{H-(mtaTx8bglL$rIkw|so z!N(TxmtT1hi^T|9x;ju;Dqvz_66-f?z|8CUv&w8Mbvu~J z6eWscdAk9J-)`OI{d}M2_q$ch^1kyn#_q1Jy7zzo|KIQY&Uwyro=1BylkIZ9 zn|lYmOKC!>d$j^8H;s zJx!iL-Wz;BNeLAj*TtwFqhyev3G8duu9mk;R#TKtN}&*sKKh6fnH;<+FyP(DJum6| zXD(JIeQDq6pjkSAR6&CVka#aFh&R>Tr)i`x?>`-=GD*Vm4^IFesxlISXOejZQIGD< zuBKXS_HbZi7{tV_ilX8X@0E2MJk6rwTS*8>Ca;-2EjTFKT3h0lOS)ryZ&lyh-itK4 zB8D9`iD5~UXrW?~rqEB|?UuIq+pq44=^9_N{)=Of-;bDQo|pG3{}Tayem*vA+AQyZ zEPGGlMZyQNHa$HV=gyyZf$2uL;uxMl#1@J=;yJ}52$~WH5>s0ADS6_V__aA_oM@0} z=2o!Kjx-8s&YE2y`RpXIw2diTbQmY8W)4pHFd%^$y#-;?h&&!PaA8{eV`$S&F?!!F8C~&rJ`d6Ya1t0h$5I`Y zPPL~}qM#x%8+av@Sl*EN({>B`I&g=!S4ifx0#rvJ`M+V z3CrPD2^)3ejnK*XB8*pB4S9i~pa(13tFwR&7^<*>vu=3ir4r#9W>i7 zxkQ0lOx+eA#17oq))d1SXYC$QaX{botXpFHmaXyq2frUDPacU=r%%Kze1=4v$`6v) zmDp93irFSqa!wL z+$e|*L8~?E)pyMN6R?htGD#ul&c|v1<5| z_{b+d7JK#{i0k^k5`C>t$KoPW5AKn|EGF|Vwsb_PJREK9JxUl}^M(({$l{u4>qOXO zEUvnGXMF$R2V?!3^;%z3GnmETIaSquWL<880KJi1zrM|+8c6O*$_ z6zYkvQ~=EgF`tPrGjofv|72Ty_)C*e?|JuoW8#Cz6lhMFoi@RWN%=(7i|; z9+BR@eS0DxdlCgChi7x(zyayFuun+DbQp@TXBFCkp}|yzQ}CEeq>#$|wmt{l zBJQnD4szwHq5)(R#lrdd=k!hcuGjfzPScoSoI%VYyFUUxtiU9dcm7?CeC5n}cQJBBzvGEoX zINJ7(F(Ve`$bMcoa6j&FniO--jjCPNx0ZU4Y z+LB4HA`4fkU{7tnW>K1Cs#W`?wM4Oh|Gi(1!b@&{VM7F=>SCNbcOiyX3=2H%?m?=# zQ_NQ~Cq~T5W!t2(xV7+-(FlE=4E-znl`u$IH+gD$BKGXwD`+?~f!T;15LOa%wzsD@ zy4pK6`X&LAbdXjXMjkTDQ%a2Oo%%VlT;05e8N`_lZE+87Sc`&AW}`!ll(-PO*vY?} z4Vse*Z7}`ay(#*AWwz%UZx5VH6{$NCXB1w`a7fyIS9N?vLw6yg_ zOY2~?m3!mv?;VZz{>3A)Zp*fqn4XG}^CLRU2ZmSZd6*2VCa!{})(uG+y=)2Suq4PJ zCgQ!nc1aX!Q_+TKR*SV62tsV*QcEpbh13+{+(;$9yQe+w{ZUQCPS#sansfVy>X}2I zV6jM2NcEV=w-Sqi$K#qz0ehf-Ktg7W|7OCe#+H&>E6E!Nv5Sx72v@5~pJLOd4e|az z{o|OPnuuTj&EJZV3llNWI~+e*or+z1_KB15e`@gb!>Ll#EA{w`fx$S^joyfZS{6X! z@2pwYRdY(9g#g@8_2Yfh_3~IVW-VJKYG&E9u?D!F>%5n{c!Cgu7S-3`c z1~w70egX*xpV4|DOBHh7tGur~aXLF^RtAnCU6>-vq(Aah&f+BvFIY;@LG$~PWQ3vwMuX1BHUU}n+=xJ|@a)EEQDixMR z+eZ`oSvOr>9V(zeo)=~pVtx^BnK^fwP*V$bQ7({jpCl=z-JUpfJSSouNpOz8SpvD< z0ly<6=9!{OhqO=%bHkWwpvA)T;vTG8wMGRe2`|VHYlK9Sv3d4}?r-|cnglA)<^&-# zI!(MHh6qKHfB-)^5Ud4DPnGC_b;vB#4o-ak=r7w7K zgMddueD=bq#>2>x0D(Y$zjAL0IE9DP(Pr3&#UO~KUKNy>9o*>4i&VorI%7*o2m?VQ z#u7W*I@OaT!8m;M=^*<{G~VcB%%$8B#a0gXwkQ?cM=P}WK;wSXYXivuf@OiJ*9OsY z-Y7!uu{6gt$?`xf+B}ErjMbSQp8=_81)*dG%c09c#7o@o>8h9jjB(YmL;GUi;iK|S z&s+o&A(-W4x{M?l@`df{J|_!MhmQ0bU-@mqeLHG0B`I1nV$tJCJFmJrMlPI=vlqrzdWBVl0f&*kUnyd%B}WyJ%`6-u=eQqP1bQ!1gk0hz**=lL+p`dbE~Haq!q& z-2H>LICil$4jeojAXZ8a2vBU`T1^@UVjx!`Qn7x$NmT(z&mYLsq%-%n3$cFv#(3tL z6Y7&%H^4LL4r&;5b?QK(y_5MSe5T=*E7ivz9_o+I-tPEM?|V=D;rsqW41N9!al~RSer9y%GstFJFH)@445Q6svfzY34baceAN-;Cyveg}N-3H+N2#Y8!Ii1p8h7?LH zoS&~oxsB-w>l84F^Qi|8$6TYc=?}oc#py!j&3*9H0PQ=IF{##3cI_y;)l5Q$JM8Gl zSgcw(9P<^oaETo#VV)nk;E_(w9nceW5E40_^^r}Dq$pWv#QOCceD-LRuPA;Rd=~4$ zkchTvqKK&}_6R-2w8SaPGyqw!}eLUQO^p3WLP)(c`EwL}+| z32BU*GnuoK^Oki?f@3w}IsMMhY5E}`^mn8L!bOPMXeq&xmO|FmDHY?MuYEoWFL>_r z8f+ej7vFr~+tJtGE2xYO#?1xxW07&gd9b444H{)w6Q3NhM87GYz(s%`i~{5I?2LUGm{#bZ>TgMeERX_M{#5oX5cOrt?SiN-xn#R;#Q4OdV9b1IlI5%4 zS6~bY{zP4ZPR(fy5r|A2BSX{U%5Z+cEOHhBJt#ZK)#HX6o~7XYoo_xMg*N(nLN|(3 zLtWB>Hv*AasF1R3mns1c0-}sa>@C0RS+~c(d)-e(Rl+S~jcgwGT^WOW@`*k1;CH^K z{^;cNqy$7f>+9?`_cL?$nkOK5zYJ9galuRo!c`(EX=5Z2ke=?oxaHQ{ba?RW35r}Z zy?z#Sy|Ea-{DxnVnU<2kS|e_{{@QrWPyd80hLxp?yDOPiJ)ZZhZSnO79*yVjjM#O> zaQyr`o{SH@?>W&@=#I-?_Q81Z?YrV{-?ciTF`eX^(=$vu=q~R;PB^dzqqU6#p)I~} z&%XG`S5HQv)ElQxo)qLhC^I3*x!B&;l>9(&#QaJm(MDbHWPM>ae*X>IqNOpKESN#U zY(Q0NaSxE^&$Bssz7(JOChMmscJJM9t%*c9%7=GPCoPduR4X<2krQFkaB;G1WwVNv zO~Q$O#GsruS@&#m_8dhlqpMVD%>J`B#i&mtE!GTQ@9*nVuk|gz{BPoKzjSY`U9ln7 z{qtwz`mu{rTm1h*5@xCq`^O{pmCNyGLqobAADj-1ZdYd6Z2z6Wno*C@kx^GEa^$Nv z6KVpT`@tsp5!f! zlzP^=Z9zLR%aKn_Oe!XE&|qi&(w(bfb?2oG?92EMUX=y;5=`m5dF=B0TQv=(dk^X zxRTpCB!?s$tXH+KHCDdNwKbiCxuwj6;NXgNF+Dyit_g8DPqV3@O`>Vm)qpq0m^|NS zwPOjgrB;&ACH8doa7dEX%>scl8srWoP8CUBpWIiF8(JNj08I5{KD#9RRj`2}NjBd@ z#~>pqwEPYoemb6f{CiP&=}TYKXfL(JeGfb!xC2X4^$a_(;ayNL0=lAK;!Mf?^?WF0 z@`w8v{(xCWn}fR9N8?awFsU#jffagk`wtw@0-yp@W{2Ich&;?>u}OUV`+Higlf8D0 z4j`(Q%;aT3XVRD8{gzUkKQ|I17cR=$*`!Hk;H}1$p(K7@{U;s>L`0E8oSg9cL#tdF>2Kb6o=i!_nUd+0qiTCRtgKLL0TYaXmuXUha<%eeAEJrMMUibNIj` zE6sJ)qXNXdSQXq#5B>P@l@sCM?Cr|K=~^!S6m|Ic!Ec+sg5u-t)UrZ(!G4h@Sqw z`0aoH`|+GxpB?wyeSb{MR2A%`HJ+UNwrtrPb2HNtfEnoTjQ{p0|2e9QbIF;q6#Mr- zC6TT5>(<4US6roum|)y?`lg%TYlmbYW@8F zYg=Odz>FZz45b>%&qhl~ow8xzihwHg3)Xw){A|4LZJ&+tN?#1ESQTA8y{d9p=Sr|r zkT`Spj4G18uFg0+axn(GX5;Oz+hG;W26`AIIbJu}u}xJ@tr~|;Mm)H`6s?_uvHS5S zg+v(XNMxk2?K&j2%A8R!CyCZY$leMHI3oEHNUT6d^{C2}F|HPP3OJ#Hu9Yk>mS*kE zyUFf)5i|31v2pFXxcU0);^EzoM5)#qKk>-Jaqa9(^p`^|hyUF#Ug-y8g;;15;@w!p zYy8g6jvQ>cUz#~WQaYsPO{>hOsSI6ohR1mAq9@md)MCGpz0VN5ZRItXsC;hA(uEdd~ZlB(0EPp9NR1mp7TWI$E7rvsmd_vb)1 zi@r;3!j`hzbbdy@3W*&pQ!pjwaR`b7l*S%`qGyG2E=E@pi}DlJP0@P;S%V-DoTYCd z@g5uc$h}Z)yjt}2_Q|SPzJVYO1(XO4f%7alAk_X!1yJ@!5Lqs1w#fYxeg)&7NollJ zTZq@(G!*@1cs7jh(mziV4I(_7Cm}wewea zVbxx$*OeTvTs5q5OQf$|P#O8+J;Yh5)XrBwNnUI6tKeC{0npmb z_TkCMj=$S5&WQ_&5JeUub)Z+~Bp7+%GeOXl@@JVC)ggpjm4=sxwGxsfvxv%yHEt!+ zI+oDYGQ@#)gbdu0R*RF2B>^_K5E3^^WLxVoHHs!d6GzOMvx+9~#kGFp-Y-Sr&X>Np z@tyBJEQpA4qn;k70*dlSAW_JNe;)M^1C)zS`qoPogym2(H-Xi;|&3GN$S2S@$bzbv;;RMvM>vrGrG!UT7)B zKzFZ_iLRc$)K|2a63`us16YP?9-08FhS%k_m_KIze0b%MD*YdP_rch=|A>4SsE~6Y z?**Jadj3z2TbXf4Jd{gym2E1)fRq5op+d#0VKQ?dK78^FNkCj71 z(b3i^Sc-+)LOX|_VUE86G+c_2(KGRmcf3QQE%_P0=!Lh(oiBd2+A$<#Gc!~1Cx7;l z7#*Kdk6O~SR8I5r3byb~y1PB=%+K6*>y7ck+n?*IprsVYjva{uhYrPx6|3UfYj+8; zp=!DNYhQ~;AN@hxam)I6!L_wGGg6N~|LimIp?6&q3$qvF(ieR?e&O}M5x?@vVq7wC z0U$N?2oni&na_nMfS7<`!*@ox+#ltRJ_X9Z`KQO?8;{LJqov!tfW?ZQMH!dE@ryA& zb}@RpJG3sx#wKFJnx1&&^H!)=JTo^Ru)Gy8TDv1kT~TOli%PW^PdvFlE>1O~f5m#i znvXp4gjLZ}QjHWaf2K8u_D8h}b2>lAG=iyf)jSi>88P&=_S@xAZ>F{-SfwX`84m{& zs9DkGFsxCepGn9eF#<0$8G&sy!318-o6eqz%csVrk?{YfldyZL7}J$Te6W8o_JT}t z5GuHPPybI$YK=wvaLarH!TQp$ckeViyUK1k^-1{|`B(c%K4cD0+5*~l+#^q4lw#z~yz;Up+lGURG=td6@N?A4Xc}@6MxZm2X7j>4>9_RWIjOjp>4ufV!wq_91QIe@dL{&;omXES2M-=> zdc6ypOE*o3L55IMi$PgVnv2cCAx%bpIw-j{JP?qHb?ev1P~SjoSie5{hKCag(HG2t zyf6pB#!1Ee!fY(e;-PNG$B9X1S%KbCU!H48v*cPdN%c$cloZU|y<+ybB}Aj<8wk8W!v=$2IdJpAzYBr!W*nNv?RL!%i5UgPYFch102yKe#UW%)CSjJp{;NNa zM<3g*06~!L?e2{~`2F9EMulp{L0&V@r9%A1o8J|UT2fb|A{6(d9-B9<)utM|I2l7j zJ@Fs^@I5iN0O_t(Ne|WF(D2H*`NkVnQ6E2gEI##*{~Y5JGphLC@T#k0$C}Cb;3pr6 z#g^W9_Zv1xDXOvN#y^ht|IO#)IhP!Z9mB{!8?IBOUUZ_tiqKy(svuT!ISMUZ(b|sN z3W2jk)Q`XhY4gG9S;n;VNA-0#Hf> z3lV$wJ?#U6aiMQMq!vQ|aBr+zwLZT8@DKHjGl7&fm?gl0R4a>yiL)zt-k2GZqy4pZ z&038Fj$OQ{Kr7d}GW;g*ds4u(I;yl&@}ZPqUiK7gL#?r-70=p6sZc>nykzxhGO&P&F-%+Ie z;zVTzLS;cX3nd{MIbIp9r?|vop;Wia(1< zp+bC4ms@Lw8)e1~{9xiuENxD$voedY^SD1a3$w*$HaBScrf6 z*0HG6JXWrRCwXj0TOo}*ik~li5E2GYZe&Pah0wx+h3_Ob2G=Kvq$QbR?tK$ANGhi! z84C+Z{I$?vL?Mac8xTe-xM(vzzmlgVGGOuJVEL1$yvO?1S*TfI8YlT@y)Dhe8xQxpxmWQ zlg&qOabR#r{o+kqHz&m~d$#+!Jp--7g6YvFva!wN-ygm=U zGH>&e>~yE`Hxa>FBn|}2ACv~jOr|6#4$9KH94)CDpnr$U8-a~r14?q>;QsiR&we&$ zX6EDgi4#g*2K)Qt-S7AfRTh=Sd9`rp>3-qMUyi%(c}Rg{^Omi#Z{I$(q^Jl6`rO-M z>g9&(u8vpyo0n^ioPOqHJo=+2qJMBj+;+WMz|-EYTdKKIpVZG}`;iZ!d My# zr{m<_yW_*3c|3mmbvMS=)fc0+(1`xa-xf#5TBCO26S1lHM4CZf(kRfF62SuJNWsA- z&K1H5QlZo-`RBHdo@ixKr&x{$cUR)RA64S?xp9eqagUuuA{*NolamwC2^=it)=K=^ z8-FphglblNd-&l;ng%KNJzznefx-URuzp>9_q#ucx)k+1n#Yw8jO2SU=hjv3uL@E6 zA1Vi0HwaSE%jLl5;Mu=_zuu2ErqQnUHd)r1Wu0KzWHgkO3&+OBlVOf~;Pj~9aOhB6 zS*s{X_+KFjGm8=XCnENi%kdXOD^knEMq!!doey_`qi&=&AEUW?PG%^RS|IDdXbXbDMzK6^TV*at>ElTu&y z9+32QxEfA-O+GLS6(No~9F)*GsmN-Je2vj(BN7lN>G8J2?1I}nBnUayNS7eFgz`LD z3u?=x%9saCwXC)f_sge(Uz-?E@#hy2lhwi)qSR;Yv%u@<-_yZNvXLR^CKR1)jQM$f zZhjU;$g*0gh&BP~!*gmax5Nvt?2BQnp&2_b({8ZJB8Q#&;3UK5<)xT!9>Cd)3-OIT z)*l%gSbp6 zMkaEh|LmlQ@75u?+=WvPC^@dz?d#I%Njlb|oqG{svXE6y46?RPzTfHsBo|ly+-wmh zIrrs!F(>(s^Ol^*?P$&e)H5qeh;w_8VwHke=S3n8I$20OkUYYexJ%Nn@MhEX8XfUk z%GTN*LG`p&){d~9wD*Njz$64^4xY)vzW+;z!aZOALKFu3`x{i38Z()nk6pX2jnn7O z#i`S$^@O~PYQx$p1O-dU-W0$0Ue6uNNPSGua;-?Ts_Twzy12#W+fs$H1Az*{hu zc|9NGX`~}nOwN)UF*!A^gC?T}mSWB-U&(?qB?Z|po8Fg3kTD=JIDCMR1Eg_#5>>dHbLIw7f0if#~zEGo`JaSwp+Cp z?z{i~`0Cg06MvwM>aVReUUd6&vcSX&?RE+iO*2LgoM?C%X z86`b@E#SFDJuuewqw+uZzu z?8iBLPM$p0?3YeXOi52+>$YubuBt#tghie?31<%M#43j^rXe6}l@*W;$%|Z)I7RMH zbMV+O%tSh30EvP~p=f$AwuwPpy9tGYnA3PN36Nu?p>~3AX38^pp^?l*-p7avzjz{!{gFjU}dwX zY*J^W%>|l`xwvk%e-cqXg+|B4I%D7@6(0BGdQ3L=NFR5I-(9#Scs?Dz8NJ{ctXjQN zNdjvF?f`2b#}KJEE{h#pcP>D)t0!-iIXO;KE6oIlc#}{lA(+byq-@7+ zu7bHlPEhUzN!Y$+YeRxAQH^V^x?1BBhYuSL@9phZC5A45#%+=lntOgZY$oxAlrbp_ z*9~{|=AhvR2^-fNwxLm_{{Erpl-gKJ^!E?P>NTrP?U6L8Z8I4W%RL@oOJ`1=1I^+P z8Diu5GD%N;#SHVL*(R``k|x=_Cmz2T{o)F z>pqbEw;d>*1Ltb0R;kCYzxhqEY89hL%h>D5utP6Qf|Pse%}m&V&WY2Kk3)XwIbq9x zcXKJfniDxak7VY=LY$qqFcpEC>Qt?Zxw$xV=5+k^2R|5B|7UjZioX1_AB9m@6g}f5rcyR8eiJA^QyS> zWiM8r|FOq+tL5>+=f6NV=)vzi82|F+do*%owsS{x^_1i7Z+UZ^Idvlb`Xe8YfA=$Y z#)j_GG2A^LEp3H3Refn(d;N_u`ow#qtvIVB!Id99OdXHOe9RKD&BQ?*8l=a)R*NO% zj@zTHqdVH$d+l`BQi`vB`&c~r%s@Q$#K~A#tjE~cNUUD7UP0F#D^LOEkY{51_Dyl) z_1DXr0K*+#_pu*68KV~`qra~wR<9b4$9M0E)-vFhSk*wPdZZ+o zB+KPASS6VNO|vyOeg&Wt+qVzK@e|`QJ!e%wX@PL~K_p8ME&+)90JED>$&DK~ibM0u z2M)yM$?;g(@juHl?;Versutn{Lqo9_J`HT{v<@v$w#1?qQkeV>aw467_vqP-*ybGQ ztT)!9X1?W`Y7&>OIq6ieH?O$*s@S+@L$r0Z#q7+y56?y;4jkO01DpH7_n$s>Ixg9^ zRXuW9_ae#OBtCmuf*k?Rh(blW0Sgr!+MYmi<;=Y!f#$V2d?+A5wsg>_a$Ss0k*QH7 zWg-dUS;Zaz4GXbJ7eI%YCoE)7tueM*v~{FsnDiesO_uZzc+D!raG?C;-=Hx=$ZbiO zjPJ?!Ob36f-)o614H>YkYm$SeNPZ3X_#u1~2Pt4Qa=R$L#p29({LIaupiH7!t{(jv z&;(*V_XE1z;$pTxrbl`!abt z6`dIoG2bH<*_jZ!OpTW{b}z)m%eU`npe26!m6z&)A3Atg7c4tlV4=h?%~J!OxAZ}s zkp#1LlTZYiS;}Uz^B1FVKtkvq2z5wF0xF9LzM%3)fa~b&imsk+NloU%zFLJbUyq|l zk60ri!9u__dAunn3Aqvxs}voFMDWQF62G$nGNCdj2^lWSkP$)R!i5o$z4(5R2oXulY{(yORou$FC}=jN?aTrjgGEf3(-^;;&9>+XBwJKuXu+y)l-h4be`m}3RtUWiocWjij7b7zjk z+kfY6asI;D_{v@P#J&TEW80Q(amO8Z#`xIj_{87;qoxlCjNR=JWJ~d~m)#yWUw2LX z$N%!*V&lfCmblUY03ZNKL_t)|@k_7&+4$Js{8ha8hBYxiJs-n6Ul-52c}E<5=snR= zM5Ky79_=hkBXf`!!(=Pp8{jwhDkZ{_$w(kvguD`}e_hem4!gLl;I&vU$H)J9e|+JA z<54YkMc)9N6DJ__wBcZIY9ZYm4Uo4hH4?TkI~9iy9E`IQb7JqWUAsE=?SEQCFgpc0 z!Q_A=9Uw{2!I%?EqmtHWPb4)6jsz^2>;yZ4l#r=nM0a~J)~@f4rw>g9W`TA)M4HyY zl7P=$VD>tzmIBYSHnQNyC?1!55YFnx}T~tz5jDU zlmCSPtA23Gkog&^Zwe4OLUz;RXJl|GKA1^uB*i2^k3imV{f(;hcpvUFBYt>p&~l_b zCo`~GEzX`j8(TMTNv?&UJuZVhb%GM7p;acS@JZlvgItb{jVU&$HQF?ma)PgftX`Md z95d!1ZEz<@()bLZnV?NgbYNl5YLRK$Bg5I&gm6`_vAczeIA7*XB!V3VQ##z>z<9cV zmVk+ME=FhzBIwiG*C(`1e5WKbhp?O^tdoK*v2rO+*y)j&V$KHl2hA2AFqf|`#AU;f zP)(4`hZHD_k_?F=Q7xP3$NDER9iK16m%sN+)EXESnb$$v12s$$+Eo}jUa1wF`szY& z7t9%<_iw=^yEJ;V-Xn)Li1Gv%q0^PVE!edSRkfQRAYrR2ty+`Ua{(vvdotYP9PPbR=h%3FKE+6|d3oRj11;L6&&Fgg;I zN-duM+*@M;lfoJ?rWVhfJZn?0wsLfJ8quJ-)?}UhI;8n(#v_X9!c*m-9#X9yYgVsSX2)SsXdqzIs~Aaz z$ZJv6pBuTLfS+GGFP6-P&J6IZ1{A3F~LGd@=@~r4Xi87h#WE4Wgp(jll5wUoaCwLQ9UsCvTMw!|{O#~w=G(rk0NVQ9_ zYM~Hsf7@H){Q1!s92`pT-xK@y?T?OfIey{iUmY7au8yzYb5HEv_l&Y)!IY4=B+^ut zP|J$pp%}Y37CW!l9?!r1mbm|cZ^omK?^pl6vQUdVfATf)rGNQ!N*3KFpbA89;#Ys= zwQ<*7cg4YjN8{iB``?a6eIaIN7UJU{`#Vje{Lz1Te+-sqV(h?2q9v$c==A|htZ4IPBp#NkKam|_7nggYjByN;7A-9?Hq{dU^T4Fw)+CLE={lbwrKie5+&QBPkMH64bH1$}V zU5M!fq346ZJ{Fl^WQ2~jOwvr!AVzeJUMf5aS2}Gic2PVxIvy9tCR2Mav-uaAhe2ld z6W8z|VM$N{{`|f@v3YDvHqqJOX|5Upim)OUFLVFCQbWGJqp2l9kzu6JXoq4~Cy0rY2;63Q zE!H)!<(N`aB1nAH=Sv5yx+p zfGHuNr52%4D)x`ZLfHpRW`9z-6jwvjWInia>nE#`a<-sY%0z?-#CGD$g_O^LqJp+| zo+icIqOti}H74=&NUdSD$3UYKM-R^45?{}wtNE=ooqAv9XxfEVb*oy!mow zmlYFpqTu$1Pik=~Qi5Vb9zO*2Y;?dRhb=8e8%FW<5t4+(T3onrPWOV>&QKVidB?WP z;*uTP+_zy-B$1;WNV&N-3vpHAY_t&Xc<1j$duKz6T$zJlQb!|ZCMRRh?#JW!@e?sV zJ`qpuITYv5;*o9w45U(5>pih*&FWacab0X!zd=wg3yt7H0A~c0jWO6apuQ)hAZ3QB zU1Cb5r9s8KMr9C|adk1i^u;g47r*dj5%#ui+Zy{09MCTVxSyPNRzGhQwTrrhIXn2&>XtZ?1NB`+yeDS-qcDf`;Bk~!EXrmYtQ!}2BNKmEL zY@O%pvADK&obm<*!Fru@NECISB|DDZhg>r&F)=;ctVH=t+(*s)tHsyQn&9AqThu?$ zXXw1MGk$LGld);!$HkN$A1lO26ypy#cvHYJYGA&RwD%LcKFi}0xOFIKFIbC&AK-Tg zl7`&to}5a-EbkMu-aSIg=cKx1Mt#SnmuoUdNi6rEUXvk?MPnAk8KHV#w|0$U1}b+_ z-4ooAih#t=L1Q8x47?Yd4xywK+c#&mLTWVHG-c%8Q!iMDV@i<3ly4NH*6@@7@H3x{ zYvj6RD7A<}YiHAPTHM6uG)hA<^*ZE}bbKCll{#RR>p|(!EmO1=I5dep%MTsyBZv$K zBkwCX{(taxafM7<%+PzDO44h?T}vu%xaTUjGEW2&g$Fh z!{aj#?2Fkts)eY>8Xe2zaYolk-1%i;JnwH8DoJ%V5e2g#lpGM5#7Rj;wz1BnMO!^P z*;kT~Mi^N;+=EQ&1Z{@nqW2N9(-tdNu2w?81vqg_3aJuvbNkPnHf-(9mob;D9upHY zO%f{4rlKhpG!P&^R-y&5DJ4(I9l5D&;5BGeH%+MF0z5qzx4+;vwf%@q2nrrKa>{!Y zU5>79kz!TZn^~{PFa8}X@#RIfk|)+x8o8xKVZkWBZ*J{mj$c#5$U7ua022P6xf^Nh zGLd(FJW2SepMH7c;)PMOXBRz=lNZHuI9@j->D?QmN&X3G)G7Z=Rwv6^0jjXk1dtS~ zgH2{SOZBi&h>hzv2o`0rdb*(yL&HN7;-P|Ij87R~)4;-ub~eG6`E~O3@}7Ku7D&k` zK@Lvt4KHyM(!Fa!u@DteqdIx)sIDnbAn*VY=(zE^8xR3Et5l;c86`2_w>_C?FZm3O_ace^THP? zF+ox?)6rB1W-E+-y22@!I^vU``ukX{&bY0inPanF?b;bi*2s*1@Wb!Mhd=mH^^TcM zCoqF;Kj-G_WADCwF)})-i3_>%_4TPWAt}%~&*IasWrM6+vodyGz9YVJ&%F^v{65_G z^MOo~0Pn$w2S0}<2iMB%G`-(f-ua?v)GP7juiPiOX1?Cr*%qJr>{sJ={_oev6&q&b z`b&qRqm{so5Rw=msqIjUQUQVxu$_}Z!Ikh96l|PmstrLkQ?j5`lt?s?N9~A~GU}jI zZnl4J>+Fg%6g=kCAkE>!k~&t1*Rns zuz@HlS=`jW73h^jc}NV_tyyiB`(j0N;IH1ZJ2srXAcH3am5xnCj4VX_m(^?IWYWve zqfuUO>AochU#@k@Hs0M44olh%Bx&v`i|wD1c1Gj6yF2y%S$dX#%dI{gdbMiwc6G}BRt(`WV=3lLl+MH}U|{aQHCb$&!+TM^=Sd6Vl+4c% zYHMkgwg5&ySlN$$B|CBXVsV+Bp&7 zo{~(v^_C}`mYDxW5S+y1_arGoNp@;-TF4RYrF@ujFN_koO~<__&e0{*bLi~Q>oF#4 z?gz=g+ZZ|@(nJJBC(r)Io32Y!GL1NN=$V+DxF~@%6h2#NyGBXG)hwl-TNu2KkaX@x zB9nS-*GYPAm1nd)w<9tGF(V7C=Zv;A(Ug3Kr$kQ4R7x&2-LT`5Z9*4-Gezh_&N%hL z5EIE4m$e1RzVUZp&RHr}Y1C->#fj~jSi9QPsXvtok9iYtu`KZZ-o6+b7}ACxpO|R& z>m>q`Ok{M(sPIp)5abqVq8q}?!AO}{B0{PEwQPJdCl7gqD7PWA$+2ERbVB;4%<6ZB0yCgO<$z*vS==`}e zF)=Y72M!*Hzx~+XMI-C}=c+Cx1jS`+;M@+<12-Zp27ePmT5QB$eefeOFx(x5L?AW9 zmYgLKv6-FM^-a%=#~a`HCIv{UEs`V9qi5f+GkSVD;%oPOCo0uSY}mLlM$TW5mOh2G zlo?BhoY@=F<$f1ZPC|3@`1q@Z3mD8erME&#Eb)r7)Zb* zVc;3?x!q%Bb4l!_gz*=F(y%gzE&HIotyh9mEyZdyie};$8z|B(MqNrJ+-)D+Hf2i9 zH_iQ9PI;M7n$+Nxcmo0pnYOV5#_vV)MI4Znie%`GwK3SiNSgEu|B( zMsP!8K~;}NSwRT~lz4J5X8ugx69n1yYt|$KG6Z}&nSZe~J0HM0Q+?3odAlUZk@%*-LZfO~u9G!GQ*E z)SgU7a(2?52rN`H>NzLv0gs%}r=M?{2x(0wg2nO-D*qYwYtCA9;}c=TqBI`UVICaV z5Y*Fp}W8dXdxc!uCaO3;QOphH+;u~!!B z@q2&puIR>XjSZY`8jFE{pB|fx^CRcuQ=k4+Jn_UHjUAb}vSby#9CqTfskfW6%*5i) z35+4HTHJEei{s62{WYn_x$h(!7xle>t>$M@o}{X&#_L}9??liepsCeRsp#G=jgW>= z2DH_IM+ugge?jy*d-jYL0tw{GRjX9d?Ay0r!G>VLYvgv34mt&9sw_ifV(6ExL$1$M zp#3$VKzQknZSf!e_|N10fBK&2Y%9n43+H3^Q%}UpZrvPLZYf855rP|Rc0v+;Xg;I) z3KBXLxT*kz+aNaLBFBd0P&er`4WlI#Az6^i zB`^`FFb+z+KoE-ee&FG_|A~Us8KYiQumO3XavkpP5A4(pP1ijp%e}8wV`7T&-45|Q zNbspRfW?J|r8SJJ9cq3YRMv)YP+5+gp=}{%bfX@FL;dlJ1AAlh@iVcdC*tX;LOkBl z5g#31*-U)-kg5#x6jMTABzv3~{Bqt)37?ecQUXtT4QY{P&fNKeCo@y6Gkbdy)O-=k=P04-9HB8h5~UCeuFG6KREDvn6l);-2JJvp6tCm5u4Y1}lEu5*>= zq{RxE644S`VK+&Pf;gBJp9&#F6Vi<`^XFV3=2%9oFnn+1 zARmeh9z_UGtz_<-<90)cCgbknmM0I0Yz08k1UHQ-JmMKGaP%ak zQ&XvE?3sI?-Gx;ywBU7vxuFl-R5$AL<|3LA=~b(TW5xm{_lL96RfXkpukMN*&w&cg1 z-;+g{|Lo*xNlH4ypP0R{;c;f3;~wwBzc5{NYF)LZu|D_v2V}rrrKII6UhWEwLUa$;6#Y`HH2JH|8~{N zRWUy|6T_=E#$Uew&*P4lKQ|im=#*eC#O95gV|DLzy!u5~Mt2!+38Ofm3Q}Z@nj9Jn zMeDMYNVIC=!ATl0qB`62VV!qN?4tI6pG#=ZVHcsTgy!GchnQ zqy&!Zf!{%oe)+UcMrksdpuJrx38i4qAn^-l<>iO=#+IX}g|wV2w#FZ>UEkcd8ERbK zzT<25_ec`!nar3-RZStNM4BVnH>=)z4B{%_3kN1({U zpV}!rkBb*a#ml0sl-%%g7g->6AaKlpKvUY<6SBf{9aKV=4^R#&PkETY2vQ>tnZ&bb zFV*Ar9pz{+4bx>m90?~iNP4<7eFb5W5nz%xK8GvlT72%?Ct{%vH^pcd|3^XLf$*eW9Kp1?DGNQrhO;0CBf_XjEs#4y`gB*GfKJ#JQEXN%bM(>)K`Jl^vkff z1%5dqMoRHDBMCW1IMJo>?jPuiUAuOPKsz}(BT09+HOd-EH4*|b)FX@{#HXsCBHCwy z_m-06tS^+>^%&(l@By5D z&Z7!3a{jD7*TJU`>maNwF37_kIZvJp$BRb85|fvMW@>sS_U_xO`_$LltKMS&;IIy% zmBTCI+_?*?Tqc-cAUUcwL{`~#)73HDKN#ybZjOPz-uR7Q`*p!kSurjzdcmj(HTZG# zz*(`8FKEoh-ucd$O_I{wuj9v$$!B2G zrcJSb|6Y;L2&81w-L#ZSt!GsuD|Jqc<$}D#|QrOPh()k3V9&FF5kX= zhpuJMQ;&;y$%)9{c}8Bah3M!+n8vfkz?FRdEnBtRL&ACAh*M7;BzzZ(T? zg2m~uh)Gv_S8QB66t`U66IX2NiIx@zpcX!BfzQjDrmA&AK#GhpC-i{vMGgq%w&FEl z(&Ltd4<-I?kBzp@K3x~>i9)zMiy2@ zM<*kWO9Dvr>ji&;u1KHWhYWD14#rj_kqO9<{qQIr+u`h@d?Vas0J53Vm=gVXX z+@;*k%zOwwJBc)-zzX|PF2u}c zmL!A%mXm>cs^ck3sK8+o7!-og_I)2gGJe%MSE9nkNvBEAaq&K!v}O zm%dPOY<9X9yPw(@vy$;glc6J8LEmU4$%n!PyiTap#uArF_tWmhP2?~^oj;c3H&;!% zjVPtkL*O;qcHm(luBtQWS#o+;ojj_X%r%vhL`TkBB61AIIttuv>rHltb zkH$)1*%K@?0-_#QB2482GouALDOkSI^5)CQ1fTWHDaew8vG2e^i@^*H#Z5QfEaXBk zwPr}2u^u>dFs72Oyf_drRgpVxZI#zIv(5Cmklvh`o{lx^*2eK8N9AGAE;T(yt4zd! zq$zvZlt|^OFlWZxH)Xd8sag7WFT&yB71qR0N^yC^u}A;&pS)l2BE2rdPrkpRJ{1aa z*Ii$Xum0=Znvc$~E*p{Oh)dh))2Gs=&C;h5>UhfJ0;hK0R1WrB=fn(&t`MCS;Z^ys= zxmU*c#JETB5;mqJLq;-%*syk8tm&!6oiErNUF8KO1B}VJqTqv@n}EDB2`5~ILZK40 z8>J(Yruq0DCQh?MAL5D*;@70$)b1-%sI1yhQ9*%GI_BT~g-AYIVsYG5<@KIlv5li~x_7KRe1VfXI zb~(5+ougiIf;zostpdvbBf()Llwv}AG$juLMKy_o9C1k^Um#JeXHbm1HmoYRG;T=+ zZ&_U@1*&9AE!u~W%ygI~qA~Z&92h4$>{Bc3xvG>h-okuzboFRmbDezu!s2}Nb$h?6 zT_Mc_3Ms!IEmRUX&F!nIhGkFBzD50P{BgRv7;`frk)OA)k%`e9lC&zA?wDJEyU?p= z&H7eb0y*zACB${P4P;0-TM_31D&L>HE^x zoX`i0@wn1%iN}wO#Z%AV1&}mb(!_x)*-)#P=d5W6A#6t1gtqCvW}_quAj9e6hE%F@ z=5^6+1T=FKEWMnUO@_s*_U&lv)JU<=KJkc>tZ@=dbA0ofn3~4_X9;l=D!Rx7!?-4o zIF$Ju(!;2kBf~x88F3AqeYhoNBwVPKwmwe4ea+;;iGUIEo}TVxmz`C3QyWGjlulU0 zJt&l-x4$EHUVWAJ#qr~3vuK8j4gQdMkK0s+!oz);o!#09SwU2 zA7__bxU=Y*9L_SlqCiz|G~KU!FxRvZG!mnm;{}lqT8(hj8|w2QJCz;6B2{C#mS`>5Z=Lp6KuCl~(_$lg~uo(0~^A{(Voy zu_MPdhr4OZCiyE6%=Yfz-+UiExNPm2s)gmrL1wffvV!%q##U2%A%C`v*zj{LEgjL{ zH>`tmV4x?ixa^A9vTdv6gSp4Q^_Dk9t?C0Bp(xrtYuB!cA3pK}5y^NSh|=ucvsX}{ z(1h+T{Tb7(T{|z2J74zFn6J&o$3FTGF)}t0+qdnALx&E@mQ@a&Ev2~Tnrq|Oi4#)N zL=`T#NvOQ?FRqtsVia?H{9+6Z4aX-w@elEeSG>fVE4N{Czb(tzGH2dWikq&#Dz>j| z#8q3mqSQjwK+vL(Pb_4!)8-=4Ghq^*Lb-*5#XJorBfN>~Vw1O)32?L^S|vQgh6Q4! zvNr-@RD&^BHob9FAiyQ!67Q#)ED?CvKgUKo;tlV*Cl(6>!aYDA^!Z#%HvJhiw_b>t zokyJ^p2exBI-+SWQCTsK?7s9*mEd`eJrr)(*AF-7ae) zi(E|Pfhr6Kdtr%s+JnFs_I~Dd%TQR=7R1a`<>VVv6Yce`q_d| z8`cS7a)y>4F0tG@f~JxLwG6y}Gi(aMPa;bRx#ZtSibSAGyc+Jecr_`Juta?!`~bW&X7T-*wVXDI4WqM3V%hC(Pa)8nQ$e1Jro6{8_e_O{q=oGb zL>q$jrkI=h{t&t0W%0d!E*ag>$*1Q9%f89=Tr!J06#F4|tB;Q=edj`a$ z)h&76*9kS^Sk~0BH2RXpf}JW|06G!RJYug~S(7K924Pnzu6kc(<={r#ci+E8VcVuH zYNJ|2qE(xVO+wHf8XQuBAmI{yP_uds%Xkx!dGWAheT)`$ayV0VjC?HQA2L3XV{E{I zzkm+$lp#@-a3dMzVxcY0FGyel$zN?g5QR?ce(hZ7*YLp(M8-jX^5h9uDT(Kh+Y$U5 zpDCjV?&Y|@r0h}sNVA8Pd{nA&_RLAO4bGfBuVe(sJ1@+<=($H$bgU_%%DpY1Yx?u6 zRi_3PFJij}%%s+Y96GAu_x<-gqLqwh5|IINzV#7nTlUN!7qyllOl-3p3}h~X83 zF*P+C$B!RTpyGRW?YveFj;sR?o6)gRE7Q%)#T_qxLG<=?#X~>%VVpldruzwkuyxCp zIP|o+9c&nWzk27jarn?dJp++{%54&2${U|bXw}Mf@tj*<5RW|aNWAZl{wThF_rJ!c zKl6!Z)yz6r&gfOJ5v-XdQLC|SO>6w(t8aa=tCz_Md(b z2QGMIi_f9<0sx6bl*}Rdi5I>ozW()Zn6xBPlFeiOM|p8qkG8*N?YLiS@*elvN~+c9 zIejvoF19HF&n}iZNi)~R8Y=!Qv@cbW zS1}iwi}tQg1u3e#Et|J!nn#tUCMCH4g;=+4U37MubuacgtrZ;tONL50*(Yuhmq?&k z+a#DdIA(z+^>@>FD%ZimogrV^gB<4UC$5>6nn!x^*I>NSDw9-Jv_{O&fR(?XabfX^ zG^t`S9Rl|7is3ka?yQOi{y`#3t>#65n({eFI*cSB^_<5d8B6TbeauM+&sbcYQj6js z&o+zpT9DO0-;1<%A_8K$)|p>Q+Bicw6R z6+R=x`G9+u&&WoVB ze%;#W=b|_6`W&)n&OsZvWO+LlP@QBPAHqam}CJTT*VF(B<4EYfB#pauxZ`ehT01y9NKzyz>y$8kb+Ee^yo2FjN1I_fm(Y#XN7`# zq^gx+>?DJmZZH`gP-L!5oV}R+nTb7lB*~;gGjz$qy?D*g1V(3$l%ylWZi7Pu3WRc& zt1iaw-Mh8Hg@9lOnxO0D?FJ(TPI$O+ZhgR|AfxtNF~pUQ_Hvv)b54JDQj`c_eSOi< z(;X}N2c?L}Vh3q}xCDWZDvCe~Jc_d%JuNMs)?##bw8!ezYhvX}#9ZnzHgz$gtUz7}>aihYcCvU#>{waTU= zZzM;_r1U7`6RXlqOpnFL`BBekx3<62@&ISR4nipaM&WjAb~&- z#$F8?-6f$-tqAoh3-lxDc{-`)IU{4uy^*;VWXbd#OlZu#LLcgSCOUn^n^%9a)Y21w z^^g1FbN7!&q16m?glxzU_>8Q{Et@vSkz+@VRHV=BYS&V}EQ$JI5BNr?!O|=O>V4;#&>S;VR-P4?i(-#sMuxj4XmaSXj%&F4}YIoo<@pMjYH60X5 z3qSXlow(PPl&JbluSdfB%rhsWe_$|HtQd^;HjA#At&i+2Ev~FyxaFLVS~ShdB}TFS&aC&c;C*?Vjvj*YjdB?gkq zSpZMM)u-2>W4F=5Jc(d$3}1(M5;Y?=?%}(Q#u}uxgiw<7MOs_*`ksKWL+0w$n37Qx zKQJ0$T)H115YwJ>j8fttA!LZi~eT)r+ohgwKN zrj3?K;ZkFiCOrF~Z4Lx9kv#0!bJC*rPq7pookshXzV1k632HPiQp>5O985W7g++_4 znZ(@IW-_Ei0Sk>7DlbNFKNi!i(OzzenT5qzEcV3YTtxzRoSjSv^1d?mOLFp_K9QA_ zVyB!Ui{=Ya#Y4RGIKS7#H@|gP6#9F+8(m$!nj+}$H!Ma_XOZsTw@)`C_qq8%+$3}j zXfa@xVG}23A7s<~fD;O;36q$7gX)QqYyWY>qxMnf7Y~N-W1~@BtIwIFYIDYAXxfmF zh)P8=d>$x*MTtC>=327=3_VBNFVAbi;onWWAkR7Tnqo88Km?|xV#mY8UYEl)qHxr&|3INafP=-@~d*7)Q^OpH&&_{60Cjg749 zBN$byYQG3tj+!bT`dl)OVGIaS59YR|O>WszdV7B8-kiE`5$fSV)Y43Unggav=Gb8YmNHfDLhQu8arG~McGE&|{suDrA2#!2|Ar>j%Q%Ul7 zKSPg15o{F@l(`%Fr`7dKum9D!Y{ymNpfD*hHZ~c*{kC6?THWF{IdRN=*$lr5>XXc` z`_(24fnpV6)j&)9U$3|+Hm>T7sAJDPr^=~V;(ihk&@(s5(OL_&XhrH-2%83`quk12 z>|h}SDa5^`H_@TdI%xs40+Z&BgWC{JV?>LzNK7Igsj-=q*$9F^+Eej8Z(C(T zS4yB*TQ9u*_W1g}_a;kOi<0G_#u`V}l66kS$uAD6{O>tHaX|9R0UgU^kHbn)j(K)Q zFPC|`+q%}R3<9iY-mNph{pFeF!^($&tC-1&2|>2R3Ui!X*|_32M6IejF~+&KTeoZ# zk#TUKHx(3AOWx<~@0{>+Evy+$4UsTwqR1nPnFrzw*B|=S{1WFg6R*lVlmDtq7 z+Ac*;zo#023W%dF@et~&(xunB=6}_CA-=O`G)Cr_Xt1XM&r@70EXz~uH{5L!-SUxX z)=6G38Cl3kgA^e_RtxqtX&%n<1#%)ZG&~%G!$VrDY7Zo$HOU0;NrFKf9v>T%#t!uX zNgnZz7?~3wc@d-*l6gc+Bc2I!v*qFtH-DU>vx&3lyb*{Dp%_LXfh)Y~eJ3$;57 zrMTo-uZ~hjPfX8D#>KJm=fZw9c4WR`C6HiQ(RE+^6 zW>SdS79<)Fk;Gbdve4e%8Y@<;jMXcLWA&=F(b3hZ>*pHy?59sXqim0d%d zdbfOLn9y@`u2T3+1ntV)yykaDFOFJQJgJBo2_b1fYMF}48;M}XcoT^MS*=WBs+AZX zUL}~Hg|7As3%=Dn6p}@=cMEai*ipf!e2ta?2$TAwITKGRkU2RaDDYnJEJXT|zk|tU zsvKk}`Ar+)H|D7Sg-sQSV+FO6C$>5$B- z33oDHskoh#$G^De*YCPCx?(nNyKYT%x6`YejYic%Oz;y*BneC{z!cW#xA^Ey=-{d3A35%9`$RL0Gd%Ccu=5sRDb3>Wyn9n?nZEsd3KVS$Hzg;5Gu=40McP- zs`9ze5)Yv1p6h*?69PVmETvTm*Hk1B`?3qC5mOgZBqB=gk{t2k!ff2Mz7Vao86k5; zC9{n8nv-Bu7nC5`VhZgl#6qnYcRw*2i**arvC;SfD&OA@-!Sgu*DvFId_h5ANqNg{iRcU1?`AD3xjP&@P zQOJU-*a$6?_l!KIUP(H|X+wx7A)OB=(vFjyNlp@S%Q`3HMm3G_ux30S?Y1IojdkjK z0WueeQ`7iZ6$*0Uo) z9TDfJEl!>t2QrKe>sR=F8^t(t`b?}|wKAT3d|!O)yAQ=Ly!JKG+uNn2hZuF={ojj! z`j>x>!cc!-BoNZRaHdwOd36ACZ{`Ao3M>RN{BJ%g)Wr|eSAx^#BT6Sgd?w9zx` zRS=HH##9X=KbfE?WnT5Vh)TR4nYgN8Dax_%3pzw?&XbS?mm)gE*{lR&4ptTkl?t<{ zIZ&!q&|*>^raay}%NW;W{Au$xM~6htG)c?{w24(sspq5*j%;%d*1RVDP((qhkuH^SDd`bI!X`hPBIQaW=X{=7L02)@xdio;xn`kKDcr zwjJ$q5Fw~i{mf2tKNbVDN$~32ykOLciK!SE>{mM^!=yZiuI_G=Z_@LuROU5;h}|=z zR3tsLSCFOkcv-8*0$VIJQf@PEgo+mOCkV)e3+Hv1Xfz4^`;^tQskmRjVchGLD_6zO z|J&E=-VO8(%H0oShv5F!xBh0dcQE5_f|3tvNOYEP)z=f#T0vTY58Zfi@U>3vxa0Qt z;SV2;v5|9e`wg4o)*H7+sWBV%%8bV%k#i11+XODg9BDn^5h22$PzEY5#}uz+0)SN- z$=LZ1J^a>I2S_*&DHBQ~OsUu4{hnsZ>xHiP&_5lFe|cau>IJm^{f6#yk2DoE zv&fnIoUXj|zdSolWt*k|+)``PvvIJuc!~+XR*U30kd!;XW*0hyr!1-MswU~f*POIN zx?>&Wi6sP(nmuAA%uc?gc$X^MJQd;3>}#NcS+m+L5wsjgJhD1t7CjUHMw1Dd1@GQ0 z$Y+NCmqXbZC17n5r%2*yfw3+%>dI(mQtN?f-BsJ$M2{XKgAtZA&UX%7k&fXQF6Pmd4I zVjR6N8&8}9sbNIf$)^yA#6jV}kr0}o>(t`N(^*+DF-!4FM%oh@>hY(sJ=s!=5C>x?Ml>VT*@7C!D~dp2fg-9CL-l{lvO7+QtJd>-Y{y@V>1oG)o!m6)Dz0?_hbEN zQZMac?7wpYV=429q0WeFH}u6oFG;?O16l{$pZ$|j=zwQ46Jr-gMUZEWGudIJiOD?M zPwzW;BCfi8i^$w0XAeL0SUkRWZ~VgRUK71tkn#Z-#psS-`^~pUVe6(%jSZVNyHy}n zu7x;p3iA z=%&C>>aVllvp#zsZ<6kJ9;GR_ih0kbP!EvVT=hE{rDMZc32SkI!yW;ec~!Jr1BVv} z2oC{xWp;W-*N>@`$w8KxrGh8v(c?@4OnmOG+qN}ZC2pb6TBu5lMb(yA)nvq-vZ=*Wc%f@R|-VkWnodqOavpWh@TsR!;B&CKj{%uI9W&j|e?aLKtY36tc$ zmwJNjZ9)hj#IPZ_r)SQbZxV-CJVt_A6i9uP)#LcFqlvBUxn2S%)eIY!U<%BqN;CP; z^Ygi##CjMU8k8k9!51%%CX+jPfv`4EaAbp*TifGJZ~ATB>;H$X_W+agtggq;^s+O% zv%T+1tFr2rEF1T3Z~_>c5(6e7{1V8IK)`@0Nob*@{2&CUFh6+uQ8)`9J5}_nlqx{FjGkEopaVzVCbA``&x*x#x7Ycba=%aS5OP)F)6V zEtxDZlL1zJZgkUbj8&C<4fQJ>yvv~KCvaGTUw!4Jc;Mkj)EeNQTN{AuE?tk+9VrB; z*jQZR0GO`Z&;;Wv1i{&5C-tm~(^&H+y2L!hlr<&0%nCgeQExFG3nCikM1Yr_cA5w- z^!UTn8?v~f%vDqo?0S9{pZWS8R3a@(-sxw;aa5DJb;dIK9F~~-fT$$FGWOcu@~u3! z+6;AYJz+WP*;-=^u-R@4Uc3i7;5pwjS4(W@DmhTmuv3()_!hrFRLs_C}E? zpM8lU=a}hAzGG3WTeAwo!=qZKMxHdY9^)rD;I zS4{0Y^@qb@v^F;h-J&%*=Y6x;c_pz7pgfc`#ifG54m<{RqIpdGwf==>1hiMk-7>ut zB9}pNwTKL=HNy6%$g0L_=WFqcd&87Rog<`E9c7I0>VuY~FQZJ1U*?oZWY5-+Z_lb2 zb4j0#F4F?pl6;F-L^AS-RkPU9l1ILnM|)?B3KhmC?t7c0V1mQX?R#NHW`F9?G{zRK z^0wB3G4;9DeJtd6?mLNmMa@$}aJi<=7>A7rX-JGIb8-c6x=CjalLVp&g4B(8%xBKm zVyrRrm+L*EXT)NJtxYo^H6bRcFuL}VR}`#`C%E@CB+6DV*NBQOhc=1}r_os^ht&8m z4ut3b2ti@7yoH%6N>s_dg?9d?}zj-|>HeDjXqR3>St)*hm%D;;hK8ty4M^V>A zq+++9`El2`1hA&F9!ZiS!-5(RPIsVp`>VCqhlhuB*-ZTSog5b{h|P3uVsaLB^-ajs zb6wBt{+&2}2EY8(E?j-h#ZtCqoMs};_kHgNK8iqRdwX?o!v@^|epDXh$B!P>{HPaA z@s)`#ibg52$E4Q(f^85jT#~;mqva>!4dPD-M2#ggD}>qkza&zxJp2TntWb~h1v#u$P}4LrxaY`DYK?!uhPR~ z;yj3bACbeM6ey>rWo|S*J*C5x{Xfof+k-G=F_Fuhcm~N*JgC%;A8E-TfD zRgSC(c^|vFyD)TmNUVCk%haS1L7Ajjz$l}sktDG>1)6hrT!?F~d5ws6yf;6-^9OkD z`6soWj5tW+8S(|3VxHx1s(Sc-OcdEFpw|Hp9$)#c>gz=!9>Eh&KaZwNqezB4_^Ras zHm}Oy)t7EWLn@4FX%5v&PAZAuh@>inA_7&m;&eQlD{7E4+FrDO4A^S041OP$RRM%AiMhc|eoACjzM>$w_iu zj+Y#(9O(5v8)^%EvAya^#eBq(fNO9zk)GdD#>Ne6^)td`iK55i_@{sT4-_kg{__Lh z_@>`Qds8#s^Zt(@uyJs(%Dx{*E7V5;aP}-Ml5K?1XaD{{<_${MB?X&JOil?U@K(0; zp4UU5W;dZudX8&O)J7)l%d#y$a%c98c>Q04D3P|A)TNQRwV-wB{4`J8ik702!hxO~% z)?hAGNaU3{VwRUF_Ry3PgrJcwd5|-p*kNHoOusAoMiog`&V-tr&xNllg%~V^nWVI}wJK1O;m*&HLzVI)*@%SMo9w{v5Y#dGyrbvWNgWYitd?h9FpnAP# zl*W6)wJ6e;yKlA^3|BBdizjJ02DVe4+z_Y8T-rmOAY+99qQwFOGyst7i1-l!yupK(q+9gf;r@bx+*yf3`3e&WC;fJ|tJ z?wx(T{nB$#o5>+1%W$wmRhSsMiqjtwEEpbq@O})eS&g3VPE1Z%vOq+GftQH_|1ACo zs%nvOeOs%9R=y+%n=Q8;bk_bMGGJ{0D{NHvhJxm?;iiXp&?;tVDuIGbY+IO9rqBhV zoUYB{(F5KCkHp$|=dEQF5VAt#)oYdr`BB1d*4b8sbE<(T#j?UK?}tI>#&h$e z%L0wEA~qSp*vxg7uA|^oS*R}G-*h@G(U#$v6aKO(1UvkFb?yL0dp=5P-5ErYK=Lm{ zG&O5;o4~U+y6FtrS~aq)Jx`sD@*1(?nVbc)1~4>)ufzA}>#AU7<4scQz-2@K zJ7cra7=xT@n@8gyob9%rI=iIaz=j8)h;7aT+$$>jil6VzKtc|HM$(w&C&)y0^Q0iB z!Ng?*4@yKSkGZ)8B@*NX(7u(Qh3J8Q@T&K!Ra|t*rGlV&!-=Bo+qYLHEBsu(=gLZ% zv)%gar83%DTQD{@ic_afBNB_Dx3^#ShgP_aO-&LkBH`xnkpp;n-#!<>>(IZdPu02I zLpO?}S>3!dv#}n$?~T!%iJwIxI9$BCSM-Tbp|iCW%^i)1grd0r{)f=n(XNBl_cFOj zhuKQU#ezGiK*!5RJPDcvfKp-3MkHw-rG&xU*qA6#lu1sLAtr1jC{d}}nC|9_VdIG+Eycr#QC68qn+SbW z?p&@U6x>|zjnC013>NfgK9$6+UwR7r$2%~;K+`AF`IpqMsukbUHKw%%DXQ7=U^fnn zgwGO5!M1w#D|8vip!W0NLhFPEnov>=_t3bQLoBMmrp=pmJw%fDd^PzHjtH{nn)1Y6 zk3jiWrQVm%Oi(JYW?;42fjkKK`sATdYQ3eUsb-2KC_QQ_uI4<-LW84}QJIOgwRYHq zhU4e>Ja`+(X(n%47MTT||x_9LB zlTT*GWm7)<(gcJfd21xok+2!pg#N7{w2;uopY;fVS~fa}NpPgmnF%R*4hHwFZ0k$r z5UJvc94n_(Xd+ieYGmQ33723P;qnqTHD(bFRgg@RT+6jc4;u3dV1|&-6_G31Ggs^m z0v)_P`9LXMgtzWicUO!Qgj0`)1}GbIm(_rmr($6qZbh}Wjc1hz*k5nyZA%XafM zWd={4f#U@Ei5VFWI@xUFfO!)nOJK+w^QgAk6gB5vOY;5RTFK+_MKaMGz9z|^;(2&( zo-{>F&p_=HX;D~A%Y>@f*bzZ}Du5*2cFCtH7qRKe-$xEHF^SHOjmekA>rwEM40%>~ z)qR+rH8)j;k4Q9*haTCDD=r>HG#ta@k3EIav2l?XuekbBRLTK-;Fgafuw~51iQ*#Vf2wX&HWUEa*=XziM8qisqf9zn6vJ+1u069!vcY+&KbeaFK$7Ov_y45ii=9D zRo+c6A|tX2v&W)eMZ*Hkr$E2Lk~TKq9cznh!BzJ?d@^gj$%z5hEoU&^NZ-|=`~(J9Y?^5 z5^~a5Bn@FiVzT~trlAS_y&X7u>;(E(t-|9^{06Np%}CXmL6cXmB%H?$$2I{21@|ML z=PR%5tJ(2-vL>&E*Gb+A)fh)cM-6olL5`>Z?|}t&3Yt*aF;kzxQm%lJkul89PGQx+ z07i#LYUD+ih#S#eWZuvky||t`1n={Gm>5{^JtzcCZn7@x z@q1N4Stw3O>xi%}pI=vJm*chggCwkV%?j5zCYI1JvEzOxxt8zAPu$b93U%oQdxk{I zoW{Qo$o5@3-=-^wcKT$@E8z*jGQk_h0e=3@o^Bj``9)0u@Bkvb%;cS#B@#ArBcVz# zU2GvLW+;y7j!68CqDDm3++j~*qO?q`M;!#}C*;IhCz{J5hQ*IZ4(u5b z%`grY5glKh+wWVVVMwGMlud~WR>fzLh=q}$gmu*7s@iu%aSM6m3f#knbQqEt#IIgH zi%O)ykrjy!+nBW_E##g##Znb5wl?fQvK#EL$F~uzQnutk#RHA1c>QcuP$$9l{n@q& zgu`-|^;Nb;el@va_ex996$Om<)PLdGVq>s|B>A&MD7aHXwY}@P0N$X@4*r#2I{O^q zRJ?NEniHt`h z=!})o(-uN98bW;?(XuM?;S@Gpc9Rmm>6rUV<^DdEoGOeUK5VAf?B8>^%QGRXI$McE9i( z=n^UD$w6K?p!+V~y+@V8&ay3HGHQo(^J zRyn!pgi0C1!zb~%FZ>-wM<#`arNkH~TC|M%iG)Td)G4=dugf1oo($AbU{YNJ@M~md zj~bdOoM*&apWKoTOYj)P>}O3($@ghR=1rQasAl^8BmoN*r%zz&sz&&;BE{MXTr1?Q z)X`6Y%7MgtH`I_yJ_m!9O?p;3{c5+k9<^kwtr~A>YsR62drd7-oD&{g z{u)XCg+QI@>o_PJbX<_&d1~CI4P4QCTZ@#bA_Qt5`;*z9p=y#RorZSRSfavePAoa zt7vLUz$K@~8{uRC$>=FeOidwGm&Teks}CW0i1?pko30Lpb~=YjF!ELNI)u{SZ4%(0u`@ofcfU%jg-7Q+vUYJSdf!&;?72$42P5*+?ScjkT=MY-w%M z!PulRj@;qiMO@C3mX ztWghnd7=mxxtT^;Vqg%LwLw-wL=6qi*tY!~tDu*b@Zz4`I`lmgnXlu`XXJrF$dT;= z3NB?bdR-<0Tol{3pQ|xHZenU3Joo(5Cf?!=KO{k0RP{~NfzrsVYTDb|@%-~IU~+mI z$#@(a1~=(|W_E4lOjZn5Mal0xpOd961$pv0?@BkX@kApY*#v;KZ*2OaKp9w)*iglu z-OuauG6;2bb;ylzc6I@Cb2B(QK8AFvLDkKf(#c z%*-TC4xK`KBMFoxTzAnb4E8r5P@;0=96~`$DlADblA}m{gu>+v$B`q`cP9y%Tm{NI zMBbGpn?YU5-|}YPrl^3WFV#~ z7!PPwm})5+8IcHDS64S4d*TTlJg<56>)m9O#T{Qo*V=|FqaLSq1jqCZu#11fvnT-tz4A#vd5hOnL5eMVHYwdRcl zZCG*{Me!{PkD~FlSrqfEH2)yev*2gbWER^-Oo%nrz_y*e2lq@{yn=z&C=!t>l66do zgQ!H(SbzDObxC4N2i z#2&@WU+#Jofeq^it0F%!;HmdxRSDr@!eq=;hLI!HC@Q?25$ zM}Li_9Fqh)Bvdsr7{n7I{896Oc|+q+7#v908VXpx)4nU<+D=u+ho zGgF-+k(_)^$P3MtI37c^f%l9Y0^Kil=NJ?xC6~;A$k}8Xq}a%4NrBzWqzd|cL>4%$ zz@(!wlfjWA$AK`ncLuq*kk-G~rZAB;-an!P ze!S7(ORG9XJgowCsXARts?HQVZQmMk&mSE0Z4r^rxngocz&@KFtxjO;maX{FT|dOe zO`EZH&3cza+P?BlSU(GIQvk-Ts+8OapNl~};B_M7=jHF5%59D_ya8Dp=)5mnm`@{$!U3!FiDmkh#MWRa^j4d4N^07`WG}l z3x@I3p*c+F$yb2(8ppSVj=I8+d?FbsN&CcFl=lAALotH0-G6IAa9w%jMJ5@HMQUq_ z>&9X>09MmnV*>+&NF*|5##Jt&E)f^1)7zWD>tFX8#3=ZeE9hWVt5If6Tw@$XjpNR{ zeu77LJ*uQdW=KN0tkO4UQd@UiU%p-Kc`Cle&eyVThPB%K+LMl}3L?|pVUkdvN@03t z*3J!b1^iT=I3G?l&aF#L890+MU*vK!!z+|3F&Cn&zAqBtDpog#(A7xfkqJdYWaMqv zybX)uA_O$WmaMaBGHaz9dd4I{&m~AinTozlFicik9t~BVcTA8%cs3gI02?WtPH$}e)yQrX4^yoz7E7Y9Z?%Ie^Wvj0 z2%mS}4!rc-Bbc3 zI;syJIDk~LjLWt*Ayk<{G0PEAH-9Zn4TceudS=DL1c7ZIeveSG%ML5=t&wuwtytHo#e}3yH(bLP2p> zQZl5C{1Kam^5czs)?%Q$R)Ymx;~}Xv=Rk)LZHgu746(Gi_0{srMZ4XZ$OZUkB5irKxfdu$Uh!em_QK$BQR zX_?>$gNg^^;}f-UZzH{j(b3a~cr=Xy`|Tx;geUN^kG>Z%`3YFj$=5QZ+Jv1LyLc!I zN>{SL(Zm4qr5uLG=JEGm`6}W`lMmPZb%?8fUNRjdnp`pj%C{1#97R-%$B<@C?ui~` z1b4R3Rg*av1WlJY1Y7^+#vN@7-wc)r+q&Enmwg*t&f{@FI5kZ&bq?)o*^;Y972BuvcY#ZBNa zw6u1lj2pyz-ghekO__#T7nC>4S`F5(Cx3t%*xo*t*`Z7_XqG}Isp~QF!W|N5vvMW0 zs@mppy{j4zp25NO`pgV8B=`~PkH!-iA05Zwx_hIr*h1$A(N3q8CQTzfe4qnsSr&+IGI#J^Sl@Q z$}Qz_{KQcOnVd@!xG+-5G&0Ri#)pW-?a+|$(TFo=%A>!x5B+`pf)9OACUK63I-ija zJ3r^`&W@?t7ff0xs7=7&#V26L1&J^%v{Mjf6Q{B`dUzhMf5RVO zskljg8LaZyqT|86`JD5GaF8|qz3+VoKfm`OtnTf_jlcI6eD3p~MI@5a0i}B^6+G*Y zTLo+ZPQjGsVa~Fc?F_Z(xE>`)W@|z4K4DYG8{zNpz!4`yh#3=9o33CoPksUueRG7h z#){0&BKhb#H-#p0V)?%`I_dD5J5Vb#HpdBOZ;Tt?OL=ZpymXv+*E~;7Tq|zo4{dl=*fh>xU5!!=2n_8cTy(eH{N(9E;#?3 z8h1-+CfnPR$~TE{9n^FVR+2!OdlHgu5=B!(Y6}%HJDu_# zZd`xetI^Tfjd<9cT6urC?TBn^LYxk}B`F%?;DMvK`+t6h@u_iBoTLJ)CeU~u8LFnS z#1$6yhL+i+n#(+OXp0v>NpuoiHI7Q*HS;y$-sL&c)(}EpLqJ>v`Ymw0mnFzKSKWwg zFoRe)r~=JYC>^rlB<{7BSCEXkHkWy4d{&n1@VV`J@>yJd=>>>|O>c!~wH!rJ!Mor8 zF*A5FHlynsg=~J)0)e#(nwxoOn^!p>l($aSfn6-Biq~kIY${F2f)9=l$+sftGRimC zh@&=1MTa;cWd#`q%@8euTjYYqgG^#B6!CCg*_@vyk*}-06=UO5$g%nl1h8SyR-@S63Up{FU1wd2$yJeb%du$I&0>9Ldkf>mmHt(3sKd zu%FBOas2pkJse3e*HJ|=;z9%LpG_fEO5JG6k)GMg+b6j@GMMx#6PhOFV+x*--jvhIVbvv`V=01@Ih?cIEd!vjNCv;v}1P9wZCiEW17||qli+@ zq?@lew;xxW--AkF9)SuCfecMBb0_{T4_DczUx;+m1$rh7kUYdlSY0=Gj*SpkDtPJT-T14|egXgb zwXfmNZv6zl^7miFCqDTFgsN^#S-n>0aOXYdg$`JCNCeFabH{wISjEUM78Fc2{2aXX zei>veXtHurl@q2}jm@JQD#BTDlRW4Dc&N3uW$@OU-UK>A5*DR74U}61P%W9R3CCss z^iMyA_MX);y%EwT2;L1`)U;U4gw3M?BL6w@Ev^rLNE@fZUPlU}UO&N2c`!<_NFjna zJaPR#&C zs%0yntc7Msk0s}Hh&0a#kGPn&fRWv-&uz^ASQOaaQb8n8K&qZ?IctSlL1ZIz#Zpz3 zy9pv$@wWR!7DKbk6A&VIx*~*yqmfD-iW@SKHgERi@40VXNdjDMwKlQl&k%i&kgt+J zfCxb-fIs~G8?kwCK)Mc0a6Lyw0hNxxVIzQgiKt5_W;Tl--g&Rk zS?QlR&76#5p%9KZ`kzBY|y_Y2=>Kno`k-Vh-=j9=f$vcJ#*%?vY~i5j$kZ>4I9>B z@3T+fnw}m+%T+u#Hij(68?9c)V!nVPZ+xjNxSClQKYZRzHt@oD0IP)|(hJE_6nkJW zUG5J`0gLWbOL@%9&udJoySq~hglcA`^wOxYaAGR^m!{SP)iV#D20pn+Fo|NP&GI2$M472A+Q4s5|dX_Bjqg@5< zW>ZQ6f?yUng`-D~AkXotSOn>YMkN6}FqnOkz{d*2f~ncGdiaWrUtW(VJt{eIJt;FU zvA}L~vbI2&L`}_1qr0;cv-9)T8qsWSKnjXP8hU&CG^Ii7Uin=VEqHL8(Oe^G7!?=s za(rR}t9m-o-k!nhcLwmv!6E$QsU?vaN5{wYJP3yoWqH$^Z^GSo--*_yW~|>hsNOYS zYuBz{JF_S2w^5XbGR-2_IMNnBPq~=KN%1LwraIuNa~pBZ)mP&Fr^m5auoe$L-|AKU zdR}+@=l4u|f&n2E!t}%>)^6A+q~+M*qgY&;$BymiV(q&1HHI?R(JvnS1tQS^uDJX% zCBEF85?qNz@Yv&zt6$I0&F9k8m=W@I@W@fLq=LBm;6fA0tI(U0ANZ`}SZ1j8m{uF*2*m}z^$ zkFr^h+3yh^aI&4{SXSIv{=Q}94_@m6n(l?KO!aKIrdc)T=P@wQi<{s6cA+PkOj?PJ z{l1P>M;x>*V=yNZ_#hsA>^FFM{~3&ojn$0eEC~DYwdLpL@(3NqH$~lDMbwy4SuM58VH-p_N%`RX8P8k@#4Rn`$XPFI$903^p>f`C^z6 z5|IJMJN`ZIA=eU3*v#0iphJu;A-)z5KJH;(dGiVx$W0N`thqJH=ty(?Sxq7kEvPJD zV`B;FWJo?JK_0R(Q@LfuD$k5CRU-{a;B)3A%M(YJuu!0;hjBcJl*D7E#;WU43z|qT zlV0*kmd8|8Y`Wyn$a|Jxc-FoCPS1=eaTKv+0@uCza$I)lc7y}QRdA2oh=ShA*`bVl zKepz)02Tk8=K-&q_mM@3CNG>zDic$`hfJTul1Iio?W+|nDy@AbKZ3|iirm5So~tII zB_fU$w!(n9g&bbq^9t_1_kM7qN~B7ka5}>-A?@zEZIZ^&1@U!CMJ%~#vq+F_^Q3e0 z%wt!HJFh{sp-1Qi$>tn|6*9rRsA6Plo4hk_-AdJDUbjyU3`MY! zN42`8uw22uL&qeKp3RnIx&8Ui|1|=A-5pgqQ)yn)>^KRHXw)oh&>$;M8JS4EDuSu0 z31zHZom=qvzx_Dw{mo-|^0wRY?cezwq*%cOA~-cagM)Lkxc}vSI9$wOf&Hp7KV(sX zS6Pp9@w1!6^%N9&h3~^rqh=R`mBG0=X_}KP5KeAy6DjhQgGZ6enHh{mNYo#+!=DxL z?_P7M_yY`F1AYDY_IH1P*(HNhJlvwu7WZH^->nG`(~K_?nhyoBb;}mB0o8^e`G@^l z>#3{f=GdwdTj6Jsx4S_=HkuUHh~x0^h%tz(oZHUf(4oU3zr-Ukr0VO<K@Dvzl8t%#RT$!I&*JJ zrEv75`laU{NiwnY)cZBzj%LqF+yiju0hi6XE|H8 zrnvriZ!Cc_1XjdBwd+<$bZgw#KO^tRYNM=fBmy+kvuCqx6le*IOCC5%C?unZYB_|d z`32l{=g)B9(7xJw^2pT6eWD4Un2CZh9<%6X%U7*GO*RCPOhnNX&7-F=fcivC7WI*E z4Aoc?YcIJ02t)C=isLi0_>0GP;fzZWnGGtVVSVgIO#Fo^i}NE^ zC@Z08Yi-t{IW{&S!zKod?v6IG><=6}rBBBIDX$3UvNboqh*Ug^-@o}yR)vMA^^n6a zfAJ8`PA}g`Lc=_?d9X8BGy9_KWhN0uQ)3FPjS0lV6>J{tmK?G5@q##bd>YRkqEcfO z3v+YY;8c0!_@hX9=JTnArV%jb8}79u#I|Xktt@AL8GEtKxY)EJc zHvmx|**%xbQXW)G*1=1XDRvE7CO6CEAq${P5;%F`_2o154LTqWA321Mjt*nVgD#Tu zMo29d(cIKz&~ddY1cldA-;mbt&CJeVOJ52nN2ZZSN>DowOjU_NKIWEYVn-@wSH6m3&O^y1*>YcZ-L)dpRZtS_dGEb<C69& z8{YU1{MUcqsl?q96gTe0*YuMOu41yi;KIoYE&S!d5kS7+M!)5; z5yI{hvlv;3q2O%8SpjQYT8@O)*Qtq*@!mS+R1*NQ#6l>hQ-37aM_K?(Lc~$wA(_PQ z{O(n__NohYSX=yZW53?VUo_L zx>{G_*jeK1pP?B|+2oA43>6k8ajb2spsgV;!8Rp=l?qm$cNG%N>%>!H9BODt>2-;m z2z7Hvvt7RvZ*r=xd|kKWYSsrli-_1755ij3fV@w9^SueSaJgX;G zTFzEeqg$o22xeq-ec*k6gi>hLoiAAvM(O+XB#~x`BaXM)QOK5ILprIj*OkEV2 zbOPiS2F0E&B3YkCZ)dyI%8YCkL@1WP-4E=?$*Gv&Xa3yDQ>TsWLA`RRZB^t;ppl@s z!DH$Z(pbZ3&=Zjm_do(aoM-o1x(PurFeNk{Cg$}JRI{B zcB#P0bXU+!vz^996^uuZ9J00ot!YCsw6(S9Ua+4=u7i5;>dQxP+=@MWi&N3m=44IoRFSEZVqd@0(i^ocH*UDvzT0JMW((L_uhZMiTT8+SXU4P zyKUPxoShn%Y<5divl6)zCr)C|o|om&dER+D5sQYgckg~QwKl0z7&_>(Xj>V9SvT|Z8&XT|<_Rb<-cOy2Pv(*kbC&$b6$Il?OH>yxB%wj&5 z#q&?Uh-d*d1@ipmaHQNt@gtVj-OV6Sfz ztT2D_2!)D%DvK`R>$m?WUVYsS_|ctrITD}k2}@R1v>j^pz-Dmed-w+Pn$)==N!D7h zL(1Yz?J)6842N(|PK;@?YjR@PWUi$UY64CSvJ!;ymeC|4GZtvSbAQ?t01-B}7iz*m zPWZ<@gTF6UaZ_`~S_?!GO}vNi!~MoT`@}?2@oG!twSOe#OYyT1@T%SzV!=FONs4zx zwD-*G#897VC4{0=7F1Fe4C3(vvzRZLc8x#eycPx%j~eOH#bk{bs>5L337(j!YLzi> z#Q{%SY9>8@{D0nx%^L@60$NG}9N|yJq8pj~EuP3q8*~^-%PASN)h6KV!U5fN}|g9cgqn0QE`o6wD4flx)QMOWx#MT8)dtXUcG| z7LS`kREx$7{W-xW?Gg9);;i_B-?_(H!D-1A*J?J)$sGFPRPp{>{sMt5n+7>srA$#! zwlYA2-S`Pa*pPq?d#l#N>F-{JJO29)eDq@M_U$V@TEu}1-lT5lz0ZI z`%KzIButU9&T$gj21m(YU4<+yUDc!I%<~Kyn>azyfR;=cb&&$A2qcCO?w zw4kA$*&0W}DhP%HczD+d{QBu**tTN}&d%7F47KKmhDJaVlfiv98_Vn912C}_6G0Jr zAQGqbj)bZ>;+QA#c^PX@V55{THvwPI7L{#agWY0?CzFOmtk8Lv8eGj8(6WCf71BM( zWs%7=VsvB-@nlR=$_!ELanVnrK%s^u2(x?=*)HV;iiDJiaS9_ADxoe?#N|8NuxaxS92g4XNB8|&$P-_G?YgxX z9T~;w=m@rNKL@J^R+$TA75Ldte=f%NMHihfq9!-lu3b;a?1v+ue1VoQxE7SBHQ{&S}L&xD!;&Z+4+?AUe= z8k!pQb3_F-GQ~co>;2Yxz;5@~;C3c{xh#JF=6B*#pZOGS|4kUhcsGXv#gX6~y2za* zew7PoEe+v6KC%N#**Vwmw223sMR)uRr{^!;iR%mdV!#(DCX_|;RROaz^SJ##et_OJ zTk!IWdu#;HRcbXv!Xpz-pJ64kVDL37U6WV$D1*V%PJz)W^SSf776VzKo*f-V&#GRW zIC>D#XdDX*b55e%#y0u-M$#i^iu=djhX(>RIea`2Z>mHwt%PgOz*YWc4&_BgVf&BaAR@Jf!YS9NXL2`phBINQFnDKxNsi^K%j%DNs$(IePM% z=dxwB8Y=Q=uy(9a0Vmq#i#W~nI~jIQs8sP*Wc!1NS6JwqRp^A#jhN1u@u6GZgNFJ# zJ6&9IYbTApmoHfS!B<;1ZuZ|27ehbznx;Jwmxl+F2A^0MQteJLhtL>W#RAm)g~Zh= zm$A5z6>@4~PTqmh{jxh>e8J_DIXe%HEM#libaxCX2;k`P)41c`zlUsYemUuJB1fjg zXoa3n7WmA#Hd2WYwss}ZR7ZEyusKau1L)a)IbyA=i9M>-KwSi_F?Y|5IBGG;S`W@t zODKb_Z~mQ6`W5dvtwTK<=cuYAMTm_h&wQQ#`)40VpufAjO0oslLp)9)lnN+jLKQZ> zsp~NkRdRlmp} z$LAOD&9kF8>s%TIuStH>90pnKaf(0&6*8MKNL^Jx$&wdu@Iwv*KQEC53wBOG!c{#o zE|Ks=+{A{Yt-u1E0v_i7VC_oJjxK{*gJhehQwh{1Luk!VGM2$vdeMT#AAjaJ>f5^T zuHSnVjvgMtuXj%XLF);gJb4;3b2EAfegRsKb~$PA3(OW3H2SIjpwlv+tBI)i1K+q9 z@)TMDm-^nRu7JM`vevZ@L)&^XLgYyZ5Z%dcMzc@_sazZ7%U##M+`X>)V?J2j8N$QgAFri^7M#j<8-6aO} zv7^V)(a|Lj2Y$BB<|HoI)P&Z?s9F%r)~gk&l`;up1;9hmOr-d45srOv@*zT|dJyqw z60sx`ktD*Q5>79!N3`Q&&6qQ}$Sq}6Ia^}ai28H}T|NCuLfJu-vYM;xr98-hSaZL# zpyC6GU#nch(km#Jar4b@$0NIbiJSj!59T91D2rQDJ4;b1=TTv`TNuYrKX(DLb7N+z z;|dI8TwAqn6HQ(Q*a@5Y-hjfaBDyp1sz{jZw%h*;!;@L0k_q!*aD`0mGq@&(iWx`N z<&TK9?}DZu4fc@iaw2UlyOlfyPi~~x*!;{CUh~@PaNj*Yk5Pb&n8ul!j8-e)7Th<^56b*So2<6aWAq07*naRI`yOi3%3cSj^ose$?cY(c!=l2H8spL^ZhJ*er!&Ns`9Nz7 zgIy`4lT5$OODL3Vz?zF*k1CugSBQ$9v0BT+pVKn4i&Y2B;l*;)L4cQ@MO37pR6@Ng=H7pA8W=UlonoD!;~qSPIk z35itWWF!Ttg##Lc<9nK1sTb6+gM}M|iQbp3rc2n5f zr^dPYgBzA$EK)L9InT{|LA?WSdZhlNgK#+7+1$}na~z|_!0FQ@`#G}=*RIh4}|7sP1UD0GI_;@jVMoz;Z;{%hQRDR3ge4-X=)t1M@LZ#RwTJ?eakR1(q6YV zN~u7VHdF5uiWG`SB7A0kPN>Q1{#6ow;j12_tsV(CI!sP*M!`NIqVo{#OAfl zsE<=?q~N9&*iW@&(CF2?H)i<4L@5#ph@TRSrP0|ph(xLj3zb$xGrg*8^EsQd=Y&p2 z7d13EYHRCgWpe6+hyT7TM@+lhl28#pekYF!zGpBX^~!(#mw&}=-}o22>Cf-OSaPQ$ z0NPs79DQXDm#j`iBMTp4lH2iF=0K`-VetlYZhK{Gou ziLd_CH*scU5{=ER8i6!LN=qm_3SsDh@h2n%<)$?ZW_DwBH8)F>5H>!Py{C8G^RTqF z{fZbrJBobBxnhbnEM(*w5pbp)Z`@if3sX?neSj6A(uE+s=D7Cp%&!p zxCgvm9`rP_vSid8alL7jA9LhXOKrr^*(FQiF&MzMt_YfE~K?VxaKiT*s`=jQcEi$$#yGX&I1^~7jL8kDmn3osP`bm?rwUw!IU zQ>@fY<})@T;mR*-NV&v7oEIltRB?))Quwsq`N|f8v}A~2giQ68MTl>gI7*D-Bd=v4 zyQH{C4GEq-M7d3|l%uhRcqzej96giIwvkfLL9lU7<0jZNgNf(arP-P=<=r4=XL9)3 zKi!VmxrrJF&8EaGQOZ16on16Z5EOT~>Y@f*yd#69=dbbPIsDqO{048q?I+O}#vch%- z$(1wn(-=BEjHXOIwr<{r{Rdu=`ySUO*CZ{ISsAiF$%=^AZC(LIBtlV~89$5JC6WQ@ zDZ%O|iK*#HtX(~Tfq{OEo}I)q&p)Si-Q3)S?dP1Mq-oFY7tNWjSi;Qgy#CwN-pmt% z&s2euTnFmBea!1u%^>xoX8#<-e6I zxc4v)3sI1w_$1P>kD9Pct##!{auZV{c=&;b@!t2p2VefqGq`VPjgSwER*pDZDWEH{ zh{?GEK5_-{nu}IxB$$Yh4q{JATfq$Ut%h3A*S}dXGia2p#}MY{rty`p{Tqs9!pbor zQY+g6mH;T6Yt0+v>IIs7-280;wUw}}7r|nyjO&YQhJm$E$jOg^_Um82?Q8fy?|ipZ zB9#n?Z%`GQr6kw!t9+Z$5CMafwZ0b?&2r-jtl}gA4-D zM>gf*FI1S5X4ET@sgPnoeu}%B(x!Bz?^1n@$F%EK1PE0N0AOHCqDC8*yXhd6n zPLj3#R2+F|-St5Xw8qhpvaxiFL)zLt~I0fO2W5QtWD`B6MT!x4+Z$Y=jWJ=A*-qgV~#E60wa5)R|$whlCxs_0B5kPU|Lqu2uW zG}U8fb`dSj9k}B1YtY%$j#GyZ;qVJD;>?j_m>D{yu`!Bd7<6x&OaZ~G#097UpEAD$ zlHYvRD+fR)i78medPIC3{k^UwVzchAZQsW%uudPs2b=IJyr2#J;qP7CZzwBTU zA{DMmy^{wy6Sr4ia}^F9JcN7=(@=6tdan2)PRCSusnw=cCNxedko<)M=aSFbfPYm3NkGN zxaN%?Krl&l%AjWGrzR%R(?6izu{SJY#cM8$%Mk6#KCgtGob#YotNaYiYMf?5`(HVL zE3UZA@nj4&w7_fQx)T#8@q_RE2p_rigLwMLB0hU>2^ATFt*8hqB@Ju`%6Z(haTXtV z(`E%979GBtG1j*`ZhpJ@Z%4e-MR6yR?k(FpG#5L3l0o4vt#SQm|2|H@RtUx7{5+m{`f03MHGr<(PE1UkMQd{tKKy5Yf=_+s z^C&yVT3!=135eSHJ;?jzc?et!8dG#eM<&S}5u&BvarV_3>yxB1Nr*}9L&g}!Umn8Q z?4o-XM!Mt;WSh%ZiathiEwFm+Z;WAUC&}oP@{PE7Zr9B#j8(bxId&}<7AG_C6>3q{5E*c&yLUHpZ@6^IzO3U z*-($0_9>gi{HE>*T9OgOqplSf45Dk}xu|R3gTU5x9o0ga69*(rEt89Cno1fkv@Eb8 z(}CuOFdCzy*twwzYdexi&`{{5C<=37&^}@*5X4^}K8R2xijS-sK&DdG0%NfFY4{9Y z*cipp;}b~Kbs-$jAir2eVWx<6gBx(eRafKKuE+4*JHD+7LPjRej@9=SjY(>Ym=8h( zMTZ7>?Q&+$)?1~$@m^JM`A9?VVjxqx98+XNRsNAFbRJMpSVpnMTUYEzz^BHLLE-W;7>V$_ts`1LPPE zubTlx=n2O)Y05xuhBj&$ZEc;BTDFZ*#-UgCV{*oL5+zr)(7Kp`q`~pzmi^JnF)981CO&nFd>cR{0j<;QbsWXq` z$!A`{u@mD6#p>~aTRw{KfBiey($bA>Z+jE=A3lngUfhS#@ez!UPfD?KDNBN9oqA;Q zi;y&LK_WUEH?7BsFsdIs?* zJsB48hc{k~qvH`w&(34_i~B_4+%UKS{rx?1AASD0-8emTM#(2-r}>N~rZ{@)U_=LH zvLa#d&>`kzX&D%aaPb*1$zp)u^^BjLwDB{g@1{_waV;TGMA3kjL=oq1?v(s=B+Rkn zGJ4luj2&0qgmgn2hQ~&+anre0t!Ql6dZK#I6@5tGu2>GF%P^=909+3o4`s5kX%hve zB7$B0>j*A&RhdV#rl&^m#m|2MfBkoVgWdaw@OO_UQ4H2A(A8eoX&P|G{MGA=`1DPy zMHc42TM+j4%uB^_eO~U)>iOk;j!20A+OHJ3pL&SYvj{BNJrd6-}H*>~h zG30y)oahhN16z5U+Cx~CVS+&?SE8ooqa%cbS|kNpLz~j4KcsiPJdT-?p$KB(llS0Q z_xx;{Y^YRq@QZKZI1xe^YV9~n!iW%X{k-QrZ^xFw^|jWiwVOQA&&{Q~lU@g}pDtNB z+2RPVzXd|L->D%JZtZCD%n`2DmX$=lxyzCmPwo_-CGSOn$gtBFV6j6E5heHeJ{++Z zSI(h_Ry=Cs`Mji7FsS{`mev1Cd_B_OIX>KDXNIS7+rNENT%amPcvq-=_GBU$XbU18 zj|ruh*i^C}n=ic)B}$J9wF!!-t*IKh9b3!8qb;5o?DqiQTU`PtGr%)~g@L$u{LIpQ zFqKqqBftyfdi2QNjc@rw1WxVxgX;aywcx&=J&C&NS@d*-kzFjKP>z9=nf!bS<3kIe ztn**~pAJ?IKv zz!~g4H;Zal2Gv9a*-{J#o*%{3*$OhP0|?XH79Un}ZNI zD+dK?wkMXd7(Y9q4MWi%1_M8d!JE&KJsbP8Q6RCaYY2vA?B?)i{Um*KudU#|^Rp28 zG$@Iv0tKy1`kKGsmD{}ityHvJARHYX#@NWH>w!vB%kfG~0gQ+9_~bOs-LVD3XGRd< z;sA85tb+8Bc{o;!_=|U~L7=>(`~1GYehlSsoq`S>4G9mkIytwy2RHq}4QLHNjbMmX zu@RJ_iADrcTaX_*iBvj)OjiU4PmJOD7hb{Xi6Wx$HUuMaWS7bqnViG;B+ZvNF1CpF zraJU@B{4TYgUN|$G_`i)$ca%zP+uL>fUT*Eb z{j`IxY}~M<5gTo0U59267#=!>yMJ;Y4jvyDv9-CS-Jn}0U~bJTny(mvR6_0UcMZDs zyUiUg*3NaU2sa@V;`C4=fg?wcqPwFRpZn}5@aV4J;M?E%t`1RtCIwtSo9P4)o_dahA&*7S_xb$( zBoe`S6+sl_@;oWcIguD?=j!@@u(wtSH^j>_V%$OXYudf{5DEeyMO$mn(VfoI&@@0NXB`O zEop2WJP(!JxiW0rW9#NrS_kngrJxgh5v*~ zn@}J3KhLt?z2RmAesahAsz17SKQ7%E#m#T%La{JoaAzQiNOBE+de`G<87bq?iE%Vt z{Vwd?^AuX94`6#w8iUSRs1bHZ z(otnd%T4Fl*WA*k2hU30CMc?osq8h%*{i1pLxWRBD{I4XWKv|Lav2@%oz}l|^V@#* z+9v}BAv=Vcy_;`B zU-Ldhf{TLG)$c1+5RNurvDAjcPrQiNUf+*maM3MRB3MC<^aX-3gyMCWoCBWQeGHeq zY8_(1arq&b_z<%_iekjDn6JmZ5AMdnlLbu91&}N8|J=x4xFn!4EKckYeIY8qL^n`g z#2YV);kDOahL3#lAxtbJasEZGLOGYm$su}aoYie!jWKUDD zM8iA78YjVe?Ey?q@Y$sB(T{%t3rj^5iWPKpcIZ}ElEkfKQ&axXcQ}eG9$YYY?FSFX z`u8@8+Nu)0v9VDlij3pm`1)7yMXXK=k?aSqfHNRi^ zzJ8K|>)9viJ~mj3yDVhdC+j?T*-m=m$-TJi&bv{nP>Z30u1pjI?O`-g@QUaV??a*v z8#vJrO6u>(U1Q>+mXZ_OBDtBr?-L}yuN48ju7p!k^a&*_HwnZ>{U;4uuBgQ)NCMk1EM;!pyI?jFb3=ozXTAy9I1uI_<)n`xp7>dPqz zvo~gaAnVs#2F@Ex0Ux>-azu&k1}Ynt^}8XIRIM30Ff}obvxJyMa52TiY@TX><`l>z zqo=o5?vDod7Q{W^A|rHVY;O}kQI_efW644{IMD?I=eNMXBtoJyaWT8;kPdF@1#n@_ z&dw+s<~UY;JzXagN-Q*jRO=0yxQowbnIO@QnwcR5LVPBiP9-&2KnRQhj?RdlgvG>x zv4-l1zvgQA9xm9kT;J zs;Z7`lKtogMil9KBq`zlmIUoQB1$ef?^l@6aE<<#%I<2GFKihn|DM-Tqx zhr7^QUu~765S8YbE+bi>GK=5evI(jBw60%T@-ASCwcapQGUUStHqTsVvc-x@iK^p+ za1Hbx+>hC*BEJ8lUm#ba+;{{lmaoEnfBlOpp^YbPRFdc6{<-Zv-->CZQI4gqgpLI5 zU_{m0!0~=eOihZPb=eg!#ffWIiMuf}HiEnEx?8Oz78iU!tj5i!rKY&T>*fD*50iVu zuPYJH7<~BLg#!%yx_!pT`F6OAi0zE0_!@>Bd4)nlS~W81 zS}yiF&EKp&SFhvHp+jJS;~h!;f!?U@-TUL7uGWeTP8VagA@2siv*4Q?pOldu(Gf2y z#%uGfWlt9Mh=J~dBiQrI@ri*?AS_Y0_7G#u|NQo^c<}xQkuS~Qq$O!AXrpkNae;VG zdQLbMZA(tFi3svLGPG203Sl)~*JyN&_-yBmi$BhHLSI+A+3A6hXC@s4D4tWF#`dU9 zK&X{XBq+7qR(G85(7Dgoy!}I+ckX(5o?)usPU~1b|%pX672oL)} z9SJJqQ5rX#L?{x%!dL)+K!3j)!&4Jzb-m&7atZ%AIDlj*iuW&Hjtmc31(6U&O5<4n zwivqBl2uy4`1Az&hiiCx*AXmRw+v@pv=Z$dJRn=KyKfrb{*R{-nB9cpR1VKkz5U;N=&t5h5iS zR>>aQA;l>XPNe?vu0664QeFT6AOJ~3K~#9-+s{P4>rzzW3xJxFkG7-LxEjtzSiT36 zF0Lc0v7iXzVJe|Hc&%DMpiVKNQIrc=~)QpTnYYw*E;{umZ5U))H_%z~Fhu@HLq z?ZKM0>l@->T!+`a`v!dHo8Q#L0Pm}ZN&Wg)y6%l}Tyo%prAD3H*BS|cgFG9stz*c0 z1dTsy8f|qv@xzh_}c^jz%$S8(^w!6WTHhRzMi^yvwOSE z*?Lo1H0ff`n$-2oF-)7+(}kJoS@iZELNXplp;*QR=bnMLzwM3KzU?_xY=@2<#-Hx_ z8(LdhF*QA@B;J!2J@oIBF%dp_AHqf)^Z}W1z}!#`4e*3VAxjd9o1;}xwQ5!E#hRH$ zsXY<40>Wh4sjon$JVo6qIB{VV-SLX#?31YoLL@-)P;iL{N6*V8HzzN$b_Bn9^pIxp zlTJ>W;%)5DGnTRbFoGzPStB`Wg1|{ivsm9#nbm6!peFpB2G<}{ptQ(4tMq+M|(Jq z>z6FT{BQzA9wt<$3luS4nMCWt8gijQBo@YS;+BQTbR{vJEn;G327_aHJiG50Hf>&u z)6Q6pRBHycS_b$0c^Kl;FD%Tj6x*FSmlPJjV3?X8Zfxhn==_a z%gF;luj*yGd1)RBZX@_0YGgv{s`HSKpjNh-Z*G!~_HMLfm^7Ht6P?kNd^mEYGG>*E zP4_Vc2L(TaqWK|5%!0Y?`Raq;$BKl9u{zdHol6i_wW8odG8n51q9$IkOI0b=8H22F z$hxNRhVct#9N{P_Sj$XlH1Z`=DrWNmEa;l2fJ*Il>J89&krzNC7X~PbU5Ow>z3~!9 zhiE?*z^Y}PNQR0yb?rjj`0m$YMJmTzFU4JdBNw>Tu?o<8(_hMeX>oM60Cl zA=tgD1aW*~N|h8VymVU|u7A(9IP=VNta5Z>Razf>uR$A4<-KBSjU0x_v2kRQaV%Q7 zs&SyO0`VW7WN4e;lp{To;44vo5Gf!#1i^pJuW$eR{QvvP-B<70J4~E|K@1NZ#K`dh zoPPFs_`}2d@Wnq@Pz%wW&ZK#H*n6R}K)r&C77gRG?>yZ}zA`8^T}-XgvQb9{XpbWM zgjv<1*VX5N!RnISm)xv$EckMF-*YdXeDZmeYjr(~j!Y*OEncX5&!nG(Uk`8l_t~iI zhyqE>D~Rr%1=z7`r&a$mMr?cS<*&e%ue%gaKeN?2)E2O7*8x2A$fGv;TPUa>&m@6~ zHX&}g#JUy&UzY?!a+sJvaLqB^@cA=F@N2E^YZj;Cx*MM7;KwI@D}%42_EM!RxV)>g z3%NWMUh7WAc}C-!7p-eUs9aEMierx^fM=6U{KFWTE3oYtMKBV*rbU~-*D)Mg!lmBiI_%s z72j$B+#uCubE!ONcdrkfv%EfN2_eKLRhmE zOS|KU2Fuv8aS2X6c@;9Tqo`M`|2;D?j+tB)IgMRKP!A@s>?JoL(Y4ABI3;Q}De>aN z%O7+zQ=Eb@VH0|A2$rjx?CZ~e@pC->*i-n*m;YVDNS4SuH9A+hFp=X6@t!bgI?}rp z$9F%5hqsU8?2}hw&EhbICT4NRubx3ZO9G@NwrM(DE?9v6ezPYd?94-gy=HFsnW-67 zc3cGUL<(2D`U+fj`K3w(NvI_!#UJ3!AZHtxpI3jhFpE-=NnsXQX~&xw*yfW@LEF3q zjf`JOg41f3fslh0nZVA4H|HLRJ`nP6zux`l>>zFm)A+=U0e^1bPL$!|K;Xw@a_iOzQ3{2pT@BRoCLdeoFDI*b2>F`**WU+1qQ3jKlg>3H+_x5Vf z4hPSorVR)i~f9xMdwGu>30#Mf9 z7lTZWzq}^;QY4iq^1Aq5_?~?{VEaSpWVMQOFFXaWx%@H&G*aG7^gUwY7m8nV-r&w3 zrYr!I^v_v;{F)cWV&cG$#~*)O9xR@}U`T+e16vZ{NVIN`SygZQ&DwF^>%-!X9pvWj zXry1O`c>6es#5#pIbtmkOXijQXnvjrqvL8g;yK%}zFp@>-`hJnHMYx3Bbr0L6DQUx zg(`l2=WPfV`++(=e_uHE5biiSOh1YxmP1o&;|k1VhgB-kRfz z#uJl&iA_HE7O7XG^o1D@oPWCFEeK3L{u=2d1cMZ*G2)-~dkhBTfyl~^ODtSZ933CR zKz1A*ts!haX$cl}x1-8{9toim0FI9z$5?q9Q^64|-`I_%>)U}q7Sl5!96H{L@830! z{&A9Z?17U6D7dY{%(8%NiLDH?iB%R|F3XLO?FVufc+-`wS8L)Qh*=&C;r%yWgJXMl zV`k?eM43sWCNm-S^Xl#Gs8ExjK;jx_K7vR^Vi>8{G1QXQ&oeOg4;+_<0sRcPIJzlD zB&LZ~az07$TA#pfha>>y3HxiQNAjzrqd!udwC&!1nXD`Kw4j>i};ESLC z9I|;bimg94a%3k~FG`@^xdj2ouC@fMsdT0Txj1FSRskJMqzyWa#KIWrA3;|q4@v)Q zO>l)7I}rvZ6#aw4LUcB4+|;Oy`JDMY2Be8mwbn+lq8V;go8rDyvH6r!(b3(b!_T8% zR#Dh<_aEN*&Vt(u*T&o=!B>>cpKEI1``;(hoFg#`MG%S3taS_J8GQea@8At@yb||6 zvK_zLy985pPB^%U0zXyY0`}6_IDU2O87Smugs2f{;Wf;?PTyW@BsrSkFm_!j#92p$avpZq^I(*@aU&EfgM}b z;hopK5eE+LMJ`MCL^IxzEOn)X|NiA&7@eHenkU4qL&R0-d~OnF(*z6I@}{k!k+phV zJOaL;M<3YRPpS&15+`+6xVBBVz$1*l7th3>NCQzuCg+S_@@5GHwDzUDFgt@xtcH^p z#xzaQmQLz#X)Q=>iK08eRJMRDpZD#uyzI3#35mS}k1L;-|T< zHCix^*HNxegp1t)LtDI%7x{+%{ZriVf|tJmf$7IzT^EUkNdjT#s=?JZ(#j{y#U96K zHiKvOw&3_!5UJ1rUU5bmiI(-KbY6&TF^G|YLDUNc3?1ynXK(*H!m~Ntv~n3%Cfh7? z;l@D~0}~@sw`+~XkyiR%`ib6y&CdNqWjn62i~H#Ugb;0#KcB35la z5B25O;n63zVgK%}*zwGRrdTM&C|37D6pB^!kJC%QU|3dr+)#Yu@mNwDikmK<%d1-C z$lOI2oQGA*d$4EQHpGU;fubcf(e^eBjf`WgN_RiHB~}rs0ZW2mq`O)X&9vd~eZzpH zYZ+Vv67AsYu_9n#V;jV0ZBp8EWF(969u{iqCp3vnUUS|uWXtxfqVoZ@ksW%o9DjH? zB{O~>VOTS38s+Q!yx4aVYnEVEn6<$ zL%Ed2OHb=TOZ#FB^!FjyG9OEquR=#hrw|>sWcTfS9^1D+h4zjp&OYnaSh)7ohVz?; zz?JIEVK4KV7}$&XS;2nYU7cXR^nEwJ4=a|h#GBsyMpa23W|uy_`p-rfd#*+|BFSKb8jm>&<6jo7TjU?79X4XSn+QWyBVbP+63Y@py zemk~5wH3GC@-eJkx6YKx=1QcBh-RD({w@kNF>w&=uklG>HpeNP0`9*1k2w2`Gtt(T zR(M9d^K zW&zqm-ufOQ5v2k?aN~9O&__OmC!X7n`}$VlNG|P^7hP+}+y2&TNLI)2m#*~6v-=wN@ph=7Dn+dA6OJ+B8p{P8dG*yCHB zQ={!6dmjOzZXT^-Xyw}CTDj`V*T`yoVsZ@QW8;c@WcoAl6k2tpNkJTVTjunKY9&a9&OHMTXmu6duh)(oYv zaXuad6!7AD;E1rKxT8@_PK+Z|E#mYQDYUZH5VJ#@gL(lgilI+yF z5@}nnRTqbdJTA3nrKD&Y7feui*zuYS=`j0sCN$nKD__px8(;p64p3WDO~p(@g$yb5 zYspJXD^YOm1x+Y8g-zevr#3(&7{Rvf+p+e96ATJ>2{M0|UsJllg#TZVL^sXEd@}0y zg6$J$kYt#BgOi};=z8~(xp$K@2lqUQXP^3u5~b5NpNV)&w@^`Dv&KbZamo2hq)BIs zp;t7oV}a${XSVJv`BV%pm2j;0Fz)}uFLlNtKwe!{L}$ihwH@3V_C=z9A2yL^h==M- zH*TqMc_$s+)K735&EYMU;jH7=%iN3@8aOv4?SiKl1*5_d+c@g#=p4MV%X-#2rV#3Dj3OO9!w+FxZ#<#IF zp2qt21m*=pXyNn&51L2_^V>5>2f~PHB#a{&6->;|V03Z_k!S$1WF2c)FGhR1RfI`| zt2kQ9;A_wIqZEvwXMPIf$DT)seHxDG6`3g1kSzspu#bvmG{CS;;Ee0lSkQ%7*E~GF^8kjY zO_p_TKg@3iK2(jVXruCP%lMSpIUbdV`F!A)^{niE4a%~_z_<&JN8UghJPKilYg5ac zL6Jda52cJlVJuv@P}31~ap-UGYv z(wASVaaPZ`_J`hF_}d2pqAz2kgCdO*;ri2`{)E5$-+lP#hdzo$OM70Rwa;YdC;#$>Nir{0tU!&%>ubb&K_Us})R)j-kK559h!1Ql~KIPbp<7wwVLua7>u< zVlaUJ{`K#1|6l%!YKfc@I|R&}%SfQy14LmiyZjPtK7BJDf9eTDs=zBRd!@d2dU_UP zG9AK1NgL3y9B47@e)G~MD#0T!`c(jvv`?HY-j;(w&3>1R}^ky zLzP2ww9Wr}Zacvv2>#y6Xvj_DJo@Nkn3|ZxWmjCL`|K0PMujgxtcvg5@pW8$!9_^6 zb>dS$JAi%p#m>-&fz`Mms$Ob!L;_j-#|^8oywfK(Hr1fH?Ku!=vmN7k6?UZp`9xqf zZxSQ58N$H#M|6p82T$PR{%ULMz`{j~q`*lP%ts%69DDZeK}jZYA!J&T*!+^0;Iz{= zBSk^AOd8{3W0>JIgCh$waFRSKN%Ts^3W{qyd^rjel-e_uSNxW|z` z`s~E(MQm8of^^)Z+f^YdajxUpJx9?yR!2RWRKltRp;ASR=1}5r5g{{2OWz_Os>P9W zCem!%7?;V6n;0K>(D9mAtzC$BU-Ne7kZQ2JJwJyM7_-V+fdN0ZXNiNqZ`N8MN5=%; zyogqAdRFm6d(-vpjq@-EHB$v`0#p9OCk)&$K1uNYIre@2n|+d?k&DI@g<>~RKKXYP zH9~#Q-9N#_n`d#~g9mZJE3Zdu`wA5Y+)Upv*>)F;A ztM_a!kG=a3%9+?>FcnE>hGx1JzNNzb=5#Y02hPq4$59Z!!o_)~pWs^(zQte! zP)pwBs;Un|s&yA?Rh-KtVfM+Z>ejmueHFoA45fMtb{x!Ow!R#FBSnl3_2a^mTXEtt zDi}_qSZhPB_0k!M0Ve#4%F*Y-)L*~ff7$znSPE_X3@k_DK{g{zs>^e0?@3Zcc z1KxZ;@9HySWphp$%eNt{r|iAg)edv7VL};3PMVWl2Y`w3F^%xCiX!~IX6>36K-C&I~y0r4rhegs57B>@#Fn?&kgT$(!?)ro7kppax*NkD(9#1KmYrC1+wki zw+pHH%9s8P(L@Yew{AmcS34FiT!f*a5&YYizl_sQITi1@{#qP8Hh|l|@eO?7rkk*O z?J8ADT;@BsZ^eq$>o9M@D%XRwaNz@^^+_3X0?si$_z3rOo5JMP0`RVtRG)ce0 zAvZ*$2uIFP=6Yrtk3GE=_ucz9+sY&DC3==DHH4!cR03{QjBjFxDehAs|NvuD06Fzp^{djbA>6~_r!PUMU7DfrLUO9~S zz4;7rSIji0$xWCm`1Ha=!GfFnWqKAq+3^*XlI~hXhwsqfASNaz^t#*!guV%dc64^i zbc=^1*SP%-Bk&QPXPbuAyh&TXaLkT!8#*8e3zI>g&*A&u`ym2hGdJQh;op9?-Z(l| z{c|%G`C+H(IA`q(3Eq0$%;#uK$lqxf>-V1_^)@#|WRbt0EvbWh4`Fa*1evys zbZC6>$G`o^zi-1@d!}7kBWgyF#XdA-n}_<~juez>Z&x+b*-g7=nxl}ol}2G^2sgdsa_k>Zp=bU=JpI%^ z@Wdle;7wP*6-!nwSKEm9b6{WqyLN8H`RBX>OINILi`N3gTo~MvZ3j1#AwH8uc6Jn> z{q*NekuDg(ie)SC{tvtlPdxK9e){8|>0Yw}Q7uug;g*ko6ib&c#%DkOZ!#|W-ksle zs*EM<-@iu;`LoV{1;Pe;iaOAXHM0Rpm{uQ}W88^K5W^|`o@zrmAMfXI{ z%jt4#eRdo6?AVJ-FMS0v9qstYt)Im3;eK5Io_C?EJA)H9Y{Z^}2QfRD$Mn=N5-Dze zJFF(Br=@8~ZpCxko1(>M4i62R-LDhfVI|5#hva4^`rP*{4y2_bGbLl-6UkH%cWY5o7&6Y{zNKVuPMoJZ z?)ZVosOptV&C|IW&Pm8D$%hgIuW0E}TWN0FBG@la3NCzl=DW=teWpyjp%9*S(1d~LzxJWZH z9!NL*F;f5lAOJ~3K~&lgGMq9JFq30HedTSjed2ZXn=ZrpwQC#F%2u$LQ>VBFT6;~R ztgos)Dbc>4ugAR*#o)jo;%*YjSJM7a*S(qJ1gRJzR(I13%Fci1G&g z+z&(Hn>~I$NZ$hDTHy0x(nwilPKZTg<~k{}Jt{Z4)~Cf3n^+-QM`T1OkoJ|U$HjWH zc+Ry(9*Yr|i6|VPH2*W232yyg}%>I<#(a2;L@B7F%0FFqx8Cx33*t{&P*CNIQdv}yEEvg^N z>@5`xVO4u8RwUv$t$QB2LlLw`VxZMAALvXejO_Ur;X8l$PsGA`BqD~LQ_{Cu529QP zU}ThrKg^=-=2Fy#FGrQe&P*!`g({}A1$1Y+aKe_?p-`)0d}tpE)8okHN!Uc=C=b2<|QQt z_2nP$$LNf?2~vu4erFh$U9b{A`Qv`n>EKr}c#Am=vs0PukbPYXAVRf8IY^pVkA!A8 z3d#e7@Ezev1yI}Ee6z-0HRy`>nNr7I+L?!~=H}g$L~AB3!X^8V3|exQBmtBVAg_UB zPR?hyv?$nnU;oy( zacJK`Ava#`oq_kxJ8#G2^aTFp)=#TCj>LoLZkvZs{J&dpE>=eNI$6xBe>C4BXZUqDM6#}IA35s~6^dUoq}j1G_C(o0^3N-&6b zy!(2jA_?8674sM1L$`he0|P@C8X5)yv|_c*%4b&(hVZdZd{Xy291SB$xoHMW1n`mf z-GuXB@lpvVF~BC(3Nm?dPXP1>xJRJ;J)E0(`6OX3D&P-b|NV2n$5$IXP?@NDu_f~s zDC1kVeHGVT_b%M~$bNkL9}!f;EhgCSeGxRDZ9UBm9n-k|y{Dj3%`36x>+v~yX<0pg zhn#rkxjrZTdKc)$8s{%JM1csG=jnL#jIYOOfxfLMUqneq znB<|)_d&E%3Aal!`16Jg*puSVFiEBIqa8*j^X=u;`5LlocKQIaOGikt+-p{NaWx)N zOdQw>>F8{e2^)XE9eP#QIom)IAF$c*+*{k3@FqU%Gr_O;_K_~c4A#wL84eiG(?bJqEnAy9he4dkx6O29Jpnyi6& z&~Ubr3zu~|XLPvZr7ahrDw0eiUmOo3{7KTbQZG(ph}*H zWMQpW$;~`9Ig5M|n9k;bAh{aS%9hnJGi1WHOfHBd5UyplL}$gG1q-n6z+Qv`=Fh-h z@8IB&s*^ZfGLs3s=H(lK)>SxR!zQHSDg64se~Q85eR$O+XJf^>3#FC*;NS1X_9y>_ zuJ#tZ_k&-Q)v<5ID3f=-=yNMxZRBbdg9C@LXyFpnP{B>_|1iS!I==dqe@8evC{ z%*f3_!S+&6YIwazj^d8*`~aIzIT@#)ej3)UUWG_Y3eywgNVjz(ooUy5)`ntiaAY$t z;6l+J62xfx{K?OL4uM)7Km6_;Qs#W%kw+1(RB-XjFIE+>d&dqeUc4Bs=~g`T-1GS1 z4}ZooR2AHe-z z@``cVhz^Y+RNo*lI`ZO;H@q9S-tr0j=AMUfPu~fcthdUa#dQ8G2JjD!tJ-R#`0Z!T zK`uAxCS{zry@TZi?K;AqZ=vvB8*$2wXS&Gl+YY8~XNQo`0;kX?WT0MC`(bckK#3iz zX(stZF8x@V4jw&k>-Wksm=gnvX>Q^{HqlI)Nf4YtTRM$@|Jv;e-2Q&>fG08d#V(LO zF_2M`ZwpncNTsNiP*6-YLareL4c><%>iQ8#CJYiTa)&9WwKP>kCtC6hNP;GsP@=ti zRC|=gf=x%*J>t6Xh=*@QQWTA?VLRlDLLwykCW4%)`th}F0wgGcr1TLeJ?#=ai2@Oc zAlD)g!s}l5a%?zpgJQksQ)n{AwFVlbMUN7?gWRK@{5q4lq2VEMK6q`GWKb4-PGUh( zHtLil5{;IH0}MR-)ezM=*3vIdh+nWz=Gs-e=^W#0**Z}#W*md91zOobE+ygopA~#W~TAPQ`<39$h(Y~s)ICgsv#8*U|CNL zZLL6eI~Dml5sB9E>p$(oSe|f15f^S=h!s5~{QwU=H;(N`0(zhP6N`osk5RLtiuOzj z2agP5_40)hhZ&#F;mp(4VCSx0Tyyy%tY2ZTIh(6sdOD1$8P22wnYJXDAVnqQW?~`1 zP+W_%UNi4?2F1RiJpT01A&ksQG2i)LaA1QHuxVtogu|m~O{YM#p^(i>pT1bgqb)_j zm^{k0ut;E(^`@xg)vuX{sX_>yi{FfSU7Z-{KZgCgpTm-cD{=12Ufwu>JnPv|ZT762 zRR^CvCq?qvX{0l42u1?9`Q{HwplRX!9z>#cD7Ln?AQ%oR`RnQFRv(%KqUX2m#Gc)I zar^DJDWM`vcf5Z9sF$&P#YWU61Is@a)FdY5DtNBr+{_r%f~nTyl%YZ?N{TGr=G!`xBmyOecPLG;ma<s#N^kiNC{krQSS$txi31+~arMfKL#UWr#;d4-cv4j|o{#$EsWJIrry$2sSn z(;#u#A>gMod}?5Szc?|N`?(h<3SwfoIdB34zPfwy-*?{r4V-!UsW?75jqf}V!tqj@ zLlWFL87rwk1=CM|4{fO^{`m8+qE;A_0GdZYJS^{9C36o-MpU)o=E(7S6Rbu6RB_o% z6nv}54%C`Pp9cm9L|)`U6N~Xsvua$2pT<0mr@+IO_fXE9N)&41XqccGTL3u>kB;Ei zzx@-!PP>6)*GAgoG?=l~J@MF762sC?A#sg76}}D+LBncJ_k!*hW0>>l@NF4Ogl#g$BQdt7TxIQ(6Hgj<+r)Dg zyk>ykJ>JE!anQ=Z)Cyq!UXBnFdF6Xe#Mv%xdYnh&yyvF0$?-*AgFt+T>Qeko`>;Yk zoq|n4iR^2lOY|9%dEnrvB;9o%U5t>cCHXZjX7cT^5Hkf|OB{qSs2$}-?;XslF-kYd z<#Cm{$fFV>PCK~vA}{DnA_@KXzr7xh*ANZ!LD)^T!=5i-$b!aaTr$9QOcf}N=s3$- zLkx{w%1nlW9W)Vn|7RXRKD-c|x8w~Q9UcY{ZeL4(C z=pxiQF)^dxZBoiMEy}=89z`e^0Soo{8TN2^t-ML>&yk@_8EMWS2at5;7=sf<>^huB zx^oeF7Oca&-ucfs^P&y-`WNrSv8@lGP%dCLA43l3B9QJxbmZHpm#46D!#eEUwF5CH zGD7J7+2hCLN5FnwrZtLKm?%OWM5Gh3020vvx;r{_ppg;$#E#>bm?rtKj#NB|u1pB+ z$q**=1L`Wq-jH3#}#L#(Uswbj*6cU zAT6{WKs=f>Lm`od%)df`p7Z$(e)`^^5{u{ePvYLEMi30QO2yDfdoFW#eMLT_o}PIU zRmslGXq>V=S;tkEoQBZ~$5t0$-=1ASbp~5bn?))?^$0w(do6cc2n?tcu!tOo0 zHRFEz<}HGL*=}G4FFWjX8dtyhO5;7$frAJ3Xj8A>c(zb4bv9+FWPApFA2(?si-BWD zv2yh)3{Q;X6Cb`6r=D~oZoK(=^VkScH^94!n)nO%3=fK1KKFS{4@}^j-?|Nvcofsq z6X-iWDzl!qUGomKBwF1Ze-r%Vx@Kk6gj^W}0(k8!UxnAd?P^m^V~eiEoHyt8^sWEj zG+3I8BzR=Tf6o8EpY3l1X&0>3u5x?@ua)2-O&?5nU$;K_6pr@p7cb%MUw8=pwPg(h zD+Ou}BcX)af!||(&pf>A_2=WPQ+f=UbOnJ=5-jN2&-kQ3M}h05&LvgpdYxLStsf(^ zHK$Gd^;@Xty&{o}VmRd9@cV4qi9ciFabkE2NnkQSl+<+Xd5@{9!q2g)e&U&@aR2>} zse%_lIUGcGHjnm>j1^4ok2i86L6N>1YKv&r-y9TmA6*dUGiHHgln5)$K7|%0?n( z&)@MCgl5duF{$FL3ob|CUqA8gI*E0O5VJyZ52{EfL+DJ$Ft00yRIIM?zmOIoGiM{m zD0AZYp<_WZE9QaD%8P98VyTXge*Ui*4=zQ(IhAn{j!kgL5VGy$&Gs&bBsE%{EMSK{g->SldA;8Pvu*Mo zW~LE~#1IZw(cQ)>rG|7oh;)*We@K1-+KALwh=!4^RB->3LrBKhBTu3;okBVpluYMe z9^Q#!J&x%aimL?B+G1?x_B4B-RZL9fu%IV}XrPL*i2}~pG#|@4ONd11Yhd&DCN=}K zrpT%`r7p|rjqD|HtdNJLfxiB6{Qc=+Y&}p=z~mzIWvmMpV#%rd+)=ae|L}iuH>aKxgb19yf4TRCeGVO zqd4)zbyzfiJ|24HNo?M@5%2%!n^3KnLGK1mdz5NbTzlPhYRUM1IyXKK09Jb@mO>qM zH%|`W<>#D*_uPClidA#KB$3PZh&P!Epzm-mdKNC$`}4h3>uWb>!TjfaQqYK@bE+#p z&L`<>jotamnAX^~X4s1*iZs|ifV+S9YrNyyYjN{e?!oTD8j)`;*!V!pnam=>!5TKV z?8Rqqe3j4@Uu|2GV3oU}h)vZ+|8E!b9W&gDLVu{}{n@Ru*L1eszT)zuVydvj;i#yJ z_pJ>frc5Ty9Y<9$Ns4N%Dvpt)#u&p1iY$Kg)1RVRi=a}qDK5qx5+;3>YcRd_ul;>) z!10b?#@FK4y&zI!iovnoS>bEKLCHeXjEB4cdazIxkw3qnr$;KOMkuu3$^AfH7e|XF zO|F8CVsmU;+FB-z%_@`=E#xM!4a4Mt_l0-S8-LmLThYmupEu3p*O@$sU|BG+DNBGN zLNzYE^kR+eCQ_7ljv(TsitRjaR@%~5@DRA{<`Zf&aO6*I66bs2t6{ZwlnglWBX_@8 z=vcqsB^;jr;B*rtti2=M1Wk;w&ET{fTo;f!F6LHjNtPj4rbA;KaZ45{2v{oSFg2ak`NxES zzt6Xytd(S9UyLDE;MmVk&rE3zP)gosWcCa_fz;NQCqvpbTH+&qP(xp#W}JlgUUN;o zy|cB!@a7w5Pg=b`8uYL-r$_~pfjXstsh~%vtQ7H8rKp zL1B{qfdTbv_=XAbL^xz@ti zv%eqv`bxO>(LRKtEynhCf!Mf@PH@EWfQZI0A&UeHxZ$%9n5qg&52J!TF=xKJFr0K(B2u6)B)wuS>Cjf-CMwzo+#cWi77<5SaMk+tQtlkoCO zE>sdcH9d>|fl(bo*S-7QNVjAZ?06sNjw|^?kJY>FPa;Q&ZIN!xgTp5P zdv-n#RI*sSV!fM~aC6tr%%&Oi=CI1=NMHM2H{VYK{*^eWkw+z*oLCNfz?i7u{16VG9F zUM|-VPbIPK`JMRFAMZ7e1C{mIDsq(?gE0?UK2HfF$r8HMI0XE-q_5Vco;t@^hy8cj zk;_`zjZo5docBV?n>DKz<Ng4lR;@j$j09O<{Ba*z@K5Ezygj*0Y|6#x6s{Tj8YGA5{eM#H1y(plj_ z?-41rb7=qV+Yr(YF;O*=KFNEcoV>N+Y%bbPuM*V#kc&GNV_Ed%=0fr;Ek`o zyspi|5t>q23o&2F3GURdbs`X?kI-R|j^k{TLn@ zk({m%LLz0+YE-aBvoFO%cV>3Vj7}WX$132Ijcc%Df3LB=-3?~2VlR!*8Cmy)i^a(0 zVM($G8OPx&S`tCDr>Zz%K@7>382lAz z|5z1=vS^#7kA!MSr$UGXD`;(rp*2xQYb=a3rvNniX*RS>W>PJ2OpQ-qaHfvEN3uw_ z#Btsk>vf>@9vi|xwjM%>{ZS?&p&;7ZGYHhGSUkTSPd>K~t5?j!g(r6+6Q4mckwUG; zL?vpo-c=eUlD8BeJo6-3Ii`UtmdKxro`BNr`5$H4@;cTZx<) zR>iz_&X?yAa0E|U@$%HC9 zmkW?5c~Py&7kM}ck@T(3W-c&yZ#K{dwFjE5O@9VhW$L|An)B#$+ZNo5zHP#FW^%ul zkTMA)%e;^;X^-@BIL=q_^s|gp2wu{2e^x8OS|4Usl*tc2Z-)(&3Gysv8ti?IK)0V*58T`zMbT3qg~rU$uH3p z*TS*H*^^P7;F3oZTnp3E#^!jVkVK7(h7@c228Zzcj=lKHUmix01a227iLQF&l8cw5 zXwyBgs#_B5;UKy@lX%OU-iYPP7V2J`xtkr@mVlV9iixOMf@_=vXGyPnZEI)l-&QbZ z(ceFYY5*oHPU!%xU!MSYM9t1)-WRS5wc}lj!rENc`d~7_pZDss93Szoso3GhK>54Q zJpU2|ZvV>X*eO6D6vdzK{xjxvcWdOQqq`Fe7A}$!85yi&6O(co(;R7yCOHXJ6tlUk zDyw`puZ6}97K#vp3W{i#%N40b)95Q%a$(A8UZ}_Vb|Fknar&XIteNB((ooI-e?Wl0 zKWhudhlkL6dasjfZUnvyP)ltUQRRvXB#cgz<3XM#|+mW>Z3UXNMm8;+`~) z^$+X5owPKDEgM=T#8Ryn(ALWLL9!DAE$8>ENFD7Inj52Hy%i}=bG_`f}SdWRfc@$>QLIBI!DT44Mc

    C9#y4LS#vFaOgRnhej*f{{+JV&SMJn0D{lhx`BjunG}Y&OAuPEg%NyR2I3<86%l6_yowq%_I!+ z{_&ohco8{6W;f0WFT(z8?eIe@+96;bE#eyW*3#q#ko?Gll?OK~#nI6*B`9jYN(Iu~ zVJYrK;xP*$9&%nznd^Z?5MzcJDH-Xq!HRbWskKo!-baT=LoN7yEEIFOLc`;L*Ue(h zlA-`|`B}W-wU=St+STGRC}Ed;a}&+7&O=>BT!TY{GUM_s0Z*d0b?b=CURv963#?t? z62XRax1oWi@YvM-XjFPy)D{=`4_*_W=k}ck@S~sn2D7u%;KtWfj9xk+l0QQZAE$N>#B&Eh>6z zxHG4bB+zM7=vE2i6Vn(SpRm};Rt{|gVy2Sl#hQe_%`tS+DD~X+Zzs4a-cG5H>d^)yG&x z&rZ)GnQAduq(UQ$in2>);?q+T$O(-I;_%U<>Y4DuxLM4N%`!m|5e4nr+_)dL;Ybb_ z^7L$0y_z%6I2GHr??X##5+ObqcO#@D5DH0eod-PK0rNR#%2Zf0bRkr);4PQ0!hiqv z2~5^IP?KH)`$smqqN+r5veqXuc*?{_ltntJTPcol9@@<^^AsZqkOaPtWCUxLCD58= z*3V675EDmr_;*C=a8(3Jlwy^@UT3L<#f#^m7Ea)<`}Uw%+4sju50>-i1RBs>bjcQeUk3-b3cQ00nQeDPDC!pCm;1S&OV(Ux@=^0Szn9Bas< z`fA7bnk`YXOr6h$hryA6!RS&IeQeO_a@K zpQ-Nw1qP_nil_H&XLvQ2u+lFFj%- z;iVX_yF~(I3BjU`Ekwr9xv$H$MeY_S6v$;@TxCMSb{)sSSy0i{ zlt6IG@{48n$@g=)CwEmxznGlOV2rUZep z)Q>~@z17>>i%hekVWskVLf|8`Ha9xr%Q)`dFMoT-*v5=W(o%p3kC6} zH(i2LPTpi4vqmyQ11R#oOj=nOiWFYFbo&51bMiCnK_pVc<%Y#(giRw zh^2EzTJx<#gJ-qSQCC7zAps}OaUn`5n;a+)P$nCMx{Q+8>_>936M3LB8(SSj97xj; zL%CW-S2}~?F&n`Wq^`a;UAhX5Sys(pyTe>$AgUsI@{oH7{s7Wqp|?XkjGi=b!mT{~N;Sfs5n7w5m;bk~zV*H21hrbV>LFqBl)muU z&*7%`-;57^{T_@(R_cBm_nXrn41Cr`2v&+%j_2^H54}w=xNkL9YSxeSe|Y^e)L~5F z9@A7+%}|yjo9nE3f>j719fjQmZ4 zY|XYd#FTth#_RAr0FUPI+3l3>{BE2Asg0)EI3|-6&s$(IXrq@TY#T}- z3;9S?lO$Zn`Fsf{tXYazU-2qQw|l(+KbgX{MS|bV^t5;mT4QeN!!p%omFp{IG4-|o zopYoUYO({b$ypF4NuoW^8!)kZIk55RkQ z-(T-VCewxsE;wHVRu&0L$XxrG`$x%&VlQp%!|3Vkz`Nh|dSqHNPK$&4i%FCbWqnf0 zb_2&*`8SKw7b6KwqIq6%OtM}oVPtd$Ba`Er;9}Ct6Vuv2Mg-;k72n1QMA_tyJ!APb zxLD|4M+un_$T{QF?##2X*E+TkN%-J9&#wmpaY4M{SX$P!v3LTpZ~~!N0+o{WB#Tmo zvhhd36;8BB#f4=W8g7w(r*ZOwQkr6s~n4Cm6C{wBj;e>O%GMvkvj1lh?tXwta zdqZC8n4?f;GhH;#2X3?gFt06y^G@!@vPDV6;|z|ppJwnbNp4q~<2GSSKC8Sj41P=D z8$aKH*=kx4l0RsR`Mkc9cC6g6(svJ5v8XGBJqL%7Zb{+XO)0Ei$f*V{kdh$qWIU+U zD@-D(tGJ1#kU1O<)e$9mQ9Y?9`)NsV>o(n5Gzl<1l6It5UI?dQVSpuP9U34 zqHnl@t|g~p>6(*KkF=s(r=~o$Hr&XfcugCXS0Wqj=`U&iaN zd<_;aStEte#yB4N0j#KXpt1*;!^||re+*W(2}6S!OYBK+Q4#$$~`aazUIGJfCtF$FI%UQybT<5m8+`M!{in*z7*Ra%`2y-X2oLYJ z_KY|==DrsfNt#6m&kU>V>WIb?N+2oC-PYcP&dx3!`h?Qe*A3M1&_fU7w}1FQC0=SN zsZg@Hbbl!ORwNS#UaRb=qn1E0mJtzPTw)SOVk8e&{(cc0izO^tI3K--k4k9C+nDeqipAzM&vRlV%mOkO@(6?~wM4I4HfH=V^Z+n&>CH`jg-6Mo)nr%B=Wi5;>m zOjs<05RFIC)z*qvz2a(C? zjx)}?6oJ~d*Vidx!||Scft7b$LAh3qV`4Ul{{Cs~J=l+du`IIrFe-G6B!nA|Bh%ht z0VLr_g$Oy~9ic`$Om^+tgWWs#sdBMH$}$@(c0HrnvT!bR2H*|r*JJPAJs6u9MIw>H z#uL}!*=^gEERdbc13(#{TfD}Av%a?P%Wzzc2Oh^ky1Tlyz_^GR%#}rpT|Gzb&FO9P zCThdG$rzy=wVK3)bVw9A8w?>OOdt};h~{F$%*LvaQ4~-XnT2xE;b;Is_PQ%HQp#g- zcN)uA&&U7#`3SNV5&#sN%D(UXGn^KnU4x3+{O&pbFhjx`Gtxa{nV;C==^ zwjz@85aJPTP{Mtjir`!{GjAR&=96K56t?}01j@hpGfu6G8`i;I!fNQ19$?kXD`K0+ znC_hai-f5h$$4Err)(QsBzH-`a+H;Qdhal%AwHDrB}`7%ux`uSP#AdvvHF0X1KSfs z54eXIplh`dN>xIu8T|Rtaa{VgTTz9}#F?NmIEc049Nq-4S*qY_W6LBIR6^j<`;UkI zCiwNNvo6xuDKl=4Fmau#PpgRu>o>~oJ4P}mRV!`Ef-p0KLKtixZJ&lh zQH+ibVd0{Mh$mVFYtLlq+c1N#e)Stp??dWVcGH{$ujg2ms%4P8xOo12-1_m4Na{IQ zuj+R$Ua|^V9;|E`RM^WDpz8XXoDi`@(BBvT`{!~QShZ+0ZjR&M+~mL$$Bf(+!pPt- z7A;w<>(*FqCL^zeLkACHY;*_@KHG<&N)!0h4HuwNB6P~2 zm$xLcT*3Z>N3d@{H7uea;6X^8)e|=`V}%I@1qBoH;MM4=n^zZig6LT!i1q7MA{+!d zGHqyUPpi#9y@J+EM*EY~OguE^_skdMZfn!T;TV`1ADE!%pb7-Ach7Eo`Rm_yHu24a z(ps995OTk2vO%$hQuU^D(hT+%<9Og}|2U3;VjxdN>AF;e@a6KH959`KNhUj|NxG`? zpqg@oS~{@u8B^;(g^zqJXjg0yJyjVsI;_Hs&zexUYX`VPoQW2%feEHOQ358oq;?)r zVi%`dl1a6v{FDMY8GOG?5(tI+=fV5Ownkf9JF;0y;xi5uaoxM#jP8zZ_2>!5OZGe% z#8Xc^i7jWGY3QS4=&R+}5dL|gWV4V2A;7l3eez(vbyrEx8HMEgBZ^V1RPd|c+>L$v z`h>`;Rixy=ls4_;sO!30(@FFlIf{{y32Tcp`O42a!mw#qc&><%+?z>_h~7?qIn@%w znOoN5jaR)6)iU{9#*5-qR}*!$H75JR$4Whv&o(6EhyPGf$7Sgfl{3!06oLF>7b~V3 z!GW+UD?j!*s4KwZfKV?X$B?|#SxpMkEKv!uu7^;pMp3H9kS|p+GBkrd`v);H36yF< z4mThdBw4|supLOA`OIrIMNTeq zPDhlS8dy{nMIDsNO(7MoLeqs#q|3;w)S4jiv2Mm+Wb=k1I6A!vBUp=$`3qEWF^gv3 zGhFAN~NriFn=wUqa!2P)V)mKXzm6Hp`AMn+;J!=LaKI7J8 z%7m7jaEd2$F|cZU*YQ*2$?nh;RY4*4!_DJC{uqFi|2WF@;~)LRjoh-bawb6x%uGgI zuhKiI@}__HyWhd&^px5POk7&ht(N?_xoZy{T8`2bRq}_v=hXNN&+ zVC{l)Psf%mn+3^o3LukiZzvPW`=mCFT9t4uc|}&K)oZ3VKs3Y8$#W$7y*GbUFfpGa zA#$QjLPF-aKpNM|s%lFRnqB~!f!DM`QSdddm;d%;M8+*9GCZI;GANY6O$G2hG4UXI zjbi!bYF#7X^SV2Qa(TIBBB#7=CKj@%mbABdH89?Iduql{CD+b|+E6&g(}D^M2{pNj zk|>Y#XWX>eOg5|Jkk`xm!}o05my#-3@m<`Z%lGJ~D7w1ZaMkN+4bQe(REH&rn-kL$ zNVl{JJ}`4B7Bo${ZGVWFDN@r>QV6q)(Tzl_LEf|bF8)U%iM{)e;CH|OixPUC7fPNb zU}cj<{NVcF`#f}Lzup_~tIz_MXd5@ex3`;K6gG+F#&A^`IW{2C+)w~3R(9ee|NK7G z>sFu%F?5QbjpEb^Xn7Lx+=O09rnmzByscn%I)|-0cN)JYOcmjj_9#QR_na}b#Z6B* zq=N61Z70{@cj$)2c@-Gs`Z&bV;sWUd+!Ic5ar|!=)ESr!Hs%61hP})*#Kg20w3Lfs z$Q!TN_mIu348@Z)G;_+n4mY6zo8?kiHqNdh~A@ph^E@m5;NlvzHw8p z<8%VWMGA7TRJN@?J;!QnqiPgVB2XTdGM#@WG^`p3*-=SRgvkiA@FLn;)6#h7#^Gj| zoSt!gI}-USvZdzu-0;|hdZ@fsAGGao;`cG>VQ(+2B!|@$MWqy^qG3!=<@qIaWs;zC zaCch_nN})(Rne9xV*QFVHm*rZ(27X{TL|F@$6Bn?wuuftZySH&VQWlbCJ`zE{e-zA zmRrUwje>?_qX{%gWh~@a=o(jY1V8oP%*vMp8}_uBn6tWIr6xAF$fHi%UJ7{3)cHA9 z{^V5aMnKVLC9>~U95UEwyYX5IV z0}r7H2FEAxr{Db+S6p!=qKW^HuJ?|!ye_ZD&+T>Y^t!#Vy-{46hzKIZC=h%3id~{H zhN!XqVl>8>_|-&-i6x2&1QCH~q)JgbEDJ2#7q;)tPA_-vo!jsIzRr2x?>plkzcFNX zXYbtd`MlrH`+3fDo^#Sxg~`aO)~pOYIge|aV~tWe3);Ohj*3|x^KrV*jx8-McQ>M| z9wjR#YE!s2!pXtY7#khK;NWRI{qzp2{9TXLCzo2A8ovr)&Dxc?`1O}y*~+B~ZVcp1 zR^oK;bEGbB13PCOJtspWJ`wQyT90ukh?nJEuwX!KKmNy-3MV#9Ufqx< zJ_q~n2lnj5OsR}pe)}?V)er);5(1Sx&f2&P>(;D9pjN){AvaaaU0jr8w{0EqMFe-XbK!NX+yp zVA~;z>8ay5w(n=i=Ye9GT$oD{j&+EAu4Gx02Gm<2sV{)P`t0X1m8Z#_C6m4f?*lR8 zirNqko+km0_t8r!^FH(5nOdy%g$@34dy?OclVDyaoTSTTXYkaHmz8Xav>xZA6-WM^Uxrh-^rTO(MPjv+FXXHZVTA^t zo2aG#nIQ-~AAHN}oC~f%;PidxHJHH#;QD+)LWL|t&2`P&dzu}kIXD^|`Ny`LlHAh; zw$_0TBBBvBR(bX&L`L(|;mjIoEJZg%{+1ltSZNZ$s3TvfB9|{=YNmn;vwWmbC{~a! z)-f_s#>wF<3S~0%d7e_0k3_vB;z?sRdwARnOz6AaZw31%=YR+THQOm!O!%y5{Xb^r z<#ItJHD+PVr2Xe7v5zcjBZY8gdIrai9YTQZ=-~`f&lAICWZwrj5Zg zb4Rxb4c(BE8<<4ds1dmkWY5aHrBabU0Rs^?KieCT2wf&Aw9>%Zo@xA_xAe%7(GCfd z47P)T60k1o6{I>}6FjayZ8l%UOg?~g5Y+#XU3ypELzx&)=UKH6#MX; zgfK(_0diJsQpGm6;SjcQyw1K&c`&JC{30}~7-X7k?S2 z$0v}_+l=x|E{n4^uRwP9w-G3hpioVr5ze5}Xhki$2p#>aQ4erB!_iy02{_U=F@?MD zx*bTmsHD3ypDp z@vN8& zopnAcI19ytXh4nI05W2JPe8L#Yd7W4_H;aneurp#NkO8%NWEo<=<^0PK=wvb=LytnuPY{gEYqsZR{8Yi%#1x)+Zl^>BX|9({Fczc~FL~zrv0JZVY^Z=ECHs?C zh$jhJm<-Ec=gaxEhkUJ zncpimxZL{PTuclgoQ@&+%8!QeI+*!N5DNwtV(G#G^bWAc+Ja1VKh9Y>C=Ugzi04`k ze9cJ2wBnUA8)gAfV9#xY&)MYMG-!Yzw| zD2b1R+8UV3Xx z4I7Z1nGxTIk7Lrvulc0S`2of!2Og#30l_iB_V#wY#>{jU>6VlNJ2gM};W;v9>(9YK zE?~Q&ZVrNXGv>UW{LGL2{!tSZi*Pc-SlS##W|GZ)PtL|Ix8A0;rV%*@Nox%_%WM9d z5(OewbW5Z(G2m1w&Fe)%RTAH1P&QayRVAf!U7LZe2_6V!e}Cz(|3U~F4>7(^Lh!U6 z&Si}R8jiHs?7DjOChpagY<3Ht_d+CPjx5(J*t7Q_P7R*IgAYDr+$3*#Epx7ftHP`| zFTO{eg$sEc_FkJ43}quQl5p&kAb;>E5e$YTm2A@kMsigwk*zZ|4`>>f!NkOvVgdOy zd=0imc$kPJ=q=uztufy#6BYiRB_^DXF~KDz56<0C(0(u|11Y`-Z_s21^Bhk=k=^kp zJTJlX8Tk4$IiesY8_at|wEM#!c&7}U7~i;tgF%i0Tf5U|EjF@js{_l5xgo#NW{)QfU5h#)u`FT&B98{}=hpO=k=6D87eC%v;mAC$GZ*7i& zV2FeG9-446M9B1YT!Yq4@xAFy7vSnEE<-qElJ_QxHMhTf#jZBZJW)U23N-x!7MVns z8+hjV-8embT7E&~ilkC>I1Z}iz|YAxob40mk0E&h_j(R#^KBM0!_qUjE!*_?Yhh2<3;`QRJf6dC#$cRQPQP2`|m7RFg z5hroTjtbXm| zo4;o|5*)a+UO|7)ljjwj9LtY!OpaCCN({DnW!}^fo8$vsq!}#AvPh+we6#=zcGd6!mdn=}zYO1E`tRJG~3r>^A$( zgD!wsEbWfs6YpGuWnJw5mKB^iQWsA-MKH=AbD_IKb2e8%saQcE){oTsFJkYJA)G!j zDs{3ItCr!ct(%a0_1};v@3!PqLB_s`jK=#Eph!*}g+MPR>KhSlU4_|71wa1D5Ae3@ z-i36AlGwJ!3}Uk_&clnyQCp@JsTLD2(ukuQ_u_%XWJZaC`z7)^7`QnVB!@q@N&O+t zgxhBSowA_Q=itAyvgGI`;bg|kj*fO5J9-qazIqTH?Y&}wzu}TM$c3;_V1-{d31(;1 zqJ8dNRNeFOJ&sL(nJoaH{l?4Kx?v$I#UWgN(Q2$&NnZzM7am6TJ$hE8*2fmCC&G@wFNAE2 zH0MeqX93LTFryv@CvFB_eP{ovU1ilgs~a1ev#gDfbciZ^ghtfH;0!U9=?HAPIeH~T zra@o_8#5?Y`+OZPd@e4p9d68IO=*Nk)@190ujTyZ?QbqeQ~@`AWs_v9xlt+9k7Q3s8?OLpa`#WJfp~coEM8`9pLvfn2UUaX_{FvdH+&(Nm&p!$ zjmdNhlVhWJ<%%YimXrtf$?A>3gGXF4%Vuvsb;6M3i#~T z(sjoQ+_6AH;-eg@wh%W_deS? zOdfdOxeu9m@Cuvoo$=2&?7;+%?HclWJYOP5ofauHa`f3)_lDkBTaFwI3DUb5V5G^4 zxJN8bO_!lzW1zI8mJpxm$8g2UVo|f5zPh}~XHmTOHFJzm31;#UNCIHR0f}51GT+i|D z90Jb0?VWY4mFve3{Q!Vz{#^OS^KixGm+4-RZ^ARuNZ*!(TFZOR^vuQ{twrD`A0#hO ztzqZR132)?t5#HpD6W@8OG^@&R7xC-G)Gs3BG|R_@!GesEI#_8fG=;aV`gIBT+I^A zIV7WI?S|_wYilg(iQv352e4vU9AEq1OZeiSU5gxJ{WUNxpS;!R_Jh*ke0fre+D69pk@W>z>K_bRC&#c-c zi|Js=c;Gwz0iU#Z3|>hK{UofF!6eDvK7Y?3f186h z)jvCQ-RHDgVQ#+HWuS(L5K>})kE%%#RLgZt=SmnHp1|=_<0zJcn5|R5C5lReQod{{ z&@PnFatP!wvq#7ISMMgq&&$9|n4ULtWPA#>dI*`;1VZ&HIugV9^XpnrEl)NLVnn{u zrFUjQ^(ta5t+?mmL45z#Bgi!}x;8q)xTxf~nZfYrXp`vX+HcLQ+%Fufk7y!g2cxob z2NN4)Y^@>oA~}U%ZAGhs)(sSJ)0fXhG(rLtH;MW}maK`KWatz(Mv+sfgubW{*lie;eH)9q4KUK@4?7?uDIr?%6-!$}6u! zBHiKEtyK#AeL~+nY-0&)QE2+ZLHlZpPds%`$kC&2+{*6yoWh$`fxMoCmRsA}<~$%A62bMu2?bR)Y{OJ4nr4uwo75-yd7KW$ zJo=MNh#c|NPqZkhc9SHmUb$b^u3m``y!#rtZ}LE*)pDAZSGvW)@vOS2zu}-+$w2#r z$)n#6cICgZ%}51FRlIbFw0<#>iP=ICxBv22c;d~tgL>-7k8sXL^W;7vEW_8U2 z)7BzeLwrsW7?p_Wv)A=nJn(%Rjqlm`BG&KL`zzX%1|KKHDjd>#BC^IQ4Hk|p@_d5C z&#e3FkPZ^%KJcEabsc+p7NEbcUmO({QPa~|OwAApb-F7qwn(v&>%prpx`j>Mh;S%| zzxl?$NE1hik)|7LRGKk`1=AgAajUu3@_C~zsHRq~j$)t(v*e9yAjKdmnYE-SETD zZEl=}(c6YjbBj#qK{#Y@rKIX5|> z1KPD3cws8l5L!|sw%83*b0J9A#sJENoGz4!yZD`Lj&D@^qRlU1L{+x#pBqX96w0i( zCRBlG3ZH|dIo@>tWI8=fiECbusyV@-z^1&+MtGdBIS*&LI$C1m7LTGfM+G^q#l>ru z)n-NQ{A01%B)G+c+id#;?5~gwKC;y`**R{Na7Kq)ZvRh^)4041z0RwiHIS z!UNn0k~E=GVn<}kDbUUDPg*5HhI$w$h6^Z^TQOeWi0-A^@XFC6xa-b4@s>AVgRZ_s zcK^hX=7>@RE$NJ#p*N(5m6$fHn~7)8WOd5`%&K(JBFf5g%(tLvl(K}4sPEsv%e(hu z&z`*qH7sy(LWG}dZgk2)j+$~|JIeP-ZP7|nnF2#3(UAjDu|sS5@+H{u><)b8YhPB? zNtZuyU>qUQMLECnEn%F`uAB#-{t=hKJx<`26Ln!QXFonSoyFMrI0lD?aPK|$>%dag z<^-0w_T(1mDia>&40bJPlWu2_=YgrJ)42mOkyIs{$%tXj=k!W`yvAhrn<8Orlc{e# zX&YTNvYd&m*a%DXBAyTr!pM0Rk5qKA-9Un*n<8ShNxA0sj#g>9a8Ku@_n|0Y z(<@$g!9mvA=iYJC`A+y`#-k6s=H3C*k|DM&oT;DFlrh!DfXLygmLNX%f8K+>frT2M zG(;zidZj9&s07>O25ZsV`#zADpg81=onomZzWmki3PCU~g%xRn+c|2^HXacqry($h zd|KQS-_6A-CR^!5vdO{XH550^}G^UVY`5T4!oAHX2AJ;%e7*wYDOWPNF5v zRws$h1R(!#P{m{k(iAyisga@BKfJObwao*MpZol(6 z{P~B^!B1~{UIt22Q(1iC{paCt{_#Eqr?qR_ao*X>adI$^jcYrRinAvVq!R{#aug;O zacvB?2x^oNC3$B4A;x!O0fMS*KCoN=eJ)wx3^x}Q+YyEgu*wUWL6I#D>)CS@(4!Cm zXWJ{LuJya-eCLh4XXt?)YPyCl>MB)m;wNUoDQd2Rs0>{&$!EGXvN~mQVxyd##g+Jl zGGsExS*gs*PoZ9?*gSVARD1lo(oNNy`*@7|a2(GPtDtJkj4=TE0IIC<)nC3wCvnU@Xt z=@MHz9t>d8<*^>CzBvlUHQ1m7V!5KqpUQiuPY+{eW(p@x4C3(N!-8!Y;EZ=*Ri{7n zP58&;pZRkSPxJ9?pAe;@x}UFbIXPgXp>`;%f^s4#Hl<|uL_wKMqDa`rmz@WKey37Z zQpzO52Y-sOF&W^xUbJu_KKY3cqNBY{(7F2jbkB39MurkPTWReFI|N22CQvGHGASZw z*6lCs!)Uey1QRIK**j-EvHn2j;lXQZ>aajdDy_A~u|y(7)Jf2ubOvDTKkJ$iwPF%QX=9E=%2$Wi zjqO28q>(N#vd&~^u|&yp==WW48G^{@Lq0MyA1Dm+n?zE$O+T6+erS_1gDdZ=44~^macdf>k{_#nC^>de? zQO)B!KY9t*U41S#tP10%pFM|SHH3Fwy$;72MDlT5abXAUe&8@RZX7^YCW_q$ayT_s zLMk4>lTYu*7eD_lWG4>cOW)dooBrV{eCMVI@V5VabVqzpT>(klDh~q%GXe`j#2J|(4#rLG%s3T?) zO&}6Lh)tEhZlW37@Ib8B@(8J?>^vUSKdK?f&n$R^n~_3DoI)Tw--MtjfW;)Dfhg#n z$VD(bauOf>$_uCkG9U!T0Hc1nC!mSQ7?+z|vwc8bhifH}6hugh@7WSeS9uX;BS)lB zSC5?iHcCo!JdHtxeSPnw<~J5UXCx3pym1=0f9F!PrkFLG5YZeYR7WVlc0>_%36bcI znJ|)xsiIb+h?Zwt&$-2EV`%)A)7Y@@Hoam2g8|Vc->xDJU}9sFqd>Gf%KjPZghG! zvg<#BO68~0oFzAMC)*>e2(2g2Kpt1+=#wHQJv_+ShxN%VAH!?I$7}S`Aq2jvR)Ckf zANx+LbF2keGzJg;jLDa(;1S2u2b9Xo$Vnh4h4-Paw-q1%@CQV?e0w%r zAqfFO@oI#aOCybL8~|+Z&r44_3t@wf`2QV=lfTKVHr&8pee?Ht{z#|h#G4CUQp9wp zjF=2DNtq;zlG*Qd1Dp&h9VGpQ@gsYh4d&)_pWkF{X)a_I-hA%9{(cOe8f+SL8C+^f zSTqE@VM_>KzF`9+kPs4HZ|}qj(4mk>XR$$=NrM4|53kT zaI}i-tc}1C{@Zu(G#-35iycRRbTon+KYOF9AYQA5ix!}>r(eNC1ld}{Reg0a^L@Wi zNvTT`5z)A`GAbZ81Y56y~;BU7Gg4gcSlK8IAA`T=}hpsl0B1sH98moOVbAj258 z-^vw1(UVi-m>e0GTjGI(hcPudfqna5!P#eS1?|sIoj7HZ!VU(N5SB_Fig6jYN9^`U zTx!xD()8?k20lLu=UWE+H{NdsG)*P6v?|!8lGHpYh+D!0h2KfwOQwvt$Jb;9#t+B$ z#0r%j16;p+p7!=mOioN1S(^LMO%O~^PGkK5tUy!0rZxEMzx<@C`2>ASoPm~U>r=h3 zhC->1U*3H`ItJF@*jNyc?j1oX+<`LUs5v)Sizn8$QoGY7SwgKGKS^Vsr5r+yGJ>@N zN>fAVo_P$#iK9ZfSO6#~S8z9xH-D&jbj?HeWL@xz001BWNklHBo zD}=`N6J3;l`2MT-%ttpPlPKVU$6m#oE?JFQEsP)E@*=LfVk3V3izl&c@nZa8`!K%! zx39xZ|N0C*|H%#b=D$3Lk6*u4w#IkfKZKd7Jg#~3TKx3Zr}3pfzX0{x6i^G}7x$dR z=;#bS`H`)N1ZLf)vP0eLCD_Ha3t%H~F7eji11MJuNX4kA$IawOSZXa;C!h(qinJI- zC`!3m>X+M1H8|d~$mTeSCjCt#pb2BS#|xg)#W(jse~?=r((61}zloKd+8KIn6Zs&? zQY={tAk}hqU=kIf`<=*rB&;}#ZEajZ2hEW-O_zGTi6$uq$X9B(?z69=RHIWH$F5o& zJWU14IBHZ@%Uds#=dA*mX1YyUSj0mmVnH#g*~;-%nK7KLEn}N8fa&QeL6)>o9vd4I z$&K>FelD8})Cf9s=8WSX{$dfof2s*P~!;X5~~S2JZyu5ckjAtO%;uMxCn zqq3BP=70SCUHfMcjkgFIt&};H62up7dIqIX4+rw`xzBtYEp1)$sOakLLPuwxDZsgP zq-w8bdiGostdKl`OR!wChizPrxi2Hb9y@*(>Ls(DLcYlm43=1m~7X!;oH zr@Qusco}?8RF#~WMKVQBRUGkHQtcP>Td)Mg-%EZL@(ZS>jf8DvW+th=mmgHp_w}#c zgz=ea*JiXtLdAkZ_WanQs&wZ;!I;DM%RM8f-Fh9XSFgs%$cQA<`7^pba*q)O>}+p$ zMWCS#b2@=Ru$>xB^gsxLBg=Z;fag96!E6#2fgLX$ z#2826n~t2+U@>DS8cA_{Hlb1801}C)T3pnSp@hG8CH0d{`mR={=iSVWMye>*afFIuW91b3?;X7Zs1oi5)4l`wN zA@;i5p`}BRVnPiX_hD?jir&^TcD!^N?LA#svA7j~|1VEt^QJ}UXpN$yErN%iJdF2T zw-M#y3>tw1CUX%y{OErC+5486RIr0}EGBz!#&ZljFUylUXvD(|o9b%J;N9#kJS6NU zGTeI)1xcJqBbID4xYV)HZ4+=~n7pwi2;OSfX)$cSlgH zGJ`etJl_E;3qrAkg?W9vj=V@!gr8I@n&!K2ztqT=s96%F&Fu~m>F&GD=wUQ2#j#)hacu$Y1#53qQ1)RJOK zfgta_wIvL`3t%c&z>yQ|gPJi*u~NYPBeVGa9j8zO4ap*S`?YUDS8tC#V_$zadV2cM zw{WR63#hQkPb+0hwsa~bCCcK^X#CCQn>DLW=D1ucZK?1+bB_PWks~;M?1(D8r=Ncb zrv?X6DcU%j$ev1CO_tUNWmRjaVf~T-wyYSyosXSDBc4Gr8Z&ERG0sa!#-q64qSs>K zf<+h`9me(@FCd>UN@ro!k_G5rvcj%YDeD&cNe`fm);mwNO;+l82_b+Oitv7&vQhr)cPCK&)PsJbS(j z_pSC4rOt^^22d}}qETUsrGeV$E<}#~7LlL@WVW+dHRtkKq*BI7AQHjPlxb_#Xe-wP z-7t9#laebo4uQW19yQ?KnS^=Wi1|oECe5PAkQXy-3g|m059DRz5F%;@i0_ckBNU5b z$>ITg`ja1%WAF6j6c#KTQ1Z&6u_+zk2-foK3RorW$Mp=)C46A^%4!)o_?)jfIXS7R z2d)8g61AxpLjc_2?pXXJ>N3&gT2Qjd9q6ES6+yuUCMIX`?SKBUiWU_r4!XB^?PKuV zWDl!CY7{WWvAt%AOh7z|$;mNsez>pFTGu5VHk^PVvSo;YANhB((`sq+6WSWLgMLnY zh$^u+e)=OqGc9(S4-NOZ$eC=HQ!8Pf!e&6v7eLhs9PxQaMy9c2=WZu0&v;QqkcU6Q zh^5m?)H_;e^2ZibNXY>aPm*QhF~)b}Y&B2JWH2D^drA+3S!#@Z$jYU zUFS3ehf|e~nMT0+WRggBn*JgfajcBe&3r;;&mx@h#u=R9?Uw!Fss--)Uvz#WX-|+8 zYKTf@tARQLIBhTy#&nialR@m>JB0fmJ&1R|{d}zGpK00``>arhhnAre`0?eNpH0!t zFX;q=5yJX!sH)Xu%sir~ar<*d#LApNWfG zGG$ytC#s_A&#sN>LpY?uzvlqwwo{sVD9sL|R?XV@D5`QSGoc%U2d$rE#7Mu;=P2v0 z@83a4XBU&-1eggOXbgc!sAnA z>^|DS&G(Jjj5j5=lB`On1%IYfX*)1#9D8J9a(G_j_`3LKS^DVC}CT-*Ovb^es@3vTML=A$Z+=@le^aVKbh7 zeml~!7_PdoTdIwZ?WXc3Wtry?3!5G=$!?+woV_R9N<*-0;rw>m*`xGuX_W~V$ zT)%_IPh!RDRruXQk0KdoWf#GdPdtGOFFYSdj~vs%N8uK(9p4M~6{?5H)%Q$T`-Q=k zghYNBN@aW%5(Qbgu|Lkw$9qpS#1aS#o@_CUPmDK-j(jc(gV|@~GjdG@bjUP&=j^3x zM9^A?zGtq!Z>@%}fAz0rBt!yjBA&*-|MU(Vnq7<|l?5mTsY?(-o#S*aXj^~Zf+m$d zN#-N>h3|pyalZD2LG+9d#($6*5j`GA)+@~-SfMjy1GVf)RQCM>EumS(2yd=LNohU@ z6C>(8Q2o*~-mQCRii&dhi_!fxfsv6h{SL1!ulMY1P7pH_BumUJ2~$$Q1I>9Ga9#Pt zOoa|jv7AM$4Ck)Y@=J2uHLdiMSH4q%=Ovsg?JYEoCN|N)qJ!YsiEl=p-k4PQsiP!hBAJ zC4NR^7D!a9;k?&giNF=x7BtW(ffDtJKpE+D6-yU&jR9#y z#qj~0t*BV@f>jK9cO&?wz($GRx~Zsf0ZG+B*U$)uJ`=Np-xjC(BMhbvnzs{}&!xIX zlBYaKJgLw&uxFxL-(I~v*RQt`IfJ2t;W#F86&yY`iCr%rM`yZ$zOE#q@i;zV`a9J){u9fssWu%Ai~ zh$^aulWHq)L93;qMObl%t`WUVD9N=$w6Ny>^RS)4i*#5F+#%<$5E7?waIcbLE2x-eR!W+OaTjvsqpi-}5-~M6QnGkv9vx2*5 z^A_ybw+qSkE+xr!4_#lF9sxBPe_5iia_M5c;o`G!bZ{K^-~Tw;lXYBs$rAkPk%OqA zy@>)zMw*adwSw;ME>-3;Su(=I@`YHxX058!9WU;{wr%H%;F`~6ad7_uY&-uv{P*p* zV?o~n?X%~f-;R~5Rv?$nT0*RAJHK^e2be!Jxh8yTLB>H8@=3%M+|}cb$87{KMmg(T zvm)j}=GpYL%w}-rKIS3k6A~XZc}VcHkfUHQyrEt$HMhwMy23irm4b1tim!b6MkODI zkDkJ94;{j>&;}F&Y-14WH}f|6l{hT}eoiI~mLyn3On(OBFj*q${?8>h7DR2eTXn9n zL&n7_?_mv?9Yyfu14tB)D^_v;kl<&=N_idlOspi!95>RYtrv4>^~j1{%Y;-6ISMJX zp==Wn*7CAZLyr*fJ+aqL32DBTT7f*EqNdeglMOa{T`U*zr7wI2ecjzc5SScmjNA2N zdG8W2*M61WfD!F~B9l^1 zN6>PcJ`Y8km~muB)5{1cjuNXqH8O*L|IsZdlx7uEYy!qAU?$C$(0Kg`NCJjX-Oh^~>zxo*$D=qdy*-nOYh z(GSjJOTb6LvyONwiV7hxLTIHtl8Gp$C&x8=-bR;J0{Xk-Sh}bS%a?SaB@;!0 z3%HSED0hS%Ld@P_(8)KuX#m0}2F)9nz_J>Hax6Gl3q!D-x4(3T8vaA67d>z0RVaf} z*|~lfnc#);ES`C33U}Ri0AtxS@+A^a0{HkfXW*JkTM&zxzPh*gp z$>|B*8wP9!0^Td*pHK*iR^--FU^YM(LRRP#(>bJ5hK7(C&mK4ziHaF#8pdjlzr)}c zsMT@V%9Z%#u9uKWB(Zqu5*aBGO*05MELJgF8T@+l6|cjAgMYx0<3)^&R1l7aaLxI> zNM(|^cl(US6pf|q72trrzFvt0jgO7#{ijrKC{hto0kYha(wkljta*UIX1}y&+{@o z`oPEWKxg0AqXCi{E>ZizTuqrQFu`Cef%n2V2t@bdy2bRYXm4xNe7~U-aZ89C55j_V zU4ik7U-%3T92mqepPRyPa0Tj-7Hc2ye;f^FW$Gk_jW^-u@Et+TB-O=>*V+=pf8<4k zW=Pi&EsWiCJA4uXDaRiU%Q;ibpE--Xuzi zl^X~3#SO1HV=dcW?43uA zq-c|2b0eq5_n|l$h2ofy^Y0ZYk`htjp~y)bUK>H@fdKyJ*N@=&7hgh=qp%LS_1X~g z+cR?olO=qfeCpe^{CBPyj^~p9z%g!KKVDlyd}zs?MS{8s9POs2Mu4%O z-Nz%ZzKV4lH>!wjVbMZ96a9zOy0GMktGBFz1g`dNQklE)Gp_ zJcaWwx)OocpSP*OzHNZA#f0Lh174v|cm=KPgiT1YDIuL|QTD`zVCr3A_1U;Nd85sQ zs4Td=lAl0ZTM~&_7?s&cBob6e45Pa(g1+t~7BB8aS9=^3wF?K>dm=O5vQ&|Ml*L=0 znQ_>}D)_-fRkU`4#yi-fHc4M@ULLUe-5~V{fZ?eiZn@(*3{Au_GD#t!v}`pQ>}K+1 z#DZb`-Cu4-0F#K4i&6In4K>zDa*0c6k_i&(1qBc*BfR^bja~Yw1ttw7&3SVy9?V3O zbF)>9PK+Wy!x68leAF`?-0VHbw6-G}ts+#PRHaCKnLG&1s@BYnufhJN#tp3!Fe%Wv z@fOuUZq-@Pe!~rTY1dBNf6qNy|J)bm(P1?%Yccg5U3Epe;pHoq;^!~EfOM)=`-?_g{9QS` zRk&V>vKZH*t0jmJU%v|f{O>PebhHGzeJ|@z;kt`^@!t=hL^aSVG>@7XI?4h;^!D^f zqIGy=1WfiR2DNqTnVN#wy>~aZZrY*)l}N(lk3EJrU3CTi`@e73*lIkH#GYL{H9f(^ z(2scXx_I_IVO(B&>S!=IJhuXaIQz$5B3ir_aW!n_U)&3_{O4&O@MpeV!u`tR zfbb~^j5K%Rfg%AeC+p06Fe`3?CAv~I1=MdRia~tMp;D_)Z_aDPddIQRh2pSPi zESUhC?GGlE4*GSYb0nBH@i^%UI1Uu&{zC!8PW%Qfx&6R~k6^S&WQr&dVQez^4G|-Y zy-_P8P|ibYCsPLzIewoKRK_kIq&5M={&7@_ggoTa>7)rM$*t7lo{^=E%}!K-*M|F- zYf3JM0dGxjve4ugc@Zfd6e66tR*%L@)i-s>Tr7sa`SNGc5|7yd!bHjOf1J&s_JK^L zBBn*)-4l%$Q8m38O<`Mtz;>P9Bl#$t(4c6L2)Xn?ae`Y;07=P(OK@#k$Q*KcubCL| zXS|o(S7w9F!Zoa-f)goU`^HUZ&~4Tgl$scjmjQ*b{9SZ=(Ya;%WX=;(EeSQ~ohTez z3%q6}z7{7g#3{0g93nq#Mb74_Kj8`zl0a!V7UWp0ok_7&2%rA=_1c$eyLvLULZ6LD z%l5}v$@^<9GBWqEVtYU>(f@tu8T7W2dt%p?*QB$on1H(lun)JV8u_(-ydrJU0d5lN8T^5nAL(s29BMY6QOX*RN>|4bvsDj{Iy8 zMa|BUOk~0oBmpvrnFOWm?GJ;UBrh}qVEvVOP zihSJrH24T(I$y=JFC4|5R|*&$o5i{nOL5lbg;>xPKwn=%+5_Hfs!(WPY+@FZ(|P1( z%P1EsI6OFuwOcM$pep4~V|sD~nN%4anFONIhAO#go#rUkR|~5z$(dZTv>Up4i6jY= zQ3V)EOtUIB(IT4|kbsiLg;=#PAu|R&(S?)4qZm9rf%9Lp9w}anY7Rld(H!g3=JJyq zmdy%La9_sh^iW$!MpajTY9}&X3o#`R`ff?nE?uz%nf5L`{)a~~Jvxr|jy5Gt64udd zvys-61=kz6;bWU|-np|##Ygev_B2+lh+*M^3GCc8jBkIphM|#|S#t| zPH0p%#DTd^HWN>Lhg*4hGF30 zzq5j6@Y}F%EjDjC6CIsh>ZRX#=UsX{+hT0xc;zxBsZJ27UMl1A1q*TSiKD28s9|9l zKeK;U|721NzONX`jh+?*edPOeVe96zaPZIx?0R_*-gVi4keJ&a9z=uz-syO7@2yz2 z6w!DLBcr1dQ)z8!#g;8wrTeh|;C^gczfp%lp^(Fa4?Kvsz2j}T<(AvDm)ko#@aQ9t zVAJ~b$j(fudiT=_JaqY9g|0|EhliO35B7*z6!4()Z3I?fMu3{r`S)BJ_TPDsu%9m8 zi}SrO_}4_46bw5%)vqV2phKh%$qGxXOKpvqb4Il(8-FM=P!oDzu=+ym$uC7P*^59V zi7FFKqIs$uO<>DcT?*Rbw-|9$C}MNnmyrn7P|pqFtYraQdd?Db_ANoRnn#chl1^EV zMorWWXoTY^)DpP;?%&~+A=lP8aX%u}tm&J`gvhFWz77w6PXBP+dGB^@h~<$5NnmOVBi<|G@9z7=L+SkY3fI$l*zq>te8-eSP9(l(f1%tE97WONxA)sK~oYkepeU_!CYC$j2)3YK(Jg?N6U1_=JmV?6t4| z69itk^_)gDQbjbHK`=yyYy;(L7_-GHrm_W0<)bK8`9ul%3!EI9#^BHdX7Y99i!3%t za6&{N_#2k&2N-=bg*Qh^=6BvWP}4h^=e8v2Ak(YgeSuDCKk*F>{xPlCmd9 zc!R;IGc$Dzjk4#?Of88!?mdD?dZ7-NzOF6|oj!r_=`3p1vJ#wRg797h$wUarSRE@C z$FX5~yQ=>}p^8`{jZ`v_>7f#y*glHwFAt-=vkOal>bUYv>oCw2MZH2Ir}sUuxnf2=V}O{JE-P@h zC~_s>Pd|SUu|%iFoJ6u>rcdHa%*NM7N5_$Fq2{+SVHwC60LVEpShRxnc4ok=YUuBf zM!JO%`5>zG0uCPRMzKT^8+)eg(=}9e>mVd+-Pwqng|k7-d|g&LOmH@D+KN!9j_WTe zVfjGGq=$)K2+FL3;)-k?83g9c!CY0uKD*PmoC-F8c`1h&aRG5tlzK+9bH{` z^_5q!X7w7aJ3`&R{omis6sLn{0QFGR){zcEwgyZ=HR{N{%s1N-LF7k|;_Q_vsmiuT z@>sXBA5pocI)52Ak{j@exh5j4P~qnibY81re5!!EAKr-vAAAsr@@P}m*Un*^t@qOh zgw(A?=aS;O88uOShk;_*53H=@|M`6%4c*H-%F^ z)E(luFAET zZeDj!mljZ^P%uegvd^m(#Dfhi>5t*;4H;}%okqPfg?epP{@dmq(s zDpqmZJx4J-&Hg8CXDjGPhjISq4A!k`$8>f=v-`Z3$yg9QJ!y1zb)YTHajGI(QiQe& z7#=HPBHO@CzdUI{mhN~V;EW|1EbIxOwy??Rd!+bpkZCWJPaq@H?xj+Xd;+LxJ!XU8! z-~k*waKOp^TGGO6=;!{qSyZjbrLBRtz2lw6qj0@g!hQ!2?7{9`yD>RAZ3l*u9N%B8 z>fXNh+H3GHKmH+VB&s@@SU+>`;d;ueGAJ^b@ikc;wNpR|z}5|C;4l9C<9Oon2l4#& zJ$PyFF(p6zV)e6X)hgK=kB-qWic-Pt*tl^sy1RRD=+LWJwQ`mA9k2f#x8II;z4tx% z)m?XsWHvN3h>aUJ;?#)~O{-@MKxEomRm-(w>VC%dCkKe5g?yi$B*ue{hd2|C`2pG( z`LiPHdA$(@EO$_HqJ~nhDu{!dMaV89`n)n(-68LkXR7`liM6~tznS5APTMV|N z+Z zua{BgLCT-=@BYx!T6d0_N(LOP?uFg-I5)D$(dp~o|1NCUxJDvInh0?17UOLBF=IPC zMW9o=!#F7XAMY)bLB$Yp2W(wf(qp52Y(4N@@xb9|qMtJG+yyTWJ)g^A|JW1AF>!Fj;H68K=~q;$_HSIe z4)chY{u(m*vdK8c8*BH-8s0fGnvAjOF_h~OOeNNERu47T#)`98Zd8$o)Ucp4gRagN zO%d_&8r4Mz+1V;i3{4&szOP0=1oDZNoBN_l9c_ zcb!>Bd5mjET`88e5R-`vI@`OkaLIrU|Ce8W2{XB@B}%M%WQ$ChXd_3d_r*o%d=;b{K(xWF z9roIo5x?P$SL4u;eOTW;g7;t1jz;T6$ku*`w$v+_DV%{&`fEz|xLFvG%+!k_Phr&Z z`_UM@6`_#*oA=jng^-YdN+pKz=_(fW58x*cmay)eE7jk%qyl*6*=KP4_%V~s7Acf# z$8jsGtbk z{>fl&BWft4@cv~NO@+Glj!qk$3eYt*B~Ak!QU%pI0`Icr%k}v2i3!1% zZEYExdFDBCUOav36c#OBESQ~D$=!GS3fI2?%y7ONfgdu3`Cn7?{vNW$GwC z^42qP;kqPNFYJ^aiP!lMY1X|T`{w;x=7eZWG|fx#S}^rV0)sKhg|qn*_UzqQU*g*|t*ZtCWL!QUs$E<`}wD-z@=s76E$y1u*?o&f2SL#uY@s$R8aR=~m~%Y*{c(USTzB&p5`*>UR=MWrbsNu!oXuodAEe)0KrW?Pa@-4nHJT=>M9OU3@o(Kt&UOwCIwh9F@vicG2n zrD{-yCev9uiIt=Y5Q~u=O z;$bfabdExCyeK0DFQNhy<3$`jHiA<_GdMIM`x?17?_cBq4Cfj8K1!7 z{skhy@Gxi3jqF`6ww~@@Nl}S{Nd<&rf=h6L|v~gNh8r2%IITBWXCw0qYsjR*S!$l66*+k_rPr`2`ks3q^M zuWC!hvZ{YiNcBpJ{=hS`oqZ;;**UN8dh^~jPzXUhVbdVQDV%|n1$;v>eETC3F_%bT z0*!_YkVFcU?*oyI2y$&_qtdb(!FU@Q^kfmt3&bjec;`g}c=y%kp;6AU*{H{xQ>`Hl zPDjq}isOAKwz>07m9SUZY?|RX#X&juF)=M^AI;3n;;Uc%N7O~yvlb^wpF~J3iFU4w zj=$nZS}ms9K5vrjDlDE%D@FVOmt@(!FcC7r>>`{s(7#{+A9(+tVsU?;>B1-}cF2L# zw(;vwNuWa`w0FFJjg#TlUeRL$@^|U$=`jrj$thc3+y+9u@}ivuMn14uYtvYM?A^hR z^DL2B0CJs`WDZB7yt#i8^(Nt&pLt|-68GNwFtREHgZg)_UGv7VGe!b_YF~RxXI~(? zxZ!jSxCVKT__{ooe0A*+13rf#Wo{{mM`qV1AM8Lj)Qfu1h`FBYLeVF36ok0*9!e^k z_uh(RbEPH!#jXSSaq&n9iAV*#sTwZY&?U5#8W>!!TuUNH(m1VLL|0djcnJp&9>6NL z5MA=^6ECgba1dzCYAMPfN!gd2F>>#srJ?r*JW zu)5?Ivu+98s<&fMmVQQ&kUBFsLRKc3YYtteENIx11A7IBS>^7Ere@Wokw=%+DXC!f zMs_AEIaOI+ci!0hA}VqWNzY9-Jlhr|FNy&sn3ci8MkeQc6g+fh6`ir`=Pv{vk|fhv zB4ZK28S`1jZl21 zfpVdQ!^g9jnXO{WhQ;XYj3SX_kG}S=@?A~<{M~;k1+~m1uPvd>>+=OV1Hq6|V z0oMoAl|ZA$zw?sGzfM&s6FTF0G|-yqz;|yxh`XPhK{`c3T3wD|p76y?{K5+_!M2OG z;lbbj4}$d?)~sEPC!cr{`C1gELLN&OFT_A^m#T`hU$YJUeZA^YKJ&~|=x%SvcfR)n zEMK)2!$U*pY;O~CMCg}E6*(qcMPuWmDA((nYj02nwnU;)4i~@S3a|>^wd)0(*z**= z_xY`eCp!^YupGbnpP!($C60@(`aWvt^+%~<_2}pbdb_(23KUR0_+7*T<-`ZQIiVJ+2ocnMAkSy*nzgF(CMG9UiO~l5?6c1W zl@%vOM=`Kqfwg<872N#OpW^h%A+&b2qqCzE?G(C+gz@5z=M`9d&s#(^R=)JvkZ6+~ z_HGv`xH2)c(J6z|`Nehv@4W?VLn0V-II_pYhP(-SFmMvW9?N!JN!QfNb@O@D+a^ic zp(P$d=X3M$WWXiz;yDWp_-udifGnlYK)LNq)Wb;xA}t7)$8g<+U3l-+TM?+xVbv;X zk;xb{oISTDAgIA8zNl|eS1d&O={iQb=F~^xEn-AZx=rE zsgJ0lWQ)PZFl~SMxY+#e2#cmoa4%Hn z4|U5ON%35P!+i~iAWtS5g?O{VC}*P)-6t9CO@n8i3v6F>@eh>NILf!C*eqV zC0ETSV7?gU9w8SiolJ@|=Mjtf+zj7NvW(66G|hWV$5xSE*>)vI&x-1cUjJ4E?)b*) z2D35#qZh-G;D`*4Y%%B%4zZ)cux|=>S}b-}y8tZ!#Y}%F<|Bay{@v#IwTN6GryqfI zt@X?Hd-mN>2>WuqB-5_7_aXPSxdxL#%LZ{7RA-xk-(?1(G|!&PiZ%OPLEnxTlzD}8@o^{YXnEti{7r6;xrjx1qUx%s+TvGzE^J4$fDCRV1SP&GuGn+1y*X9 z9G}G4#FR1Q8{F(M{kgX*jkXMlq5Qd3$oApa}YzICvVR!i>i0Iy>5wQ1tir;nls*V*AU7P%0ad zkk@-+Y8qF+`5ovP=*2TnJc8r--7OrC<6T#As+pn#$pF&{t_*nZ*WzJX}Is+ z`7+k5TZdeB3W>=(5U=dBNzHjdkXI{TY~aLT1)J6`z(3zHiY4o>MuVf0;iwWb_Ujm2 z+uGYOHadz~vYe@uI6WnpmlZN6cvh}lg+w}oiIH)+XmXDb9^Uivizt_7F*G_RT@6*! z(Wo{tiMfh$h%EqM;@#d?pz=ao|hmOu3JobmD z1;5_>vs<+g+B!Scryp3*hpEYF@d(`R&*zPxOd}xf6i02*^DrO`?|+x0Yn=6GrOSgvvb7A% zi9U>mS0b2Mh`vM--~0Skh=B(VA#^)Pb>KM-024Md!k)gnea?N$^)F#DUm&>1WYact zY;aX$8t-$`#5(9ocnv*KO!ACp+*!6XY@w|k^e=0+|eT?*+1uHP^p!8>jg9lujn%HAh>wi_HArD~Md%?@Z;5i1d}L(1Gkjljh0&nEyDR7^z1uC=o^ zmi#8i_skT;gd}{A$QGCNlUQ-^yXn?T{YzQ5nIrkpKMSVfS(>PYxCI^s@UWq~Xf9c> z>h1rL^&Vh$Ue(p`y8X`Fxl=WLM!ie6x@{HPa>q7cLNzhPjtRvO2;~Dpo+PxN6bK;% z5{N@}jJpjOV~V?M%T<##>2Jpqt4LDpio=ruBYNmuyipZl79HB z2T%$m93d~H1E;dr~ zMm0BUP4M4~7A?WXO&4gqa@Vfkc;w;xF)}iQ&t2b!^Up~lU4I4ohJJv@AMeMz-~CY}TRu>+(&lG6u>Szo ztX_lBkufCGk0PFV){>>ll!xgjoaswpcszjZ=WW3^?jFUt8+V99!9%~MHfae$eZ7c_ zY>}kWwAl?~WMl$$$r{PYQoWFZGbAQXr_wsq$RMUl+d%(mP2r4BvBER8O(qF%oIHt4 z%6J;{TIS)IXLpO!!lcxue=NY7-LvUN_?ct|R6irn3X=#{ZB1M{^Au2NY-+}$C0*$4 z9mWF>Jcy>oM$GT-Mr{Mdb*7QaQrn~+(-RbIG7iAl@Q4DyMLRFT-o1PA+0T9+x8C|g zwN4mZrl!Yn=HyBB&h4P3qN166u_YllMu!p@cYt0WHXiCn`h1e^6K*~W6Y#N$*(A;F zv-&F3E9DVk@Z)^^yO~H$VS*-3JcE=_M5M9rrHzR~@V!ZB^ja5uJtiorLJVlzjHO+T z`0_2+AcU;;sL93?=C!KWY@@vl_^i2-W`!KV)FTJp6sJ-ZYyVnrR{_TLv-$j}eZjMZ zLG0*}6Znt+ycJP*zieX2EXKKO?aVZHK8x^y zfzTEuN{$R?`Gmcd7Z~y!1R-ZmGToyKmBP@W71D+wUn3{If*f13w4KjzOrG(hfPu3k zk~!bA=OB)pJRwqZwUh@*uJ>-8?!kD@kNX_{Mu_0*#I(%n-B1o|vG^8+6_aZBpc+%b zM$D9JQKn-qKZ#2!Rm4(lld(|6nHl$Kf+k3UK8fob+c!}-vlb_BAfN=HHWo!oeH5D( z#j&WPMj}*1Hg!+u#9X3dyhcvKaJ_H>&&~_G=R`(5lEa@9k`RlUP?kg7O+C>_mqzHc zg4Y{6IatDx6|LM+YRM#h*gw~lbuzpZGebc4eU>{7tf0=3ZAr8!~kW7 z9)r9dj|+;XG00Yd1y-{#cB+bcFxC&Tz{lY2W=@%GxYmMI&*U^1oMdKGmW^}7PuJ@* zM}q?GK^SJ>#COQdrpSp~1X>hM^^luVqzx__2cd-`9VmvI5GZkUk*^! z(PBHY(q5^wZ%ky0i$+XmkN{K07yj)PoEdEp>y?(HY+E$Y3bs_l1zRsbCX*BQ;Nd_1 z0mn|9)`7*VU^YuA`@q4&2G2UBUP(MtEzU`ovbrb6blIg>pt?GYC!cx}*;Ez_7A(f# z*#Sh#B`jaoi8Fnp7#$~!I4wPcZ~W7LArdd+i=X=hQZtiy)5aLy|JF{Rb_c?>51=|R ziA=f`g_{2o1Xq`=Rp8)zvqvvd?o^}uAAc-;#9OXz~3{7n-anB0@Y~HjT znY_(HGnjkAS(?>tv5Z_ct)w9wi3t*ypirSGodmYGSg8u)tWC;2v6xFKFf-xd9+2LB zFeH^j5)>Km7)<9cS&Rqn|0Qaw637*eDec!W58u&|Q5%i*ZgP%cE`ny1Z4pQyrJ<=6 z|Nes?;->e#6D{-F@ZyVmP}fk4rHdB}5nwMfmCB&Gxd|=J?Lx2k8558ik)e)iL!34LLE=$zrWWf5PUBp9ejRN!>g;Sb$$jZy@n+pAxuoB(Y$mkzVg}kA{I2VGq2zNp9i&( zxzqyi?NoR0D}i$`Yvlm-5Vk*D9Yn8oimx_RfjPE5$M^Ca<)dKI6#n+_zAEKG`40p_ zsw_D!?SnAKvq|FBJbpTjD#}@>Q$}=j6*&{9iScnMf0FDuIW?*8lb{;)47#@=UB3o( z^=;U`B8tD**^Cl<%I1t$VXT`-+8ktI4w@j|g8OVrQXC(IYt>6S`y$07vUcXrqPM<< zF!$>|d9Vc2Ar6(sl_Sx)WJ^;H^l->#9SS$C7PAu4GH~kDDY<68_|ks#^bcy(ljxX; z%f6N8Vu6wsk@2kZ_9~2)$a>=G?0BS&vpNC4U<|2J0+WGy05KFfHp4c9`hIZL*l3~ z(Q_Igd_T5bY8&eGY}mFnB$)|-1%Jj=ww9$*$vEvz+MHGRT%x0IGbkn!iFY0|LeZ7j zaXPS!?UZHy$4_2Vj)b{z=oN39g!dt)z6<3q%}tDBg)x$5NoW*l#W)E(I27zE)L<7- z__YeL#S#c693DO3`}m%tHTqdq+X5Cs;WAKOjEAQ9b-tHZWHVzS2TjazYttf^XpOZ8 zWYptS`#h6c^|!um)wn`>@)A@pxEd1^qevuc5Y$2lAjpl79Ww<#6p_!KMJ_#wTzU*; z%CMHGCC*Bdq#CLva!#4=%UN#rtlZo%Z@gpt%Z)L_D$)=FPp-4-B^e)$c|E3cxdsS!={2(!mgm^z7a&-V}sF%g{|<7GvC>q$8pvjN{KLI$|*${7gPZbC3`cG`Zbz@TNv zhtZApA>a5kHa%fq^KD=m_c>yp6?uQEIpDunXP85od>g`ZHvZ(T{1l7BQYuJ{yU$80 z3#^){eKVzr2mW0n+mt~slFyXF^vpP(fAIiL_w?%ia5RwX`%l^lEDS0ZS2z!tD%V^MvF}dL~9%>zz-cG1ZBp6YALXIb{+isSBNPlS@Pp`24*pB{>vAA2nrSk5yd)=l39$ z$Y@X^N-R)(k|5N~Ay8U_&S0-{Puwz~K8q!#HUh7h7y!0id<_D-pL(b~a&{Esqh~R} zJ}OBf#grt01IWv^h(<$U5N*h*mrhr!P$-9RkQF_vVS`9QAv0tm*)Rb99|?D+Fvx0* z5Qeo3EMro3=Qs!U1!qI-i8D@`S%($boMfZ&P+$+!7&!*1_$bT8$4pTfo^i3Hjtv&ZaOqF@#b+g?##~Mq0vw41$4a1WQ!dm2>ka9Ui>ncd zqDj8#<~_j8LCNUqcr}_^TI@AT)G=?wy6s!>n|tmM)XjUDthKrBe8EI!_;(&YBcoJO zw9X`Z#r$3puQ0mkxEnXEMbD{z3=9up>5`RLv3i5<&0W9vxyCOWt4sL153N+7 zj&&?Y-_UJ%=(pqe*ry)A-+lGF`1prEj$_ARw7x)DG*nsMp*#^Qz`zO3D~gTUQ?YkX>9e+bMi%CfFqAX zRbEwRUi9_!YdS!=ofA(Y znNSt8!9&dzS^-~YNq$_54ouwX$q=Fgw6^*%B>uHe(& z(t>T+w=C!fG|*S-ZmyZv^pGbX)E5JyLb)DQL=5i;4y+eo99 zvJ2L{Chj+RyfBzYBC>6!Dx8Q}5t|H=9kR4ksJ>@w)CYL>*7?gTG&1?(y=D7@zXYj9 zqe@J8xUtoz_0iaf(a}*Q6qKH3661Le9`i7FO&xpbd^r7=O1r^O zNhuP#L_xODBL7-Tb8g#VZld55hDr<2O+wggIT_+aR&u%z&p)>ZzkKlb>Z3FH;WOp5 zPc&9#3a3s%k?$$RL5HUJz~zf7CI;MNOu(tkHZxU1)8=<#D%^&~hGvvQl*y;0aT>Q= z+JI{}%~M5c!P_I71~Dt(yWrpx10UQCHJt5bTaY)>=B%`_OE~5b9DR4eCkvLJSW;pM zyzMKUP5RS$K*)L1db~FCPlZ}ex6NQ`W*SoyQ!0S+&WV+Q@z9~eIC1g~6w4uj4#DP|#%HdfAr;lfMag1`$eyi}%m1=-A0a--WH35q-{32}Wh$6{3@A;d*sy;c4oZ@kDy+6c9YYAl#PUvLM0v96m01cITzr@$BxGWJ0uj$s&wSjNs&nH#G14mbYAo+S-JfJGrqP5?lm#Zu$^H*#qX5X`+e}ZK_GeE1S=2cXPM-@ja7+4P!E!$A|uYFNy(@ z^HiHmMmYUASh|^U<8c~O{&@`(iDoC{5UHCZYW+m zNrTMBCEtUu$pGSe_?}e6AkPU3R_H`Lcu+8iFwJEk<@z#Ti3nnnW{sk;sR3QxUE*l? zB!NMaN$%L>sQ48eF^ z_(b9qgFFK@TPY;xF=3F{8qJs{O|_AqN6K)niZhKBQ(yE*1ON0q1tylmKm4}VJiT$?s< zEsdI*I!sPl!bC!)7g6HBP1Vz?NC#?tO?fEJV4)HBp1fOc67= zqNL-S!=t$Uix&e0Gl3!zZT8o!ZL&{t9L1`FmZ+WN_*NdqpY3J)*0N7CY%0Jb6CTE{ zBvoSnyOxJMD%?1tvsza5?>HUi=u5{|3aD{}IfYRYfywx%(On>jU)+9=k~eB-u=s)KfJ7;pLLC6?w1;VJUil91@$MOX= zc-yvxn9igX_-Xa7X(&hRC7*})#k+q}po-(6yi?*%$(h*J3_r7>Ol%(pm2A^_S5tvL zQFFXN-`cAbmTpl9y`X56({8ZkZpf^VglC?4rp(R8plORUpf@p?#-Jx&Fta%$C~=cn z7D$l`jxk2*LRKgslO~Ca<9=y8x9bUPxnL6}#zryNdjeBqBbXi^2Fhu~!+C&xIcg@T z4M5%fBBCK`gcnswGYg~t0r?85L}GD-0%R$(L%<8ON>&F{*_hGBZJ@pyxe)wTzK$`g zt>SZ&7Vf5L@lvyuE^ZX)V3r=N!gOg73Z=Lnek|FHcy&_quJJ^ZnMVZzNTqWk`BB-g zxupTGzkUF%t!?P*??bY-7H3YJMsLp`u6fHP`0c}wDNt_Tz8%Y#FRzfqIBt09<(Fdj z?&pxr$#ln z_3-Ezmakri-cv`BOeAzYgjxB$Jw3e&$~<5=jhtlrt=}ZG2VqtWC>QRUZHhs)vK|-nGiClv3gSy>ZGK3K+?>tDv{LY=G=CU z%9;$=p|IQ|PaZiS^~k=yzDklnq=trBqeDa5FEnyWPtV}04IA+2D=*_{{{XUSq7!X; zUnVB03>{KE@zz<;vK5le8D!5aUrMBT8F4Xz=fQS-P?v!3&1Avc9IdS)9*cMcaZ{*s#!n=gF|d1IQ#orBg6)##r3*T&5-GdiohG~wVReTf*1O-$h{U;SqV5s&8S z9Cb3)CUtEb4pxBVGguL0zfE+Cvgc(Kh;T(a5m|K|>YBR{B+)ez#zdy1BtZu|1$xQ_ z+;~9@e|{%O_8 z1EoMcKJ&HjV>&nwrOYHkLwn_=lAXU3rJ{|&mnGO`afp)zvfvi#P|}!VG9E^KEQgQ2 ze+TN2!A#0p3A~1Q+@zLC+T{9S0V6Rgw~l0d#YrKWC+3S785==!Go34qY-#=z#<`(D z8j}UtP|r;b=d@o;ZrT^iww8Tc%4DbAIxm;7edo0Zy!gUPWgFjNmSufNy`df=`zmIb z!{5{c5M=FUaCzz|ON^hwIISPWw8w#}HFp2Wd}r*Poa zeOP<$x!AgOBZgo5chtv645HKhq`x}*>qHlfL_-vSHpa0qd)?-hspKjW#A7cE;-7Bk zC?5NuA&J+>zntiWas)#l*h{kw&3nn@$}}_lZ{K&e`C3aTI3mZ&TTp1RD8z&TwWqgV z<6IP;ipN5D{|)cL-S_-b_wLe5-h!%R5>G$%JDfRv%IugEaco~%gZEw2j$p$^WRu$w zuSyszI2=VZ9>U9ec473){Wx}P2A}@IPcb|;f!g#l2u(d^+8vbe&J=L$jVvZJHF)uK zGur1b!>YCG)wbbbz$D9WI`0*r7MZM9%}SV1FkKYc-eNmxYI;IR1P_o?XWqcn_*n@; zu>xi_P5Wd%m%*Wa4D|G%wY62c5XC?d*Is%Vetz5kB1PvwL4+l=wzkN%k@rucK~5Wf zZofOqsxustnG}N}Q49873B9+qw5qj5QdGP;fk-?qP67`LCJE9HfX-|zJk?Aa2cpc)?kcdcupIi z-`n2au0ZbFOAK`UMdXF5ltN5WGfL`M6&c}+jQNZz9-;sSml`x}#fnX3@C;$F;I$Av z@Q^J3@6EyBg zp`Tu=IYJ~iiR$2pCvUIuWB}Num|dGhxww;(bXkX zJ|Owz!1EWpR)$S*n6?M^*x`dm@#y1EDaqu7KxfN5oEjXKk}U&lHlM=I3%85^W&0_t zVumD0wTz@@NuGfHpUjrjJ|H>R2%u6E<+PDn1*T~reH@NWQ*Q%`|<8fy7+qQ>2St|{`2s-*D9*Ea5xPjLO8 zKFQ;?@-I~7bZMcsHRzqak-tC=LcSSE{G@~H z&t@?)G=SluUQADppp+ZeCW%&+#A;@h6()xwWMhTFAmHh7#9{9dA7n#wtfJtQ2oMe1rLK|=6`W1-9s&VAlDO|Mk3RKtB;;F}ekF$eh)>jF= zYHuv#b2oIMI=K=Pi7U`BuTjt8+y8nCK5=t3#zyl%u?Nq+lE)1w@o;^qIt+uunq&b>aRfA-GodWLI z5|Hb&X0x34u5gas{(hf zh~x?|$>M!sGT@UoPqyOq@N@fnB9bzo&&#CAsxY=aIKFDF2UgtVmt44g8!o?mhYnz> zsQT##n{=2ZEc(eTOB@Vo@WqU^;@#+9rHgM|1{p6o9*M!^mgq=km_);TQHdn4fA7B6 zaL@e@RSGZ{LzNgPF(S!Xx-3LIEif>t$rEiY2IS?DTyZ64>ei#RW4<74qFXFZ2B$b~ zI}7)-jmfKt28-C-n#Mogyhh2RcZjV7WcPXega(mWB?(?~S)3-vkaPKf*Y>w@!MVwj zld4wB)XG;c^7AJIMn4|uzK1pAT=F6nTTQ>lzE1Ckd++}(_8;1hSi~lXNGKL;?$9c> z5aLx~T(o0{oJ@6AJ3^nANVm3-B?Wx8CRoOEnW%wH^QaJ_uSYnHScEM-t_8Y0vS4P+ z;QBVfBB7F1wVJhN(Gv_;3vCv8QQSF>aZVy0E+JVH)kq=}B?f=)pB$Zkoi+%cvw1Ao z-Z1j3#ZSs^OK~xuM~Xg2g{;s8wpd0-$57YM=*AY=<|=?KK_YT8cB+s>ti`Uq=SEO{ zvS9DWXIZr5U&*9#SX`jNww>1?@ci>Hlo>48pY#lEPAtghTfI3FF^qw$wl7(@@<;cH z0yAe@G#>Kf!spL$wo@C}X|3C4u$fYK6%_`xjXB!;5N`2{mp6%<$IrKlov9HfLkzra zr$!x_6{kmW_y69CzQG}svsnbgCB#Ejh(t?hZmhw)dTItRSd-~*WIs+pFo|I2f=C4` z@v4ZyF%-0s${mvkR_JnCB%;B4VMvHgYS@UVk}V$Q&X2nU_K%rN*z7Ymw1`pxwnV&k z1FHZvL`B}@L5Con!Z=Q1S!p@nXX2-lIknBK#HvKz2hh^MiiyNh3*hGRRz_W29H0LG zUc`&1>JbXk-`%oSqA`9xU!$6p&20)Xny{s#;V8nd2NUUevs&wpUCL~`OwKZJ0UcFF~$ClBD! zKl}}rE{-ELJ%we<7b4#HFGx1DpfELnVDEn*60+xiYH$YqXCoL3Ux2B6wZxEwh`6?t zpUdaEfX_3(8bedG}( zr_+J|2H=4@QPl+7A-H;RqoOH(YS>2QUvkLHI6dr|$o>^y_CW zqS=34vudRd4DvJx%~P)-Ju{;uVcXUVuyFAbwL>~OJ9PNdX8D=j&tm6A7vYXO@6tMr z1Y_vyKdHVi*R0w_p!4b!x;i?L<8zb^u#IvtxU)LrXZ8n;{8UP1BxcJ)C5zoJ0vC~l zxtqG#q)j#x7C8bJ;#0Sm;c5uSfJrfXK9 zTvdYwElnB)j#kHUc06O$ayK1d(_&mZR>fD9Q@H7Z7_Qqff0jSt0)WJWbmkbl-%mJr z`FgL7qxI>NAjch;yJpQba(0x_-IhvHB2upXfFOLeft_{@4>IFWLHms@Je^6!vJiwj z?)(kTj*ViVzaNc_bx77#qnvk*cQA&Vp zYKQSvH5a(H4Z*c`7SU@?dC;JaC<0sB+*kAp%2aeT*v4X;-!D{t)xfX#vd-mws6tvt}oossL zVQ$KFe9#<2k=C;t+2i5G07CY$gg?~ha5~tWE_K;E)zIWauO6Nw4pIlelbRgr;4MmR z;kwL68M3*tSvJTIHd}4^4eE8a`Qd)^;GKBsxjnLmRwYCDMpoCHQ;i}TtHHHzeGAr| zyUGlyxT$k#J+#TOG2}VYSS%oypFts?LS}MO!X&x$fb`zQA1vfhS7Vzw5($u#q$ESC zo06_(Fn6p|9WtC;fE?JOVa~rYb2BXh69O?cL-JSoOQ^S)xO})~w&F={miak1GFF~E zpc4@}LxzF|_i`(W&p{S>Z335m@L80ro6W{MND`On1ej3@O?Etqb5{7oFCyP+@Qhfs znq1=G6FI)0syumfm~oGUgMvW?i1En@NggxH<=3}vyBPCYTJYS{PhfOp1l5Te83y(D z9LLRXZpXT%Nz^R68L`?0n$@KSe>hmeVBaAeKXNZtE<1}<;18oypPu+o_GJs-YWPS&oH#*5hO2ShISip4o{LClo*!Fjucxi&_#P z6V(_Uoe=M(rMVf~wr<7ZWy@qdHGlp>X@xLozqIE?Y+AP-_dfU_@+m_3)p-5YS45`d z>8&d3%P!X5wL zyY=z4c>OjlVv_Ja*h{F*CD{DBiUj9{!2^#!MBqXHO~FwX4nl~bi!?J?p`E)*ZN~J#cL&* zm1109|N6HT*ojW^GjV;XEm5E^OhhW3-m#YFANe+mmM_LgWG#lO*B}(Dm7Q=rP(r3q z!Z$`amqS#>wKtTCI)YY5d#GE74q4ltIxfqF~9W-vf49Sm3A-4Sgv$$7#?4 znZ+hge5?eXIY@+WF&I2Cn<)5T=+ACLT?{hkh;T7mz=^&w?0)HWy!X#8LtkGHPQNjL z+wZtjGVyF*N|u_MBkuXU?X6b}VIaC?=#L5T`HI{ZHNMTHb1>{YTqK!HqbROvYc(h- zaDV3-=XuGxmWd|6&(J3GrKz-JD&r!vsFK>(k(g_1yYHv*VU+8PoHF{F*myhNPsC`s zP}-U&H;E`_ie46(0}JB1hI3Y0=iN2~7Ft%KPmRnAyn>6HM~Y zT-py>1N3j;+9+ekC08Tx(n~}V7?sFMwu@)xVCoou*ABG1U@0SX+Yc?I9^UP;3z%KJp5F ze%sHH&savyJ)wExVjju5W~@7BJubWKQpBpvA&YGmLYxv-DizIb&8dlzkjaNZ^Q*>r zO*nacza%gDVCj&RotaQ(%&CufB#2CE3^S8wkxQkO;l{`p2&7RJ38OmB&&>x=LYydu zYjs!)#>AqE#Vq1sBSG@mOJNJut&J2^eAwX|mKMzplG%^h)F0?ea;Jov; z=rFCSCT}8)$%%0c3=HXW%IQwYnDKCubq&@}tWJoOr&;BEM#%+{kxVXyBZm*FbwTqa zDj3rAhA+ZOoQW~vbD}A$mQ`cLqADDCbqt$ZH{jR%_8=$DM?e*Uo>4R|w2gsEo0SbQ z&1{FHD?ylw2L{(!YjdOS9YNFNF zS}O4#zUIEy_F~5cTXFk+_hM>fLfn)S#||OE@mLoigeYWfYJtz3dxWhQ`hGBJA{oz; zOluLazsh8w;zG#Ev`|DOPJaPIBG@kRBaBQ82*C^1CHYYn*+C^3e#(J=XVRee&*zmC z@MnC*R}pS_Xah)eZ}cDrw8Ga1Z%4~ z__P59DnCy}o0Ms*}AcKlR2i!?3JRcN>%@6Jt`5j)pT@x96!1O{Kil7C7C0q?H!NBQU=Fi!JdObLV-gIA^1_{5nx|Qv@mMvePo2}lj6T^^AtAd&-zFFWj3tROD8R+t?3Z`^V64iuHXQZJ|gC_RbGpQ-g ztAOfh98Y0yjRzaAEj2zO2s$-2gSz@8%7qj%sYwLN)OVlMp;pRIAsom%IZbYKzAxuq zX)?u)#>3W<6Vu%0qNkpL-J5e(bfG3bhG2lAPJ}YeAcv6m*|8kn`Nfl{YiOITz6ifN zbV5?glHRqX&U7a15arjUwimCmS!LHp^E4*4Bxt?tgtUBCt(H)b&xTc!vG^Hed6?HG zYca3A8||$v>N6fb_^Rx|+uA#@Z|@6Ow>XY>UQ(xuNEIMSJenkxlZf0&^Q#d49 zHB=l#BruJ$qiOUH2QgIIfHUK9ba!{6tFzmgh?z7vpYb?tony2^rVoLQB}#yV<5Pkd zL#ph&7Y3`xXgG?|u@Q`n4B(MJ`~hc9pLR-~c5w23`KpYEStOwADQjBCKXNcnB9F?q5g2d0z&`@vZ0A-TXY3&JqUY}_4 z=h!0Q-ebbSUqmK7s=)nyc6d~B)Iuwnw8$FSzQ^k^@C;(V-J^`0ei#`UHQj|o64zb# z7OXpGrOqf3(I}YX`p(v)HnAw|nR* z)y_yFGgDI(ib`Scs|WGmZ~suyj!-*+_f+KKh-A*GK*{rU^|>qXvA_Ha%uHtS)q784 zBHD$9L=@RV0mD-?#dGd{YAaa47pyGfJu4`9?$xA@A@};7Xzo4-t2S@P7v6hr1&LMb z*A;QTV6)HbCo3HLeQtZgAt&04l|;f#A4@*iS_%wizNH|<$B*JU%>+y4Ok+g40L3Ck z$EHxomGI($Ud$kd(UG%Q($$FOcp2xcUyY9TcKpLvzm4Tfn{mVYJ|J}F)TuYH`{~_S zwS2KA9z0T2X%)EyuEM+U>XBU6LJJ}y5*l%khys%W5)h3mB#u(l+HK+_5QTDn2p&xl zp;fl!=09S}z=nofG3~|rjCW!aSkC9jDRwHglEkv{T>SG;3(^^Z5#cmd(t`L%!^5K( z=sSZ=Tg=&({3#-XOv*|2_UDmL46MkUH7QdYMt0%;Ia}hw7N(|QTuWO>!oGbkm!*&G z*w=izg1OzI*PDvqX4N2X5)C&ra_BNDZVb}~=eQPy7!2O`6{)*tf<=5XU={1E$`}9T zgA5lc)$I%tXOA(efTP|{o)*yz{VqeXJBYUS#%|(h7H|h$R?hje89a_EiojE<{#Yg4YAkVa`KkaBxV3G;Z>p z7hiMYi8J{xe!LrXb#tZ;V9w>ijCM} zB$J&7rw#>bY0P1J+sv&Qx%flfD+A7jc*R3-hbNz--#osu5{&OiswAfI)Z(GU#EIjq z%U7<_EdB9ghtSd92^RHxUVZ^xjd6VVT?>#1r$i)*McB5mMK8f7txwmc(a0=!gz;H= z2U8fCN}w;W4O1y#)rysRjRM!F5H3Db3vPaFmL3g607xRVDIVj^@c!@sBe#R(Mot3! z{3k!gOD{ZcD1?Z%vu!Yue90J}gS6Njei;kfIuVY?u>Z(WRe!1+92C!c>}8K_G|9Lk z{5k_7<%dmw$qo>H4+AS(8sig_N-9>bU4ztgTBcp?ZEe`JX)~5DUx87YAT_WzYP^bL zCk~^fp%%wa_u=4y!H7mtDOCnv*VNs|Z+`aIhhyexq<2$F%F=*Q3yc_gN)$U|#h z13fV8(B~c^r@-1NVSSy6m~k)m-~0l|^LN_<9HB}|-Y=jSF`)ITtapZw%DMB>%j>smW5sbCW39W~Fp zU<+>e^LL^;YGOTK|DR_t7+Z@>0T|B|G=e=#BA!hWq*Cdf{dmkXX~<3@-1iK^^A;mq z*M;lX7xAu3mpRu`3+f^vI#f_euImg~fbyb8vxtfRexWE{_PLT+IP}2l9(c!7N0_t3 z%Fb^knt75mix@mRf*7Z5suH;8kFQ|yf@Tc%PoOFpMrSgFC!Tx?@4Mlh2#2ci<*$7m zKmY0Xw4V7qBH=iG{mWk>mm^AJmeZCbITXWrR=6=PC4`<}sPWl|jnH~@iET7Vkw;7n zjB8gs7T2EgmAKA37vu}Yj2oLZEgL@~tMie;nP;i)r-^=7B=+aD(JPg_YvV{KLFa@a zbKHN7RUBQWRD4g*X{=ne+R%rn@p$TLla?O|m7FCC>zllRnUhiXXp+9Y(l!gKSTL1h z`?`>Xul?QMmp7e%9_BCX7W zP_s8nm6q$1RE$BKpwjHujcxDYB4xya{%zIr@TOCmeO@=)DdCX-o_Oqcc=V5tN{m9} zM?y@60vhXE@!^kt0(A{lhAN0OXqg`u6F-v@4sH&$CG78F_VdBWFe8Ef{vN@pHqu!Z z8H@M8-xKQo|Kj#vXkwu{9+wpF#MCJ6y5mk115t#^VSM}(A3>p*#fvXKkJtAf*8SMA z{bH*60@6=l@7wqjOjJpUVf93TpppndX2``uHkS`$ zI<_7?GtHV6UbA|=LHkY}(Cnev%e25xc0H>yejXlvJlH)9$*PVA3zLU*dJ5nA=09U- zpx;gWSQ0fCYUX|r3@#*w_nCwv6K2YfkKuD4{xH7y{qG?f3@JHc;>$U3rY~gQ^R;L} z-P&q4usWo|R>3P7%^0#k`(U5kPEDDVF~yU{C&n>3IgZx0cAUR?3zn@|f&PI3ES$g4 z#JdneZ{I1j)(mq<-#D! z#6e`|LP-I77R4)TRExog*H5&DzeIcvhZQ`DObCICM)kA&(^@WJ(+-HmDzeO8?%BVV z=O;*oF_}bx?D%pK(^DzL;t{D$e(1*c3DOU7Y?>rSt|=xfj?m>37E2rmN1N9J%LpbP zY*(5Uv{S|ORk7>$%9}4=c+&Z2{7 z%N18%ia&eno3wUS*~Y^7#RJdd;nOV`EhQ@Im1>8$bJ{ovCS`9N0joZJ0F$7jlZ&2T zU&LQtn821bEk+u3a?mcWID@{~DTj*Qft#S3TL75xo}Z_;gu>2Fr*O+F@MJiLk{JiX z2=NSfJd@w(Ig4m8f`*oPIN3ji`<~c~Prvt4JoNY;G&R=XoP}+;?e;ry(+A&;`r2CD z_sfScJvD|8-FO4yi5hfvbl}&&ehAs@gkG2T-n%05*)rMZxo53#->$ayHmh$wYbCWr z5L^;V)RvqDCJ7Aiej38=thsjjRtwd0jnwK899K*Wk#;;hJ73H`(5p(?5P)yrSOMTU z9{xUClHevCm>^`b$mY@*7#u-5GmSN?&$W0M1QIoD2PO>3sgR-nwAJ8~Ykzhbn(q=B zzK+(eYuD*TI0AVU0$1(WRu0GG=;&UEt=rDW`R8p#!I9~F-;Q(7+^jqptaoPYTiyh+ zo;?CUNmQ%i**Le#(P#cd80KE2hw()k;(S~+ufe+q{&hAz%W^<5Zb!*ba{KcDOS`Pt@fr(8@_O`36I7&s! zUw$4|Q6y>d5!eBjQG122JvlLk@zGJt%w(}}(E_xzwCd+}J@vF$wCgsmM^jUi5{p+} z*@H7@`ox^S;_@pnlN!hGe)oHfjZTY^{m%EiM+$iRUVQ~mKJlcq%U7>B7uUS?a{TUh zzsAX9r!*3}b?YVAv}qx_@FY4LGe}es(U7F2L64jX=G016H7@$VE~Lx#sHv$%C>X^# z=bnq9!Lv$QNXC)AK{lh$%|M{VLza7*s)7Tm>bRbHm{Vkj|6g01bVOFFG|p-%*v~=` zBG-rAZ>m(Y0*x8l@^Lm22iiPc>J)KuG?FawyM_Q;DV z%mz$E6&1NJ;cyJ$suskn8_`6;lt=@P9Xo-RX8KR8Gx$#%(pDb>DWUY51bGJ*;Fu8d zkf1ON?}vJg(p{hc(POy(-n$W%xRh-=J0P69sZW$#Wx@4C(=3|wFc?zAB|kNd51q3P zx4pIpsc^(v=B|y#io7;itpG`gec^&`X&P|d8zdOeniRsL1dG}s0ZgY;N;ViE*R9*A ze*W~#gx22H^De;hRjV*KFogNt3p7ecD0OhK7xR))oSm4#bGu)`nbRkYh{r`89qbQN446F^u8FfBqCNwM*C^$o?pZ3{Q7EIQV7;1;HjgnfBSJ0H5F-cmc!{SF4 zy|9u$!2KAcN3v9OkmJD?3)>)0zk%QHjiwX`T)T$%HJi_3W;%`fhFTrGpa1M%qpF%p zqh?Rd7MFqm1F?H%cFtLgP2pAR#oQJ(ukI>iLq6T}mt;D}Bfa#o6TgwD9HH+FCfFyR zNg3BG9K!d%|09ubjSnOih$Y(P2;P1Db-3ih^IeO>DO5(n7@JJvpYA$}*JkFq@$^|F zhS%x?kco*|lJ46i_IZqiMjx6|DUXh-Y5dF0YtTq*0-lF1`B5e7D_d6$`!Q%k4BU8} zP!-!t{=WD&o3$0}eo1E8c_fIOs7V7(u30;psrw)za!gIT@ zeeDu_^T)r&JFYqpi`tuU``y1ncUKad*KgJ{`R8waA7A^2&xw~rbotoPqd+NT+%orh zj2LK6pNtFAMsV!_O@WaA5sj+Y)%1?z9vJFoh?k)YvqhIj5&WP0d^TF`N%e*{d2Xjo zkPC8ghJB_bBSUiCB1;bDCSM+*VXR_2(v*W!@Z^4@YwH`Qda-@S1)3N$?qCo#wG@`B zRy&>7=TUgSm;Csn71?Y%m|&RkON^Ietp@&bNlO{ne({?S`0_0q%C8(OAy=vbLQ&Ku zTX5keJFt4~xk$2am^Z(2Pgdj(vOr=K6)zlOii{NGaaODqX0R#YDSL4m3qCvY(+=Ex zepyCiP6|aZgu)OJGWLzMX|m2#1!Lcl^Xr7rNRrDH zvWSPsY_)8bNfKG}3~bhW=3F|*%~;8^vaLceLia8Ts89zYr8)fi`bH$GDM~~=?-X`F z_Yzv0+p%%uIVevb#gfD`Xh`NYvdK!*FIb->#N+k&)@=iL=(%xpv@J%wI)<*!1sFQp zt9jc()+CuVlEdV}B|bi@WvR|fN#VPK#SEzOPS?p|npHbQo!m}(kf+SXDeqNI&J0Q}rcg84PF zq}i@X=hJxT!QbG}f&Eq;`NP+d*K|NIiBZ``;TJ<SxufDG8Ms2dV;7wZ3hHxf|*oOL5^PWY$I?D@_;A$v|`zE zC0$fUY-?}Bf{re1y=aG85Z&DinU&T=-c%zMIXB^toQk9&d#swNondFe1Ppz@&R_t@l2QI3TSrmXat9596FzEeKd zX&mrg@_qOW7*r`3#h+(!LL)C;B%c|tPkmvRX!w1s*I^ql8Z*mbaTrXr=#!uLI6B%J zgdS8yst^*h+|(ES1jAgFL0^R#IBdm)=O_4nvBOB+*q~K})KDoE=|hndXNmj}PO=b1 zs7bQb3G9FU5T4xiyk_r326sGxi~9)cx@{`;*BWdc_|Arw;TkRz+UEm72Dm_wP2d~Rcnbj7t+ zjv+jz6$BA9HTB`(eM=CnHDHN?c~^K+K9ecNRh|JlXH#kP^$noDwg%k`7TREdNW(GI zBx+T(njV5fl;&`0d?Ml#9IkzH1^v^uMCII9Tcn8X6jPenwXr-?Xu$n{7{>Dlfxcm~ z=Nk|RMX_YrQe1M`WmvR$k(8c%|J3qGyBLXIC|O`Xb=Ek--%MYzdqlt+GAYUMv-$2O zYJ+Ma+J7m_al}S04!#c$H2MQjh~p^uDa9`ggGQh zGoSVdf*tA{_w?#kmUYtaftm?n2|49*84KVNj>)OY^KMx@2wvU07Y7d<6zhD&idEQh z-bTE>|5ZHo)N{yZiulM!K7wRjTn}>p{#WtXqt9T&hK;!3f-NWoia0wsgcB!EWA%#F zXzy&bgSTA5kz>ci$for#t3U=D2B6v`EBLTf8f&tzqPymG)K(D@uu;hXwdn&{B~jEx z2#4!2I2pj(KK>Zmx>sQRhVwLcOlB)J8_3$#f$nUo z#hR4~4-~xkGo1V90qtj#m3*+LE&q*K2Qrb^g496IYLl;Az6_f;ornDgUY92XGx_@Z zI-I+9CHe=>V(+W3>bb98wG4|EFIOcpIx>NH6`{lkmaX34NS9?yjE{-zM?Zr|B(CaT zrZIUNCz_s|(z8e=>ndhNBE&^0vScG|Bco^W?eBgYQ69)@r8x$>>nB=vZY?+l0k4-} zFrGuF5I}uht+P5VVcW*d=sof(8tNK>X2QKR+p=n#s(gmV0sVbv)mv&4wul{-il%_hqDcsvj6}f07*naRKC7J zRK)}6Ua&;>m@?ATh2VimhBuQD?gj3ndKL&&;S7Z|p4!vXBf=&7p}c=yw}7LS490}? z&63?_+-2v@^~HXB-i)kNnY;eJ_7a^Xr>4za(@PL*0*9lHDWO$1Rbp$(2P7r%PO8}( zim^?`pW*$PViHoDR1&&r!+N~s%~v2AimC;{WI+kOCIajr*93`lOsvoB`8A#dXaT}` z5U}O|v_MP0@m>TDVbED91EQ?ZMm`&ktxio&OW27;!_;&ZW1|yz;KAQ(579@3Dzl&d z^e3@m*?c2)8;fgBaAKkm#Z<0@Z{7Vmo*Qhiy-AH18RZ$bLCK5Ljj@pLDt&jB`m?@8~9|w5fB+5e7nJ7jgcCCqTo@2N>b&7_7te)i0K7^3dj{n zVl_VtPT@>t3V43+QPefIVejDqj7hT2_TaMauQ~q*(`90eg~yc6J9tlhI{@viZ^Y@n9`-Py4#%FHqf5@OGaHlFy8Ag1znqYh*_)c- ziF!jCL*dT=&p-PZ?!Nba!Ps7hf&D}}41VB)@7IPk!7w}cJtQU)7@;qTH@StcM1r%a zVP(6T?@!N|N4U^xn{Z%&CM?XkZys(F6C>FD{L>id8$)ev4X(QKN>C8x-uv#u#AHep z|IIglP}i{U)tB+ale^TWSh{c(u6^58*td5No_+dxNrRrVc0I0n>s1P3|9kuGQUqkB z_!l?bEIHA;@A?Ju=^}#BFs^^sd(qlfkH*ZCXs$kuM2zhq)2XlxZvrqpOb|>U*)ShB zf99un@kFfxXGdq3dc|a3a{!o$5i3JhWIWJ#0Q0c(LBdoA30V{7rIO+}@>z0ICa`4b z68Tls*VjAf%hmz4^>y%TT+_{8&#`Lt2N@9zKAR7I;QcuD#wnpfTubZEIY;AT2M*KL z*a%e@U38(|o4*vKrl&ElWj@-w7Pz)l5odZ%qb5;}WlL!4#8wh}`-C2iGsED?U}ru6 zTq8lL_woP8S2%L?2!8R4A0ZZ|65A{zSd$e_cZ0W>iR#SsjP99?v0Tz%=o(c?smT!$ z{Kw>J<-#TCO2#odIfH?0R_&+Z;UNViYDh3pvaP@|Q3jLE8`lXPVDKPUfliA)FmnC+ z(Op(c?Ok13m!o52=xl4p!0-rq`+B8+PlhX1KNE?V_Kpt0P(Y)bTQ+Qv6zure2$Izt z6|_XWQZbVY!Nf#*4s6H7b^n;K@mfXba%z)Is`x* zSG<)3f#2r{kak~<)1}t05YQ4*nJfl}Ch*YHM{st08Z-H<9CnhSB9_mehj>*8hffY; za3YN>FWiXBE?BGA;TgoS^Skc;6*jJ0fn`J=3ITlf^IyW}KJ!s5T)bH8^^rgR4z2A? z;+$CEH&HDkAG$V}5NO*2yoX*6S&5;NFPnPs|K{ftzeXeSK9RD?FmE|9Ti-e~NBjiU z=avvKD6_hkzL2kq|Ns1hO51@0h;Gf(fG(S-#d=z2?delzuztfjslQ5!z!Cf9{1~fp zhRR$UE;-QTixE_*^&`M#-Sb>?9d`JuEb#D=JRm*<(H}d%Lq#HiT6A=;)qQo_{_xLWY30I4~3bI zPXJUoTcu`#Le?|!#yd7Aov^Rbr#(&9@F>3ijc*{ACQ;EwHc3utY3;%-AO9E%PLG<| zonT=%x+ldg9S~*NZz?b_;n9J>wbEoh!q05dWMsYFe+796V> zi3JhvBxFvbtg3``6cW`*^z@#=v7?8@NNsLz)1f;!&@Yv~=C)3}`OVkbp@kxT{No>^ zoDX1LOCzqn=2|3@RrtnNzKn1%isqJXy!+4Jjr4dgHnkr@Rq!n8s#!r9AH>F?cn_IS zRmo$5{rgZfhHF0b2TbMblwsRv<_03#V67b_}=1U>skQ;+Z%y zlz!zb`y@iqFkXFaFYdYH4mUUdr?RtzOZhqsX0tjS{F;qCnHZ1P_h(`o(OBTZ1@qOm zs)|H$)%jcT+)FQF#7}+XGkOkeFL{9&o+bPDA3*E87BtMOH%LC6Q2-qt8P+v0Ik7{H z&WY7%Xlk;=Y-AW+9bMSCej_$+-X!~I+L;fJk6~Ut1N2!u`qWc+`Q=wII?#`q=}GY# z*b-=OYt?JF6LlyQkVw?%^}S933j>Yq$=W%kYK?hJ@B}v7zbs6=@syc=@xJFvVf=p2Fm8Qv z0)>E$V6vL5RJ}?p#A&Z2V3ou`?c7;i1Wk&RO9&Uz*xELXzx&IJ5T+o#n{F^ToJfM# zN0^mQCIV@Pv?W?TxcSyFgP~0b5oODYoJ&OY`PWY4zCXNx%^O$ahPS^NQ{&@!WzP#3 z96F1Ekx85yoFH)tUCjxsU$GDyHk_lR&Y=DvUV8a896$0J-g@0zwYPeD2XM~=cj8N5 z_>%VCo|j$}C#SQsMIJ&-TBU;!GBl>5witBe>j=rImK=BPTXFH$s z_{0=m+4q`~WrkZ?wUao>pOF`X+%soetVGvLe9$Inq+Q{NzlKo!sYsr8BxcsB76aoQ zCuPW2Iy`5N3`{CsSk7?SCe8Mc?`Ei}uSam_P}w=PatB4h=>Jx?pD z4cRPX+eKG1N!a2NVpe>-Nj!YL3~3C3a2tMd-(l=}t$?%RQ3L}q1fo@_scpaqZhXJk z)YVl9RnR<0d7*XnoTVnb%Q;wz^%#+2u6i0DqVg@>Jad<17Q+h7ZnlYT_|X(QF^ZT; zPvd`n_yf(U`%I4z=)9&DeEgQbLO5pn4dfV@MgtTS1TCqb8AdjnlIAwYAtlc{N7;>k zH&rWho153vB$$>7g7^e3$>Fu9)6>oviZ-woXvvDzye%tBR}CZ*Nfa_!1R~~lUsGF; za>?m3P+uY%Q3XaDZr&>4aFW2VJpekqnO_nc%&m#sk{~ zrj1WzNN7(eF1hDWFph!YDZK9sFCrgqsEiPWWpHBXj5Y?PN8@p4>}C1@Bcr406)#*k zUyxU8bF*MRaWfoo%p)~iWJE(GKth*L0D}Vq`d;53^kO*bE$8SF5C>@oM=fTz}P-`1QjNA{CA*2$M|90)D`b2QO;&NB&P zfiN&Ip!X^jN@(lskiip!5nU#iFIk2Q&fkLJv2nRU>Y(60BN`M8AYPNi4}bV096x+O zt&+a}eyw#%y7K*2u2^1KAN-8mH%yLrPvN(;P4qkk@2?*GOJC zj8_jI$AA3#3{DlhB-yTs3mK0E)wYwpGuO4wP9w`1htQyD-@`VS~hFeti++CCvg1eaa?iv4%F8- zOOp7jU;8FL^H(21U1Pmkv5!9b2o^7FLt867a7-Q16X*GC8BA?#-#7-cVRwm^M);j# zrON_MAZ^5YmYI&Ye5OH{#l3r7zu}a9D*65qGc7Xvwaf1-|8B z;(*?r(=-)47om_(Bb&(!nVX)OLcWkj&*^?_*}BzTnhDymsOEX#^+kNbXshZ^(OdsD zpZt&%uA+wCM6g6ug_A?rZH<(SlaPM)f-)Bi7Z>3xCJCh?^}iWpsNO_j48o^LymYXD z|GfPOCepRYvqCMASW|-?7wy2MmtQR9CnMI_n4)wE%x}7K(fkV!MfM~8D5K3n8-(gB zOu|IDyafaQ;R%`CdH3yj{gu~^+0O3~#95EaF25G5*I2*WxD0laOc%XuJxC|L%EPN9 z!3dk{R<_D+KC{a}Km;&WR6H2D2?$B@uw#|LYoAF?m$QR4lxN!?E+<5`U z#zygzAO94wNHs3L_!4Z~yjHI{GIAC_yX`h?T(Kb%+b!jnj ze3E26W}pnT#vr$ek{W8`r*ldsirE}$0%y<_dl5C!A!!Lv#j(V(C|IIqRSyq4`af`_ zhx64T43Fh-)0dvcc)q~`XfS3R3^BwBDbrT~Nar$2@D?ms;B13uaOChYeD+hHz<>VW zhX_QYXl|aTwgM0DOp4PbHW$x?KnE2ytHL3{>V&6NB{{Ep_4mk9Pf@d=q!xhx9v)IW zz@_gm*U&uP@ve7cWMs@}kotcTJPTO9dc6`BuA6jfQgCT|Yr8%NgA5TJ{^FrU!W^%Q zWKeQfq?ZsV;<*=}#qOteRV;snKFK97h=Kk=Rm)n_Zj;-du!2e|oUEiwpFa}4VyN(!Y_b~rc{a|P5$^NKgU4NDXlTK z500HUf&PIZ9db14TE2pYT;?$$6fc{RS=0!j^vOxIx3=N<@ndLfYu9TqiQ@H8NQsGq zubjBgeS*d0ne7U;Uzjj@F)5#DDv1vS^?6x1*tNy{A*|C_p z&q|HX5*yEBSkT>#D=xoS91vES;UHmXliOvIV6Za@jZEq!lQ5T}+1f`T5$cGlHUTS7{-(@15kU)f zWa&Tr$P4(+Q+ec~^MvFI_oc3lV{&<}nzg@8SHw$6^Llm0JIiKHH^|(soWYXNNqp~f zS5h?EWiE5fmsDL^GUEfA)&$AwPFI9yGdnRXaG3Cs$UHeYgWGQVB~G5A(`^Qy`s`n$ zv%MK%ghV_Z8X3l+!$;B5n8eCuEAi|LFJs?p`|$qvy%X_xLgsLMPfiGpj*Q|r4?lwL zj(Tj~vQ>%R|M|j~aMKOfqbk{ep57Cfm>5-YwtU%qv=Zs&neK?L{%rSWz2_VFgn_ru zpPQcJ!PrGIG|$qh$rO6~1~4)@tmL>l9>dC&D|ANu>Q}#(DI8-FiNDl^;hy5iW?g-~ zkO!hiJ{hz%TGoD-%jXRLG_f(tb?Xdq94Z#yD2{ODN77^i1};b!OTN|2N5>~lZA&K`VB@$STRTO-W%SH z>got?z4b>X_7jNU#+z?MGEt4b-d^1Qt6$1~IhzaM6Myv)UGI0k^KY602*>L1<-h-; zuKVd{pTHk~`-JxP`i&Rh`WxPk=XXDaUp?>;N~Ih=ddnBFaB(XJ&YVU)j$vJQACl2= z1cNq)V++7wak^BNOE&GGib9ohiMm5bBs=iMe|{8??kyr#)1V5ShdMtWTO+R>*spue zd&{JR5HgwfwRK6s*M|-rL*GCjmMmHlORk$ePKxa?IM&oRB3V06 z2NT!W(BK)NGz+>GXqthrWJzs_fD%q_NCp7G)ocgU*5b~)eW|*h&;gItQG4 zw{bMCr(np$UuYNPx+xx#0V$-$bz+KnM7PWymuLm|yNHarjL==oUwu}iu1uL z-}7tU^Uimmz9FgPkqCyb&N)^bVC*IT6GA zLM?r2SCC}J_a~~u)(26Ae6fJ_>o>?p#!EhHO}UXd4{;kI(co$6#<-DdwQg8hgkm^2 zP{1eudq2XFYB`Mx`PEpZ|2-Sfg~B;xK~p~JPum&6ES_q8>^+B&LtFkhe)Kn2A{u1d zlix=~!uQXO&?akoAqe*Tx$lZ}HI&LE&-V<{sXT^8r%~HbgQof>R40-+boc~*cE*Z>92fOnKuf z@K#!p#Wh7WU&h442aX{eH&2Jbp%GlT{Q{j0r+fNv@Zb>@!)z@rnBR$kzJ8?Bw)VJ3 z$yZx2f4*_*!p2XqBF9ZGWYbFUxrccsFqz}p$)u;$uIW89fE^cZ)43qALMMmMk!_E( z`&NTELN0;uXP0ph%+EsTv|t8@oXjC-S`uRuTZR~wuw&=72&A6fR;D&SFI<^~N+iyN zGoy_dyCj*4pRXD*OM- z2a{CYy2JaPbN1eAue}x~vq3!g`))k?!Z>n~T4d892Mo^Gk_az{1dda zREwA)?E~jAL5S5BgX1(%K}~%k2BVa_7zRD@60s7n9(F(@ellNiB2GNS_&!<1P|F~d zvi5=r%m5SY@fOEWR#K_=#)*pwX(Jqvm%{ojTO?LB(0>t+KJqx?(GtA({kJLj(arHU zzx_3i9z3qV{F%>vR#oobeeRQp#jBB+&f_zm{VWzNXvMd`_OJMpUG3PsY!tCjKf*y% z`lFGQ=5p0%wMAhJSR-HRetNgca1`l46F&O+|3P1}S#rlBEjltE;cRBb-gcE@J#B6C zF*rOd+fp8g^|jS#Yilz-hGg z*a7hzG#{MJ%2+6soW!MUGC7o|)A-28{}NyN`qxAfWYC~`C=*w%6*Bn6v5ABbj~3&| z@#CtdTbr8%rxRB9hDZ#)_Is>w#?jn5SAA0SD&b2^Ta}cURs~7HCHCEG zYMG?*FeSeusbYhQp@tN?gGeZ)>0W5uRQmD;RrmHAX_OoSem<|v$e*jS6WmVMJ@!{k ztjXGAEO^M2RHIOX9ftEju(%PPu2nw6U0Ed1XdN zt82$}CyMFE=Dc@`?_GNsH|G>xc`rD|JTWmUz7F+TSa@(>aLq}@HJ``4wuO$_K3me* zk&NYOV`M}_6>JPnih@d5y!xp!^_B*#=KJ*E;6<&E%CV@r-98WH#Zzi+c{^ z*u@Nbj=zqYiZK4<)_0-0x>DSus>*UDlx#)3^739h{rq#NudPFAX)%^ATY`$RN;EXo ztD>!}s?>SPgk94Gv0{AV8+YN|@4QZ}m@{WC;^D_0!iPTiLA7To`TqL8eHa-X($9(R zEp1<<^<&P%BpsUHkXpe`pv@D$3strtcasD62!$!5{s-j2r}e?rqj+{;XsGN}|6E}XB#ljt~A zJ=qGZtFFPEIdhEnm=7Y8C)$`p5l80P(p8&j)|jRnr!6n#A4rAH~2_ z4KgT^AXB`!3X2xc$NN6`ezh>v-(hOXs?}xY+(;y1v5&*&w(%;$k|ToY7$g_~zjxQ2 z=immsyvppuf{F6yc6lHpRlk4hR`qjIvh{o&EkQkIcaJaP+NY=4n2O4 zv(~&>e4ngHJZvdwhZeNbus3PnXPON%@rL;OmJctp038{|LqUxOE!Vl7v&`}Nu?U|Jc@JY zy0CCzn;^8QL`r>OCT1MP>F7ACgRHr^MF|yQEIy9wg-IS02aZHB17-roP2wv?E^Lw> z*}G#xr4c$O@FJ$X)cTUhq{z0-U`|UjuGp~?9UbQtI4f(LJ%>spQX&kj-0JG<9O=ot z+V#1eT`J*L7GyvC@%Pblu1m?GM4vcfn4p|)!c8mKeK1p?FmAu~b{z(t=ew0a${QmR z!MXFD+SKMXVX!xY8LuxlKT(XKfqrbRYrvYFJMoJr9!3~paSGZPgL5z+~pnb_A1!T57Bu+%qE!$=CN->4Ns;U|VC#qz&w6m`q_#V}Z4TU7oMa_M2L7c?1*BO!TJ;#|72?cohKu9H&?K~dDX^mmh zYP_bZ0)71hT0>TOrW}94S}aTic%Oy*<#KvG1_AY~mlps4AOJ~3K~!FU-Upr)YBgoj zSik;KEM7EUBa&?I@!CeCL?h#FWX?HUGBKgRPS^)&2S*c-=SXJO(2vQ9aamw<9GVFW ziLli*bt3eN5S-1Ux~kea?0Q0&Rg<0w>63axZ2p*sHPc>l^Ze9_DT?3^PwmDpUK&LY z+K|y+c2h)33S8xAH1~pYuUdCJKlvxgZ;Yf8i*gRVnsUgXE;NddU(f+vD$C2z z+dqV^o(?Q;UxaJka-}A4PMkU}Z=86HoE@qmvPGK1`~_`5E+TaBnHP`aiHCotwX%5W zB6OZRhlOqP(Y|B}np<0x_#8ca5QD>mN=hkfzH;SKk%)N?h)?9*5j|?)rkMQs$b(z{ zJ#J)?Q!242+W<=8bha|#VH_iuz@*X{H|_rMyyW`kTJ`bL&U*{){w!va!K9XJma&KX zlly~vh5Ld@3Jaf0*00z4F+~O5QuFQ+x};*vqO;HhH$!2s%eC~!x<$SvVLF}qB>J4* zh0;&IXv`mZTuvlmV)wSZplQysD?#9G;dq5PK3Z}+%Nfkxr9P~b`ldPSP778V@syyW zCxai{djfrvm6%Q!OEHiY7g^{xzv~87dAtD}z4J4fJXA#3aUYr&hy)^$gNp(TWeC z+8iMqj_xEK^eySw@^bS#Pf{UlKaL+gu8Ut=+lVW#+=`Afr}5l#yEU%T(%g#c-@Xfx zXb6W69mbx$uW4ER`G@`j!Eg>e=ezOpE3ctAUW#jXU5&c>YGt&Y9Ub_?lTTyWvgNqx z<{QLgV5M{N)Je>rv%uWql1VMRo}LS6D(S<#qL&Z}4a=IEpo&42GrsrMd0_x_Fq5xT zh!SaD){CzM5sFlxe>8?WfA%Kc=%iF~Ts_b7vQp5yoUk1$GtSlXI@0rihv30OhZQ8) zH=I9jzVlVcD@ht28WPEphX^+aIU77onLI38x)eu_9@TxHN5LOQuJSBw2K(CTDz%hY zW!qGWSr1oKRAJYyT_`E9F0i(H`!0ZlpG6DX5s#OOGr%wJ^u`L5>x%F7!3XX|Pfw3v zNv^?kE@vW0PKuoOgDQn3#pU>m4}S#H)G^4Bgf)RP9i503MNm>&s{3~Se3ybKM@pG+ zjE;>dh^iMT8R(4E9j{)z1SRw4;(^B=!}!FQ)|$kSB1H;@y?x}C5Tc({McZ+%ONy6E z7B5uL<@*==I!E-ubOq#{kj|jKp+UiEa9{w`b$v_?*=gtecs46eV=1m(lp~B>cNCLGLSoO1S?voWE zY>o>=LMFejs;w}>7t^(8f^HrQc}ohMJucUVzh?Y?eQm8qLCruaq%}w+>_YEFwW^p* z@$+|fcB-8r!j;oqA>8Uw7yho7c4m^$($u8tkFB4L8`h(tu2$`b;*z+gAjpAWAwZsq zSz%iusFo*TS@#-w@?R2D`fp-%9Es^k@hB+##Wq%BQ!7g8xe*9yy-8z0iTRA2yzhIP zi>^oh>`?bS5G4pMka;+nf9ie3qImf67x42}0_e?GAxrNaHx|j~)}D7W{WkI72!?z& zj+p2R2!k3aqimB=)KMtPk73u6JU(*MI%H%-*{upj;X z3wYs`XR&U}cI-XYi)%Nn!qT}_h{obLdh{qR_V!5!ga&pkEzKgdPE1eY)af&b7R50> z$~IgYt5>g5(B~xYKm60zQ9`t!t{sEDMA@dWZR=%1qj^Sqbcy#@()lG67&7vABot63 z-rm00%!@RdZS7Z&DyV3(+{zN%DH3Xf;#JUcy}G)}#>C?$&cyrl$Rm$n?b_8!M#WtS z1kLi>p=EqLlV_?DYiyXNY4qijdUZ}?_@-lE9ze;Yd4)_(6Qxd}yZb!m&zpy;Dz;k9 zd~J3@;L%a86VFkYJ;H3Yq95^{(baHAqqS0<0GDsI7}3?<7ZIN;c3zLb*o!;z22tB= zCzaWlwJ>Ecc-BTC?9lUi)69Y`qfsDoViSS}!yL^CqjxxrM_(GkBhU3BAF4n;7ep!t z)YLR%?S@P6mTRt-01?OAO5-I8Dnt;Z+D50o(NVQFqR}AkxZ@7>wnH$_Z_jMcWZBz$&y&*@>X#xul~q*=c)W*%zi+(p zW*k0z82y6-QpbGbjYE#T4Ky}1h=I&tT~}M{G{a3JLxL}1`d~yQJY#B}78KcUHf{F2 zNIsh{+lGdwX7u*<%eR6_8iNm$Jt;_PE}qJk6WR{<|LQ)B4x2g~g@|~tQrVK#m$Gmd zxR)+lja|F0(}8jE!Z{&6Y#oto#rbPWV3Q0=gDS2Ku0hYHHfK#+cbbBkn8tgyZb7EB z823N*jQlW$M@O_7siw)^Ycb*eR0_jGBNCE2di(^6OGgpQMHg7)O`u4Zu(9uJ3g*3-It0)fc--E3iR^p5Q^zSH+R}@?kt=~+P z4@wG;A3v@!*cHo{DM65sS9!UTJO=3$r!t(EhaFOWtdwoH3DnlsDR>id<>;f3I<}H{ zi05-kc9{q=f#Q?~t2@($$jRS=$iO5&bI#yy{#RFDuVjfy3fCOhHj@DF3BmWtz2W%` zrVhy#m+f^{PZT=hG*&t>tpj-Nnq}fD5UJzinJB2O6SL7W79&jlOoH9?y;EYJ)8TPU z*L`x_?4bEtW#yHqZ)ilUxJ>)mFk%zg;(6(L20B|^kn-cRh5*{=ov#f2NTf~FxN$Y* z4gustVZ6BK48Hlq07kP_$QUr-)Dvy(`7fV@YedhDHX4Fptq0#uHVY#DGmUUQiMi1M z{Gazj%y|BYNOfw$gx1OEN42e5F_ zBJA9}5_9WIgy2k$jjPo`zbukriJI~6RZ2wroZwlR*6o?DKHPcdU6|X_q-0T2;pr)C zxOBY}^79Fh#VJz(PNAxz1hJ^;z?jZX1PkWR#oW0q_8HyipBG3HG_RJY8SK$w{*}FZ zP+w#E9aGaOA$weB)ES`_``Gw|B)~_9C$MGndPJf&8th5PJR?Y!rTXc(Bjm1F(T@GE zzmAHEY9V2aBRqrHnxK{lKOgl(D7Mw!zEp-(D)*dBfC&t`&*f|oX1A+++r+OSpJ4iR z<=2E_x|<;MV1N=@$4y`oBP3z`#hsQU$U)3Tf%vDj9lXi2!0UnrwKS)tU2brT`uoYW zL>|=V(T30?Ff|>=zN2IK>4T>*lBz^D7XkS$@pw7rEnbQn-*G+ao9h(JO@t%o0&^OH zTn^v9^J`Mq3kDvc$sa8ZFDPJ;DeuXmJ_xXRENh=`m z`#jW{4Xe6hznkmCi-QnK&E=J-G{_=(1FEa*O){8=dlB8;f(lpz1O52!cfN)3(cyy0 z7Y}{v>-$kI9v0Mc|G@1ZLRD?G?lFBHCMQOudp|TVC|>~EbgVeS=;%15^}xMAcS{}) zoYbI|Edv8bp%RnB*s)|O&J7*Mh4D#DB&ywH4n?qvFipk3Tuyo*Oo|422hcarkCm%d zDOu!t7#<$OI5jGy)@SV;z83%6w0X0F7C&QCLyN90lkma80aR2~EBQ9joa zlOd|$X?leOJ@OwWFfl$Nu^^s(b&buat!osb;6T>`MD0GDOBQC-9gSIUB2RyuB=CC7 z=zRD?-;xCz*_@ir;Mu)r@xAB9F@{Prt~0P#;L7YI!P*%N3|?m3LDxd@TvaLOMw@zI zf)>uD5zmic$C41<|F%nns!9JKk=AEt;N?hSS9cHE=FT+-S{TXpEC2X)v@LAH%{ROQ zyZ4{LuOEIA3zsaxg4RmxT)ztG#H8F&$3{jRQIDuEoi;5fW|AiHec;e>{L8<64fE$W z%Wq;%>jIqYIEoeR3sF{9t)#$6d1eI2^}}SPsj(LAOBUmeLkGnPBT<~6jNGfbnkp=q zKOa%HiCvLw{5}>GhT1XVVzFb0cSb0mRE2X{oH=veM7}CZQC?Q97Q^M+H<>$Zo?NRW zdV2>jI4~?;X+^nB$4yMo&?}?~t89jCD^A{7o6q75<*PF|*L4mnmoJkJidn|bsJ==C z)>+znBQKu-%uWQ1r(l{zK8f%Ngjz^W7Fs!hjGo+_fs?n+2Lsr4`7X8_u41$>Baj@c zOwN)z0pq;$D{yw3JSZ)jG1oj>SQP4*mT{06v8q_v7vs-u&QwMcff(L6mc#>pxPW6_ z0i<(AY$IE@dH#G{wq>h&-11?k@lGU+=bwENkN^G&X)x4QH(<%qrHGfrHF{T7Rg8On zey<73$U4}BKg!DM@tM#3jr7wAk+Xlui3M^H#sr(&tg~F()N1 zfQUCXu@pqCh$DAo#a60aKt2PrVa{1IaUr5W5?x99Algb#AsQJ&D8TGjT3L=DYWxT@ z_AnHH zXlO!9Q>znX3hJQZwTs1zCDv0~UWVtNdkzcQ7NDc^H0IB5!}+dGEMBw(=gxPTdzmUd zSN-JkMnrQXJaUZVm}8FBDrf#V%;~h|>D-x|(0wk7mtx-H6}ay0Z$()tnawnCDU!|e zKYry)m>4HwU~;qO?w7+j*N@=ADCV}z!`rXFQ3q4F$Y%Fxzf3kZRpYwOb(ve_bV|Ki zjgal~*VkVE|O3jj&oVk3F>; zJr@Vj)zgFPuilBuh8pD4c}yiH@yzpkt*=g^uc~XpysH?30l3;d?5xM{+`#?u$GG<3*0~Cv@lq4)Qks!#uCXx8mAuyIVn-04&=O$`@uws z*UYMX?pu;%bGYW}Z72#w(9~G3whFHq+Z^0$v}z}0%}SY{iAX2U7Zw+M?ZotykjuLI zW;C}@{nO^}^*`-Dn~Lyfg*-WxXp%wh1btkO*@@P;2?v|3u!G&S6MP`kesKa&)Wdjk zPY-_d!Z;Gaav=%=58Vi)Wh*w8Zg8?mF{|B1xZ4$VJUc9SnA#q{51NA^i%>p^lH3S3 zFDS;smN-ILa)jy?#JI+W1_$II%lkGoG$QYnL?VZ8edl{v);=F^-F1x+z&B2G;Mv`8 zVlt7#s#S}zcuos8tXhQPSP&yjtP#Lt&%K7RB#FWyt>NLp5j^$G6LN^HERLeFX%0F% z&nW0$wt188w-K^!dQSJ1dJUNr-tqRg>AH`O4de8wlTy@FJj$A5F5f3738<}LB6%|k zoGgZUPFUi`d(UYFBb1W=Wlq8zuTF`$$#%5oJ#gK6l$tF^DyDL*UiuXbd*KMiC&r~l z+S@;jdGnej+(hg1z5xo;g|K+x0z>khmJs8do_|&%#l+R~9`rt)4urL=EcsNApkPd9 ze>Xn~>mC?q%T8ZSeYn;y|E?rqeD^hZT^O4x)##(GDKExh{Rt)rPVJyDKH?_FjajQ1 z${CT48DDZobo7df!4QsjWbo+o!+7q%G_r^}j%^ghmDRZ9l8xAM*=9^l58|#ne~7-m z9&s9&ZP5gX3sUbVo7Rl7$XqTt;rrnS-gV6lSa<0PBiXpoH;!B>z`#aZmCDM+=>hRW?V$6_vxR z8fGS_i2w#jY4&Fk#u%D|dr%%G1Wrv4<#K$oOB8DF>wUr&3I;aC+>de5YF_4kwHYgT(Xfl_nb*{OfZ1S=}AGgT;L1} zI_N_ooIZV8Ff$bsY0kt0h86P!A>iU-LC+%f(2bIUP7d+mVaIVRnm<|p*$%wTON(*K zl{Hv2mjuVOHtUP84debNdJwB!j-9*SD$Rs%eB&F)xMYuQ3|7um?$n$&a;PXPcfIcl z1pq?goN|!8cp#^>Ko~=YE-WuJ`NL_MvBmMHK)|H4Z`eHgUc=FJsSC)sF@pH@|3cy!Eqz4VcA?}h7{i2|>YiK8*7nf3!2 z>PGHz250$vL4uiwocDF`W6(@2m~=5vbAO9K8e)H+{tT0ac7oT9AVOih2tygThX(q| zhcV9-KChpgFySXAA5k->N~QEUN{VCnvp>B}$PEh*5;pl+OUg)!Wb45SBNjhg7c3rZ zypiq86sl_*F?Vj8s!to4b@I&y=+9_usKsC$FpikX%SPv~p&J@ebLyQw5%8WE))t=e zcJNgr-~WaFK|H#<2fx@ih3R0q(_3@UY&i2)YWShA!LwFqKSJ#lQIZ{g{{-!R0$Pqp_|| zJdjvPH4dG;fEQjlfNVaD`ldSMQXGK}qHkmz<+Tk?^h&*A#EXEJ9{m~G<}?c-oERU| zYj4}K(R5N~jm~=B8MQ-p?$~ZJ%x>hdum7U7UHBe2)s)Vdt1(eUBjj3A%_N?FE=(M_ z_IMU^e9`M^_+-NP1v5TGN~E(ksw-b3=guj_SsguVI|;#NlAo|iF~!bYUOG7)9p_Xq zd%119wmzu4R+MX_dj5*%D)6x$HBixLhkPOVDg4|ejb7S&28nPEo?Nv7VC(j45tw-O z?b1n*um;Bl`FHg{nE7+Wh5ca8v>TLTnG_R(nK#Wt&S%Xw2|)3p;Gc=I6=9>c!d%N)p)D6j{k&d?E~jJDu&Rz)GL>nbQyD_%5?HpC}Jf&to}M%K1{e+X`1GRy$=yg+4trYNG5|FYohqf2j(C}_cvD7Tp?l( z2Y_%X_8lC@15fs0-)Y((Gx;#xc8WKNUqSBynithnsw!s7M~M+z8^-sss!Ea_ zoY=Ml(V-5_6>v6GvKvm6KuDTM77A`@3 zW3#zT4)o!~;r+P!iuL%yKYR^S(>cVP2@Ve#2I0=Gb9U{sd2GD&QjKa-Bu4VejvytN zzOuqui03Sb(sJ9)XN!D?yrwP4A7IiaH%wJ`84Hf%jAf`7H zg=|*H1K%6pC)bO&j`ky5rhj3CG`4%VuDtIEqq2VA5hA(H)C!Rgja5-s?%0aUHgC}T z?C$OoL|t1~jd+ZtRQ9z^q>WHElM6#3(x|O#MnmHqD@q*yr@*9l`~rUn8xl~!%=8}Y zfcJDV(>U-t4VFL{5;1ew+gWWA?DQI7avnxc-!LA2sSE%8dIG6%nbu#yd%L1j;Wzp$~3Kh|jt8awZ9{+>oa#pB9Z{+6r3Xf+2J*q6@`V?849V zJZ6MNEYl?sC#@i2rWR&3=`$Ql4y;)wLY*LxBHa7?0o?NpIR#3=NOyMhp)R>bW>>+222`F&jcx$|w;)_r-qA@;5fs zqojm7-$9%{(}A%`y6cr=(ZYFxZ3#CWICv7-R0fL|Ekx^FBWAt$((C%{gu%95wh6&- z5RX3kduJ+=$IUn0DERcg`|m|05B%wk%du?EB*Gk_3~?c6b*O2vdpI-5>W*y-n{3d3 zoWEw^SCU|Jww7_*eX>Pm!IHnLAnHM?Km?I!sR*hMKR<|P_FlwvmLx}GX!9C#k+W6A z^+eR=jxYTm+<)(V7#|yz-E?zPqZtIz1c}w7#@8m$HqS-_eUF;&K_)A1gmzU^2LJe1 z3y{y5f}-z7GO%gVmzL#B3L?cgdohdqpXkFg`v;LsvGTQEE!Pwk5(#w^*7j>tRS-9! z>jP?5oK?FMwNWzaO~V8oI#U>#xUip?(i$`CaeQSZ+3u$LlXYgAHpIWRqlaGKsQ^5>2r%0EEKkT)rU=UMPz{_frjgoYqb% zrM4IE4?iOpxEGP#NkeQsMG~M~?q-aqIv9AOJ~3K~!fk>il;5+mZt&0$z^S&TJ+R{4bXp z2hx)WW)lddM{(1RMcBToO|QsF1zrb^2l6v=Ei!>4vc>D^MYhx?l}vXSuOB#!-~R4* z(gL{l+NFz4H*0Qi--=6Jf zS*Lr)U)QGOc|yDPOD|cgvrBuE@VrE#nB2zjm4EmbUAK?@`Fl`NRcqtVj1QBO?rdQz zkvcubz4GT_p-7%}P8wm>rW}kTXNiI|Se#V2CPSQ;kT1xzmQxvBzuvw9T=kai){fSM zkR^Jae5lpq^2yofvtM8S{i$K>I4(wdb-(1$9y`fRk3)$e0ReJ&r1oiJv+N6OyMmmA zm#^oMi9mp)L*6V_j9yFHl2!QqP)-pvd%g8f3E8c`Y-l~ zSzlFMCGrki6+IU&YQ%-&EPl+8ge6O`42{WW3ANi;i9kg{k&cAI8ztX0Ckw4?mked~ z)q?UFuwHIJ^1$qaFJ9cP$pS)^M-QLCbaEOimdwYBxk;3TyAciN5Dld)gH?jXOqdlG zc?mpVh%6X-AZ-Q7WP7(mI-xs>6^AHz_>+fbDC|`otw%=$iDw=sGJ-|5c&aF76X`1a=>F4qdhbPK1CZk_@Vh@1Ove%gb<$RSB8>GS%wqlhP;e5y#1x zpuG3?_hQwWHF)s;d+_!vH{%EY^($nvW;%cXoOXnjICO^Qu{VF ziWme-duds5Q!2SwhpI5^%a?Dpf2UNzA>$z(_V z67g)Y_4Hhn?6aL8w2e1~MxFygADk>RpOde{qr7zf&tANq1oO{Z-xD zI!{bbV9AojD(Wo2v7!eyZQSU{%qA(!wz9~K$g2%_&DB@w{%HJ_GS`~4Nuldp5AJ>7 zK0U{~Z@d!M?7BvVc)STi!z3vuq=7=zknh8%cm90l1m47$P41BYX33f#{k5c4LRdN@ zXOa^e&!=w;J$Znkp;2_6@4?`}DBgPQ<(M;Xj&bK)0-`k``EAc1n6a={q~#ew$##b% z%qA~-9*nIc`WM;n7NozqbS0~5>ti;tk)L_%_G=Irf9bk>F3%4`7b!cW8P2E|&LGDM zS+ciI(ow*N@4?7r(K25n((S9sx@Q%O#l7b^g&1?+HSlA4@95-RmTeW7L zS{Tei+5aZo;|+vZ0dwT>;)Ndk@W($yX)&vzAg;KA9t|US{E278-=Idpb-S)q^-5>S zJ$v2|3|muEg-z>M3!&)fyoj#z7i4qV*ifO*&1=ZVG5C>T&BKhFk8mjAC^{nYpjBr_ z$xTqR(M2JSV-dzT30x*g+}t$oDbJrpFx!uKFo{?(ebsY_hbhj%zZ)+h9AePn_ecn{ z_Cr{K)cWbxQ?$_}WtcjINp$gt84(Fj?y=3vKw=}aA%vn8m`FtNpZ6cc{*%+_=p~ZF zS@be}M&2_fM&v9ovuA>)geJ(KQzX(@M9P*7z?3M?E0||<2{aT>;jX`5j!=G71Kbh>`xsCR2EP_X*tdS^{I~awQ5BM6x56*TUKaeu@FPl(GMFDdba= z08xbG1lnqYxZ}guAw5m0bmg&3A%waX+B}Xd$o>Yz!-b353Wzh&pPf5*IH4!w!|0rM zzFwoN+~XXXo|sGssrJw3Nu|8@ zEEp*@PO&2vwAL1KD5KLFU^2nIV+ey07Figx&B>&qI9h~QNih!We-i_PL%3}7My$PL zx%e_(wbi#5)E08*d!VF!=PgJQ?f^*2ZQhRLq{DNiJB9d+~};N*ym)n zRZ&)hk9_Qt2!*WoBSQ@`G&uI81;mQ47;Dz8Ro2QcQ^R5l!+uU;(%A4Yj-PrH&p-bv zO5$;>Ub#ZS^3<6V*t_qDuE&a{i^NRj0df4~X`Jt2<(x$u=W$yb@XFr($fOO5g;g>h4ouSum#=t#exR-d}(HAkx_!>g#K3By`MghQ~ePP zj<9DNM!ejd0ofAZ7Y~=jbP`Ps4Ja$GPy)cUK_1D}#F$z=?JZG!?Q`wOCi>)X>3~v$ zZB-dj_Se)mXT+nN?Wy48fV?BJN|J&I7S-WL_Z-9vZ>G>Y$v(Er(j8%w_m;$1S02cf z%@SR!T-9z;Z_!-k7A{zT3Rci+H`q)&rz)si$u-DvK8`Rp)Yd97rJsUj_9lr=t$!Y* z3K7KiG)~NGYXV9pElnmf6YroIYt`2&n9ZHnrnO6}=C%d%alY#uPM$ndFoa?v#?8VY z+*((SYp>dbN1on|Og@P2?jG%TPS8wGPGQ-ycD+9ye7pyQ`^gYTy z&(!#=(lhkb5)D7gI3wNcgMeqtYae)Ck&eck=Iej`_+I?>UrdH2wW4U8$rx;n*3RrSbcyES=$8fQ`2U7_qGS-Uq>yod_Hl6wZSa4^25~nK^ zlmjf|R!wDvMx;-lI)m2M2E>a?BuYqEVDBB|*S&>Yw=Vpkfm_?Yo!|+JKAH3!p_xR% zNufBKd7(gVB$mI!Bwqh^^31%q+u3gD|HGwu2I^ptNJ5dh1qOZl!N&7Uxy!W}JbA)p z=0XdUj9GPQn_s@6x~L*7veMItrE4=N8L<8hZH)is-wxwwZ@J)c`G4!p8}yaVu#&Rm zh43dogmk>cQ^@HsApwfQ9^9zhTUC_}c=xUEMuyB)=kCS>-K);=_vX!=hnm_N!AWAw zQ$|=)m4_q_Uq0`dIJT*vkxd8NtWo9k6oeH6dCsI?mbo z8We@;N=Aq^jbkUz>iv^_Utd=x)Z*BQGoX(KE2(*NoAsHF9y=i^WJ0b>+83d&wgUV1 zzaf2k9;R&z7Gv$&RobKvJ@i{SJ?1h~xN_Tal!y8d2}~j$&7!O%kD?$eK0^CItcaDb zBQsKFI6%iaCIg&?(48m*tZ>-a>LhNF5NQkFiM#MH3Yy)h5C(lB$bp1f}@ReM0{W&)?q6HT1wKjFY65(R+x2Ouge!3G6J~e`Y@h}!FUxB9j zIZAOU1Z9pTHiF73SV=DO7#SW>rO&Atu0aMJ3wi;q5pGaw1^6nW>wJ&yI}e4*vQh-; zNJy;!wk;Ugm@JS>K_3rQiPRb>!qlX>l=68sox{WoCQM`#2T3$Ev}y%1sJ6B?iC1v) z4DLP&=AV@%QM_fx20ZrkOX^>9(u6G(2ImC}78HV$cb6jrd~|%Q0PXvV-ped= z4^Xz6dJi0nWl$x=%R`Rn3EKn}rR6#_319m5fH#Tqva-BhzUAQ05nnOQMhl1xaGY#T zODhJ31`CqT9{%R@d-Q?Hh@X70fRQfn7h=(3?f;gRM(jUu2;rbRHlaZYY2YIte!sj_q;cTLwVIHUuYvbv^eqF+{&;Sv_!2ZcQ+duH2X>HK za^TtNR_*%4z>ol2BbJQ#$NJxOL`2@3q9Q!@%wF8LdkCHBS|x_&jB0&ywvkIBAtX|h z2&N{G&rBgVIfzwFK{S?T@h7+5EMAGOUt*>$tC3Q+?AT^*Z+>)Dij_hy zZN!jYnjBK=n8=fz-T7b$&%d-AM-CklSv8r?iJQb$mLZGO6-Z;rk|ho?vbOlLrAs8p z#`VVMRorn#RzwyUD>iPVw6T#BlZh;zdh%%;*uPg?7ru5fF@Z0A;jhuYWU1|!YzCtv zl-lO>3Xw23axI-4$oie+*$Im8iGvZxYp?Ie+SRKRr?{4d0y^_FuEo-_QX$N;DtCd} z&N?eR*c#@0GRQLJn_<=EM|!NsrX@+zAjc#f zZbk@Pjc+Bc%=#FJEnyG>A*MWM-Xr+)FYQ5X>jGSMX$$IG%TQcKm~sl)`~=1)WBA%P zPa&D$O!hs9Z>u`gYSlo8&zq@irG~p zQ&ZzsjYyk4gYmHuoITsAWT3Q|haX996v<(wk`X+o*K|4!l2;{o6R=8x8^s7n+{`xh zAq{TIo@$iSM3+w4rxNTdoS-#33Ia6U(vE~*}|Vpb-Pp^-5(wlqqzlPYnnUia?Z zhrZrkT)J)@7A|Q=E__o0WY?ekeX&`&T}i^$ps+@t(HIT`-IVAX042A**#Pf#llAqqF0zw3S(oVc+b0T)LF*F zk5{RtzD^`gqPFt9aV&rC6JBSo7Y0_Y&4&6$96WRgW#v^uLCv0fhW*ciET3T&AJcuL zIUxBkB<`ki8AL)+iJ2Wab{Y@d{~!hiFG$UB;ev%mbQYRGG$@9xo445Ly4p!BRP9Pi z!8en}<=eL-lTJw4H#r@`H^1{;g!2hW535C!&Eq}qx(2(h-KDaF*N3*|{M^$?wncd+ z+ok67cXxG}iz^Z69Fv5IgxM-e%VgVLD#J39Wsb!o5?bTqX7d*e^)L>L5pauz>=L2z zBj~=3X%wFE8J~RADUQUkwjd=_+0Tub?=)-Gp!M-g&eCr#rEk{ja$-!ZteJ898CKF( z#CgakCDOqPkRz8L{qoCbU$YRK)`xMba~P*ik703JIc~VQ1kb)OihJ(k2wMeu&i5dd zw&!OhW)`=OaFK`L8Xnq97q@FfkfJZKVpBEbXJf@QJvo7utJi8GfnT(C<=f>rq$VC5 zW11p4|M{aIix-ee<#5X_*Moh#-#z>U5-EcPcfDmRA|yQJb9njXJs2BL33A@DWu0!% z`3o1Z|MkO?G2XOct&QKvtSy9#y)^VGLrL7kt5_uxEfJ*e%%6NJ$p9RU@;;b6Y&2{m zps|v;#twNfa`CYmjYf;f4nR@d93Oc-$SdjVI)c9Ae?TZSfp|QPiWt$E9HMkZ3+0sv zgdfcFtXgRx#N^PjeIsBIswMo+ zgVbF8vPvQ-OHGKJW<#8anHZ%jVmV&f`XQ7#i4@-+&-r=;i#%X23QYe z+BlcF7xExxJAvfVdqvY9#l`xb zwJMA|;R8MQtEx`wQD|%{pjIP)m&pnr&%|rCkq*%wK9=nm|94-lc_eXSoKqPUPEW)K zVntTHo(@vy1j}UCT9MYH<(ai($CaASVS*N;YiGO&U$}!-^(Lmq_sd>3D^%O?Uh3AK z+sgn819R8SG))YeHl)BMEbey;RUu!(JH zHO&{T?HnnL@x=_1 za9(c)c@_!ubzw58mVqmxee&lKFOd>MHWgwBr|IJGd}jfyq~MQ)k!Fx2AL!-X;Dfy$ zZzS&7Eeek)_=Mae5xzyi_$jiqpT6;ga>tL^a{1K=9QfrW`A9H}q7eH|ggPtnq{w-hjVe&xvm}@ICRQb)5!_E zO5>b<2!O3u$@4~o;JOHfNh&i3GA183I!4C1B?d-*w4WR4 z#ilCUIjgCeaL^`MNRY{c2aSWsLMD=>S!&n_EJ>8)bZB|y_#37!=rd{G%T`=>h=Cvh8N5RxSEdY8#tYay=_3IB>eF8GO10=LDyANR`QHKxT@c@QWjYy?AopG(L z-Fyf=J?9HhwwVaU(IwPPN39(280JY~Cp!qZJoxmhR@Mt8W;LpQ` zNdsG96loH&5Q`N&7x;Qi2-vSK1iO4*&&%lyUlH;C^0V-{Y)@LdlCsrIBA5X1J@9Az zJKv-9@-x;hWAfqu&VMtJpz)I+S|+HDENbt;A$pFFQeY4|_hnB)RH7jCCW9r57on-K z(NtWCuI01%`!9S-Xe+r3=IUnzIxnVVsH>~0bau`p57O>+FH{&yb1mJOo-z?R4|~rd z=DLI3UYnoA+NVCzkP@L&(xc5Vk&%D?_J3i|$tg_c%Mi#UP>LZet>^n8r-Oxy?e+O{ zny`7}M#-VGomE{|t817`rqR{Ytu`l#tQyHBUo2^I_H;NU%H+pZ`CdF1gNdDxsWKvI z36xQ~JYju*aYlkx&{6)~Ttn0N;g9de*)vDQhu{&haM5DfeltNo+i?c#)~uD+2ssFr z=$ZJLZzWR%ZPl8!O0Z9#?!|rg-z|G^BG5E$(=xor!;n?FdaV znf3z3wn#c=tHqPJjg(7eQ;LHbSyt^JiH%tTDo&5cp~h|UEdqWX763$qjRb7PnNO<4 zgYs+Bp+twY|An?+U*5o5a zX;2+FOvE5Wn1>mSLl>xd5Q=HuUcweZ`yf_5@0KL1W_sn4U`O0Old?z;=B;9^~BGgdd4WP>GR2j@2bw8YjAd; zU;K&;qSh=cMJPL8#MPt#03ZNKL_t)7NHBwn5>6M8uRu#{6WgFtBo{Vy7l3w8*YGxGba9+Xh(zL^GnFc^~nl~5l((EL6N3s+40 z9K~ylxMxacGXz+P%TURV(&2@1NaHrhNXL(*6|h^I8lZ?6Aq1~xC^%1eL|W)WC{Tnc z)ZlNv`Ujltt3)~%MDx5BgkZAGtgeWdF@O_hEI^!MWf{E4>qNMb6&DZ4)2Gh}xtmH* z4mpH{3)&=V3P=z~sUI9+5phS63IMyNe62 z%izld!XJJH+gc)NM9NxCiZnDd==)3_SWQxmlA~`tFBsJP=Q0ILYcmwa41AwoYhwoU z_b3AcMtgfZs%xul{ysoG{y0ATq1!~DCp-|is(8JUZvKzA-r~i z1rwJX6z0fipYF|=eA{=X^{b$q=lbWIzWL%5T0jbRX+(lCM2gGs>jxge`3v1f{I#np zxo*lUv-S0%54;a2Pn|+%XBRea-k^lfM9_*9@OTEXoyGe$G%&0^-PGKuGmuH5Xp~u# zFXrPbDl5?6*N;OdkK)fi{14_0fd%vC$;^z2i6sV(fX6);4lBu7v3!NB-S_M{jFYDiSOPwk6w0DABOAbH z|K?9|>4ptpp-c2`YAT`oON39B&P*PrXzn$lM4x915de+_b00|3-AN@oj7oc4oCY@v zYm&$_Q+%GEpq6eC<@zl_vqbNY`2}1HJ}LiW-69M8vwvqcPk}$<{h$39&j&JYi{p>Y z8iVBHl_Wg({S|qQwvgc-F%kn8yr5@}&kJ$^1!3{< zV2`(^rW`llaswu*W6wG>mBy!$F?qmLn&&11#N#Y!-^fzl~TX;KX?VzZ^5JLmKdk}eVQ z6#_XC9N!6sBYF*HuDJ|*`-Ge=sUdMkkfR$pV<6#y#zcVqQdW2jVmuIH(FnS_dr?wS zhW5pa)Lx)aP5)p&?!E6mlvh;YVyx=M#_+HI{Ld(kmg6r!^-;`kZP5YxqaS=9 z9bG+0CZ_SRkMR2yIJoCGNKbU5EKaf=6UKmKP{~t?geZ^9QCJ4Cq$X9k>6qY2tSL<4 zAsfXrHAkzY#20aWLEdtz*V*x788zX4*;R8=ArKK+HP5vbFm}9+Hah=zr#j~$L{7cf zLh|mG*7o8xk_e2fz)gM9&*>Yn(H|THgPbr5$HFKD&3SPNOHsH*vl7NHQBTh*$jM|m zzV*|CcxHbBfk>GS87d=k9Lnayvm(OszW7baO&*IG(xV=3AdJfDDjYm`1S4bPrdI)= zzOG*K$xKweY9N`^*^Gls9kI`EbS5aqwF#ht^1&q~GF;-iY^txrniY$Y4To{|WG9|| z@g;2BxDl`I-KR>7B(CGfPby&Yy>Z9zpeOfWMlFtOl?ad>RB=rxkW`vhLO``pgN{oy z@xZ`g)xDt!21}c@Io~VSp1CZ>3RcekKof65t-o>oE}usvH7Cc+pLwFBIbxbUG2e%O z-2zE05Ksa^RD#dTQBx8*`PvLBY#(JgI_vwSj*Ot>vw%9e$pQxz^AP|4d~pme!@#pt zhza*-DxJWtYp=lO^=oy_7-aa_O)JK#M^$S=4QBBMOxDwJ3ue?6nIzlyZ7{3}!d^rGd-ff~Q&0XuN{OSRgIKzBg<4>9=g&oF zM;AhoJl3zf)QRhv+bGAwd7i4>lx3pMb3cX09{-&Rpjfm_XB79Wkq1M#@$K93&YN!* z*FuSFDx+~p^5}S4jZYb|eR`Un9Yn{u){TS3I7KATqliLWoS>kPcarr*q_kGBxovhfbQuqL zoz2(2QU_{XLj&G={k2%tJ{P?`Jv#I#di31$d-1|cuVZ|A8n?Xry;!-j9r|W_ckm&NRcfJkdBSU!Rh20n$;o{F@=XSO;sF4uB zYX=Tuc!b*9lnC9dvB2(&eK>Qf8`0tjwr<|wnEENX>b}{E?uBt%LOwzY5gwh z$8$1(H`6L7vi{RlPS+wVt*BDcA>$d1a+#P3t5gzYI3>U~27?sgt01z1)8rB0GE&BB z_Vq}#qf(imDr7J+(1mj+UPa%zS5OisMO6exp z7^SN3LNASHr!jY}H4!%TP9_I}_N5SFikaFGr1=mZqy6Ffxk3(H!lCu*rXc*e&F|>2<+xS|lc^vc zd1eg%`OsNpgOyS?oj1Qti7|s2xdn2^%w*+gN`3$j1y-~=90Ea+zq-3GptrYA*Nh4B zk_8Kq%A`eHVgj2=7!jBUsP>~{GW!7O=kZ%wTBR+az{H9@6q4I$>%6%*u>TF*cH3?E z(T{$Fb?esY(B~fFh%dP|Y&nP*Kmt=HD@8D;ip8HF!+{%|7=80d}ZaKVkQIZJ@fbZT6`>@gGmLi zxBne}pNNR(LRf3e0&;RXg|ezT-Et+V&LhG1lzq@PT@V|$Rz>eB0jtW~_h#_~cm~$h z)u60|8WtQc4&aW@|CQV@`5Gj=d670R`|HQ){AFYu83o8F&*&Wpe209m1TZ2DHwZi^`fBC2*X~ z>NtB=>3sM3ZjII6@ppfN@v%wW114Qc+KOz%kq9cUneGGmCkD*vJfe;O+erL;Y6Ijf zIbeZi#Zbm#fwMm6b!SpVG>cU^uK;5UfA@UX0Dk_<|3d#jzqC3yb~|UzT)h|WSSCc5 ztXqv-+Q`kC9CH34LP)Z}#fukYKmOWldl99OmD8ETu_+cXqN4&nC(#?tuEm)VoAM}UMxj;`s<4xyp32K)9M(qb?p>8 z^bd67M?d@-qOlTe+IR_SD$Hc&f!{u=@w}GCI$XMDg_41uo^BjE-eK@uRW&YIvrIxw z2i`a?8BY>))~#Bm-WU^-Lq|>_o95VE5ZkwH(BgP$_dW$IZqO^XZqdR%bmSO1JI*WV z+O+vnjkPg${o%=Hh1^`b>sl;Yv``5IU*}i%{Yuj)pZMe_HKte`FO}ojkz+^kp+EaD zMuvw}IaF1b^CVGWl1$~a`KbRO3DtZSnPdvnlY_W;_6@wb=Qk*hOduN0qc|Eslv2+k z)euQ=x(Y!P$RT+%;#3@^c`k(Ah?pcm8d-~p1?QA`?lI$KGD+F!tdIz`uz2{%;gJU; z*AY#FEOC+%5}(_(3#_-x9<8s+I0a$^ElU`P98h4%5(cj_$Cd@fDe_EMTyo%b;FZ`~ zy=D^CP87w9&Zy5wQk2{@!LZk69r2q z6nv+XNi1n!jAx#HR!KGQ0}tp$3m2oW{{pHcZ|?O6;(~{X9+2#qa`xxE8l_~jld(?H zu|v?v_u;-Mj>R>-!L|#7l;;MB(B=e^7(n>Co*TsX;e&--BE49YlUL?v<$mx^ksNvC zo@ZjfKbZvZIr+Q%oIb%Q^i$MI#8ALCqMf+x;oA(A#mH&JYAeHpFCso zL?O&=R|Qn02w_dxaSEaYwapE9pz<#@7)Q>Jaf?T<{HQZ!RF{WzsY2PV|Lb(;H_s%I;@d6gIm1t3;!g7z$#bs>k?@qYm9_P zeox}W2E93UZZ;6cckeld=Z{8hl0p}iuvQ+|U$+x)9z2XU-aLY->6Ef)X?X{NC@-dK z9r+3iuyE0QoIG_*Gt}8MGrpvHtb(C)z`y?6cM+4wT3%JOX4BaYkf{@00ZB6A-={SK zNo!Hwc=ljTrEyF*gm$PLQIuFrFpJR<5^l1nsjk%f=0QuJ27dk}ixw(TFtj3#XP@7# z@vtqIZ9sWxvD6@6d|{7*;fm$$Xm4Ml%KM>*9x-LEXc2CG*Sk<%Rf%tW^P5O!Legts zWw>SYM$}YQ;7ecr3YAq6E-J#Uw|)TYE?JImfAillJlH4GpsTLE37gifLA<04-~0Zz zaPZ(k#G~c-+s}O-%}tfqvv(gJ`ps_;jhEoPx4jRoEsYXY`Hvrb3z^AIENF@%kQzm- zD38h#s)do{%FYsdl0=y})<~}i%SI_+#j2kui^d-18DS(xC6*$$vRdPql2v*lI=Wnv zj9;m)$&gBO8VEWyP*Y~)MzlVUM4ps=(i7f{cccfW)&bWK35>>)7J9%WQV14dbPb1D z@*r;pYo`@>Guq&eU}WjbjGV1gDf2z!RJIhm4<_)I_)mH31a<9+LsCv*zX& zp-5cY{5QqEmM>k7(;a8^+RNIPig8U8!A}u1H#e)Q=lfH|?yeKt4qT(AV#t7Oa5<}C z>I$%p#Q-mv<8gEEG@S?2eK6e-Len;8$LE$rwbM}XBaKWhyf+75%aasUr4o%vCbi!P z-SW9OtuS})TqPQ8AMj6aE$xY3UP;kAQSyB-v1Ni?QOShJRO!6>qCYsj){9NaxFpd9 zY=5ZF_?FlSri8>L7JNP$m=VtAbu251;Y(lmw5Ep0?_y=k0PQ^k3S0G6!EU3!L z)Nyooxl~ZEKgk8Z!;zyWabaLk3yr8n zs3?kxvI>p!>43=Paq+@MWqTxE@vvLFdOQB)_S+GSQ^ME!Z(P9KaGZNJ=}&%-eYPnK zjtq;7AaM@rh9`I+8X{6J24@G`nIQoH;1* zh!BYhg~U6ccoPMf*bXQzDOZNy)76ck@d?ycS7Gs@CF+Osb3FU}vvQ}r=Gtqp`LZo~ zzd!uJ_e5|juc^h~eeUzJMP+~PgYUhKwF2tuTkv;xd`1c0m%nreLgWM#Me*T}egd_X zrFi7=hq3$l7Zthd>T7WOd#=Z;PyaX46CEPB#>4b9U~7u^nhJ&t-h|!AJm*1WC=?S< z@fV0Hag9i@$)g4~W@eeTC7a?XC;_m^bxvKV=f^%-hU<*gLB!bCPTJH89{N6zJWJ*< z`;R0qa(>xV5@lvbVXc564W2;eHk&H$(T}T1sL9%9xqP_bXw3Qg8P?HXV}ep~qud#~z;a zY3lco31_(mT*AShT*j-uMHqwZ#?*ClaWO z&)48OC+y2afQNl;Z8at*6H07FYIKJ`|KzwAkvM)U9Ep$+vAyNyoAgeYn23z(Dqgl7n6MDN z;Qiyh;;60Z!a%56jJgLDq0_XHeHN`T?NuU$}-uHu3o!La4rwm;-Vs4 z=pDe=*t8DD-rhm=;cj^6F8u7j?vW=sm8}K_22~01Ce+k4eG zduDfLc4m9eW?OorhTaLiN@(X-5s)IH2nt9SrKq6TkIH|J3Q7?~0cldDV?rPV(tF?D z%gpZ1?3Dky@8^AYSO1*jm5}Vt&V1kdJ@qbgt?-J*#P@IOXhZYNIRX*!wfp)y@Z2-c zV&42kIP{1kF*Z7k?)Key;?ajOttx<6-Y7!3A;iL@_Obg7q9DYnf>D0RIW8;Z8iG}_ zO{Dl|23<`E@~kM(iosDSjVEoKWv_;)5j#?rU7d7Hu_7I6&5`5qS@g8^Pnj#RfJqTRigu7z{1^u+}W0wyb;_!;2X z@p}1WuaUs>%n>>F!92H9lfCc6)SOHS_j_s9I)SfT=u2&bv~#%$ymnEu06Mt57$`}?7*F+ z38{vOrN%@dLoF6HHREYL@0+&l#O{_(0S%>RE7@-ANSWLzXTI#CkIl3z6h>3yberKi zS3x#myjJDqmC}x(EVoUYZNh6d#wI?;Soy_^zNo!E3r?OZelJx=S!D2Y`J^bzXbMji z@T^bz8Sv}12620EHgjYRn4uVRM@SQ18_*d3hQLo2(gx7YVcn)3c=hFfNKlN;(8!2U zUR5qTb2q-O3UsX*$!yAD$q7pYGGrWW?`RbRgJw~BmZdUlz-udBOq1n-2kyX(rrEBr z31D<2j-mL7Tx$6~Wne}p-$We6F{;b*ec0<*<729i_RD-Wm;!wQw-NuOGpLe& z#-B<4_XHDRs(*u<9!z-d=uA#3FZvawpGw%7wtx2phl(0~erv`i7&9(6t4P?mVO35S zDG2P?xB*?e)}nRSTExPG2nAUvP)x=Av#mp9vLou9%1~b7lN?Wu8#6-I`}G6AUO-3Z zsqN`;1f@yG+;!Rt(SZO42FLNnvSGZmB8j1-0jWqq;m(hhb9p5Th9(8ZLk>O|3l_~X zFMCSD4h@P1xO008UVZIt(V%#d+S@u5psS}f;HH~y(`PZxwH+)5SUxzfyz(4gd*dyn z$FrDTSC9YtKj)*fV-FsE^hxCBQJF1`OTYAaL?dCewzuN-H{Ml|!>;V2i_SxGEQOa| zdKE)M2_3vEFZ+_FA>6IK{qB2c+0(7@^OcuhtnOy#j$K&w*=mHth4{i3Es)~Qv z^5qy!ByrTyN29!=NE4a(XcC{TUV{^kKS5kz8{vjgLS6mDs4xh=ie=@^eHb`9YG^X)ekpJx4=~qTPE5+|thE`_ z`{NWqKqgHV_`MP2=aE(@?xleurS@pHsKmNxvcNuH+8pCZlcmC7OC?4pO>1II9$d@B z;YYs24wy~s)au`-5bHDzTVslu434%|dFRss0t!=jon3}3OR8$j~ zR)RI3t(fT2IXxo1QZA~*rjSwNrWPFM@;$H_;%;B2TohWO+a=FVzJV1vs%E#y7)$mM zRq8lt@SJ#4-{aXau^^s(Vqf?>-5CA&lmF%m1^>Io*>bmo83OIzjfyg}v7RctMll-5FR(YvkQ#2Kd-xZ)t;Ec(wtt~o} z$)_a%03ZNKL_t(59Ol?=oduDgz3=~nNt!@k^lPa)9CB&HO!C$2J+cc(LsM8 z;gYf#PjV`3@8{@ajzK}RSUxJfJsnE)<0&ec+WJ}zuPgj)A^}`-@!2^0th1f%Gfl+C zF*G!Qo*qt^`MT!sqwkmB27j(Sqgux}V>XK&R*)J!-wFro)QuJ8Wx9DeC-4T|yva>f zd@|R0ap#feM@`_A>CDuXhc5{J^Y2s?IL#uD-I%&+@XspWvoHypHm=sY_7#LiAL$gf zZCH(-)(z-x*^Ee_PpEWr6QmD!79q*>5{+q6y@qt>jb-N?6uyBVLM9v)6|^kYXx{cm zW*S8KFpl6Ih$xdrd-o_l+7!T}FSa3*SBy9{3dU17|G&<|2k*XzuI@gKfe4-{2oafW zqtGQwjz>>#H@Z5z@X4xAux;C3b<-UA68+uSFdG+Le33dyc9<+sNS|bM3*`sUvS$mH zFaJbLf&KU2SG#`#{$6?IHNDq^79W7B>T-d})~{cSm7lEF;XYx>@o1hg9b30-!CP;= zFS_HrxwCM}NyqB}+p=Y&*cKcq*H%x%<(FR~x#!>g?qR7$a;kFctv90pwLnV0th5k+ z`r~8RylK0-o@0+a4qy1kmt{#?*DxFR-E)UjB)4wfh@brA=SZis`0CfM z#~EiHkHNk{JoVIH@!|51an1!7;`GywLpT&cv>=3M{{FlkvJ1|?KmtiL7}>dFha^uI zAGjZ?s>-!HEiNiiVHGZjpqPe5oM>cCz$QL4sG`d6(s}zbV?)@qZW+3Eeu}~Vy(o&3 z#bMK>0-g^FN9cUyw4NZTFifDVCR3DOCab|rzyx|EkWo_?vnCc3LPZ46jyY2Dp_A*G zI(+V&sS?TaW#(iw(DGnM0t~s{VxX6gh&bEao3h(5`D;mrJ63}w3>%A1Aj(CgFouZ& zxBlPQ63Jvj04o`YiPoD&JY9hEZdeV3t8~UElL0Ae8Ck?qr@%Bra?)9_=>@53rt9Eo zeuiAOz$f5eD(&{4#D->dhUP6;fSFA*^`41ZXNT9;wntrTX=xcMs%o@OqFBqSk3LjK zZgfOq56sViegwugGTN5bSxVA2rQx5Y-@w8}0JL$vHdPyq<&YSFq zIkC{r)pargKE`4bU}V2$@V|RNB8%KWzO53b788C<%UePNAYOh-CmVp3`{)6EZYJd! zGw0gc$c1U`v3;LDQ62aR(qy?{!E+KTprG$j;||}z!^HSWoQIt=0s-@I{dHHOqAY5{ zQCXVHjS8G641h~;{w&FX&kNePM9!vx1rL*SIz^YyA@g?$7buZ-_fWaAOfIP&C*r$D zP8;a^vU$q}J3_Y-DD#WjVK9FBxcRI-N)!^S&zQ9&4}a=BNAc-oE2SCpfv(?LIH&HxmU^|ToBag zQievtJ8);__R{PswXWbUh)KY_4gABHNMz7IG>*3303Q5X3)+ThV#ED5JH;FZhpDHK z5l6PBnjKkC1~=!PcRE&lxEyV5?Xu>5u?M;vh^rZ+TcJZ72`dE&cj ztd$&*ZU6%y*9gQUq%s*K=_RgRwgqa9ltmdaIbrKAEbMR>PLLS`FDZ^>X4rul#k=o) zh|HwyyN7fw4?bcE?z!tG zC5{`fzaCqp^p}ULzi~Z|KKdYR-?|0&-gCd+@#@yA!_}X;U_=-p{^4X`kJ+C@ybj8!0dVRu=MQHF&6K_iuayFynidAc`1bR z(ah6#xO~+h#+W*s~0}_#%wU)o-rf%evCO`$-&kMzGJt*If+5ZWH=J# znulLTZ3ZUp2$o*=9!3Il1)4RpDWh<*sN-~rpM@(2CKF9|WPZfSlX;BzU%bwIZQ)?J zgAW&2LGDH_b#)DBY@DIjX17J4) zf3;naQ^cG6v&%UX%5zhJV17*@%(Qf1ENOWMM}Kx`JjCQo>;xO7lTSPxM<02x46vfn zLTRx`O;dYpEBq#kPJIS%PUeM=#xz1X>XrxF$$ z3sRm5OdLs!qO-FbZ@vAx=y?m~&C?2<o+Nm|LpM@tm8d=Tw?E3voP#A>!vg#)8DnwHep*JE&K1j9o;GI-)O=;&-Q z{L>UyM8T?wA&Z3Y!ynv^>gqa&OUO!iY2_!Mpti0?Y%#_XuD^ZaWgPO_1fDhIuY;{i z|NWZy$&?xpHmjPz*ec624)`qjiGZIVX#MCWUsE*?H1YB{FIUW3-2C^Vz`yo?PAw)d z3=`1@Hc8mL=~Ff&5+5>mMRTF!jz!}U2ilT6Gm_Y_@;wZ8Z$Z3o3&O!sC4XR44+19( zlny2Wo^FB#VfqY^^2dUM7>2Yk4BTNe84yRr?oY^e7wpsN9D4eOk zy!8^6y}wGzeAiz44c*@l-v1{a{=*Z96~%DPb=PTn(%apEZ(eg9QrQ%mXUxSffB8#{ zBnI*M^Ut+|mKVaWe)Ah80p90JFTE52KB)Qmc;F{LLs4M?zWJ?dFg`Yd=DK1Wf8=5e zc5Oy5Hy|UKaG2PH913H!N6w%q#$9Aq`!JrPppyn?T;kWVOVMh9fJdDX4{$U}r3|Db z$Ye>_7&f*Rk^TY!vMffmdf=bK4lwH<&vU_Q88bO>oW!*j~5_1o^{T_3bA+3P8@ppQOIU}Gcu`6s0PW2nc2^_#4@SaXLnjLS5qe&7h7j%=1Pi} zxeOL9T&Qy)CR8>nTlX{1I7Z*gRSb)R(Xo`08}EUd4u`_`I2it?VQDzxrcE*35R=$% zzeV`#UtY%AP1|tz5r@cT`NbDru=g1ZqQ9>n$1UORJ%PiII6~`Lf(&1Mp??p6=FP3YR;UEcZfF5MiceLfg_?$NVAKr zmQHI8y<^8t>}lDH{=Qz*E=Z=4T1EyQwszq2Hl?ZX1+0AzTYvZ>#;+Ot*Z3yE|M%p% zwkly_-LQG{Y85#Ir4Wq4hu+lkxRYYXV}d{N_>fgNlDGx3$vC#I{Q!L(>w(dBg!6`t z;-#%P9D!lRf z8^{YrR3uz`?bon-&sO~5fBz`^Y!)S7zvfCkung2sJo%IWX}N3=pIdq=3Jb&daK$QY z+qz4I(9)%6qr9vLq5Lqm@7RG?-*{VE@mF7MScK8h1pf7}mFVc`#^qOBiRsg-P*@y8 zS62@@yLwPpH(e6cObmSBwr<^q%9?4YtE({^_yE}n)#_deQX3x|RVPXmJkh$*SOopO zeWKbi0OWCxOz@}xXE}6t(O8Ptk)uCT{7R15h&xso!EirUHa%#bJrC(5jc|(a?%QwR z?RP%FWmjCKZl4FXAX;Q<}aL&Z{K)>tJ7?#s2Fm6{*^D8s4b;TzXqL^^ zVmqLaD7_rH%IpL$e7F@TDnfpw28SIq7vX3Mr!Rd9!^340MF7<@y{aU^coOwux698U z-FHh!-d36SmJ>JujHq`J2w?vFMFPzA_4S~CpkL2KZFP+t5_!$U&T%%$oEEHFxzfOW zr0{}jkkJV$8CO8Wsql9Oc;OVnZW^Nw(ddvYa*2qqtF0A7LM({*u+!Zq-HagKJlUp8 zi=)sA5Yt<6cnXL9rmh5Ii`FjbNo7XA7v))Hk>iD!eDLJ6$mCXCS*7QFI3CyMB7=i& znEVV~UEOFV_)J6w+r#=*foB!?L^lCe^!s981PajSSWB*2@KaB}dC*iKo0HWx6*##T zAq{cSg4tO5xsy~7Yr=tmu>&0S&v(a+OZFOkCQX@>RBAGm3Jar{IctW1%mYKCxcVD6 zW9j)z(cjZ6x;O32bqaI9KKt&gMuwtU1T@p1X5IQVm|oYQ=_ubfVvZ%*#z0Jrz`7N8)%yVX`~KKWhq+HE}ntq0-5; zv?G{QdwaSuI5dFHu5N7Gwnv|jvip<}9~R(|;99O5GDv4rQgBp3>dw9Ko9c&SPRcRoAaLOySa44mw*COoSkwBpK&6+ZWz zwoC=&`l*Ys4Q?{vU*As#G(~Yyi{ES0ok6*I?Pto-(o80oN!be_S@?F{9K~|RN3eRutH>m_Bb(?%B!5J&A?aQPcmmSW zh!E2tTtmLVZmdpOByb85Br`(eV|(3^G4jU^%*6sLnJU50{aYU0oxL07XA|2)RDt#Szz>-;+yAB6oUS6Fz^@=XDK+2Yd1G!+%mj zAh&kjyjcnY+jnljzusRZ;MmL=jaay7E{2Eu@xi}75w(!r^%Pmd$o8QKsZF^B!GabMF&HciHw6?Y2=fC)!Mr+@?{%XVsY%D28M^^_{ zf4T|HGa4~_P7`&6Ff`nc!J&jEMYUDs3NqB0XMjtlC`gi(cu8t(1Z8Cvh{jC*Rw7hZ zo|{#6Bp)N}n%wx7dJ|HL3`a09*e@isx)Sbag9H-|qoZRxcC2{^$#@qcVWRWtFqlPQ zm{TaO8>q9uLe`8enNe_%WvLvQz>uq)DhkCN(WU@bompA0aDa_6(eAi{#DsIWvq-HfA> zm^pKn43wya&#x&eDMn>QrN-2LT46xKtR$H?u3nA&NJQY@uC6Wt7p-f{DcQ?dM=FL% zC3b-pT|nd4a->gD9n#$f1_q_r$SHxX+NcR)iG_h$)VvT;|K&PAQ}qm(NShiO)d3RI z;gi1S%kvrL>oFnt#K52Fjhm?C$KrtrfZabQY01=>*%&7+5%XtORZbIf-!nocN2)g3 z_q*H)6~@UKkqhwFjhW^P0l$V#v4X>BcRW+nbeTD`8MQUFhz}3yIhxT_hx3-6YLe_k zsEbWP^**ES8Q7I?!RT_5uO6rH+L#2m z+J4=pM7ADC+qR^c`cDtOIloiwVJ%c|#@htL7W}vTiBidSbpuVvVEp09GH(-1p zPQ`G*={I2OyT6f|YiV(z)J9oY9DmHQIO*gQObgF3K5g3NCqKMK)|K;p^LkHUI%MoO zuEeVME5?vDvm^1OCc+&Zo#^cD#&CQ{pjlxva>N3q(B0Lp`^o~A&;7(`UclrGeste= zQC(T5>%fiBaC`(^?d^!gIK9d$#(6O*TNjz=pNK2Y55$r_Rd5OFwzaF|!B2CVgZ2fmQ$HTxNz{)lwy@i5E0MSrXg^5CRAcxdgTEIo4(gctT7U9)*d-3u|aSUh7nNA=X zbzebs)1vH1Kis(12OqpxNLEq@`70DOdKs%o<~xqIqXmWP#;R*-Wg%M>D>8s3th^O3P6W;V~1^PoVP!92Y8ujM+_=bU{8a`Ys~3*a9w zy{rzfxp_90EICFG>eEmE6?^w~2*JH{=~5hZ73edX(xB=ckV$uEA6rluNX#L7gsdjoDy4%_`mQ>+T5Ji9AAR-g zX(N(D!{}#Xc49;voBC-56EHRD`8xf51G29s_>YO3Nt`2dCUm|w>9+jdqT)hR+KXDJ z%-3M?!WDr>z4MtG8XAW ziWnF`b5j%ATHBoJVMt;;OdNd8n(FD2EH;eo9vGMI(pmv>;52}7t>*`;{g9&b= zD@N^Wtws{x@#I&Tz08qpH?Lf1HfYJvA;f#bn!kI zYTtqM;1(78q_I-FLlcxh01Fo%iS0Yu(7AK1is%w*YH$TsS%sdiE|iy5;D#G+KrCvj zBNYUmaWH|^ur-9&ikPaS!1u(@$Fry5MGz_ySg6n=qOZSSbj94bsXj7cbMnf2#c4D@ zI}@`tkQwKK7{Jn{C*j<4&lOvOlP;dAY|5;oiR<9sc|fRj`Of%G69mURn&Qvk8vtV} zSs~Au%VOFyOS~q+#F}7&4PniT&((gqFm-@|I$5YMJy#Q04lY~(fILqlB%mO6A$V{u>tH5?lk zptRWB?3kojfl~>utfbr|kBJ9C07b=RN*omYXl$B=_`m>0sTDq!6r%jam!8AyS+jBE z5l4x;+t6HxJ8!uYeFI~-=;Hsv;>C*;=m+}x@ts@l)B!wZ$+0-))YDN_QH*bX^BN>a zGAJxA#dq(y2ZgZ^UVQ#}{QcP%bpH=N>^NL~&828-X~Atbe@6*6mCM7=e)?kpqgJn8 zj{ClUKf?J1D6Fo#cWDQ&lN-y0t6cLQnfzL_kVs8b#3n3MdU8ro=2%9Qerq3rn6EGG=5nkRI*-o+`A>+Z1D|z;aJ~w4gV?t24#F!=?plJI=v))zZu2Dn241(xFmmW{J zUcmU!O2{&ZVwFFJjl0sg^MBUi$}0}U$xG_6Y*j1nyn74o|KSg?b=xj=<2BQ2@W(&? z8J~UnnK;}$Ka#Q*fRjL73+PNjq#IV%RH`%cdiU(4r`Oj@3c9?aLQEF9lX8kcRPn^R zqCkmr#fs$;M6)16r@t!n_xCw|bXpT2o)!MPx!NTJfTKwd0~((jY9?6YK%pY8A%~^U z&(S_*o*5rVzbq#pZgf<6m8&;ipU!T|)z(aa*0@6OPLCc_;B^rguvLUOOK7i~z}RHm z{hajs2L}fAoDq=6XNb=j*&DouOp>IS{~g*WH0+E~lM5&p$O$PB{J~j3!4^WW4&yt2!?%K6xK`rp~|M zTr~xSMFmJDtsyicJ|;%eV2dyu=YBrna2Hmb2x~#F4qApMQ#kH~<1npink8ab;Q)m3 z^!qK?x@H+Lv=Ifd0u>$R`fEVO#-;{cBdUseiX=aq)C`K^$Sx0TFOkVQ^b7$kMr6=Qn{SL6aK^uXtPTYO(k8u4BS0NZMEQa(NrWh*u zRlsD@HpN80M)Nuy=5A}4H5Oj{UFX~3UVP%Va@5Y+BwoYTFP=T(L5vdsN4J*ng^8ME z2afcZAKysmx;eOkgymdJ6L9gf&sOG`*f=h;F2*htKM?6-@620W|+o(7a(ww`$001BW zNkl?~GA%Jr>pOkbLjH!2$W$t4kW>NRy+(Vkt9Hzkt&c7Fi`F<>uB`7&Ehz zf(SNk+$!ft-u#ioFrq~TNQ|Zg?2=GcAcqg$c^3^cXDaBkYbC(&&O7fGqW;^r-iE}` zppr;WM+@$~=lf`AXvP;Vx>$bl>C_1R?}NWaUMP&R$_iX@*;g<$FpQz$KK%CAzf`B2 z7>(omcRzq!AdOpZyGgzgJX>GB^iot+)gZu0RBjBPe)I-<_I`+1lxv7A%8Lukkuu*p zX`aD?uwz4L~jcEC(R+_4iE!_@>eJg8&B-$@1K>cN{n@p-X^ zz`&aPcYd8;udsQM%bxRv@X3^coo8JlQ^Y|~cx+@$#SRNVuY%z5_Ux8zOgsrp6xTgt z`W@C48eHt(iUVh>D`Bq*VVZpO^w2SJ7nUwP4+8^3#?L=;F-|=GFr72)oSj20pIhIo z@cQr>;3|mg%G#P5C2ynr8Ww`zr^YKk9~WQx4Fsc6L<=Z{woB`(|8wEzP5OB(jt`fu z&`08`fdv3R$LG#D6KmFNP~m2Kek&j}Wr~EHPlDkPwDuu=(INhA6&(_Auc#!3lTJ8A z>s>46^6=nqe~-QG9VjZKqGJ@>wrz9ln4EG1F%Z0W#KsV(;{7*>r%0x)@tHe&wip(i zK8P_hmPA!$C2qg{)+u07@5f@#ub(FP1UVH0pu8hvCdyWK%lxlzUvl5mcHj9d*z|@1N#i*D(EV}kHQ#XHVq0U}ap%3b`KIffJ$z0LsyH?i4vN;8 zPGS;_z2K(+#(wb4tF6a^=zaKt#Q*LK0-mG)EE4oJ z&Vxf|-|3pDNcdp+J2puWH6@~|SCW`+-_IB0o0^cOb+Wbs*|;@@uUrI_B45z~OeSui z0xr3+DU_EMV$HIrkQ-Qmg8bwJ-Ady+5>`2O!#BNeJZI985@a~7h$aRyF0n_)>UW57xaYrAa6-IAwA6BebW0JF>5U#uaIypMtd;j;58Mi?4 zrHj6(?_pf|%Tv$TPB)#wSFX4mg|R$U>Q6lJwCs?-_=PWEW@EkF9N&KX9lZO&$2j8X zWAXK?uTW=JJ8e4t{MeJ2RzDN7XHUnxxeL%(H%$qO4{!w=>>w7A63=xK`CF!)1bN_J%AyL0EC7#r2fprN5& zB1(LSNz0?Haal>B#*GXH6oz8q79SeG@K78jr4`b}An24kS?=74tB}m~XhI|UP}m#- ziRfRqcD4Su zEPsA3h??43aj+R^nwslz&=P{^<1Zd>*Xe)&xj3&km z1WI}5SPXsry(lX&r$_S8S;&?Y7Yo2h428_Qq{?cO4T9x3ZBUZRq*N^M^D=fYnVajW zc}Dn{W751vYva_RrDYH58yd6<5r9#?3{>}v3LnAFoEQo=6P#iYb5UDchk^nYKfH$w zM7F+Chvt;=tdg3XHu_bA=bxKfp3y&rk#ZAM>&C5^U{}r64-=i%W9e~x?W-4|wz}LE zr6z?dN$zA)_mFElcIf?sLuhPhFc(!nL6DvV8DKW?;`;ZSVXh%kl&7>x@}*Fg6m$&Ru&HCyI(VRiY_ZiCAeoPqBi0+;;mNniR9Cvy}_YzalDB zy>|*_?a89?Vtp*a~x@3EMn*`o?J~&PA69K+H z@8iOKX5sc*ZlDB;xyR-*=;`ehTSk+1Q9upU%QIzu6_f6?ysiRUPssY4ZVO+`Rx6BQ z1ofJ-qE=vT_2ZvmU))Z`4cLjbUsH<{4`h_owWH}z1u04@-{o7sl8|)16j$BPmNi2J zhaPbp0xLdVrc)5inZgzo4Eb=A_90*Ute2~u)V%kA3I+)O5c|LLTIwDE!#78sGXn$P zK{OJ<+wZ)BkN@==7S9Ucz`5LI8hYH*i6kl!2%xwygOb9C5{yvwdZ>fo`oRu}QQ(Hg zitww)cVZAtsGmLyx7~3&x_jD1txArLqP?pHyS8sfdq)S7qgN|!m@|0d@n}baeFTUz<3HiAEvP*Q>|NGa!K~A>XA$gZYFba!{)XC8Wjw=_^ z^Z31VCuGCVed+Mvkdixtho^;c?>{y=jx}r6s36D-j$^oU2f~?FaR3xs z%%?F~UOf9C=m8#2`IeRu{G}EHm#>4aj;i}HN>P>VlTpvUW z@yUv1;_90zlbJAi%XbD@VoI3QSp=4p8i%cabE)Lva1W$S z5=_Y{g$#pe2qn`i8*|6w^phymNZ6>zb{|aFz$Oatsgt`T-0L^yqo?AT@hmaXnK^bY!ILvkzTm&F0&RD+|^H zb~Aaa&=WW_gohq^7F)J&7lVm_P}0mBW;9QLEPJ|p(AC+l_ukapjIguvUbAi;8m8A{ zG-cC978Lwhg+-j^(MfVl#Vy}E*#@m0?Z%{W=9mi4xhzgRolDQ721;w1&ZKRmY3k(?|e&MIEH@%`UeJ7XbEiUid|t$++N@3 zKchTab7^N_^1OL0iWh=o!9IamnBuSCn{K_PqdZ#iZw0h+uRGUvj%`9>t3KjT2UAiCb{O1QW&a?TL zGZ^^kf`6l)TERES;KhLd^wZB^&8I7*Wj;0*M`bLIvyQ1nb!pt_iMc5Nqacfle3TZa z1vO{aCzZ!M;vYDE<^DH=vGE{!h6?fE)15f{? zQGGJ0LPQl9@{rDPT4EqL?q4}o@fzS>sDl+U_pt2XNC9Nx3x#4v(aR(DfNO>z;v=K7 zb!C8Jr^C*6&6?HNv9}B7oPCzMNG6_+wq1DqvA?3OzDb~+y1Ho?85zL0zkRF5bo=hN zAAWe>kFa{}Y8-Un{`lNk=ji5D)YjwCM;<|Td<$A ze*X(uLqGe>-|_U5&mor|!mob&b5xakZls;v>_kuZJpS%a~F;};t=fFxkIZFcDDTY?!F$OxCfiVCu5+qMGH@Gy!9c8n36$3lS;sV1_d(Ot-<1on572sf0u z^f|QiCpd~iU!G2BMrA&68UWQK#6_ocMJW|StlMzX&!T3M#bTDY{2#}|ZQTi6^P?7I z@(MIHSTJV+o_qc!SilQ;+cVR(493}j(|BNE;De^RNXL+pf}_{0Pn#-UNm;3_ z!A1yxEYR~Qqbj$y=#}I!n!-TRIR|#+lqD;@1yigGsyJX#xNG+=RM(i=Bx4y1 zt^BYtCVY_P^QsQesz2-B++;y&ms07pF3az#^(C@2r%07)r|{?VvslL*Momo#esI@q z=z8ZwVKQD~Yq1L@?L1d~>+`V4dD&egNW_@<6N6xJF_G`_5PgD_rkH83}*4FEQhj+QY=1je;j_)QTW~+cOe=Ji#ked4DTDCtH$Z|*xS;g#7a@Bo4)-` z6huqZ{nIFq_fB{hSA?37Rss=f&QM7=Lkj7L3Rvn)kdf2fLy9ot{)n0uehvTUn_Es3 zRFt`ik}m)WOeDDdJGXrk^B2sQYAAm&nGz!jD{ckkHyppSrMIHfCvgAgiG=RDf2})Q zVZq!>?H<0i&!7JLCeGuO0>H0a`1^lqB}`1hy#B`&K_w5MW zk_aL~&EH%Q!|^c;jRY~4EyI?UQXF&MEkMvJECF2vzDXl7LP_B?c5L5_r=NZn!-EM_ zR+LMVfVX#Ga2T65Zb4~9Ddx>FWibJK5WwD+cJ19s_af4qK}Y`!Mf8vg zw8d(eVoFk0D>9*&b!#@@z=IA$d1X1u%S%NQeB#fK^ ztHOonUx4960<-7sgFA1(Mcu8`)0_e#lhvoI*GzEy`5srUT!qG_TFhOr2>HRVd>Dcl zL26((y7#U`X)J|UguqvzfJ^~WYGrFpYO3jX7@d-xnkyVs+;I%d;fzfd0zsP4*jhp3 zWGCQcej|Jho(P(gaWw1%b!6ZrQs$)MTELLuH$Jc&8#|j+jKvDWIODX_F`6*~C?7GNjF^HWq*D#iiVPYO7$gCT&IU&CO+=a~RA23;l#qs5t|v*(Gk zqi2%mvq{VhyMBHxlO~^au0IIAWFgHWhHEE&Eq^A1qdKzDB&utwFgVQM&b3rjzjKA4 znB;c40#HT@oeX16?W;gH4P=j`1qq$IQi5Q#Nvv@im?9y3sF*Bf!_WR{Oxa# z%TFUQJfw4f!wuiU^UuACuI^U+~Ch$2lcpavhg@D&IRP zqV(tCJ)__JhiFzXUi9uYDV3Q!R8KU=>Eawv{wQB)8yIud#Cc{DjmVjM+CX38;Mb{uBxdz}0Lc<6a` zd0rvKDZ%=U>#^*Esla?rsaP-PRo6Y8-xVS+21Y8?XtAKl3Vheiv`jj+i z1DqI1qHcPP0Fk{tz3MOsfQv*!D2zogIyR2d5|d~pU5efGo?Uw|y{Q4acJ4+)eZ4wT zj*bapD=8{PHjt09vSM_1wj()8J!~7VlO{U7t_CkW_jkPc=9~D^#b3t!g^RS)e(lA7 z;H|g*iEuQEuU&Jk9&%1_{`R-WuyMmi?Vhjw*0%-9TE6^ky!^sT$OUt#sI0*a-?|Y) z!*OZ7i*GK&t$e)t+Uwdmi>?McKQ*;gIPB0PZJ+AIj#yZ5Z8Dzd!f5|?v~K?wDvI+^ z7-lia=>Zc+5FxD_$lK@Gma8{6IHzC)+2y0Py+faUZ%d~DWKH!o z_~$$CD3BEu7Hb`0E1z*mk;@oqcu)n(K?fbG>%ixd#e;a*`G#y4{m}Ui_&xBtHJ>Sn z@LW-z;-&m<;+(*<@| ze0@$r1iH+y+Z&c4(O`T)iJLeO0xp@@IH6#WXF}ooV3FemYs5C-dND639=u}5*cd96 z@RG=;$5m)i5}C?}dy87D_frv&orXNh_&{u1E$& zH{SZ-6P+spQ~3c%?W1^>XnpK@^Qmz$f|k84DzK=0$N@%Wbv3TK>ME^V*L=EK)L}Y6 z@_RJF6&RLw=G0_JWAoN+*s*grnj7m?cpY=}5$NsdM>3PdDJP$X@7{SIs;djJd-q<1 zLP5-)wE&}IBLWH%^K{3pH{ySP_c*dadi_Ln-)1&7V(a#u24o*k85lj676yV$oAR$UWmO@`|r*fcCDDC-?K1w!=`ub_O^`>j|epEaJfWF>A zeXeoos~9W7|MG=`UuF66zgPF1z{Su`o2y;NV$n2PlSsGTa+c0oSvd8@sRf76%lzGp z>`bP>=W5@$`+~(|BYe@o$sUVMvMl&_yw_x>c}e^I4_u7E^5x65ZV)ggWJ+v$h{%m~ zA|Srf_B)WNx(bFuW;JC19y!IiJq+Iv4=-^5k38}yh6ei(AC2oq^EK&Rkfp6@k~`=z zq((+jR4{@ImegW?Gaoh^^%-cA)e(InfRaM%09i>TMuJF;1rg8A#XcuogRyagUieDO z^Sc>5cmZB}^(B0=@>9&2GZ)ipD$(29j%{1FVdd(L((7J0Z;t4W3>F+uZP>U~UCQ)n zHR^&%p;^9iwJKn8dbv+z0%ibz>E&0%wJ$EM#Dy3B7aALC@Y@F;#Nfb?-v7P_?2pf# zeY!@z_uhNI5)*^;jo-cvjSba!=9#DQ{s$judUEo~XX5mQ_o=Mj@>xmz(a7s1!sw3RyVC0+)F<9!s|Hcb`v5Ijv#@K z&JIcQQofYv@SMBVorSMf^WEef&oeJhPHPdt!II?ANU?M&vqEoJ2zZMyX zvhM8Z!chMZDyu7S_~A#J{db5fCsOjF>ZbXtqN)PDogL_D*?@tz)rj}3M|p7;u?Xdj zNtI=XZN4IAVNLKMA3iG#Bo*$gta;8@k*mXxMuaveGeTCd!Z6r5(>g-DNd_;|UeE(8 z4m3NS9NzzI1V4DB73pjQx$zW21qEnsZWO-bki!pGu|_H@i-FRTGI@|Z`NUK5CXv>C zK}21qnK2RkN$fxbiw{1;>E+w>k7q)=S>Y+{ndWCRP~s3au3w|`MvMXR4aFrT_MEs~ zG_R!zBo&+Ds&FC%J+d%oVrHjbjn0lvQ7j7yHcQZ4s7Q&B&l;}5arcP)3bAh}x9kRsZR|{UD)i*xW$M8X1V_pS$;w$=Xbe+xN zh$9b@O*9KAx%4>~K>bXug^UvEJrY=K_4V|cVHrI=+*)FyilMH5ID}j7xF0iS&oj(e z%Ew&daEyV%0?UgK@m{sHx1puAP2F=rER3&wg&13d`YkDe#W`i;Gs0M%7)>CPOk-eZ0P(Rgj1ZSF zI*QTpF`CIB$)?1aGWGVfX;Q#@#$wATvQ{*)DE`5{x1zDW-fXmUEbihM9by z@=OSuY^|zy$MaRCZOC~RLg{o8U7ejW#M!%NI|c{)L|@c{rq6FHHsl2?zl)4<@de_c9N|G&p!JMHII1wn%{nNU%j$<#ne2c^QJ$1QLIL0yGlkPHcv8P{%)NO|EM zEJ-WL1h_LbTV$#*c6N>`u|D+N4m|l!j>DrENsg9I9%k;r#Qzh%H;z zqr0mEt5$uA*4Az`H8x@>KBUC!yI$=<(-|Cn>~ZernB=geZRt}_o;(XR;sk`K&PuMf zt!?i_a%Jc3SB8FU$!CK}l%I!zms2ekdH|_FR=-?(`9!VtfMSJd{o8txlLi6+E z0^bW)WGqq`fLPSA@L+Mm-!;983)S9<5#+8-n9h zu2VGHcW#>e9yTZ(Uo!@AT1FNGJyVEJkYud`b4^`02+%0a1UFcmBDQ2SR}VZhCIZhO z_udAC)<&@LQQiWyEG;(ZOec1>vesR~dFIla;pw<7~0I;S9=3%LOXrB%`FPOn_Ai z&oQR5Y3uIkvTLu2EaPGZT|M0h1tWOx{dW|TxrU|Y2fs&DdV;sx+fiIrfh(`L2nBgj z?AW_k!11oWK14$yb@fc@{JEpaghcF`n;Y=aiceHrPM=n%>#}S29?Y9F2h-~6aKQ!t z<*3@6;5q8C)Gh-PP3oA7@x1RWHW|+;gHN1Kd}IhCV^(O7CPuV!B^}c1RY<0~r_))n z+XT^=1*ZGM`+LE8r{lbH&o-%ON7bc&NH)U)#aMk)*A2cPut~g~8$VgFZr?T4YQ7BM zI62X>v*N#g>h$10*BBoAIqM((!K%e<4_VXz$=gvQ0cYhWM z%a$$62@&n42=-=7|A0Y{R2UPlFxM_~%`+aQD37Uejf;xQ2;6a_4$af-0_@nf6)*qe z1q>0ClFg_a;ka0y=dAV!`f&R9x~Q2fN{V6{J5?5Cuy}4U7R@U`i~zNenQyQnCrElU z$^BCpg%yi%*jd+LB#}ZeWV+a-?JW$$!p+Ign325jFhKLl22cbjc-` z$>EJoa~n2)iu-@?3rX{S^_uI@&{T^V4bySu#g_?p5G^gk{SVwPk-~RT0kRQk*R9KFm{`@|TYYCFN{Oy0EySoSHUw9Fk8tO2f z9F^XKf_idH=W5ILZBo)>2gFN5v7x3JjX3JaV^pBghl7PGuWNB}sqPie4*!nblXqMb zQa>6+b!8clNuXuNN7%9EZ4?IjP+Z8bXF{dk0`0;%9pDa_T?7G;&VHJ^eq@jzW&k%~ zC(pjopQ)>$htLqj27a?3Lv_x)aIuQg(eZKo?9mSVYZITFu-F0|Q#RE%2!lY60czv_ z{tv&GbS~K>{k>FFY(glKk3@V_s|22H74%u)z=IE&kUG|c!;P<*jQRXYh)IbogzZ~4 zqr0bD=yG<}JhPkxkQu;a!aXztKCu_ZTJpBe!3mawIt>S|B5;?_@FW`BMx2TrDjvM& zOI*S_?D)BE(0k)&kV2y+H(o6HtmMo(n7>q91c9NU_{7eg$&Z=|oJ{%gE0ZgqZB8mg z|8&XUPb=6V+hio5&zLV-weQ*jMrm`ueDGDl=LL)$dfWm$gSg#WKKs1ioT3T@?PR~t zJmVysbH+*Xws3^TDape|$R_1&KbSN|0yP=>d^c$c%F)K1-^@SXT8965_%R%`|ADBk zt+w@3L4lecCPc;^zDJv+&>zEg_8lD^*tv6u;`y|iT3xro!eTVeXwYsKU;%&h5)Z6n;j`5k`9_0cPxhyjEp2zj1bR7=1^M21PfLI zI5~YV3wag~i4jhHtytr=HHsqFU;)%mFTr>2yb&cu#E7wB2x?N59yfV*HpO;-Cs_`r zC*j1foUell0qWosMlG*6D|W5Ko%!0-0>Kv>DjXffdJ-EmS(s=N<>`>_&%Ou{?!XoG zUX01>CGh)rCL-aeR`S;KTAn{}@gWF&_~G&#_0O|(uycMl{6}_brrm7`lii3YQLZY| zL1b{rWHpX7jDhXNIGJEK&tUk6-#@5z!)S6`K}x>rTrH3`;vP=@JfbZ{|1pyp77lbs zWOZ}e>BnLI>}lxl-mT=7Oc)S_>T~sT_QUK&hta}F`ymEIc0jy=3{Ilm(AG2Gc(#Ub zurWVx6}#2Jfqry$cc8bcT?G$Et`vpQLo4SujDLYLXBjzh^V_E?aY`Ed{}*M) zb@Ff!VNL2Q{W zI8nimDV8C007gmL`fM?XhtaWTI4-8<0R(~kT=9_B7O5Ep&%3z8nDS|tPC-~d%Q z^Raf#S_L)kI61yuzizFVA7`I?9(L{8qf@MD77sU3( zPd)i(tXf8j!{!bV0CDu$;1l6QmKVe;H>-ndTB z9TOeb0M%7h6P-5$CC?;_RVG^lMp^-&u_zOmdwy8_dVn0kVZPX4lH%78lfY|c&xREa zG71U?74&&uIJ)N7@t!c@^Rx2&)8&#BMRu`#FFX^TS;epAn#AaOrmROpI!QM>Yz4no zEGid6_};ed*e)CduOB}MlURL2qv))n6*?$wkLOIsk^s|~E3}V_eswFb9QY6SaTdt!Bs%FgOePZ!9 z&_5`kZE0C4Dl4mPx)+awl*BEYx8TF&E5v?dKA1CaK2pgMoN>mPx@Vg<@5JuiEb{w> z8DYF*TsN~af{2Yy%x9A8p(m(*TvE(c%c6GJsUV3Lp6(vsT zFcc2ruJ7K6Su1FX>?fbn} zKgV_a>`d&2rgc@LXmBP~Eua>qHuLio=xp3-!cbh_a9_&z!S^Gise-Us-Wp(xBU>^k z!ZK6h;b$<7kP(q@S^)ga{N20xakR^^A0Kvh@BI1XIU7yL^!CS6V`4?LwYI8q^j;VI zxm>$cl1e3{b-q~z3#US@bneY)Z5>fzM`0ZbACY0g@#5yq8!&tJ0*#sZ_Z8I@`0SI9 zv3>h4G&MJ2-+lL20mo7Lt1rEXy81?(aN^0xm*GuHphCNU5YN7)rA5JvptJ6d4)peS zYeahfg`bz!fDi1J#CUe{^tm{ZV7Dr6Fduri|7ESf$&?j(8JSweN{SE;%J=AW)c%TTp-q0~Vbr8rWlB)=K#cn=BOqOJr1qYT`<&mQYTWPep{9U7aO zRIG5XN*X`UB(Jkq4Ae8q&N39jCo5JUF)}K}#b78rp^?u9foEroE~gT+DOR9hfodRH z2zkw-M*%NmiO6^J43ZjeyDo*#uGH?hLMSOQ4TN#S2@o?et)>P&J-sqJVwcaN#M?ku zl$9aj%&XYd(Wr@Q5j7#gu2?eUKHdPGT&VEY4U|ZP~h2h<-98DB-+# z|3!Fj*~h4=tQL?_-IqqnypJKNS{eY&lG@bif>bb_coMG_@0~ieV4hS~@4o9c#KPug z=qClfBed~6);#~rKZ+4j*k zt@X~Kq?R&vdjO-2u5EI`c*vr+tF2AvgoTDLoGBDVF9kB71cEJysL!Esn2*LR@AsJ#6aidw*+*yrsp*81PhX;~FD`j2ybJIu>&y--?HpNA* z+$fbzvpr5esIOyy$)s>s#1ha&H^r%da|iD2=`iQl96`@^KCFP?`A_5WOU}hyVI?7PjRo>DTmUbiiCJXS8S?M{{`Y6_+1k|@5^&F)7ySj{4dA3e zs|(qY24&qmf8Jc2cFIX8t1Q;xrh*@XmGOVa6}XLh#*uJ7%Bm{#-XzKFs!OZaCU-y@ z6{;GX+$Zxha)idj!Z8bro5bi4x;ncsG%$d^zAkikcM9Yp>(UHmUsJ+C@N?Ln$!?s1 zg=~bWAnnk?d|1q%ougN?YBqg*ih!`t;7TH2ou`x#T~d?zPH~aCLz+IR`VIo+#iDy`T2|`h4 zGFmyYIAOxjv}$A+o40IL03o`0-I~>?s-%%k1@=Gi5OoSnFjf#66-mZnD!THW;~v*z zNhM!iCp};S-i;~17II7*p_MlG-f1j*_YL&+b|Bur1NFrT)K{fZTR|1a9CE>ogvMk) zZI6$@Oq?{(-Be&lO&Q1p;ChO>7@R0%oPdh0sWhb-9>+*B4dj>L#s^koPalDUr08?+ zYslilnDPF(V<+XXxTI98D~_ZoHLN6~UE#sVqbGv%K_M%H558RRXwJhkn$3U~)GUNQ zc<*gpBc2tW4Wi>&OzHgPQRr$2#f3$ZR%a0)>)FQ#|k5$P-lcveW8$<$wkavknLXER##Ka^&y8WZOhUY}qCykWOggD42AfrBPEfU$@i|(63(h|q zv*#=_kf~NmEan9rRujv3Lz?}_7(wv#v7pG2=_PRDtRjI7Jm=jbd>L2LTsKez&EfFk z@j=PfvtYEO?eIkb^HHgYqnD(>Cei zHRE&bX`E9Fg?}$hCp8y5h;b@D$QK@bubzcycn9yGY3E96tZt9RbEE$b22os6W)x~h zH&+nxV6d6kv$qwWJLfzEK3x8Oj)#s)RXWVh{?@x`Dfzp~L)Ncugvmq7n<)UJ_KLQn z)2K3)#OtrWjyK|q_*SOS;N$ue@t#cj>79&iIUR=qK>Uh`$wjAZ^gUWr} zzmiYeCI5#0-Yz7D;usk2w_<^liL7-R-bv1nhy31&H_EF{YGmaAP`oKJancQ$oS^U; z_^QrV{=D8wX0bvOj|oLoS+*}iSFevUeU@o{{zawRG&3o(24JQS4>!%;Rd zo|W;8OuZ-&!$U^q0`=jEcs71IMVa`XmAojcJtdIxvvXRp=97;wJQ|nh{P<`>e(|wD zANHLSLSs2O|9QyIG2s{`%7A5dZwX#h(I9MtVH#+MZc30u*;^rPMlJ#L^byFHhis?} zU%Pt+x<;9FP0)tdgZG(C8J-0OPo8fEOTGqKK-?FT+I9Gm$GT3>3SaTviSSn;&Lm;# zc@k^MUzI zWOR>N&~nX0rBq%gf~Oe=1dc2&mO3LROBDFwbEhd23)qn{eEG63;SYa!Ld7DdYFxLj z{_IoCnl%%Zpj3Mzpg6ZeXDNeoV%(zce~X|p%pC2 zmSo8R@tnYN02>EcfH5}4fWy28W6K7NF=1c^oCwAYZ%AViY>dHKa%xFdPOaFvx~r-y z=UY|x&i7mEoLdFod-d6$y1Q=p|Ih!N9oAlZ?PJv`p_Dt|IPBWKL-z#Kjg2R8d*so_ zqOH9p_U_uFam;8=kWjR>v`DYv1uwih_U%KN5{{6|6`*9G0Sai>$_g$uFJyI9fr!o& z%DPL-Ds_RDs48aRJW2uBf9yzdh)G<{C6oHPn)vk(y)TBg4SQN-B`i-r zzmNuYtp;F+?V?+EjpVotWE74m!ypw#bN;`Ogj^QL;z~+%^Ct3@{Re(R<_6{0Z7zjl zw=!{2XhKq4?Ck25{pWXijJ4=?2oOrUrW`lC=*B4g@SYz?C&7$nN5OgQrVLdN^}_|R z{8@AsCBy7or6b}r)lBdAG{)cl_;0H{#t4HYHMtZo3em3T(F9=FUB3Dto2#e-809{$o#_cM(OGMFq6tp=xJdzPj zktwfr7M_GIk|>pkE*iK*pwJY}&5hC1*DERB-o75yy``(K42iWbyNyXC%1mr)lF}Zi z1pxu;&j1<^{_(&TG~s!U^e00Ufn5&CiS?bFoK~&Weeko=<|p!IgJFE(Z19;d-w8yr z#<|NA^^%(9d&!3RJTf34MAg8OQ(>PNYAvXo!u9eDpL^yhJ$s38t**qQ4?iN6w%6VA z`aoJ1BGc&DnCs5WtN?13APBq<4>aO{YV5Ky+t7XFJ-#l&64CyuCgLF>J$CkNw0E?{ zgAd-XjG6!tC;8}Ok4BU(#3j4i;)Pds$IgEC3gssUr6MY(8lGDsJ%*Sh4DLdGEu=yC zHe?U=>htG2=ax!Qi{q*7iFbbN-k4bEl)%u`KNa%8*N4k|9E61+|nJvR&c+ zaqeqHpDAm{Uh<6 zJCDY__dOf~Teid$eew-WLalI?JX)(vI)Jk@vc;14x$M&Y@xlM{%Q155bQ)Gy1qMt; z-mv9nJ8++A3@_(a&nuk?A%o(*@;;X={^oD*h>_8A(n@*a2_(HM@!Hq^gdE|qC!dsK zX5HOl+9bBVbpps_*FDuR1>`DGRIE}-u*YlIOE`kQp57?Y5~#T!POjJ^>L!t0F2vaQ zL_GBHL$P=Ft~hz}qz026ICLQHd*A^DEZkRnTUT6m>EYP6bx5TYbY#Bqt-IoxXO3xo zM#o0u;!7@$@exF)YUAAKd7s~6F%BL)plpA9bUf%7V6Euf`qf|kV6?TFla>7q&z${7 zi@tmh%AF;i)3Sn3&Mx*!!NN*OdyF+BP#|G(pkPAc+KPh&p~JK~7K<@He$K%m?U1yj zCTU}n0@vcUx4$u7`jQvPmU8SVhY-Z#4{TQm6pS`!K0@Xh@SH?)O(=+hghVo|k`bk& zfg0il0Wt>-8U5K@lE}yb&o2kp)yl$unfp}1N{KFUHp$8w7 zezt3SWLG$tF6kot^gC`GiX464_YIQ|K1b&<*Rx6aC>>gl>>As2`R4A_`*jt;Y1sgf`m9=@T)x zFsFL?;`EF&-PFoSR)mpM0>R-Hs*&JT!L~^gn^_nL#Bd)fTp0r2s23FlRVl1VlQlIF zvZhvW8}DV>Un@$B?QPNA*lbP$Y~?1#db=z{p^$7K4XvO0RhA)i5n zvIrNMe2EsXG%$()g#F~!TKFLIG8UA6&Yn3X{s$ZNDZDT-R^P1Ph>5=m>*xMhc z&YqDGWbN2*@Kv~PNh7QCg?38wUvQ{63k-|qIxswnAV6G{VjMsIWK4{WMssVc+DDnD zdHmUD)b)b#B`ZSEs}L*E-ByW9b~nb=7u28(Y5)Kr07*naRQE++*J{+)+Hh@-@J#^p zJP85^N*47EpbWH6gy7Bfa$T%YBI8ik^~TTMeoxF-y2UG?yrbb!+V>Wn;n|z_gU&#$ z%0oBa_%fH!s$2jg2N`lyhld7S)o7jXJ^F*xi9z&W2gY^FVI%?|nKy(g)(mIjOxM8{ z^<)r=&aQT$0jSO8@8a2GbTf=ehInCoLV>d#_tDFaFVhv zJHXlFhkdH@rjq2co)ugQ1{0}tS7RX{@luwNdtXsdLK48f;vVgM{lj&T)e<<}fRP$PQ@PM~h_kh8&(`>j+dmYuQ{y6^a;8Bc^~@wp2ZzO| ztP+JpiX>^zGeoRXTGYgszw(the{M_@Y|oBP#K`$kom-yI>)!B_nm9?Y zJ}@v)<%pmQK|;m((R5SV*(GGP?saE+BdmX&8Q^XwT>brYp3JLkVor}UT%DI%(Abhh zlb(I{nYj4yAqDzh|Hd~Z$4tk7*K|QB=AJ!!;_xMhqN}4T8XKD9si&V(iSCPE{z~-s z_2`-@RiR#+ZJ(z_5}43-yC^~@(&J>@Z+**~qob?0YP1=5F~#dF7gLPTeO z2{iy2Eg_V&C_jL|VJ+AbtP>9y^hXGBY8mCZ&CgB8{NjQTz1+&;MA!bQx2H8e@v)CY z3;Z1jlkgH27LAZe;@T~dSvwiu}FW($Qa6TFT0?da#`&*pZw!b%b@AA&@-q(NTW4s8=B)|AN^Hr z#^uEoZ61+s68T7?InjL=%nRXw1y2Wqv=qcx z#!y>t9|klnbIU6r8f2V?`&cj;m||UYb#^Bw*B%}1W?9oWyhaOK5y!a_>nL(fjmF&K ztVoSyeL@{HN8I0s^5LmdC&i{#A9gZS5`ZbMRgHfw>g<_unwa34h?fLih_d;S5*|DT zj3|(QOQYH*TbnzgyQ?d~%@uV-@JQfnaJcv(qhC>d)bKbSg(wz>iG!EnuPKULhVhx4 zna}~C3xT0t5G;4@+!bSE7nHRj;YpORfz(-yFnrp97a6-T`N8j_poJvE^ z#EOcH=@bD?;699SSnZ8Nfzld(2X$d>_`bG|_Bi^z?`W1qb3=37dDl1Mp$8w9gRrru z-nphJr0Q&u--e{P7VR~2@#>ql#3lP%qF8WNk{z!}Mh+I3@`&aF!ZQtZAPtqMt;1QM z)JBY2jcPEODo*-mCwIc#*KiNAC2Or%OY`e zIG1FScHXt|(1Z8K#KgFsA?JkO8yRX(0hQ+tz(L?UInx+kDY2qSVa;lz1`;*0Hh~5z zL8fKa38(?&Ejm*YAEdXp&)GNx)g-G7DN!w&tZA`Ma5m1Pqswi0xlT)Hru{mP(j&V1 z1t9|6yl;mJp7z>A36hh2>byYar%1%l|6-FHkmR-`}SqCyKQ8QXrlvgTw z01LAb9DVX#i*aF$;ZO6bkz-6CRG;I*}FmQ4i zxDrQQmY@#!6%VVunPD_FV%5sIDl4v$ysWqj4Ghp(RYZ&tGT#G{rDC+Sw@In8qpeGU z0#GfjN;rCIkcMPk8&-X)z@VvCeGZ!;XNbAp%K8)CX5tQpnM}5|xlIvfeN%&{!PPRo z&Xf44zxDQZ%dlf)Fj}AiI4Fow)GN=NIV)DP4&o})2_1A!&rYdr5m6!z=IZi_AbyaM z(`V1<`EiJrmgeH&M;?iRzTUX_@MST-yc9!Q7^yrTgTuob{W>*qLHmz26K{^l^=einaX4x>}%z2&!5;_kWFI-gCM{r5o9?upejWuGBlo|J4SA^RJ`UgaM z1sdo2NlpkP_&XUKM7Avh{epl|B&Ewi4p377No+RI80-V<)zQ%!x7_mTxbn&?WZ1{X z$KvSS_r{}-9*dSnkF@4G2p}qS!icnN)P=Ls+1woU&2=$6xK+9o7OCRC2_{YObQv_y z#BmGdlTRMgz4KY{s7{?5jfo4Bao>Fp#ykV@;A$nEmK$IEl4xmaRj0ufS6t!p3ewKl zXO&$ushqW1kEYZu1@Rn|m~{d@0A;D71|)ka2-Uq%zFaS-^2XC~`qUW>WCDd@AAveN z`|Pt?Bf1x8FC}TCB-q*25!YXLUHtvueL(^5^6GL-O(4fjnW-_F+gf8_zz6|j>glL} z7%c+%!a^LlXun|m8*jQk`g*sx<$2TfX|JX^6ZjL>lz^4?Mosul$)$7-lm{2rL-m zP6wZLMy&oR4VQ%W<#Uy@e3IDzKXf3Y1O&lVlk%ThBdbY?M5P>HY(^BgcGFGz$0JbC<-F?Y4{ zu$m(oo8ccKFCZfvTna>!yu6X@=y>ZQuNNDK`;aLxMga#Wl1E0r)3LOK!$x#tSui~d&-*bz)U@bRcCR^PPJbWuKE~w| z1TayJZV}o*30O1|IcZ4%Mat;ZQzB@Qldo@b|11ZXwo=vllV*iPu4sL#t5+sRw8~&8 zN)rQH2BN#GQ^6i1U?pHPKWk&12BSDAAX~H`iKnSq8BcAQa4MprL#{T+wRLMZ%q^?U zi|5MbhsDkMiWT49Dn>KL$w8Hw*vJXv1Tf4xFl56kWP9!E9I36N{nd_Rd1)aYeE8vL zhBr}OSNqesv2)Sc+8M8W<*Vb~2kwiD4;_r-$B!!u1UVQVA2U>@TDvDZ;>e_cn4Sf# zUTEJFEbv;G%g9g@jO^XJJO1QT|2>W#y<35u92&X^wY9NSTG9IQ**REazmX|}zyJwj z@@okuN)vI*O9x`#j$*XdliivN;r|<9U}|Y|LquO!vuf`6jruy25fNcok5Z*3{@2&n z;=X4aRg2|)1n8M3Bm^&6i=p8i@w|N(358*As9v53aq7cP?Vnr#_rN;cci#_HLgSe? zHnu2`24P!S=HE;-fIw3Ob%f5lrF~tC##YM}zQm(9n zkV#Np6rX}MBXD#e;pfMHId542NL@?7_hjjH<|9xuhDV?_>0+(k^UO2Ph;T;$1$7XmM^?L$Y{+1eI(PIheCa`Gd*5e6G)+2XOJsK__|67himd%9M{k zaV*A2ye1}Nb#+DAHzlXx;jPiw+!E)`oK;}JcXai3#pJ}K_B-czU|=x1JJ1Iy#EWjc zA-Xy}n}R*5J(#j+osFRN(1WQ!+VDk)l-XY6R~RM*!4XG}{V{@&Q3SYc>@W5;!fqzO z7j!?%OY{0pjat@-X7$3WQ>?arJwE;WACI2?{=`GDM#C~_1&AN5!Wx)mCN{imlPDcG*X$r0Uo6lHlqBvb_;Xe1D%K(nYqA&1v;;)YOStG7G~z;Y?o8H$IxS0^)NwPYwIyPHLpzy5f2B=eP@V?`{D3od@v6D z8Ccn!BU}q4KsHxGA1K-2{tDFe8>6A6F`DX|VsKzkPmGjdh~kN7u4jesp- zSz{Pm+CWPDc?xz!Vyv%btYo;YE$xOQ*BNLvEraw|fAyzv{ORL5_-3)E>8B|$=8!;a zti{~oQq--@#M@rEJ@yV)qP+=AW9Q1VQjdShj=Zh4KAIZ{ z&*JDxhhu1HNX{7B!d~Nk)h3xC z`85JTN^-P%yF`qQ;5)fLcdZzaV;xCwJiCJuqM7-id}mLeRx*MegP(Qaz`>ZAnu)Os zW9o+J?dgxYhK6|Xf%}vov^TXxO&y=#EMYOYG}w2wE3$v;>Y}f&C(fK1(R>t*dM-q4 z+qOew#QuSfc>Yz_L{n3HA~Tz#qL~@+mR3FJ4U|IVr-T?#7MJRxob|f2U!2{S^&a__ zRA!(I!NFK6QPw7rF)~JpnYP%>NnnT-+$8L?lGxgaUwi+%;>eN9l3YKwXFirlc;Q4W z8HLVV1Gju`w7LA}tUm_>?6XYT)yva+vTu^#+Y~U^(UUAxL4<0;AYsEatc?BK*VnI7 zrzVezFT6&{bS6dAATxjT2X|J4AS9xcYaiBUCtH=86eCDw zxGXyhWX1-hrpGn&`@i^$|2Mw%t#8Ot@WU5tob1YCeCD%%tmumyCaAD;@C(^=hU2X9 zM9IKez9TV_(KJ(n*CdT{^>DlGEknXw7Y`ni4FVjrim3!MgEz@CIciz zHqWKdwWqn|IU)y&f*1o-Eyy<2zmx?pLxfpT27~&bvKIPyDTk;V#6b{7jKB+2frmhy zv%jZTNJ}c5*hnrf3UvS;CNl!UlcAoSmthzAF_j5w>WeDd;8=JbnLvtSq@IK1V{4Vk z)zvk{(jvhG*+vL*C0iuJw37g8^K}ydkY%nF)?$?r)e8`cN-;4$uKQ(vJ4i!SkcMYT zCf9=DW=?&RvL}{+@`dW!g#@oLpgkQR?#o$ojf_4E#=Sgy^0?LpGSt=AT&)fWLT0to z%}mGW*tle-$xM5Cn4Y;PBgp#k++pV$9(N##L&6AgeKRvtar^DJ$2!P|MyFcB7y~A> ziqe_{lo;yd+Iw?zTg=Z+>KTKgkp1#q3oA>~FaXAEYg&(Yzu}_TzpEkITTOt?B`5X( zr3LsQ9qsi|S3`M?@8$bz;{0So{NdkE#`H?BxjeKru5Mh1c>->Kz54mrMk8>)NUt8Ob{{fpJ+SLj{it{N3KCZk-gQl68U%sC3cXq%+4eqs&I2QK+q}8gQN)h=DS# zG#dlvI`8K_1PZ`tg5McN2PY#bYg%a%!kWLEz1-AjXXWp=E(H20luOtrLQ7T{K}`T- zMnCq%hzL&Gofv|(mp8gEcpcZty=D8MwI*|3wA$ac;U3l2ckS4zXN^St(sDU|c+Xd& zy<<>BR&@wyK8VXY@NL-Jk39BRT$rAX$qCADkL&wYn!$mut;JGM8}ZZY#vAe)J{rrZ?WAby9G! zIIm~RHKEOrgWFsxsm?@7{;^tW*n}!%^v7cn%xU3XoD6$RbxtyKq6}i-A!QqhGj`vd zg|+fK1PDC0|Mq*IjNZ<{=<05Xn_uxVss1t#W$f&k=;-c?AAQ9uBp4^XDmjq)DBSb? zJ1doHE0;59)eS}XYmkwXC`S^Lpk~OS^9`C{_2iRJ$0t7V-(qEjVN9FEJ4&V4Ik+W$ z_TBG_?!Mlrta<>8dgRw2aJjre_`t>l!t>`ErUiBu6F;f2(MBiDhQ!#!SQ8}@?eZWY zKIRdkz1`F#{ke+trK|0ziAY&3TS=N(-<=>O{+!VTWd&qbX`l}g7!S^(Agf}?@&Kjc zMac!Yi%2weX~1IULG9eOO9q1=D3h``FcwBXL(uttHs6;Z;Dtpq(X}o11SB)EIqre%&TU90H^L3jJPihFF$8F7Nu#!t@TY<#f)_GjS}qSB zJSbum*G8}XrI%c)4C2wpo`{**Ib}i|uKXMgFZ%Fjl!}9jyfsGYH-7UYQNv_WE;u<^ zoJtO=G)*zBCC`WM8?rP6doa4}UxE-O_jNGAZ*tP@QneBN?Zx=1mv4*xI|`as%E4v2 zreJge?LgRNFfa9$bnkU-ZCo4zw_)iUoYo}eX4fFbS4=fM~O8fYCrH+$+(hX z*WWAJiOCbyl(W;>4uZBC$4{J6oAAEpZHpVOzb5wV*rokPnUaz2BWIt8 zDY`_WU0Nrers)zK-8T$hdi=>}MI1ggG9C{<{8$w^we|>Q(n7rGh8Ia=V&pundnWWr z4nA=uM4}~WDOx9ky*NHPDm$p)MA?3;?%DgsxghVStH}XVIgTAW78fSQ6u2YHjJ)8H zBUh^EHaRsO$Dez~$t7GD)DP#yOg_s<{r{tRX+|@PtP}ZBZ zgtMnTnPi}`7v}lpTTF9LiuFnFBm!E zH@ke1S}2tTNhjOUD^6HOJB`MKxG3Y81^`JROTsw_?J)a1P2fve=^9!HLMIv$YuM!n zHZF!Dw?tfeC3q%f(zZv}T7Bt0QSQh@ZD zPEnpIEysE(b(ly_w$9V#=vjtX)zqvSJ~o)s!aD2ixeGW+6O>%8l7u$KKt1uGDNJr8P$ZLF zQrQPG8GEy}r6q=khEyMC4?*VRS#&j(%~9YPDUe0DD`}$OP~ZzG028;!C6i2`WG%QZ z&V5D$#HmQChtfHLSc%$U5(3KCz%_}yo31AZ5FjHnb2BoAd1w;>Bmd6X2Fb{!2{<%J zKjUZ!co>?-pM?e_XTfVttPFjIhE=KjxzU1&IcjfdGvRi6N_K5w$z!gw4PifcD(1$J zF-kTBNKZZeTx=a2jNN;N;^vp#q+wnX0RruuUWk>2@p$^lyCNF*M}1>mbaeFSb27h& zK=H!lY&?4GiTKWU?pDdlt#cbwB`qRW8?S!Vt8{;mJ9*ZWn~!Ix`YuSx(A3hh5X-zT;4@53 zPa3ULH-b9^)Hk3m_Hz8fyKapeufIWZ#`q`d`n1TyGa@+gnK1f;A4uuBKBKfwInHC5 zv1!>Z7a%llsvo$du!(3`u-=BcdsO;&P^0OTIY3A)o1id#eOrv0vv*W7cQs(OQjUin zI4Z(sS65G5e&q||nJ1r(M;=Sb6@+Kjwa0XRw*UYj07*naR2(21A)ytlhoZI=WSA4-&yX;O4xG^peP5k} z9goBYmU0AXM8n@dI(9)2SXX;TH5)f!#%nHeN|pKS%_s#z&5-96HWGYaX20@1)(rQv z1d7i=Lay89dTFky=HKUx4MQz<@jUfII{_acmwTK&IYY^17&#OI2niXvR3J1d8B(4H zL@4TYI($0u-b@5ttfjaU3Gs0@V+WY;Q|-0MpesWym4rMzcj|QNhM`2W(dD2PTJa!U zTc^};{`}ea%fI~dC@p)h@Y#a%Qh>?1F*}`oh|Dz4m0&B0w5WZ~YHs`xl+j&6mj!zQ z;vNo_&qPS3xuG_OI;P{AL(Q>gM~B)*TU!dzAQjM(x-e)hTUw478Lz~@+_N0xbF>no zeZc@Jt8;?HSg*u`VaVQI@WShLjnc_b8yHRj)imo1VALr|*)f;nd*8X!rG+#mouHAx zjeBWtYtge~!XNhvaTDH(39XeVHh2nZQ-gImc=ov_4qOe4%UNV^a^HN0JD*nNe7TO< zIkyvL_?~qnK*;+j2dnJ0%|UENRCq6YKtW$}4E?=*3Kj;o^v49VAf$g`mO5+eGN5%O zaO7_HwD?!GETvXx*L^vUd>`axI-A_ZGhc0AoYtsm4=Z9_lzp-fySl1v;6|=ou9=#e zj+yy|=xAw;1BZ9Si(YVT?ApCczvFe26SJ|tHXrxh`{n5BJ)%GyzE5MFq4rF;Yie$b z`yPBazWkN1sch*?((>;NUIX6dI1Tg<#f>-KV5LGzp(&wLa*#M(pa$4FI2c=pwp6Eh z@*bX_hin;H0EyB5(unAYwaU6CGa_3*tqhxIRUi8g9Ez5vcFB_?rUYUNFUlywvV{0D zIz#YCV8Xa=P@An=1~t+0*ppAG^oOJ~`U$8kZrwf@J-q{Vf|8&nZ@1kOA+TZ%ntUdu zaU+fvWrQ>WS|oTUnFNb&@i)`L@cml`wcZ-GmNZDP9jwK}58Yoye)jI$AG1?4@r677 zEzX{wj@P{A74ai4x+?m%ZjHi2_kX`4hm6x+FRLCWW-(d@ONMPZ=sHXi0P-9MAR*cZ zKlYJN#JTZvY5@`4D9weUgfRFVl>wFv1rf<0#B%G~-zEVM9v04;9#aS-Yy^S?7C}&n z`uvHLtO8ZVWxVV3S7dO>Lfx)o=0BN@2PW0Kiy}o=Ig-q^BDq@;jXbR}|L}VSNMsh( z(XRSZZMs~-kWo$yR;~{%0QEa3%abF(oZ;{ZY*++H7^sp5mE^2k4qwDQYPp_`0YogP zq~2u=41-HhfFs~AT&22GVl{9*8YxVmq)oZOuvf5?9K7x=5i}i*`(Ozjq1_516K#w2 zS<}IN;BX9h9})QG2vAEyw!=N=s z2OZHG4FBwGT$rBG+E9ZOM4qw&T{jZIEiF3O1V5kt)TcD@0|IJFO;To@Cdv`uq#

    p;FZi=24sn@N1qt{}6miCA3l0IXtpDY{zMV&_mX23isJGRJ0O zdMz%@lw)+d9A_@nL`?&Om3a0JdO2g9J<2@p`oUN;YJD|cbmNP)4rE-J&CX%)p0MT# zYbGeZSd8!7`Aw~>R4AF++SI7)GeOEcj2ZD>kUX~WCo5A%3&DxAOG{>&0GZqU^juOP zj)B0jSwh`y%>*2(Yp1Rkx87|`&Ldgi->^NI7myLKj66V!rFR>rO-X@g%D%u^yEB40 z5;I0P6BAw8FlwlfmpeM*^y$-T+si?)x)9(haGv4JBrOS@a3Jed=DGMeEiW!BxDW%L z5=UFRN?)vDcK91k6*!s>k;XW2@ATP|ou2o=7W+370#pOO#Ui0xa4qqC)`a?<&m@04d=ssbsK5 z37b-=g3)y$NNek*Dxsg!u*`c-ETaDjK;3*+vLjzhId5a{(HYCodhkI2px`;TsQOp3lDvAHsgAs zYo-74FJFx>{qsLZX%&*3q5nLXg?c*&UkYd``p-@n)Zn$RyCsH)hgAzwFDZ_qEUiir zuLPIYyG>F@seeM{2p|GC&xWMuSik-wXGc zjSK(oS~Q{|D4s0~a%U}bq|E_UV6+SapVn6^?5T|?k1|&4o?D?TLt4?bW)`v9Mb}+h zgk7xp0L7w40ITh%f^wnj>mI-40Fr~DpmT9C{`Rl`SCWuk)IQU-$9f<~EMjizqTxF& zi~{kx@!`7j^GPn8cDFOuSIWnrw%LJ1bv^%aLEWrBZAgN%YxHB%9KcnspJWS zwGLvGp|6zyOq)L0N07s)W4qbXg&WtrvJ8nX#99*nLQ#0KJIxsSL-~H~L z3W!{4SQS|fauP<2c1)E4)a8TIDoMCZN|*3+>gt6Ai43W(7&-^$f{BeXKIv?biLpm< zY#tQkd!eI9-6jwza|eaG519So9{r4TagAtjWcZ#gDa}nlDYS_((uk{}cVVe(f;D(G z1Q1+{1l45tT}B{i5y@`sLTnirsNO5ta^_%&$C5I-Y>4yOaJhy3m_*vtN?R)gBa2vh zEHx;2vpfCCd`qd6z zQ`ewC)8#;a4mOSGA`2F&{a5D|DP$*Ye5->5mm-YxCb{v%U(=LeI?5P4ML-m(>wzGF z`437~+(NmqIHxo2a)Xf^xd>V<%jI~>PyTq^eDjU!zVe`?P-hBfEi2us9Xg5H>CKto zpKO-O4OK#8@*#rmH+UEp#@kSM6#|~r8}k~u{ktsj!oL13i8r|6-_^BJD#bHTKM^Bm zPQ}5)m&A3~U2oET;xYO1>@WHTcTsNmj-CLnRgsvc#5ww7lWde29GSa*UygI<$Kp4C z=XYaeW=1`gIB7&rc%NGS=q{-Ds8KJtqr9|hqQ161e(W``jKRSzhWm*8)27YSv2X}P z(y9qTuuA>oazb3#rV;_KGZD*mb>J%$8*!5ESa4mPE8sdX%o`5PPb_EI{29o4!%?xx zQu|X{pUrKUIUtZUa;o>+L8cb2)Ly44hngzsjsqFt+JdgL8Yw0bBsnHpP*ZI!2X5jz zq>M2KIRqS8g-iil3KH}ll}XmpFcfo2vVl~Fm^OSaEts?eNe2xEYiD4*GfzXXHJ_i9 z{R9I_Ki^I35mN@;#)T6l;GBl4j-r&(> zLLNpukGocYn@Z_F~V08038?0%huU5*ZeG=T=&L&5fZ}ngxzT!b@8EINMzAQ;A7) z7tDtc>X>*F`E0FMXxDQq8G0)OG|C)7Ihch~@8>NdT5icqh>F+T8V#OW+N?e6WXRn% z3RDy7vSECECREqw^#s8Q5zBjrYes{Fz0G>@tT-b$e1bU0ekV_j#Fj1Y@9!UIj~Czg z!npL{VeQSjVoglX7^PY%t*fL&7EeGzX)LRt<}xGB@1CRg$3K4Y-(t`6cEt-{@ciiN z?1)2$E{W25sD16om6ytve&(}(sX$BoiTMTX5%v&{P^7{{oJ7hUw1NOZ$(%^BMuA2~ z&Q*!tpvw@CDIItOvxAo`Le$>U5?5V$b<|QOljxTN04r>`w3yFLo<)!oHGWNk!3+5#Z=XMwbuc)@koN8y1VdcYGkC)!@}-0BJv#|i#a z4O@$E2ZEvh{QvyhxclhQSX)H{pAATRnX@hqC(aP4(1yhekZUL|70@%@8n?dnR*$7l z+ycqDYK}s!)B+7Dn(zlv$#9DYI?+aju~Ms7B06E*Sr|o}DW&r;6|;UbYg(b$;4Je8oasA&$yrl=O%7JF;r6|H zExh*sF|f#`7hb2}1Jo!XDEf0k9CEottvQvlGE5*s$yp~dr3RlQ?NK9Hl(2y19AxGZ zz&L06CG!lYrY7U5V~-0N;QrcGJCu*%X0jG!W;{TfN2;V?LSVmcavRQ|mxq+Hs=mq0e+^5cdJ#*%a_C6@0 zv#d%imzI^8(<#A*;W;VzP#yr<;eK~G0(`$vLWp>j0alhRi=O0}`F)n0=DPC$p?vLm zzxw$sSd>N_5C=gZo7u)VSXh;)6M?sbz8VDwxkXyq6`Q(f$keB%XJc+|(JhCiQuGaU z#C0#cHV*9F6$5>J+E0jumDaIS%c_Z=A01U|Ds9mSnW32=r}eqbCNjEPglob1ZE(YCHPhybORum~Pf4CRVpeO+3WiETl1-I! zPG}G7NszK-urCJs`h_aiH(2Ar=%P`_tXwEGfgmLDZ}Ox|5HOIKEY-|^v8nD}a6l}l zuW|%lz&tY6MqLi;E~}9+s0(7vooYDDiHR|v0d+hjN>v&lDBf9ZP26(JE8|CBc3t%M z4OPqX_(5dtHD4mxYz3*QlPcTas>9D+Vp8QyoT-GMD49#&P4_|dLK1Jx*aPRK7z2ZY zB1Ie3+Tb#y!cka+m6^}AxOjgp}!8Gu5(@h9ID-Q6A4 zOpyf#!oi@h5Nuqd1pisgiMp1>LsSw-!Ygum>3eiv+90kwb6<#jWXEaJUtUDFf?*K! z`joA!UsarjR8K1aQQ>$uh=$p)Zj>!5%8+uPqS|8`P$TK-#s)Ft1?wdyF@}N%lgDq1 z%`0AuXh8_W%Hppc}p3BdG^8xuJ*LgK6+ZiZoX)mW2Ush_1gC^o}_%0$&Sjj&0Y zS&)J$AuNf@pb|z}qr5-d-C@J-DBTV_2N`NBtZ|mc_pg-PLP{1c6ae@<1$jm&h^FBo z*g)rl!0XPRJ11lU$KmpgTNObWM$VpzJHGG*6aG{lLcOwCLz@;5bSaf%Zhl6;11{!S zWHg8ox8~v086CrjQY-H06iJU~gm4T-mpz`RlU5I15-7=mm~}?XTOdQ`b*$|M3Dv#N z;`m_bGWRF7;hDAUc`B5BF4})sogFL&pJkNHHAntULzWacn`^)nMyNbEh*mm+6F3YADA~E1z^K+^`ua;H zaSM3%!^4BR_TKJp%aW%SF(ze@Y_J}1EyVq(;Na*4aR&jP<8nurP=cI&ag90f&;NB7 z2d~KlV$X`m&YpEZ8eH>YidiJer7c+DtRIs~5oO~ZL{?1Q5t(?I3C8@_h!ztQ$Cb1o z1jhaL_jSfCx7;j3-tgd%TItBnm)Ejd?P^R+O}cE*)EKQDZPH9|*{mRhZhUGsK6LwU z#BH~|DGu&GDBTX)cvai4sf~vpdRUz{y*-_=TB(WO|NT$KKwpovE7%|B&yT8&lx&EloHvKsVmKDjkc)@BqW{hgpz{D3A^=i?9(a zy!RJwiz}|UT&SHP_=*IzrYEOU2Zp7jrMj5zF{?SMQxKcS1*O_JpJ_zFWe3isISNJ$ zvq4nyCp{2GbazKbSJ#G3F#TJJ5GW=#6knbFS?01i1Kp&^l;p!NzU-{i4NK8~^Pq}xW`2#7~a^`90D+o?}5rz=C|F%YoiXjM; z*XH)Kj4I^lSgo%rl^8X!RJ5UN8wj^`8ir0=E0IyHIpJW^Fy980$Ns1?+4C4@wf3R> z2R!IC5?QqdN5r4KKVbOh17K2|Veu2EPDE*?EQp(X1KQ?wJkN6@Bk|3zf6XI#LB0xZ zaU+-*pPq7dlQM1*bO}%>YcW`+wKaC{*&SnJ)DscMG8czHBJUFiPe^PtSD;qPlB~V5 zT(xPs#?7NO%YRL!8~Vnpy7+2~GVcTjouzN3qmZ6aE+KG6(3@}xs4gzO;wow1d)>Ha z#sOzD;D9K%&T<|fc;Nn+n?ah}$eC5x2;?|FM)=6cmrG09i|FU`0|}Swg`WXJ$euJh z*qQ8sVS713_#3qh1+yp-_m*2zS-VUgLubR?Mg=(p_KE{=?*VtTBw{S3fci9(Lamf7 zX@sZS# z?UqDHg*-~21yaV$40jSyQsL1QRCAXTCg|AI8kx!r z`RtLXsZ3r%`^K&36O&_ArC~nboop7c({+_A(bL@)zx?iZ#Nmq%sBPL&MI|OKj7xkj zcOto)E)8=^qoQ+JCMQ_f+WeEz;p{ilI8^&}&X4@HZT7&Hp{PNEJ|z+2X{D*U=gyyx zojbNkUL01GeX%~pfm!nV`CRaQhcCS{3g5Z&t0G?_N@VzRT~HSfw+N>oMfphT^5%2n z6Y-Ic{Dy|x-CRJGEhvC0UQb zC{C^yTdTqwypT8t*)e8B!cIOt{M4pH4=hABw}Y8k&1TRvv_u{<2Zfq+Qd>-=g)EGs zLy(4f!Mc|kVag=AC!P}|%$zM?O!(}KTJXJc%qc5|jj{H%qXhdtLV^SbD)JefYo|K>#VjNMz|; z2~HJ|E?!Z9B6;RCGM9`dBMS7k=kdL0$sc+CwHm(V@{m7+NJyDrs<)G=@)-me-}=@! zbsw%dGln<^u6`!$7nSqs3Gh~>lA4*_AXf-Fxy#2L2r|HQN+d2yK07$Hj3{9|={R6F zYUq%9@|)Cl=~*n+LNJ``L<1+D(LO%g*K4G$qs_m=3B&DB5Ce*cAzxjM-oD-#JwK)( zfgi5Z`UMQIa=WG40P~(GS7LExQ9*#=SR+<~qBYaR!7)NJ*hLTK2@P06&j9C{^&9dv zvp#UI;ESF(c}fG1*xy|p9YLx8UGIF0h;3W?djc6AhV3vE%{6=+8dB^gc?$VzYfYoK zH^{&v&%h~Unv={uDbTFk3 z##FlCI~64S$!9)U(TLDQ4n(5>l9066$$WACK;sNOS}DaRKmBKM?9oS~u@UhVLnPK3 zx7Z7CJzuEkr?xhpd+s^GTyAA^X+Yf)9E8?}xbn#5arn|BA_{V`Eo~h#rZ`n3K=~|C z3e{uO0tZ(iiBDu5^W^M#0RGun;2a$)UP=Zj!!hd`wgxG{3&5^qZIB7hnrq-uSgwJ9Pm1Q!CQfyvdJL*5Y z-^h;FUeeXdK#inif+npv?8R)jF_bxg$^j19kw)yw@SE*!jSCw}L)jZ_TIs=Wf&nw! zoxg+EXUSTzZWY*A08736(!?-KFOuncSx%bF2?N2v8Hh6(%C<-dd`)qht+%mManjx~)47L2ZTTC!d0>~#uIue|DtXsm0DnfV#R z^+~s3{K9BdQYMn;t(y#(_y>|n^)m)m&1+;B5(1k?Iy-as??FN`888O~3BpquDUV?{ zM8B$%2Ivp_UdTYX95eH?al;KSmEjaQHw939kJfV&On24B zKFw!6>jR!tCRP9dAOJ~3K~$VMdsdT4+3UFz2?R;|ViV$5EsLSUvN*4<0O03bQsDI& zIp8~TGQcxN1|GTKk@I6wT3U%M!$WcQ%-I+o8kF?&d*1zaAyr-N?NQrMCxRmU6_jTY zcp|e!+MBgjnWtP1jm}O3$K;@*9KZ9s|0Bl7X5;3U-xN1MDyylJqphiNHv8o-|6BA8 zbjMXkE{~Ruw)pjremv?MTEuuqkd0CAO)UhqrReGEOl{2t4T)lH*kj8JCRYmum2I+E z*38so?B2aI<`$=;sp$4Z5CLXj96We978mBF(SQw5Nh)1C=Ym=}&WW-WwrF^8iwKI8 z7czM?6K~}tH_a#Dx|DQje?u@NP&WZu&jE$Sq!`NFA8dwXt0|QwP6xrBv=nk6kZaovB#!eDE6sr)Olxtet5`_@zj%#YgDkDvYY`I?)oE+o#>edy;53J^vK~Pa)zCp`=OCS?dWKX z;oPSG9;#vs4 z_7q1$LOA<6L7<4Z2+D$lm!fb!U-Gai8#MEjEYNkqoXKU8DgI4?1TAO{jUtC-32G}( zCgK-kdTCio%8cqe*H9SOwV4}`1v@|;=zr0npdC%4r|AiIcAnQVJE{yDX9PmE!IY`- z{bF+Cuv5lHFv<^|25O;A?S?LW6r#PeTLI$I;%pS_8boO2dpWoqz6T$;KkmKzZo$Ez zIXLv`nHdq@*n50G*W~G!D{<(+{+n4i`8Y2PytPCY-*A=KXvjW zS0IBM3cN9R80BicZnjEs)P zi>^Hq{R6|E_b^Y_0BW3M%AkZyupKw-4jCLyjHI{ObBTWu5kL3t{~{yv(cAy;xcHLG z_1dhGO3k0=^5DY{#mjI05$&rFy#Mw%aA?2g!4Ui*ibT*cIMA=bUFsZ32?^yd1c7i6 z-s`#DZ!Jd7oRe0=o?Y9;KWJ`lRlsrP^x4?CYqt_gkTH=}g*>|S$PY7U+S*$*QMSIZ zDe6Q-XI4uR1|l<-W{S&4<`ek6JR3&?wzCAXDmSRT*u-W}LbcEma?JW%@oCa$rC@+( zn(YyRg);XvP118M?65h*1hxESo;6)v4bTMh!jhns1{`7sarz!^2b#oLx$V~1$930T z6I%x1-mq3Wix1&H?MJ#_ei(94C+WNLn|k{-OXRp+4EyXj1DcQ+m6ir>{Q+ z$~nMFYbSZ?_2}wuPvaH%Ds#qiiJ?kx%$*l0Mj&}rknl^t^a~Zqs)}f2qes0`?D?Xz z6{%k62-It0*U6L5MR#|P$WJS)D~jS+Y+5K(Z`VBZmYANI())p!IH(*(7?TjWT3ec; zwG9GSDf)W)qJ;>%SRWm&Z4#v5(Dd~58J4MW4QFTz%u$o)VCm*VYz4&BW4>-fpH;ZAN$uo73bCY;2za(xwa zKdaPjpcv&uj&#XHVnbEO;t6>iTD9|#siGFPDQn61oKX-yH`k%rJh_b!oGT*-4kidn zJoiCPs0@p|q-Hd3B}GdPHQ=-!jDwYRm4H1+wb}2vBh>*)Z{1Pd}Vd7L2n184&qWn(z)j4c~jhDGn1Z z03(GD96lgpftGihi8y=8Wf1q`j-TI zP*CJL^Sl%SWce#2CY_Lq$45Cz~DPvnpyNTRMZ$78)If_x~k0C z)zu;OK*}|s3DoN~wJ_=Li&vCNULa@Y%z#{>vtkk&kT2v__MZ2eyOUU#&0Gp02&*gF zrz9_G8LUSxSDK<~fg zlD%>L_18ydTWjpt!8qPJm38Me%H3Hd*L7k1f{cAGL$TI5k;xpYJHGIx_?NGJQ#^>z zf9|u<-P7kxb!=2J@C1~9@JFAH55E81QCp~svGJ++t&jgf3~d{V3u9w?e(-L1Eka3r zF5O11+qci{&8aBy!=u|$1;JD&oZ&rr8xE- zw&=aT__J~O<%goHvroQ*?`Lh%kpS7Oq_#}fi68q2$3xWsRem^WMdT7i3MdHVxvj0+ zx2H1shQcGEPHmw!PMtgvyLRuaO6zCTQ@km)q`U2z#7iewWb{H5sMAKo!OJd>!h3(| z=PN8WwJIJW3qmUrQpghRSvK3*igwH^Sc?Z9yjQ)?j&3Y@EXb|7QNvOY*B~-Ie(FpW ziiIi5>tKr$SoL&wC~%;K4Ty5v*6mhLY+)>@+yBr~Fjv9O8A#5e7Vrp6lEYZwNLdij z42}K8_|?_LYMLp~mQW1UUW+I+HYti{*hqVuN8|F~nPXpdzTsX~W#y}@VhOVuq{ODk z(}O+;G88?gl84vHP&1#UAR+b2>tS0fD#1ZMpxJ@gIV40Q4OUVga2mFf%M5N?+8D77 zBbs1ChceAo$PhHfTLECPKDKNbkTJ(0@oxkR$R(@YsMZi~FA!v1ow76ateR80+(|8Sczo{jpL39rIx6@Br3eUeX13R9lrP`2W5@P*>#euRFi=}QfBu||G5iB} z2jB>n;{3>I8I_p&;am zXHiot?gBw4zlUMZJ#uzX5#@U^=&U2pX6N>uF}!Vu_gdDJNX|upmdJV@nuc~h+2sQd z-Y?DwXw~ZSickr@TY(?^n^;$$G~em26YrxuBE48NtV^wvJ(cwZoHUr638JHktEfPN zdd$w~nNVKIB^TDDtFy;F_eoDAODk8)d`SzXoVrU?@~j7CD``zJu*VLYLcJf{=KPgr1zvR_?Yw6?W4 zpiYEAy1H(?^}QNb+}Gb3pZViYsYP*c%RoH$+_T!B_uO+djvTorM$Vmz!xtZn#~(W$ zfAhD0E9V4%h<%((v6*Ay?hT`sJV5p>c9^|DNrC4J$xx-%#4qDIXJ^ntDX2>b?oCG0 zuuC{SQ0W|Ku-8R$FM|Rk=jZ~pl2ft&^E?IB?k&m99=zz1p?K{Z-Wc!w+4oDQBHI+% z5}}nz>xAwF0_D^KsW$4=g~00+=xZ+_L+hc2b;kA8ST3!{#Q2DUOYH|C zUAEmu{hXZgcRT%>Xl-tc54`W^;?O0BR9122zaj*8{KACEm8t74J8yNgrS3J^wnR+K zh%{@Pf4HZi!L1tbr{ZpUUuwgM$%(1hGRWK-tI@i}d_&}~fb0RnZmEOLfeFbzXUX>D zz$I5i;XUv9`3eu3AF@4{51e7B%#doi5~hF^Ods-cDNdX^8D~zNh(dw-FWHQxecNfT zC>weqDg=&nR$3EJJ@d36VIo-9bKKU#!KIzXj9xRmr4UyrdZZ`=qY^9K1g*qUO`;S$ zEQ~{bKsm$WddR3VQ{UM|nng}cO2bP$+rg6!Yb6iu=#{LbS=tfq#Wn6z-)PQ-YvmrX zjlqD~Erqv65R!JSC-rU?lW1Bkp$+vW2TC^CbQQ_CHf*p_ol$$>6Ll|~4NTcApQ{L% zYtsQ{jU8!nnYyEJG6#YK z8zgtyu#d*4rsL25>`yIC4f9y_;3hG{ft=|#$KfOY4Yb}Rb*_l~6 zwbN%##p2Sk&=<-W(=!wC*h3F!A7hB6ZISxBP1ba_E**~5Qi2+-)P_Oinh6wuxwAs0 z>gjE*%1XqNXFB1g8Sj~0%pN94Av1SRx?xtnleNY$?by9D+FHB(yb#7|YE-|yo>$W7 z7l$R+`q$Rt```PnoC4Q}Gb0GlB*+!U7%!=`m7O68LN!Zos2ACcE+aA@&>WR9;Mpg{ zfoH-!BQegJ(-sO!!aidUWQE3zj8JkAQl?iS zQZQ@{awzSp7#krR^9y=zd^Vqv+t*BXw6t=riObF<`C*|}Nt46Dg&}N89-b6wt_No; z*V*%P0aX)mE_G($fN}5)ETYuFIvhT9NT^n8b5p$bwKvD^?ZZ)D*A)E&XzClqVa|w= zHwV>|Q*O^?|M6VAdOG!7+!mS9z?Qh}9q-lO-}1JfimNWaOw!ZX0@(Be{R8psZ+$E7 zf9TP8+pTZW^ZDO*d^twWjznWUf#`}#2Oz-`K@);VtFV!ntOo#xfW1esoe@9QL!-Ub za@V2H;&+`LJ$AtBv?vuLoq7*oAEzjG#Bi?@N>*KORm)e#nur0;x++0jg zO~~G=3oFm%P*ueVL`JA`NttWWdcq5fn&{~25pP94E!~?Oex)3zPo0h3yLY5PRJqY2 zweu%xqdHZ}l~|ZtP-je~Toa2+^Rc)vCr-}v+)VuLAATwdzw*BKR`PHok*0EXuGSu$ zS5eVFhKWNfvYMdKLYz8zHXeQaQMLIXnTs=LlS8P;wei@FlwaCrxukw9t=^O2_JcucD@G_e`=*Lm^0UW0G;_5N@qGChf@X@ zAsESjVr*vh_Zg9^+I5}$4ku4A+RO^wag<}XvSU`{*YCV5nHQ*?B+ zR$HGi>JUY1>#5mVJciFj!EbhS zVjMc^^Q>u4PiHL7Eya<`kHlNv{5G@B6?E|ba-2VVItGUaHELQ6Y6%R~#K_2*IQi_; zR&?8hbO`p&6HuuG3fW33g>^+`pm|Da?rkRs$*pw+PyDE*P9>yL%1$k|1r$%vNAEcM zgmVTuCSjzMtq_#F^kpxLO2uMj3gnqKm`JnQ(<#7}AxuH=vBw|R{sB3`fg=^`pun|S zWh+&MwSwBya0>8=xDGf1XcoBD*Vjt$U}ZK;mE~#4NI>IQe|6}f)S3G6`TUIfO-@ZF zCj7egE!q?GNM{a)h|sj9rWqL!Pq{#XB3c+V7JA+yRX7E{UuYJcA}giXvSlzv$3|`J zQ~gF(BHtWRAq5%G)9?o#{R*A zPyW$g#DfnXizr5X@B{CO8*jKN#_6olxh$$w^vENRNB>}NY#SbombT9L#drUg*tK_O zoF7GJq(=M%hFaOSKtg8#6X++wsb_fPgn)p6OQ1yKn*CBRYn&P_Jj+2NV#doOxk6~^ZbPftxL5EVCpA@U+bZv+RMgM=!|$~qLv(O7Jbt=o50H4qd; zQyNVINeqi0!*}YEmdA2ki6oh3UBK z2j7Uo&%W!YD@4nJ9(l9K7|7BZ>aT$eLY7U-AOb>(?P{&-H5r6+XU{5wW3rc=bW%Ue zPMM6s5N2ca!0KIGR8|eKucN(FMi!zEL>PDukmC%mr41w!7_E?II_HR1%6?UqssvRl zD)rbVOm9S}HJzK0*kdK(ZGggSQ-2>xZ=*4=}f$ul4)cK#cRc$pl@XlxJ%K7-7ejmP?c zW^5VUqQlDJ9q8{9A*#0*1jktmedmk^?IatEkdxb?NYQ~z_NAmv3eSUv07TGgH{<64P#zvq{ty`weOaExg_ z#M072oId`Xkb;qsQ8_!ILB-lQdh~nlkCwQK#Y%GjHP>8I;1IfFL1iJ8lDZ5Gxo_LHO>jHLDGL-ya3*mj80SlwfQ*QH!!FpNQof_RqgKcW zfdYmX=e=1OlJ95F3awhQl46!9cW`Bfxe%~=moLfC!p{uJgJw2;HVc*_e@$@stg+g%uZ79#KmE-4r`i*M&<(Y5WIwqX&z?AY z=1epS}6MzOtWs3o5eq( z^&BNoG)frER%8-vi_RD5XXefD4B)C=a`9!=QbX>JK-E+P$m&#DJxM#O)LEh~tuz}a zJ?Lr>AV-}DqLju|_fOpnl-xwBPV4U(DNf+nQ&QT^dI1V5He~a2f|gZ;Rc=UgfAlO; zpuM5m=ou{VK4?XjY|wWj1w)u)E**#@EIT*Iq3&Fi)VQbUV$^tTa$6 zw?*<@k>I1ckbFH)XF|K;^ITQ;@5udqfvOp%YQ@zo^WVHv>YVWDd?ZZFeJenoGks> zY-%1-Ce?}jCTHvsxQ1P<9*s4)RO#MqRJBovqvK-~YEG%DVf@>DlQVKKvKu(VlM7NuC@Ax=4{QTGOjji%J) z5u=W_sXIw0fg_fb0ugrMyE(vWG2|fE*2;iE;KC6@Hsaq!^g}YZo(Y}paq=W^XdW$E z77_t+GCaH`CMKp7@DY`QWc2iQ$6$Y-HvieP=Tyh1Hp%CXoI9s=&Y2z2Ojmce_z%Fx zGYbo`w&GeL~jx~%u0 z{Xz?Fn(&9C@9!Io*S_|as^Q48&L>Yi7rS=uj$=&lgQ=GmuWewIm@l&_4l(rrW^yY^$sepHJWEX*)2 z^EuiD<$F!(WFQc={)Huy3C4Us7%HPnoFiVJ19YCFN^vQ;7o=QQ7c+A+N<=toa=>M` zI=NI&c}{q!L9aIR5K@{ShVal0%=?WaK1+@J9x(#5Gb>^K=jmFDb!^-np;}k zwX%xrt~oVKUc4}Q!9jW%7W#^UB=$g_Es+xn1=Nd)fSHnvY@?>8X4G1E;G(_pF}G6&_ZxCYDPjp|$0;1dB^$FN7xKAV|SRTbs~V zI}F#WC&p*vgTMA$ava;Y4a6V(-Y1;N7VBdC0s=tJ97oTQB(z6a&%7o+_OU;V!J)yJ zo|;tlFPoH*K8APMi5gWAX*dmG;+cZFm{bdrxh`8k`*L63fE5?vHYAC55j0bWS9W@G zW+`aMT!6g)RD!KK$jnJFlB@tRbu#1x64z2i&{D}ph(x-6&r9$e1ecBNICGYs5iGqY zCB(U;Yt-1S`+UywidAbzM@KXSN@b=r_>hv7^9qX+X~u(s6l?SFogaMvJ7WLdebKw6 zKaH(6N%H*pu~=PSQF7&ZHn|U9w_FVbGH0#3x6duaYG`&~nO}EqVrWrMCREfh)+QhEt|F01juCw2O_SWlMQ5} zosB2KLDsb=8zaMqR76`K$Wd2kmr6z$Rn-sciqesn;@;|djEtPsy-HawNgYcyZlxrr zLcI>MpGph0wQ=^$X=P+&02mF#ZD^xKxQNf`@9v4`PM*;9Q*L_tsVBvYKqG+Xh_DN= z9>bh+7V45kSuJ(bvr|>A4({DD;6*muzZwaIz#6eXpIx`x`g;_@rw?tAW0 zpFak2eqk{ly#KyfS+zzzqCz>_U@d6FWq*3860-w5dDQi2)(q~916=mEYT%pNw=_L* zeol4tMFf~yTBY76W__b|@3ZmDWWPLs$w6x&u6egXyJV*E*cyP9MsL^D z#v>0uAPHQTZ_NC5@ZBiGO7OzjkTw61Q|`qkzI49vWQg$1EhS#XOp!&%|`Saa4O z3v~&KZf}d3saZK|v{cx`IAdUKx=aZC?Q~4|C1~V1@m$pzLHUFlZ5o^eIzWWuvPhD!5t|8kn@g)z2c5F@ zl;mzG{^?WgcXEczvjtJgB@A^_q>^?X6!#xW6PZAmGHmUrtaYP6gaE{-Ru;O;U0Inp zxgp}@;2+W=-_Kf{I`N!!3e=J0Jwn2$J(x)48RpOTLSX&AU-_9hxOZPP$_5%SV1J$; z8*}M{1Uz+hh>(r%N;8452Td()F}P(|_oDAf!`cW>K=<&0BFJZsOA-pByUT$PoVK+X zJwF;>_^UhOvC|`((wu$BO*g$bNoUW+i(YbVyz^(?8HHEB3M9c$g))wcC$l-iDr;IE zhlxyzn}h(S*#$79c@PX*!l}#Ycsd->d#+*Hsd^EC-xTl=v@Zn2zEtTZj%;(>ipD~aPrG$^XCa$dg$7y&Is82 zY&H-7flUmWL!eS4%p z0!uB-FKd&kwpK&^w<&h--W_xEvoSq|9>J`JX;A|vn`Y$i-0V!6&(R=ZLXu4Y`)!24u| zW>%2oJq}z@T3ix}fu;a`-Z(W5B?uVW49L<#jLc=MyrwuWXXw`42L(g^Hczh1Gc2-7 zqsWtKQXzYT_Cb&Y)-c2SI6%&+&Qn71l*LfjZ)}XakAB~6UexB*wn^E`9Te`Y%yq*Z;=XX|1c2<*j1cl#u8TDiN>x|X{^h<2%-|)kZYD{(geGHNUl(nZ#1gp| z$5aPtQOSbsgAh8^kA3za#F6Dwo@CET`=F^QmJt5Ip>?Cx;`TXghR_HC{WLQ~@^37b@|~A9z=EHrMNUb$9jX?7-zgopEV}Ry$8rRo1;;j;Eh_E?V2$ z#bts#h!SJ&uF2UW&*Juv{7xJ{eNMLQJ@5XRICA7tofV8A0W65s6OTU`14DzcZQDR} zclE}v|K{&R8IH@!lF$>u+Nqr{cP;5YX$MUxriAbkv6)T`kPrt7o*GICQ}y~JH=oy* z^XufxiIE6)xmQ0sG{N(3dE{E8L6gXb4jf(n%jH@j)rotPM+V3_DzZr011fRVq(M{Z z^VJw*vY=}d9z~F+O{!EOLBJ#gmk5S9R$FamiTBM=Z6BtT$nEHf};7MpFb9TNmL2F73;dtg`vSOOtr?JcR* z>ZNh}!bF1zE^yR_u6q@@QvN8Uf#9N?qU4zyjdFs!Zkx++u}Ub_{(4xccC)w+6P6R<5ci` z*xUQNmaOL4C{RuGPF*g^qz9Sd8FGD~4?TSYayErFXg@2_GzK8#fnYc4kI_D_`t?Wxu!STnNP^SQn4MjQv_~&S|$~m?Un3*!n%^ zZf#{yENo!>DDb>^TW@3L_q<><=4OVRq=|idV!Q4Ntov6=Y;yPpP8sgP*a&K zYqz|N;F*c4tkL-7L<|iuCYyCBJ%EUvy-xhlkN$Wd-8?=z6d(HWACr*NrK^`?n6c*r z{j$k_@sW>;=kcnq{wj4?{J{HvJnp{dOe|i%6`e+MzY-CX9Cfw});?zK3c;-!IM0?+ zB}n3#GiN=)H=%u%#JWniCiU@EXhH=uY&dNwX(b*H>bBiAl8P%ZUR) zeMf>&o@vDSb`gUAZ>mK0l1E<{?|%2+jpN549>UMzH@)%fv(LDrD@R6`KNXtLXvPd> zhH*4sY`^?D_PHd1M~@ z$5$%|$)0AhT~iX6fCfjv0u}km&=%x4>X(okQLJL}AMI6S^4_+pXC|Dg*Cw33vbHKm zSgc>60W$0^so*#y7^8Zv%LUwHWgZxzs&!R)fzRf^yC!N_%;SG8q(e!;2hAIr@&j2c z`rFp{w&)3e$7@+@U}RuSLvp<;bIr}pY1oe#v<(LU1XM?l9Er`%9ew^0CbCV<#LZhb z^^DG*IjxMI@&r)i0c$31MnilAco!TRN)XILSYBS%CL_?H7nt`XOCLswb8<%6HoXI^ zQ+sbO&fIxd+`N8WY+CFG>s~}ZIt|v)lHY5IRll;f7VB$FeOy)RRdqqI?lljdd#a4l zYt@R^zUFad$%5}R0ExP(Wrr2CHXCvI*^9BZzS={9}x%7|2WNd~jZRMC-sKXAFklDeWuEg4+}vj-lLeD8e^YLJgm z8VNeJ^qeUTC`;9h5(j5SAlmWKkNmkx8T_7r$#WC-f}oVZM41-gg;A8PxB^I^_LwnApGg(w*c$VF0Ah@i`{|Aioq4cOVW z%s=*2nnXjxYU$^Eee1j57h@Ci@!$jZ1a1qRk8k>>x5wkJeO)xZ{_DTC!-OgXK#163 zvSSF?^c-fOdFfM&mw@c1GYRVk_(6J(JcbP;#JEi(2E31%*pBoW9721I$Yxxq6r-%1 zrHm*KDxD8J)Rnb$IXi*?Lq@KTRc~z7p)rKY6fx-8c~F8zg8Ng~n?)>Plw!T|`PKk9 zY`3Y_Majm7jVSlRJ)lfhq#;2_DUjp|f0kLU@wBQ}<&1MVW}rVYXPFi5OiF~koc!k! ziAkek>oa9A+4D8lS_nfL2RRHfbF!RLrlThrB3BZ()ST0hB7h?FU|Ce|CHvjD?{x>T)uiWW@cu)8KZR%a!OqWd|ZD83Uys~p1o7X z+k!tP(&3~iHITXTyq=yhcH>>G(bCHz`-K~NN&Eczcjf7Y{tX6~_A+Cmgy zi_=T5QXB}4vx@3Yz`+xM0duQPKJGEqtZO-Uo(Sjfr7wB8)F09DFo&U?T|i8Mw0$bk zF$Jc*z47sn{iUt}4h&MY1SSwD;T@3qTGPP1g90%npj+R<#hvhjvqD1yJvw zotag(eD_^vb+*^G7|>;PJgdZImy+xQL3c}m=FP>Msq^8EClQSsO=);wKwUy{OPL^Q zWq}B}Z94$U_hrA8K#cn06S*t-Y@Ibt&m4#=SFcGJj50cBO0wyF=oD*r_ zBx~#e0tMF5+Bbf_1Q7fTl&ba%XZ67c9_s3V6!X5Et;mFVUdtYexSdEq*}V#u}b!>7KQ)^O6E%DfidE6h{Q(y znd?#pKA^QNQdLR4R_{JWOQgVNqpQVV5u_m3BqFl;jTE?sCi$6^9i|*XkW=+)5s>!X zc4ShP+h;`TDn3R|1Z0zy@iVK|WFpt#X$ON8Y6;nT9obZAK)|}@ItZc&(g;XYE=m}c z8n)}mdqNxpwaeL zQ}L+Bn`pHe%S(&8|1u~AFV~o80urtZJ_Of4nkbAMsMz6d+2uK?RS<)kj-=XUd2jZf z2W2Jv*+%hjOrI^X9NG1-yLt%p*tfj*3t#jStxaXls@W!)uJ{5~+gHcV_I7;iul~E% zpT2h9+c2@qQ$WM~+uaC!R-Nw}4C6Dw9wUgDpPLWZ`;ZNBQaC*C*O1C8Dw6B#+bXAk zGP1`M*lUj(vDw@-J6zKpTa*N?QBrVpeW!G(4wLXmX=Z8Q#EX>cvY~lKtQ+fB4xC_1 zZG6RP%5lDQ!Vo0zx7AZ`0&p|7_qJoG-&_{XEj9yL=CXGxV~VTc>8ADbLaO*|rcLU3 z^!CQW{1IK-bC;jfa2>jRPTz4hk=KZ~zWMQZ;qxE#o{dhNI(1rsDnqOm7u~TVBq1Fi zM*Q5l^9pQvcKyBm;wJD9(7Qr9V5~!C{Ka4SwfOiaKBM*f?(cq2Jod_$$JMJ>wbrLj zozTFi#hc4QSDw3aBmV5ee-WSh_z|gF&Rb@RP zEhq^0#4rBJuSf6Dn4b69`MLPsAN)trc=Ojj-Vyw&h)k*yjucg6X{$~TBu(86Ye>xu zC=JFePNwRFHkKCOQ4M$3#?ZRZE;gqI5an>E+cI>uT;+kr$%$~(*RN<^q)QBL1|n=gP!dR5EHGrm(t%eGcS57Z zcooS>M%l2Wl_5RRl1NY4S_&xnfuR6K9iQ(WcWqvTCzv_4$_>=x=}=g zz((mp6CX!LfmC2_ z2p`=Cx0(46L$-bX^IxR3afuI7l=pwtT*c>sm?*YoYGyi?n82v|J)}ejl>}!VVa?2ltuB#~`{eoy zLRHq&>-*Z?vW^1Jn=kATUyMxV8YqKuwj|)RwXOT+UQmz(jmi)_%MJUwW+PcrVUtmI zFy){HM1eKux~pvw$IP=8TRh3U*a-&BRr_Oc5mb)JfVnzQuz}nQ2y9I+WMnTvYi&>DA=!v!U-T2%SUy4tE>T~hA&wn;% zr>BB8ZPu8*!x`OVeo2<1gf8Y}O8snTSo>7G6AhQ5WVRiTJo1Q%<=rvJ(w`Rz&L$}>ytQi;2>cR~NDlTiCy&$dbt`Y$7BRf4E;w@NkoTa&ScIP#up6Zs7G zHA#`43!?y%^eQ{3skr=|ucyiy`H?QUG7ko>MDp{lTt(8|d<8B@JgPjS;@tHxz;LMB zS>%#_ss{&y(|Y3l-~ZiuO_fFF=jPNhe&Ok7;x~WeKgA1P^kBU14X;&F36E-aav{F> z`7cKAz+gP`g8TBG+{VATb|aoU|7Wqb_^J5sAH5PI<2&*C*E}yCc=UUs-IQLFSRxR56vo39DEyJ zcUDv#661g&kkf;Rl4QZ{gbmr)70@Wc%MuC)0@bzBldt|;pmiofihZA13HQlp)Ed?4 zY|+^=*Iz_7HWW@;od~ebMUZsevsm94U{C|rzF=r8Nt*vqWtFOD)nq{Rt*@@=S#*(* zBrlrO>E3?UgZF?~ds?Nogj7VP7^Z>&6;TR~D%fG(ZRh zLr<3FkTnBOHQQ3Uw61?0TAU#dj`x&kO_n8!DbC-)2{0t*jCX2!DsCZznq)SduTU1P zkGnwl;+_dMAZ8Kt@jHyD;ZRyUQN!DaQzuSH3Yh1mdU|$~xCCXwE?Fc-LZz`j)GmjN zx@7r{5(OL3tSEch&fbY?t=Oq`ku z(ybt1f(WRRpM#M)ryj4~tNwjC^<=%%vWpGagCCO8>jhtPy_`kX)99ZSEZGa(6Td?M zuAB{=8fm^H+E@ur-MjaQGh6mEPEbjKf<3q7@xIt2k}38OK|I6g{^nDkPyj@`Z6i#G z6hz%Rh#&cp_lc)Na7Nkn#EBC^d*C=|?t=(dK}_#Q*WPe>W~%I48{vR3X>aHvHm323+Ub`Va)WZ)yVvT@;@vFZ-_l@S8NXW{nk(z2Lxn;(`8_AY^kRqb9 z{kos}&gYli?s5ilW=uD5D2;{Ex~cAnB-EFxrT7i{^29~Gp8^oH4a`^TmY}Qjke}tx zwmiF#Lye1vtba2I6u1PE>MkcEiTQNz)fpA?6;2XKB-Pc`0}3@C-}PS4n4z6`Vd1FT z;d$nLjp(4IanOm?Ri>(r#1}vJM11(KKN$}^cu&0PHGju#`Iw8ioJ` zJq|c9oU>U0d8_PzE0ui-1D?;k59P zN%Q`yog1puFb+_GRNk}nrpYkMtRXw??8Yz*a}CpRHmN#4YHMj)AJCq89d9}8F4u;m2XmpB^<%=4Ptq5(+|wpt_*pIo6HRL7^@fP=3eH z`5DlxG6;>S9n=Ar(~?k-gSg_9@XT>~4nX#F&sv{C3+T&lx0E&W84T9}auooXTJye6 zVDVl(0|ir^j#Ml$vYZWwqzZiLqaX1c4V)=6915WU;=Jdc2efx!({Qt&70R$D&RFo=I4d9j8V(RaSEC9ggo9?Tq5`oz{$yzu?itjf0A7Hj4BZ% z!`_E)BKM{9W<-I{BhbTu$v(&_ui0=84!Kii7X)F%1X{G?x3?7ZvR>6S!gJ*;;1n$* zi_EU)PH+wh{^(GkzRNWnl7t<&^K7d;z!@k#2L&D6cis!6FA;dFQ{*-QrGkrjAD3!O zgjESm%y*w>fSOA{kwYJXO?EB1XO?z`ty{JnR5gWB+DK|FE% zxRBKfXmIXDtgb8?WujT>_IYed)__ z=UsQj$&;tLZpj91PmS{?Pun$ zJwBuONrg^uk6a7i7niO{8XLPUTcvIXi_#&7&udgt1!*qsfe4^NjibK+03ZNKL_t)C zL%v@6k{8CC-taYX^7M)5?>A~{TVSDOw`ERz%Lx(*T5U^rT|T&TKYf zYa3mYf!N;MicS;62cPA=TnMFa5&!Ep(uZF7@@RbBTfeqb2Zz31sqBe-VUY)>D~b?8 zgi?bnq~}dWXGjudv5n1bL*b(%8Ud?04$@E{rf{865C;G~Py^;u4(x}x}&8Fx2sm=2M-GlA&2|p)r(75W10&#wdng>0tj^C>V zFhxT6Sxxlg&=Pf1yCIPAB(;qk!sP5$nObFCIr4M@0i&I5F~hkZ)>gg3_>ye9aZT9_ z?{c)2bsMhFxe0xq)QF+Psrf)0mJoO!WvoD;Id-*3EBH}4%JC6*2aHc7oa!vgSyGRN zdQ33>7Q$TXKy^~LMOuB1%!f?B`rB2fOKt_EG#o;SuK_%eallHt4|z9L5V;CXx2k{o=DyT596?@4|9ZhO*vioFO(sq0nuk^ zV-HaBe-i|hVX0O#I6i!_eq4K%$3Sh)+<6}s&pd@3(goqMYUFZsxlj1}3+KP07D}TA zyK&;gaXp)w0_nCchPoLs!7%XJg@t){H!;|ZAbD(9=b6vN&@uiUzERcVA?|S=cPJ4} zPUXx7& zRJ(6mdB_;t-1 zk_jM6E}W9BIa0D~-ExQni`!8Q?#<Y$HOmpMKoUfn#VdAYlL#}TB@D&_h}|Mebkg2`0(YmRb>tc z!DyuL?6g|oluZb7L!aO6e*8D(1u}kT)cai$BR31lM+W(TRtyMby$T#QH`ZmeF+8v? z)pI>M+GX3?;rV(v>_FChmg+@GII4^vghDE8d3d!^vV};7fI4yZ(ev;%J3Ob3;c&=y zR2NE}c$Fn27~*zEGFAd9lk7@h#5H0*%j7fypSIeGG_Dzvlwe%4wcc()d4 z8RcdYi@hyot05}2ljcw;i43Lk9mG=%46NfSKk!^&q6>0vnw(j4DOmd|Ly-NA4iCiU z`gZIc&?dGmc}|fM`_Q0(ptLTy7)J!cbnDilvJDPqwM$i2XLUz2`iq%PHs9(TDBu9K zvD|CQf9pLMQ*FqeXRI3kKyoe`Juy8qtE`-%P-CbTw%ZE8$bw+qqult!=RdD?I&$== zoDRkh(kyjVh+PiK9Mlz@Tn1L~A7!#a3{*q!Q6RwQiX=(dtG7@4i>K}E+4}*REYj zl{vSAk%96>Hf>nG6La&^acgl!>Td+z1Pq*oO=&hjv^yO4F6Bu0O{k=1Tcr331Y(pn zcFk+SF%zh+txyh`)4YPZ=gOcf03fJThQG6|5)=WVI#IG~g4eCDt|}u3E!CM7Pssa^ ze^*JBwl&TR3kXYJ%f z%sz;Bzxy3==jl_rkHw|sxa;hh7#H+SASp3Oiy|o zv7DDP)4e^)yFGE?*(>o+KlCr6({9D%uX{Xx_rLwOfXqvx!Lz}>5bTbRO~}bnWB2HH zP$JObzIgGAU*ZXqOG{Ggd&x^5jlQ0mL|b!g>^N^n6hSc_8EnL2Yd01 z2OWdtSjW}1&Dh@95KIr!_Tq(^SdL~a9Z<@4S;}_$(0LakP~06k%M2jo_Of$A&sPYu zNqUu;Ydt|h@qL9bv|R3}K~Tku;NR?bcmEh!aEZ^{iBu*~l0eJh#pli|Nl+=C(x_$t znN*IwAZSq8P=tSyOt;*tg<69PA(;~_M@$TY939Ay(2;QOBhQcNxg*h^;|WOERetIN z;fD-vzlG4B=4+sVl6xQ9$Muhof~s0s(=F@$CYE+u(brGC0w2+e7rpEi(fFo!zP*FP zDIpRDc&x3js9ssHj>%*|mUFR9M2`>8j+hDzuKWNppw;1rnZn44L$KRI$q}~Tdw6P zIM~@%`xn`rG6Km2yZeGnoh;JuxZ6SbohCIRwu692s!l3PZ?{ytTlB>}%KD%09D{#T$dED<%{PkacBnF2ErO~e8T{%e1oB-FG z34}cA*W^I>F=XyF<Z2`M}0SC+@lX zUIouruU?72`{sM&H~;Gs(P*LwnM#9_2;Ykj{gV$UK#>%5Pmh9JqgRw{=`t`{A#PUI z&8cR8?$b|rG&Iu8;Wkg6Wr?#%gN2gI&bEH{E0LVT; zEJ)=$&{T0X_TtF=5&dpuc_r?=^X_=~;fE}uwdZN5#UZh?Hlk9FnDaEfyB0Ge1984F z8co^zo!DAijmep*7@r)Al~t>AQhHliUX9DwuEfjkJsWcaLvg+h!O>{8&Yn1K?ugTM zW^k@DKxWX&?u)1>(jiOi;H8j+DnSvDaQ%J#JjWDPa$cPrlI(U!7`}oA6OnJ50GwPJ z1^g;e?#8)uU)Fc*5docp8cR6~rO7AAT)9T<=Kw9r;_-&w=INsd5v~VQh{dlb@pSo z-Hc{C+nzg}_~>u^U^L$Oj<s<1zu2Yhoa)`(l*%Z{HNJZ6hCkNRlXH1l@ zT0PJ{Eka`0Qfo7lUt@*o?aqV5;ljCaI3>B9S)HUcsS)jY@|s6Md&rEKw}`tWX$Mrm zFeSt^3tM#i=0zm)<|T6_19UcTDQNDA1I4E1-`%nUlj9QdreE8`csxapzd_0E#*OP9 z<17PHt&8rZCc^`PsbMG@ki}Y2OP!ohI}`*ZYS;9utJSE+#0s+Cx0Gsjb3n>c@N?Uo z3LHKLo>my^sax!ddll1ub4$*nrkhpU5`l&y#}xaq&=rTzhVt5tn=+(i?I0);icvp) zD0`Tip3vtI$nd;z9NI6`{Iho-qcJ=P60|Gh#X8{3Z!Ipxh6I&>M42}MVQaSw-#ZgT zXT#)A4K7LOmwP1m!?BEvk1E?CqtoCRGFR2%57b^M7BbgGC&kL$xHAM3cinTJjZ4+evI*C zFL52fq_ea0CZ4K(+_A<&vq$1QAQ9?p>F*P98Kj5LKp2WZR@(L{CPmOp;KE*_bif&z zo0${e2K<7I2=X0)KEbRctw+s80*Pc_fQWED28RbUc#Kkn+8-&=?eA;dfoc^nz}Vm1 z6i0}M#5w16tKx@P0v>yZtxy1#LTJTjsj^OGks30V1klR#aYPNAbGs$^amH2?B)sZn zN8-;u@?7-v4>=A`2L`MDyWacvV}5SREu!p`xjF4Q{w-qa+KOzgGgK=Iwhs2i*LvcK zFUH)$yn+Or7UzodMu`guzevcHtbFlHPsac8GryueBZsQCLxi(P7_8BuNsCJUrj%GM zFW*x8>!}lGv}f+S|A8EBY%;lZ2Rx|gFhh5`uJZ{$WNkU#{K(n(=+bt4{?ngPf&yZI zTN@gmj)h}$dZvquHx-OO^VGR`_};tXp_%D;V#o7yGVC}c7bZx~eanAj-QMv3ZEcQO z7BE@5S4cv^^P2oCa;}vYy9&ob9?Ww>i$EcMjqy%IqL7^`FBiGB&@F5$<+bN7U5Lr? zG5Llh9VB&F>$I(R*GMNA7uj>{2dQYi29j zdXAjhX6&jBo&Qqrdh|3qG0^D5$s4XrsZ z`}n{9R!@QCMu}Lt37lWm`c-d}jPIU|00)|lq4CM86%hnE!gE$UAVoc3juFi=!13+H z#+KWJAa3ALaBOT4q9aK+YjUIOIk3JtBziFD7xZ&;J&G`=bih4IT7!;K+yjys?LZPXGpYpDyyI_`opWsTg=Bu^Mefn;JEBFb6 zql1^QARE&C;*6+9q0jQL1Pf%e)X_0W)eg!1nz(3vd-ZB>ZHk%BA?8_-CG#HYgO{YW zc?Lz)BO74HaBW;S86pHxoRIqK)fa2nlF#)u?rP0M%1ek}5HN(xlpkij;G6Kkjb7|a ze9Nt6j+FUK`sjgQIWRccQ7@A09DLa(_?jw!1@z!+Olm&u8WgiP9wpY3Bn0 z(p9ied!mVI{4LkZI%(45LB!g|S{zwei1m$CWdU|T@F$$Tf-sfA<@uKSCTnImoRQpq zel7{QJjGt&cl>R2IFK!~XYab_Zmnz0d62Qo0br$xQJH3CO@H;5A5mbUuqnsq-n_La zBT2T(a|6vo1gPM8_C42z!>kFRh3;S*xMm0IOd9nW^;qo?sZI6V1{xlo4Z;0+-hwBw z!Y2Vq@ctN$&7B<~TtyI6`7i7GI77-1&t19{$B!MA1Ep(#fRR9$AZ=BxlFgW3SP-f~ zmdJaF;MHiV1EZY0f{DRFmH$MPtm&_6$#p`ZzZC@SeO~0_%HS2C1BvrK1ctjfRilU+ zOI>Yq5vtqYeb+s4^X6i_@$q}&KmR|Uj-FoI2==-CSWgU(48)KA@b^k2OQgtVQwpdA z(@YZO98gk{Sei3OLRgF54r7{wHWB{5oZC1N>(Z^h6JCopFh`*^T|DcC~7T4 zCfZ3G{nj@WGTh*WG>utt`_Dl3DLoj>`n?DRmVe# zAGz#s*a1-c)GE9GQzu7q(YgU3d#J>{G}#wKYgM*~Za&Tu0RlFNwFKtp8IdSRPz?3n zjV&plZtQHw_+2lK(=Yy(=rqUTfRd2*kCBl!5z@|TbU;e_@oOVptr>5$h~6g8u~%h= z;Xe0WsPxdLtD@i2Qd^x^*Ib68jo!K&UDxCxM#REN&Ns#r~ zFxaVh@*6#NY$e4!CQm0niZ-Zp@|4~T`?^M_>t>CjUzqk98rol&EyZiRCxt^!B^hrjAl zs)?%Q$Wd&y3WA(atHWvYML?zDJL>VTpv%Yv@H7N1f)6qz5$#lR+4aDxUex3$%OGj% z)=NH5$O%K9rl%F;6+&atDGy*Nwm6@QqvNxiz1FS=c@S4XB00lyj{J=R%^fBSvWC`l zATp(8jO>8GvbQf;ylM$F@ym*i?nhR)g^al!6^@L64C7Q|TrK?J`xMDG+W^@QC^OnY zz$P}2gX;w~Dj1oA$siOud0ZRL?ue`{dK9uDcg=60g|)9Y=4a-F06{F{ewEqjntdK{ zj4H*fuIM?Jv%Lys z{dlJOoCrDph53cJv3RQsw~y*9KrnS6Nid)@GK9#JTlU!NoasUi3$lmV4boBk1ilwS z!)q`=hl8_H5%%`hw=7ABTh!a1fj0rL=W$f&Vq|PA&YZb3wl}t7VP-fkUcM!i!6Y%t zMT&-$1%B6ezB^{7+_Au!CqSQ?n9#aPBSK}MmN*4f?-#+X-Hw}!OLAmR+(-m^V`6+% zDyMWQ%+1Yb3nOqlz5ku~>=&MjU;L&2EBg8%E~1<{qt7OBnVOi2J{%25E(t02aco?? z9+UxT3)ecOU92-J_#AR!b`)S+u+;=V?A!Z>4&r8~C$@X~qGxYAZe6_^t)9LZXz#?^ z?m8KNerqi*ZMuxM3JNtk5|5pjk0&)^~GnXdNtbj*+~)ut|z zXjV~^i-0{SEtOJp?D7|q)F*pX#aB&xcEC|`;|eUY#9W9>QU#N%V0%W=>A=I|2dpUU zz@+9FsobDI&FH1ZtRu}#*U#Qgocqet(Km5CPQLu_MRVkYN(w@7#D!~VAk@;OCnKKy zm=sxO9(p{Q6DJjHh=<{Jku1%06ofY^9j`tW2ix0m=L=pHjRr!6Bn!PN=^^32vE7QT z-GlhOpL{$TZ~MA8cBlbU#|Cm$uXfPkV6hyWe#sPb)5=uRP%tzIf{RIJ{eqB0zDS6Y z$PMu%hFYLIKp8=Sh8%!1JWaooiWTBAgF1Mi6#F?_TY@-47<@zTI2~tt{R#xsUPlH5 zyrvqFbpnVwxerI+)PSx34rEGJMlIYN10xJ}Xr4Sq%F1W*x3e>Is=;%x<#e><2)zu7 z>?4J?{$2-2sn{o2DK|5livXik_qax9oR;v#0m(Sf(wTvPpeJea?<=UPfldX}^B!f` zym`$RU_IPLViI9Rz8GK(w}oKbbI$KDYQ^F=@&NhNv_x2J?W^sS?*;3sPOt3F?TUiKdqUg-&8WBy#Xve1$0MVx z8n9>FS8bH*Mfs2Spp-TxDJyHEMzU5fj#uS zfBC7WV|JFg6y_Cy63|tJ%@q>c+l(96uE*H;Xf!ElMa1v_;fLe*e*eSTZ^w==M7y;c zcbqvB7tUXE(4UA5cJRo;F~RO~%y|#IN2#l-^B_gO3huAzjJjSB!>wC!Y-}vfx0@37 zB3MPn`R3xKxMzGUUUXzC{_};!*gxpRi>IgJ;hC|xvb!Bm?h;s7^91K*Qf3AU{Z>v@ zjlWhlg|sR-FiK{@qT5RX-3|?pQe-US$x$ zwfkH~@97&7Fc%{~$)Ej>OD;uZf|N(U=||h#@J_x_m0Z zuHI(+^7~&MjW@sP^&RQ>OBJq90uJs?_J(9*2!4cgrM5;t5JC3TPW0c1ix|FDu)u(( zO~_Jxsz(nn-gO(J;^-K$5MX!7C{s_(-eXDIa+vp-18<~)O%LKgjmHnh5NFLtumYgl zEuHDwK_VKXO)Tz&H(9amVdyi(kW9(53{3c9Rt2q>4AR-$T+d9;-2m0{X*z3;i%u~O zGf3S|Q^ZBqtk$bGr??wZNwd~L5#4x@JOeUbeumMOvCE-5;wm6j3q&oLSK+N3l}07w zY!wJNfO0((1jqMAhVQ_{x(Q;tbg<(s2^{oz!Xt4&bBg?B8Wm@!vWDk2wK8@DY)5X9Smht zb9WKau%bzv|Gf;w>>!G@OkI@jd*rj45??qs% zC|!(xvSj!2W0c`;V3>IZltK`_Qfnz13;mWrMmvD(s5NKLbGWTF0>4D+?7AnAg^`i* zIDYbkRpBTR@od=Jd;8rsP^t4Jv1)8+EbhMhc>M7n*#W@Z)-!_fEb^UOD@_<}>)LUm zB@EWDIS*)bxD&^ttIh283=;=7AO@@v4oE|<4qDt<#qV{pJ635mUxWO8?OvB427x zCphShgXTaq`zfE|4=KT#hd`pC8Ar6@=j8RyG^a+Ilv&MTe=3hnigRADnw0*AwQ zcm_CSpf1V>95`TFzEuBaa8c?UV5kI_=gNgTt}UBWv9B6D1SXuEryv?~q~=U3BJgOz zpk!ATaY_*sWvCsOR|ZPkpe5AFWIyjSGIkRN&G&G*#we9)pc)s8v@UH|>=Bn~=&k2@ zVWzadavEs0_;Fnj$Y_Ne9`OW2O(f-BQ-Di^!-J0Y6oCu($zGv@r~2AKQWO}C917m7 zEHCTXR(Aq{7PWfzBZu8tt)E?$7x-@nd*)(DXe&bV5OCNvS(Uvu%p}idPu&0TgR#54 zmts=vS5*C6{^IO$&n`3dO3Z9^@mf4{`Pmp7olqH&J<01i2ZcIOF5qt{N+Fo&oE`;2d&uI+=!#QTXFwHf9$pQ z<8!Tn*cu*ddHQCwPjF+4_8+``{an9gwI$pV8XWlr})G89*?GyT!JnOLvbc~AI&%Ep=51jYjD72KFU(lbH`$RpZgC_S>`z%n48g# zp4dUTihzewgc6Wu3{4)1cF$P!z$@yB7>M2YgP;G_XuR?Dk9TCqAme0zESZy3wT6H+ z49O9}v)MS5Y&PmtJ7OYdT#y=+s`D_3ZwQH3XHtTHA#Ei*Ea5-r5CDBZg1?G2JeUtD-^alRQ1*r)=Rr$wa!nWkX+>;pr4Bj|8YtY^o`VQybu~h| zCOE1-T^k~YO=()8TCdzDq#&o83rIt)CP3Bu!Tgb6NI1*gJgb$ z1*m|hsf$5GCG%FaE~2Ur2&EsjsOB@r@KfsWYzto>`-ODHB;& z>y?@PW=eCNo@ZgQCC|wjFa5mM2H=@M>?61pq?c@PPzgTYHE<7^5~{Ga7W1_5qT!L_ zwAnv`lv!8qk^R%t^z_s5F{$~fcAn3TYb=cjAw?*J?(gY5&_zRFZNi>2uPOx*$kiMH z0t8-HGaPV)oIUoe10}iuIPgO;gk#;@jOV}bg%UM$X3xPknp69QpwefNz^pf}U4AyG z65Lp1pqA^O1nXSarAwDI#Em`0d1Sv88ISj0UEhdP$4|u8&ZamoJ3ISAxGGTK{&^or zq9;$BP&=~9H#m8<*_s#P4wPO6kz$ee^vGtYTVc{Xn%(Uk5tj+t9N>7!)?!Nd#wDqECQJN)`-Pm79 zl@KCG!O^PX3QS(`MiAPT3o$)Js!E^RNOr= z8DH83UT?&KI{i>N2VB7_D$uTAh+XzY;5KA@9rHvMz(k zw)hS1&pyNH-g6hetUZR$nLBz)ok!LF$$k=vQES&cq!G|Y+iAxBL2umm@I!IW19!#I z*|9i%>`0tBHW`h#zU7VT8Nuk1IlF$=RCWT77H)tZcpFW0%LjWixOQ4B>uc9<$lziy zszd<CL^iyN2+o*9*GMk=7U~Z#H)p7~vqx z@up<&FbU5jOSf)uzco2hP6#AHP^We2J!04#4s9G|((NwnTOA2pKS7i?y|c{9#=6=P zsy~}RD$N7J^2`9pa5QyKQqQj4QYr$b_NZug0I(U|gFhnWKHl2_mvsvW=*Z@XZpm5| zF!a{^itQL39*ynYJsIXHnAAvv-WF9?;KP2QmMsUIt)~P9LOu}sNJ1w2v$8ssK~f*0 zRQHOQCTJ~du`X)tufaE2d-(37FiQH6UZBaY<5&oHYsPqcMW_? zrA(YIWlJGygM&&skh`sOEb>^2qgCd}J|!_>jW`paBs?e72vPAIq7>EJh=W!~0fiG7 zlVxd1BY=QtC;OJLKW)35Nr~=cIkOyzOBJz`Av z@{&tm%%+*1UWgtv`FTx$e|+$VzE}D%7?f(uq;$fUGUG(n%9*%S0@=-|;9rlcrs4U z&&F#`9gB}FfpGLhTm6d;6mBmk=)Z3pb|%Mt+x1oO;GD+qQ5ikw-ob{aMs|OnL`icS zZ2ufdD2%j1a3UGL?<_f_lP|QR0uZAI=E>D(SCZu}5ht<^IxL8F&@iIPy_;)NL~Hy- z4vi}jw+wpLmTtw$$}Rb!(TOPqswA#lyZlMcl+m+S1)&{h@4Y)7dFbA_|NcAU*uu2h zD}`EgIx#!95RJ!Q`)bKD1C#FVP*1GsjS#lXus1|cmI;Jy0U~{%#sOOyk1Rwb3Hmcr zr@wdrz?h3mp3uibu=8}?xP+G6XY1Od33k?cH;Q4_Wx=8%Mv2+#0Wzw&(0{L%IX1Gh zb#+!`q)6t<-!iLQ1+vLydK|K|F6 zKV^MgP6gSRH2?|%WAjzCUqJvHgCM3dGTsxT%O=#6KOre7VmbR)kVAQ;Gy~Me2{PmB z#z9F(KYRTP#c(%;Tem0$I4ecJ-=rK7#s*DZ)TrK^r=eP_95@6+4{54V+8TQb!7R%o zI76P1g1jv8@H|nKO|v!pUMo2XsJPAsWMr;#k{U>fI!ahuE>MB29qJxN~tzd z8?Nf)VDG_@$H-&wkpd>TGfZoVSILJnb+KX5tCE*3Lx@oYiBPL$mQ2`KyoZpGs^T_|f?Er$5u>fnZ0^pZki4S8#>Ybuct64Fv8LgplB!`$eyT@)>2bQje3S3C?VB zQ4qSifh4011iULv0%Vihje}?c@o#U$y4Vqpt8*VuDAP`k7eC^I6NZJ_(D_=R8m)wq25 zdQMaIgv3H_ts?3Sx`rodW&q`og#Ohrg1X|)cFZ%L{a`O<$A)5);A(g@uG5W{W3%b1 zd%=qyjgNo)Q`$#wJ-rYgTiuH`uzD9AFmhPaA8R@*H%($9UQ`C6T?jw#vDz2w*;lYZ zkZ|Zgb5Xjmf>BuqW`{p4#KcHYDmr$hnvG@@8sY26`3tPS#zCVK zJq@2BzG`Z)OB_84#6`$jbPvd& z?V(TajL{i|hd|K^se=qGoD6#m3WkHVkj}v#a3TBz8%9e4AI>!>mOX~asDOv>Y^<+K zKc3H4rkK+ak^bCo?Mi3CT?U7}%67EWU#)7UP7akm=y)($&)KwLY-zwV_8G!~uGjMb zTY^=0BdcsTS90#Y)ej5 z_h|=>(=r0*I#>zk;0#P&^ZoBJa3x#KBtflyXtG2T)y#eHH52&Q5LkBGT@8kTImiSZ z7PWHs#Nl8nml;a$fI}!p*Xtnhph3jygT!^#^%TL3o_1x73GuSWgq)=Fqm>bHANCvp z6bJ@r7C~NR$H2;<8yIhb3WDJxKx&^PBbh*jH7-61YsK~80B_v7>Go17Ar3hhPMr)m zAe;~BeGtrPc$fJ%+^e2lvW3Z%Z{E16_vLH=4YR)N4FYBywQAf%@yy<6x8sE`d8rOM zYmNc1I;kf#&L2H4DRb6ikLj26vG?@G6QBFE$Ei!{)QCsPc1v`uuSaVE84{kr^vsNu z8AV?1vz7)30N1JVU0+iKN&wy%r~O;hASeCb#I9xjo__jE|~iko`O{J}Em{L4p#ip~0A%oEFaD?AIjH z|M;8#CH~^0pNX;YVUMv+6+_nJ@i)IBZY^%c-+c6wPS{c{kTsAqPW=QXHYsQ0duu=D z`XgF9dvRitflmjqgMHm=$5!;jvC}8xGoOAUUN+hjU+4_QK7k^@eV&mDQVLNibXhy3 zvUxd3Yr?41ngi$Tun&_&)?A%S8ygCC3Z<%WpyovwgfLjDDm1{7R2%vP!as6(yoSi!njkmq^%^i$52SwsJW5b@bw!RUo z$eB(}E20*Jtg*(fanjOMhn;Q({+rj7SdX$fNrw8uU9WKvz<07b9u7`dtb5vzc7gsv z16;<&V2OK3Pd78%-_vW@_&lh}9u#HegU*H(D@*C1LTDq)cmF)#sOlKSO@Ap(gtAMDeWU!kK}KPKft}=aLG{XIz92u*{&pZQ|yMH zNh^K8ijHJ6YPAb19ai+oA@ytBGKL`mov|2J=|31=_RlQH;_eYgp$zKjlJHW5hE4*F z8O^p$oKY8Q*BD>Jv+DVk8m8CK?SKwmxGsx1nN7}Tx|4%B9CoM@%)wDGg^|`(40P7q zWCZpt!^_&4kmN|3EY86U&jJCggBVDsEr%wk%7Qu=CO&IcjBj7BI{-S$!u?F$;ow;r zo`fjUtI!aajf5^RAyUqkpLv~efZ)m#{LxT)&+fr7J2-uBVi;`zoX)Zc?wt{Tcp4=k=Ad?ZD zaq`{>!oVl8W13Khhg4GKia_N&kPWp@f(yifj0Ek(I)*z3YgPLfHlWHm(hJdWA)`o? zC6I_O8EOIrIwly>r1t9+wIbl+efb&p%f{CvR+S$t*j4*LnRRO4SE;1VRSC0U$KXXU za#<~U5U}_5b#9NHIH~8$`&_(uUID8|zkA)dKIUvx+uX_HN8`Qk{dNW7d~v?GceqDt z;bfhgO(i3Rz*cZcu;+y3AfCN+DaJ;|vMcHE9?*$EBApT_93S3~XXmWfdj3;0bJhyc zpg8nXBA)#6#rT*1>fcCiy3hnlNbh;ycgDu%TKvI(`Mp?Ei+Og8$<=r*B%_>jbhviy zhaSdex1xdlL3(|lCkA%5;`roD43Ce9Fna#dmH7M)4$=sL+Y_BQRN3GV?$4v--cs3_ zLJNIw9XVQwF(r4ZY-z21`7e=~vn)|%=PGmP``;RnWaOcSa20x?U?GK^4$BtFp-2v$ zxgbWUZ!e=LG$5JHj9$S|23-UVwI4AKRWfP71Jkv+yhUK};PdW|SHA2;n%&TbM67WK z4hHz5+l4Z^Y*|l3-95~S&^Q7J(vwG`@uoLgaghxtF%m^tZV4pQD$Nix6px93e==Kl^r}yu0|cRQRTeTF>&Je5k*zZ>XnR4k%k8St%nZIptC;Wg>S16i+AgM)8D1 z2QOQxac@~$`jRDYjP$Ig+0jDjEQUT{44&`P>Vh>TbD-C<#6)(^p-3Y~vX4&|9(T&iqDkT9T{HT(%5FdR97s#{&{%#C_D`ZvnS+ z?{Hc;yaXE_!#=1pG=Jo196x@_rID;Bvd62l+<)Sw%x;4h~{{YbQ>fI3^(@>iWDl&xiqHK;UHBzJ_r5r{(%S zLzoHz^+;!*7ol*-@zNQzw-?8c9oMswEH<4z6_(wWpV%i1?xHRbd`NL+HT$QoZ2 z=<(hp7Hb>uq%2~?`g7liDsgYCE6cI8yr=-yEyBKfUNbSt04+r7{7m2Y+Q;H$FMHI4 zXF3m%p`M(GsmXD7LgDNVIwF5oaOtk299t}rt5#fm?y~kN&+m4K-Q%WvVq$VkHnbc? z-Iub+nb{Z^Vv;N5-6R#aB0lube>RrZkP(LLj6&%_Jow1{@ue?5sTSShDk%0%Mxc_K zA~Xsiv|fp&%&|GB0)pbUr6?Ht?HGgrPC(J)nK%Ucg8j3DPMQMxJUX@Lz9Si}lmeEc z9k)9moNH*#34w{!XS3@;8GY)dsH>rB3chD2#%+~J3D|2txc$6lRT%jbDh*OnijUng zMSfNh6Z12TYUh0%ATJF+!jk!&hV=@>@u=EGJ|HJV#@6ItkODt-GR7uH;*D>9ZJa$d zAI+A7Fd+)L2EJ#F)0C}&Ufw%EVmugqJQF5aGTe@VW)X4h#GRBIUfTga=fScVVr};g zDg&wdvU-d)Gu~S97)-J{Hadsau!W_Q$^NJT6DdpZDEoL-@3~DWOU64VEebj$OH|#& z**;LBAXbSAxn)Wasbq9r-^2l`MAARtnms~D>XGM$?buTjFwtPDa{kODifDu zl$Z=zrXxG9-#h~X4zrt;F(ns+%)yQz=QxmEX2ePqOq7jtr3TF35}**FZLV)Bi=}2= zWH;8n^b=TDSlcdhkjZWfv0y|m(=UrKk% z;Igk7NL=gPKs3o+D%=b8W3G$O=4U{pd`8_Xdqu=Y0??LQz}!-ZEbW-G&x+=q*^|Xm z1~KtV2nzk=2W>fdN<-{-oICAGln9J48Oc&Wx4$o9Am|nU=HA%{1O>(Qu+ty|HYbE3 zI#zu=(B1@zQYXsxmb*28sk0Nv!4+h+L!AqzARaq*vO8f@WZ|s2s&q0k;`X{Ew;G1t zi0fA`b*DJ8r@4mNIoI+@1QeLl&YVNaK%Y3zLj#9oS#u1wVus*;eN6;M)(%d=-0Ym8 zZqPiv7uxWY2RTnJ$8cQ)2bRW$Sl1HzGdl}|eOqWHXNgjYhL#<)RXQMO0c{}jpPrtG z<)u}153#Q#qD4tT%BcOa8LTPJKpcw|$_u@6ZjeDuMDBngr;tn` zhCzRgHwdiH>464vojH3(LRGX$_ojVxM(H)+T#k-Ss+5?AHVM+r__bgCt@z8o z`X9P4oEgqY_njFskTsf(LhnTOb1B8pwzFsbJ2N5){!rdXniZO>%LR*4d3+k_>F(}J8|JF=dDRl&M|{&Y(PC5_e9xwR#K1M#6D{{pFL|gV2~r{ z4K?tOY~Albr-4w4%J|hm){GWX%c-VoVy6QEAqH7Cb}(fEuKpMJ54S0bteE>qzq^g( zjk+s88yXpl$%&!3>%P@(=1 zo`+#C-Pgj2vvfDSslyvd3Nm4jK4s1rRJVVTt&t5b-CF7npnz-?9crEZ`alkgx(XT% zWg6lQNHpY@gjAwf0>A)L!0G}%4&HZ&2mtN*VApCL0IVao?jrb8jz)u3u=iOZ1CA2DEvJU zt7b=Z+!BTH!^v<>DjmVr76}pYBXk#re4jv4>gq6OKs=Kilgs`nxETXet#-u&DY&oL z`a+xtREAvksOfCh1~5qwXT)%;oxL3+5qm!13Y;{f!KD#psq33!I5%s!nvnZODC`raWwfb)j6XQ4kA7(6FB%)K;Gq~FnERl zwl}A|?g(MiObW^qL&JiyL1bvX6hT)LKzr0hgP{YFVGl}Oa(hSbLk~C45+sA`5t%)Bbm55BlrA0pRgSGMlJoT&i!Lqe0&Gi=Xg+rA zL_B-(f`V+z-Gj!KmWY#!(Xojb9-S~q-|56%XU@cTyyuwS07L1TEut`BoBNi8zABu^|(fH%v|1;f-(6r=+6tbnit016Dgfv&;_F$n9 zSPu>~+N>bsHu9tsvg~}q?yHQ=nPRj!2!o&X?Jbg4Ud#bX`3y?$qmT^;CoT)O6>NFn zoyfXl!!a~65a0B!ua7%U9*s7^tX|7NCnv_1j|Q2CJnRx_&Fay7npQiOR#x@Ql3b$h zMVD9IR$DEg^T*CcGED?uA4YaiT?2;M9YE0A+t-WZvu1z6-W;sj zw5mPR`qyepWv|-ufJo@ERu44+hWcM!6L#iL+l^W1d?~wA3*Wv5Wbmbkit@&eYvNK~ z1n%d(4h}Q`W@>6eq^z#v&Mdabgo4a7Qsr;O;O_@nu|gwV3B?L8<*f=Tij>7QOFB6j zt|EzH(8ebu;={qK&r@%APHXgp!Cj#S{Cyc~@fh~@v$LaLK?1@^e2)6RDFcDZfIc9k z1ECIshcYB=e?&GY7fejV5+XvwBW4?mW$cm)2H6Uk+^dx@>zV5y9key#d1_)@jvnJ{ z@{>u2MewxNz_4CJa9B}t4WubmM%Ev}Aob0+5f3t1P6q4xu4UX^GF2IJd&dZ$rVm=0+vG|s({As8 z;L%2Dwz!+cBaSQ_jm5?h`r9_eZg$N}QOn$7sxpZhoQ{xW#%l|UxMUo#CK-aI3$;7 zvUsF+#B6hv27$BN>RKa_t1tO21rfZYEwr`*KYre?d$ixg#2HdJ{ScY%0U|ICBhX^}+K& z#age!;w-EBIxRFI<2X1dIF$i0nn_RBL8_&3s6|3VLUnUXVl{Ll6nt6|ujm&n-ddFQ z`qnzIbw>}rlp1k}G8ox9CW2qiK)_%)k~<`WICDq6Zb*xIMiY`2qBG|ejY zTzKx83>1h-%=D4r*xTNf^Ta^$&{+eriy9bGBt~cF44gu0w^vz)rawxd(b^7*ezS&7 zOXDVW_~9WriyD=?y|)`v+*8&}$=v1GfTo!{Ffy!Kx=K>oBPO!(*`@lZcAFvorlV`e zA@M%dF;b|9l_vKUeTzvxFsx&U!(w*B^vsk38J@@P-i~+zwDhqKe69{k`#{c_s2qj9 zD_3vEnN!CVZ1JAFj?Zp%$=OZ~KDl?%a!n4Wj+a%4VGJKpk z4wALz`OyKueo(zX2a468s48(8YP7ZmuffPOV*<5PWvBfEamU#^QwM}LMR)9A7zmh! zW+f@r*V@vxoqzgVEZw@H^Mft}drkpRqC(0ZhlVvsNhl8}#}a`gP_zRMwOHycVO2t)YbGvaIFLsZrCGExCCG3WjMLW zAj!xniHeicMUIWf5a4j@se0)qAE^0$XOQeB>@82$lkBv`DRL|WTsjhg? zk<|VNe&9nI97hfO0pS)@GHUt51B>0|VAI>mD7OU%y0)ChAeGH_ zeAoBAC&ngbNGXy3L9TB^jL(e48{YDoc)
    -e=uJ2@VsC&F4rKY1eWdOr1-9l4dJoV>?10qw)KNe!9s+i-6Y;rEKM}w8yC05i z?C(J<&R>379XT(0@yp}g-}082J$l+m0>e%)dO(C2f36avVt5q&de552Q5V}BV0GvWUmke`5QKwbpkAOgn=X|phN+2u{LpubBOdLqd;`ktM|bHkYP(^GMdWF$@<+- zZO1@hVFtYi+Ys3kSsUKB+_56fhUW-ScDQ`)YATp@WI(H4Ix{mB>uVcwtkiooJ*gV+b5rWqToNh!7mn zdPvTNCil@H$FHU@UX<6MY5<%&Nt`#RQ zlwfS!%73l4W*HbNCc{H5kf6zkPqllpPB;^uHGwICiX8dqNSr)%hahJ51;Ge=A4G?& zU((UZ-(lZzeh5I%pF0=J%Qsc3t24;i;rU5y=CrJv zXTzCBdRly>-MIh0d*l4M^WqJNTar8kX&9)_A0(kI1d(8Je$FG=tJ8+8no=eEVSRno zWyS+|Ap5bO_3a9>D*)NrFy{iN%&2WK^qEVswP^$|3ByM5EC&y%vLItNNR?06qas@8 zI^y_5oR)x_b@>PShk|LHpdutk1PR#L5B}iyq@rmv_IE%mwqs#oUOXl4!{tu%FU(Ic zRdHl~Ccw=}S{1lx)&^5R zlSIpXl&rJ@H6{#uk|WPD`Ruw|?nRSVQJJN*xE=9ZzxIE}h3BqY{=2mm?IwE^3P8v& zUA%ZPe)6Y(DkjH!;>giEqVa~;J>IFThC9OeVMKVq7(5KNX2#1NIs&S?Wc59JtZrLT ztJ}?7lf)pCP4RD_U?4pcXY4G95G{%nv9}A1NbPwunZG#k5skft2@h;PH#e&TkAp16 zx*+825tdR_DzV{!ScICVKsGO9k;-5)P|T4?9RuEj0HL4ZIs33*ogG&uWT@&uaH)eK z2LIR@05@CDenSBU(V(F5oEC{3Y;glPBV^NR<4hUov57I&ohfnfb23p0k|c8#!wqpv zB(EHetTI88VBB>uEMrdlmyA&!a`+yUJqX4%ak8f=BSr~A@Sl3WA?VpzVer`x1XN^C z7-~7AWMrFZ&Mc4JLzcZ{S-n39u6W)UR>^xqxYFE#Mlj;H$e(;}^_u${+*LwQ#%pxbc$>Z2hQsW5(E!#@2EZv zgt@f3u2!s5r%vnHOF~%(*mFuycr0xWf?hs{d%%F=)D<{^3M?C~@(hj~gq4n3WiR8) z2?HX9yk<=T$d2R8qS(@NIDYC5v#NpT>8cnT71;=fsR1<@c!KLR;*>2ep1+{1h@icu zwi2ilBoH`qrqE|#A0aC)v_>-sIy$2`1|at1$AQOh37r99qJ2{^r~(Hx6kMi~5R4qG zgL3W}d*F=6?b4iAK38R(ot-#nTARS)R%B9cU%cz=U2*Q*IlZ<7yQBfp-q(zd;XxBM zr3=t%$r15yf@be4J0tWOW~L#TZYywA8R6hS!uKBr1t2~by ze#QNfB=J@JjzXsN43hVu66KcLHrXp`B2!N`2#u2nmDrNkgw(dV_zA{mTk*)~xPm1Q zY2zi$ICb)5{KJ3vF4esm^@|gtgo89T>*}^hL(UZ_aBY>4@!bI{rP^j(xNsrH#wJvb zEkr@VOtY!8gIqLfs-7U*r}L}8IlG^D4+19!g4J|HBTn#Hw&S1t*iQxgT}oDHe$;I$ zI7qGmXRi1QMgBEc!U2hPo1AaL_BolcN&p4RCvcu2fWIlY$ZM^jp^$_UVk&}WH>gtL zS^7G@PVwy+0g!5wB>-4_J?YlS8N0NiOD^<9XnqY(LOTVH2I`V<%y#3R2kwZw?mrVR zdftOE+=mbnQ(4V1BS5kweN(pEg!-_?#cfk>tDG%yu58(sKUe2MBL<8 zHg;o|jx7S9-kMEe`Fx=@Y9l^~uX+9J;>~aPYVDn)$4*7#)vx;MPBG=(<dZU~`Yi z#dyPX_EbiT8}YLu5xK5EB1cUYARYQ7P%$jZ1C_k7s{U2=|N2{`h50@2UlBeAV|!;y zqC(scS(jQuG_HD3*%MCE2uZJ)-Fz>HLxk!2F2j$8V`FXIGZIp_y;#U&a?p<4apG)f z3FV}E9P5iwR!0YIgF~Y_kOWzjOB`^xql3-nZiCF;vOgZf?|`hW^^iIl^>0mtbK4o$ zZgD2}nyaUM&zYjKtlI=%T(dSOfylHnZFj`@Z$->RJSi18$q4KyafH;ECk^FBBl!Ui z4yZwMJ!k{)IlK?|#QPpQc2rrPNn38gL>`OXV&Imzmz(sf&%ee=uj{b zlP~s-xG#N3D)-8{-=akqB}8RrHqfx->8+ognu*I-ujsi-<#C%Sr*L5Gz>B!5cHV^e zH1fH(S5BEMn#}w9jT?f*)uuP*jsgB&&Zbq8=x*P=_kjoF)-8rejs7jM7hWr8m8zqf z0;+bjgLwL>r($5hs;4R+4D?F}Un9g@?KpmPLD$MTp+vg5wVv}U%vs?~yM@%wi+`)L zU>k%670s5iVfFyRWjIfx8hr{bupw|}2mmy?mOuh&;8Y@IefeAV31=Lqy1Kd?V*~*j z-qjSEW)UunPTkD%2|gDr44psoKgckAJ%s#C$hqOAyF~bt1{c=6!WHoTDeGogl?krMSPc6}A_ZQ(5r)sp% z0+9c5vWh<0fu%y*!IIz5X@v)nEOn5*_TvE@iYQ?qgICQyo9Hp zJ{Ldp)BjqduIasJ;$?m5zSN}%0nzHQO2^Y45lq3hcXDRlh>9DxjdoWJKT!cGhTf*Q zDo%*QG-vZ!a?t(dw8t6_<#K}q3v&qaD+3x2P_#5Y4!(2~Dp>I~9HK1>a0qC04TL)G zwCL?^$Mc^5P~3g@9dYW^LQD)#sf2=E?rHQzrinqD+al32MS5d5e&H8?QZ0}m zGe?e{jK-@Udu0b>r-vZbv>g3O4Ssu98HbqIJx!^VsUIKg{d;=Av{}(pe!G42#V_^Zod*Qm&7smb+h`~wQ#~~U8D)B2}Qxge2@V>ry|WK7QZVHS7Jzm^ zTHLbd`W*Mj`|zyPwV^DiA;-JAvMOkvpYguz5x%p=tceUP&qPpgc8Sn-s%PuEAzB>V zJJ0<8uw`vrG3mnkxO}b)^y-yrL6k;(1Q=i2#|Rr&pXg;MWbF- zW{Xi|UHJXXEV)L4VBXi#)Mj3zWsws@dDb9&>>tj-iKEA2d1XmNGi75D;veLhUsx;& zL{T$5eaq>%c;TXuMV>X!4krd;X4J@CB!jeGZ*Rri4Eh+J^}=61Z` zi4w%LQPeCP5%V1!0A%Tq-=*a8lqcU6pZomZTJVZd+e0m@6c)G}$L@I=4!9N66F{J+ z(DGjAi@$GeY#x++l(84$H}8v%0;9)WTDN8i`zWX6W`+po$^=F`$3zse^n%Le5K6QX z<-v4z-$Y{|JA=8H}KXIz` z+ZO~x67hrDi;S99o2}~I3?qZ|XItwz6A@!$lhL9zy=cD}G_f|!7r*#GyyN%Y6$ABF zGzUqBN;_nw=zK_DzzTs$B2TBR@B7x0P|&8&b3kCOqSwZ+ch^OdMN8YtO{cF2;pU7V zW&I{jcp7BkvSo0nzn6cv=7RTB4!M%5uR0q1K8a|kO8~py-HBUoKNY7>pNwZe`x!BU zcvYhz#6TRe(mhBF=yHyyPqOEvT#JlAgTaWjUDKinp&Uey+t`oZo)N&&vGG{GwiF-z z$fx4k{9?>6FA9A^>KeoD?h2PrKxtC^On*;}n|f8q;V=BVUx+iOW|Zi&wkOZr8kKwR zeOaG@Cmf{g!RH1=ZW6N>WjdVSo+3XUj_a0&9*H)TMU_@6vJH<$HT;V~A_~d~Tv0ij zju{W7wJ4DVK~KQ`sOmMF(S(`4x#c#ZVXkM@tZoEZXpvK2x1m+CSN*Qa4LsNqu8@oKRIIj{8pbH8r=^w?}#QZ@FN;6nTWvOQYw zfTgN#^Xy>=nE}w3P>EV&R8MoJWFaZa5O!*0=*^}}0;{XbWsZZ_lr_LH;%IrMtWQcu zbC1rCSVAx8Z0;E)1G z4!5ChmkW4~z}*%=qJC&{lmxv>K;t&lVMF+d1jqu{bK* zTL*iHeJHYUnYt))naYGHt9E5T2&Qq=6O)tb5JB9?ydA4GD#HS$+3kp%z}aO@GTTOP z1Dym~8O8O9z5;oI6oP{j$4iD0pY#?9(^= z(ob46sA@eK)|}wv z;UQ(xoUzCq`pBZs zAYA%TAaqa?$&yT^5_jD5^!WaN_P>fStI54P+i}~ScSq$VFL^;xD zbW)-Bc~DU)u&`_Vz)ogarn;Wn0o{)eVM7NG!d9t;>0k*)Y^$!%ic2!HXnUvf91p5d zqXc1QC>jeunm&MJ$Btx0hEiLfr>A9I2?Ia|!rvtVrNir5JXtBmLs7jBo;NWtG*b%2 zwl8Eh86T01vNeT(9>R>3{4iQtqcj{va7wL9g(WV%g)-fa4GouppNkY!B44*tRm2zv z(cvHpt^##{kXGu?y64VrtglhurB06|G%ROE(c<)7vm!{5!&b)Ak<;R{X&-}_DG{g5 zO}7f=FqC4*$OP-vfmm2vEVb&6jQ`<2e%2l5Y!yggRS#%Vwo(qa99OAJlf{cTM<+rD zd0Ed^VC^M3#KD58TlN<9T;5x)thA;vys4N;)P*9R50&q$td>6{F3yHdjq-pQFgyB|Z$`T$L#XeK1p|mT@-br}h0!cpO zjIwS>_aOV+1)Vd^ab!%hA3WCH=VoqtI)3`KKcw@W8MkfizNRQr#^gg26`}+z@~pl-$6lzmc-;Pi0o9l5(JjtY?V|=q68-i7o;Q1 zwGuj!x-vy=P$h1ja}kUZ%8SN83O*H$2%!t5Jdq*_x)Rmh(dr;!+K$<|@i=+QiFn36 zcgO7XWXymRs%+ue42Q4HK?v=$d(qz~`K5)}i5JhvC|H@%qY?n<2nptX?5uCcr$6~u zaqa3-oV#*fvi8Ja2eTGb)=_5}R2g zl*V+KILC(3dnI`%7)w16dmV2e9EhC)QB+;V4ESC{p>`p@x&NGlN{x)abI{#Z;@FOB z0Rh3$rJ7_i{*^71%*3-89DHC<72&Gw%suqH&RMS2`CMM`zY)L?Ol_*YDx#_S zS3mlUF)k$+u94qkbE!QQsoFZ45;yrBs^gW~o#!Zklpx?jogMv%4eec8G`S`|1L7Y+ z)%NDL96Bfj^{5;SMsZBS~d1dgU=R^+_Zi2}C;@tIW*_F}IfzT)S1 zlaQnGMp3~`N0W?u_Mfy7Ha5%PDV!JZuZ;<%AI)H>*A;+*P~e!e?#=J<49P0t1>hW% zcL;iQJE)v6eeh+*fEe`Mu7VVdBRdTTe(}=91Jy!{@t7HY_LkGJC{2up#FsS0s*L=m zjKc*GXs3L$ovM+PR3_y9CHl3$uVCoJ>03l7$^gJR4-h_0eC2a6#Qd2v3rTZf{<>@! z_d~!;5WwCwgl*Uzha#xGw2k7xwl?i7v#iH6n4O(bfX-*K{+fi@fO|9ix zod{Y?A+1&`dQR%xp*%!O@cO3K@L&j44mcuEEUJk7F3%Z06vN$wsDWs$trh(R?j0w; zUC7H;cXg)#Vo%l|v7U=F&C!uD@q!4*l9L3f7*uL~bHg)S`um=7u|)vyR!xY#i6U~p z>{ZGeW1wHfZqPEixVWH9TLI_5fRYp2K+AM1xj}D2ed!`4nA8T5kCw^O4!lpz7`_jr zZ?erICWIYSpfE8JV@v`qAUk{gX?Nch-~HX+=DK~!=99ODgO;EaHW#6?{SewipoVCk zcnT$0P@n*+K)c>vFDMhjg%}&PW(9sVQ9=Sn0wYGQQ*Ia_S%BA-3XO80Mm1>1Ja+te z%+4Lv`4qZa$~EQ$xK;H2`yYr;|MlnM>cxd<)SC`^!vW6$7ohb1Nr_OOVQ60KQKAnE zH6AJ@Bv&DYn&dl6SwdvO!c|CB$P$!f%j)574D(4Gz_EWA!~V>Bo)(Q}HD37A7sT*T zO{DC474mVdC`-B{;((Ky0!c!^je27%A$3D+7cW8`3zQigc(FQ-#_tSJt-UXMg$iaobUncS|`}ySwr3 zcfTuM`-{I8l^4I{1;Uj?d{FzKYkwF=7K(`8(6k9LKznRP_ofm&(5IWF2eXTT|1oG{ z(~9V1X zl_dZm`-Nb{HIqG(^`juDYc0LiWI8h5WzGOk86+m1r0Qqlve2GpiCLa3_XlFYq&OU& zN;~Q>aHOc~S0-Y)V%7j67w|cJG)aMmRT@2@kup`wxAEiNghENh z6VV)$=Xx^8^uoJ!Di1N`s(rPPN>c)XBLX`GH14=y-{wpT)EUVt9i(~hy3e?@@G?oU zJU;>q)nyA0N2R7p#LDt&%uG+KM8=-L`L3>kRu!!hkgB3V0_>a_Jlv8b$%@QN7fI2R zCsV%bsZT$slV&ys+IM8;NX%cK7g-FHAmyboD$C0Yv9z$@U{7PJElie-d=WymhD?C8 z0nwyZ$_{;#OwGZ7_k(n~%YWhw5QvtJnG6JReo|6gUvt@wX`y`+_XcW6Y%|ilqs(8< zgRG@iHQ{k(P45qf1OlGsIy9RS0K>*mo}r~NyOV&;S-Tqxi!n1}HAxUTp&RUfNSVx; zxN$@K1O->l4P5~2DXyRQP!~YW4jhhzrfQZJaFC+a^%b=;Dq%R7k3#V4bHbXj4(yfn zH3+qa?Ztn=@S298V1PLxp0a3*j?-|*Nip2;Xtdrw+w5KUx|ab)rE`S)8yaT*f+yv= zzFdnJzTnyM&98h};q$l^kG1B#=z3s%+;Zv9q`U;$#-8TOa=}K45`82QymaxJ&I+?m ztYhPw5+AGqM`~2h4SfrqRib`*j}B%+dJfpxv5B!bapI&WRhD~KIZI~*G9vY%&hlr>v=rs3nubcq9)&8HO@S z7K48`A|mpaW)=*_rUab)pm_}sa(ILQVoz*o{@pO@t};^$nH+ofrZh7SZye@2qh9Hs zmiSXs8=d=PEg_Og1+llU;6Zz>1fKLktG-pHKxW3wy5fklOfWq?r8RP9;6O?DQ$v^E zakY#X+djlDQhQGt4h=w*@R^I3Wl?xgVTFvlqACc845{%YaB< zyN?^*2*CkmI1CQgCBdeCKW@xlk;7+QDD$wMGEfbVkj6=XI(QPJ=N#~R=Eay-B;!H3 z3}k7LE)FYdrd|l^2Oow&g=<(x$6~J&Q{&@8L^N@7XFFz&Ovc4aS5^K2;UGC6@u0&6 zvhe2Cj!Iz3(P7`PMsR4vb6}Q63HW7OR5$MHxpJ1IR60DO@*5lp%9t)`GWK~tj!aCd z&TjeO#h9BtD#>opqLuYEWxx<)K~6cNOdeH$J zK-T!3ulW`+=7UL%(mLsBjW~mp4oFaxp_Vc!TqBSu_J;jiAvG4Qf6K$y6l|@mtSK19 zP8yxD!(orI2IB}T4L2pclnAMuF{8RgmUG4qI)@g@}=T$bx)@E(92!|L;lw zZF_rN9IS`G`dD1KdObRA6kyjy7Vfq8^^6q+l`-9Ze!fNm06FMFgiMEc;22Ag-~`7$ zMBlTE0kEgri8E(T#N@V;lQtO*&HZX0vg*x;%qza zflL~~uEd}on@cP4-~*4uSHJvlT)2EadVO~z&??NH(YS-6m$1kB^IzFP;zAXaR{?10 ztE@K(b^Vt`*9;8_lp!|&+biesP@lmcj3O5;vMhJs^G!&4aogI#KQ`dwPp zih*Hsv8WhB-Vf+2vq=-|91!sP{QJfhXbOTY<6)J;ZL1Ed#Sf)D+E8GpdVV*|P`rW| z+EP)B7#$uK^hU5mDFq|Qe?oE&Ntbefot3+733S67@#ZE2L71Ik4Dx{Moy~>_a}umk zC~eXg2PgZuIY6vELL}x*)WmP#v+1hB&}Ge)_sDiet?()(M z>}PijqltOoF!dFX)mX!=1F|Ns!vRg8>i`iE3G|6c8Sb@>)p*`Fe0_ZOvwx>&4OGv* z1jWNaapnk+Sw~6|e7;&>OIHo+EnCw>qrrh4&n9gL_r(2Jxs$FHL;f-)1pZCs zFTeMn#FK9Kv``}%-p5=td=$z-7R#y1PEh*eJgd8_D1RogE$uPyv$4JtSFT(U?}=we zAPG7Oa!PA3&vazC6+^=#8rhy)hP=;%cEU0gFwts=x^Swnt7^?VuzyChwFcNam96oQ zp7O}La(yI_8=Kp4;nL-}a^+fVZnR^!-HR{X|FGWIE!+h0drERVx4=mSjyh*TWFWyJ zVwbRor%oM@*<%y&+^_$-7#V8B^z=~=Tq=o(;P^x9%=2`D>j8TF%x$+I)$SDG`t=@4 zNbScioVyg)F5ZYw-}jkV-)cv{Vi|3>?L#m(QIcSmVNr=9>!Wo8>Kf2mq2r)4Qp#D0 z6lAiMCE=Xc!S7HmLbdcwZ+T;k4_RzbveEmUc;|on{rK|3kI44?;k*7UDldKM3;M$? zXY)c>YE=ac1OU!-?3he6>u8V-y_YB-QRy+LXwCfy;@Y5A?_-s?$|{p9hu9dS_1_%tIz) za^g)+1rDAsplZm8$}R~Sk_;zE(MW?yYmS_8f`S}1e*#F?q(&cF&z`{W@EQrv$kF&| ztF@)q6%5Xy;b)$t=sMF@83!v-l41lv0gfM=Q&fwwhO>~FF5lUtkQQ;w*-vZ(WFk)n zKzvsjrDz{)Y`JG&voH$0EGb((Glq%y_a(8d8tzabikh@UrsiI8KMU7cjUEv&8L~Hw zZM4Rk8eCWodlJi^R!i28!&Rfk-qko_I$S7MPzEy(!Ux2G2M7kT&`kxo+X$VF zxgmQWj*Ydg*stuzEhkRI(h9R5hGS`YQCYpR{H-misQ zQ6I$`iuVHtN?IwNkV$|nJ3?2GW`KleTMP}$_(6UoSdsE(88pS2S4pjO_z*zx3=kia z7!gTE;S`84%kwDm#yF?kkNnwzvE`WU6in9R-Z}p{-IixUmqQ5ga=V$;2fge$3Vro@6~A|%#{3+Jy0Wu2HjqI$V}f)pZ6x*co|>sf=!aoz~* zbbYB)Q>HN{3~%HBJLn0oO!w6AGO-d5l|PD_q4`7jA)`I4lLC>0IzK#sZY-{C#_slJ zEUvA@l}lIRnfKfyzjpQ7wYYX|A=WoGquZ&(%JQ;?Q}IkECr6{z8i*IaH=e{`9@?Lnq-I`&J!f)6x2f z{=J#m)D|HjjZe_l=gd~D+cKkDBnsekO|!G8j5bFhlkhqY6NEfqGBQJzDLNfbfdjS` z)a&{Z?S2?G+7Nk9$cQQ(0L^DBhbF5bRy1ts%ep7kVK{7{$Vx#%ET+LkK8yfPRU8TR z_`7uyH82q_Az9Klt(guMwZU;~j59UXQr9J`G&|n)LkZ%HK%O$3?L!6GjT&#!LnyUy zK}HB!43OpdelRE;8w*QXhg@q8EUyEel}?8A96Hvb*SK(Zm=LfTIdj`4_sZuuc=Sly3_?tj z0>0kyq)Omp#*r4}CtD^lz&vN3A@8AV5WRt66X7uS1PlxS6D-_91{fZSCrV;W7F2s~ z9ApiA?)1!&c>M7TarW#fkuD+ji91pzoKceode2ra*N4r`PzxkvsbVCxH!+rFHU;ZR zS%LEa1j}BQcn-s8BvC$E$Vcc+z=NAVP*aP~Ps$|Y3?WY)!?8-vmC-uqmqiOxn@6|jQb z6;Uice{pG98WX%;!MM&viAW2FXiII&{b&|~qab^nuuO)B`S2x1I;8Fqx(o{`-d-<`9-WmwirToD|Iup5{)iic4oR8Fs?QM_xkw0$OVN+{ z>x;3nvL3T@(=kMOOQK37TYJ)P0FH0bZ8GHZj{R0wnF1b4ZAGN0OhI&mhx!TRjJXyj zO+su|M_DNqWcHhDeh?XfF35KC{+3a$*BWu*+LbtS{KUapNh3gAa1b<^N@n|0cWJ5JYQxV0Jk{bqdSkyGCmr`|^?1{Nd_#1kf-ITRSXsUvzx%eg#nx^=w)fDZ=*Rp1;=@sS z=}TVNS1q+{cnyjmv)17zlQBfg!{Xsf_kMU-w}_#^;1CRu*(E$Cr7sW!MWZH+`7_)B z!3|Irpw5{NibJLvHf4dL7D%n0LppPGRvV2CjbrpgK6=9))vEJhazeEkBN-M}+NIo3 z`o-00KvurFBgkKHWb~9FDN>h;p&_s|#OWw9i{RQBoP_fw+vh<#BQS)Rq$q+KWyb1- z#gNcf3<1UhF=OM-f(cZ(Mka6adYqri0g{lei+!%?h}&Cg_2NP?&=^IWVAj&*SWrGJ zXn;gTN4`@dfk2SwBQ%57 zGO|}@9gL1DNaFWc7pCy>Xju>T7+evqLlV9_+p1x+*Quwo4`E@G@!>EsOQ2q#foMuc zlf_~bj?K;KIcv@a=o|1oZG1vP?9|1j867!`c#l|G+hkWbMGrsxW!)Dj2_>b3=*euE2|(F~>t9`8 z6*9wwQ+}8I$@_u4pb?cLn#Dv=&;&9v$ZNFBp?g5h-!j53DN(>@-!}(o z_4V{U0yZH>{r#AmohwAYy;xdab!Pdja%dnx%d1vNWKZx}IZ>2#WshV~z~2)w+ui~dBQTB_ z9BN9~3*;ng&Uw~YZ`N4cpyF(?M`ER?s-n5a`tmiKouCe(LN>zzITQCw-Sy$}ft{5* zxKL$GZ3d~wR;%%EUi%|4F>XXB0|kPA>=QZ|M~+M%Xa!)`#IsmkRY0D|agwCDCU>;C zJi-LoC(fUX>4`~oTqu|kn(Lr2c@LZ!+J-ro1m&PRoX11}OgeNDckoq+hx&W9B9xc? zt?~@M2IX3&JQ8SYofr>bKf}9dn(RP5zVgu5;;tv(c_1R?Qk6ZtIclCIfems=yj%fj zN+EM9cq!|rPB)c^92D|=#S5$AY+W8za0qHZ7s<+IEL~fRzxd#NvCKK^ZpA+Bq!PBc zi3F=8z?GMvRt~+aC$B{Stv=9;iQ&!oiSIcZjrQYl{W`7bV^JTvCI0=}uEchI#6zD_ zGP{(g+&*6fp0c&He8=zHSXqnT`@P?cUYnqUDViiw?f8v1y(#9GR-;BabjOL?pS|z> zQMvbJFYas9a~Jtqgl9a)wa)m}9kM!V+(2<#deA%=>cto}^=}s>!R%&B3sZ~9@`NTR zmdFOj;t~W%0CjDX!^p~HK!A90LPfZUh=_wr^iSr%CPuA}Ac7mfkh$j-X=XM&va1`` zA;17M2SrlCk%>J`5K^)LZvtd#ciavH!LcaLiN&j4_H{W)4CSelr*v3GHSW5uEKBnn zc01~tP!^re8M);hCa*aQ$WjM~$Si*|kg0S@1gW%i!gEkNXLC>x9P33;WL*I=J-1FK zSq~?pG2ErZ!RuGn*TrByb>c)Z#GcK7bJpgsR-NsYR!+g7kU4j@b(keYRMazBD{9|4 z07!Ex4#r&5`@Udee+Y;A0a^Fm9ikf))RN*KI{ zCaXc>mF5CdK)t@m0n_>B!wFi0w((?aD~ zxNqpX;TlLg}E4Dnob4s;>?xNzZd!@q;f5!ou@P{X<& z5H$=0CBZ84y|ub(u&fP15$}`FS!F=b542GR5DGJj0Hgcj^{at;=h35cv4Avt=_1fv z5!#sPWFkn`MhyjTI5dKEmlzgwPC28_u0hruJRd)LR0bJz4y_JIlN#+S3FwJfE?GZo zK+p_9Qld*d>(WKVeznu6X{zS=^A`n;t3?g_1(G73kcYSNS=Kgi0^@*gL&28Xlht!h z##W7WCQa5&Foc65RHjIBCz`4{M7)xz?|B>iF6w+Uvop$G69MMAlYo(Ik^E>@ z4<*^+goT=v)=~nQix;mb06ul0EZbyaO*6zENR4zvrJf9)Bp+Nj7Y=&t zltC}#)J5o|q)`+BO8~{+u@$W*lS-N2Vzo!v(lROd@9%#w?s?kXT5px43Syw3tw>|% z^vOiVZ?2Pt($v;jlobhpGB8kJR|Z|_dllQ#kJTHiap7y1;=>>NWVF>G5YexB=0vp) zS-uh#Iq3|FocZIwD48%6j61dJtWhNNw`$cZ@gIKbDY1O{D=|1Y77yOP9H08Lug2YT zr(=6>BrXn4$K}C+=mx5*4nPzjmw-U4m#9@Kd-I%s`TzRmn3-%wze8Z;&X7O+-QS7F zp12t6+m;|`4mCv+_~1uB5tSFe==psa4~&q=L$nH7iZu1pHE@F{j-Fj9zO~gZC>i2z zPlr)(U{NS^)@;poj7BnoIdnvp1QP@GW(>eO-=#;GsHGO$ZIh%ZJMj7KJ=f-O0Lp5W zJzJ}qk_3Miq-jM7M@5=C2@~A)Wd=Ku(WIya8wI1l#63ZWz`uK4k*{z#lM`cl-`YUY zf9L^yu4;^|+4RmBRn91Z4I7@`VOZ!ul5BF`5B9S*e}M}j5J}jl2oTX{&VAD6!ZqZ; z8gFcKA23)LSF%_c;f5z5Qa^JRNDE&P9@<1pqKGLG`Dy@hlYp+nnut`85+MV!XE}PB89-oGsmAOK(;D3uZgk3ID2*+rbB7^P z1=dz452||%i7NUJf)0^x?(7D0Hh5kWlVd`m*iSrX45J8$?d_rgtRzWSIA%44Rfj?ip27 zWThEG&%xfVqGxB<5 zY(zhsnVb?5WrGajF(Dx%N)v9|wTKhhK1l%Ag^aApd8k=hD2%PZepZ=5WlBqHyR~;r zNM(-zub>0cCO}ra%rU^$us;w;V%>1)7cN}1UPH%Oc&%O$3I&35{``5Bau$R%9VJ=f&{;3TsWL0&{nE)9aez4b4`&m=0b-z8Q=^}qT-!E*to-!9{*joR7&f!L zyk8=-%Bk3aH+_5gN^`(TbkmOs*Y zv(H?+uj<)yP7z{akRFguGhnlJr>V;#y$Eo z3783oAj~FdW_N+#Ct_do4lJakvSh_J7oU|KD|%KUv3o7MyGRxf#QWd#k+}cM4=R!D zReI5{n9HT>${7&FN4SjXjtg~2h>Ldf*?3GvK6jXu>+$b?d@ic%Peh|R6aV+Gd@5df z{JAl`yB}TJaOpa%H{)Wx7Jt+0$7Zb&`(@0uo=%yP?0w^4VRLgk{_%Hwd))h?XUFa? zUlqj}yZ{YSC)_Xs@?}xsn)= zX0sL>8{08;Wa=O*^t3}X_N^|6g9EnZJupBJyvQKP!W>~!6C}f7xJxI7RM#UqC1N#k zj_l{g;*u_$iHAVABctOQ{<4CBnw?cgs z%0tHhvQY`3EX=g&x^}J9dW+mGI^;x@^m=bG^r;SHPu^&uC=500MVZB!azm&DL^QY* zK;<~^sqx7oE<_OE%rw8m(r&ess{v+CU@#s*`}GkY?r%}y(| z$fagkT63g5APxK-JtMMoje{0^Z_*m~mF!Y^%XPbTF44qkRdDPZER{_6eSbR z92q-oX$~dMkQZrq|EU&nv^^J-KfJ+k~AV zzrlvT_3SONw74Q80@(^85=K_6|Ltv+5oV`n^mB}8wvBZdv0ST3Ob8SXt^5Y#fExo6 zUrIg+L2_tJ`bL~QemZ*9s>p^eftbb2`y`U$x;4`$NA#Hx_pV*NtUc7}_F{a*P;DY4 zQmX|1g;>_GBZNo@nzg(_U3yyqHoqq#rX+=}g^ye~XAoxq+aL5#&Z}sqfIOy@Ir|yy z2qrg9PaRRPteR`zh?AeEbtpik*vArbs@LMgiR0Q^$BrJ=`J(GUM6hba&K9kYgARO) zQY&jhkSX5N25Orv4gRtewv&U^m9^O3*%CK^apNP98>^Nrx4buHo0d2bDlIi_Cxp0A z5-eFf=#RKQYGuRecraHAS+O2j)*_f7pjC-VJgBZDqe(Fd7KH|s3|JXyDM2Xn&2~?+ z_flfW;9J@70X|O2&1Fhven@OdXU(I7>-}o{)c^hiF?ob@LOY^6C=#*ajGevpYz)FP zD&*xXKVVxaakjT0!CJZ-k0w@p#ieNvdP07BUe9}WZq~%nlCbC&1$nz`gR=_q0Wbqc z;>e^+7I!~{wl@#!&1p*?t_D>P>^uvlWvz^>Go3p$DIz`D=4?h zd*Wt*O!#^5d%9#eRVS``_*{FyH5a{WRW>F(`OK`Do1wm@!9n|kAL6PL;Ix;imz-f?Gy{?u=N+V?3<^fn# z3YNQ|&XxlVGD&k3ync?}9UXfP1|n9T(CPL=cby<6gmG7CLj<`YW&eVy1^JrnM7HK0 z@=X~Gf;0(0H9b5jYrovT0u8za8qD(8k;7>;JeUb%4s^~n%9%Diy%9%b3Db%KFv;+0 zwDG9kkApx7gvo;#O{rI+uvgf@WS;yE!H?GwDdSNEa9QI`LK}{XOpwpl%#5N$!b@v2AZS5 zM@Gj~8&`|)uE%GC{2=CYZT_0FC4w=~4~7D9jRYwxOUu&i;JPPAJ#dSzA&`Por_Yue ztM^24*DRNg z3E&7s!4=8cv{3?cHcHeWJDdjGdLy3Ape~ovuFAR^A#{0G@clp|W@nBT*xwojoR5F@ zPhTBRy6xmaOFQ<4FQFx6)HEb=aVAvewd&;d7EZgn}6%> z_2cm;&dZiTkVI>QAmVUm0G~;M#OGiW(m$9y?fDWj)3cgY0UBmxz-@p=${0}R44I^l zmhCJP@ZC`RKz!|yN8?Gi-zrr`Yp=MJZCPtCGk?bpXW*?Ng__-9UPG2C9CX<>|NZB_ z8vo_D-x}RUO$b(gW|oo4TOXhZNqo#_Ym~^tq2QXCD`DOU50ZVfD*~$rH@)ncyK&3- zVm$I#H{yXt+*)tNP~Dv)%r1iPe$U;{j`re0EUc}>v;OeS@dv;B#<=hNjo7Rj$uO$v zv$oTV_^to^Yq7n}dEJjbDADdty!Fj*j;l-S3V8PWRn2|jylt;-$Y%ZVd)^zB*Z=(M z`fL~p+fV}^8B#X_3)N}?SFs7)mXdP?L=2?wwq%?*FOT-M<6vUi=H|K%3m3?NPZ*EI zkXX_#VjiA)MRY0xO4)?e|FX`c;TRD5AXBOLp8-)0VC>M{ibo(pW{z?fEo-|w?ylm3}M!-dKhkIC9u9a?}LMJ zWPBnXd*ZwVnh-^rotrrroaBA&5`f2|quiJ+rzW9tjSv|%H$Ytq)VT)~kP)CWya`br z4LWN>yaN>@^RMff)6$kCSOOTKgAD5uG1DXCrLh1y*r6=BA16*8i}iJDDqv%Dwr6Hy zZPnQkhFC&JWf)b?MRBQ+q{Sr^_9FL|H|h})xc z9*(*oyC95o$w0!4`0CdlQ@LYycJ3hINQY>r?9s^tBxJZaGGyA>TkI*dh^q69iHSF- zI|{{6;NU65Bg12wS}R9LIfgE%W-A_j{BccP)bOezj>NOKe<7Ig^^(co{Bq|>1`{lt z2Inbuqg>dHfBTES9<>H#%QA_wBt_Y3s3b|H1{eRc6fKlq{2K_C#c8V?P_%K1o{fU9 z9wJhk(P{6*v(K)?Ewlaj?EhSh=XPgftk#TyYQ)e$Q|g<~`uQJ?zxs{0#qs4{#6Tr> zMkeB(pZ>o1^|${~JiJ8$?k)=^wQlU}##`U|#^|)yU9v+zVy_dw`Ri|rmCe1N;ale% zK2^<$!1$;K$-VDGAC1Z{{?hCE2vFc4v;lH_B@s_|UlH@@@TdosRH%beN@$C)rCxH? z77c}xrAQzL6}~b_kwe4+WLA?7H={WBz`9ngHpK%HBD@7=IXF^>d?@F^Cv>Gc8nx4U zg+RncO9xm}1rvoqK*anG$Um$bMt5Tqp&)mEzyfxwo^={DBD%1RSsSM6;j~A5u#FXuDh_>-*2dzrlE;Z<1| zPXQ$yH|xhbQ^(eIDtj>bi^H3$aeCH8JD;D6eGV6aKKlWa8wnP8kC~Yx(cA0A_3Jle z%vontLg>RY+c?i7YAJ+RX(P`#VMwEEF+DvOr%s-ZfkB)gj?|E- zYR#GuXI8$0M6S&+?v=|I)bEU19l^3;>3x+z*xL{h3F0`1n!j*lO8w%>1iL-K#RTG3 zSKL&W1JBTEiJX6CBNSbMB7mf4GddFI&Rq}!q=2E2-HuF8%SjQ;Xi_U(P~BdfJ$p8G zcNu-_G8ZK$B@V+wQk~@9=(^b6*^ISSW| zP$xiUy_^SLJJ=eHiSfzeAZ(+7vY+=2Ul*_X)>j-npPVbe`f@+qA3Oz;L;?%!EQt~U zBzAyxB}rj#=X@H@zv|bzu;OU32kpJMc;T{;RdieJrHH+ zg>2VEFJmBEPCX1s9IUMO7p@a~82j_kgOA4PTjpY7az=>{>#X*^(*5Aiwko6A>I;$H zQ!^a^8zHbTl7x`pux+*D|NPar#$JEd?UGT-3Y1dHbMXUnr-2hY2Y`I06*t|ADHNz@ zvMPHeeV@+_cD@%YD@!pqv>i{HYsZZ*t;N%;v(e(L)dxhzf8OhVBEIzh{&kFh_G{8M z=)ymWN-R!|#*NcQ<3o>Jj($lHZY;0Ge|Xcc#AFKhh)fQus1hlv?KsDP>)Ht26Q|K6=5Dd z^DA5$Ap6%G`@K%Iw|C<7>04x6K^?AMomY?l^74}E?`(p#^^KS+vbxl_`wD73UO6LL zW%i|a*%`M0;(YeUt-j9n5d`j zS`3FwN5W7TiE1r2x4HiT)$-X3i8}G#7FnvR)r_^~&mJXh!$CV=4z2+v<2540wOxw9 z_+SVr1K|8w1MY<^l(lyD?5I9l7zK+LJqes)PW{9QXA3QRg;rJW4@ZCcmeaAZzA7Of zj7IJ&2Sr95^j>4bx^Ivg3>Vt`5E?P|^oAocHU!iT#6LVNqagWU7}reD6afky37;nj zcLXp5N7Vmu95@ixVj1YU0twPHMnsIF`J~o}6DLkbYuH20XiLS|=AfbEde}KQ7$fLg zUtWrxoeepm?6%-J9yX{1cPev@j>Oe#^U8?nUgDYI5R^e{yt*AE>j@_)k(tcq_-yv6 zkivaNwYNR5Wdx!a&)BlnWKalJLHq?hn4X!EVU+NUv_ybeyHXC-WXT1Oqh^l{(Q1fx z2sM3%AJsgz-Dsu<7x8yHFNRb3dO+-uy_P;h(N2N;1o4r~2*i`KVi{+~kyq6L#kGht zRph&~_4O+9(^FG|y49Ja(ae24+q@q3bgGDwWnZlZiAdw8g>o(@z_ zwDdhX6ScF^z_^n6T4LE9G};T|3%DzTGJq!VHU?vI>WH0I2@(i0p8S+M;s?L~d!kKo zz05mMVn}ToHN#FPPM$iWvJDOzxn*o=ie`b_P-@W(h@$#Q>$tM?!qpN7p-iykJ<(Ty z`vKZUFwJ@^el4>UxEJo*Yhbj1uSAwpDKdqq(jK@}ne~5@7VrDieevR#yjVdg=TZC) zURS16($T}UIU&o=2y=eaQZIPkM8<5_B*3D)0V4QYZ~gt)*f8NQgF1I)+|*R?dLQa! z;E$*$DnM`vFHr<1g%&IHS=bRzZ*y%mmRA*K+ z#@y|X98eqy@5i56{FK(sTDM9E4G*T#@R~|B)>hYx&;%RNFdmr&C4i1FLGGX9_Kq{34Tu2q4Ce9zRdH$0a9xt;2;~tDeF4x zb@3;1k2umM!08le80z&PF%z!ym0?R6?OO{2!@_VaW?}5d&|pIW68lj^$5O7~UVyOS zqhx)XvV~gz8UqSgct6CJ__MeTyF1F>28WnrxTk4?@IoNb;Q*woAijsy<&d|=8KOvs z6IxxTrZ*OsE?$ungb+k<0NO#h2?s`bfaS*MvcJ$}pPrqGSu_#~9L{^^`N%z=qGeg0 z<6a+p;QknDG0ND(n}$b+zfYTJRnMPHtx`AK$dp#5 zK}dxDmD4KR z>4;p(y&pJ8Nl2%aOvmnQlV_RPuUh7$HR5?I>Rb?0zQh7W;g-EKp}7iUV%(>V-u6^hP{u?-rS~9opr9WW z&&EJTdHx11vjY-?0?yV%N(QLG`6~Ndpv0jeNuC$swaNg3>&!rv*DE03>csUM7vk=x zJwwt1`C6d}Dn}Ic!!ntde>Wi#O@aZz?0hcIi=@PU$PdM33a|3x=P$(DfBR2#J|v}F zek9IiK@a>a-HK>dgNJEZhPn{Ci>``@re!Vzdx-rHiq_tA$$wyPFYc+-;{^I4jb{9d z-+oj4lwxpQc=Wok^q!2nGg#~38inI zha+}r5%tkriK1pEc)7IgsGq)&cJi>vI4N@*R(8i`MgWFr7kCikrds?VRWGuMnIki? zvBj_)qB+_wnGfOVff|iHOfNkX5e-#y4a$^@?m}KGPD3?w$VU6VFAforxggb{mIzD) z1~^zNj@|6zCnIN_RW?CAPGlNS5EDF$lUDGC0WpeU(r8`5LPqpC4wTIe%bYd5af6yV z`Vm!WAwclt^S$*^_Hv7)lnys(f3j!~hD4<%3B@~v$dUoSX(1I8usARTEBcWOQd(?%go?njJ_v|?#_ zEsh^0gLKb1nS?VgT6#T&kW33B&HZs0SPzUFK@#XrIyV9;TC{+(mseJ`|3Qej1~P7| z0~-FcYG_~CCJwqHQ5HJ`95nll`y;@>=@N*jb+iqsc2v&N!dw-#Jl=WdlNt9TXT{%h zZ|C`8-7?GKyUGytdVJ-k76vA@`(oD<&r`i&bx znlyJpWkP4klpH7>D99-@Ente{WLZm<^acjhnZ#ZIZ6O$;U0I~g9S8TB#UC#Fum;DD z9+NS~R-}Uw*%Ja?dny&t=n4#g)3PCzt3v7u38VGL%+Qt#FCdwjv7KCG6 z7M53HY}B&R=C~AD^)kOiLPsT27Z;_#<%`Qpo-t8M5bS-OlY;VjHh|@PQGdnx5X9>_ zLO5-=m6WIkT{?jNe*wb*EN^rmot#>(OOlYp+m!H44Fm2)djh1VT8ojfF$D^Tof8LV zbYwh!_y@lyjvQg0MXCvT?Fo);+lFIqZdzrM3=~Lo2uSPoiuN&y4O$AnM71|g4*tUU$H%ZtlVZ?;s{M6J^j@J>h%2Lw0E6fP53#@Ims!b)rwp543O z^`3amKY2B{*jQlco&!gHf)asT}f z$2;HoJ`JP-@x>+|kQH+ZV*wP5I!Mk*A%g~pmDYRqs(5lWw1_s880i@lktp7Cq_Y>N zH`{UN#AN)yZ~y!F!q5FmH2al!?i+tK`e$e2)4%?f82rLl<7%}T9~m5s`OWS4j(_>R z@$%L5(&z z27bS1d1ckHk(MoOIYphzBvVV_@*T&~-rbG?*w-S%G2{qD$xtLUcN~E-{sRqjmj>3i z$SAi|+Z6eTXEQkH{`uYASXf&2UMU83uLEynRmO}!2zV6Z0&0Us29PX=hm6)FOqaqS zv2u_s)WXj_E}D`Ce<$e3+9qqL*%^g6gmY&foH}tzHG1+d-Fs;XU0Pl_81jRI#n5Gz z*xB3FnaDB-jBlJ0ffPbt44C4zDG5yXj7mL?M(N2nX%fdsmT9P*5#mF3#0*y}LNTXK zo$+V2Q7A-`nr;&Bi|ks+z&Qg3*5$EBzgjZ>np6;PT%V8e$#JdOwfXCD;@HucUs_iU zlb{Hvr>Te|BY~fgylx@D8Rh0Vdk%vnn9D#b)|+8YJUfO2fd=6i*&$8nk^lf807*na zRGXlStTFZh+2gC%uSu(b(h7knXI(O~jHsp~13iZVJ9Dp|JlRwb1+tMaH$k>KbIRbS zR0d6AnY9X-^TMztJN@K5sGNuW&{+%ZsU-ADFM=|XbQl^scj`8onAF~pqN5T4&`P6@ zT)*o71+wPMgG^A)%)xjnS8gy1r!Sj)!vPvJozI99W`UU{w4Bim31gq|Gyna_MS-v7Z*s@*~eYZB-FiIH?Zvl!=d0rtFZ=q4-mW$fLTKyD3-OM({cc>iu@sx7c>oR>Q(5tO zwoQn;SrQ+=NkIJB}WvE0(vx!RZ_pI-c!BInY#J{aSvk-6$Ok6ah`6j^)hhr8szr%MnF@H{Ws#~ET z=9#C^ppB(r31k8s)zC$xbN!OcM&dhCf~1{iPwgZ)F2hgMJ3Tl@>UrhR3Ob@*-sbws zRL9X#?Nyu;zkq>DnPDD0CY0`4o$KW-1s4pY zkuqDE%n4e-7X~{eL^Ej0S|6DPr6Jask^o->B+k%X;t;2SsJygx5y={Yv_J@mfdU>G zRfwY&!Qm(XXOoq?^^7dZbuB(qQxJDyBV(+o^RLJ4w?9eQ;9zUG=pJlnbBc3OW=Mz} zRGgQLOu3Gw#Z?)<>({Sp@8OVGBRMkK8^sS8G|B`g1qth-E(z?+fy0Tzniqqc=UwE# zB@PDJ48>9EomJ#;&ADN}(*DK)SGhphbW62a)CUEh%NaFQ*QQg2)=oi<>J;+$b9C^9 zqO|wKTY*%GxRW?K`@MMXH@+~|*J+g`aPl)E`%=xay{9=Usv!f>i*Qwq)#a7AaN&tE z@X79l02t%~B!lh>nB;rCevA$y=+%zZjg2^c>ZJ5V5Duf&6O@2;)~prUbLm=Q#5e@m zG7?;};V2j~SSdn|6z7by;PtNcx*r@HhlAhS1v%k!OtjTJk5)@kk)pqw6YGAnT0@* zyh(_yv`H2fOzsakX96;mX0h9hWbW-#zP1j6luXguSzC*Zb+>feA25@{wq<0jr9az7 z7rU(KiuHK^d;dJX^M89yRI3i?901%zVpKlPnoJJ3D?vjdbe5^FMh&5~y46SdTmn+f zo+yw+awaiOwOS);m42*kZpSA+_BZjDfA!g@Fqfxr7BbM27E@kx3P`{QBY*-eR!=9T zU-m61A7h(6xY(uf#e7pzb&upSZjb*Y+d6oxC@3ILXnUI*wbo(8jeceFc}>MCe>M$Z()8ZPM!oJgbUEpCK2pXGF6Neq%V+8 zsm_(UBL{=5llRJOm`$H8H;E1iZdZLCTjCOgH?Bz|{GH92QnD*F9HL7m9yxX3B1M~ z8&*5B0m4`?r(PwMg0cwS$KdFhS*xDx9E4?JYBVlhydKTL`T>&~XF`i8ec;?LpWzaS zrL?6WIN%9^{5$V+^ysvnEoBKD&wlh`ZFxiOr#LN)l?iCDsd*NbNKH-$MufFemZaWm z*Br^9G$E66P#07L4Tz?Pat$DN%LK`)_7SBhItp?&1;d4=CMHGH<@ebScRcwnl`C?s z&EawTF?+{|oM%&H*>7?2MqD~~4s)SkOw&oDs@A~yg&T6nbSPcFu@G}JQ*vtb?BkGm z4sKzs>8#Mc%zao44QFfw#KbvI+vGY@H-UAsP?DV$_ee3iAyAdE9WAlq!##Z!=PQF)QlB}<+> zg+wBfvp|AZiN)oWc>nwEiw7QfSV53mA$&HnG;}~dDc8fA2{9)SArWU>JIw(_Ur2L# zKpBTxF%bK4+r~yb^X%!Ey6t3auCB$omDTvd)s@(+4a7hG_E*JAU;LbiE+fxL(srY_ zyB&Y@jz5Si^YgK^iuj$^pGm1l=Z*@Eg(pNnfuEwhYF(kWP~{JN^y5+ah1dUVKV@rc z)d3B6$Xe&{@Ti6lX)mdz4)__Jbo#_6)Wf1^1*cI)Ub6Y9KhYULTN7CkYH}C|GI=tM z?6>Cq5+&e)Bi|kayQ5?L68hQLJ*?7W?eCFXg zstUKP9)(>d>*wG_GRW4n*7Pp95^!L|xjq6esY?#QS1D6FHKUyj$=Vn;g60Jz2P9=v1+$kD7w-o_ROl2Vl*=^B zgrOZc`W_*HvW`ib<@sgctFl42t9q_y+#8OiyW*D9XAj!<2&h1Z;CMi4#hJ+w&^o4l zXr1?~*Dl5R#~xE44?5={!9+hBa8I~Ib@0rYQ&N5GmmYP9q8hUfm#1Zd9zg@o1znLN zM`mJ)pSTyTE!U z{CjvxsnEwVsvIo}Ix#S4W}%0I0+&0TJfx@;C`bn81aU`?&Bdilmtt*wOAeJ*vX#yC z7;Mn4?HL!4W07rU4alhZT+K1q*^Nfa!as=s5L`fhhX28yp#_@OF|HvYb)F|>miEq; z&LqRC*fZ4Mxi88|IEQv;M*?Lj+n!SIsg!zB~btnpi5ItG18w=NCeQhJQw%R)9g2~}-Nfw)u8%l!_I}qr5d+~t} zd^Dc>jn9fky%~EQN+{T#L37sXHIYpT-qWWjxfJ3;2N;?T$;EJzq_)(;LEs(;5_EQ( zMl;l^UNdhZ=OG--NKnEgHkpvZOP8+4``>?GJp9#1rH<&pO^OOeIZA?|X%$M$>_>T_ zC)3*IAGB{u9LbtCd>??f#dBjW1n0G1k01Q8ABcPIJQLl$9k(@uvTkq0pS|l{@zA5^ zg!(USxZR)0zmyG`%|z13nvH-kt6Pg{yDm|qxcSNd`PWhTxu1D$ABY)9$!#e$vw&Hs zhMDMcW@Y3j5fc-ytgz?)(p0u0Bj*s%E~aurYe)na_cN1C-pq0jBLdm>#{<=*$<@_^ zRwymP=BEChMx4)ZW^0lQHGd2thZZAcBBYtRw6SrZu`D=W0tx!g`F);>71}ylBpjZJ znpR(gjSa-8)+g21Xvwq?43TsGJ==1mdMMc5LQ1GL0y%pZ+OWG0ZkgpI&fzG0$UHh1 z@}J8j7TL*QDw)zk8^ouu7P(-uGQE=b${A!slK)25Jol0fhlgrkDsz3Qw^IAZIEPrn^980ME@UHYb2rz62n?^z`2)y*kNPVva=I@m%YV% z^Il1kQc$HDwkN*<*~5|trQkIguJ-@xc9mTV?=MlnoKEj;ofN{6dJSF5i=f1T20(+4aOj^2XO$_ZyFtQ zCTg}mL4kurx)(e`c?=GN_zZN+aE4&);{eL=o>og;6lA^=6ObiW4oWp@$=%#k*8r{1 zI1>U?&ae=ArGyp~!{D*LLIaE5gT{=PQS-b9!OCNgJgRZ*Qe5R(3z;$^#2#8+UXVah zpDrZ!3lnD|_CV39BEmy-db3S`jK*RwOM({>;#67;};bRT#f{G0;BnarHB zzGa`fvTcVB0h7N8+E>!XJ_E8Y#No1!3*2y!xhL15IfyE&Nvb(#z^H=>fVZ7F6R&#J zH^t;Q-8&8>^dDTSa=u*ZstGZgo|=+~7>EMh8#rR~OPKy>9+Hw!B^k7AmiaISKa}{J zW3m?rS}iWF2%!-wT_AdNXEM3sx*vS-E72UP#Z#XAj6>+Fb!b2%Hr6-e#{9f=0dR)! zhX@>Hf681M`JcjF@LJtO9HdWC$obfF@p2^iMCr{Ue!>Qd=7NI;+jy0Y%FLN_7p}x# zeBi!#?6D^loS3t~=d!R43bG860YqMl14OSq*PKC)u5%v^5V#c8*sWCJ=YQenVs4TS zF68igntOsRf8U?JD?a=84@x^F$=OKQ%ru7C>7q=8StLGloLLg2?-%{g2 z+7-wYXkBV^=0|W3+)LK|Gb6K&Fp_ao0@<(Unn4d#@&S=4*|@WKmn%RroE1BO;~KI& zpy-eZgr%fp_HR)(r1VneN@QPr27pA>%A9C{!L2-dk;h7FtA{?- zl(h?asXM@0T3L|1>3&YH74{E-G3O%A$s-2}XB|B$a#<^LxNr$esJ4D6QLTgkZg9-l5e>`hW znH2RPexcwA8dUskBbP}>GWb^Y((p`u?6Zvs~aRx z0_G6~`XDjvSAt$pL=cGCsmVBZ;gZzxB&Ay;xM;=ItJjPEgxi#Xak&niMGXR~$*#Z! zlGJ>q5;N0`Ft(wURB{7!1KZ=FN&Lr|tQq&Mc2a8EwVD{)4?py< zexG(r&KY}_;D(^Q3F_DDimXU-g48q54PFap3a-NS`S}hnF+NmX7?SqovV=_6A`j=5G^ARQp{y99F0LC-Xqeq&wD-?k3W7v zVt-jOCQxv>*XzP_PhNp9Z_PxDt!s|qc{ma{C(fsCo8Kp zxIkJ!hyX2!g8)Xtxn=+(y5e@n6o%l>GPuA?s-w8B~VG{hY4+??4;NklKX?m}BPJvQ$6x=6`|MmePMVnUq z5F;YlZi$geF38RIaS0)_UDaO;55#0i#GgDV&h>M25==@}H%T!f?1@A`Ft`xm__=EM zI6ks4At^PD{I!0($!Q!q%1YFHIjF2j295+~sp{zf&-*ZkI%PdPgGvWb&UQUu$PD5P zNHYjcXgMWnlZ!zsSO%xc0@uu|0PcniDy6=nGw+F-S$Z(vhA+?u&Qt~q>9F|OP-{4j zpFR`K0frd)`M_(**YfvdS0|T7qG8Qu%wM?_U--i3qN=fSl+dh_h@+%s4RRlW)W}d% z+W1CCAfGm3ZF60Nm^gpyTMWo*sTPU82cHd#9izfMJMeXe$az-)Cc>@JE7p)v*!(-s zo!}TtPgl><@`CKaSeI9{C)p2Vz7T&Acw&wSXNf^WlyP#969KE-X$ks(W5t`$?2;`> z7?b$|%Oa$67_H*^7(-1vEYFDG3diPh-Ax5i>gx94lrh(3A3)y}%pc+*q;p8wdfD8< zm!hrBljz-N@4VCe0i#zA6ojNpCD5}TQU?Y5$UU`0XdKYgKL_`=)Ij5#3v}Y7leeDrz@N>m>j^Y*$bxa_r)saFypwGLdS!ZIL^q3r=oTDlx4FSoF$pS zNX7u1*HnFYSD%BBhO!O8Xk>tH2SeNhV~b(Rnk}EB=#F^}f~SdEEn?*If#KK;6flCo zgTVW=vna?or~`#3;?)UeT*thVcQWQPqId}+U)@0w@F9w0nN=J1#c*t6Gu~mBTI3)s`gvc`6Na&pJDh<)UT@V`9 z3P+<(kV63#2Q?@7xrPpE;cLqFIvl?Dse>NXCJ|dFlIhgw!DHENE6YGhP;ICX68Bv; zV~xnb$S_zJ&gj(Sl=d&30Zdj@=L+hiXc92Et;{_UKZ0y?T8dtAfQ<>n}wQG`DmmF}VR_2l%aW_bjH|KQ(gRDEr071#c zOP914akz7Hb3*=jPOUN)9f!z_3yd)+h6JHjSHxrDnd122&tPOJcc8?_`;Y+>&@O8N zB&bXwR<{N<>b^Pl%Db%N!&%hvRZ z7cNRk(Gv|l=!?LV`-LEkjmE}W`orftgBW{JJ9d7i!D(nqD4D{s5`c6>vSaNoUc3>H zKKj*o+SBijTBS+$~FoxvR0hiflP$a_-s0NC&AI zBBoE%oyErXZan=tPmO>5Bi|S8^;NYQt8H{-P`3WjuRap*`29Z=w{U%vvET0QLkER@ zi0=}@6n&}EV&9G(Kd$Mse37fdU88)(`TpZS{j;ci^Z)YlJ}pZ03#*nbSepS%7FNPB zX{_qzhMXXqT+x}xIc6CHMUqJoFr)!Ri~+(Cf-wXdGc&V#(A+%^9W;P#Pxdg}YQ-Xw ztkg@o9cizVJtIbgmc396+7i+DuGM3Bj5?SGqQ>glmfF?GQ21;%I#~&sJ#wq`_rmU` z&JP=&OhP&bMG!@kzu+8nQ3D(AK$4*>hW&hXGmL&k+BBNULdt68duHK;3pfrlyV*2Qm;V z%WN`7=9+W~s#Nw1#vde^R!E#A!+yBt#vlYSlpfi*ha&OP!2+?1^;9dRNT}Yp1YX<| z1e`3FSOwFqLjwin)F(fzU=;_qy1uTx&UNstkOC%1gCBFplkSMeA3ql(qb+GZEG;d^$x|m4 z$l<(c-Nf)Q(j2LA&;pZOJ&BTi$T{S_t$es$kSkhh;Wjwv`5+i zn3wz3;g5JiABl-OQk<9^pfQxsY9>^(1~@jZg>mH|5*a9)*xS@IqD7IvA3uH~E?>T^ zAfC@=J(gEDVq~bHz)!4tk#Glfwy+0e?o5%D{z#d6s{;mFRrk32ULayM5NFPui7QvG zC^^8UaXmsNRe}oH8#-9{IoEYfe2Wnyr3&=+L||l}BAL$KGyTBlGu8f7zc2eB&!W(Q zqBzKTbE(puOP=-ME(W1J31yd(gA)+f#(Cx-HMI0Kn%3pe?<@K@Y)SAneEywM5+^Oy~Y*4%HP8)uAaG)6tI=FgWm3>H9M1C$E7rYO|Jq4ag5G;{}`5hJ= zV-2O3lLB&}v?Z&zR)e_*l063rFWqh8EEIX?!d4VY!m}jF?mhqjAOJ~3K~&H3InPcg z4>qYe7=QbPFUJS|{FAY~GOs{K1oBd9H#))Whlmc7Xj_f=&EI)Tv{$beRBb;Hn%?bf z#n#4FT)%uR-ukw;M_XL2mI4~))p&0k+36Us0Si9V?Qt0{wBsg!Yj&eY8wRv)m2 zGdU7w!6Bs`kcU7bAUc(D2U&}i$sjSoiO8|3hKvlGn&3rX)$1E!pkAA>k|5jYD|<;e zeIFqx&160>9sn6KKPM}moy$P6AtI{Q1eA%ktKPogZ~_Ch3l)V=kx*;a=rCk&fg0{ZnhvEG z{+2Vh#MLX-T*$pE!@UdJzopkgBunqzY{rxByvqSp;g_)XGBDD+cln65)c`M?0wmqmQ2gb69}(kwYhxpp;fs`R z1@<88j051nV;mlR8sh@cwEt(xo6)7l`|qPYf0q7$%aWHqRYNqYp{K-f4T>f{6!DRjgBCZM2uN?ADX zLn*4v4at%bpG)9EFhGFpStcMoCgb762@?2Xy&ih_Q9$w8drZDzY9b2;#E5eh z!DQdHV=_e<&vjDF;AeAPJJP9a5MeX^H}6j1BZu zJ=BnymGe9v$Md{&)bJo` zi9*Q8jtCRaa(8D}=diT2EMoGQ9@Y5;YqoE^@##WYf(#eu2TVyv2laGGk8Jv(P8qmH zU94tD@Cha|X%FQ=R}KM_UWs+qZR#k`3W44CyuC&ZA>d z0hBYLLvu?1hphnXrjIX$6c0uDCFs-jb%FnkXcPo6K1h(Ce*f$a@y zVfJ2RU=v?l56{YHbC5uSXUbk^NDL4t*SNC0tfCm}%)AAjHDW**G-`OPcf_{Bw}>`C zbo}{}!G3bAI1l&P_$0hvyGLHf-`i{G^M6@u`xE1n@4l5tOtQ^Ko(h~<^epkgln;cx!J`ZR5ylnlMr%d}~tf;c-hU0!T%lu!TM8|BA8 zdDHLPZBiKIGHyob`0g=;YlemHu>&Llt9Ms)yl?&VtwKPxyR%=OKKrmdxc|V<;`#}K zLpqMI6a#(u;!Gw8NKm-Cx}uaX!60QCI%ZH3ZSB3Bf1Z7`RzPqPOtbG;O9K0c4U~ySL~Fbvbwfd{>AV9bDDn3zyEjtXZhln zz90vybutWe5a7brgoNIp{5X6fvLKBjVvquHu=3OLcWkmU^0o5|MDO?im;bf=H~;lN zFBg@l*f;>m!0D`^+;Z*Sr!-<2`r^#42LjE|1EZM8*G<4wVS?uPZ?%m&t+95GsIqwL zwYNiw1O*@!DMJMDj2t)-mWflH2-%{LhA#BU2c0A%l;E{%^6D<^tcg8GF(kn(ZS|C` zoIm(Fi~;Wv70E=h~372>p`v}bGJ z;aS>G?c9&R=R~;#1sEx3SPTRO2;>?Bi}!KUQx9Z(_|$~8PXs^+R>_?C+TYtXk_Iw^ zgwx<(0$+oS>uZfX8*6%I(g8rA29|$LPb)h-0!VyKO)@r_u7$MCVg%Z7FvU`YDx+b5 zvm}^d@A3QG8_tqQox@4+^U5o)^amXA^QrMkVba<8MI9ac-I3$f!Ej%EzqQTcSjlz? zRIV>h%b)$*KaNVD+8v{o)fmTY_s!vvLv&Ww)*KY}V&kRf;qKj4_XPq=7zM5yN01I0 zh8j_hiD4zExVV7Gyd)Aq?Hgwe+{-@aGk15kMfWJZ5H#>ySqGey!4%Tsjm|TOcR}0r`M@2cU5sT7`QrKx&ST%G}&SxwEjS zvsa#;X?e;RH>Uk{nVp*}&!0UnpLp%H^8WkpyA~;{jatSd!D2syDiK%^pz*9&ch+uw zeIq&wD!Fp*;((e{lT%Q$U6BL%0H_^S_fs_iGCn$vo1f`qYU!cbPq_uoWN8^RzcXZl z##)Sw(&YiVTVeP*!+_6+Oo;sUfAwE}#b@%D-}%e3IKNna>6bpEEtB_v!ecG1g4UTq zN4>aQUI#&G2w5LQkikzIZPk1bc{wWI|KWGb@BWMbwhVPLmfc>0Ivb{ySqSiy#Xruu z$L3i&X~B~vmfAUh4Z1aG>$cNx<()=CPUv;RBy5R6dlu?0C~}ryfNXsTK8ENm$aF>> z81Rt<)Ut*5QOf}Rbr?!e#Xu&mk8UIb123HR*Q;`LuwOp<@I8lR{mcLUUzW~j*Fkqj zC)ljC+0$7wH9e!!CHsdK=69bwF;IBzl~>B6MBGhjm;@A>(uQ9Fi)(g=rlyqk^%j1Xcglhc!Z=O*W% zk`Sk-Aa)gXC0J|(YhX;DN!TOPV2a&ICDnASqi$}c^m171ML2j2h)BxOsgw8!juz(9 zkG;II=Kgee5+l2bkWa!urH!dOGOi-w(w)UVsqmFoU)8uG!~^F7^njTN+-o!?&LlXd zeG4Xjl@qO`M5Uam)6?r*+f*@h47icB14>fKO06S-s6w3KY0VHIIz{P`AcXpGW8=## zN9?BR9~dZ9$d}*25rrWiP6qdpE)fiCYT%8B&`L#7u8j0F>(d}bHT4ypibg-8I%Ll% zAu=@)Ljc!?=SqO12+-tonO|5kNJ>o~Iy^)#P(~Wn=wW`Qi8fW7*$@ zZ9bMstm7d(O6o+bV{fl~>Ww#aegp(KPe^>vpFc}2x=KwGe3|*E)QWk*c!~Wo2*4H;h5iJo`l)`&v%I3s`Xp3c#S`uYHvJQ;ACNQG5 zZ`o>m-1i2)WvvNzK_lqj=Xt#P>Z|3aZ@=Y!(P>^?m)+ecF%md5{z9|8O$f;{!{AVy zN7b@1^Y8O}YB>UwPeL`wrPOW9h$+Km0;l!(s%a1!L*R3gE9A+QZLb{?@z8PL*nrX- z6jA-f&%9B-@P&UYpXdAE`+-wBfAv>?*(s`-99t!)4H{~Bq+V~z671`6Alg^TDc9v| zfA9z8Kl{%=Q$GFk|H#j_EwYYGYF%C#oD@zKWr+4(tO)?t- z3C(2#EE18O(V_CqZ~SrTeECaX=uJ;dDbvaih`PxfBuJ5^jxjYYT@2JXQfI0f z-8}dTK>_nPoP{yTW^D8Q?6&DabD{hk14D!+oagx5@$%8r=OGx@wk;kI8O12I{ehzD zA_tB|$DmM4CHg+t-_sdWbG)RF|LUTQPoO~`@*hwjFrva9XfB*ym?aTtAR7(j!hOLp zhyY53u6Os;JZG_iC&>UXRB8RBzPew=krK9RA(Q_kB3)jVrFqmSJ7sg@Wt<>ARB%6y$1 zB^V(1a4->BOefj9EN5k*Bhw6Q-0e;pI8g!u_DmUOq>PMp4U!0Gcs36nJWw0r-rY6V zjD3M|#K_Xsk^wu&f^t{`k8$oPt=RHo`{sm3oi$X;9fKs-B8Y*($tW3Lo)cLK&yL_T zOk~PAC~YDD#zE)znbD9@=aDS#=+GR*RXHZD1(G0w-?Ouz)^TrloUl*%TrxsNYV+AR zs#cORTY*Kcr1zxj&gYnQtKxWCyH}zjiXmk{X06xn;xVpG14L?o7 zEK^x48FO%;_K?R=?(c0&T(m0*jr%Gj*5;*f-6{19n&qQhN3dY6pR>kUI6Nr#*6x-M zKKMX|MHMkehsxsoTzT`SZQf0ZEaaqMJIfs#lW;xjNcf6`H|;3CBMD2UQJB; zSyR*bJ}REfujd(}!9v#JY>&#raIjA0T;M!21Z~XcsPXJvi^LHKdQPaNR%1-yq>%*e zJU=&JV2w#6D0y&JAf+H^e!n_&w*3OPWnq!MAuY`SJDd>!T{sd$^ClE?_H`L+Z zd+&)|4b4tb`r`Z}K1EPw+3hekitEP?P-3C2vvql4H#T2xhG&GldF4Ne;L+-Nb>+1; zvYY}~)VFUk(wC? zl}y|bPDM(HDGsm>fBT>QQ#sh)C|~}{SIV^mocP_^_F4T8@6l!^Sl-aa-N=QvzqgV} zK!Knmj`gnSOX96tZI#-~5Q*FSCqTL(E=02;oG1AUb+}ac0O><%s53r<-=)0UVfrJ^ zy|!lGU=<1AK>jRe_O3;f_jmTnCAt%XBjr!N^+)A9-}%cjhAvH&u7=w{;MgR^Sp)vg zS;Ve@(BcO`>_PY!78mM_l3fw3cBZf$1i2)ufBZ+^E}hSQ_E&nNid7^#hU~#Xn-~jn zfTL|C0!4a=P^vMrOJS7ZOF&PEPSAsS9`!8-69M6)uTNcUAVYtuOIX z`ed6Hfy4`ypw7&)KqokS9RAdx!dn2+#HjE+7J-|*e{W3=0`G^zp$&$h0|!q41M!Ln zPy5yA$dGJVOCONXYy$~j0%V}cFLN#YodAV4F~>nqPWT}B-3CErqu^+$ks~}4x#g(| znDdtf=n_Y>FwgYB5N@J@AC)>w0}e}y=nuh>Eh!@@oiy%1YV?W6IkeicfoG};~Hpb6dt0vEu|59r|Eua4MFNy+Cy3sIHbik8jIdA*0n2j%tGf3CdwqaW4r)C6l6Woc>Nppl>&6rw-`5s_v_6pJBuWA61NFqO>M&Ab;$&9rT! z?#O(N!z0hE-7Ew_w)0*~YGmjaX9fG@dv)RXq>KS)<>ZXM^$2=l7f(*lgU!!?MCR(H8$d0fP1TV$|qlcrToKR`1x{m&g_!}&6HGMyx1W2)9?K9FaIOS z>=HIR#kG3z{AKy8@BBsiXaB|Tl$p8tTC1;Rh+C*b(}ZYc0g(yC;^>a3DwZEZD8lr& z{6TQi@Ajz7g*pW_0ZCOotcXoekDDOD0K#X}$3N=1Z#<4XlokxJrgnE#VK}%PCX0P# z&D4z$g0i#^%3A&A^+m7zo8SLh`R@1rt}NeOtDQ*@)zMgpW)FJ@os{q=B0JDjj46kZ z+~A{mp0wez7aMVVdUB#Xf01$V?9D&@vwvGUpZnae_GYJ;J%1dXf5!xmmB9i`7YAhv z2s;TTns5pRWnpe1EsUTR^ppd!Oiz}bZQ3Qr zgmhr7WB7zKPr?9|>Alai!ss@Ty<))lJ$^=3h(o4ln83o``aA~Aq^@_ql9hx zg008bneHGeJS-)hE0bK9xsHBj9r)SC=0-+!*V*&aQ!@rhl7Pm>WMwxJk~KLqq&mK~ zl6+Wy*37mr;Q88qNx>K-A-WDQ>m%}k@CF7V?Wn_+bqpepqryPA8V__uI+0O+}Ll3^>FCW>(9Z< zfuhV{0P2vbu&5hpQI`BrN(LA@>egIK3q)8q+hQvpgXjME@#_X=890<~2hoaJGj&f_ zHne;Zx{yY?#SQXmuqB?<&5Jj8KurS>y*vSkp4iVI1iLq2uis2v{X(xoQx6!%6oge z2bK^qR1JNTyhy35J7zM#z0WNy$UDFufJPjhgh-7eW}l-;!1ZC!STEE%2{N%^5IzZ3 zT3M99k1~Zp4>Kwx&4J*Z`2GjS$0>DHq>?F_1gOlfpc@J~a7rnx3Bh=Ke#yR0{WoPE z%6VjqWc>uQWX}YATzl(O;<07WXOo;0llX*M2jpz9A_Knb-Ogs z#Cgp3b<|1z(pfNAW+o@g(w*h9xHw;?CdbNydu!#@Pd;+(&*@MgAQ}n>gYLF(e(f9O zwNE`PpZoRCyC*;HoWrNc8YDbu`?W^+eYBw8>Crk1WMkj77x&-SYYxFtPyP2tcQ-Cb zi=--&5%OfcmfL|xm1%F+c{>=9&%kHdRWqPHmv*3XVv<&aoT{ArfBe~>m+yY}2W4|- zw_Nr(-|0w#8lYVMS>%>kJ8U7u@y36Us5~&>3>19M2OoV<#wVuAou!Doku>ujB!4f~ zH$-s>>i_i5|GacQ|4%;Kn?U2;agos)#~3g*PIkV%<{1s_bg;@|Z$mPo%oNsVQ(ff4 z*i459IIhUmn&DU{LY6a%Y>*?y=&Z2r-I1+nk0zo{jHsp`AH9LG^qAw=quLec#6fhD zoH_@n$Yq0((MH>z%sh}ZnhmyI0^945GC~;Rt>6nY9YzqKV88`rou2yefonOmm+D%F z*p;bp_TXy-ryWj`Y7zogm zrqj@}QBV>Ik|V&J*UBZUg>PFJ+7m$~luLEO9o-~jwkfVG-!aJG@DmLa)Ii9h=7lp1 z9FAxQqD6HWm7+-3mV;V*EzYmCMMYAYzTtFxfCzD*kkoy#v0m>tYM1orX98n7RWMMH z*QO@Z?Lu&f^eDk^0?~7gu#*sLD-+Kb1Z4HjLODK-0guoV#9QFwNK#uzt^_mg6X==4 z$$GH9P7!5)*8o5rcva{^f~0l#wbwr#{sEmeb%urkIOnIfXZl_mh43dJg}wQsACxzL z{Jpemo}bIzc>CS=blP+ixhK%k7eQN)xP&sE!bb9XG6^)TT}&3dvVWRDlq?oUN?n?D z?lv*lsUJc zL+l55KXz6z@M?fP1JagR3NqI#_keTGb#SH;X#z0;Z35-teaYrmR#q*CpydzWinZp8 zQXE23ba;S%Gv|V{204}l0;fiOmxKXBZt0WGnfffa4%P>lmH-j1f&oG;6-7tovX92K z(kXkBy=?7yAkymW4c3VFmV|kH27LJcM`cOd{k{^cruYs#{R-5U{8=tO2(6vm$tt4rPIFUH2Z0Gw3x#efEQ6!1f3>{ zXxYq+`;*thnK{4QFTeMD|6LjCj8+|iL`qebs0IeNAc9(A=sV*|xVF+?1B5UR>Q^mq zG>wS_Rc)Pa-O_FJppF6XJw8VI%zL)aP9Rr5E5H2lpVe6>mdxY=)xk~@!bz6sUMl6U z|KhL9|MfS2TTafd%J$w%<;)41GYf>y!X$4XH+1c_(E)r!Gy3c4J8km`Xg6%V{tmvd^WoUKbH?d1=_-z#&jk(OpxP&|jA@4VfJks1+#`mo z5yfD6BJ6bk!99Cz5vRfMa~(vskk0r!*(C1C9eUxT#tN%IjjFooIHYQ*!9k z{+@=B17c(c99=qPdvDjk1Y^WOfq;@S2(4f}$NcUPMb;j4NGcdb3^Rs=`{&+SLyRQt zfOi%b%G+-}iGDX+lDf_aEoIHp8V1h*iEPjp+ZzdZoL7;uhjO4Nbb#R8FoHo<*e4h| z?r-zumivND3k+>-7uIYYiUY*FvT~wM1pzePT?`jWzzu7+L}gGVeAO%|pR;RPi958_2`r z!eZIq*($@%wa@xAqG|SMTJ5O6!~Yk~Z>AS9~fdn}iPKk?_kuH5N0v7~r2qNEq@2#@G2T^XWtZ!_VhxhN7=j#M><2qR- zhtVL-JCr+SAuxnD#&!VE20tuLX0WSrkO%}Z)XCdeghJ-x^;-f>X z^2h`ve4eum#zrG5rurL(Y}^0_#EP@%J#lWU4nhcdln9vBKr3-Xv2ga1IjPHzHeG^2 zyM<^6M%tK~Kd%Ym5xMaM&6Gbc`cmFx>6 z^L}*cMEMoMGJKy9-Y5koaE;DQVt~}ZvCGY#e!PYrcwL)Z9Uo_e{S|?sAi++sZ5juy zZJk*I7_-V}z|nASK$S?E*b6BA`Cb*}^a?8i($Dy-zC#NtLTbF-IgqZd?VYXid%yR) z<=1}s*F?ld#iF=)z4L z)Q<>mg&h4ixIrdvf`g9*4P38DW1dr6bM+T`J?EeN;Je=~|M!pHEJr6KzeuI;iTZLb z!m$`A%gak5X!yuTw=?xNC_B#pTSXB6(bE?O26MBt>}PMXPWWx?10_L{Q06NiT~H$VUDJ)(0+U_k2#`(*mokn_|ra;hB?Ju9(_a7CQDwKF1j>dKWFYYQQn z>hY1aOq?$U7h}h!Z)B0wGown#CWTak(`*YSL{1x(!&JzG$T-up&alcsKjDfO*fD&Qmu@miQ{4R^0aiSPAqAH?g93R;m2tgy8#W-H+ z3>#|~jd6w`H7J=re6mdp6}3t;0wO=kIb#W80ypCzCo{q96wQgiV4w_S>L4IEAB=Rj zJ7j$lM`Ifv1gG;$J08ezY)gfAz_iEOCdEbx?4OBvA#z2jP*{pi3XHYW&d|?~`X9$` zg3`)4PIlZ)jAM>`a|S&DX(d`sIflSP*w7KWL!weJ%Guzo1BQfB4;wrJSf>VB1bgf) zqFA&38~RjDdC4T4we=cA*(h5&$PvAVqMIRWvo4I0f6o~hF-BX~nl$r_R=5|Ba)%wRcS ze>$V$K-KiPyey9%JuELbUt03PV1XjChvYyw`SGwn*oOeea#3~Omc#1VYuqKd163G{ z*QbMN%(KJK2nGmJOgPjp3H;kyvaK0=Hq(j-TFE{mJI(Ba7=6xzd!U;(ZHZ~@_2Xm9 zF%p^Uq*Z5gC}DkB4nYy=q?(<c8Rpg<*o@5|4 z1YM|s&8>M8A~TM5zAEp%`%ZcP{g29zzW+lJwsWWW_AK$!CQNzl&e9#%7~h9KmFRtb z?#vYa-k(5fn`N%w7WmS!Yk^WAJ_{6CrOj!$Wgv8!(*mm1&MepVt#AEl>HM>Q`Xz%b z+lmU=O;qfV=TxPsPGkfQSKLGnP;*jBu& za|u^C4mKR0ebwtYK%>n7;C{FdKC^G6PAIiZs98Z!gwtp(JFKOxdUev{G!6~LHa_2B zQX|f;H;B2q6mGpz|6$xVOxyhq_CyZs52tK#3KKuG9eC~#jqD!TKg{NHuoY+!S$hWh zkj+q*fhdSG5n8uDIf6}L<%gt7cIVjLN`l20E-fthnZn!*w>dtt-&)v>`++>Gb4Uir zzDSGYwLyg$+Qfv8txfwQs1hX_MZOzDLqHbOWRN#H=(IfoHuweyharjKm~F8eh7&`{ zA>t0@7D+^0^)bOVil@Z(-bVZP@cEriC`;YPnnE<5>+S;DH{S(h40UB&&0vhVq z7-=MknY78nr3Lum!v_Y#>~j#UX6%^Cxm1Ok;0Lkxvhp`0GyU#6@05S=na}hU4V#2D z*GXwn4G3CHIeQr8F#=pP^Fb2!%G%m$dG_qN0TKuX`@vv`3{oU9+$D@UniQ5d$()eO zK0kM2D9@i@XnJz0Y;14)`z-+gU9*!%f^vdy0>?)Bqg5aMvZvrZIvEo(|bx|1I(kZd`&Hl|kGt?+(Kr&RFcSRdot-B=;&Isu9 z38H5pp^e|K!_qj1t@9z}gnXH)!_2R3gbs$PZG`-s0E&Q4Tj1P|luwX-=BqLM5d^xe z|G;O7NN%i)LOy=<$o&*yp>QKa4;uZzx&w|doon2W=yKI@(MQ-Z6F&j6t&S927&;70 zj7CgUDLLXBrp6~k6IoMRMu!t%UH4KlH-Q6bb$mSvo)Za*Y;TO16@HR11;bbjZ{U+R%r8MR(g zhlf0d@*LS?dPUi&98L}$YF14^#hNB9S*W#*Pe@iueFL1u_OmmE zZ?{~R>(WKDemsOPP#H=Gtn>cCu32I0B;g^Q9-pcYPG-f!S%0zarp5SEKebP}cV))d z1X9MkBZ_m-hS&&*msb&|Qj7_Qb#YlHCZ}ZV@9pkrY;atZ2{O4beNx+%-jmrmBYy1Y(|CkIA>^)EsG9pWVoGmkW%5xFV0l6a5|Ka!kE}~zQ zd@zokjsX|lDAu(lmf}#0?@xxy^LqC5d0AXS{47u=YcJs8XdM?;! z1fV!V;C6TklvN1O=q!kiKuU=^(Av@oF$xPuc?~rk#{6zp2KG~*{AAfX*p)M|w_o)HuCIbn43UH&LA|efWXQTf`e-p^uj^oY#ZlL>PauW~ zBq4BOczGYLgTR12Afc~LbwvP)ZVSp&*oDP~Irkf=4M-|H6SNT0Tc4UT>lrvXAUVh+ z*NaVRgRUYTcIcUH64wMWpg26Y)>Xkf5EO7-=Vuv6cF1fNsfT&)K?`chq1xAE#PO=F zebV~8r6szJQV-`DTL;GpNm#C=y2^pjAJvg!s6A#sX$dH)1=Ttr4@ zi?s+>v@!~jWRcXrv$rG1iwTzOpB7|-gc8J)OtkU=L4xHYN=hmZr<{SGbCmqqsdi6g zOiF;K1klXWKx+Riop9J@q^>Vc%QwFM?b7-3Z+^b##%6J^ftaU+Hk(Qq7r_SR=71+? z!y(dw1V(m9*1-mIq_kr`VIGr3Wl|uua)J&VD`RPaJ9q#({Mv7hG2kYN)*DZNMNZFk z2z*T$Ylq0(`fpk<8TV|Bc$|ncK?e~r2Gw~BeGUa#-$m5UAS+eE%8)g7NRt`mdQ_bU zd<02~MAP*k5-3sc1j=HgXR=r%ps8VQY`m89uu8IJXGY(*~M$r*R%K8z6k%{sQsEupjdy&9pqwtxLY9)FfELRsH zM{>P5Q=Z58*rbR7j)%+`=R%nP1wjll*&y3HZLmR-l$&kxu9PL}=x9C*l!Swb;vms4 zDw_&xgrm@IoM(EiWt@jBRXhmF{rYGel|-sT6PV;pTIBN7#PQ77-}9| zhPwg_onVvuYm*;?9;6kI=fhfTZ|!(pNVJmOXDVZaYakXr`S8PJhPCGW>3{GK%lsTY z%aLj3tnBW=g~_u)BZNS`!MN0?W%s|_EH5{or*)ZuV6$@?NV6pZdS-7_R0Twe_dh$o zbTZ@_6HN)^ZBtEP2ycgT%-I2kmk&_MRR#yZnJ33~xll9xaT{Y#dn+Xog1wX%)4jqP60lJ^ zU`;58V$(RI{0?V+cW2MCf$E}WW!Nc@&Ww(az!=&g;d!-TLZXhHqRtD?Tk`kep|+Rz zY3;Jdl!hvqnlsBfL=82C`EU_#W;L{Iy*WA&hU(N*M65xB_g}RY*q>Ps_ztm4O*5h? zuR5{xmSSNGNE*bRpdznJ=_8poYmGf`x&y-7wSArLFJAZhCtlAmBJ1{j5Toymn^SH- zY0f{TgnSw7*B#X7FWk~VsIbV*AFXr2-%0CdyO;Qu+Io5G`m(zv_7D4;mZ0GgVHh%F z;Ud(+s-e#wOZyR797YNl6Zkrv48SrYW`EqgeYsWJ9z*2ekVH7zZ_D6w(+xpHb7gIg zHVy-X4(g0kg&=`NrzR{RsJ4!9V@Bl)G(nWg`~-$V`PmM8$vqh9S1}=?a~>v6y$ueM zSk^0Leqq7d7?Bl52V-v=2@s_+$k!5TfM~c!)*uv`z(HgdsMAsN?{uz(;~6*Yym=-X zj?jC~pqp?ukY^v6hB`3WqO(0vP zr{$GbANR*{pPgj55YDo711QDZ9TSDwSYLOt=z#;IE>!bVwepyNiMn6*C#`xQL)_QH z2W#cYd+(>#C-L=KVH-IRwg&dfS)DRI z9-*)GmzzSalnVO6K;vKZIyzt0yP~GEh@9S)kx!GixwY88E#Om^jB{^W-)&-_rspS_?IP4r>Bn3EtJSWIvDZeT^ zzp@&F=fy=?Uw>hcDn3vp%56=C|J5sHYlq+ruEVKaBTWd2{T$M7-}j{aP!$>5_cPq6 ziXesd*LSbl+p4R;wKe;|Yg;wQkjGURbCQ}*{K=H@|2!G z`sk_MIr!B5-M#Yo6R+92I5!89J!pAQ5hT!mP_2soWFKG2FKh_`95mLOas}nrD9+x9 zG0{B0EFyIhKKqYUX}j&V>ghIkyH3+ z!yML`ab3u|awtV3Mj{A>AtC^38V^Wf2I`8K4%wh}s`1))iZu1L$TRqA-S|V9aLf?7-S&b`0CN)F={UaGzWYn*c}|1ICuogQkI>+X~7s-lNepPm{m8=HHP?Cq2? zw=ky@gFMUHKtd&G+1lQ!EsfW<(CzK)_)Pfh%gYR`qOA7|zxYc&*Fb!bXk*yOWCw@h zB-xvEV_-~K3)b?Tci$?Y<^)*bb;sDM3@j0B8w-BCh%e}0L^2R zlC}2i4gz*2sNrXnidbVr(h#LeDd|#&`h5L`s1N}M*JUX}G$62QBieEAJTrnD&I#v{ z^ZCxZ?-@vNjdPW&f!zTuU={-b-t}cBqcZr5`>;%h%&m%{2^hE!e#YmADA$cDq6VMR z88b`%Ey>OC<$=I&JA6}?%1>yS{%sN=$vxB%g21K?(9p+}Bcg&T8X;#P9c8!67|j9m z1MQO%(D4KOUJEP&>4z)9{o9^g-9Mpq$dN`%O62NyTI3~s7QAlGh_#=T3BlVHT(@3(i>5|2?x>-uO{m%!xqSIw*Y zXr(W^9iZqt&dbK;y62KXa7&BKD@igFB7Qn{*sD$1RdO<2Je8XudWA1z{!s}E26+=7 zb9r{@S%sI8@>ojvtt#N8+u9MtXMXh$zFsJT)A_#IKWgA08KR#kD2adah=yqm(lk40+1hyM6GsS?CS#r;` z@jy`O*{?fXM(A}uI4WyvcZB=wBW2iTRJudf*Jac*E>yh)b-lwki1S}^Juuwf*LdV{ zqx=W)6d|b8z6?+>-d&za7~B|d0zUraJ%Mk@j46xE&M-LZ%(4dii04n4gSIf%mR8xh znR%gMkQxMMK79Xur|UJx#yaEFZmSq3Q#-P~5o08Br0jLF74`-C3GhoWgtXFaY*Z(8 zeJSw}z5tFzxo-`9CY$zZH;nSv`-i1N9lSf@e!%H)$O7}FotD8$^K%GQg@}57#`IJO ztdR&NIK`;nSzaoyzV^E73LL+?yCb>;Z$sGLk?ZMH;Qh$}EUR<|%YXQrzt+iw%tQ%| z8hLmFI9El=1_sUGLsle^2$WCT6g-i4pS}$2R9iL)MAp{smUrHH*MN>a8lFUmtON@r0_aoXErz$=daFEm@JLPxGa{ZpeI_zP&`E~HzE9@>j?&`nAg4j!`|u4CO3D<0XUcwyn97BoRnO26t98K@^7hA2plDXmie(Aj&#&zm{%6Q$%ftMM2nS z>MAIVlszB4idv6{6x*-W*QtzE8Px`dq}zSR+TMe2OU{;m7N5ZWv)t1c`l_&eeGkhg zbtExpf!9zIPF~O64o@cKBJPKM&>bErZ+!aGWvn~t+?gIyjPe5#XtZlFNV(;JZ%~3Z zmO2@~vnFal)1DdU#xg|h>IlStBTL;%DgEW(T_i*X5orNNe0y4k)Ai75A}uhuA@{SE zaz!fn(`&E$sFi|5paweSop;_!Vmvrd7G~$l>@01-hn9KiU=tx#*CkzhJQvOsPf)JS zaN1)z``AIy*^u+6R8xh+MnZudNwOYwU#FCw9Ayft^8DESi}FW*{HLY!rQiHwFGjyx zh6iEn(hiYYZqt2N!A(~n!qOJKtT4v z5R+MPka2eOv_oD43O}OlYhc)+6SVtmZfzNuVE8b|jsE~#Lcl<9B3utq4o7L{0yjSE z-#`5DBMq9PWEqo*{y(i$L!;$-pjR%>=q1e%DrR}}zHQ7chaTfWprli_bit-iNx=Yu znz}=ehHS|sa3IUV7z$C_jyL82Ce-QDw++NYJ76^1Sw9>en*d0ajSNW=lmfvQvQx(x z;|TVnYtKDu0L>z`XVoUs8lS*8V88N z8b}9$BHaLF;22N>4OAt0c8cRjFhs*3{1itipPmStW4w6&TU)@gOVQgn%SH@4eL}c* zZFMb^{19hShzKFAjCJNS;0}abc_B+4qss_jGO*SYPr0WlkSPvy-Roy)96I$2=omS> zFd#vh5{55_hIPSl!NWjb0wOFy$=1$R=5Z`7mS<0&>d*)#&X|fgKVO)OL#Bsgu-Bb- zSJV(4rHw4`dRbar@I46Y@Fy(*03ZNKL_t(O*EcuilyG(!V>~%CT~^obT4v!jFz~50 zf^^C9N5OEG057Vew(r)A?Qj12uXL1Le~`G-va-4oqHP`ILeL`Fsgx)y)(NfefApby zo-+!f13!a65r+?~xp-&Ez=ATBWe$U%6V(n^SC?Hw_E3``#^I*JgqlA?(+Eh;oCF&w z;>e=&`;Q+#EFXOMLD^W}wBv#x(nN#O3O(Kv5CPLQF)@j_8z>tx)@KF+eAevjyk`ou z28WP+-IKHo(m{~hv`>IkL9^(rfgq+_x$3UWL4lWnD(7UF-?oDXO%x_7*`ow>?2q;J z=Vfv6jsu!-G}u2An!P>CFxWM?LU9C$m<_A?2{HmANEZF%op-%Ix;t?6w3z}MX8_Nr zh}QOQkPOZ$_JQ{z=;R*Zyx^U%8C)~1(*%&L14v%R%VYmT3|7srKdw350kPpA1GN)L z<`nIUwLH)tZ=4dAfi~~Kh9_XIGbA$0CXUfCq$2mNrLZynn=`b7qs}VeJ-KJfs_ZT1 zhupvSuwGN zfEw)VB#~j=D93}A!s`Ong%3ly5k7|8Q>HPL@eW@oz#M7vKwQYhM2bb)XQUe(+@Pq{CF{!e$IBBlo z5P^v)YyD`&V=z&SWC6%lIf%S35$?tHdAWD*e%adGln`@rLG5~6gT%ef&d)eGj>sKS z6NiuogFGw`Ms=zS=EKkR$DoqAU>NO|7#uBVB=9?G2B@+ZxoK*>9A-y}BHcQKhWCJF z1mVlQgK~Fm*~qyO#5k1O`*dcEMcSG??>aSpr_)_A$O?EV+ZH3rHRgd2df#MZ^v7eE z&d;O&ka}@~23y%M$|zGZIB9&W%+FG%J}48@k+d2{SA*Bf2zLgJe!HY$rud2x=%jt}HK_bjmf}pc+~zs@!BWMDnYjh zy!h-{I32>Qxo-9b0RRUt!k z)#(UZ!;EJ?QVIYOAbBA9K+^&XBKekne~fvd<0u*#5E5A{gE}}=D3z+sKzVG_vQh6k zq-wLU%CCynNyM1ACaxD0i2GqrqOSoT#35=!qkbQBgEPTi&cx1~TewgR;6Z%Jvenj> zzeCG2=vn&yhh1a#&GU^Ht}&mB!G}9h5%V~3eR!O_nRMd_q{v{!C(5tUrORuXH+zz;LX2l zM*^rwh5mUCI{ey&@b{f?bLK55_r2@DY&H&HM3W-4lni{w8{(1DUV-7^ zkYea%=?)HAPnlE#dau^=(*9>VWF>JlaTT=t$%rvDQEyDG2?K=lWD(Ukhxafrq!9vL zNG&`hI$;_`jS>|@Ui&tcaaAucQ!$nk#E zf`RR*zvJvN^aOIeKT#(e!YP^~BW3OG-SUGU{HQ#7aM$}sMY63e;yDB^%(sAm$vTnw zvKXKMZNpOzK#XUT7ECfrU{LigXw5{;FXOJsW|{&cMw9g?BT%_=e7v%8shQ{5wINhY z6Qmra$W|Su#6E-^NbpG($(|y(dF>OQFoTTo4(ZdG7{kM&Db5e65~mnry9IW4MHM=f zM=HFEk=9tBpO^XBS+h5uG5_W;zTDU>GeqS(JEAgV&wKm3<DgLR|zb495X}e)7Rn%M0hHAZ9^%7~woUGna{%`vgpx^a&bsbeK5{i0RDDEf}QZ z;HX#AqyO$t-<05HYwF0Ts0C*S!6?cmWVsliHh2lrVCy8wUd~W7?hEN-&s`^7N$hh1 zvW=Hp22MP$PkrijrzU>%(MRRyUjL-!8{+od=aEJa?F!a=b#+b0pLXLoF9N!jb#tyb zkF6VqGb{|;>y$}43(n8WE~C^Dg1Ndj(50J$y$;d;i&OE3@y4fqu8ei3`qK!T z-3bvAw*O5RM$5t*8p*Zwfr2IlU7h2{I0sE4`BtP5jb9S48U$4Ri1yz9U+;VSJzMFZ zUjn%`P^;aefmB07P{JIfd~+^p#+f%+Wv0yhtSA6$ND}q@#kzI@gn-|pTTKlPx_2Bh zNNe}8DE#{N%QDZ58trE~^VnM;v&&0M<>~Y1evd#iYdfI5bCq{5;ChdbES_V-G1AbaG z1c%N6#b7{Y3e!JrR2TxHIn^8?jZ6f}$p~&{e4j-$<|HIJ$SPz9^w09pA@a%Ahd^kl z1JYmGPZ=xh90sOHF3f3U(MiAn@_cxopdaadZ3At{u0HvRS9J`MCK)Q##7CIBVIT!U zF;R{wgK(HH;XY*CFIl+4Fl0P+a^?AXW-};!gEj@+j_#Po3F2U9AV%SXryrF^pf@|f z#4|O3%*0Ean1WK0f|I?Vn#gD42vxPLWf1}y0+5hMfmbuUDAON-sUrtHH8WYZws(9E z4rZE}(eU!`vC%PMUYP!@vjiVenke!S1Y^u`%#;x;BE!RvVR$}5t5opFIyMC(tNkh+lJQhRg< zjP|bsk{?;|2k*Y+`mj!{5rHSDA6fC-{9?$zqUkRY|WeuuAi1m z_6)NvIR69-%3dRibbM6KE(7Od-1yVlro_C6pOH*Fdi2QWz&=+GVr$EFBOvGg3FM+_ zFeVWh5~l;;;3AD?f-EDX2TICe1pMqd$fP(Lf@Is6CngQBapb_UK_$k^1XA+7o`Edo zQqBj)d*tO0t7WqDqVOZN{lH z(2e(Ct$5bh4(`3x-B}BqBIlL=Lh#Kj4Gfi@dQamz>!x!{z<=KP(R)+$*oX@=5J`GVHupYq2ED z)sa;sVrU>UP0+iSs9BTw=DhpF#J-+l0-7q8a6>?pZe=XGOASI140%?ES-|1n87>`5ic8B!0gI9yktWU}&I@UA_`BJJ>s@uo$x(=qN}H9`!fJ!`6-f>SHW)SmLAB z%gBPvaMst$_~e+I5+jH~HmjKEYA~%MR~`a?@-sfe-cIULLW+}xjsl``Ggx*1BaLeP z`ufUjaDDxy#_{f2U~tt7>nsP1BeijAu`hRMwF-H|DS3WoROm3M5Vv>;S?ElA1TyE} zM0W%o5RG^pbz8-osHsZC$xH+c69Go1!Hv5~0T!P#m{N6RIa(gon$h+kI}mh@S+@^9K|3&kfMZB=bKYMhl@a@ z%5!2Z`3%((F`{Gw@E+#pl@z94C5Pjjaoux?aBD{i-^Vy3ielY%cHRR3XMg~MP0F*u zP+;tu5Da82Yx(qwkBvD{ipV$5FN3U54qOF7uSC&?I>?Qv0p;H(Gq!ptYHEX3;0hqT^A6Z6Xn`<7myy5cr}A#vAR-v;8mes`~Y@cz4b zCUZE-Ex8m3qVW7#V`gPw{w2R|ZJ8mD5X9~6iMDZ8xjufE{XhV?Bcc?h{?5y-GEVC# zh+Vg4BD+6dy7$D>fi`z2^U@bT^@Pl4`^|9qD_Vp+oF^~+W zC!-rd;C7X1s*qf%pCU!e^T%k;JMQ`*(;ll#H#Q4L3Gtb5ckAW04x4TW&MSt{@*V^~ z0;npLO)%RTg8PB3NutBOvsQF@J%9e9tgbD~D`GF;@M$F_6U0bkKPW@us5lR-1MSHK zxDJVjGnh<1oU zXmBSgZJzbzyg^#S79f6Qx%lMN^Z)lVZq9bJ{rK4I?FQesPJ+HZLZ2*{@`Z}Jb@Vi^ zz1>o%&uoNA%NaMNiAH=>-{b(q?Xo<$|DdmLlD5Lg(vu9P%uH(~C{w0YrX%B)JaQFY z3m>q;`1N<2Fk34}aIdZ1+aZ97jSNn1BNP10DzBr!elsC_(*~wI6BxuOO><{*BLb+W*}&A*TRJ(2q;Aj%s9UP=JH>zyELl zzI49)#Sj`xC!k=VfK0*#*m9vbWJu<=$PD%?8wx@an+Kf$U^PFxj^^b14m~vyCq8b7V|xx`+uK9MIx4QWtu#j37cp1dVj{F%A}}h?2r!e`W#S z1JQt=!8HgeB05z2+c92^NQl8rppn5yvVF(LGdfmniAch7fFa4SLHIXDSZUdfZKL@( z+DrrFd8vBo)VYhuYmdQ!m=F;nkXl;2<8|{a5Y}OC25oPUxiE@|`G~gES|bELzTkt9 z5fkJPL^}C!a?-s*5P(`<+HC0T7|}qtsgyjMz^4#nMm=;oUU(>Kyyrdc2<0=oBH0`y zGVX^U_3}K^0)h5HQ)cF8bd1*BD~p>$Vt0T#8%&YB>5q4&g5!A4?L()PtdTWEVHARj zG3Vb-xrC^=KwE40F+5ZF75fLr4xP~{pj;@aZrh2K7%l=DvMnHD%0BQz$odeE+TPtU zo4`45zIbUZzsbV}CO#467#bZiNFvA>9quakN=xAU!lJMwEn;i;?v|ha_{}obh4fVi zS6wGC1L-S+==&e}oIp}QlblWnajEKoaGoeHC198?<4!*9I5OF6l2%O4Rp(mLFVBe? z4L^D7Es-8H2q>p*z1)-w#Cc9>f${^$SEiRT?}I=WH0Q*ib*fCz#j(dcf-tCeb`e>d zDjQqdWsMFN1j>3>CJt~N+E6V@KNl7K;j9vnkTfXvRb{_<_GI}=daKkrp3MR5L z_L|NI&=(L7<|-g5&V*WcycM#?iP24>AP;B8^At3}PKMegX8EV`)S^C^x_!6}H|PWo zTRU2{7eZdVQ7lAAh&590MA5D*gB{Mat=`=+$HO-zMfPc&eYjh=a&%)5LgTgYVgM4* zlesg$Ajv%hzz7EMK1%l2fq|?8SJ-$YA>mRE&-eH&ezzqP{#k9lWeE5HXD1Q7Ge}5z z!vv)w4-zQrK(YAG_%3_`&Nk)JsD83eqCTZ#DS;Ur1hqWlh~R}QMgnrea7Aa8>}%sd z2-04TofuT_Mm`LLe8s*HK}#u=5>>?hkm+aCLg)jc!j3?{SA{h{p!k`f2<2oEz+eBQpdLfL&gv;|Begv2>I6P1eBKL~X!x(W-5E^lS+|xJ^ zJOfA=JViU`F~)GR$;oKy-3C9zD02n#r@`5aa-r z{y1MIQlcZk&)8^<-F?%uOBo0VcGkm_k-#W5Ui+CjBy7y#43Cm;5s7X#IqxTt^x{Ie zOH|@Is+UM)BU*z|clsOi9S+H68QL;oR{_v9&NRUmBY2|^Pxcg1r!dUhe;Q%b{J1V= zRScz_%)saP*dbO;kqmx^5HD!hWXd%!jP?6J#q}JwIFCee$6JEzXlU7_GKXz|Q;8UdZ!;csMsZFX?V#DuF(0MZg$N z0q1hm*WmC7Tsc$RkhZ5+%Hv0LO6+bcWdO^BXZrTc48@fm|^9H8T8wnxOq^dgm#3w-+xTnUmVbOA}lvAShB9cNW zgHq5ni9%$fMLQ~Yf)1$;nkcE>@z!eUHWwqhKoJ)nhiYNiR z860zhltDY2NZLeHYuSeN#m2%_ixv(^KsbOTBIspUa@FPymgz~9evb_{y%tqHqXE=x zF4zCy!M*am@Bh%!nCFs8z$G1JckGy9t^UpLf36gCT1EMgqcSI|WlWBA(Wo~w% zT)<7}!V+gRaB3z*_^Qi|jJjd@H#gLJxQR;H1S}$D0U4cw7{07)HhAV>gh8MBezG2(BO7wYO_n+-f-OLv@)0aCFf0UF zY4{IhZ^vn&V{2Z?1r~{Kp9;Hs7ZiYiM zai1ehT{088MaUM_s6bkj*3JyPGNY{%J5|WLx>k_r;l2B1?=TRaa>mnB2B9*@nTm$s z6?>B)XCw@B_Am8%vOBaOX6NZaK65X^*I^(R<5uH9Idp?%gVw^SsWLLsDNo*eR#w)Q z`a)u4`F1{BUYb1<5Rq+4{JOldLx`YGIqnH+_?({v-A<*fIs>2qJWG%xUeBN))<}s~ z+KQ`y6rUp(VW3k!dbU|cMhD93(z4|R%Du}=a2V*QNQ*7#09onw?!IT4cF}g$Go#_O zk}cC=!eB5s4%|27KoAZlKJM<*n@#pq4Dc;2o}N3w4_*ZhgY_lo<}>B}AV+QX4{~+p z*#jk`6_>toC622zzr5~QlDNNi*YceiD}1EdQN(L_ZGxCVc`r?)f<2R9Jf*W%gXS9M zWOvhk$lvExILsQ(J0pTj6oiXlsqtb&U)5a6h;7g{Yr_?-kmqvejzJ-T0qxS(rF*D( zW~RhIhnn<|s0*c`(Gjxm6N#8`s1O;$HptWJ&nqw|6P2Zu3ez1W$h2-UFloa!WK}A= zA!DojsDK_04>a;dfw8Sa$ab0Ga8u`x1_2WzbjUTilm3^H2US@yKQ}A43{5Z+DR}}p zJ31yNM5FlP%scL#|5f|gN{QGG0!Cg#kR@*i`&C=NaqQSiWvQ#mVB^`f-)+Rg#)%++ zh=xNGX{s{JwFJRUw~QbA4Dw>|cuD(uI3?kXgzMA-5XtX7lAjFCvxTw>F|lX8uIpZT z`0$}5eh}JW5WRza_dDwYUoGW<3-vOv#{}ObUt^<`v_YGuMVTov%pg2QLPfb^a;A)T z@gZ9#5p+3GHUsq{5Y@IH=FD;rK|7fTG+-%~HDwwpz6hWB2Veh2>HPL@|8|cJMwWMZ zj#459_fm(jzaPn7TD8z}X5k>}QM14hhh&17(xpZYBSgg7oFEy#Mqjlx5Q$L{03|3o zS$N77w%!gf4H7+j2w{W%41>cBQA;E;hA<{{PYp#P(1nnt8Q3V}L8+-9#7K7rWcbc-UvOxAmw@yLjoFfI%22IJ1Eg67$ft~H3!;4cY#Fw|T# zjx?Nv1bSpcJQJLdfm*pPvoooI;y{$%L=JU;OcF7gb46M(qN82Z5f3#&5VX>7ovaMQ z#X*hA7o^Fwr15)P3+u&N@fpcjJLyyJU0X+{*OzC7p#=H`O&A{S_Swz^IUEv#It~g* z3r4PqPC+80ubv2(jlQ_JB>JUF9Rf|WGX@-aMj1PdF;Z8fO)^F3Yxkf`O^*5e2~5fQ zK$ny;RXs0~rAKXi)PvtsnZ@(19P}y*RS?uEK+u)7_Nid-?Gi9P8wv>)3#M9t!T#5t| zfTbO(dE|@$00l`&L_t)VZjwlm6G#%wknOQ=Ekl(~+1uGQkr^FD?J*fBWgE^lgR3%4 zl=4Ez%Q$ZW819KoIC~+^igjk+V!Ikdt_I51c9oJxL_Da0C0s{hN3ArZ2Qp%u9Efe~ zH)n+GI0~X!7Y7{ij+Oixs6X|3Y_>eMt839zgrx{t2*}$PIyDmguCa5VA+d4nXM*q$ z!;=)4eYXL1RWz-&IyO!~E2E?fA^1qsRVLIuv|a-D_56i+Ixau=GF`k^Xy2@)1f8_7MnlIJQLdM zNoa;eqCqxE_H27(6u=(SA}JjYm7|kPlVu;UrXXURfrt=>K+MdO`T1!H&6H2EA$-R8 z#FzolAAjplO6MzI`JEolma(#243JbJD297vA{bCAH93rc>~+VNrhSG*i?gTJeWpMR zQo>vSFf8x|s6ngku#D8n$@*2_o17{KC%`CV>*xL8uej6ccoWyq2kJN)-?B z;8L4}Ghn%_GVA?($cK-u5rwIhnM0LwEwd|_d_ zT%2CmU4m05TeYRJN^Tn{IEk=ppFgwBxyFzw!{azZphuWIoiRlG8T2()&f%kIW_l7l zL3}c8Fwk1ip>%8D5DBc zz*3(~xsAy2)cfv~$?m8_!}vMt11f;s9wxmukUG)v(1xs|)95lBY}9KyzhD^Gq}>>5 zkCa{wBvvHRtt_vWXV0HXv;zsey1?m78jRb|4$3hyQeMD_ADhVh_%nufA)O17RScNA zqZ0|->zL)%b+o&?t>PttUSP{>pXulzE-5*?PX@+)p>wADPlLm6wUz?tn>4xCqf$> zvhHaW#8F;@{L$KGTAU<{P6mQ5_7VIbI#JA68GdzoDoVy$(_Rc(hJ$FRAHjU)r$8cQ z09*oH9cn$_IJT%4f&`>{K~FeXRQ&^OASmHADlqaJN-sBl!=ICQU|?fM zQG$pjqNHN0L0%;Lkw<6$2Q^4J#+-ufYEU Date: Tue, 19 Oct 2021 16:08:09 +0900 Subject: [PATCH 080/433] [jsk_fetch_startup] update move_base params for fetch15 --- .../fetch_move_base_common_params.yaml | 110 +----------------- 1 file changed, 1 insertion(+), 109 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml index 9da82ce6e2..0d3130cdcb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch15/fetch_move_base_common_params.yaml @@ -1,112 +1,4 @@ move_base: - controller_frequency: 20.0 - global_costmap: - inflater: - inflation_radius: 1.0 # 0.7 - cost_scaling_factor: 10.0 # 10.0 - obstacles: - min_obstacle_height: 0.05 - footprint_padding: 0.05 - publish_frequency: 1.0 - local_costmap: - inflater: - inflation_radius: 1.0 # 0.7 - cost_scaling_factor: 10.0 # 25.0 default 10, increasing factor decrease the cost value - obstacles: - min_obstacle_height: 0.05 - # default 5 (http://wiki.ros.org/navigation/Tutorials/Navigation%20Tuning%20Guide) - footprint_padding: 0.05 - update_frequency: 5.0 - base_global_planner: global_planner/GlobalPlanner - base_local_planner: teb_local_planner/TebLocalPlannerROS - # base_local_planner: base_local_planner/TrajectoryPlannerROS - GlobalPlanner: - allow_unknown: true - neural_cost: 50 - lethal_cost: 253 - cost_factor: 0.8 - default_tolerance: 0.0 - orientation_mode: 1 - visualize_potential: false - publish_potential: false - TrajectoryPlannerROS: - yaw_goal_tolerance: 0.1 - xy_goal_tolerance: 0.17 - max_vel_x: 0.5 - min_vel_x: 0.1 - min_in_place_vel_theta: 0.5 - escape_vel: 0.0 - sim_time: 1.5 - sim_granularity: 0.025 - angular_sim_granularity: 0.025 - vx_samples: 10 - vth_samples: 40 - meter_scoring: true - pdist_scale: 4.0 - gdist_scale: 2.5 - occdist_scale: 0.00625 - dwa: true - TebLocalPlannerROS: - odom_topic: /odom_combined - map_frame: /odom - # Trajectory - teb_autosize: True - dt_ref: 0.3 - dt_hysteresis: 0.1 - global_plan_overwrite_orientation: True - max_global_plan_lookahead_dist: 3.0 - feasibility_check_no_poses: 5 - # Robot - max_vel_x: 0.5 - max_vel_x_backwards: 0.3 - max_vel_theta: 1.0 - acc_lim_x: 1.0 - acc_lim_theta: 1.0 - min_turning_radius: 0.2 - footprint_model: - type: "circular" - radius: 0.3 - # GoalTolerance - xy_goal_tolerance: 0.2 - yaw_goal_tolerance: 0.1 - free_goal_vel: False - # Obstacles - min_obstacle_dist: 0.1 - include_costmap_obstacles: True - costmap_obstacles_behind_robot_dist: 1.0 - obstacle_poses_afected: 30 - costmap_converter_plugin: "" - costmap_converter_spin_thread: True - costmap_converter_rate: 5 - # Optimization - no_inner_iterations: 5 - no_outer_iterations: 4 - optimization_activate: True - optimization_verbose: False - penalty_epsilon: 0.1 - weight_max_vel_x: 2 - weight_max_vel_theta: 1 - weight_acc_lim_x: 1 - weight_acc_lim_theta: 1 - weight_kinematics_nh: 1000 - weight_kinematics_forward_drive: 1000 - weight_kinematics_turning_radius: 100 - weight_optimaltime: 1 - weight_obstacle: 50 - weight_dynamic_obstacle: 10 # not in use yet - alternative_time_cost: False # not in use yet - # Homotopy Class Planner - enable_homotopy_class_planning: True - enable_multithreading: True - simple_exploration: False - max_number_classes: 4 - roadmap_graph_no_samples: 15 - roadmap_graph_area_width: 5 - h_signature_prescaler: 0.5 - h_signature_threshold: 0.1 - obstacle_keypoint_offset: 0.1 - obstacle_heading_threshold: 0.45 - visualize_hc_graph: False recovery_behavior_enabled: true recovery_behaviors: - name: "conservative_reset" @@ -157,7 +49,7 @@ move_base: limited_trans_speed: 0.3 limited_rot_speed: 0.8 limited_distance: 0.3 - planner_namespace: TebLocalPlannerROS + planner_namespace: TrajectoryPlannerROS max_trans_param_name: max_vel_x max_rot_param_name: max_vel_theta max_planning_retries: 2 From 132da3aadddc34e45eb4d284aafe1533d1339456 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Oct 2021 16:57:43 +0900 Subject: [PATCH 081/433] [jsk_fetch_robot][jsk_fetch_startup] support development version of fetch_open_auto_dock --- .../jsk_fetch_startup/launch/fetch_auto_dock.xml | 14 ++++++++++++++ .../jsk_fetch_startup/launch/fetch_teleop.xml | 5 +++-- 2 files changed, 17 insertions(+), 2 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml new file mode 100644 index 0000000000..be7b25f86c --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_auto_dock.xml @@ -0,0 +1,14 @@ + + + + + duration_timeout_undock: 10.0 + duration_timeout_preorientation: 20.0 + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml index a9711dae9f..0b342d0db1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml @@ -94,6 +94,7 @@ - + From a711ac5745a8e7d025c8f7dac112df69c61517ee Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Fri, 19 Nov 2021 09:31:20 +0900 Subject: [PATCH 082/433] show hint of trashbins --- .../jsk_fetch_startup/CMakeLists.txt | 17 +++- .../launch/trashbin_occupancy_detector.launch | 82 ++++++++++++++++++ .../src/trashbin_occupancy_detector.cpp | 86 +++++++++++++++++++ 3 files changed, 183 insertions(+), 2 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch create mode 100644 jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index be9259dac6..b65f51e87e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -10,7 +10,10 @@ endif() ## Find catkin macros and libraries ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages -find_package(catkin) +find_package(catkin REQUIRED COMPONENTS + roscpp +) +find_package(Boost REQUIRED COMPONENTS) ################################### ## catkin specific configuration ## @@ -20,6 +23,17 @@ catkin_package() catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks) +############# +## Install ## +############# +include_directories( + ${catkin_INCLUDE_DIRS} +) +add_executable(trashbin_occupancy_detector src/trashbin_occupancy_detector.cpp) +target_link_libraries(trashbin_occupancy_detector + ${catkin_LIBRARIES} +) + ############# ## Install ## ############# @@ -54,7 +68,6 @@ endmacro(configure_icon_files) configure_icon_files(blue fetch15) configure_icon_files(red fetch1075) - ############# ## Testing ## ############# diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch new file mode 100644 index 0000000000..2c8b72f2cb --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -0,0 +1,82 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + use_indices: false + + + + + + + + + + + + tolerance: 0.02 + min_size: 100 + + + + + + + + + align_boxes: true + align_boxes_with_plane: false + target_frame_id: base_link + use_pca: true + force_to_flip_z_axis: false + + + + + + + + + trashbin_l: 0.38 + trashbin_w: 0.27 + trashbin_h: 0.51 + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp new file mode 100644 index 0000000000..1f453e9f88 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp @@ -0,0 +1,86 @@ +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +class TrashbinOccupancyDetector{ +private: + double _trashbinL, _trashbinW, _trashbinH; // trashbin size param + ros::Subscriber _trashbinHandleSub; + ros::Publisher _virtualTrashbinContainerPub; + geometry_msgs::Quaternion defaultOrientation; + +public: + // constructor + TrashbinOccupancyDetector(ros::NodeHandle &_nh){ + _nh.getParam("trashbin_l", this->_trashbinL); + _nh.getParam("trashbin_w", this->_trashbinW); + _nh.getParam("trashbin_h", this->_trashbinH); + this->_trashbinHandleSub = _nh.subscribe("trashbin_handle/boxes", 10, &TrashbinOccupancyDetector::CheckOccupancyCB, this); + this->_virtualTrashbinContainerPub = _nh.advertise("trashbin_handle/trashbin", 10); + // init default orientation const + this->defaultOrientation.w = 1.0; + this->defaultOrientation.x = 0.0; + this->defaultOrientation.y = 0.0; + this->defaultOrientation.z = 0.0; + }; + // destructor + ~TrashbinOccupancyDetector(){ + }; + + // draw virtual trashbin container and publish for debugging + void DrawVirtualTrashbinContainer(const jsk_recognition_msgs::BoundingBoxArray& handleCandidates){ + // Expected get non empty array + boost::shared_ptr handles, trashbins; + boost::shared_ptr handle, trashbin; + boost::shared_ptr handleCenterPosition, trashbinCenterPosition; + + *handles = handleCandidates; // TODO: Do not use all boundingboxes, use most likely trashbins + + for(int i=0; iboxes.size(); i++){ + *handle = handles->boxes.at(i); + // decide trashbin center position + *handleCenterPosition = handle->pose.position; + trashbinCenterPosition->x = handleCenterPosition->x + this->_trashbinL/2.0; + trashbinCenterPosition->y = handleCenterPosition->y; + trashbinCenterPosition->z = handleCenterPosition->z - this->_trashbinH/2.0; + // make BoundingBox trashbin + trashbin->header = handle->header; + trashbin->pose.position = *trashbinCenterPosition; + trashbin->pose.orientation = this->defaultOrientation; + trashbin->dimensions.x = this->_trashbinL; + trashbin->dimensions.y = this->_trashbinW; + trashbin->dimensions.z = this->_trashbinH; + trashbin->label = i; + // push to array + trashbins->boxes.push_back(*trashbin); + } + trashbins->header = handles->header; + this->_virtualTrashbinContainerPub.publish(*trashbins); + }; + + // main callback + void CheckOccupancyCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ + if (msg.boxes.empty()) { + ROS_DEBUG("No handle candidates"); + } else { + ROS_DEBUG_STREAM(msg.boxes.size() << " handle candidates" << std::endl); + this->DrawVirtualTrashbinContainer(msg); + }; + }; +}; + +int main(int argc, char **argv){ + ros::init(argc, argv, "trashbin_occupancy_detector"); + ros::NodeHandle pnh("~"); + TrashbinOccupancyDetector node = TrashbinOccupancyDetector(pnh); + return 0; +} From d0e2b8cb8a2e1914a08fd8e5e45d82c98bbe1c75 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Fri, 19 Nov 2021 11:18:46 +0900 Subject: [PATCH 083/433] publish trashbin candidates --- .../launch/trashbin_occupancy_detector.launch | 58 +++++++++---------- .../src/trashbin_occupancy_detector.cpp | 21 +++---- 2 files changed, 38 insertions(+), 41 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index 2c8b72f2cb..579fdf7453 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -1,7 +1,7 @@ - + - + @@ -21,25 +21,24 @@ + + + + + use_indices: false + + + + + + + + - - - - - - use_indices: false - - - - - - - - @@ -54,7 +53,6 @@ output="screen" clear_params="true"> - align_boxes: true @@ -65,18 +63,16 @@ - - - + - - - trashbin_l: 0.38 - trashbin_w: 0.27 - trashbin_h: 0.51 - - - - + + trashbin_l: 0.34 + trashbin_w: 0.24 + trashbin_h: 0.49 + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp index 1f453e9f88..0f8d93bddb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp +++ b/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp @@ -20,12 +20,12 @@ class TrashbinOccupancyDetector{ public: // constructor - TrashbinOccupancyDetector(ros::NodeHandle &_nh){ - _nh.getParam("trashbin_l", this->_trashbinL); - _nh.getParam("trashbin_w", this->_trashbinW); - _nh.getParam("trashbin_h", this->_trashbinH); + TrashbinOccupancyDetector(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ + _pnh.getParam("trashbin_l", this->_trashbinL); + _pnh.getParam("trashbin_w", this->_trashbinW); + _pnh.getParam("trashbin_h", this->_trashbinH); this->_trashbinHandleSub = _nh.subscribe("trashbin_handle/boxes", 10, &TrashbinOccupancyDetector::CheckOccupancyCB, this); - this->_virtualTrashbinContainerPub = _nh.advertise("trashbin_handle/trashbin", 10); + this->_virtualTrashbinContainerPub = _nh.advertise("trashbin/boxes", 10); // init default orientation const this->defaultOrientation.w = 1.0; this->defaultOrientation.x = 0.0; @@ -39,9 +39,9 @@ class TrashbinOccupancyDetector{ // draw virtual trashbin container and publish for debugging void DrawVirtualTrashbinContainer(const jsk_recognition_msgs::BoundingBoxArray& handleCandidates){ // Expected get non empty array - boost::shared_ptr handles, trashbins; - boost::shared_ptr handle, trashbin; - boost::shared_ptr handleCenterPosition, trashbinCenterPosition; + boost::shared_ptr handles(new jsk_recognition_msgs::BoundingBoxArray), trashbins(new jsk_recognition_msgs::BoundingBoxArray); + boost::shared_ptr handle(new jsk_recognition_msgs::BoundingBox), trashbin(new jsk_recognition_msgs::BoundingBox); + boost::shared_ptr handleCenterPosition(new geometry_msgs::Point), trashbinCenterPosition(new geometry_msgs::Point); *handles = handleCandidates; // TODO: Do not use all boundingboxes, use most likely trashbins @@ -80,7 +80,8 @@ class TrashbinOccupancyDetector{ int main(int argc, char **argv){ ros::init(argc, argv, "trashbin_occupancy_detector"); + ros::NodeHandle nh; ros::NodeHandle pnh("~"); - TrashbinOccupancyDetector node = TrashbinOccupancyDetector(pnh); - return 0; + TrashbinOccupancyDetector node = TrashbinOccupancyDetector(nh, pnh); + ros::spin(); } From 64e9204078085438af66287b23ec7fecb2bed2ac Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 7 Dec 2021 16:11:46 +0900 Subject: [PATCH 084/433] Automatically bind rfcomm devices when booting fetch --- jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 7b4cc539a8..99a36f2a0e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -47,3 +47,4 @@ windows: - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log - jsk-dstat: tail -f -n 1000 /var/log/ros/jsk-dstat.log + - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log From f791d40457414656dc390d7b5e473d51822a1f97 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Tue, 7 Dec 2021 16:16:00 +0900 Subject: [PATCH 085/433] use cropbox and detect whether pointclouds over the height of the container --- .../jsk_fetch_startup/CMakeLists.txt | 31 ++++- .../jsk_fetch_startup/data/burnable.png | Bin 0 -> 17972 bytes .../jsk_fetch_startup/data/icmark.png | Bin 0 -> 115170 bytes .../jsk_fetch_startup/data/plastic.png | Bin 0 -> 20095 bytes .../launch/trashbin_occupancy_detector.launch | 100 ++++++++++++-- jsk_fetch_robot/jsk_fetch_startup/package.xml | 2 + .../src/container_occupancy_detector.cpp | 126 ++++++++++++++++++ ...ector.cpp => trashbins_pose_estimator.cpp} | 62 ++++----- 8 files changed, 275 insertions(+), 46 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/data/burnable.png create mode 100644 jsk_fetch_robot/jsk_fetch_startup/data/icmark.png create mode 100644 jsk_fetch_robot/jsk_fetch_startup/data/plastic.png create mode 100644 jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp rename jsk_fetch_robot/jsk_fetch_startup/src/{trashbin_occupancy_detector.cpp => trashbins_pose_estimator.cpp} (53%) diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index b65f51e87e..9b98af04b1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -12,8 +12,20 @@ endif() ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS roscpp + std_msgs + sensor_msgs + geometry_msgs + tf + tf2 + tf2_geometry_msgs + tf2_ros + tf2_eigen + tf2_msgs + pcl_ros + pcl_conversions ) find_package(Boost REQUIRED COMPONENTS) +find_package(PCL 1.8 REQUIRED) ################################### ## catkin specific configuration ## @@ -23,15 +35,24 @@ catkin_package() catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks) -############# -## Install ## -############# +########### +## Build ## +########### include_directories( ${catkin_INCLUDE_DIRS} + ${Boost_INCLUDE_DIRS} + ${PCL_INCLUDE_DIRS} +) +add_executable(trashbins_pose_estimator src/trashbins_pose_estimator.cpp) +target_link_libraries(trashbins_pose_estimator + ${catkin_LIBRARIES} + ${PCL_LIBRARIES} ) -add_executable(trashbin_occupancy_detector src/trashbin_occupancy_detector.cpp) -target_link_libraries(trashbin_occupancy_detector +add_executable(container_occupancy_detector src/container_occupancy_detector.cpp) +target_link_libraries(container_occupancy_detector ${catkin_LIBRARIES} + ${PCL_LIBRARIES} + ${Boost_LIBRARIES} ) ############# diff --git a/jsk_fetch_robot/jsk_fetch_startup/data/burnable.png b/jsk_fetch_robot/jsk_fetch_startup/data/burnable.png new file mode 100644 index 0000000000000000000000000000000000000000..6b00521962842c6a4cbab07ec0dfd7497499dd11 GIT binary patch literal 17972 zcmZ^KWmud&v~6459Xe=n9b|BKDDD)OGPt`HcXxLw?pB~U#ogWA-R;hI&d+=Ak9jih zGkKHA%HG*)WhY^Z@{%Zs_=ulAeL|7?E~X4ACq8}pj0F!1`4)$$+zBZ@J1R?xe5x8J zJc2wxn+nSbfBIA#gY;?$19?WU`>yHu=@V-2f1l3-wk6Sm)+}le~a~TkW3W9l+Q;eA}c!$a8E!YRBTCpir-$ zu^LeOd-KsgH>lLOEZwyG-eMr)_FRoxG~+m`SD;Dq`bwi*@!do~doEk5Dn_ zEHWlo7n}8vPqsp@uFG70!?W)%2iJ)xi3H{#*jE&@GpkT7N-G6YAG&a+k6uyuYfCC) zhm-E57sX!u#C8$wx9)b?LTI6?1l#RUzTSp|r1HMPUYhbqE)cg~D+t~V2m05lxsmxB zbwn5#QHbY#709K(I_{ZVTwC~A{{mJP&ebhQCIAQch+{G2_(`!kt5dzyZU`- z1IE%tW;wKC5;)uP{GxoWSva1T%OOZP6j}75EIuA&8{V1b(5fJIbr%gQ%I{M0b;_qH z2lV2`X%Of30bD=YM_cBSLBe^1P~)0!?guqW#hDaX*HFg`sGw9VcZ3*6^NnM!-8Gg{ z-hG<=Rglk;3e8XR=0}mD>YBF5J-^M9|82FkUp=9F)t+l|fLl}oyOen!&kF-=tmKwv zVUxvGD;!);)hQ4|o1BoBX>Zd3n4ywSWD%$1sqT;u#$HmczftWkzt(p&KlB(k=Gpih z;Nd=+R<==1E*h>nsc7|3KLK*={*snI2#fDKoid^CywjtUo;(27TJI^)%IaqEeoLx- zXFl=1-T;Zm0b3WyMO%#0CC0rTe`#mGP9f%~RDydpyiJMzlDLoZ&^hD=!}`fc9tBCV z&?s#od_0n$d>k6lSA5N;*#el{PGkc`Bc1uRmgfhMp^d-Cp-8(0V+D8j)Td~M-SXWq zu;MW#*OHM#pR}FB0+hf3nAwJ6kAE-H4)sikm^?f*9sOneh4j zK@cE4HqCpUNa}gy^%lkD$FfheHH1sarj<&(uEJBe+;C!kFa} zgDeie@~5q3Td5}jCfzcB?m0CtR<;&UBHv!!PD*Z`>z;aI8;{|6_;FoMk*8*%eGh5! z%R2Kievhuliy%0>U6FLWKfLwe3D3&fD|y``0~y$R`2q)vh8<84NDbFY?C}qOzAnW9i5VI%yh!$3460wM&S@9pF9>Fu2cB|saj9Q@KPBtEyBg4|<&FW24 ziF(!#T_Xe|x(Z{A@W}sq1|@{m-ReKEIEHzx=qLk8-Wh*NW#I(-%^#QmhGO0o1daGv z_2X;7ku7C=L$H*5O9qVPdE%aMCmkQ30rZ5&1G|X8#0W;+K|lk?S<0)pgff|w2MRO`PkzPVTcP4PaSA8y&2 z)Za(EGZ-!9ss0&-pyzuE+YhY1*Op>rf_ch4cC^8F`|&$W$tAr&WacZ~a~QO*!5sNDsWswvE$f zkYOW0M#AhpVx#FW@H?gUyf`PW_I5I#L#xG{_swwLe#n@i;W)j*xjjl_1y{RRXFdy< z56|%{DHvk?iYVDY8F~J-^gvlS6n7?pqnP_99)!t!eqL2Z$16;La-k@K0&HZCPh1{@ z?{mX$WPJtcsaXB{<-yAnEP}$oM%7RL2?a@i(oR}5)sX}MC0~HS z>umyZl+bf;GENW~zqA`{UZTKCFnKTvE;^g<)WiHr#mV{$gZ^R`=LWu}a@+`hkzqJy zw(!@Z9wXQ$cx`j{NiKB%CD3#2t29IzaMl8J%@9`nQ%(GO`~Vu(7zKbS!zAc zJdVo;0g!8hUI-Oq9pkHBE+#BBpA{iZqLAwvlRtN+Wv%UN6%FC$I7#clmP9)4uR0)c zJO^8*y__&M=6n?Ub7DAPt2K=2KT;9f#55KWYLDf^~#b@Nnk;}YeEQdrsdcAX+Eh$m% zr97OBdqI5*;9hjlJ(iYRSGT77$A1wmN8KJ;|A{ z>5!*<$($Mh03=3T#yT@u56`{~m(M5r-jW)LjnL+q57#475Sp~xb^^({ds>heLj(}~ z$q&9~YFjBi{*uBt&@S`tMBOPM09%0-aeG9u9QYOZ$C5L>i}o6RT}=&Wkz5DNw@#Tb zH22V1ZN0&>Q4Raj&-8Z!vuj|)l$ zpAOVsOM}=PXppwH=H@ESAB~p&{aLRuscft@+U3L;?8HBdm&o96v}tSEE8r%PJl4F> zPxw;nhGE&YpT}DN zl?9=M->Il(9?m_jrbt8TVg6q9J$F896``V@bSS0Vr&MpXbmh~ic5U{qWiGiAXJJc}>W z^qSV(si*=LiE8CB9owKZ<*&D%<5Ao6@ZmSl9)OYTWhk^7DkcQ$SGN;0PO=P~VjKxg zM6~Ymvc*MSTT}KIlT@L=$ym>VAUGnPlAG(Qm-Cdo*UbX*G72DV)w(?#y$<}GimPlT}FwZJzKxAPlRok|1J_79jEQa*3%xSLe z<}Y#OpevCH@5(?hWYK)8ETcvjxcv5zl;>uFwx}OmS8yJFZzrrajzKdBlke(iUzWB-fd>U2$9#YLxsm* zYh#A&W1>H%YL?ZMMgavaYZdReGvJEB+Yrr#f|#Mf!Q9iJkX#YazQnC%oi8jp#FmmH zSuDd?8u@~LQn)Qt2wr5i9q>b36?+!(NU~2t-^Y3%C#_CR{*=5=jgX`MHhD#2wnG4i zluzt#Tt)K^b?FYyqiDilEr!qHiPo%hmkHF!Y<6dUTGTSjQZ4wV07~WuD=E4TZtlOb z1@fQQhNR6OCevO`D!w=Stc{iZc@s>lL#}UktFksfxQy;xWHnGmRgJtvzr)k}CYqLq z6F1K|#WDY{|JAM2SltJTPJ?ka$H(ScNEops=fLBGe`EuIlFs#KF>~&;5stuXPe1LX z0Igz}0w>=Wqt7b$O>?OB<$G>^V6jCdyXKud@9^SgtmD;X%zZREptJwQV@JMt&xBUH zY+g5IjyUzr_fvIw{cF}#$o?uE5qCsDT{q>S7sNv010E$uwzrx^#% zk zNaLv~N$r%+-<~>F$BH^>@OOv-=Gv?c;WG|*bS5*+<}m^0_xnw$t*vyVRI@LA({){w z^QM1}0#@@g_VWk3oKN2#>cTGChIB|?W1>87^WwQV@x%$uWnj)e$@eZKNsA*Y%t;WS zhM7vUV#nug4JnRxGqgXc%Y@R!g<})f@supvK>_HA3iH7`$aaH=`X(?+bTkUf6V%R6^#)73F}{RQ=|>90F~%$rSWM7ONVf<)Ehr2ZfjKD;z%>- zx~`2O`@FBrpmEZvyA2w`rd20mdJSU(@UssSs93CZ>~VXIp-_q#+OMbp^gfU}p;q&c zi(y7{d6i4`-Dy43t%*+j_io+TV$MncV&Lkk; zVOI*~!G6Z@ruE=Mpgur-kEWE89eAcy@V%RP|J?I z^&u);_-w@IZHw6C5|*RHVOZqF+MbMMy(izR&q(_e`*)9xk}$dUIzK-!B(w5? z?}h||M$+uD7-=yr``v~XDw52nMiEKjy>O0L}&y{IBA{klb)RIXi@OGSN_B!3nc zGNO0|7(Z`?EpX7v#ytC{(N0BT~~wz372q>B9yNZr7WSp2hryso7 z*el*KRGA}5kg*;VQQGlnm~`6OJ%3iQbFc`|VkgYbf=IMl+N}oDQz)sP>#Kh9Ere zN`b&kb1Sy=qI*)t2xuj1oy|76kwS{W5~zi(I05PWE-87}h1-DxEq(iOEdgYPqreWM zxUFE0^>+*j&>QVTQZo)UUqfv9{UAB`pZB0-&-a3_!5PjWgjVh44n^02aI-{S;3=2S zhadS)+22Eudd`J0%l+xI=3Ht^zHjA?WmurmM#uQQ#|Q|UV}dw9HJ;_T$0vzB_=SrQ zOGPh`e=$;W2`;$1C$GF?!DEOe_56BQtYTc!R;sa;mtJ|kXapYBgZQ9$umr3`ghDW4 zvB|?)MN(N3#GlYujw1y%wapjh9vmk|CI`R0j#&ZdV(H*4n|FT#Xni2-i`h-la|Ba7 z%L}vjQ_|g-hkidD!SO|)&$CoNqS34rwfby)bT}??{&{F`_|Mfv=Zj8oN!^jxiS;aQ zaO57EwTq6=eHus|pxSmhS#y}0QDxfJsztRZIuV(sj-+~YJN`>57}3{}V}GAOx|P?R zw&d5==iRfSt?HDKRJl~DljdhFK&k8~o7HTMdOqx)^`MR556bxXb2q1pG6k z;cbRRU03@cYt&XIU8IUjF70Nv=&@RWwsaig8*I;8^;fu`E@Yg*meGvf8x({8FbE~i zK22mHk$8#DcFcPJ?rGiVrS0)TM7bi=jD73%h@tJVum(zoOYiTO|2uQtp)wT7wMA+M z*Is+;fyjbF>}=X` z2wa&geq=z0TCL*}IdHMQeoj;N4$UTRdQ9C(W%22d9m2rOT(N0tG9yHY)Yu{|aUp!@ z@@lI5!LmPYjP$Tn%>WY$Z8~KrsYR!)my3zddzK@vKg65)b*e{H)wYv};A54wiJP6% zJF6G>ypMWP-zBw(J-^8=Wi5@xv`Tg~3KH)PvGmfo^D{RFAZiR2 zzk`amndQ&wKR4YhS>Pv9jfM7y+9vBJ0(H@)w;ZqNWP8_n`y*rbvtbDr|AOj{@Tj+i zwaA5qk=eKqh_ad`{`D>6aXe$xd}iKXwVsLRP_gMSw4lwX z^U(JR0P?(kZ}45I&ps&DHg6Fjk4N!okCaQjYHKuV5zwOg$Q0!?+B5)8AaWn~{mAqw%IntW3FoBw`l7YRHv5qeoW2&2k(=T^}s-!C;hxq6wJXHQV65sO!)q z5j$P8A~qX@U7l*Sn31dajPSf@JixhXw&FlwsYp%2wZLJGIQ}6dQBS6@b(I~`%N_^W zh-<fCw1(jxiXpqva)^S$umX5W;1WqFlEf=zZcjE(m-EalW2=d})RtAAj4 z=dlXA6KHvzy~5eCIRX{FT}DM3i+lI%SghyRUnNHF!|K(X>^w;RLmESDvm!^YxqoAM z^EP4B_zIBHZlL*zWr}Fx;-pa=?=fh3sM7nG$|7rNCPY7N)=1$|pK_#9q*~GGE9=C6 z%WNrl@C%}=RPYMY-`+FZvLLwx;fF$JS(E*eQ+Luu z+iZ3H@haIHeCAZV^ba7a`@?u^j$8PhEYm7Us)%rdzMay$zo=c@0%BKNpsA?Y5my^Q z*xtZ)g1jL=`KV!QkKSNi{#zT8#)FZUW#O}<&@(Iz$jC7sRS+gBnZ7SAVoa8@NC4)-DGp8(F zs;XbT+LL`k-_ZoY``eVDT4rdY3wO~DAjBE2afy2_Y`pPPNB~vJ*f@xS!&nyXiV_a_ z-;khGLOX|YMU=eZIjSjVuTvxUWQBWXR*zqh$Fh&_=!Y?@YDe}qf9PQsHenpT$O>hi2ywh=7J&|-(Qt!TnDmk9 z7F|FT4?~a4S;9v41{Sy*MO+H`i#s>J*g zRvr_*p8ijQjRU@)_%865Wd0;xhbT+U@4c{X3(FhJ(Zw&EoKE9I*x}fA{l!bPT!EE6 zqHMt;-DP$Y9I-dW#_=L7V0fx$7(7#sAT9X@6+3wCxhAn+=lcm|AcrqQ%siv5@W z!#3G}%B&ASR|Cf7e;wTtSyeN>eK+dq2|5E+nkCA*{;C^-KKo%fK^zhu9+yP!8I!yMRQbs-3sAu9hJEXxv!?sn##VoJC3 zYQ?xX&oeXc^k;m+_Mz19`&8h-!XbA6l6OKRi1ZP-KA+4AW<%94c(@o`MFL~HkNvSl zY-%Gduz%DYlVoK)Pf*&v&gMCon_Fv_w9C8OKY3F!B-ssL+I1^16wur`#iG#Mi~RKp zvC(!K9R%cvJ9hNCjgj1-`sxS}A20MuV^O&+qqh-0*^g})<2~M&fh6^^`@ikgPixr( z-(n?|WB_JXsuHCzlc4VU^ohN!e%Uk5vE7AO71_`+A#pf_W!BC6^KS*l6U>^KR2=c2 zw~MbLaE&keGHy6tN!GxQ$~9AeBaqRgMI{G@xvXMHxR9nj1uX^@f+l&rY;2JNkAXe~ z4|@7WH+=$s4&Xoj6tbt8hW@$i3 z?>#I)F@s~sfvKMmXWbJX5u11hX*mSzSZ4^3Nh58TSEn$q9Mx-FFFn{@(Am@=G@usDrw z=qS35{lesA7?1!sSGk$Q_JjuT`~AeEb&8j>g4;*9A$VGmbp6=+E=zukW?l%rn$EzJ z^U7(lltgLxj-L{TSm)Gn7XKuFzoouq%(RhXGLA%C#V6Ex+5p}=wzzR`NVTVc<&87} z09C*hfWjr_r*+Sy3_Pz0W+QEOFimug4COT zH%Qy3p3C8x3htHw6P~<1^ei*4o@GiumaZA%r}(xG+(dw!gWsoUYcE43bgm5O{UQKz z!h+7%tLwN_B6uGK{X6^-rtEqRDsW-n*^;)=t02gN z0KM>sQcb>Bt#4^WW4reUS>bQzx4=&OTn6mziXB!n!VK)0ElIK_)US^^V?W~Y=eO@| z7!$U)tXKgensc~My4gTaE2R?E>cJB0$;0u&{(h;R%}yE4tqh=B$AIEt-t*5_juC)F&c(&YOC?mtCIQt`Cu~L4h}a__~un5^CcOGcG9( zD~5WoO3fuzKBe94Kn{;IQZ?gENY09zYk_U};bkc_7OYRQ$E_+b~Lq#RHMQ;zWvH$MX6lM|Q##q?2WiGK*67 zcue6!WhsVkQbqK0z=f7rC1fon<;q}SyKgS&rzugd#x@gCg1;HV_MgdTu`U;ZmK1^d zLh2wz5VjxligMiPt$%UYFjr}vXkc{H#PtsWHFf3dZTq)g%D$%L5R*gmd=^YB62x(0 z88deVngn(mdH--puf$5SQh<4PF*oLDq%KflaIfqFOTKy>xq8yAo@&ve(!8d049RP@xCTY}ZI&90AH>6;Cv$Y?w*Gy>e%-6X1`)IR&<$;AGs4mIY^?1m;S zCKa?M`9Bl@^}V}U5rJ12Yv9ld_aBQvM*N?B8}sIw3t9nkZ3 zR{+(_BWkwLNCwD;zC&W-YLItXluDkp>uv1#!uhmmHGTt;a2hE1ZPiA_>;`K+%slYP zApy53_L*d0!3w2#WQ`-5gE&^I$tdTtIYXiUe({vJBmc(-!vgQ%>Zv zct&XiisB9~+i`N}#92G^ghNmyV?YF+TojRFIKDTR|FtuR^!yzNzb{=hev9iD@r1+b zCR@sUl$I&#@D9@|IESe-y; z%GQnV9kOl|FMrwMvV_WFS~*E{(GimPhpaC-$>um|D1CShMl@pGwk!e^4}KSp z4aacuBoXPDT2&^~N6c%4Ud{HLq~kwvbtidfNw-C1^N1$zRdko{6G^hjostQVDVI=& z)tKZi;@J76$8Z?3Qg)u7PoLRhy{IY97+i!?WE^<+H>?o4H$o^xl==S3;mJX+E?ZvCA3x`)m%{l2O|6DQ{Kz( zc>sRPf_3;+opwswwxnyUEUzdC@9r_Ch&+c2b-V(7z<{A9esp&QTlnBT=UlY| zLoBy(4lU+akpuhboWMU7254w%)I-)!9wx*Ota%Gp!{)c!)&&mwzk7#t$cUxx`=UV3 zDm19`d7Eg8kTZLYrwgZ$+EtwmwoLh=?t^Uy|NN%j6-3`sG0*KGxZRMW;vcJgcU1}) zLp|w-d7LtyM^_^Aum4Nrg;qy)URmZ27Xr9%1`pUiwE$oix(mDO!`H<`}f=tYT*vg@Y?-Ceh3yxPTo_5 zH)Z@PC{Q{_61}VMrh62o|jBe07G18Lw6QQ1;D?m=WC)-3V;* zS}O+qE6rO@D`zw3CV2RU0%?(IQ_|;W)^|h-l@!q-9$H?OLU&pIH-nFLOxM)*70U-D zMSZ5d*}f~DXwZku069PQ5WJ8E@L||L2eH&9p72^Zw|IH_T9Wz^${%{y$Ks_Kp=*z7XCu1LM
      uIOL38BNy%HiadWGXIWh>?gsS4@nhw| z6;#73H|&+OzU|!j`TTrIquaU=mn%n_8_`3mS+T?@hg{QV=msuAhF>)Oqf(E zJP&&%$Cl+or`_RC6MmUn6IT!}h8A~+x>mzuzZ(SW??^&SQJb*wlk16umU&~Yttwa~ z%HXvN%E(7};Nu4Xmald*a+}8|$$}H0fCODkTET6aYd|g6CY_#Vlw%O}6Nj0UR<`NK zuo6YLo^N`S<*5)XU@`w&PRPWWw?o9oZsRFLXAeDU zfxZTWW>C{o>C}iCGfT@Xmga=QH8h~4v-NLLAP$f<&$Sj(g3$MPac~AGL9|4(6>CAb zTx*^a;rZ|ii%!Uk`F*_)A^1%yUY-l$@YH2LU|Gj{hr(d)1f3WsOQZGcd^5dpo^3K~ z*n+gaJ4eiT+OO-T%_mGEf!L^*rYiBI0EuD#YLsXcV5te31D59E2Qb^016$I!u99>K zy}(z-iHvDbR%Ti*=9cM}8L0#h4iZ zpHRp&7Ws9X*TbLa!W`)}#a{=nVbgqRmzH$VwcTqRN{N>e8`ET))119b&2sA!+agC; zZq}YGXH$<2MG}8+1he)>hgZPf!RQf2>mtEIguu+{aYt19?{OZ3(^q|r>g!uE3!bZovV6*j35$$7LMmKR;vC&Bo%;EMD(>s z)&gbf17G7icXxa0Y67J|4703vIdU<~L|mfN(!hfc3H{O)o zO%pcW&NPQ&^qKfUZ}!tbk(P$UmqHe6ePvrNPEHc5!{ld48sB>R_gUFvt*$+Olm%I} z`bN>?KceN0?WGayv0GC8m4}kpyIJ)tY!{}t_ValKvOi&~c>uPYwUns=4J**Vv(QwW zKEGS-oo6SJ4c*|MPk@Qox}8jAMfR~|j1pP1A`Sx^oFJ-&gBaUvv31S3fgvp@JSKSy z%O~OfX@B*!=gAC-pCimc%@|M7;q*K>q}eWwjVQ9q2N7pIqA(BH-gh{E!JosSZR z2~juQ_K;$oV7m(TT;(j|n9fA?W;&wGSEgBPw4PRMFbI2os-AmWJMr-E5Omk}qW-Fu zdCh7cIHaaM=L!vDW*4kwL(h(zJvk6gU793J{Q?GECQaoVItc59Ze#o;SR>sR*7anb z>q1OVh@=-czfNO~`{`W$*tK%(6LQ^7yGw1ogF4>mug1~ivNhF6k&%DjZ!n@=ayE37 zrKYIVdtp3#>^P}s8&Ze>$x)c2LVwAR!xDoR_a*dA?P)+{)l?z37Eq0ND4jcWo<09d zl@Wz6OBh|zC=pFF!``bEmX3)Z=<7RKqI%8hcs~Fk6el2)ErYET`|mmie=^TH;#xw> z%_hs*Ff5&s2RLE9{r~rP zs{u{CH)2son^0vOqrFknZBEy_nLrx65etm&=VlYxqGahJ4aG`|z$?^u#-P2%W{d^7 zIRt86P7wR@H_Qk!fz45_23qX!jHTl4z%p-+A%lHHw<_nJV3&zqm>YBVr`%2aSws!* zQc6Lm=qhc~y&P|{KPph0Z3}jxXO3}wP-FI#rL=<~wiys6vbEQbQYCivx9wnOOdnVf z_Vtn10gGdeZIp>kcQSN#IyyMGrU0m;eQ;XF!Ct8zxFj}CWV8F{2mE;-`$E^oBn@%< zOK4X5=D?;d_1rZZbc}1jm-%Y3PLA}LgeOS-3ekk*b_o-?6|+lh!RZKW*nb>?P5vBdrc_jz!_!`+m*h3xa zU-MNmfC_)g!yC1mG~^`ZNS=HMPZS>$h5tvX?S)4Yp=3S?KegCTD@o%ezKaqG^&1?` z5p)QA#&WOf)Swv|Pt{*etuD{zBCo(#3ud?rpU9pMMTp>SpejY{VolTnFkTT4hDNtqCC%39M+*J1eW0&hN?rqk#+v@zRWLPRA{9l$pj_L9=7*$#J!8Q@#E{g zhE0h`GCHH!lzNx)UA(FioeK~?#LYi^=0sLrn-+Fdw8<0~NlT1j8S!O}lWt!|6nrGs zy84}L*V@(&&Liy{`PYbk(tXaW9QWJS-70{U^|v!8H}h1pJe_Bo^B`zBZ#^M6zRp%8 zfU>0KTuA&5lQI4f9@Dt%xR?0Y##*js_75IpqX4pd`$xl>-rtRlCj|q^qVg~r7Pn+C zI}%?H(aEzyER4#na1#lrr!d#tXk1{fL9PrX^tG)dj^R#XW|56h89^S8C+fvSYjS=T z*A0&|F(smyHsSzG$!A#X0#_ARoi@q$- z>nR^Ya#Z$Z z6FeG_Qi7H`BVQx3X3{os>+|cmN%}^fmMNfzkooVVY+UpBYI^D}LV=_X^9YGcp(dVv z{f=8n?@{PGCUiQ#Ic0yhLeU*RC_edn`9GEW5YS{;r})w+@>s=*>yzHf$oqXei+B+x8FGai3ma027uu74!d{Ui z?81-4e2p#2WqLCRi-O#5((BBTrH3VS7DGqVPM%vpB9=+9OcEaArkU$zNQ@1N$36qH3>ubiptIxax)X7gr( zd#D}3eK&@(b~r(Pn7;l3;vfF~ZKiJfL`kLE_e+9(Oo5o9o1AUUo;3NW`4Pw*3INAd zmrLM&C&)Jvg+H?+!F<*=!}B2?Wk1b;nXD?hhGzxWR*juxY%lb_1OxA+)~!n~o-A>VnURpH^5PUv5(c!B3q~V;@JWBD~3J1CX=w0`<7yUGx3XRkgUJz*@bH7B$wW1Y1JO}cbxrmr97W2+-#7q zc`9(uWCKm{EZ4 zO@9(v&t3utc^x8m0XOLtySHi6WFNtlAFNZhd2yf(c4jet0Pv%4OdE)?o`|ZO3OeVn zs`bPV=)k+uHPlw83Fc>eQ`%!*kSyn==qR%e8Eq@YiJxki49!4Z7HO$i`SJg`dng)F zi3?jh$&=2E1$9C@m>A^PB=mI|PtF?1G@$iqQnt1#%&~>}ea9S$;wq`L zD#~ecR_f8P(vA1zzma%A9|-H#a6kn(S>rP*y){W#?vvyu*Fa9WoQ}MBISZt7ULecoj>qP!yn~C3ALRHzA zn&X(z@)knn8$=Us)vfTdxj4wY>D!$UqEa#}97Wy!(;4yFl-tO@n_9C1-mck?-B{jD zS-rD}Ola|(G`z3OG+UtZIdD)Ibk(Gw{K9QgVS7QAK;p3JhSeds@Jt4)Wf@=@Y>%eT zN=n0IKErs;JsIS=$mF78sAGyco`Lm(9QH_%@j)Nh!tL$YBpWWQlQJ%wlWe452lW1A zo6vULke}O*_PMM-z}l}9$+7AzvpF&CSC_C>31}+LM;qdpgPa(c8zhLF0-R;T=-q6XpG$Wc!&a^_-c)3~N&&h4i9N)x ze7F17`2z?al@&N|tuVW#rsI-g)7+YrDGThb9a|8l zI(hz?=9lZ%UNphlde))zkxN?~Yu!4(kOmAQd+Gf*Z(E0&T6boBC#YCksMX#Zw-(B! z-@dO7qH1DejPGaG)-7D~yl9mX=7^1%sm*tMrLv0C_ZT`EsA^_Bfo6i(^A*Eip5O-l zW`s@TW;kd*_a46#Syc=>9o< z>Z=uL#5u>TOM`?U`K*Yru{KtB8{wY=L`14JJp8Y5jl2fcBlY}h%stqwx$1HQIi8B# zR`i|Y@bAIbTt?k{!6xn;ph<-~Oo}=+k|?Yq(LQoh@`N`=g-qsrTk)Qmf{6Ej;>o?i z+ek4~^Tpn9m3w*7ohFx>-|q^TsVhN1?88CD6)xZe3LEUfKs&R_Oxcyld*rf3weQN` z09pC4b<0@t1dpOLRy%<}#Zg~|_~Yb6{X5v&Q%BC6zz*oM=9{&~@v3LOaWbkG(miupwHaUQsZms>P~``tW75s(eP%B7ZDQ zFKj?esG>fX9=CB7Yp3a=9nET8{yOFe_e71;4YNc~tz1gZ4cD<@Ope-~eOY1d3)|OL zw4DuEkTDq)YZAFIngx-Z4b@?S5?5((qBmDGSIRj(ibR=D1RoW^tuB1-ZU@hdUF%bMZ8N)?K$XNB`_|L-4G!i_3|++uaLdB9@3uu4d}{`xpw#MrJCe<(%2fD=>8u z64%YDQWA}I>Amx6I^+0H0FS@;l@8IHSKy){us!Rv5W1%~#?O2BNM&tQL-F zmwU0os_8SSB8@ZHrY^lpoTQ^*E@>AG_L{vvEci+<{_r3L%@jT_k{!L7{yBwnkGN=; zH(ifWtLDKRJ62#`TI$%S_)udfND$Afqei8?7e>+OS{}P@p%SB92g6EFA;(eYbf9Fv z0ZL2S&I=zD?O6UB0fjD(qwkryLy)fAZ<(_Uv~|%DBS5l_(KuaIvXiJ`rPOW{);~%LKVX({SX2n*zmX%&h)D)caYb#m?Bu%zb#-Uk9~O#v0*C5B<_D%btN3 z`K>k@Svn)B8|4vIE0GaPk~Ztu2$CGE z4a}AeUfj^YFXyrSk|zOA|NTC5=~~$Od-Wzbww9qx)gA0n0;DvewH zr#SFV?x8$(hI=SqLdb*dCe5Ee=+bX$&1eZc1nD{mE_uW`%Bqy;yU1`lo& zuat(WE#~^-XPmqS?th?+T06nvnP^l`CM6)O4WeT|QLjwJprpbRMb_jLqB#`i2#3kN z6ZI{UHeHhblgWKls+|i4fF4gCD4m+gGj^O!hd3XHQN2~QXW|&=Yd}PX(gS_Hj`6WI z7}99dEf+f08Cw(i!a7kvi|+fGb8b!i@+wYVi3UZgOncySU+lA4&&S0K8iBJ$;!;39 z8PM0Eq5d_4E^nN}%0baANA*LUWgcSpWVOS(Q|FXOuy)sd6$Id{O-6u)!eFk(oA zN9Ww~>IpT->f};Zb;^Vspb`8LE$EE zmDk|>IK7>AibERI3h^8b@5a_(Of$(t5466_9c$_|dW<8(DpT?Qvnq5t42U9#j|Gjt*UznU-;cse++juM$t*K$jyi~c)tXh$LWM{KJ)oEXShyNS+F(`XBn z@DI`aQwN=P$fnF$AL;jcTYUqaIe%00wkVoVy%>43ycN>2P-tum#Q%V=-+&&y18x@Y zE<(gIV3}tf!g`@5CwEuBHHG}^AHE~_?!}d*2U-ed2!36l* zsB`rsFPNx#Z>ICe!T@^Jx_B)~Ru<&SH)=JJ2%dWl=$miizQ>^@dKkx9OlUgpV@KS_ zzGzKv_O`a1iTiyLzdf~cbe%iV7dA~HAU}e5{zscaEk{J(pVeoL@!T0rr`Ch!kSHx` zVE{q7$kbRjYUDaxe>vR8-qt;t+CHAPmKg!J_dj^=+qAU$8WX+#SdL+Ml@IU!K2OkR zZAOgz*d1l!Y2P^lM#-Z?LWQdMT`_#Q6|Lpr zx=wwGxw!GoAvjdSlbsYgtKw%Agnc{-CL7erNBSA<01s@%7HREqBNQIgk?N>#yR4ZYP2+f5$Vij;)gM{@vU&x=v+axF7 z*h@WbFPV!FXu)^`J)iY4#XiW;8vNc_=%{WI6&wOLAKhPwggx$4rS(VlT{T4jzej(Q zbPj$u?T{;;dp0`g>*IMIK%VW5dznTfe-Pv~aN!FUwvIX9vbYdr`z0Pr6dZykRB`QR zQP|hPz3S2Thfmz7VPqQ?@c_=-F*@N4!C8m{@{ylN`2YbqRxtDT$j~R4!G2GI6PY_h z2VY~4Bnl2;xyBW220rWIJgZ!ye={BZu#FMZgXgFbngSdJ^%n907*naRCt`U zy?4AMM|to4t?Hhc6LU_{Q65E2Mwlu=ymD(!0Xo;`ccnVIf-|EPMZYig@|X8qo`^;w;s?g~$Z=l6tq zs#?uVPn-ViEQab*;D0OkH~t+yqakfvZrxQ^UtE5Q4oRP?uZfoUUEH=|^ry-T=^y1; zs;;_zO63dFr^;!nGp?(yyzpK8K75uMGZJZ<#-*EOL(dxlc>0k@TT8&dBXBl@UN~MNv|66)YTK- zhiy$wvSH=L^u$++0a8pA(~&B#?pat*(-2QHq3ae6qk z^HK~xOfrl@d-yJuev~p(lQ_KUq-ayQb+k2UH+7OX#oXbf9R`-e=&nm2*D(y->wqaW z_9@Vc8KtRhb^Xx9jA6bMz=rSZ(huv~CLnGCx_JK8jd`k^x_J<%NeSK*onali?nM)$ z)Kwmr6Ej1TbZe5jb&|b_5$m3X^~RGwrYWp@*aVE*7`H9e7fsSJEWZw*VsMGUJw<1# zJ#~GbV!k>stz(Qj4X5c@>N*@@6yC=|U|5-ww{Fbhe5w9Rfnr^nRDaa9DfK*6SJ;MB z-uPL}k97(_ipS$QsheJg?^5@5L^h#rs`25wSQ3oFOv7l4=}FZcmoZF=H=%r!lxmXJ zsd7e@qVc2{R(6WM6i~$Fr^*;6#Z&2HfR4w$j+VIm6r-kSivgidfW$PW=40LXrUajg z@*K|ir`l7OzNxR``IqYFxXf5k)$wbbPS-I|YH}P76Q&q9HBp)-ajJ}z^oz@@n^dVQ zC3(YZl(J&xNJ-Ds0+DS&MP!4$1=d+LBco^VY-U8i9Tljf;< zh5=wxA2$JLSWaAKd>_)EqM@$LloletQ*||gYKmW)>PXGqFwZbx)War1(|t^29kHo& z!v-uYD<0%J8k)3)QPY{|UlY)#ByDQYQlQy1>FfG!lt~^ldP=Iqv<<5#Zev_t>RsIg z4f}PJIgkRdraGIzGA=hId7GqgogiqUJHAr=9j0%39=0U~hH*Wqd0AIR-Id~*rumh} zmDE+5>hz{gtwYtg{5lP!NotO&DWu+o^)wA$69a{1l1LXbP7|ob{S@9e0dibV>Uka0 z)s0zGn^O}qrfZniG)yw5${EJEA$@i2u6vfsKTJD_%d2}H=NZ<%x_J=O*aWI|ebq!y z(^%DAP0EH&RWu3;j>1@}Yna50(+(RD`8_I_j4BnI5I#&d3d&2qy1^W#1;uHaG>;UG z@;B~>QGul?ZCrQVvskLt0aRTX!+>$v90KCR&|Dk0(|9Je59m#S9&fLux!yLL{tX6zw3cC-u7y?Bi=x zA(2X-V#qLW+_$65ht!xfjcr|j#p6<^-NZEMIxQe1Bqlb+fOU;c4Om_IVFTlarRZy7 z_+b(~d>7Kw#Na9VQfXpfjr*()cxQ;rBU)SDL-uN2!KBTv< zzv5@9bWLqY^>ZB%)Ri0l9z`pN8F$zmJly%y)K~HII)ND0k*ePS`6vx;LcJ6yj51i^ z^I;tjmX~U5szibfwxE-q-al#H8hH0B7XkDG*6%TZihExZtbrPp;^3`3b zes7vwseVsQ@L`fXHCbaC!hcPD-_(CGt#u&NB*DXS>(bU;!-Q>IcKCM`kW1A!DnF+B zX;}GEhl=jwvg-IS7Gk=tVRe9zl3a&#r6f;yrL==#lBrG#G<9xDBBlT;)gQw>)Fc zhD>QV!z6J^YSQpKd|n53;rqCpQ5ZEYE3U68f7}l#n&Ziy0<${d($wA*Xw^yVlpsir zcb#xdU3H+E0_D`$q?rG3z$$*%qzJ@x#bYb?192#+tBJ8=X#<0uoRV58W~l4H)P#uh zr5Y8ct7G_-Ce<|g>m+peHwJ?`y5qW2fGz0`MuDJa8s(Y3it1x{GHlvJ7*spctStqc=XLZ6arYoMSDd0`f7}go*58pKj z^Ds>wCK!g$F<~hn80C4YuCTs3WK2D)lLk!#-jt_F14y;K>8b<8I%$)lA=Up)Qn!iz zIDHpb9M*`#ye3@v8Bk(@sjNwx0{Xf%;nf7f@;iK<>hHR`>KG?3Hn;>z%nCQB{sXCh^SXgEX zEK>9~fmNyYoY%b=R(VsShh0rb89xv6G^u4xojh!UH34I)tkhK}QBqQ%uAVwD z3)2PCS_tjyjrkYgRHdvxE~*JBwqEJ&rXiS2DA7im^_cyfaZ#!vBq{ zq&I(%g>H{sd-k#Ii6_{6-~BxB^V`|EcR!Es+QU8f-OI!G-NWvE7G`3w=>RR7$1Dcr zy76h!QtI*!V_*{Lo9ax>hg5nJ`Q&|*#?tgGq;FKMr-|=V<@z*7tX*sNZ`+nEv@Ua# zL{Aaj)Q~!jr%qcM1r+K!HKaMtJ8Y2aCR|u|s{TXzCm)A?0d#Bq3nm{&VVB?(&@bkb z(*2lC$8pq}wQM}<7|y@+VvajzJsVfAWy8_Ouw>baM22x#`Q!OT@+e}Qi$+JU_*hyYHcW&pAEf2AM z`)+=I|NUHl?bU4EvW3TY?%{#^?mHy?6t*u~jAMWv^JKJvE(M@y`!OjyZBPcv9;(|7 z#%&yOF#Q5W*Y-8_V=q@7u+)M6uxr@dX#%QYT26`&hTRXN<#71G1454o<>N zZ=p}`V8P--LH}TZSu830U`j)oDGMkW=uDF>&uNckwAzZ!bVh43XM7^3Gu2_Dlase| zR;`?5{rV}^t(j!q>Is%DX|ZJK7T;ZJ>?G z3>0%dUkD%>lk}JyFlE-PTg%yJpT#++pUG1%eFo>AauO?#+L)jY_C2w{efRI-p)Gsa zzkiXPkMHOHyLPedu`d06J&ImQvA3iEs$k8<2N(_jTokX@||RVH$m0Z|WLGOI=xwV3q=uxbRUre-tex zE^k^ zxzFOl^Dp4s^Da1~?tOD}Y~Om2T~Ew$#|_)L|IVH4-nq#39SiKaV}X9(VAf`|CNv!k zMk`cXk>?p`(7D2BpimfPTcV5srN9{9He(bjGpIt@XUbIVRm!VY$|9moqix%jQ51!t zC`yXLQ1(hp7w8#^`GR7XA!{jCo-xkM+6k7g>~O*vGn{hzYSyk?!iFQ3Fut^PNUz^` z-A}mnmOJ?N_b%s_Tdw87haT~7b0(Rjq|7uX8$)Ga=KH9qmz%VJQG|pa*M|I~g48f` zqbdK$W=KOhqm&WX*@P2n{o1u=cH1E0HzDt+X-3s>!uw%bz$mKcsNhFUx>2+p62D_w z(i&15@}-a|4lF+5^K4kZf#*H%Ib3kjQ+dt{p3BD7YX=MM!$Xhm=O@=Z!sh#S^Ygp+ zvh|LA6bn6YCW#(b3-p$u6G7)6m8ROtW(mkfo;vH7X~l?o^gUT^>-F%B_Y~qh$JzRmC_> z3P@6e*d%>MX^#`$00VMz`RWy1c=iSS$}hj1OE12VO(&l;Q18C|^W1U!PHwt&7dKz? z2>W)NAQ7Fnjyxk9%TI`rE zuukmzNTSq?vY;bXxinfiEvBr%3@mt|tNzFeC^J{KQWRRDltT3ls$W=brYPy}>(kp@ z(AhM`lHwB_c1T^ZhH^OCN&K!+6>2Cy zZpbLVhdqn0rVbjWc?<)g_&zQ>wBXM^>vUf6(wFnRm%f10PCs)X?Y=#8T>IlE_}Nb% z;hy_<^6>Ze&|NGs>oU}2MtdwLYilSBxhYY`Y9FNnRe(~8LL0lboGU`}1>85{1vXb z?i&AmigDNG`H>`U>RFv6A10*gG>%k#qi8~L`cz&x{IXIsrQV0vKpnA$GEDmzRkceI z(xgH)sh>^hM;)kCJ;Ok%NdlzG4WAcOu_B!nOL*?HpT;YH?Nz+^S=Tn-}VGI{qQk%+<$=X{ax}Sb6P8MvbI8NO`*WF6-8;8vDGcD|3fLuGqo=@XJn_(>~<4QW#TdItH6Z8)w3}x=JydJZ&Y~D6f_H z{!|9tw`onT95_||sg3bw6UxvB%Egk!T?NJCeI}1=vGTYM=RR`-XPma03ol;BvZ*Q_ zx13w#ip#&xXFmIRzH!Cn?AmEpi#phKpwyhI6LhI-nC3A|OBt4@uCCPc_+68*s{_Tl zys3Iq<$?p0eNICe1%>M>A60dW>uCasQB zy_h&cn{%`px16MdXQ~X^=u8=mv1wi1qD6%5mONe)iTVU%K}<9rqd+^eO3WYSG$#X; znMRk!ZbmFkrOgENncM=Ikuo)yLQ(Wf%7s3?+q$%t=Nxs(3NE;4Etfuj6DOXsgj`iV zmpg8|lP`SvvwZ$DU*LfU27N7Y+rl>gcjoFap%v#FR%X-Hq)mm-hY9aG5NiU|RJ|Th zhJi_{kU9h&rQ*7}Qe_Mqs8P|g?)|7J+ytnhMsn&IXYd=Zd?mm0Td!ix+I2qd{JtJP zy7D2u``w4Q^{Q>m&-WqMjIYSamH1k;Rrg)lrDHH-EYszsp)`sz)1Em8=qwp7Ogls?p) z5@#{Jl7;O(iaw05$~pPm6+G*C$8hN{9Lv(B9p99_dv@`e|M(1_{@7=@;iembN@E#i z%nwH}rqYZel)`Hiftspg6rf4HZvwJZd*eC>0Hv<;>I!OV%qXf@Q@&9LD@9YP-qh8k zj@ruxNEzBdhGPDZGD3~y)YDGmwXb^}zxm2nGP884f4=>}z5M65H*?*0H}m){`|0iO z(>{G1oojF_EDBJnG6}>y2pP&KwOdfgNM={W$ZGrXdtq(6XY`*>z5Hg z0KAzK0*ov%2fvk4lv1}c6&SdsX%+fXf^Eot%rdK8DJGQ_g}=0kV>d1LBp+Nj$bWqH3w-zkAL9C(ulLVo)NFiE82rN~(J8C6p>BTRcFu)YwL68U4;Ux_1E6>w0JF>F1uxAHV)j_|4yV7423PJ8{F0 zALD!9e~|0Gv4veX9VFkB(^=j^yLb@131iR>RJ{MeF^)2d(xQn4AJGP&0uQhNBK{3m zwlT)9zIc!jh7Wuzq7kT|oR9{fVtxS!mqv@$5ITSZMhEAE2|x}QDBCClvTPmJDJGZz zpIed^(@vbbrIbna-k>e8?CD|d>9X{+4re`U9WQv%Nj&N4M-Ghl=RW&6KJ=lFarHG< z0M(MS>UAlYLIUFqQ!qA;Di@$T>*r1kHgy8DZe9*!-ljQRr!}Y2)d51YP_56Kd_O9n z)HUL8)wQM$ue*k+nZr6MMSJ-B(E6t_d4}pA1i$B_O-7rt-DbAC8-QbvJ&M==&p+b# z{>Q7Bo?7X1-+0|4eCx9Nxb~}$u;=HCbk6KBJ)Tnb=o@e&P23JH8C%GGCZT9X480UzIQfd*AZrpf@Lt3$OdF_ByX zON$EpBmu}6x6F;H0`YtVZ?x+`Vf)J%1xle^`re)%-Mi+QI<~{z5{?IOrn5-IaEH5(Jj!O2vEi`5Y=7&MQiMuzMvEUUtI(>w!8k|&t_JS}b4uGPdH{Yj$nWd=wJ_tPl zSP^JVVSZ18v`@w%G}*w{LkT)G5yK5pp#wJ<&(bK0Zo$F>3$Vv<{;SvXYrlRnPkP2N zzCClrLEisQ@8f;%{Q!?Vx)pGa+iVhw61(JV=Y=hI3dYA^ey1;^PCIYniDA+|bzhhN z|Eng{MAJ|~9*5pHb;2k}Tlc%EQQ`AAPZKf^>%dWHPNwfn!(xtN4>0H_dC4!okpKOc zZ|1ynp6s99e%lWI<72mR-FF{lZby%aW5;NXWzZ|#m(&z}%Po~u7e}cB4AldZJ7zAc z_oAg(qJ#IM4LAT$*dQ~gg3Lq%F_}%P1K&irYU2AOST6P&KnMr{Q272FUaqJaw8) z_`XRKIa~qWbRDv6Tn7%r8gn=r1c`TX8Fgvmt4;-M(zu2qajOlz44C&|a{d`l;;-KJ zCSLT?m-u8`x9sP`AGnztzq*wJ_jDOMZ=6;~d-dH*M#nrV)HJ9hs05Og;57j8KTre! zBr87Bz7oi+|D}Y=JQC0nM{DTA2$q(8Tu9_Ikuq>ALpUbZVuI+3W^c*}D1@5{1q=d^ zJY*b1>(Ybc@7o&on*`js^rZ>3IaiKR#-?}6;2u1cV!*+y47v|}W0<>Vo@_khqF>s; zYhHOOCp@`YnfvjNuI62T_ddS_f{4nro0*x?V9XJikS6A1tdh4DI%c~%L zd_f(WjjBr35fi7aL)K9m5|$N~H>_h*G^kd)%Ga~fNX}bbzI+95{)4~Z5B~Iz7+Ye! z`n&cn^2N{H#n(Q6H@mJm$mFSQ#+J39w2`ERa~N7F>Lz^{j&2TJIq}+rP2g8Ww15O4 zJ_HX&PD3$n#i!C5)Zmzu)d>gk+nYq9;RqlEOUjf~Vfq3%@d{16f)kYQmxGldD>a4^ z;~cq^&H?S)5`dqqHicz|w8MbEMZi^QTc-G<6rhS=PGojft#ourT#izTh53?&n-`co zvBlGV>v(?qWhb&BSQYyChd;x+-u-s&eZZd8VzreiRGwk_`~KTJ5T_kQv-s}_`4kOJ zeAWbJbpjk9TQW8Ew#5U3dmEahd-yEQlS&h(AGO1WsaH+vS(twmbfzpYWr5BzC<|t> zaV5|Cg=g^54}XN0{pQQbJ9azm*T4I7{?A*l;i`XlfZn)b>FJZ?ZH?;Nnv{$BL@SJ{ zR$AmgT`Ie&SD4sXf|LfMt0>fvVC%=QduRriZ-d78G}OkBfCV_aw`Y)9(Ux{4b?b_5 zGthHY7(PmZ?%eCr{O8Z{9Z!&nNw81VfJ1|wQ z9bk7<`!cX)T1`aAwqUQ6vLNHr8+2jFTZ+!HV=QEF$G<*HA?^9QpF3z9ggYb9id0ciZ=<9eX z#sL2})=*MJ)-h*_AQ)_H>Kau8s=H6s*Hl*%ZDC#sPFufj18;iMTlk|teyuO(&O3JT z;dfrk&7XY~*0h;8VVn$uUM%T%GzMpO^bNT(e$tjYsw)i8GL@rI1rj~(?7ICR-KCM-pCoz$;On<6YOXVeZ(U3CDMYDXPC;wyRfv!BI#-u+(A zIP)}{zAX9J2Y$wvK6EGh?p$E{$y3nMmigWBhzff+ujyOqZ%Tv8ttzhj?g+&UH<6u6 z?)KCGgUh7ioOJOQIsg+fF9eJRPmi|cdvip9%&+t)C=BAv)#4~S+ z>FCUqLKP+ZZ$C)8rFroiPUJOzcn(uD;{fd6xtBkE^Bef+M?VErM^x6C0x1o-F8wgU zItoAxQwE0dZwkcX=c)AGt7x#ltc_n-feAH3%t)J(?Y$rE5e<2J1+gHn*A2A!dz(kok& zQOfVm#aJn7MJtGTql|(qSdukBsPdzP)2vy6s(?g$oWMIpT@_aAx9PNU4{%KBid2%= zxFR!m@5;5vsQl&~pGP^VFQ>dI5tU!5YmZKEJBC0GBPrNJ7{Wb1gSpkTxgR0#q zhamz~$~Cb9Tt!u%HT9G?`HX9mXpa&@V|_%5){z~|nBtcIc#O-h-NN*;4#%Iog3iPk zFM82SIPtiXx$gQK*g3n89MG*cDlaevDB5IXC}$3Z^SO=(>i8%An*xD4{;CtUaXBdv zQPk6#qItlF5?7k4q>h-l(W%N(gr^!f4Ex2D-~a$107*naRJfWzD0QEDrhx-yoCOYW z`WYwlsZakqzx(Rn1E5^!@vrZ{iI2STI=1~}A5%|WLVKnKJ>$3aTlL%8`xT>m3~{Qz zJ1tEG^eZ>vGhANd!A6{f)+s6gWDB%D7S|3VU}1d;#xa&s;zM!udCkMMyu|xh4Am00 z@ttEFU^stD;H%IsjdcK9rdB>5UPCa-w#x&6MEHgv>zG*yP1=?xnum5ERIQYW{{$!< zfEc_6r5sQigLfP&tz0<1jJK)MO2D74Og-Ox0afLEIE5i^YuZPRvHR+S{PYVCv3X&Z zQ_fhy)MSU#&p3@|KkGScxoazTZMm0jSu})iUC9^$k&3G+FJ8;1rN>m-esJ!$wo`k9%ghqnn z1LBn+S;__gR(p0(IhEYO;n;&0#k7T*2# zf27^A2lRaNvio@Z>#t<<<$G9i!8B?~Zru(_L20b11DJv!I#t;(&ie?`DC$#*$x~5e zna|}GU~p!S%G_!M%Ey2R6G6o^h#8bsQs0Ng8)X?#0I38ebrs45y5Z4Bi76utY_JYt zX_1k8>+md{Mg$I+1n3ZRg=)n{zz$HQ#^lyqQ_k%2t3(9ntOU!+J{YhJdNw%oMQMc{ z0K8V{L0l~l;v;hHl<*rRBPQA<%J;383reA!zf9+v)=^{ZzWV?_{oH2ebf2@% zUr&}Pp8B*)c*?m?;io^jmhJm?qbSJfyS8K~(+9KA2m~pOziv(s1CvymQNSdmA;s5q zd|TO_zDY4*=2Rln>y`qJ0;GWLg2dlke&s4%oYo5Jmx4q`O%N^yRWb&PBGu* z|GeocKJh0v(_N7>ecGgFeW(3ab%%Rf9P?Snp0O;U)c_I7sLGe%xA#{|z$&EHNp+Ff zKBCkS5&8#w$b6`-qe4RMbFcAW>vd)Wo+jK*U+FMqfypuCKv=y&ILt5C3UgK(oBUOk z`3Ej2P5h=-GtjC68!^p9J5V|Z&zF97fF|H84r?*d2*yOptit?NWzHBtSF{`HCous7 z^R>vVv1CoMYBg$dO`HC>;ik_#!Yz+H!O5pBXZi98Hl4VM7eDWL+;;n|+`nZDUF`7) z_Io6~#<|+W?D4#h)1}@ufj}MKgwIlGO~X4y!iSO~FjYW`VdJ!M`ldXiHn6VqQ?!Nm z5?k`jUw9^8{nBMzaQ=k=-1W0pDovwq{86JYaO4@IPd^ila>J$h=gAXNjKMV!yfTXGH*n~=zJqn1W-a8G~M+v zzV+36c*h&B;*l%nnRx0FvbG}Y8?w>`N*NnZqA-{oCsEZvTQeuEWf?Yf1cqFs9V1kG zX{u5bmJtOjz@TJ_#pP4MD8_>b_?3=I1F9lzeV^2HwsK}ws1cM}{3QVbIfh4z=2iiN zeJ;c(4=fT^UlAOjplC{NN!?}e!F6Ij`Fz@TkeF|!5z<2NQ&psF8G$?%5Q|U9W|xPy z46T&aSWs>*;Dm{*TeP+e${g~IV;tPpXL~Y5G$eUHqz6r)QF=mAk43P*i3l9QN{s-asgxZowUt3(?sDk5Cdq9K%7WZAKxMB zy>Tp;IU<6%70>ueddxb14>@6YH))gVDO$6NDPrqM%Ac zdwGk}l>F>d4|C6sot$<48YU+@Jn5pRaQ@ln@`Ed`WY_+k$k}mTdkf~POp!VO;V_=p z0Z;flRZkr+#`sY8%mYfsphJ9EqhcnG-=);I)RjWKxQtXesRqUL&H@wDlYHQVAK(pt z_{a9yz6IX;XFuYbe|s05b0!#H)kgOXSz&Cbg^QC=B|h-XpsaS0VJCkn6LN58s}N$D zBiL~Z!G^mKU@8Fc3X2KiEJQ)c1bnERpyCJ>Yr$07Q|VWn+)D{ABgl^$+}{IUdoZd3 z3(r14R^=53ZMfYY$6KPlyNz@{9e7~!AnuvbGOCYS zl@$+D^^gUhYDLE{m%<@i_!ZUpBuXM^ORM2{Coxp#$;u?qg8+b(E%d7B1bgscG7u3Q z0Ird8sWgT|CcM)E!gF2*t{@~oEF(O7*LH6OXki3#>O?vlwy&#AnAmYIfl_HQoEfYH z^WBz;LXlCT+&7QPOj9aFpO9wo7C$7$Hc}6Sp!uZqbwSqz`%9f(twI5h7 zwe@uv6e?5I91^E-2^7XE4cdjNmX*_&7__|7Wx>wxQV!;Yu7YtKxGUe+e)UUyR=)cx z(=9wo!LLj~8n_>bSW=-@e8^A z_FK8@{s-*}P&SFmmqV_h=#ppSbj$>O493mraK6V^laLSZ>-akLH>E(-l^NHYbjsG* zSEaA1Ro^44rMAZFY2^PHC z?|lKP(r!ZRF_{A>SxGXW5R`!KzCQiM0@cx|OrZ)`*w;lFLpG*;`;4)BkP2fcdIi1x zeHIo=+N}(eTgj_>mVp+w_vrOYvT=CN>h=IsdO9m~ABgqBwH z77At`UL;?VlVvIbTIVMcpNRCgccO;d8mN3Ne%Uzy6A=i8%4BnnU@e-UTf+93RExslLt@SPD7YnZYx6Nd0a?Uz`EfW)yyzEzgm3!~Gn>+8i zo3826%EwUMzU?EeQMsZh<)px7{-}EwzE6Qkm@cI}q{>az7pKjZOijIQ;lQDvW(*6i zL#$yy5T|KE+tlwEnCd!F11j&Zzu3#!Pr87wedWJ6Zqo?>eC@KI^RCzYh{d@+%TAu8 z04D+Mz*kbb@Z8Yt%blnZ^B80QesDj%`GVGT%bzAkkAW==z<^K0H`jrT zeO7g{kDF0J8Y#~WnK$#4>u;xqs8R$;Ri6W$W_yf&Ik-XI^k7U%Tw<9KGRa051FLZT#bJ z|CDSdV{+ppJ!8lmF!=Jt(JF-rQ+ptB>bHwFHR4D``Q=B)&0hL>`UC%jQix;4wnIC` zMO6V@c9Wblzl@kyR4WsK*W4d4?XXG9rZ-y<#=!jJi@fajPv;fCb}B#o(N=a}J|?6nvB;WD zQ~cudk7v_~Gras&r*iJa8=0DJaq{V_+4k@(yB?V1gtM3PTdzBtbIxAN`jrzr{rShS zd-p*$->?U@ET=uwVQgi_GhcEXzy7MTm^VGjT(S4jd34*EcUc9X_QuX0rK`TGR%f9k)v0( zxczgFuv7JT%B4r5wC1J1^irO9;t6iN@kY87j8oWZ^KnesZxqP#yN=1j_eAMJ{z?h! znD;Pp3= zt*|EGH7Aj2cv<3f84g?}_+Sy+&lw1z#5js@0?}W(*D*6Q#@9c17i*rpl;8TDbNJd9@8qJV9m8%) z?z?6ix_~uDPxFdboXU}_COQ7p89E(ByRVp8Gr^sA?xefF$2n)M=Df4lvVP4Z%T|uD zY-xvGkI!@KwU1KVTky2sJdPJU_gGeMm||k%Qr51TV0POaKfiSc3w!&V_N2AE;@3~- zdB3`et&i^n-Qm%P_Oat9d+Drc$xv96Lsqe*J7oKSdndqQ1W|odu^RaDAhJ>;+KNSL zr;Vt}S!?jCY2lJ{HBJ?HSXIJ;meJJ~1*JrrGMLQztCSNGdMqQG$+_)69%akEeOz+M z2C{a}^Pm3$w(r=(jW=9J2INf9Z%?B7_RuCjWrBHMC+zF^Dom5Q5A&zq#r4MJg#UC3 z-Rf+v)bA9U)d7i#@)4zrpVygJVfq8W$!DF#mp=CeR?S#2`P4^l=Hq{MBdyhKCRcXo zyIrI5)%5X1PIoc;R`vitFQIum0Y%wX@W z2ifpzYdHFZl{~g(AH8nDA>GtU({}Rpx<_K5+fw`&_v%2xN8~EpEHzd^eVcps$Sa8l86OjK;6X8D)>r zvrsho)?Pjcly-OtLh27z5wHIUD1TCpH1!Dh(<`a$v zWdg9uOa)jXr89+|RkV#_GP9CWPj_r|>6RWdOFFc3jp0*rdh~J@}&wrUeaAG zDf=bL82a>>?-mq!hoYZZt;rbnAM8?6(p@N+XOWZ7Tf^3S_ptf8$5^vwl8whNN9CHu zoqbNcWF3=Pi*J7FZhql~r}DVKLY`9LSyQ0%p382on}ML^B4odG$EM9 z^<>kL4<$uZe5F*XI@F8b#pQ&pgQd#+*x^ zek{FmKY#QG=d*o(kGrql&g9aZ13Tu>rQw*Awb(9!KyYpP9z#;)3EGY~#t!rjft*auGY5}OBm>KqzW-%TmEeL)+@`Uca< z&>P!4_+LAC^uT_e@$6$znc~GSc>%ZHdLwt-^8oVw$&{HfiYXKGRs23w0^+}^vchL6 z%}MV4Do?7i_)<}tx{6bkr2s0fqs~-{%bf+*tX{*nzy3{5J@Zrm{_Bgk^DlpVBV!v{ zjIU_ZcTtdezog8xQyLt@d6&PPTy`G1N$KMwL=&(z`!hTULfCQdMFVkvWT{cgvgwqM zeF!(~`45;2usJEJ94wV#jEm46EJ@p9ZBH8{auv$LQ0y;w>WepW${DNq(cO=+^((tr zdh!H+_{Zn5`JP>T<%{>w%M@m=;FJqjamlkb@z6uF%Ig$4v4MZ@!A{ z_sr62D-Jw1&u{sR07 z(qBeF7RI8;7^#7N1kpxBa45fg?GF!kt39H5dJU<>X~DKEaoYM#i9(-NUMtpFM!qiR z-Y-AS&i+9zdFIh%y3Na8{&KGQ=~dkGz*ai65kE@Pl@h$cbQ}PIl%``6>B2NAGbi=l z14=*8Q0fY=tAIqBrV3N#rWzTilMb5&mP{|@bD#Yz7d`bU0DSE`ckY8`OAH8(Wd%IkH2badDaP(+{UryE%4}tL;3h}^XR~W>xn=j9K;DNpT=$c1aoa>PNh z$h?FJMZLH|PSc3%7zRGR%vKxS>$1k(P7!jHa+cT zNfd$}ZVo%-bDIom3vvqkKpq$f`3^US`I+g;l4x5yN8Qd?r?CKse1iv9KRAuVs6!@) zeAG&ODxy(^A3-1ZJSn!m#e)S!Q8F=}+kmNF$-@2uJ(1BFcbu0giamY0vwd1CThJ}Z zGEKiD3tq(Vb~^9+A)$3kNNo|4(}js>Bd{Y+kfQU^|g$f2PARS zOH7F?PsU0Pgerq=3x|BMFc`;y(0^lWfS@t<f^S~s7aaJKJd&@qNu(R@r=9`^tl3+Yx3!wyrXOwcuUh7 z&tQpm4oRoNYr9EOcQP`i{YFZyu%D}#%FtsOMW)Cmb28^u6e~fEXOyL(-!JL)EfZ$B z(>MeiCGym%btW7e7rf`S0IwYq2oJoI-LJGc)1}(zXS@*c(aK%}vgvSvjq(*oZ-%L0 zyxp7C2DzY~`b`$aO0J^2o%QUxs`e9l}csyIW z^tef>1BSQrLZ+iFU*@#I0+;}ee6UIl^n4|ah2e$S`~=5IRcF`B$G0jUj?tLe-k?8CAj!SjZnJ3T!%$QQ7-{T^5y~;BHe_0(-5wpA*A?XqP<4*3?aQ&GQG8nDbMn^p()_>=uJMLwBRj>FGB@d)cLoMF@PGps*i z18df=JdXxTmBGW&uqb6UC~i=wANTnM^6rNLd}JD}@aMk+LxXsmh0`Ke5Uc zHz<`RRc?4c2V8W~rF`Y9{{_IFU32`!A6(7mZ|`CH;wehpiSdqsMcR4kFWQDk68BR= z)xFm1R9*koItL;+GfEDQwhfoOj+A2`a zbW>jQ!25NKc57}W)=VpLM{BCe*ClOsvQL5iDgqW*+7m4nbf2GI_7LY?vW`_pOmX&^ zXVMyLamD3V0FaN3gYH8C8Er~;W^LHS6n}+(<8)1cld@3avcu%XEe<86= zz>&J21vVaeEZ_RZH(9#OeyaNadGpoW{E4kBd&-oJT~Ji2a9oaGPIQw*o*}-73WU6> z>z-NRJ-CeN4>3|UuivgF6Ga7qZK#2x4g6w|tIOafrc7ok2dx|=ZA9Bp4ETd2t#76` z)1>ZzUU@puxxt8t&qi0$8wV7AD?$LsRW+v4ek35!WfSKq(yyVm<~^YSz{mG4uT5D+ z22-{JG{ zS$rQ86W1ePvXnNT{?sQq@@N|c`~DBz!j=DWA5-T~*ubBxQX|8tQu$1!oU5T_MI}&Y zL&vO0S0!b*04Lc$VqAIwB_G)2A~mfOf#8#CyqX_<-7NukzIhB4UTfbazdkM z8$y%RO%*8{Mvvm!SUSn=gR?@1uxBFoFEf<`(p2S%q}PR$yx};xelUa}6au+>FRF@| zY!ZFyfL;Rpyea6loT_}^KG#NFDDQ+e1Z7HqoVI5I`%kyZ7`Q-1ze!W*3L=i>bE?KU znw3*0l#8~Nwu;a&&XMc+z>T@?>j5XN(N$j<=ie!n-GimQsavA@hUw!c*>cq^Z-3*J z^yh3e?WaEeG0r*V91b!|$s*+AnA{hC2mmyJgzwkHyU^T8@oTJL#CfzEkJ?P}^DuKv zP!kHmU_;|{s@1OQZnfRF{NU|>|2JIv^h*Hv#<%b1^M8L6V`of|k7agZ6qVLt3#b4= zObanTN*Vmjct+KZ@r+Yb6>buiF8b7!Gw?l|z#cZvmN4ScSApL{RuyzW7dC_&SC0?h zcFr7o6oRTIctAfcon?k70@trVDc{$^Y|2H1`aahd#4ImGqa`aX0*FO8P0N-?z66o&}$39nj>!mg%$(S^e?gFKri4mobLH?HDpv zI%uEtg_|p~@5-+{iFqUf%P4Oy`Y{%eGC`jhg(+M(KP6dF+QYBi_)cFk&E5aGlYe;6 zbpT8(o8+_q{z+EM%rMur+@T$y)CvAr(8up$@Tue7IDZq+3^-*|T1pc*ka!ii=E2QIsNKVr^!60<48e>}_zWi=2r?p1%0 z?wP6lCoYcwnlD34tWq3>L5~MZ*PaHq5*B_*P<)m0OtP!e`T!8;vysj)K28K2t|BI* zP3I#~RrtA5HQ>Kg?wRc{%p|igU1_Gb3rStV>$GNNgR@Z zxDEt~be$WcYEvkl=4zT4-xe_!{W!YL(Xs*tDEF-=OQREZ>s#FY*=0Ja+khmYgvGedn`qlSrGehQP-GUXArDAMTxe zcEN**V{jo}mWRop=$3S6`{ZNVn@q}SCEo7$Hn!(R#L1{-VmaGP%Y<|Gx|WC1G46pm}$^Jr` za+-#B6uYhv2dk;J3kb6s?FP=^>+%|hTe|nFRJy89mSU^e5Gu1&oU&zQvf1$s1ci3y zppftVCSWy9Y`sDMh5h20$oqR_URAz4nHS<=6Eg?dJ0xS|Odx;Czw1m1vdr_0{si3o z&4)SlqIDdxVT#kwIE$T6Ji!e&-iR&>UtX-Ggn#4vI^K@?GR3F9-=e>Auj7nj)}#tm zq${awOp1Wi6%sS+o_**;A7y%S3NXCqA8z38%eJ%pNfW5j1w9mYvfDE}wOf&J^aTEb zDwI8HpG-K7^~O7u)tej6)amsM{R1VFGh-BsC8n?wz6b-=M6C}^lc3HrFn2J9()kd; zGDDe}0oz=B1*%Y$d8C~Ari|Y}=)cLUthAF|wN+iN4q?7PqDns;GM0gvqNEJ*YdDi< zV2(JjE^#I$cu+7ne}@jzmsQ{RZ{)bXD>eSaeUk-I$#s{|T3Y6`{48Pe?u=L&XV+Jz zw0;Y_M@U%{)6pftZGt4F`(MmtD0N8RdEN-LUjZ)fuind#{^m}Wojp-WqQrW?_h-n` zZ@^d*dFsEp1DH%(?Xz!fZfQqeSjSkIXLJ|)^nZGg*SzT@-t+#ak!#Jtc`Kf^xb?;H zXN*%}E2p2(HW0z-?Q>%tc;X~=QptZ)29dT^Io^2;;DE(C1znrOQ5-BE8;KGXCXv-8 zaUPp$33Xs~L&jD>jH+A&yaWWLJojD)ZNT}VkZ}w8LQEheodA+C&XhGCK;;S#miGP~ z2P}SmIUkKbyh{4j^^Y-C^m7UvE8kfFp5kj8P%#umSyG5Y9veeMX{=AAtop8W{Z(dE zrjZ5;;~l`ht`c%U7f_TXHqJK^N zn*x!z4j+dS7Z#&e{673!ci;5a&_waju|y^BgaD=gGY8 z^-pHynn}LOIWfSb54cC!M;2bsN?}k#W_JuB5{ZiU~CHjz=@>KYDQw~xu= z#+|fO(3gStqRMI@BGKXodk?&!pK1EJBJUeoJ^N8FTH2kiRic1?u36mQhnwg5t@oeL zo8I&kPx0B8u15DtOlgrxNxf2+G2Sj7SUM|%KJX4hRrz80q6vM6>4-|n-x>hnU%8YW>m1Uq$(}VAB!Mnjc9JA@t?~e zQVR}bOVaKem z6{Ui#1XYx@QM8V4^P#`Ej=S!C0)V&u&0BcxbDqvDdoZ*q#$}#$E$yu_RBMv>N@*oA z$b^;$4DxUt9=PEhEYLLkPN7>&VAB;7r|F_FeuL8+{^HFXyXhnVKK9Amx#g2vSbD)U z1HnsvJzpk+{eFs)B|VuGG9g60_0Cs2;f*oYv@yn=vSoJ!clY<`-#X80K6oy#ecd@2 z`k2y2BVKs%8rlFQp~o%2NW*74hRroWC!ZDdyF@` zjEj*OFlij4tHPR<#R84ycrIq7n0+!H3cTrSTwCnc2#}?30-u!aBllPG7~?h0 z%$XtLoHnH)TYzW0@Ob{}9Z%&sf4GT**B@Z+V4osasM4U_w^B?0!F30gqA``A(LOvt z`o|c9$t(X#RvL7#WPHsSdp0ldkMF#R`K~4UU;gzYEM2~gS+=3(LDBYYDd~ZlKg2w# zQv~XGIHkFy%7Dn^X}X#;m-tDR${0*jr zz~Ehs3lWXMf#`Q^k;uCcXyW&AxpwYGFXD<)g`^6KiK^u^XFcD4O7o-%XRSl^E z`uBC&bk0ihOk?O$+I3!D@~bEC){i`cqf>M2Zy{idCy7 z`SuSUU~X%d_H@gs`$jm?6H_S}${#mSeVtHNCqn7u@=6h+^5Z66U=ldDNx;-LojGQ(ZpTLR7uRzfSGj8itu<_WXJmqOea@+mec=YOhwAQxK+K~53f5xz+6?53H z+By0p5YVm)RT@mD?6~G@avuD~4wj!d#mT3y;)snKnBOzUkFWa)o#0pl$WYNIO{JT| z`MIP?srHd8~2NX(A-vh2{Leq`h~%T~~GQ`yF$wT~3jX%2Bgq$&zeY z#YJ+Li)@OqF)jDPO(DrkAR!?)1d^A0Zb--l^1@3a50Vfdfsl~ATxx)XYQQ+gI5uG1 zFvhscMQ)N+PTytCdH(iL2c~)>GK72L1U$d6!Tc+vHR?v{T-yL;3 zOxZy8Grp^k06x(7MDJ1vgv#Suj^gwd|MX|K^VHKZ(*3Q!^Hw%Yp29R;B01ZH;}Fa7 z!elYjl7Dv`veTc7t$CLhI4pIB;mwIEu$ZJ8uE=7~z2us!dF@a93;^Hw+9O>5?)zz9 zI0_w~4&Y9jDB}{6r$SwpxtrAN2$jS8HbHur?Dg7!y)W2^KjM?SH|-v_#bhDXDoh44bwP%mB?-RtZ013+;59R= z%rvkgCM*?V@@iNgE2ofRQ#^GFN;O@)WQ$b=L2hChhcMud&Ph-6G7T+6TQG5avgfUR znM>LDBik@&=2kL?Bx>jsU2EJLJog7%RGCPK6}iYm@U z^R5vB{*fN*w=Ln+)0PqF5}FGjCDD@xK^!4?maQ7&10Q|`Kl_JgGJVG^M;8J`X_7zG zZeys^S%x?#sz^Rjc0FY`22FZY2)me4bZmW_XKtV2!+&)b0L#~|9rr zjx@Kj&-3-3{~RD?!_Y&pcp<}(XZW5lbYFcn2|x#U_0Rq^=kAFKc|Y;Le!v5tewMLQ zN24|{*r|}fQ4fBghJ^-`6Dw{cWhqo;T+oHa0|XJO!ZG#DY1W@V!Mp$dD$c%OErE`8 zh5oFlq>GnI?bVVH0u@zKQm1cU$)>YbF@MJbQb^o^Th-c`EO5>D>tHJLpcvtra<6D3 zoi)}_i1kArK$jr_6A&hJy%E-CYC#H&(}$Ha$i~;#We$(Cp^OxK=1IYD;&Z~+PTdPN zx#$MVwS>?vlPrSvg$aTTDX~bMQUI7D7K;(dg+q?gLJ>_0XZ@6+u;iu6$xxeP_MON8 zp(#!%9QZNE85gXJANEUpXk?3{BG60E^urv1Szh<%-MsTNmowfen7L~f3Wrw{MtsoV zw|ZcrEElRW#s&om6sD|_10ql?E9e~V@zKA$1AvAb=a2tL6?I=dJXM9Em4QC8@ni5h zksMfT?GKlgMt3ndlV2x7AI~R%2A*#;kw#>pSFKsi+u!y-0XTAGhR^)N-846sk+gC` zzZJDlkp+w8i!U`;HJ#--aV9*pY2qVfb^So6={Wk$X|}#_8SnnPm$2o`m3Zcl>!LUr zI`Ir2&9&miQ-k1m?cA{vN1%_76T6H8WFQxYi0)vPq$!g}Boi#TfRt=urjzb00n(5F z3XZf#BzcZ9)L1sMuR{DGQ5UbXeqjZ>WV%2mAgZ?9t0DH8-bxT=YS zm`1OnQqP7^P~eQEa{=f_cq$|zbLmCvX>V)No30XHVf|w+KZElWAx-!cM`Hb@@hK)i zKo`Cdr$h*!w033^nAw*L4IndBvVgU!j;76bW~T*b3)0+~nX5X*p9G15!Cb+WYEN@B zntx*TNJMJMrRfA=zW zyml?KHyy)w`iMrw+9`$_siT6fHgSAD?io5Qybv}xKK?g%)18Xw=y%`#HUMV3fJV>e z*NIR`jzku-Ku&~Q?DqkIaw1daMCfF(7sSh$(Pd-TN z+_9*I`Wou2CPYrMdDYx?7A~jSvkqhm5*Mcn9*4(^&~FtycgqxKzG@YJ`H`zxvw5i& z-cS`E>nWjB?ze%^imld#<%6TIgqyBrw(nfd`kfQ>rYjQ10deAK{hhC0k?+(6YV*uE z0yT9~a-BTwqQx>eptAE`WYBbhda^-nG8p>F$y=!xTRJ1zT&|YF(8apuJDO8@CJciA2w4|E^zv3dJ)Mw`0Cy`x61R=fB^=n<$Ofa?`dO%Q;M8{2&FZ(htbzjhk4 zx6Uv(-$%*7^8PDXG1*Sd z79noXC}Iuk(UAIk;$X*6X(bKSb(#9fA3sR( zxmru-hkEBxscCUrH3y!Tbf0lD&QdYj!d3JTi~u#nLtS3-m{`!BBBlYaNd96&NSWyt zmAWKE5Ep*!t{zypCTxsgc7uI@m1V+9O@XxWF*A)*fSlCkUTxASNp5|p=r##X2FJw| zfsxIj<7uyIvi(#ucj7$N4d+pK3>>}HjHZwTT%({_H0e}%FsDnfHI_rL0;%mQ`4X#e#~ch#|^D z=dej^v52D-5UJ|f1MEI$4bA0_s^jtA*XQMgfGVb_DfRTb+Kn8NAhZc$A=n9d7*`;Y z@}{J|%@C3C9>y_6g)V7)>P11~Bl3-l*i&YX+4g`T6D1`>GCo2VY|sHV7;g1UW{sH~ zMW|0xL`|>Ei-Vaic|9$^t}ZYW#-zDW3lg8TO{%!as$ryJ_07#ht9v%b@{NWGq4l6Y z+h@tnQFiZHOL{oY5dE2GYAviFp%;mxQ8=Lp4d{2F5Pt2~FXI3F z80VnBOExbC5Uvutqf1Jj`qE+k*C*})VB1++`H9#4BpuB7S{#9peKx$ZhQY-!h!~h7 zWYcCCVGIk1MK$UP{?1J$vm^mt_xjhfe8nUHpZWB?%skPdxwMQEDa4I?c#wV=STsOQ z-svJUhzm7*br4D2zGwQ|(_H)ur|{nY=SoJ}WxQ2}Yv;7SeV|Xhs%+NANf6r~gWcle zF+1>i=dNbmo+Zp3=ui}Kk{Yy6WUK^a@aPm$B54(lRf^4^PC{hb*0>2H;f$QqYMRNB zn*eF|uP1JZ)P8c*O|uMVDuI#^k&Gm@_z>fRLT(mh;YK_YtoD#Dk3QX~&d!N}xHf-i(Gz@HW}m z2EQSZu>%OEQccvUnECcJFa6!^yytITN@KhMeNR;ddby38wM1wki~3&zYR6F@oPtNl70KsO*LKx1Ll)KGq6fT-1L(59DxKsz&4QhT%xi5#`ITK(j&)R3^nG}KQK*g>L*5@E~5wx5y z&D`l+Kq#T|R3TvoGMky!A6Uf8GmJ9qv*$xE!_O}UsebyW zUdxJAtAL8nf9?*B-rb|wF0eFvu2L5-5oMrI&N?uaoq0p*BMAa!!!b8kG5y^cUiLdX zdFQ(>k35DC_`>0fJ}w1Uq`T)Nns_ zN+cQ0oX`sti!dn(t)y~3=JBtO(6xr`6#?X zVB7X(yywGLbM7y1=J0o>=ya>tPDAV=Lx0%V#=OeLiAfMz+ZufNv-k7Np@>p``AxqF z)cKlIKUf>H--oaKo)cLrWS^2T3&BLMrKIKquz z+Ry0OZIuPOSc)h}V(NjK0JH&4F%S?nkWG{#fOE{wR4m*+$7|kw4sZX%OA+xgRiumY zDNPCS+}(8fWc!j4^&$?Df&oU*EKtdXQLN25d)Cm{IYPhVaS|wWM`_UyQ7LJkq%;ND znLJ7OdQymZ(nQ89WMpBX9t;yi={O2ATk_Zn$riNsmCppxz_@9-=6*E+<7_<53d{ss zs(1XL7IL zVVR5EyiSUs=esbudz6dUk89bwcP9}Vb`FNrgPt&T+@4oa67Y3D2S$)@_aT{e&vM^yr>vM%8}GKix<4+npd#-)Xe~V z`cwOv{w}n}U4r8gzMGUCL?vlcR~FQi4lvh6)S2&7IQX@XUdnI&*7>p4p^peuzDu7# z|2XqSsCV}bw>02I(Mv9y>+P$lFHYS&!PW~`GyhaKM%DsOzxReXte;ZbvM?xx=gHlf z^*d^E81%L6{As(rJ)5D3G#;5SNtzlRm?G3C3aXaN6Iq*kJ_!w5#0J4lXl1`cL;+&Y zdpBVAT3m^E^suau>Xx_=t%KJ*GDglC&y%}@2TmHWx@R1XUCw2w*4*!@>ub}&+|&c} zItWrmVK@7Dhm&?M=aj9>^E(FSR0xic6p^P!EEOhAg%ZT}{6L|d7tLf3eNW-w9lw7G zzxbgGXtXQBOg{>IRWbu>)@!{pQ`D6Xx253gpZO8w81k^9@PpqzA@DlGyJBT6i327n|NmbjdmP{W*CB_XT z(oo4d3)+JE$jz*VCX5oKx6cv+m->5cr3JnL6nU-=o5We1iOb6*Tfka=N@tk~o#g$I z802RPVL&-qo07>FQoYjIN@V5OJFILKKnZEM`e(iX>|Ph7KKjGBp4h-d+x<`jOzYU<%HX=sj-Lp?$VkaTzt4Mq^Jd=gsxR}lw|s-ofBs$$9+{zJgjV5b zl?|Nh66k0f;@c{E^rb_UW_*B9=!7W<#I$|K!M*H*7hZfa<7bS}neE4K}}Pe*^n(FgY>pwoR)=|3uZd1)=suL)Qc-29U0ho zm`o_gfXNZ0&Z3{_g=|6RyO)!zR)t*1gl+04MN4-6Z%*JQM3kc@jzqb06Qm_EBVsP`2EFlM6#~)_&z-Bnb4u6@p(=@RiR#6j_~yrb$1 z`;R#5%r(6H%2U{V_G)CwC@I8F7j+RzoGnIyZUEX^8Ahh2ezARYa_&CZ=GShaba z$L>5zdt;#yr=$a&%nmnm!}h^AadF*N5!oaZ5o**C-=QfijUSL~e2kv;-@w3Gj4|}IZ86t7fiC2ZA z<7E7k%i5g_Efdt_C`C=fN`WHJ@h2b8&`h_kHcf)A z;jG#xlnFBQGmsrcIt-bIrPTAGl>FI1j4YiA9k!gdh4;PheKZ>lzV*$=_?HjgOLI+g zV4@46pdi%8S;pCxCSDv2?YsnYbu*g-=Qa7U6I{EX+}J>zFm+&_hpvB?Z~XJaeCr2K z@!(^}Xg3Phtr~}-HVI-@HldQfDyI}$q_E<6@v5f~N3*67_V1tKo@<|>wYJ3hxJy)s zB(3GHm0C^L$7P1v`=jzewRr6H7`&vDhip%b5uA`vf*{E%2+B1j(?L5?hzngL_91#y zs-cIJRv|4Gh153MnYm;BnJ7wXL}?lJLV6zw=~zPQNH`0KOKq#W+~$Y%n|&8j-BP)t zs7NG*(Z}S{CO|Tws^6jCrGB>g7*xQCXcgmmP2FdDY`$x{e1h|-=WoLf}V?9BafKfEk`0Y z3SsDPhVHRv%KXOs;S<4~#R{$qjSP6VnxO(-^_rJ5HWE#rZ+zhadh>yn=mhjq!(|t> zuh&UpS-@)oF4MLa)MFDwHH$HP#~4B(=!ePDFtemV4R<%13-xguCb2M6MMX}C?N7gxA(SwPb_NhgG6_`xDOyR2Bzch(O$dqL z&gZH(^TpZXmK5V6kfL}^(_6nf7oS;ptjmtG*D%tu+SR5`Y;}nBGy$6D+7Q%KiL0sM z8cA4AP4~F<)&pGoulIA$*PrIty3`DCtmSN0Per%Iqvw{Q#4nVn(tNTyoVrO*N;Y(B7`c7*%+!Y zpwW?%L8tJr+*a`xYSl+jJ`2!)u9UIn8rwqU|zKx?Ak z>C2o~^G5H}31VU8*71o*Rjr-41c?X0$GWK?NTyFFI5Sh%!(iT5<<@E$Wt|tFk7wQt%|+wYGS6T#nWZk< z%(0;5#cm7AM@e?hkd}$C?bK!UduTCu74(S2s*|D)Pf)(9p1-ky&ptE5_1E3cS3dn1 zkNoRldM695wN1t@8Kd+e9#0DDeXCm-h<>8_Y-oK=)HsnQ>Z5uv-d8pp#~z;Nt6zPX zpL@euoPXiPoO8w=Zv5^|$6FZv8l4QAIbrB`7Wo_&;ZXAHKY~5OLPk2h7|@^ z!4&}9@a?BKdhY_`7mh7jDa+oDO+vdzVW_e35@&GyGPwieNr29Ks)kTCTsoZG4mu4! z#DKF_fiz%jyr4R%&D2zv8$R(EH+}92)@&N(l1oqGiWhBU*WUFMjYeu*TxxESiB$K% z+O=bB-Lahezi^PTQ$`tx<#rIfB(IbUP<1?22sB1Y22LV$AuWo5{1;hSps3A+s(E^p z2=+zL-=&U3%{dt>BNHxlTt{t+)tWo0*?RmW)Jeeg@09pj(@7-ZB-A{NzBgvr)Bf{d z=LRKIs^vzWM-h&TeHRzIU>0c#q)U8GHb1Qnw)m`GYVM_eP~J%S?D!4`y`w#roj1<5 zZN{I(ngx9@M&1fY6~m>{Kve|#h_q6>@A=U){L8=W=e95G=kTL5gi2_i*J8Bgu!LK| z3G|~Ri>WP0f-hJiYwGr;8KS7oy1+T;_X9;E*7cU_ALA!qyNlLX!K;7b)!g{qo0y?X z&E5ddbL7T}1j}$e$`cj9A`cB;$2E#h3R=JFRWFO$e%|w)>mGrf4V(*jUlWWGdYT5( z@`ff9l1&B)*(N%Lx0*b-?{wmN9|OR&46hi>qk_u^DC6$p=F$eO@si--*~9aE`v3YN zU;5l5oP5RvSDd$wy)W6!)-zTnb7b(U^#6{2fR?}o=dRMvT%Y1rN*`e z6~56Vu6mxEzx4!P{Oo;v|Mq7%a?3npXN}O>G@{3Rc+$b{J`RI#3V5LkL0$Bc+LVF< zEgYdz#ajsYY+QoQD<2qH+vI^S9pv`ApJ4Arn|RsFujEhud_7M-egIm_<4e1Tk6Y`D zp_Iiw&-<`Ek;EZ;Xfa7NEMTG%>e2xwCs**ASG)p%n{Ii6$8I}JYof%P_5+g5X|Oq{ zO+7%CNBcRt7j4mHlR#a8-pa^oH88PIdz+x)`0>5Y;BX6C%?6E28Z2}@_ucRu4}JV8 zKDFzIY`uIP=U=dnOD^BQrc-LzYkHy}5aWTzIP=2wjBFZXeyT%jc{838XA7YaXgFq{ zoTqhPhc|!r3Jy*!@c+K+cG{B-d|BYj7-1W%odL{SkuZ4jy6D6XLG!OjGK(zQGZ2!= zg!ZQZb^y7p{j~E|q8l}Jqch|{LOJFU$>)P5HF6Fm5LJtN^f*yTyO5*6eQu3c$!KzbtwcKB?0<@zSC?vE*h~VQNS1q4k{;nFHkjw z9cN7v>61Ru_tgX90j0&62nU{?<=?)(pBujN2>Y*pmfkaga!1L;rAyGQ z(NUh3g7HO(|1ocy&fml}>6{nMASlYgB>|EMaqs~g5%ox`pfla!hMS*a??s!~x@{L% zTyilV`^2ZAW8tSw3JPKt!{folVt~Rv&t*d5P;B0v2#E|AJS=E*Tmjg7`93zR-vq$T zHy>c;fgZ~*ZpB@-p%x(KY4eIRvw2g$C+k?tv*FDg2%;D`Bw{zH(6T+KlC+~va+{F0 zARDB(2^RvRr6ZiuqJLV8*^cMCA9$2IKJXZyyW|I){etyebot4gf6h84R@CN?)99_q z4P$J(a3yzr{BisW6M(9T+c5XoJmKkzU;pS{UiM$Maow5%oUEs17m^N#3#Q;E9DB~0)HxaA0`^ck7ZHI}l+No)D!A`Q&vET_k8#VF9^t^X zhY9N(BU?ro*@C9A$aXtxU2E67B%vQ{?m}_~#X9(e-U8IAN7JBZW21uAH-&P0$@jnU zG_!B)Gd5as&C7m_kA33POfwVBo<{=Yv-xxK{W)km%+NKF_D)E$%svn2>?FxgC@P-{km-x5TTifU&sPA76Xd583#_6`Xm+M)tmPE$42V zWNaj!a6eMOMdz*I&i6eUV_SS6h=YbO_wWqO;P|aiy@0E)*$lwC$x+r{xPr&-K0;%u z#wCcP1E&<*WHDyu9*>hHk%$sfn{1LM_p+HI<{c0cXW*5uF>M%<+fyfzdDzUwZ80Ir zsn`-WSHGbT+bL`?J|Pnyxu_6A+Ph?JPMnMF=OUUM0aZ9z@LiNkk`P;pPf=%@f+v26*VJDdtLt z;OO_^Ti-jtb)UMA+yD7-rXKIm*xsgf@hG-Cq!sC~e%dnHOI15&-V`{<9po_85(chCG+=?zfy%sAcQVUCt93+{yI7j_HjMpnL+wY6q0r1s%5k{h@UPO1b`_ z{i$_8=Si9uRc0>QLM=f0G0eR?(`R%=i#NY(FT2iJ$+4TK=z8$2BBGfpni5`5pX@!` z}YY0NZod z1!n8AvT}2ou-L!+nKFMUmo)kHAN?Ju&GZX)pT(AKTL8HJn+NEvgE2kas0czoMAu_5 z!q5$tH4uVcWe^&Z;x!7%bA|>bFD>RnyRs$*^`5v}EQ6JjYrpuJ6GazB?p7i0TrM3F zgx1L;wAXw3-N1eK9OH+d{SN&Enhn40s0+JbHph+%a*u=6pNBfMfCTSCsvM|1eVYU<1~T>uqnJw zU-PzTo;x)Jq~1s%_X zU||5g8Btk<$Zxnr?8b8E4)`<1S1>+a5LiH(F@@;k4= zx%!2d@ySnqk~v^WF@~>ZQ@!lUfkuv282a6=fxxz5NV6C+8Gf1lJ)=LbygF`^?krT? z^MiwgB^f!=*Ej~F{zVsqH`CcxOYIr4Y+o^3SUuT@=(e7u!8%(=oPbTfL(UaM<88{xCbNgT-1HZZ^4(Jp&|cG`wYG>cF|@tzh-05f1!tn#Nd>G>|Poi*QXVNBgPX%oge>&zv7}g9D#T z6hj*Bcwug?=ja8BpG7bywNT3ixXTbn=H3fEpOPCP@JawX4}rRjk{z6o9eul0SIwKK^RcIG=m#_nAAr$;jFkt{ZFI zsXWD+2IpP4R;OE&JHGb>U-;T1+;;5&4u5L~S?OqBG>U7+fJiehBFa;x<$!K<2U~r8 z5$Yu5=4#h&N^{ywOf$uE#HhkE-;OY_UQM`XQ#g zGLJm^c;tYp{~VZD%me~c#vBh_PIR59aPz${9UbGci!TJ=j$01!^dnQ0OUi7&h#vN= zl2;&^IDl>;*N(PmKwTuxg54m(-{f(yNt|h2U&C{V3&P-_Eh<1GPO0Ifedi)P4eC9S zg7}Z9iH&3|LZIk)d=T7<7NeJqQ=T+JrwYv7IK|EvO!Dr(ehH`Tnv5C_k2ps^1ga2M z?C4mN9XnRwr!{O&<3^IXXYnBVUCJ{ertzdsF_5+21~~oH#hW%F8tk@vEC56MJSBq8 z1cvvd7#}l3Vj!KQc$LJlFgOOOZ^_08T8`iN?F;#}f4rDhKQQ~~JYEDxpm(gtiro{eKWRBPedh^& z`%TyJKVE(vUwqrWJU7#)y>AI4+eauJ6#XihYIX#OS3)`UzmBUNlxE`@`!MTgI~mgM zRfL{0&6#;_X09Ual%LqUZ2W3!KqOE!3%ZlSw{Ch8fGyj1v2**b_}_|I zzlT3hI!aD(Q!e?23$)8RZqG#*v2Djr0Pec|8D?&qryMC#tV8a`jbK9RMIvE9a|)zg z#RGM;#p6ua#EETM(*cEY(LRw4I$>l|m))n8+B`AM>}Ea0-P`_&}o< zkI`^0!aZ5&GyCls&i}b}{N-O?%}JY=5W}0>n3LI4;l-kEn_Rx{6lBU%nSij7F?5w? zrY>Ho5mimbk=g3XN93Ll8>p&Y^a1Sy^Ck?>0m=H;1da)O6F#N{tQF9|dc!Y(yK4Z(8TyVAul+b{FEa1QW>@NP~ zAFgC_O_S+|XX9usEocyU*YDrR+y2|vxas|m(qCJ!Y~KX!r6p2%oQI;Sxi2wu2|yg7 z)cI4!Q!DN0pF9FNPn>OS7NSDUd92*btI>3*6N8(Ovh5Qd?A#+ekgaeKmO6fT-ywQ> zO5tTMihO4m2($?*RPr^mm@FXsEJrPlp$~E>GhD!85GTLqf<0$ZG#XU%fjjR!NO4LT z7a4#LF|{KZf>5by$i&jz1tqEk?Rfjn$iWQm<#n;a3C`RHq(KUrc|QLvciE*iYb0%s zW^$5K>*OUO3TZeBqR+qT^qKzdH2Z$#Wd8K8uVl%}mTI6zl42DL6ao#YwZX14CRw#- z3H`Z#(zfYnPxa=cV?!WLMD443Vury9Cjp!vKp1J^+vRGPIhi)Idr}_U%-oW!KY~b| z!qECS-564A1tFeE6%xOJ%9T5SF&T@N~Uj_MhZvgP?!7fI!t532;-NH(-=M-HOK$} zAOJ~3K~ya%dY)z{L?Pk>RZ*XRT-QehN$PWTNN7JBuVI2EnQS5{MW}g)lAtt!ZQP;P z=M0@YTLYmU0D?e$zb7?Ssp!5^C6`_RM2Cu}hq;UwlLutKpU~v7 zUxu~#VmA-}Zuj(n@rem8zT{E>o__W@9=h{6%83%&$Kry}FWg|1AJncf>wHN0QS#H# zM1;`Sdn-wBaR9Msr=~zH_4w_;GUClb) zo2!_V0#x_5PIZL1STv~5ZF z*g{9&LC%F zqt%IkBP78ZGuqd4Hl^k)vct}_oFs_N*`UHVM|lz_1u{``@ z*=LJ5c3DV*0~oNw)48}V``p@^p#{8pw^ZQNC@w^lVaIr6{8q|ktKOz`I$$oOw7v-% zXRb_JC^|;+e#vN2mlx2%gai zc-x=t<7fVG59R%HOh2;_&y3Q#_%fQq&c}1&lDXMeqFm~>5Ncr}5TmrUZAQF?{*bV@ z_Lw=Ccp<$5c>wZEWftA( zGbo=zlMPMe6VXULsZ$K*UIv4M7Ne20xDmGYylDkx<-LnquPR7+O~5pu&^^|ncTb0( zf8Tk$^&NZl+X_k{;Au!f!xcb`v#hti`{+tn&;4aroXqmG+w?o}s3$uC(P!pII_}fz zm?mt7xD454hym|Y%EM$PQ44KA&6te8QQ;ASB!0<=@MIPxf>+Wasl)zFW7UG(qxTlE zEs0}MA)PYx`?`Lqjw%?9he^=h%v|j!7b0>r?f`$~qdP`?bp(Pf%I zhhP1j^ZB12-pA5*$?QXOT1}~Ad(ie9A5vy!xuIt>JB)jiEQP5bu175Zas-{`xFW6; zF@0P^>b|nWzl=%{2fflk5Ssl!W3uG7JC5+&a}kl8fBIG+S{lQsB>#8ZJBL0CWL}>9 z%0C;1G{c`+I=Q|3E{~P!dJgSBf|~?a8UYw^eW@p`m1p+2{_YL-W}Tgq>7bJ{xs5}z zA!{xn)LwzaMX2zw&1oTL+2cgDqau=LLxjr3eKn0KGVFWiE(iZMC%)} z^MvD$a$lpBob$=ZcvN!-As!T`WjkQuNS`&EmvH({6)2e|6q>}t&0~F=ETak@&pcQB z3i?Jk~nqk`|?nozG0rw2i>}&Dx!~k~mheEj2fk z&;N)bGtW?_Bp{*~!40l!-K$iIP>c%wL-Raw;1~cGTy_O()~=>A*foO$J^#6DAnX0` zgNyy1ORW4ld&lVj+;``*JbCXiTBD8Z;Q$R{3IT<`<~ayejS!qN+mJm7l^4G9Y_f?kI&OQ8hGnJU&ia+ z7;Vrhbnq+yE?O)(Y|xfOGdt@+ofNKcTyV+B_=kGwbC05eejqfc-GMd4h#G4sz!CYk1#3 zy^M2yY!&l2P1EaoydFeHCiLQ*uA^cHf-&{G)Q>rNoe7S7K49%N{v<(*xgIOEJSS+i^+O$+Oxf$`6JYuE(JR<*ubvs+W~m!@nanM-W;x-a5d(lw1<+Wv|IAO6=ej>g&R$nbR2~dU)uR5Y*06; zKngEUizmc=6jiQ~6|yIfh6LRdCh1%qA0jHjLD7%(tP01}{c|j9HTd0s+{cx#-lnhc z6rsTRCNURAN89WPmV-3)twEwVe{2q&an=f!oH|N>p^6K`AT~q|>={_#$wZWFpNkc( zf;L5|LfzI_t=jDl$&3(Jdwz1yf$f{J32mMvuVvw)AWo)>DTnOcmNz#|NLSY>7jV|z zWd4|mhaoE&Y(p{uqj#mi6oXK8JTfMnf5}N&Mo3`*QIK>2L5SOxgNsV88OA7CLZ2>^ zCynu^?|&&j_FJbj|D73Tr~A;TA%WG)7Ixm);l6 zyvzjj+4!niZ}myEf<(_$vnZ&Z^gQr`g8($!qwG2(D#aeh1BP5CoCt8(eFK4QCxSM^ zXrx9f(e-)8*=KR8#-BX?37+2A-I30R6~gIh`saWHk`G)qrv^Ul9}5ifkn7J^!yF(kZ* z@C6~J0qhbqlUI7L#Oa%cM}n^D!1gmH*>v7=dQWsy+(w*;k``=A#FMqtpf`{NhzZ~n zs&3@0nSIpStj@s_-%SCSmAUM#42z2q)3%`A85uw}&JI5}qEPE@?=duDChBqC zoNQ611(YclBd3dgK>G3h)q=fRYb>D&9jiQm&5(@sqpgv23MKWJ zr2shVt4vYk8xY0CJS*iX1CVKH*Q`Rs;rnpUZO_6<4k>j}8mu*&+U!D|gvn0Kv{1^6BIe5v15hmfBAAaq)zRtV zG8k%nigmW}0JTaR^!`XT_@!!ZKj<(!M3U=VLGBf{WK>wW(t7l<1&491S3- z@Tl{64YEic#HcW#-Dq&;`KxfxLRE#dfMY1Tj)g;a|4K3?0=|xvB%+fP2&N{D5p~uV zIWdivYp76Q;4m@M=gF*bHgN`B*GXX6IJ+7(4Qv}!M3p11G1KKr^~*~9OCVjmOZ zj@f%=@uj3aL&i5*;9h=sSsW|N=3grWt9$NXNb^$XcT$$>)l5i632m}@ZstvzFNP8& zyGH`e6(vvHKgAEfAI+Yvr>xKB=;A-a(C_(W?>p|~z{MUIMkw}~S)to^#_-*lBORW8 zcnX@X?kwVDO?*hk;zPaY(>qiX+cgkIo}@}0zmVUTv~zsXz$Ens1Cu5Tbw}ikyFzHA zR-?8Mj@~@Q$yYAr-5E_PAKsyJ(nx#xErVGW@Ebne(I$o=Sb;Y8R&UhnX5?vL4q0izl&h&yWy021so( z4UoCkD~6I>J$dug1l|b#Vd6I}@^SnCKyBwAbj zJ4+qDD9E*5E!1qR1>DZ)}oF~rEqqlwz^)7O4ckU^T-7Pi2E#^wr zxm?v{BSKi~IB+0t>)pO%H)rjz05_{|hIF#eP9$g`bLuVj;9|&R_!@0D*|a_qUJv~6 z5c5y(hi(~BXN{>-MOx7rQc&&aLoLyP#E$0# znhmzYG28V#ck>KqzitD6^5<7Exq1xf#YycXx_7hgjiETDG=seZe^mxPs(IPPsv#%F$5)jte z#>gepKk_@O>DWJc1QL3bcuw0jk;^#xVmM+D{6 z6>8c@>cyNik%oFp?iC1u;9R{J6B<+=q!NM;X_H$)++JV_u?az=okE(-`5uwD2twTU zuG$qJ^oWZ=BxzLs!<6QQ8zC?!THG5y& zOlXOzytP}EL!L9H&heX}QD4s;Gi%Je4cYg#2^DJByv|I3!mHA03epz#-+P2=Dw={D zPFZJD@`Ps1@b|-?pO8ZtytzpX0E)jmnh6~4IPV;q?U-ZY&`cNFLg`7Ycd!o7321Pz zcH3rJ%n!cTG@TKIkikPTAz-fQtTWS<5rav13~9Gv7iy@4h3P)0?_R;X-fWI33qrtY;91OU?lJ9LP>W=*i>OG0e#wO=vF40%ddGUnb*!vPotW9Q zwUuHcneiVr@hY`e(?y#mr|v}x1-gMRtC~oR*tLGKvWT2m+I?MS2XzSRg3_;Y9Rd;fSDqZ=H@Zl0!3ZSo|LX8(-4GE-JU-JYzC*3LZk zNFZjo^Q2(D*tR;7I=)PjBK9G2h*aRJI3B@4*%GE_yFB?! zWR{pGD<=STaT7EEN`OZ5R4qJRqys#55?n5rQZF8&TNAB;#mo*|=%QtU|< zhhlI%6uM1cT=cXQIzB#7_&^anh4NCaufj1yJ+_%M5$9fI5;+|sn{yMzhSTPE#u3>qDOxzIoguM&>x2=#l8seD;2EbC6pV?7!a1txiUW_u zh}l!OoX)cGvEzDVSb$hPhJ{HSlcBC8yK!+2r8{6Jtz91TZ9et*Q4T&bMKS8|&L;$s z2s$HOwUPNoJnI0TEs%kO(#eDlH6%$DApQZLC=HmGcbpszK%jbG7?3)s83k+Ih(=r;;1UZdHm zD0`K{@tC^Mc@R8O=?-iCS@_sDr4R9NwSJ5wcHKasuwE*Ut30i_ibhY*&Mo6k^KPSv z=O+QK@-fY(4RJr)-(#siO)F;}L+3LOhW#|xc&4QK-HM6x#yB-Q`Xr9b5DZS2Ax(o& zac(qyn}QYrPvv@bj>BMvQoyHhVAyfSI^Oa}7cjo0L2sr~FPx7CvF55B@N{a}M9MW= z7`dLIF^m0C;gXVA8z-rPYTy8SZDLZQxX7WXu=YV{v?DKSt#^R>V@%ES>{6MN2F#rVz^ot~#C3~hJ~aucKq${WP~k$%>n8EF?9idI6Vopm8o#&U3i zZ%9h}=!1t&>?gXl+2L#lw32`nF;qVHW+{ms4tmyaSVGhIFFb`iC9Z*kI)37KNrnzzJmtvFOYMNr8dh`jCqhEkJY`&^tzXfJl2Z%~?lFdoI*-f(O zLSwbl`MYuQ4Fp!{c`S;166tBSyFuqX$E}%Su278^z*iyi8>LXTOPU)?!pVV7*K^-Z zQ{4Lxcks2dMmYW4m0bF=jhuPLTDG3P0!Kl!Ff`JKQ0g2}NM*ZD0tE5Ih*))B7Q&7* zR&d*g9w+n^bht>qitZ~i4|NjuK@yKd1+JmUL?S}-9(pr#T%GrGCWiqo2` zIH$qb_$Vt^j&Sn&36`yFF+Sd6WTM4LtHhNO$2NF;6{va@Gc!GAj&+!s?sDkaIUYYS z#j)uQQ^yuKcA&@1w`QpDG}kw9OC7~%LD?>9uMR2*Ld~%yFrsa9A)bzBiONAzF5m$5 zv8y&m8;*XzVq{Z;o!eFn%;!SH2G-u9$i$_|9^ViNTaU+45UA)=(Xg|vML78M95?^_ zWBl8fAK{+spJ8@?pT^lO#x5C;CQKDH`8nzVi){@S3KK*ny^dKrJBlP&t$!l&jzZ8j zd5Q!(<1Q*nAD^$iIw(pJvzTk->PSe=EiHKN&;p@~z-{A(4M246)j0*V*+YLP;mqZr_mmM znVIq2@{Omt)uUa*F}FFctG_npFul{OKnP9^7N&a4-r1oT7n<8ztlhPQU9VorDW@;z zv@I*yv}KHS8^`nM@c-+YnO@+rho;&8@DUz<_!vLB_Ye<0IK}*dIp!Xkr8uR@lJ#xX z&Wb<-7`GL-2tTcv zB2pog33>nM-h+Jo%MWwYwU2Y)x?`}x(OT1BVqL37#zrIyahpV;ip@*nxWq-VC5leW zjLT!1lag>M7znkn8Omy(Q2YSU3iU~d_O6n2)Tva08*>~!G|$mP3oKvLX6>q&bGHLD z^78rrVDc<>E&jlu2WLrpghF$pKKaBny@qGRQBMHVB#s!Rmn3GkhekD2)JQrAW)mBs ztLMF-C)lNlWj!a<0wRPYjh&AmCAvnnT|r%ShFnCj42|gfszRumjb|YiO(=a_ zayiEy4)oc%a|P?SO>p1$4WPfL8LbG(w>_lF38?gkIvH-^Urx!>>1&LU)jW& z=dR+y3)i!8!!njF8`eMniA&-0e`F(%FKM%LcblEN8Wc@cRv{1yNp5804J@L$@X?0z*7p)IsHHIoK-CGXK7E`uYnEt@ zJXzknMcReVp{OxLlVFu%@j-C&zwPI1*FM5+H$2I)Tjz0G3)*|z6h)z47$4C{MWShp zCk&NxNSeOGOcAS52%$c6oA`Zfi_d^etvqdgc~Mt*?>SfkpzmrcY$Ky^LD#F-}lJOLOf0)5r8DA z>C`5*gR>0jMx~>RTSU`An#KyLa}fx>hPDZbBs)_wQ=%qjC7=9h5!ynOfedhHdBF)q z2r;{yCoOnnVAayf=@&?JDj&Kef-jzv0cA zkc6Hlgk}V20D+J!Mgzi32IJUHutVBSXSInPucUjq9ovZ=x1H`~l1|&J?YP@<2ix6E z2b%`lOa_A_GmCi?lR!fA@bsqNaPQf>|JYTv>zv>HJv|9$Eiikn_kQ=Dd(J+4toqil ztKNG6mI}L`x`Q-LzUX@?7%;^3Z*|gBv2~{FM^z(pV18%MrLRA|W?TR)d_>7r1nIj% zq9PBaBy|kfp!!?Y9v!*=VczoRckrPbzs0R@y^D>9dZtfaW%ZdmE2p310kK^-;j)v8 zAXKIn4-oq36%E|3RzN}bh%N+?T2DQBt@WOUy`gkm?@Lmf-H?5dX4 zbglc(J-2?J!)(2$n>O)7)4yZRYla~z5)7W0Mhq}frq+>@I^aY!V-#IQ7?3sr;C1!V zygfZp7mfb|YR+y-*sS+S5j`cXgiUJrO7nq8eO5la%fnQqz%JmsoWcr%H9Ba^0e zx%MIFbLpx`xAB!V%3X6#efB=CdHp3^^8@>N+EtHZvIW|YNq~t_;*P4~qJa_yQ=Tti z@e)79s!gFfD3$E(-aX+t*Pg|5u04w%|N95|@XdE~^LuaOvw!hzj(lsz(o{{y72~g)hDVI-*9#XEUPi^ffmAAmuX4NrMv0rmh zN!nR56LV7WfZ(aLVU8{phD>}WTxo*0L)?+DGSsY|$rEa(#Rq5g*V7(qJm7p9r*fT%c)2-;FW*xZ_UkQjF^b)JILa^L< z{A4FGH9LbSWiHO4pjl}=*|$Ba5Hslp_cQ|vhb-cnF9vANbRC#tw|6~D7!UKKaZ`7l zq(0$?xaiFvBscg;b$6ajVCAe;vJ?)_Gar8IeSGM*zs;XL&(B_v;QS0@%)#Z!^>WAA*Y?b zL!XX^6yvN8zl(G>J&W%hTuY`Nw7Jv-?lo#j9U+0k3}51>E%hJNWare}#{{ z{dNw2`Y^k$SVeYpRh*c+kV?+Ea%;duVKif4e>8LQ)w?+R+&xsbUl&-(su}63exuh^ zu(i2~&CSfmK6n>@{f@8l;rHIb{kN?;2M-)&V||WHt3QN$#rgsW&#Okeia>Q! zN`^kEOsS^8`k>j=l~bC@%oK8_Y*Mr#;hv_{t?!_qQO9aaJRXbss3g^^xS35oHjB2| z)1gN1U8x+hg`>3Vxb>lkxKmiswyaJP{n<<8v!*<7{{}by;WxSYjo;wJYj^Xc7oEwo zpK}IJzj8l2mOD<|yUHckoW?ib{UH6B)o~SI{r*ihzqG-*FFt`E`lX9``D-p>b+v8c zTtJvCAQInQrKcUHyYAWhx$fEf`OItYhLm+A5{1B-xdnW_HaoKn0dIx8*3N=@Dt@*L`R_XSeD)3PTqP9~@<(W+*^KnINK5 zaM7xCnr1hoE)}Gy9!C7d19xo{jvT09Vb9*Z?A}qmWg`e$qz*B`Hh$ltLm5LED|x}S z9XqN5=jhs;yrIw|Xq&_Sa+qgMZxqo6E0xVkL{ux?Zi>F_AHXpd;8{`a|^UV6kk8r}pE4=!DeHuUd z+KV}PPYpZCW<^F!GIQBPO4m%C--V@+nU!^xBtc%P^FAp&`6(yzJ!cAYe>re6WeSRlFn%~Fr(_nol++&!#zOM#=H9;EG9IS+<_(aC(DouapKiK!v@@RGv@u-sA3y@P@*RWV|8-Pj9H4O+(_E@UOAMFYsyt7 z&I$UINhFqcO;~;Ul#RaU>z{gvulzrE^X8|0fwM0^iSD#1>+f4ZZmTgqOi;J)%%br2d^i-Km5>u{y*5kS68IR}fKk`NX`1e1{U2lJw z)u*l^JG;iDOj%om%|5e|;M!-@=wn5>fnnB-qwBo$J>TZ08*k(D@BB7LzOc^Hg)6L{ zvw}=jX{)B|*>cSYX`v+DVrfWW&<#_jT3c#gOkZM(RdG+)Mvx4(RAp+74Ckh0QC*@M zJ91V)FJ6)3Fp21u-$Nj<;%hoq^I7n8G1d%I@8}j~%P4I$~Ri%A&tr!X%Uhor#M%T`t}dc@S%Qy+YQC!sSlp)t-GrhR88Z`mXapT3 z^RlgAR4ICe1x>7>RJRwxswcVUj>EkFz2D${@A(E_e9r@H-rKX|Da))}zo&ZfV*6Y_cU64J>JODu zu09(W-5YvTEBtlmGD8COS*jI7k!)4aN<6~WJiJRVCKv)yypikGQEuOSOiJviR%8gJy;Ph*c`?c@cF;{4sxc&MX5ylR!98tT8?w&0bcL)+GN`V~ zj#yLyYg{NPYBD-f-=)-Czgv!&qOQ)?W_L@>IN<_nyb=m23#n8yt?MmSZ&WlO_R?l? zl$X~Ese|YIi}U$s|HBoWu)3SdVKxw!wR$yOQas*9$$cHOXs7(HE2SPo@Uu05x|Ip) zg20?Y=B%^#@JqjPEmvM~Du3|rKfyhJb%>Q`?nJs8CZJ@<4{vhzwWo8&+0{e#)1SGY zzxa!<@`<Vcdar2wkpQszZtSF3KMGvl*1H0S`m@dZa0 zP#L7@RkjoplkM3c0z^}==zIJXB1p=v$1#V`V(+Gkfi60Q^HQnTEDFH_R2dr_S!*8f zQ#~N4M_d*>aLw^ck zp*d4Yabi}$gD6`)lBsDvp}tS;?)7-TD5}8q0`pXn&!Jn7viI~I{Pe%OhF842<~=I8 zif+=cg!3ph`9Y_gy#RgMq+*q!U%_`*$;{I_i4|3n3RTU$Nj;P|g)%`(Pfi;ombu}j z=kt`OpUQ9j%7^*r?|qBu70aaE6Id@y4)>gY!9G6v!8`fSfAV=g{+>HoySrz4ddJ?Y z_mHSQK1C9_6t(tNH-Uj(z*!ow`i!gjt4emYL3KhJg9BE{voKv_?!S z>g+9?h5cqalpMqsMWiv>pBS77iQavk8KW~Dh>Fu$#p4=>7H7Ee-AVUEF(RTOP$p{@ z1Qnkh5fh9B(I-p0*;h^{DUp|8W4#d++t((oJ({u*4@Y8R;;nsWQWZ8L&1-f(%j7k+ zo?si^Iys_oA};pCGZ@}cs1t2opsKqdLdU2bHpmA}+%Q509&ib0c6{Rk+8)dEBZ`bL zu4L^oos9%eW{Ns(gZm~F8BQG3ytjH_wMMZ?(y61!Ayv6YIhX+X6JKL=i~XhM?GuRt8ZBG-!sTgyk{mOMxRe z7x9C8aJxX>!GaJCbR%R2;10X}kADFMR^P{2!jj z>1Xfa$OjIR_AIfyt3z_86mvE!OiD&Nn0IL6`*!xHkjTme&4bj7ZcdM-TdJ=|{jFJV zEZn6?NQiD0OMPAp!Pq-QoEV6<(>Hxwt2Bf|u1<2cPwJkuJp*S>Ck*A0+*%<hUb%}MCT`XPqwD$;}aeT-U;iBPtPBHP@NMsUiNr#fiR zl#g^KrhF@HL}Nxnpvk78 z9usq{4NjoIW1b4lNMuL!JAh6&`0xz*#5zCyn^*D^Z@8SoQ3@Gk33JjYSU}{C?{?kD zf5}p(reIlkrR-#0W}JTBZvMyrDTy#xJ8R{*d zF*s9pVw*moQZvVv%KSX9w(3tjWTT;KBMLN*Zeo)3;#NB1zDVt!lxU38(2XLc!5)q3 z0V&@8iXfWkZf$rZ9uyJDn6PYl?RIj}qB7v>ela-ely;)hJymVPhK=eS)&a~?;c3!A z%c+sfCMM*qa-g(;zB#w|3pnMEVvnDpP;Izf7eh{ZugCaQ_h(-Wp-(Lk4$WK}%yfez z2iA{d2&nok96d5;_W2Ed?oH3)Ctv?m3NuPxCe5d9tN>wB6_kWk`F&Mv<|j~=fzIjb zM5YurIP0uc{_XF-i1S`_5(jQRq866YghNqGt-dQo8Iloz%Cy>V9#T|_D^dquv33A0 ziYmQ03imw4_Kq^zBPzl%!9{3C8@e{d))_QYvi%+rbsv(hM-(2!avMd_)AAnuEf03{ z7L*auh}}5`7t{`y+v>xq7%ghu!+5-r4Gz`^s%SLG%WBpgd)zj0P?#DKavzUmFtmwAR!7#g7YUx# zYhsIW4HJ7});l}4?(j7zk$uulAsv)t7V|Te0+Z@7OM<*!IC9GoUj187;vc{M3hku^ zOO`oIGC5Vh(M<3lu18t7%*NmOqN0wVF6q>O(Un8bsx-?|MJi|S-;;`@Ml`am52;5oD%#Msk?kS9#}xiiv^IU8ttl0w>`~L@L}nDl zdK1Ad296I&SYN(V0)RCYg8Oy(gQfY#L=$$XVqBugW8W8D8;Csd2U+khRvaa^O1Vvu zY3Cs-wYEWV*)VF*$L7_6&P5awmIf(J%+dQjX_)>0F z8Xm!^FN`4S_fM(gpvHGf^>U<89p7p~wPh%9!9^$W%Wu4%Y;3r`)&Rs zGZ{FbMI~$3P;3@ES|N@;Oc!IB9nHYt$ky~G#?*{?8p8`>x0#_Wpt~Ca>{*mB#X5u0 zW2~F>GejBib3#r1AaG2TTqGI`)g9rQi#&vz$D&OM{}}u>zEi~q8D6u2&V~eZ@Z-Rk zObEEb%im`m51c`agDBU?0rp9l$f#A%Cc*?gNc};d>6!(~(ML4d5l0ITonSJo5tSJH z+MesB#-EUq5i$pEKFHaxK9yhjSI@@Tl{Kd%GE=ITUy+R;C&cTgrOGm84%Qx5|vre znghfb5@wAtbD`Crg3iVXMb}Jt=J;dT1$|Hrodm^ML^_6)auHG|tlhfCiC664*Z<8A zu;+w&#J=Y!SvG24q-KDr5FQmIJH**Y{QUh`8ursT)^tqi*g?k>q0q}AC^h)U-}})E z_|gCAsjPkCNYy_~noo$E_ti=gtvc;>(wLJeZlMtXrE#`q%vj*T(Cxbsgdp-jc-Byg zF+5v4!J6qrO+_yvdQa`2i9uL9$6}hbl}H$mje3n}M4}QU87oOf4{i5AtgQYX^c$v_ z8nmGP-gm`iIIQErL}zAMBP^B&8B=oQ;RM@z+|R`ZOz#i#==tg07Z|3Lz<+FI=6ZVl=uX+Hc_|f)-#YVO! zX)gn)^!-tKl8V_j!*R7$uw9+xGB72Vsb+A@yy0iB;*wWAo(Dd9lss(^(*2@fsCxt7 z^k()oQ>_yYn*!HSj5fX^0!JYf}t}IxG5tYQY#lMAM<%xBSiAt=r4Y)M3Q}F(*xoAUU)yd2~Q`A3R2H|PNyqmYdka|Zs z#y#InWvh4%iwSTc(Ulb>C5;(7W4a{#cfWQmd!M$-(R((KNutb)GaX;=CbF0qk?NdA zglZy7v+5Pi3nc^h1gk45KrIlvWJpx8D=9Pb^=9IWqn>sIK=gam7urF;n7>%8oxOy* zTKf!TLu0ZQWZPa5M}CpoV+#?&$ohht#)M=cMbZf3?Vd8YUtpmB@MpU=IN7MJ%CM!# z&`HgRh)sGxGlCAH9|+XniZta|(ucw%xhJ6#1P?=y8)2kKGb0*Th~pI76Q9etJnZ>r z`+7#_@RyHr-iuD)4L@^bZEqe!=XHFXndQ1R>n4uOMTu}Si-!1GF5$Q63hznMO99RM?e6ooCQVOc zd&Tr7S@j^Lp{b(A2%)Vrmne+*sEFn7lD0<8tX$hu+t>w>C!+jCV$GPi#A_24+#HF@ zf;k&iWiMB_maCb~5*;B7V5Jl_f7w7$bc5?zje4UiI4zHk$-JVt%0nA?pz9hGxJaht z;HOgBZ#KEfCQQWb{(gcK25{D7Y9A9Re!9~ZWMf{nKc08ChqNSY9G%hKSNNGz+;`}lGUSDf9$y4-!7AvPoUq-C$$?$WL6#jqkgiTmIm7 z_FcQ1K4+Liw8SGgB4GR*kBo)sreMimlu@I#OyW*gX=|#LYF`B=KOKnd~ zbil@pLSdLuHiB~2`ftCRWyZoLI(03&b(5i(ItaEfY`|iy6^{|CRJcv1^0bki-a|WD zW29g_t)4ip?UUMo+I9)(B~@-|YL8SjI#w@EKw|{CBexvk6~Ay1&${*ueaEc6yet`x z1xF?@&lCD0OjDirQmB#csnKXQjvnS~xBNAq{+qw%o40)EmQ6rhHpoabB3PxtnOK^3}{ZX5N4_9dlD>s=8;+q{j{A?&AY|dILZLb^}s}t=&gzr z&r<1DBy8!c*J~28#$yq|^B9XJ4XY@)5jJKcKqsfRGk;_8dMQCUK zE`DlM;iJ>zV8$+*gxv(B65pc}Q=e(dU^BId4utsznDSL0ph&LgnQ}oo$UQKvR-J?2 zTH~~5?d2c6{_;9j^MXv)0YSvF_sQUI5<_@(bBI)8vVP+nVhh{24FfLxbpg!@P&`PmydtouXxuV{5GF_|J!-;wa??yt6s>?6HcY; z5;fMy49YZg=6k)^YSx`2=oqd;?jTJ#|I(BB;nzKh-~IWIv3$*xG)ZJKG6U&!%~;?o z^%v17B)(2fbhmXE_lG3S3zgzJRQCww8$|*NE^TiN9PG^6gPm8C#`uCI(ep`VD5)Y^ z>@$J5*}H=c<^6;q7)6C z7r42>NQUPToFYr{jbEMQs@C7a+SQJWH>W0PmnQN!wrns^ynU@Ny&{yVU#ag+CK~B? z)PXM-sTt%%TF5{Z)w)t6r_XPj@gu)}H7B241A14@|1@xf=wDIan|ykz7;^BTZ}8Py z{+f?};62>;?Rz-o)H8VD-}@<^aLtR@b>f+T9hIwFY4zkYx$?z7#l_eCFt>f=?R@B_ z_w%m*>rH&*UGL!XYo5bpS6|ECGcG|i)B3=P>wCHw-UbFC9+tumhS$9AQvUoezs^0M zI>_Ejb}%=zP!$dUny`zy2}9`5T+GH+m8G^Ue3Or8v-wL^QC=BT7JtrzCKWv*pqoAh zy~Y`1Wygk^JdUv%5-MB{1jnu`gYQjcAT&k`8VYsm3K-J_7JMGxI~fy-ShgcJ5pbQDg$VtFvy%r=;RJWNpGMN}FH9AS+<{7{m_%dcGY+ zD=o#P)l++>e8BY@ra&&L)r?~(liKgK&#ZAE3P(i%03ZNKL_t*c4X5ymS6-;UWNK2G z743c|Gp7b+4lp`rr0eL{k8;zE@8|P3{}D&;`aCC}c^)tL@z-(wRWIX&eS7ro9&%=y zCaQp|?M))=*tLgCp7#?x@#-JqYahRvPu~1iZv2b?$R|JaPM&o2%ed;g8`yp7B-CJJUc zZksvjGbDw5sXDZIyb+z`ra%i5Wj-yc{PnXBAxBVAZUbSFrHyh#jjPZGp#&su}vh%Ov!WaHmoO9*XOjdUK z7*>I(Q%!v}L$|OE#ow{CYcCf+`z2g>-4F83FW$sgKKxhQ@}588wl95(*Sz6Z*|~QQ zfA`9E$>8f8yz+-H;C(-QD_?!@{p`4Gf`w|dg!G*$S@nq)Ezr(*>H1Pds>c-$Z*sSI zOB6@_EDGVXA@x!;&8QtP3@BYgP1ZGDoZ&)IX~4u6ML${(isp^M(^I1aY9A!|ZO8-{ zgJ7snjr)EqsVt%qTRde48)(5bt3;9nlvM9ZY9gq~~(pMOQHG)_CBauP{6M@OU)7$4iWYT1MZ&Ob|O)I$r+j zCz2k{%=^9`nV?42a}RH|)=}eAWuunhfhuz|V*I z9yFgUQ|J~G$4lEwUR80uV$}D@M0V`l$q=A!P;&*D;xPUui0Xz;Ipus_ z^N)U!o8I-O{Keb=op;>M?#G?Owa9$Vu?iCzSqnEG6+spc>c?t$Xj0XWxn=-huL+} zYE7$AR0(TqHy~Y$B5!5js|1P;D_TkJ<5Aa#hXW0|L;X;*9`to#SM;L#!eaYK(XxqK zO61HU?!Rfb?O-b%nv+M@xLS>}d9Ig=fNHlE%e|2XjLR6U2*=Q&jIV92u;G?Lws}jj zV!9MlZmP}RJX4E_D8czh5Y26EekeMLMG=glkZ8S8WtyRial_+)WFr(tDWe280b4sAX7+|abZwfU1)Xds9QArT162I|Xg@0VLQ`c3xr6z)=KSE#oyWet zJL*#s7kZTK7t#LGGNJ=J_w3{H7rd5Bu6q@?e(VE$_WkeXBX9XneCY#k;lgLUfTvvZ za!!8yxdhq_z=IFm&1XOKZoYBTf9B4+@8|L7Ud(kr{xe*9&GXs4`=l_(QRCR=-t*Is z>UGYcRtKaSpp*5`oU>%nvWt~i|Ht1W0a`$ebOV-7szO_Oq)aKLtLbq3#z-I&n666d zJm!+=q~p~;bOCR|HC)7*NVyTLWDah!Xr4xG4y7#k z%|)K^w2k?~cAvMrz&d7|4L$pk)Qi^c7$UiQ-Kx#+1+W3ua%;d}w5q%CMyP@1--*@ZbZg@rBdRCEp`KE3Gg z_zlPVT_|Mw(vz4}&s8aG^c8WgPL}DF=^U@GZ&h9k$iU;)&{LbN zT7{u52mE@>z{f{F+T&KnL}ZLmU?lR4<)uZ0#Vg4}q9%H=C~@#-P2RKbhBz`!wkxuMpY|Lsyz-gc`k7n!*v;?alQ+GO zuYT|yoVNcI?!WgS_dT3B=aS2L@sHoY`ByxhG~K!7T|Of+c*7%>8V<3FZK7yJ3eXAj zl3AOtlO(Zo^0$|tH8h`}Ii01!wWmcfTE_w)+nCM_Oa)1u zsn6n$TR*{Uu_Yo2)~7hQD% zAHVTF(nV8bmg`|TX;`e%OsNU&11hb-p7n%%Zu`YHFQ}hW@W-l3(@I4AFruxgzOMaj z=4E?FP!E`^gRMn@hWbl!LPcp}O=P^jZ*^?z<*oCd80F+zP$GSh?M8o*7(}=>ywWJO z`)OG05Z#a>^&03R99Ul3=bZ5KFhH~4>m@NqHyO7K*KT_s0x_rxyXKu}6B$vI_f3&c zXNu0K^o{*D6P<}|B5Xdi$^IAb;Ib>LXwlOn6uRSFh#SE?$gVu?7F^+4Cs z-Xh9-N>L+N>O)eASn;T9o-V^C%k(MMv#5Wu${&MKn&5ORJRCFC}566D9r$VTv#X z>9F8V<0a+sd`lqYDN{<19zBCc(ZBDsOsOjEZq&Cj5wdhJe>9Qo>gnyG8Lpmr{aGxZ z*fHOjJN$RWs3~Lhdr?b^`=vnhkBVZkji0}fp<=@PSahw9T^y_p_LvZurYUQ6O;$uC z?cEU0u7O#>q5;LqIE}{flrbT(xtNTX!Xjj{u)^efRjFPZ42Mv;QqZjM&rbgu(a4Em z5EvaKQ;?dcpbdOV73pM?X9d@Ei&}2lso!v*%cy^96x6s=wbK`uO&uDVhhhm1d{PDz z#0+FoIn!*jXZfVWW#`vZz14iab<;m$kuaz}rkP2q9l7J{U*gb%_t7ONou=iWfUF~> z*C5OjGRsIwNSU)yGCOwf;|b?K31o;M1a}wO($)e)QK-~2LlYVH>*0e3IP}eLvT^6# zOdmRctj*|U$=rmf`hhYyGX*T%Tmu-EbpBJJOnS(P>3Sh|!hA(2YlUukCuh9$2bk>L zLof0uf-nfsxyW$Faqp^b@Z!WEQpw#_RVi!x@IEYLhz6|EFS z4))oJ24Uk5#zccF>G#|P%Z}bF*&^BD?eX-eibzcK@-?pSE@+=dBNI`EjQ&~~(+GQH zGQJRR-0mSz_+^{3RNaS|63QB(16i*Pe@mswqyB>t6N8mX7~K2MbR9}O%-mbdg&7>x zNJK&=Dw(-2+W%D^%>^|(gDcTYIUD-#O;{GMBxu%9F$gCq}cqr|W zOC=(?w6XV;M>6N*?|d^Kd(T^$&o`l)){T`4BAG06rX@4YRcYAGC(I`uYaPhuj3UBQ zpY=Shf7L&vlU;7z)kLz0Ob0EAmN5Wk8K#LT6K24{n?B3(+y08>_x?5cleaVB5Hk+5 zuB$(@X)hS9Cq;WM!H0K_?v16o<`jA|Jrg#733Fh^UC($4C;q>`&CdO&J&Lhbdc`IM zSlzS4Q=fh+x4!K@%Bd?=lnR?UYA6f1(sR%YV}!OzRb&?>Hg-;@-rEiWHvM2}Uf+G4 z_?CZ}1w=>hQN19BNc4OfoqjewiwHF{K(GMWSO;Ps>3)<(&f2zITkcA3+(P=Aoz?oke5;8N>T6@I8^XYFCRH-T|nu=l8 zAu&-;M|-X=qTr1yZRC4E4rI=``UFnhZ|7n<7yAYq^O&Vl5;r3j-AIzyJaiAA_~82~ zYY($`&oaHt-C9|noIvU7DOrI@Ds+-(sQ z1J`j8m?k!X>7Trn2jBAN-1Vn7vWGi3ku?&q1K7nr3RBE}(FC?eSV~xqCVXvONxoI| zO4Wg_u*rJWa4;d$Gi8NC-1XtNu=aabvh&w|;W)=xhr0A?v8wMm|Du!Gan6*y-jh~3 zztQ85069w?V|5lY#ZEEBee~(b!&gRqn>(x#;GwO_KtzCMJWx>|F?|j0N|6G^aj|`1 zrcv?DbSyBi3@w7vkuJo~i-^Acw#CXbCM@GhhQGAWh5)?r(l);PY}mpI_Hg>Pfr}9m zgP18$Lo=1>Kr~bsl&$)^`=hurtm+QhG3|nTwYl9_?=|m3gWRT1v3jiCDhicSkj+AW zG;`_YkHdW83)9LCXs>$YQoK)HYd#2UY!;T5CX}Tqq>d!1n*NH$o+*h;M=yz-VBTel zupmwbD^aCQDDJlKNat!6~&fDSYXx-1h7Lj_Du$4okoj*@du^ z8GG1J)RGXE=&2D#R-J$taTz1uWBs;ZR7iAeFs;aq%o>Tr$?W5PCbxb4cm{azl4|*@ zDPB9^vL~O+N$2h0?z`7nT~UVMjIBNF0jo{iHsqmeDH2Jy5+iK`2eCw~9?@Jw>fmYI z!jGC5(2a=Rtfkf-(cdfOX!}^1Y|?vM0=q)#f)CiJY`^#0@8dGrI?2bba8V_0J~i(@ z*IQ`TwGbY_2~VQ3$2ls>)Mt|tm0Ztb*ZRZ6MIR9NB8=@6wHB4e0X&Rkp<=S!`e78l zq5`RI@1p3$h@G{=?>FUey`K6^o(N}NbV3`H0!5NBp5rWyW#p1clET_qWu^rDpTvlW{%(k*4uP*hHyk)IDb>=YM*>P=i?nT79t8A^GYf0BrpwH`zcO$<5TJ#2Pd~@+^t^3 z-Hk=#OGbob$i|794W`|f+WiGQ=dsmYaX>>z?K;f*p514ya>8jXMoHW_kELu8lcW+3 zPZDq9fI6Bb?Cez1@m8@(sux8~F)~p9X(>#ZusiQilV@Rtj=j@mdf@(F_%-IQ{ik$1 z$R=l!SjD#0u$DM_i%J008aa>1#ujz)Iex6g&!4Y!oU(r}>1Y`S;gTl2 znKj0chFy<7N0zI{>-Wtc>YfZM5ozXXB|v6>&k8Ty)!!Pdqh={TTw06C!!j*>f)vluf|`y|A~-+PbLu&} zIQN{rZJ-58F#SH3GUnEGEb2^{qR-6Xr8Tp~>!s9ac}foJQKtpaR)jK{s1k1uUB?VK z@MHgs_22wuR++JfeJn8xTR$*~g&0G&5C;}MQNkS&(X`EHpA8*IsJrmk2}vDOTiLa~ zi=T8#b?BOxYNr-)w}8m;O($4%T>#BsP|9#)+g~#e>ttn6-;grYw*-;j_e{pEpLS9> zVe8#;92Zw1*gB32!)GSw$4J!hmw`|XR4**10g*mL2_Y?73gaT--=cdR-WKt}(iS@! z@B~NN5lMKYaJ2I-+Rz5HEnr0viNOIZCngejZ)pj?-0=rI(Y3WFiVvv=Q=Q%_s7{q-o&V6iLTOzfvLBs49Rf2D&Cv}cCOJP>>*PTPJ5!20Nxi|Z>XY?hI&;7cf}gQ{Ecds@HR&$u$ZkL zM`+49fa>NG;3?cl%mm+XzMxbk9PJfsVH51$wwkRSwV5h17LeXhpVd_m4fD5^posckRX21b zapaHwjDx@QGn~XS4|6h`+UZ803?W3kVq{~CN}?VlB9EdD?L*QcekE*<1!CHFGPc9^ z+27j7llCsL^!O=xvos~EZsZtnt8{JcxOi%aLf5M+ZFSv?&z0>1MVRjGTK~Bhx2-#^ zHzxdwEw3X&Lp6kruj|~8o*0r*<*qZ-1to=g;=5vrG^3#WYzsGBP(c~}jUta-G&60? zNbk-&y~@3YM*86*@)V8I-CJh;M*(wIDy?Znn*u+jrKdFpB%rd>v|?h zSo`XI-1iUuCHsIGC$UUT0}6#@=1t`Cem2o05{}};Wr%7bR2~zG_6&n(wvL93e%;#l zM_1Yw-M4pz6VKR5+01p$!-n%5$EEm*_=TG?Lr&R6q^u&1l;+J^`JOnEsheNNGN2fD zwFoHR(Mj-;G4+5y7skY`Nm2$mx?{%7ZK(=Fq7n&+jD8aqh&+oB$zqBa?lk0Q1i{3c zQoQ5Vp#e-Z6PU`Vxob->DvivA*$34Iyekcv=)g6f5$bR1eAX1X$^}g6tMaKi|2Sdu z&dWgbN|xcRuU?FK2Hhla*8bg#XXCM!EgRnulY;%CiqUL+6GthA9vd3bh1{2g`z{Gg z)W`AYFa9P|K10VTBnms&V1+puVdkE{ZACOPVFY4`I<#ehtTdE07M;fRHWXq?*fIKP zE%@6iCqHfnC!M~^e65a@r}$JNA^~}r?~=FL;_OfvrZF(f8I_^w-$vq*`%0OYu<7}V z3=A25P_PdZoM=|Z;JV?F39GWjbuL8%f~DZAvYk$Q5jrX1-}tu_9~w{1v8O7KnE^7F zKtM!21%rP_#ucgYjEoe~Z~+w+grBSWygXJkL zbWn(tx-{*$i5Fg%O`hpu(9NXqQk1y((QkWBVO-lm;PtLOxUDjhNvW3275N@Frsy4xCDpeAdXd<*;xj4#1`3=?Zlp84<7v}53yQ& z)9Q{%jW27PKCaDZP76v>Ut`92;uHNGq7o&RF&G&jl^B` z(#|Pt&@59B;I0exOVBSyy^C8z%aDnsw$99Yl5^ch=3Y^t=@@N4 zID!d?PZv!IOj=A&If{C}Nc0~e|G!y;%S3$Bg7dG>kpC80qrBRD|xo3FYE zofsR8-07gJ{2Fx_-Z8a$AkzFU!m2VKlK9@-RXvUL(gxlLTdqDSagzLf#sQ*EC$;ya ziO_eOKvYWEhs1caj<1ZiT0yM@^;$|p6MakRpjMp%k~68VD>sYOC}cYJZ4K47J^bEx zGv^Q+>>(pe$t=_B=CyS(UIh(d#Mts;{k^dx$!48P2rOj7Zw_z1-w7bh2Xy?*cL z$-rFEO9#wJB%tdbMJ|ZJTWd;I30I`c$Uz*16dPD*Mg_B8jwxAikEq{^|1({P5G1@CGZam8@-4H%p5ay=u|4Z;FEHZdob@#69~R*$*%rl{AEGT6`{ zUD6)XNJlMSzwU;5WRqH3g$WUDc zdf_&Z?V}TPBc2l|+ukfLZ<6r%A0-u6Fe401&faG0V}Y6z)y8NM&UDmWkM4C6~z5nT4uynlC|%^A@;oGc2&DpVq#0VTVNM55u+(loo9N#dlG9D=1N3X znKR`<*4Si1J)Jyfh_;W#)C|w))>ncB>%c>t&c1)}BMV0HSjFUAt3A9=Uv4MY(_sFk zS$3$SV{FL9lcmoClM_=_FI%0H6V>2 z;f`cfDXd=+KK^zW2ZDZ4HE2Y=?wsj2z zL#DM^4Ih&2sW`lky;Kg?rqi4Rp*TDSTm#y>xZvPf5+)ZIe zXmwGsrP*_aq*}uNcD;^{=@B>dncZx1lzX|8OWAY7<*a6*%X9it^+G_1&!P2XCH51c z zQFKz!0nti5Ah7qmc(}+?6${mbY!u!(L!Z|qmB9^j#SN!-hfdLVG3!bT>MnA58e zk|KfgN(Qs4R|-?-bD1^nWy140;Ztv9_fsyT%P^BdN2bfB%x-3Hmu`*N7w9|4QuQ4j z!erJlPr{@VcIa-Km(1k20$LSEro++Bm_P;fM0PeN#}EzH8;YNu5hRE#LldwuThAk9 zv}{ZyR1|UXKbgyf`tKxT%%=c2~hcN28 zsN2CVy&San7M8QBrCwtbN%#bl|bwZ29^d^z*2usY! ztZ_SMvj65^=8UIYR&RGxKo_KqV=ZYb9sYoxKk2DzRmjY9X3`zs*e@paioyCJ7E7vc zD@Hs_4^d1H*N8`5>*DC6BE#aI*v0$b-e`M(f-_Qc0`<+S^P3f=S`|i2+C9E7H1hLq&{8vVQ2fyXw1Y{AdkNHDTrDzj7aP72F zbC2>JOtYRY1Da!+);%VAwQh0Ui#vVkyRtd>WLgCC5)^ErzAdWEN-}b(9yzt8qSmQt zqU6HH(OK*4pxD-Yw52Q@_lj~wheBMhBAs#fqE`7jo&|;>{hSiDS~vTdrc0=(q$i}( zRIIW+R|=cS#4KRF3J6R%%sx(I>B0-!`wR5Un6vKD_{|{QFZgHg&F*JI_Njd`6r&cCagw>H^w*32R`*mjg>8aD z9$HD05tGu?2&Jy)@e!8jgRIWnJYL90S#h8)yCUzHkoFjQ35b}8WX>EHM1)-QpMDHB#|1b=Z=lw*+i&*wPkj!22k z)s7=w#|CH=wQ`)ad%IO%3DWxEnIrBkC^6w{)P0}83CX}$Dp*?Lsdg*o30}ZssMulH zruUMTls&rJOGEx;RHyaOS(zzl^YC{IgqC1n&Dw6nj%NfX`o7v;hVx-?XCdqf2qp3b z@kR?SrlfW~p|qeD?RdQ0!r6%LjXAV5Hw$0GTk$kizJSS$UX{5Ub^fp|ecMBC=7#B48z7A$v zICe9zy0Vv}oJhweg(aXGYwLnZetU6Y$T(XWtPg8R-5a8aV;4I)#O9CwBC~v$a_uu~ zKQ`wzNVHkuBryzH5MXtxxJPoTI<1^Yy)c^`rk5qA=RASFgHn1Xa=a*Iv1l|uJmc`; zP10&|L@iP0U?@SuL0FnvOow5^8_&$dr{I(qe+Hx*UVUA z(YTeWyKY4%D4UrpF<7YMK+hhA(KbyHEKRApz0@#}YKb!DHDESoHuebPp*N=dEupO_ zEJZ8S1vZ%o8yj%-Aus>~`o==c~9{@BlQFK3c#@I@s*66$L` zkJva{pul4eb$IrY6z|9{xjki!`BA3W8w2*YFD$5jTsW-v1&Zc;RXmy|G%Le1caT4!>hr)CL+QG3okheIdr zM;`bpd)P?<=5z>!O%gqcB{CDT`jyzGZ)Ctx5S7GK;i*nmkI-{E9fvuUPmMU-cy%@6 zQbwyV`t0`V=GL>u=Fk5(lv_saE<$KU!z;@Y7#Jw3*5v7 zZMiW)o!{z6mR#pzM?n0bZ16?N_Peyt?ZkYY--?bDoqMQ+K-OK~qWi>>xCQ4;N+X7G zUki$ebS=re*1cWX%1X9=58!At(4mq=%h^lRp`SNv+H)vV@+`gFiOxwOi*(Mhi8eXbZb^Rb9KAbESKlVQ-*+ZN%fDUa23S7w=q z?mIddn^f~Wx`*oDMk&r3Ydf-zU7f^;BBWV~lwP_OdlAy#xs%NoK8a=EC==!+R+(Xf z&s4opH!$bDwh3)^GG)}ycFM=rQev4E_OQxsmf6EHdstyNOYG5qyI5uqOYCM@uP?Kk zm2ls(-m`;Utgw?^oI(NCK5`?+n*_DkSSBH*qz;6&^@kqbWbIoU$TZdd1qEsiwxc~( z-AA%@77?@R{QP)_>f(%W3<-$pN(^*?D|scXOHA*l-%DyoOOQfxXU6s}GgTXL@}B6P z%tmbT5P^=DNPrI8(ggcGjW0xgv8Y17F9)Kg(6I#njTi&AwV-~p%zu8m(k(#ZgFJ|z znQakB)0VqjnwmvPbth)c@yQSM`+%e8DX4JKfRB40hA@-n`tMZU;G_sLFHH6b58uDR zLDQoIxEGz!9!)8uNpS9E-L|%dYn2%4XOs5}P2nA^Xv3Oe=gY1KmRVxXoWvRvrWB?W zR+t0ATs0#S&{M<|f%L=RuGYdiqKKvbt4R;49m%d`(1VH9<93cP^ZS$5VQX3!ITOI#w02#H-E(}Y4GD2oWmU~oni507uz zj|!(vPFD*{Yel`^(L@Ocq*N41rtOw$Zu4+>YGQ76)xl0;j%Q_PLbEm)M-UC!D2+mGz5vcCDgMtFfmi=r(jW(;!F(iQ^|g!w^DsdL?N~DZg?m( z1_!tSqdA0DrjayZUCUP3&<$qZmNGCc$50$X+gnD&jGum3fR zkzVps$Ri}`WW~LEWS83nl8p*5$CMvS#~e z1i;;Wi;(KB3>7!n=dm2r#xCYmX74ds(iB`O^To*kJo3CRMME4ph%6@C2KZ;~k%*M6 zjnL#=6d4(TF);!~St4{Ibe%9i&~w}EhXGvEkV`wz_qS6jN;BC$r`qmLIai{YE`z&5 z5E08UY1{HYe?7Z758*zlon}1qHb+r6GDIM@oQJ5wT-}Gr!)jC37Lp{A!qP)N`hjM0()f1EnvHP+xQWiIbO9`Q^Pb&3tK- z7(?lmPQ4JLtv=%+{4C0w_c=K5#b8S^5z<+S&wb+FFwzBceA*r$K2q8GoD&GtdZjW@ zaYdkRbHQD&k?`EMl0na|i_T;Dzx@d|fmJs3YF&DBgiR)x`Yw_hYiC3)Q7jT`Yam36 z`#K~71XtwC3ZXr3r1 z2&S-ASBpWajKJhPxwjgz3`Pgf8(JCI(iP4a3f3t7= z!5x9rh-`T#27C5sY_x@FzA0u2a;23kiU>$Wnl8gBcXr1(0T(~~9YI!%O0X9BO&ns1 zUMH!!*aA^Ut$VZ>fjj5b?hCT3Qb_3BnWMp zn(4C+goMWh*~TL>lbKV1rCYr z1zOA>>RR`c>WP7f69Y?&uKmG!4LUzR5Gc)Y(F3z93Lj^K@C**I=VqKJLh7q?=A!Y7 zIuvO07x85L3$V?RAVv$IeP48cZ=BmY@6I&3d?Nf(loHpqZ8<;vXyQ@Seq-Wg)2BGx zv*$HyTNXV$6=Yzfxz88W~XlWI$4*HQ{Me+?^pXc3bbo z{+iyfwbLTb#dCSqW$(j+af`E1M&A>ohaO2*@=Ajribs|=y@Y9&quxTfyqR;|{hlGg zX_482$Yhq4s7sNs1XCN_4Al|Hh)Gx+VyFbdDPkHd>>I}#=xPjMxd?;1N*j1t+L>7U z=A2J{>~3$=Ae-T%ES0zpXQuDKNM1>{;Nl(iOHQ{?}s8P87XlU0$7&0X^*;T4*!ZH+l@79P$3!|!Qr*8yn>@ty}A~si)TBJ0y_CNw?1TqppYo9xEh8eKYj-TV)FB)+_ z92hChm>&#KfIk`*duWVDqF03BgKWgX{5L`)+~d`tVbE(7(@+PUiz!+~+L<776+;{q z88n27oQ#+ZtT&~dk+8<-@c;>gBdZAEoJlqBy-wzI)R-eB@^%MujvN0;q@Kjz9ms_XdyS; zC(It}Z13j5e$4<$e7!F!Mgzt~q>O$m90Q?jC*JsdN)e&Kvbf;~^_om*g9h$Z+sDBT zvg5!tUZGob0y5_xKh|A>w`>>06Rpc8q9Uh;RBBw4;)}q%dM)V~&{A+{J49vHWEyo5 zN?%wyaf#b+et<80TE(97NTWC!(_`G7%KZN)@6F>ayN>$aZ>_!0aEG2-t=W>S!IEvs zmM3{OLu?ZgAOt?}47?14@PY{>F*q2<1PBHm3D_iN2speK9770GAYcc1(A1hOYo2GR zTdf|XR?l}hXRmsHtg5xvKKHgP=Z_aiwmz+U&OUowt5&UF{i;?K13FrnFqDoUYEIo0 z{?(!ci8K-sjkHW@2uyU$5<@18>6#Hz#gn=j5>;7=3L&H{YDtH2%18bgn?Cugtg?-U zJp?OCx=3eAtfOIKsARx^h7pRe$}-Oo*oU%@F^Aa53R6=eDdKj>qD7BvV3|2q7}GFf zNB}yH6L^*}ds*ZeM(kr?d1zCBTf+)1EgfTE^wpY{s?~Hq<@W2ICQc%4(^xotHR;t% zV;#HX{D;l>IT@2Hg<1)?0&*oH$;=QyLoD$pE(0dpP9r1{E~wk(*yTTu6-QGu>}amn z?PJp>-&9Vw$bYYicxlpGgOApC%$hc}Hk#E+XcLsalpVt zwDawFwJ2JUULM!%#;p`k&aoL%dqkTB0+KnA9J}HsgjNKUNM2~=Vd_yLjVUKpO`5%q zk-^bY5x8h8HwUA@iCt4Zcje=}^>J^un8e&0tJ@4K3<0PJ9l zB1Ad@D+CS`m_ulJj@`7J_=dmD`LBN?M_zc2Bfs`}PUCKdoMPA_4dRJC$cil~QZ~DEIO@ctD&;;)M@*eKHejnpA zhagI{6}~A6m*zq3!EV-k)u68;x}}&n*{kT2WyK46;9Ex7$_!OdnOt_QlE*|#Bsn%I zh&cdEk<@u*B`dHLoQbAY()m4DzX2Nxk5cOe=<5usW7aGVTyI-XOZDOcw7N#N0c~lw z+9+`iQYjcO*j3DwYIUTNHELexV=ta+C{sf2eWhFF8u6@DJ)e91o>d2=MPk^og_{XM z(rj(WDSD%;DHZGN7!sM$pfu++-1FuA9C-dXr)*m=Z2i)ueXZLq*#CtXr$*|5*s{{% z@=nBL43YpH0b#;Ok3$ru5tgP6F?uSc{)Ev4q0`O+gWu0+G-MmF<$bqvSLUeV`MxT6dXHtoY6~e z<yzwkz?+z9 zoa0u6%x{3?yvsQmQ-h(3bl;?+C9j8iz*R_0u%ssG?#BD|hwSl|f`u*4oQtE05owvwu!lw7$)?Z#3ZqNTVqn*pyJ!RB z-~L55UG%lUb10D&IvS2K1?Dck^rbg6<-M1Vt#bXJ?IN7l(75S>4`|KFxN=f(Z?;GZ zCWDNWvq=KI@}sj0RqG(OJlXiQoY!-AugPvvO62$~f$SI%=V+wJYUT$cy$K|Bw-j$v zk%A%{_KIuHtG=%%+F7B@YNGYcoa*<=%OhEX#{$FrrLyUumMf+2Ud!;!8ZwcoS_%}+ z#JC9L0H9tHn-EQ*l}=TALx+*>ulJOC56wrjSZK< zf=DutXP*<#Sfli^>?C`KD(|IqMcRO`NXqt(Jy~8i2d=q6<-5*Ifd$-T zzC;pVq0wM?zEOH<94@+Uabij;Id{cUYw50NR!p0FSyPMPD$iL#$MlF5QnKgB3&Cnv zAZpL7$TajKcG99mQi%u1!AcqwqB4HjkO%%^Ki6Ehi@)~nb6!Gs^jfxR`_z7&L8(jM z^bMSQ!K+z5vPw4y1%ZLhtT7956isohF%ngon_FP>jwg5s$7nX@}Olt;BJ3r#ZjZI2dNOFyb>#s^lD&O}Vj9+mfN~*P` zal(|C70*|0gNB=K*u}kHe3tP=L+eYeMu(&XRTW|H%R7=eoO0eMRIy9+gEMi@U_}E^ z!X|wET8!QYRp|>88BgkzP47@5U2_I}=O9hdrE%eLCP~56k-n~MG6fL&&Vw4T*9xO< zKi1ioZ#{e9dKakwkza8J%Y^E9j|1_@zx=T23NexqLiVkjc@q7tW^7M^qL}P^y@Xqg zu!VB%Y>WD$D^n)8H_4%%H@Kr8=S++j%GWZ%P%Ie8xSM2(rA`VF=3hVNjw^R_{Ug7@vHKph3V%Ze(n1F>eBc*Y;c+(n%lE<@#He<@ zGONaoj!ZjnN~kiiV~Wq%BG< zuUO9hKB?_t+}{7ts-cDDZ1`vI85 zj@8)FvC2@UX?AM@XZ_00Fwc2B`or&M*SEi)qt||sqqkhoW8e1^?EbcIBeI?0=YEQ2 zoD|x?6l~Czp}aUcse%2CUwE9m|7;iY=g%iuo0`m-0`T=WIlR3l{CkMN0~mcth#?Y+ z-1xCsMk)o6CtK%T9QkH1Xo(C*WQ}}e1yS=kc0cDXb0RZy5sLpVDXKPln$~sOtS>F= zp_6)h(L!H-f%Q(V_ti`Evp?Lq3QUn0FX5f!13aS?+}-6-eiXZ~evx{ByMi&BH7f(l zkts-7R|I+WZH|ofL1+xU-~<^3wz`Hljh^2$RFV62TQoovWL4StiZM6;_C7xQolo+O zfBigMq{VnwCqYFtCyMHW##usOG~<>#S+~~v!^saj$zAH{V>TCVV8C3HkWbVxgHF+D z$MK*n{*xbM<8TYz`#;3o2Y!^j3~5YvkyYcs2$2Xxcl__0R zMqxl)QGWHe?q?;!mJm{CUPFQUMvw$YszM&P*CH2{1BS z(M_rxyhgH1BZ^nW3L!z#^-31x>tPBpc+ea<%bch(m~Y_Bz^8xpPTu*ZGg#a+EfJrQ#9DXY+=d4V#SnYBVe5t>hMqSnDtYB)oq^6+*L2$$&`{z8zz`2) zVTe;j+Jw;JMA>@o98Z4c0Kfa6?&bUc>FY}%8XYNz{MZ^udJ6k5<0ke$HFt1Q&O#T2 zfdt}o%A}nzIO}{)`@28Hw(tBw+Hq1e%fJv#i}8ZsO9s<5lM`D^+fRei&d;;>-f!j7 z_k1fdQ3k`(GVahz0JNha>``@X%$_|$*6m*LBY3`Pw)NdaDI5(4KI zva`kGMU(U4xGan2LR{+Wb1MGAc|u19zOUR!tgf~pSif#8_sHWwgJsJva@d)f zMyODUA8%%GU9yzSB??{wWOj4U?|L%X2NdOdnBA!}C)5}0A(*K7!M!i)v~-?TTWzgO zn$4@A8|PQtUvI>s$FhVj1>US7tg3tXBot^W(sf)ZXnRtxMKXKwD5&Nvw^b2*8LUP)VL8U?eac_FE;%(G}eC{9gwy?rVfudm%pb81K>y_2r%ZLf_0t^U>h zATyuW&4*GS=oec9&w6^PM8D=NXPN0U*l3OFuGf5(9y+yI+QNrJHj50BIhiYU+(~6W zT8Gb)wRPtFx^aNAwjv!^K6t+B#nWF zfSEu!fP5BU{w3Q?(p3Wu4MZ5IG6*S~y$%yHXu2ez9UU+w#7G-bn{*cCmEOO_i;XH| zQ>G0{BT9#|+;yyU-ac*)q_%BHO9n*TOQi%$=a}SVKkoH}F^=@|l>nE6d{T#ih zYTJCE^{Oa9mfhm|Eyw3c&P@#W20EI7q?kCu->SipvIMest4(n z{aJ8a2)e41Op)d_N_qBCbQ0P4mJQtgAD`h~r1ne@VAA+G#?nSwkDr zcak?rM3@c&D-Gc0jW%cqEGZnFbVLk_P^Q|^#VLaZMhz$(9aFm4 zk>^=0c6U^ms1gkEs79hp5;4Pw=k^@u6F+k!a$3vWf@OX&#S!V7={_;|AasPA(^oh$ z(V`#%_M7M8iRt`ak|j@+Zj)e92sTzkvSP}7g53iPN66tArr_K&nGw6mr=xA$N}w7; zJ{fy{+w|fm?eZ7fKWh^8@}YdCtv;se%W{)w9pijQ&6U_gC)20Ah(ZOuyrU#{S`E+Y z#;Z*kjbzAIXRh+b%L>M{dUPdXGerFwInKb&&F*Q{3KdBqhE;nVRibvKiVRlTfiQg4 zm{0%I9o+S${eYmROcY=$i3j>CumzGQe4@&#rZqXP2!ce0iP6USDM1)D4RdY7z*hOX znM^t)p_eGQsnSk`VJC^?S3#x?O>7deYQQvB1*#f}3`Aiyp`@w1v<=Mv>z}!Sr>;K8 zhI8kTF6RCWMxf`-xCNhBJYX`1I=FmDndqP(f)u2gc(+UecsxiT5&JHSJy|Y`2-U+G zob$+XB>7o=BKFh;*@TDwDt$MHW?)B;Cp^ifGoSllqW`<^%O=lym!Cy0^)YqYxL$U% z^t4%V)bJno?uho1?4}bd^Te)EXK_pIt0ljylzY2*DBWg1gbVTIu zYAB?nT`cFge;-qfISGzdrNsTcTsT)E<5NZ~Pa{A7FLrYHxf6(G03iZxK*CEc^!-0~ z6Vgl+qSAD!Z#yC#p1%!NyGTbVRnbWD3`umCMMr1sX99Oc=vAz^ms%nx2~1U(MvGuJ zVU)Ze$(~CTng+U*i7i;v>>qyWKCb`wPq5)l8}J~&8ZCQ2`he~&^fQhw{ZxV;6>@}X zUf<<1Wj{5to&KXM5e!hn*nMjj1yVjXtm-2GU?>Ae};P2C~iss zx%ihl?6ZY?uBGeb)dFQfmp7uJ9q*{jg@mH{HA1NJ;`uC+pWPXK-*4~h&+7^)zZ0NS zSa{7MkA40CKmFnB(MiC=)uv3D%3lSDQhL4#LL&`oWI!;4(UDRB_~AWS>7X-oTdU9D z-_3gw8=-5wZ&Lcp7~CZC8iQI1dU}SgNeOj>3=jrf^~ERocYpUL+EOWjCrZiVt(`8^FaIZ{ai zpjnu_2@Jp|SlR$xL^@^T+c$C3C!gRqK6b0Mo6yCMu5*R5-kkALjMD#qw%Wz&!FkDb zn_Te?!Z?In?lV8R2(b-xF`%)*t1|b2M*1`i!l<#}GGL^_Fa$)VC=*ijqDKg(GZjJO zGphRBb+$J|tqSn}{7o!xjepB|ia^Ljp&!uHzuV_wkdmHa?d9t` z5nSB_&HIEF7(&;YYiPohmE=B-14IJ*4=nS6AHIg?Zav1v-Jr>59QTsX4sCe)BTB zd2)^9kd5rIYO4EbS)>T`cqEsy^+3kS_WAeRttT^QYDLpSGUESBGlMr?Mgfpbh`c7j zAKDu%lv%<%V|E@+0K^yH^-+YQ6xZ}_BW8t>8_T7?AR{chRpxO*g1h}B#Hne^nw{!* zl5pqg&=sLSbULxDL=}sUj45VguwlU9;t`*G|4m%^*(cKR1A$4JI@2=1&XSc&BKkBK zSMgWDG_3#%wX6B~j|pbe}XoAR?iehp9l*?tz@wn%6E zg-4sJMJ8u-X+(Q$G?S)Dj%1BjrB*U&y-gXUZu(@C+^-GUso-1i>s#rUY(7IC`02vw zbI!lx&H?)OP{?cH{5|VR07AtDnc@*^Nn)V{{MmqYV^iwu)t`M#_U4IMbEnow^@#vt zq0VWG<$SX#UF-JD0_X?aSR>?MqH?L?7W3=5tF1adKX+~O+PO4ZDzW7QYnQTsN7A~h zu<|fbDaDfPN%KOm=&nGwq5T%3)w>r(D_Ph|OwIg`A#tPcHTg7j zBUngA-Bun7;padPnRqw@At|ZOpQVC~)x6(p``TKWMJnEgq24*Gb@B~nPE0$?C<-CK zmf3ib;>*v0Wj;t=5B9ik0DKnuL`PNkw zH{@r{iX#)W>AZ4WiDMC5NtqJ$$+U&GvP);{ar=AL07I&OYfPS61Fg5!C)PJ{0NYe2?{y@s0(*FlBuC+Y>F~* z#F4y0#ciEiN~BjrEYBz+*@ft{k^s>I>}%nx?C>T)>>}d}7g$-E@^jyN6<@gW$#fmT zID(YEc^W&=h6)z`@3Sd61;iAkiw&YJY0*n0NMLy-^5GABfg67DVK!W`i7*ht)D|I| zyu<*>4Xs%Ydh5z6j;;<|F7hau6Umc^{f)*6)?_Wv%O{%y(44Oclxx^^iX%d*kcBc{ z-17rijba-QfnNB2X}i9112S)vw^%sA^u2$Hlj({@$9H0iPB*?cBJambXl$Pd}_%E2f0K?PRiu> z%`<}L`{j12kFC5>)C5}nTA?~t3cRhkBD-*EtEnPgWZ}#as}lLye{eN_@aYHAT^dQV za0fv~sH{S_g6CNJ-)0j)e@B(bLkl4fTH$@^H^z=Sw!NWb)CSN7G3!jYyM%K|4(Pd|b4}vP z&h5cB7m&IQ>X`(xqRC3Zh0TO$c41czY^q{ue4SHIkxgypi$JH$pEF0?-0*8Zcq9M* zmu^eP4FWV1T3I6KfUXg`W@Vk;`Cofeh7bb{(YTKhw8H)O?B~b6@AKUM={;^k+xQ;xLISOzy#JLHV`D*J#bJd27n4wR`+Vkd^ zmfR5bDboiwZd?b{{$Ts-=D!fKtb3Ki2sE8AH!KuvXXAR-%sJUsE1I_6k)OG`(Ch{M z*lrc3HVd@lKr?O<+wL8Jn=cd>mBX@%ho~9qJR7)Gbt&Id+Ruif#r?BIE5t zRz||_{OBD#^~_=Z$&XyYX=g4HnIe){l>gl}MToIQLPVm1MHK(ppFYGVe)1Mh+%;jt z+vjMeFqta0GBL&exaToSZ?L6ANtU2o&D0e&k8TwkWl7W><>YBFxZ=RfWhrh(Ff$?{ zosi8b3zMkLqUfOplG7H{`}3MKv1hRR<}7iIDK;~o3>f!iRTTAcY0sM!j=BFkWwgO7 zTSI5-Pih?iGn3}b{xv2KGY2zsaDhCjGdtkKQmT_XH`g*42AGyL2;N|Ic)mbJ6w%#V zl^?&CFB3}en%~=>*6tBv$eyKs;91{}Wk!4Zp!dIdCiC~V-*U%W2h>rA4kNP}mdRhu zvrg9Bku`pPe{N}0`Ol?emdbEd8O;wEzIlObKmHgW`lp}cfqM^->hd*&7--f{wD-U4 zCQd`k6hcF{9Qn16-OR_n_XbWJS2ldzB9r4Chi^X4(sL6g%ZjvOdfp};)k%`?v~J zLo^31)x=s((O3(B3z-XS01ts~oN=$sHr3*xX_S>?Q(n042rCaRv9N7SGi+=&Ni*l- z+cxm{)ra`tU;iw>_gnV>fe=#R@C4h|_S;{+?SJIys&h0MBq0dGkO%JD&yRlJU+}v> zayQ}pA@gUCII(Yq3tzXLZ~BGTu<4=&miI4n_=cmb9Gl`1r-Wo;)-vR>?TLqyIa?Hm zuRIQRjFYl;_B3@<$|to--tr^*WIrjySVQg5Q<@g)-oL0H(3#`esAz8S{p%>A+(%rvn5s%A1sEa-(=ARw=?h!rZx z9E&+i2!SZ1xDeAz1PEr{bfE}Oqo7TynL6U{PHi|#*v9K3aOh!0&|zlbL8L(zxI8%aM$ho z_$4LSjiMD%#akN&ea^8W9?jH|DG zf}Phr!+kd#;Q8B*6E;J;Wx)89At>1dS26F5M1%h6kz}g)D!1U3&qxTybB;(1$@3VJ zY)WU5xYCzxS71@JEDV(L(kdmBTCPcDu}a!hS=K6Lk&wRT)$BcYvfZ;rQEnEc=wSOz z8bl+Zi?pjS-jo(n9y@-FrPZ|@onL>ZyVh(y>^!T1%5WSSoLTLmu)~KFLRnZC(u|ul zfU_GeO##`RD&m@kwB~}05~Su`+%*T}SdbtDJ6+Xm$N*?SB_d6!)A#fI-6xoT#VEaG_;etMZV)|s{ElAW-vkEhD z?Ao5d3zd|b5(}~vse&yn48qWjxDw4{(_^EocZ0HFAt99GM~|_z(pM-_{axGB{cT-i ze63|)^(>hrAuJnF@BxdwOr`UQ<-)!MA6G;`)G&=NbO zWcybe&qXUmOADw$X7!V-@#&Jr4k4!5#+3=lmFx9tx>ii6(zRupGPUb4mBP%qKaA*G z-M7lhBdfFs?d2n0_4V7i^wm3f^{aRA=F3lKVQWi0NaJecrmLPpTO~9`ETRgS zM-8L5Epp_k75?A%f0>;(?BUzL<6_?X%@;t^f`^lvQV-gYvz)DgoYf4OM3O*D-_q`3 zNGj&1+Fy&BpCzfiv$V_rWL0wFaZCT-Wb$2+pfG3<8g@T&h~N2>2f6O|9_9G$D-2#g zPcz?G5pp$DCN$%Q6Jy~EpL>coyz%sWw~Nl(#6{aEs3!qC325*f0{D#w7QAAbyhxy8V6KEMeJ2(uT+Hx)5c z*fge@6KOfRvEi;sMH5(Y8`aTD70{+4gpLxL?9W>9EYZUKvkTg_J0x`CFFLSU!&)uR zSkh2e7l^G|mN+tB64i2_E-T$?$LbR+gkzDd?_A*QuRVj;zV4rX8qCo4)FA!?q%*gYiChpDriemdX0I$f-pRHjGjH>!7m)(7ye*B*S~)kfAf78 za>bj@O7AFQ3-X+`?@)7FiDU3ykB3YJ_3fVeb2OQ7MKAPCsF_V8Ym$}N75s0a$%K|c z?w@pjVc*`PeE!d#;4}Z}0iND@gu(0Q7`(_k z(`2)1tDJq|R=)eft^6O~bukY=@I2REyNlazdzPoa^c+Wa9-+BlOuMC}wG4C;l~$o^ zlIvLQKZ(f{MT9PBLZ?F^L_@cx9D@UGLk&5JHIiEqND9;yt@Db`3#RTVfL*FEgs9ez z;y;>llbl+^#}-0~O(7||fPyGpgfI8IFx;JMsm>#Z7_ou6vuvIe2d&P(a@ zYV~`QQOdskd-A~x!v>6x$nGhB+315gHFV-Uw7htrWEOWfnwd60UdUHO+HR_n$3U(J zgquVLU(H=tos}Ck%?L>`_zw!H;|8BLpBCdR3mdDiZ|IWM(jU|_$^@+|ch ztnI#10;q&f5~Qy=lj`2mq<~+I#0X7j^DUp*eT=I=`xt-p=?8iC)?*AV8nXD-1%gP@ z4G_1clK=o907*naRAAu(HmLDI2IIwsefJ*a)}4EJ$Ggv=lSng2YqmXu8Zx1w<&sOb zamgjyfYplWFplWTO`d+7*Q)CewKhTwOv#Q^{Em-)}Ys z7Uxrc?ccW#%zK+(tLnj8FVwnX4MLf7o`^T_KpP*h)hr1XXaLHey6oOvEe@Lo$a} zmnZ0{g`1<2@ofnJopC`@J&Z z>(_Fpha|>LL%;(wT1S^&fefe1nR9Dyi?eOtq zEUlhkZaB}&UbYF*1m;WL&*G6$k{RL|?du5IBq*98yC?TW>8ERSLJCPULmh4F%EaBZ zW}Z0oQ%dLfz3PP1f-5gFJk+R6rjezGmkCE<$6FS8*}Hb|`k#Cmm%erruexA6!};2j znVIFq!?V+#fka>l80U14U)s5c-FF;jxY#5m(@5ny$I^hPjaQphrphRG#t#Y1HO#$g z9-TxU_}sHR_}jbr?e}ix4R1Sx_q_EiF1g|iMvJuvC}eXh3ulhMaI9TVF-1{St!d{~ z5+wH5O}Z=f08n@ zPJphG{X8kwNZL6SJ6G+PLorO|+j6S8Sg-g50T z9D87eg}2TlQ$+_hWR305X$DhcCH^Qtm@3^sa@>oANN9zHm(LN;h24*x;F&Kx$W^C2 z%o*?8&ZX}-lS?nz!sVBp%C=MHS>w5pGEsK9%5iGQ_OBM&`rfIIGap8M{3jt4*YG>0Et=6DdsFCVet?c)@6Z15q5eRsh*O*4 z8}gc_wD?j9iw(P;JkEoU9O8|y-vJV6L}-2H&g3~XuB2UAN}1$_qre+3Kb<#RemdXt zJuBRH!?WCa_g-$laSzYldX%MUBrFJ{?ZcD{*r(;B;Y&cJo6;)TX^_!|yN*33#gC22 zb5q32(1b7D2%25Rb=ZW|*LM>O^70gcRKL0P;J37>vOBJ9IAzSjrljciJ(u_suM$0r z=4TPh?6$__@e^i;M?FkjO!n^I$F9ep;_NfeVf&87wBopnFfbRSc~jJcLm`JCXHB63 zMrh@GH=07H>zmbx2cN}DIDbw-5HS1F2Z+b9kZf9yWHsd$J7s!2!s?Xi{j1DhH00&) z+Qyj|ZsRR)K9kqIW*cXoxv}&w%Lr4TMNy_YO{oTQg6Y0GPO4-=j7pfyA;WQQ&?ASA za{X1iXfGSu%%jMp^opvaa13{_SX;y(#Gw<`nrrZi2{Zu~PaiQob;L68@Vy7Q@Avoc z=NpEc_WDK6ebq)Tz2bDvxo|sYp1#Pot@A8wXzi&}+JxCHzflFv!z=~o<9rH-4xV7| zzGLiu_6QH&v5$xEe4btRALZcP$B3hr(WP_n+IcpJM~Z zC%EIwd%5llyLj-SgFO2eFR-$r3|==T44`eDYZA9SQ0H5elB7M5+{$9hE^MO6HF+wO zmyR)XZVD%Rb}YWcv{;Us4I1)9ElOD$&?edOMZAzajGMNYOvaAK9(o9X5{SQ!3{>A| z70wzj&w4Os_IpMs&+g^1M<3y>?|3JhHjfx=7!apgW`7&Jp`*%Nmf|-=JpE&^!Jm#5 z$mCKQAjZ1*_v$&amUnlw53HKh@`zhQHm)>-d2@6rGHl_jS8wBW-+u;|ykQ4#c*AKd zj!Kg%6NCoUfXFz*{$$1s)`xSs?FPp7Pe3(!g~F6T%UyRK;n^pSGkn>I5G@iU6osDo zx==by&3*0GTrvhI3exU7SdBCd#6}oz9>Cj%#MO>nPaNZ^dyjJ6AMQbeGJnw`XPvu| zi?$Egw0(hXr*GiYvo^44%b3j@2F%Y77>-+-L7*{s-c2KuNypOCgd;~L963DU;QnLm z-*c2h`;W6{-wB@ByTXA-4>8$4O{H;w=Cqc@w{1+pTDFL^okUbq%IVlv@@B}(QCJf| zC0cmAuel-TRPBZWArLh3=nc=X@&m7Cv^YkirinQOnn6cLM;C>ragkeg zq~kVio#$)beGXsq?w51q@PwOhc$%Ac?&ixkKg-cQD;(Q1VR-(C;l@;ND6O9%pASB` z4Yi98_zKy0{ECR%yJ<;^c{R(*W~!oLQYG#ZqC~ucrK6$f1E(`iMJ=dcB5Yhpc;v{z z=Xw0W2XY_Gw$90|mh$_Wz_!_~zG!`N!yFw;95{RsfHStubLu&B?Am*rQJ3o1=3un| zOzj%21)&*XRC6Z^rKBUI1V&CaRY_|+9>tB;vO7JgD>4tAkdR1tvGjsl-!kbOcTdM(UnNI6j?bmVfxrAkw`eTWw2$yaC6Ieqdv4grjaNR&gO42M;IUP7 z5C|Y-IqhYO zJn`sJWMkndN{p5iTQfh2=8W6DGzWf9GihSRjM6{O%!C|btddATo55-?Q+Cy93XYW~ zusWTx|KJj5y{s~6I*`Ug*}cT&(B8RLGGEQs5R!(-%4q-7hq>>jXKBU_%}|ne2SZ{h zZ%~3-`ZH(GDD_!6$aym!RZZp#u$mvO(I>_v2uJuTm?5x z6=0G$o-j@Ii9-}*EXV-btqp@y7t&fIKgV2Cbs7tgZbc-!Ox5kvsvikuRW30aqLpm< zdCZ3*Jq66L;n z-Nbvp^&7G!<;WA z$MTR(D=~EB?MY15K{Q5Uy4o?neZct_Z3E!RJky zGS|D%oPB=ukq1)C3}Mr$b94v0ybubhk`)fh14xsgS(#nwleM8B6;Fqkiz;a`XEek- z2q7eaGFNl7&pGRxNO^uynqfn`x#dqjau+}TPp@J!F*HSIGepQQD>*Up>~``NTXUG( zx^~VjckE^Vm4}$y(4^?b#@^e|hm*>l$j429+*VNXY#8z8k&`Z0k~t;vtmjUblC|B? zf~FDO3}86dGTJa;yk)@L_9653Z|>9)^V>$uoi=2C>yYvG0iz8~QcA;y))a9u4UL!DQ)@a-nP53L z(!ghGw+!Y4nBwIoZ@+5~fARY?VRA(2X&VQd!8*LWj3mmiLJP+ zco6Nwe;Wv5_wi%0cJGQ1i#2#mJqBH*83q=vSmdgI`!FB*(W_WqSxJ@Wv?!3&f!<0L zL%gObUt|+d?NEyL-+9w6rdv{Z;4XqjM^~tlar@mR;`1f;)S6AQD@j2j>h*xs7`c!d>iS!s;ltna7wrC{ zLku>xrtmbGnvfz}t2W8zjm5P@$ex;>E#oLVly=IirES0V6p$7rR81H`1#QdH003Qz zY}zqq>nRBy-1Vg|0m+A1OZcqi@?w@u$RE};WI0J2h1J-%ac#mra&(Ek2NI8R-uYXY zzhKB@Y8mlW)?60>;2^#KMi8`7u?N;PPG z_JzEDLoN4hT?9KniW*cl#o{Jp&JkmSU#NuBjsa|KOquDjVsOQk6?65w{q-c_B6;Od znGhhmETu~eA~g8D)`3LJZG!cEuj!cSB*mDBjD zHbI!P4(jatIHB0EWGJ@frkzjo)Bo2OId({xf9C>S^tmuOBm`(wX{Rxx$s9-Ga_yXo zN?-1CqZCEs^|z_UkDJAHr3mOxB;Kdq_j0V`<*(dIGfo#e@ciMKw_l4=PPWZXxkVT# zz&x8M-2_ivkj*~}@;`8Fi3c7`YkDrZcpGz@TjFvgh6LlKb0>^7T$~Xe*Vfgnqqe_B zCdCGqtZ@8Aa)KF1%gUkTig38EmCKG4G}TzBblWs6ylIiEKJh3Y`SEL**g`R7dJ=P| zL76feIegO1MvNGky!!J`a_FgLMhi_!i9nfc9o1#?zz2OLL|UPiJfpkY+~0SGkIDt& zeP4#!ZdOzx<0zm~Y@L~%eotoqx&TYvyI5QW8GU$v<#!77(oB?9vRdT^mXbu=lpRpo zz)f9y*JdbmW8tB@4iJxd*(C*07oy*E0wAdGlXR&@IO_@Tb-pol&@&JoLG~aI9vtiWkVGH=s1OZJwn*T`mcp`td%~I~;Zw zn?JWJEP*Dbd?j9^Hq155U$KF!e(@3h)rYP@k4J~8S9E_}csRV6mU7$u5cMZ2uYYz zMsc#HP2a^z2iUAtkx*`Pd&8(9jZ7qZ9b@}F)C0oH4LF3P>{pRg%sWR~DseTLKl5)| znKh>!lnwYDH_2m-y*paLm${iUX2EUoP z-{%2+)xKyVvDh#b()@NPHH8 zXAZ%!S|4PnEWj33>aVQ6=V7rEI3SoCIpT>yUGo>CNHE2wzBuDF?*CK%cwEh z$vjJF_1e!p#{c~fuVH0>!@~J<1S@swh%@s&kj&QLCSi$#t;bcgcJ?ump1JT@c?Cn| zY8L0eq?&}Cyst?794YHEBf{!Z$Ch_2a_)Is0eJGMXE^lS3%R}P@m_B|>tdZ2TQkM# z%x78WbGq;lH-jG8wTBbOj{|VYt4~39#Y~{4hcj=Bo1&d$<=})=&SqsD;Tky;P&x9i z2(!aMFR1MyVgB3^%}PvD zvn$T2mWd9Mj7BYnvmuaB5!;SxTyf|AuKF-aL4DZ->`MQ;tk(!AkHgN!hYC#x)8{6f zdf_Hs@yg^fzIz6p%u4tyB3W<0P$`sIh2aPI{``W2q0QC>I^K8RJ=}ZeodBG6>O5gS zq!~jc$5f>2NgC0iG-j`gy}yVHlR@D;qeX}z<{3KA#s(vUD-Sax{Cc62Y_m$2JQ6Wr zK~+))Yy*Kv+Xm*|wux&$_9*}6UtDd^UbyeXpGDEd!g=3bA_aJXv&wvNGek{-`Cp!^0~zHYIzZ1{lmY?B9KyNA7!$EXi@e zOYOHLLyP`k0DR%kALe5}a3kGl#M~ugBu3h4lBXEVRJCBcELW;X7ip%Nt4Y@0u!2mj z-RntHOMfNh(QiM298ysit8=-KncrxVvW_pn_EYCl?qlGl8eQf06G{0)!3KoTsUR^jMj2i)&!2wm z5&q=|uVuQLG-G5Lp+#)9gJO%!vi%XO&r{HEit5;yG<7@f-zWT zxaz&7;tT?LwRZCO*evLLlzD(^d%VX_G$jHTYm;;B;XJZAYLkL< zAa%jDY@%AbJ9+E&e|~oRJ-3x3G=Dzl4onVI6=|){D{?bAT~hi9RwARtmV;kD&NbIQ z1q3=3CX$v0r-JjEk}!2jTJduN*GN;1Otnh|up|+?|LqSS;a`2zwM>T%^P5J5r4;8f zX-n)6B4{I78RU0p0$o$dz4Kd@30b@CJ*hh0*N)ar9~ggC4r9yhXHPWk_II zVQzciotK{qz=4DNd2*L~#D?oCk6ExWt5|#p^f;9DPJS^PN+_!mZ@cRb0M0viBd4CT z$YlRCg$J7;=JTqs=e$gx!kq{v(5`JMjT10r2 zOi4wzOCg&`qd~*M8y5KDFFwRaf8x57=!kJzM$n0&l$A7jNq+jOkpe1H)QG^_uHVhk z+fOiBY;$@*%>J*DU_QNa9ja=t=v1yyD5c$cWmEG&OYfO8zZ(P&CU|L9m+WbC9wVc| z>NzA$yXmtB;MM5D6@d+mnq15!T;0^E2aokRjw++QOQjs8ehw$2O)h46Cott30@b%~lMcd<^9xIL6GaS?OAwZzv#L-o5yLvax>7l%@@k&{-dHZUaturxM z%}Qx-RdGDAv{^6(j+1*8N8;DXXrkgVG9g;ENw3r<37>hzyQ~!aS!-qHv!W|)A9#%& z?~vTuA)9gbJyiYL%V_3kry_bw?p8ZL0>MmKV0`+3hp&H*ryoCL=0ULLNsHuG=?t|5 z!Zam;N;7TrdSd*y-+O?6`&~CO-5OXpWk{GNWD4}c*uiC(=XQixyw_bk@N1uOzArQ^k zGOHJu`M#d6$OvWj0<%y@W=;~;MrJ&-XCIF|_9y^vf9sjFB21>SN4&bQJJFV1#^xjU zY}~o{kqMNjd4j@>0J`965%L^@?LzEuva-d+8aT%^iW~2+El)WqogXc;)8+xbVCUES@!@TaH;kGWpph0S}Z|3lTxO6QVjm zPJPyOUd5ly-OKitoqLoZ4I&?OmA&up6x38i6Nn-VMuE|57x>J-d5E9?$rN{!2xdWO z5XQV%7Ky8_eTvm-Bv>)8H0Tm?N<^euqHLS7#KY5z(#)Qd`W>k{ImB$bI1#NBq?RFh zQ?6OZzVtGR<;RySxIJ6nubmNP9d}a2TR0MN&ctIX>Sr>~jEa;sTUp6!QW~mus3D>l zv)7||IxNn~%EGED%^)z{DBOJQ?#g5`Gf7q%g@#r}#3Vcr{5=A{|DW#Ta*S;tr%}7ul$)Rm#Lb$lu1jwZw{Pt0d^9Y z>ANsjCK)KDGI^+rbZzZ%FCNnN?rTM z)h10z+Zpn)&fVnTI_rz9r0iMM=NHIG*S#bnsg8CoU~h3WDp(l_J1;839Rr?x;2;m& z{T#`UH$_pT8$b+(MVj)!1U~&6ck_wAb2H(x5%ZgeOrKxn_=6`n{QQIyC~*)H7v*hb zsIYS`PNdgY$=vFDxiV>5DTsQe*Q)=-m9!zYye`W4u{vi?Hi4}{atK8$OpkP&@->UR z?uxSjxc8n%*|TR4vs-PA%<6#kkcuC(9?I!$y3Xg>8~NWGZ@P)2FJ|>J9RL6z07*na zR2+m>xa87PX!e@mNVJ}1HtBGJ49U%KfT zp1$jlRjzY1q{Sfwta1G|6))idOP;xWhJfrv7gy$=w`on})%TKGna;Ri(L`Wp)1~4* zQacv&L@G$`vf=$4Gb)KCdbvhHMnq=Ws)%$9edO4g*uTCLx7t)|n9LOMri%i@g#pjs ze4IP)I$)307@B~xra|#Y$N%Ry@8LK9(Ji#E8M0yPh@~e_@Q(MqjKBTC%h+-$YzY~CYW<-ROZ?%a7edUtf#_Pcw0Czx$zpCHrf6V;m$KH4M zz1(&8y#T!N&1Z1R74xi~m|CKkB!JPXnq?-xCetWB^?JpzdlP(+xcj$gcD1C`K9iPk z!J2&F!!e-4nZ!OjynH$&~( z@Vl>9zqn) z-T+iK(K@r}g+kK9)UIbUhlVbn937o%kB{ba2AWUU7^JdaVC&9$_C7no@4ek6ca%> zzW+~`Gk3ud_uPIbU;ECt86O*?ML$qXS^K^Cz;x$4kPQn%NjYR4?$pssy)g(u>207x zhj+gF56H0W*tUF-3G4t(qrUDw6Heda%;htJ{s>JFqpV# z@!|WZ7QcyImYFib9O77rn;EYPcoo-Vq&*|!V7x5ya8De|IHrbJtST9#FxG^E;>dMV z+cRQQrXdRgY11iFs1}som@=}Ewo+!*gOOlF?~}PC%%h3aY~uTHNQJ+^>}&_}hGF!{ z31%NRgOisXBwvz81oqvp-o?Lt;vSkO4KOg+fKu!=&SP5{Blopw9cwuKMGMgVJTnGc z9C_p{UV6cyT=0gYIQ)z`9C*wu_7xp=K0CqW+BOrT1^LX3ykYS!F-m(=Rr(X*7!BWs z$SC8&)44Gf64CkdUKxqZzc-Ot8E--=Q4jmJwmI_UbNPdJpG4j;{O6B;z^||RH7%Mn z@;F1>58b_m;+@9@!k1_M z{wsI!%g@|L|MCG^Lk(QvLPmLKgAE37!;X6&*o*g#Fw`YX(#9BQ+7<`&wYcz{Bf0RL zBiXt01Rh(zht(^e;r?5<^2~#~dH%^US_e1iAGWk+=J-rwOr%b?8npFOCpmqKD&*ZZn}|k&N!Q+jys5>UpkL<*KVQz@czJg3m+0yL*&dx zL{TJ4Wf&F;X9M0<=}Um%8jb05f#k*nbzPD=8$?j+q7Wr9B=I%03&+@#6ZmZB=!W;Rtgz<>l5j{P@BP~h5iCz)Z zyB3Y1CT_^n_jDP@eZ?GtjU{D93aNwC)1C9`!t9D%Er|>*-Ml zZ(UN4rb~LNYgrJA%bW-qh$^KwxB>=_YO?&ojDF5MV?M=4+uVKs z^W1yyHXgctBahs@n~^*B;enx3`)T%NF?NQ+SNo%6E>*?xGDjE_st6btY{+68R3}IH zYy-KAOc`Tnk2{7>XmRd&hXJtu@h5oT_SN#XOv?Rsr*=r!e>&!MZ6>|1o;JE?L-pU# z`z1|a61e);zu_hOVq5Zf<=_-vlxI*y5LZOXkRZ1?n^&}7*~3px6PIh=FGTuwZ34l`yB#qTN5 zNZ1Zm%4ptk-E)|Zr$JCJoQ$gLIP!sv!IKC0?G=xZ+l){D&3QcX@bhfDaTk4ONa7t) zJ2Z_W-e3xoq*@3%F-D5PtHD|pf0jt~Y5@}$4kGblOs(O-^B8l1XA%@X=8AGQP z7IkhlEup+KmdJz{WTs5pCf+I!grGTtv4RkN1^W^8GX^jw$Wa-OR~5C?wulVJiz=t; zPxMyhVhk07w6)+$Pd=;3&XprP^~g?+J8BkR`NADs_4x-Vr~)g~T(_*tI3 z{W|FZVg>I7el&{9%E=5i9@uARp$kd-7lXK&B8+dH} z96Wq@-nrTF=R*M81Qr=4p zNMj)5^kuU-ec5ba8TUT;9QQx4ojX=+=IKXwGji()uFo@YY#-S`j>(BNjf|A_@KL?7 zRJmw9K@R!KCSS_vSSSp*$2*+;nS&$wTzliS0Q514D@z<@*E+7R>H7IzfC3VgCqdyo zb))^gENy&%e#YA4{O|w%l#`a7$Wg~1$kMatvGP|NVIW60^o5OsK1xS*kw(dc!DJp& zgc1sI*QxPP7))m3?n{O1S#BvNN+vc>z~&OWC}Z})104Uyi#Y1c`TX9w3px1U1CoBX zDVV^!2G+L7Jmf0bJe0N!g}i{9S8ZU=qZ7=2@eCyMQeax5`)6VZWkyDJwB?sydx&gS zPX9rzDqzb|B^K5}7Z~UX<#+oE9LSDnE3|C!INEp&ne2dDzHA=Lm(An7m!810TlR7DEzfY* z>McBS-*)z{AI0zS*abO*b6a3-jHN=5ODsEzk2R2uM@qGdN^GGsS}^N`eqMamA^`4M zeJ6L`b8oeli}5MzSdZz}dL2+igi^neLD=5JejFl#tSY@`RHsQ*&e7e9* zY%k_>Rqsq%wJ~icxXi*CRoPI8U7-XG1CL=T@;_o5iA0z(R()2bywwHcqX4Q|PEa+g zO6FZLN$0|MfJpXKRrDsf{D&mupzR~Vs|>@5;l2#$0&8dt>Xx4vx&n>O#|p8K}2`o_&XdgnH_t{e%9 z_lYg~1~c-^ka-WzQ|P8!VdLHjZA$tcZw#Gh+AMwJ!5n$~K>+;x7yrx1j$I4@p0R33 z)48bqp4#Ky|G!`k!|C*?^r*PiP((Tp-+4c`+;B4&UwjE?oqI5g&Y#J%o5tu{(2qty zMuee@PW9&qwdER?vMI>HSZwAg_Y_RrKaRmLV@Zp}Cm+Z$A6>xmAc zbSm#MIv5&Cu*L>Ucx?xC^iBw6-+$LuHr%?K*1}dbfT=CW8cabf5ei^4i*-S5i!j`R zcQRVSM2sRG5@`%E?@Lu~5~8}tRF|zsBvu+tOI4B*X~RVZBi<2Z99~h5oY%R~i_&dX zZ@O$B>Y~<#uV_lXBkr9^?OsYZ$_P_oqTi`~QyYyk7q4xZ$}KJ^PVcAb;@EkI?9i3S z)GWNyYRw}d5mlqrBNZcby~i7iv7W}^O;+B#iFdw#8AF3jjIm_CSqY3dm(U=`(Fy{} z+wdbgo2Lxwbfx>D-2dQ3GdOtB3|{-{B|N`%oYfC*<$-&*^589-d4Am(er5wdBdg+t zEVx3<7FJ4{n1JHTiIQf+a{jB20-!TF$n!TkJ7YheK~O0!FHqYDc0xm%1YgF&eU zZqn1?vCy8`|fyNq7Ls10PyS)%i zknX1XAh~|iif7pORGYztnpBBsyGW6RDG6Suv>3IxWGhZX3=WH#&*H`|jS;ClJJGl$ z5TLq7bgxHbqTUtMmZ6IwARWz#5>*frf}+w~FcCMZeMapzDWFVjATc`_!dQ&VtHy&^ z9dDUh6(A{1rS^vy;8nGsGO>81Oe?YZ=4-2W!?&80;mJf= z@3Ez)e{LVotl7;&kL=*AQy0jb>Bv>aB12HsEzOEo)Q%E|Y*PctN8tiy_0YU7b0B(>`-S-}JzENj~nGvAD(IM;yReFFBN@%MarC zBWKIo3!+~*GO4ghFZ`QRI74ndnLyH%$fG+}zRHW_vj)b-+dTNdbC`uT*h!o$(3)ga z22j}=LqB|Gqr^qkB?JwWCNLqZ3pb2pd^XxsObnD$X6|$m>OLN^`zXVx;(UlIr0Udh zyygC=`eaN*M@MJSVz4+@QZNa4EG>-5rG=7?cfbVJH-Z}`Hw+)xM{}^r*p5lS;w)rEG-CzC zQW|_iXs6>SA8GUA51q)+P{0m9_|N|Wh;|%k%W7y+)Jo;lk;-%cBYkFy%2P)v^@e)g zmtMC7Nj*rD=eOw$vAz+sS#M(Q%=%$M3#7QqdylgYOUBw& zTiJZ$4*HK8h)5yo_)ghRIN@waE9pvt?(UG-j*6b+zLdmvjw;=t6BMI#>E~)Adfx84|wR$J7BqSV*QnQqNU&e<|@E9ziP-w5Nt|V+^IW zdK5!5eb5Gj+WGm-Q>$^UxYrZ@D`lj;xDk1h$64dSvv%0`J3ZuhGz zf5F7Qy;y6w_>!Z@3QsW^#Hr>9)i@HhVtWWoz>LiMxGf2N6y{vj8lE6Hh#5Ht{ zYhwQ}RE#D-BTzet#(<=`U;+XmB9n+_WZXQ&2-kG}G>#*xDbh~pj;R*Ayj!a|dhg>F zc@3gdwKcf-4N*5p+R*^Gc(|Z)XnKXXcunO6QbyJ70!}Ip3Zhb#Q5hEU&5^N6|FRSX zJAJO2i}+id1$yYtbr0mFqqM<3krgG)c`Y{mdJn7b+6ow9CX+%>iBTqY*^-%@hV_Kf zrWSO^bDSH166ZUiv$=()1sgK$-+Ikc{QbvnVQ<6JIAS2sVn<%XpK&z@b8^<|7gF-}RFg7MgmR3N3iq0UI+SS8mjJ#O;T{E$3Ye=!hz z?xn?d+LXdj?!D_?e)WG>1Msp7j^Lh>CRas+~sr zr{z3V)q=>d;tpkqX$E3iM@LMv5Er#e#(@CAHJ6EwS71cdco-9shFf`Fzb}?CwF$G8 zeg;*@2y?5{O6QWL?2~N*ItNr^mhQ&YaWIjwR|Z`m)CIO-*Lj|2v?*D2$7Xp@CoEkN zskt+xw5W`*a$apOrj5#XO@2WM-h^7%w_NiKSG?zD#ySP9d3{w%htw|9(e{LCw>`Oo zOWv{+fIWNm@Uts_20$N8Oru$O=4wCtJ5tnAM=4zhWeUem{;oHu$CQrbnpYKQG-FEs zAN<=70cf@?FMsV3u(=Eqsbxxq2(3VDm4Ysm_9OF#;j?FO_xCsQm;diZihX4uLQ@FG zFN9%qPh!eUcC?*EALFaGG0_ewO^#)9MN&oznE+Y0=-xl7@_p5tDK7Q z;k)Ji8p-SBUAiqGmUk65eH?S+ajNWzt;`gjz7tzKc-vM+_U;qfYtUu50jLSFfSdzE z(LhR+C(80RCa4}^17?fsfA<(){_rh~4MP9o0c^)%%aB^tWi|*I?=X3oudHn_*0OK? z1jk)8k5f+#sS1Aj-#_N@C)P6rAs(jF-P8KIPJin>_#XGvpS9@?y&6r=rK(SgRN_&L z1EW9_Z~A~Ht$dJMZo7#UHwE48qKl8_;8)CIe0v*{S1JEAQ+Rxb4T2{at3%+}z*$4A z`tBA!^@(d48*78ju~wrM!7zj&_4J6^)BUOcKMr9iD>gFuY)PY;kr#o{#lhCaD3T)B zT`C3;U#T7%HDIb_)&;NV!ARUnve43ixS0A-rL`D%V{VPi#|2r%zEmouX3g(Xy=?Uk z4gXIW77nyvSo&RQwE~&E=*msULm_YsE)x~1dd$RyP13&ek`T*Q-)~dIq;rrm!ITNO zM1l25=6GQ=(ax0Et29WgE9p6qxrzaKf-&6SXtpey@7c>Ow?2dJK28RNVCL7!*K>x7 z%NKYi@mRdq(iOgIA>Ml3My`0nN_O>?G!7ZSbqFfAlX=Zeq&Y;G*vwN*l;qa%hBqCH z&7eI#$v40L&#@QbUETY3>Y7KLspzxGmvlX=_u2Z*DI-Z4NBtW6Ij1=xJ!rYXg7sN7qq|JFq$Uj?_Q#ct-F{h(ys&O=m9&OV|675Qq>M(jBX|uzlSK zjbUL_l1ruQNnH#kk@`m6n#6E;UFcp6n97I@M19yPK^s#UD>L1X6Mj+~jrXD=SgNh> zi5lgdNK>)9q?-YQ-9q{(YEVdOBzL4XAHp@~y_9+t)kWLVZ1;)u*KvrdmG{xe8V#S4 zUNRydQ>l|c#oY9IV)X4&haz*UuB*W|CUQ<~JW2{KQ4iCAIbR_%tGls{kqxTdZxR0##WF<84 zk&MGWF0nfaP348BY2DWYV6yff$v}Y&OZV$Z+43d-+U;YwV@Do%yga@+l(<7@5sb;SmqL()egIT zXPi0A%5Of+Uw&={osI`93*S|eLCLeE#K)da9ZE-mH)ZL4EH(fDAOJ~3K~&g1EJL#5 z#-~Hfg9bg3Kz@iR_f#d&_=~RC3=RL*MWl;3k*YCQt{kZpkF|tUQd%mbrAm4r+9p!3 zQ)+k7`RO5nqv10eek(>7Rfxn892tNbi{%?srHkl6+qcy>RY7OfLXMsz9ZMOT7{ijd zo5TE4F+w$BCvh|3+k&wp#-%7j5@T|jJwBouW4e%|_CJlHrl?S%0a|k!Y`bnZ_lmbC zbX9XUsCrYw_a2PbXbthwn1WCQDC34}H}Ito-@;^W=sT<*UwUlmLfTMa-jSSyS-Z>% zXf;ecImyv)p2y41IShcSe)DT?U$KJpsB0YQx%y#x{O-jY^zSJuk4b)f?f+gJtQ)Ch z^3(3RPwg5%|K(3vdwq!;->IWE-uV+0OOm4N%nZg@jYthq=(021$I93%m`~&K1bugEXFuE2xTrx zqNG(faZ1?Hiy@0M9qc%ULe!>AJTkiV9=eRW0lJH=$@|1W8`MJ0)tlypO_@&2es8Ki z#?6>&Ly$g2wJEV9xD@py>RCiNv0Y)F!epXbnM#7HOS~&-lD=Qt$SP>BOjpN38HpGA zh~BhR7R+cWZo1>!77Z8piY1 z_Z?5GF9_Hx{^2V?s98K6IH>>KtJ{8>d+SHf+Qz+J_(I$)TpyPoWim}H{Xjq|d!C=< zD_;)q>wsCqyz+fZDL0h3g6_PhUIUr}v05*NC=>kbWp2PZ8s0GDv>|T%yT`cvFK(ig zaOV(yTJ^OXcuxIFizTB9m|J<?cNjuyQR(?%B@vEn`Amp{z<$0g6;aSKi3f zsFid5wHx@Gx8B5L!!vYfA9P&U2WC9J5i-X)kgAo5Ajl1N!a)urnI*j^{=FR$xYFQiB5Iole5X2>?1W&LCf^Rr+5 zH|ri=1;8ucaxC*NIDpArlM)J@#6}>&L|I7Tm=&^dE3=eF@{1InR?9N;v|+CP;-mcS zX9e0>g5}IPJZ%hvpuuiajIsu;XB&=!2UkCdncWIWdI(zpqOq7j^wFcEi_caB8V#eW z3MC#2>uhE4Q^{u%WMhK2C=k7sxCj>)pVM(ym^(cqD1C3V3t|v!%;I<6_VjFRop2mNJ z^9@nSsaR(9KNDwhSFT0Fy4bhrPoII@U^v(!r2e$%SvvjmM1_cxQOsdrrbg z4b>~Y^d%tpNYXXznYyN_UF!uT>KY3$g=g6M$@Hb^|Mhd}3#aRZD<`2nDSwyr;~CvI z#^?U>n*hw2(c+ySJPE(H#CKe^0A%oNTNY6k&Kd79r3*CSO|`SK-!gpKFu%HDEnoWU zJJ5WtLD)7ay`fr)$(|n-yryKb3@Xv1kM7~#yLK>ic!N$JybhUElPfV2AD~TCHiPIf ziMHQ>s5IeIq_2c{Bf6nl$lgn#_hhl8Tl8bBN;o0IWnv(jx@8NqFzUeL!l)&ZC zwSaD{8iAE5sZGR7c%ULBNgi#)KpdGFVZNe=CyB%9O5vCw549~tcX+Bgrl`WYiq@2= zI~_Yg6p5`1MJ}RJT0t$*n4YRj5|x~yHzYTT^`QhzX$_|IG&(Mngvl(Or%Qgj>RA9X z6CztZdGO2tC2iV-AhjsLWe{$?b^~90%MG**3@#4d98=2NiMpjnI<_tg!qpf<*|3b? zGr^e`FXE-=hny!r`tFaoLu@C#S=;n$o*w6Y@=Px#qxV~#v;8rW+89i^K5b_utT(jV z#t_PNT=mPVx#`AR0eIzWj%LZ54rJfM`(l`Sw6aTD$iSgxvH1Whm7qL}Nj>gksho z`uM2~4rjCrM=5bBkyu5_N8*zHRw3t_fT^UBW%Rvhh%5j6Zoc-FpjO!oGVg-hQ`Lqp z{O7=QXjls++`n=obV__8oxKs&CH2S%TF?!9nhY3Z0dyG`eUzlCju;;T&Eg&vK@VE@ zIT}q(6=Prs48jyPs1$14wN#!YL3lCvN!u=~IWjhJH9PrR+{X^893eID3C45lyN8D*;S6#$bO?#Jxh($s^Zz| zdz^J~JiL5&tg={|%08rYn2ZBdTP0fq8T(d`v1;`uxm*&m68ivBd`9MTXe-lfaQ*d< z@P$|2#K-^)9yy4abXX_C(N4HAUTeM=O3}mCPu96n+EDs?I@puGlpgnF1g?4Ks=N5XfBy)8Q_o(+ zS#MsJqu|4Nx zgP|$tm|#eLc+Ga6T(OhBQ~N4}V0;&Grjk1I0Ztp$-=QLKVIFF@Rdp^hTpzq9mCaJ$ zXQCG<26K5IjDRY^O)|PQ-8vc;vt%BEV)&W)yBer+{9BNb_pGum_1J0RsRe6uJFBn5U zBV*m_9X$Hzj?hNo$W6$IS++d0iGk)!Tz>;wcIr{~J=bNON$C0M7zwp&das@C z=K4$12YW%K^yR%EQTj|tP<@_!Y&~E3aU7UIn9#>`S(A5knex@{_u7KxPlB9s`zz$h|I;{3eR0DHjy3M5<{lc zuAxF5O5Bz}sIkbm8a$=1PNRI4Fm)hoH?eB$h#EE{b4-y62~zW>N>AtwrXZ*l5E+RP zT|G5!lP(-zn^98{u{9=ahmdxRKAWgkF+!Kb<0J-XwG+iOlZDuga$#t)$PpuZM01Kt zbWG%(;hTMISD8{va@s{5af&t*0vc!&TpZoX~+Pp-%*FEBGwa`cqmM(fxm(=!=(yzWF?vzfDrhZRU1#OMy_4_pvny`t`9+q?Gip`SP z+Cry{FTehGPxFQM-okjFVQA@4a1DD$R))f4>U_Z3=+f6A11k5il(3x`EocsBeCW^4 zqSXq>`%|C#3}X}HH0Z;-0#lCRXm<5|Iz|xH%-Zktne?7|Tl&9EZ`>cZs&l1!gS~XE zULT-84(J1R?b^l1KK{o5WO>eqKYJ#9eU|oUfl2sX8lh>^a~4cV2+@};;IWw7q+?*X zLAJEPw?1$OKmYMsz+g1(h9HorGe%gDt^iCNeJX9qrw1d{KtP$m0cWyo{wzj0ZpIXzwb(2|_58 zDY(iGBWS6Vady5^;bJ~qVf1P+4fY*}M#m!Gl142%ITzz}L`92pmx$Fk4uUviAYv+d zleijX;8;UrUe1Qww(->Zo#DPbJapSlo4Dc~H!|)^h7KLT398K69*>W?R*Vm&chvxI z@Kvr`6s?BDW0Mbz^Xg9=&l$@@Ci`!H{Tp0=+bs+*glkqCOzYY~FHq1!%uH(o-5*f! zNU`+x=x9$1Z~DUNI97U39nI7k&eXP>7)l<0;t7sE>~NNyd@=_gJjBlN3GVyxCi)H! zetA!j#DU&Z39KRH0yr||kpZw9Y40fc8qMo0P1KRn33 zWoTb{=`V(G8DDIJ=QL!d{qxN?wCLD1unfPMkGC zBF==xnT0kpd1i8?VC>Ned=najc~}hikj2h}Xshe3#o*8^c&|YS+ znE~e++ct^G49#YSD}rFiw75H__agA&nlZ}I!#CrNB*ChXBJp0K9ivD`30IUnLq%IQ z%$E%lU!fp`DJc>(rV?z{FtKTpS%(e=kBc$fc>UA-?FVjPBJ&I#H5fJm`Y`8ClCeXg zb_oglxTsW(Gx&zVWH7#Bltt$sz~x_gDXmtAF=*V6M@_tNb54b`;zPo_e zbn7wwzt{b}p6_)o7Fnn>hx!Yr<50bhIsw$*kpWpg6W^K{4bXr3|31r>t-J4r);zlJnKKuHf1$*Www&n+}k% z?!Mh@zI_+{Ga4ZxSN2C(E%lKYL*tJ(F$z{~3~ChAU9O5&QXSsLBt=ySewvp?KgyyhdPGxxYz>{z{< z@n1?HwqIHph;Z&R-r`hOV5Xvla|MMs~GMd zZ96rUs>it$i8cVY)wAlJkjd@tTQ~F9Z@-Zd4}(VxQo0ZU8)|S_JT`bWO%;V}dZBx0^U{$uP$pJr98Y`Omei zyK6hyK@E%*w{>PJ#|B~_Fv(b$WFk_JPYC0UOd~*QAxMSV(MU>_R5*$x*{fj!LkxRs zlJPZ3u%Cr|!qI4Ey!^Gta{BTGtX#2?&RCngkum9D{*g0y-y4r*&&VW)oIHc2r_SMt z$M!N=mSi2zC6^w{#qT(dB_|!kyFPd#FFk)Tha5VGM<3nJo(-d9gE@Owk8{GC=keLk zpU4j%MM)860u$L2TPL#`gR6aL|#1T=t2xdFqKBJbBggEI98#-u>R=dE$ZR867Ri z`ZAeo868g*wy$I2jSz$vcexR@Pv=IMM3??*q!7EQ=Ev)t3ksFCLO@$2+{)JNJsO!5 zLK?u%$(U#tJioWiPrkQ?JbkG@LN9fI&};2yGlqsPpBx>X zmNWHYAnD(psh#QdvMJYn2jeCo>%)3Oo05kgdX(c&K7r$xEai|RW;13p?*9JM3?9-9 z3mv*=qVRFyS0U=*O-2aDfk>thFVZ-m$@pl8d%n4uqb{7oym>SD_Lo;PI@%$h8Mbp; zopF+mD;J3$?BfEr(y!os=q`_0#ixjB6Lt8&sH*TN>36D^Bg{w$-z%ZnpoZDPF*)Km z=aM6MZo_VV^38j(dpfko9PPrh@Yn;moaU$zn9_peVlyCe9XR*&5!TooZmZ? zHFs}j-RkF<94k5S=wVJjbpb1H*udV2Hbtl8{eQTexeNPQ^_z{Dp)9DD31O+ap`IPB zWfZ+VRK#!Nc=@OzDdP`0Vw7QvS}8PSY*2SJk~!L56pbcA0qZL7R4b!BTJqrUwleNZ z2IjT!g{0_^zBsSyRZywZ)uK6cw5*GD;%#hY>|Hm;Q5VhPi+}fW@`h#Wv(NF?x4e~I zyLZJ6fOVTj9Vqky4(WQWujg*+>}D+VxMzx&Cw*!9;^}_ZUr=Wp)7=;EEdyrM{Ij3< z=pV6h(*^)O@Sc-7@%8iAdB+%KpB4R8pe~^fu@Pyl+0wcO##aGpYV|j5&+wvtCgvA> z^RHI(rN6q39lIvU<~D-c*@YdUF(568>qx&xBQ>KpKy4_fvD8$^1(mK6^(d}k16{kU zHU7dQ`$8jwd?tZzq*aBoA%Pc<2H222Qseu_ByWq`FbYD+I;?#H*@cgwlXm%Qp24mo8O zle-HsouwNPD|8amHX;rcRa?|}tE!BQdzb2@-aMfnjfnPg-RqqAM8HJ%aYfC+RWC06 z(qsD!%|#7beOVL^8c~h(19_)r@Haw3YWVj)7}(1U+(6F6_DN=pdH(#f=h8P2oC+U) z|ND93sVA9Qh-3e2GCk^`Azi1_sX_H;((ATHAR)q$p{I}(WGt&NZ|A`w&VT>-+LnnXADIEunCc;q0@ZXV-? zpFDwUS?J3G%JDw#e~E5O(>?Lt_>iz!iCKssWf19Jm8h2|-W?+Zt;{2hI{}Hpb-_i_ zwV#7vBfvS@lb(0{!*bfAj{o=JtN8E-Ph#oIj^JG%I*l{la2TB(j@P_(34M9SHUDxy zn4~S4aK4ScuC(8eat`n05Mg|x4(cV#T(I=Pj)=!?o z*m#GZ|8xxtjy#A3C(ohS(qW(TIAd6L);uo!=u!rb?dQH*w($64JDIm=2;V7Vyh_Yv ztBgTh@J{R^>II9aP~GtAMs^hgGAW&i%}qUfN<%Ryj&QLnbHBQFqcPq`_q27E+}f#V zAxYiPwI+l%DkHMkRDdFbqT^|=nc#z8Ue1Xph4A`sfA8D;@;ASxMR$_Z`ucq#WGc9MIbw0D^ z4bYm~$BKV`0()SCylKgc5MNL<11wd2T4N*(1pQa&&xjHp(jI!SVbfpMvSh=V^vT3{ z5PfC}<5V~tU`S*js>*0B@u=ST1Y%1oRg8ofnzLa1MLal`(014%Ed7Y_8EQ;1j6XNY ziNAjcZ~TK(*!biQwrw8aoR=KN-FI&0p4D4u4fZp1aEoQf&1LuI5!O7li=9u7@~U^9 zz$@Q;EW4iD$HTwdNB~hW`n0z@8_T(OJzxoND-!cjZ=1lAw& zl$u>g`yjMn0IMlCqI#wYwSsD+3nRurVS;PkT6VA4%ej{==Hs6`7p&o-hu822m%fYf zefzr5iEB17CmzVA$uZVkxrNrDO>qYU4I83GjS^d!$smnnSR$lF z_Cd(P_eolSw9npztikFDP_;$u9^ujW!bpf(zF3Lg*owI0kG5~*mk;U@M&4tEScRY> z@tW$n;9UaxGIHa&;n(ZQz2n25KAZJh#`xV2ALhYdZRNQgBaH5CbLTCam~+Swn|F<~ z>Dpb4^|#sZ#4c|9?UQu+45lv!<9Y1PEwr&LKlMuYK)Btbc5MOsyK%X{o!L zd#}B&d*!zdQ7`6Df41JH9$ma*(fs*-&$G{VJzRg;bm#W>g8I3x^LanM02uFa&mbmu zj1=Q6U9yzhZ@-u}k7uV(F)+c@CGGq8nl;yP1Moi$NiJb~cKJpA8i`>@d} z#fl}6L1_~8B2iUhu2@x1(uh!XV?q_>ng)%jF;9N$GfGija*#Or-%5LF#<9?y$`I^x zLow2!+*2?(vq7F)#wWyOJR_qhJ*5c=!26xUw=%Gn_Lgzns3SkLg&k}Jo!>(-)?sp2 zs5{-7kx^!rG7kplybSh^&ek^lO@m@P<$?eJAOJ~3K~y`ag>9D6)7;=SpQg@c#Yw{e5j8@iQ^Y$$~{p2&e z;Z1KKYi2B2I*Xfbe}>U#+w{$Dkac`0AwaEIhN=`P0VNAFm_tl}vXOxV=;`EHHQ1E_vMA9nxqDT^Y5{6-ukuy3|Cj4iTSo9d|mW2&=ww2L0m{SsijI6d{)f_^jFT>Ak z(P$d1^OSiA0Xjd$z(02;1m;;6k{fyBB`iI-b*&ACP;aX-46!@J-On+d0g?;~LIF81 zOho1(Y#yZM#us8yRVos+??OA#J_8Z`x`;9>q-$hy6-lWYZIV9dJByKmi8bSV_@B?_ zf(wrX;QK%P7MK6|7XTRWeLx%EB<49z*IRn@LLj}EL9fFw_4)es^nKZkBo1XduC%|G z)?fHS&xLa#+jB1{W?g}!jmdJ1E4Y8{Lo^!$ocH2$IB@O|haNkFo4>xEau(zR8Qz(= zU?X8^WT`}qs;Xd(`t<`kDNV@wh6}`m0VfbU)CDr}11waVwmiYDr(4Md661q=(kH~> zOjQ6p23IN4&;Sb=g$kA{;|YED5+UrxE$#7S7_uTHRw6UlrVT2fH4;gyxp*PB25U8D zLh{E1YQ{K6aIqUq$A`pHCM@XOiFDV1J!9~h4T-NrLT9M7H(?`NZpoUqa`h_r%^>T` zF)f2NSu`t|A{b?T!*&y>*t0Sp7=7@lNn4`J7-in=Zu4}Ew! z0C%sxhj+g7QYI(b4AT^OR&?jNq5JRst-<{5%RNCny- z6AFL#V`u;kEJ1piMiYw3m_L8j?JHS+(&-#^?2#OL_yLr&;I9981~SwhmDif+P= z+30DIScydEhPdwIzy;&6sdB=~4KYNB)Aw|rYXj{m@A7~tO2|X*l;^hZn25%) zm`rx8s$@mb3ZZ|251A^7l%=a)kClF@j;?iSfEYUwgScvAmAqF-`**pvlTrE4cL1cL88? z!{t}Jl;ba%%ifhE6gikY>|}K&gg0wVWb3Ld=P}O*R1#6&CjoL@sS%Bd32KIVRo8xBrVZlAYpp8VqWqs zE(xa7e6jl7=~$(i={5X3W>ZTRd_)3jq)ZrI%-!m!F$_~xUeuo$r=gmI1fQjS)WcP6 zrc5^ye!^hFw^bW6<5&tK=^C?|3#E&OBl?n!o5n{05rgBDnMM^ke5+}Pt${SceB>5J zpWH`wbjD}D@luXDDr8^#`ZvGHH~;xtKwu{I^+AvSdmX(NfBHRB1o<@Arh6tmy1YES zUfPSx`P#MpL7-koz0F?jP5H>?Ag1)JTfdH-8+Y=`*S?bezKpZZUdXDoTX^oq5e62w z&?t_X`l^(Pu^xnLnXh24F>w!$@hXK43a>G~iYJhEtQdt&`jMi0 zi|9;WEAKWElqc6R*@Ge~Q-wB6jO0{TYLz(31hvJ1#xz8upMelRfgq;JixoFOsxGG3 zJrg@ZLZ}G0~I|heXdw-w@;`Z#PuTDULnW_l4U` zR7D~SiXJ*s*~R4DY8%o%3wI}aluXsEi7sjzs`rH+2?I1SIIeOP>zE+vHN#g}2N=u9 zt~PeE zU3w5z^r^H$v7q^Lp{i+r;h zVoYRGbbTK{8Zf2{3J?!iBK`3?kd?6(ZJWv~r|CZf*Q|`5V(Y;sf`PEoEi#G1@Nw0m z4m>MWZ4y{cmBmieDynPW=$z_&E0fiM5*%$H>ua;u-_Rot<%K%h ztF!fIr-Mzs2Ba60>N=P8;qw8E+lQy52}}al-h3@{=g#Ex)6Zh|oPJJv(E?Vl-o(xg z`)JK-hMG;D08`Y1;)6ZG>RW6g0TY#@auf+Mc)ib~VewJ28j~!lYN5rAiE8k3RRSMf z_|c)G3mby_HXYlBU z!>p^kE?s$d!+=&yLx1F2#kh6w!;cZ9k)o-r5{u6_3o|qwl?ffFJqDC;6`*{uqEIC(PmUzkeCC2Xpp4IvN7r@~{A7xzJd6-F1CK zMB@>$2>jQLXg29vR4aVfAXl|t0u$^U67E!X&CoGB08^vSin2XV#w`h1da5HhvdBLv1=yFjxE{j%N%}H^J8AHSWX9+=i9fMF~3YNsj{KR5ew; z%VL7pD58MyJ56PvNFoLmN`Dnis?9_ZPIUhQMpZ{ubu6*(QBBn;_Z6+Awj%vJgV!vN z7!QpS#zsrpJ0|(imrmzh?+JlxPd)V{7rg2sHaz|$!-VkH`r_@iW~N)<^th*snJ4FZ z-P`LP!_;@ypO1{U*HOQ@7lWA&)%4;(N6g^gXq!e)X&2_pM+3>Q_|) z*&af+Itbb@+-4Dr=y8Pie&BuFao1e{oOkJQeBvK2W7+Z{rXQaGp?pv5nGY+OR0dQ% zaHQ2_9MCZ{V_9z}S!QY=cT?*F?(txel{4BkHYC-SDOcwdKnx*LBx6 z<=V@9q)>0=DyA%twLWvzezP8Nc4Lh8B&ak2T#ZZD%j`hA@BA3UC1?Y6uIeHjUd--? z(EVY(i499&Z>BefV`=E?2fL*1KjA*$Mb)nM3Q=MFOGKrWnl=$t-%I_9q5<2i%)kR` z^X?BB);?BEFw$yo64d^%6l7#f@9!d?>G7+7dN#lG%Vz-a(#zYq?w!BD^G`j)cxx35 zx97=)KS>Xwo%r9}yfOLo^Z6h~AdUMiUpzkkhqD3KdpGzDh5*1v$q=m&(uVScwVJLH zj&cqt5F;S6jM1Xak?F(S@r}DU<+M{d;rPw0SwGInXRYSJ2VZ92^K-P0YSZdVXZJ!8 zm(J{E-KgzsPc_>Z`P5TU{iz30@oLVGlsd+YLA?&g8e`RWH9mE1o!uL|i=wA;nM0<% z%Zx@)F-5h&cFqwg-V6zcVY^eM>TY~EjPX`o2cfkDP0!d%%*9axW2;faQwY6{o=LSE zl2vtZJwWZuj;)$?(YH1k&A-u;gfRqD$*iTBnVmOL*{sT{tjb`mG=*xb+Tew-b{$ts ztIXhFmx0!UR#0HA0i>?!p52?d`{e$q|zW6iz(l4F{!2bRFx#GI3dH4qp zDg&$#WW6b8+|LiL%=o|%k{>@0PCB1fh;~RJaMQb3Py>`u#uP(-+#q>l=;#NZQI)Q` z?torFR`e(kj8brDYKpIY{Z3Bbat50>9nYF|b~&T(I5ohbaK@x}W)8>0 z6R?74kKG%fGty!PxZYAmpnXv)6<%c0s_jD8OA2Xk*O#SkA0uZ)()iD4ampK4~3rbZ#8W;b% z?N;?KWz|mB7N)D3p}e-sEF+VGESF5aI7?oX{N6vE%UiBI6@aZJ8ReXF*YMCYyV?Ei!?f15?b|iRsF)*aR}31NFo>b&V>>W2 zbJ$A&`oNvF#bA~j7$m@1VX0jR^vr002&uJcVKA%G8cf}_W>wvpp-@j4K(Jbm*?BR7 zC@Xt_>dtKxhH3JL13`W0ZMfruKF&7xid!A1Q#jlcgE_a zg?hN$XmN@M;iR*-rU|FdTm@8QjvKgev^(7fXsycGCU!M8qls8o0S%(6ZrDqi3{5?p z^brM+S!TVMC$~;B+Rpjt-(18MSEyJ1p4+;OtKWJZkN)T(yEW_zsadtfgr30fSbRt} zLuo<)6rz)o=ipf$KVz(r5Gc6cLIuYv6D!+KCj#F@tAiXGX1G7ZezLh zarzl7T{X(ZS8U|Pg9q7m>t4i~Hmy8EWF=W)9FH_bBYRr?SKEkGGprs|GS_NM>CBea z=v!?$+MC%NZNV(7tXqRI+?u})U^vsF1iN)Dow6hvOsM!%25bdF)y{2w=0(G#(iqfl zsox+{g6p)cZEVNZQ99)bp$aGUQ!!_qgyp~;C&F$yTMbFNnw!~v6jj@s9VERb zHD{=-5!jYh8Cccsj9w}_ZEBs(GU`TKa|4@HM=;7vT3?jfATFv&#{eI>GNq^|Y*8;Y zmL(HU%&_95aX$IkOS#~pV*vQ!JwM>*uDP0Lw?3_3)t(<**=Yh2UnYEcifJmLrIAlF zR$eHtB;eQP+;aFAzj-b1!JBX8$=`w+6cF04pXo^F?pupLs~!sY2Oj9ZGH>GgH--I zWp%HIa6kmTv~bV37@<;I-j!{{I;07sIS9QJLAjqBheK7NYAiU*8N0iqD{CJ0GJp+O zjX`FP7KgBR)!4F~fmQ9oiOS+`)C@$eJ=|R&_0ocHT>6!ES(y7@B$VBPL-)_{>PuJh zr+@i+PCET40Pg+nJ-q#$@8HE9FS5uP$8PY)zln> zQAR#Kq(Gnq`lS-=p$xNCYTs#*j$olDIy1u>J_OcTz%C^;ZS%Z_v9(Bv1sJ0*n47)K zqFr5csWlO^RjGv*SHO*04vJ@UMBeb>`ir;*Sd7gA>k3~vlv(N5U?6P0jO|7m?M52w zh6aklARLuZ*DP~T?PyLos|&8o#*Tq-?9xJNO`&F^((S3X`c30kwjXKN9C~0Fo0MbY zvdc|tPr-V⁣7mkTAM&c1_--F$;AEBT=f18eCls6W6iOP0r=AO zU*?_fcn7=p?Pc*$8_FW8^_#zA6M5*H4u&~S@$Uvo6W8-{uG z+b=V{r%P)^TMeMRZmTySQJrtW4r=tD?)$ku!){#l8lB=?7)j8ET4Bz;m>Cs;b&iu@ zE{YOp!=YLODbO%GI~siK6$cs!alV&>j$EIU1U|Z z0UE=HZ6smsCWbCxf!E}>;9{0zI;}ATn|4)2XBI$I+dAzjvCn_j#-;{!=`1rdz+M9( z;K*~c40keq?NjIS>%V>$tzkv@Bfs+z{^;X>3_Z**0;A7jD}RD_XRMGFp9gad2TC+&0S;?PO*T+nE8ZovD-t ztOqh0e9!_doqJZay(BZj>K>oB%xksWZhxvznaq&--V!BD(t?Y*Jzr*eRyC^-^-*ab zCXc`huKGvVCq#s(Y!ym?O!>n8UAv4~FSAUe8vz%xn%xbxYL`Xgr z10m}D0Mcqz3fn3l7OCws)~DvpeFdE!euD1~Hbd0W{_%$qEFt!?cR(j2N&f@pUkbctr?#yQomZ3Wd~ zx@zV(DNOVo}Gpw)O}<$z||&0VHhA%@DJYeu-9nKL6g?sCO3 zf*Oxf<9Td7U9G`WR5l7zzIIeA&63a9NL(WD}+*JKy;aMp2i975>=t#_J%)yM4>!tC2i!$ax&SbEoV72JIlY_a07F_IWB#}rL?k) z3obmCwObbR&VjK1Wkb-k5I4G_lTR(OD5JVZ5knVq5PN=vF4Tbei}v}LYNA)CjgY+H&77)q*R z{>t-H^Co58hs5yY{6)}5|Baw>EL0yVp6v2d80E$qg@x2@ zq3bD2vkO&Ei?NAWZ(_w;R_(uoP+%%b$>ifRh%D!ApFW3=f9z})FX{mB<-h+N?|J{P z@buQF7zgq;$fASZ3!1lNp&~u+-zIy84@{wz!a_8h5O1k`J|DGP?|s2d5o-d3RNfTO z#F%YLZyTX(K~Vxd{j^2_`7reQ$e|AHp)tC}4Bxx^dp!2=qg;B)rF6zRY&v-b=e}+o zySE=;`|bOfTAnd7(ju2q-Pl$_(aNmRE-R$9wU|f5tYaEjtwDf2(vCaxf<5ML8q;>X zp8eciCad04X%3mGxzL*pj%K2ERWd7l#*Sjv|JHbF;!Q(J&wk)|gW84`%1)F^Dn~FJ z(~fiU)~a(z%ppTV*R+SZvccWWu|b+0B3qGpT~4&Nj6@zoZtS7i}=NBHAWLfgj-~A{b`TgHxYHG6b zel0+qSMEl~vKtpNJETA*^gUEgN(Kkv%MCG2XP!~kB=P~mM@t|1LTDQUrchjnMu=gT zx3K!v1(f@;y+5Lu1-g)R5E%>?vvh&SpL&8@ZvHCk*B#4=C!fHw6&>DmJ!>GqipP*~%$|x!_4^0HL~dSzsNfEKlaX5rZ0f7r+>I?Mw}o4Z_aEX6HfyNTz2^ zBN*lkkd;*vocyW*gf-T>ODlzl!Y(rNHE&SDvPF-uU zH=`MtGY9EprCk_WwYu0(l_A$27R;(8m;rT- zE`;}YOgm2jNh)7T6NxQ@LVWt^gEzLlQZ$Uk`IVvJcPhTAoY)!Qr_B03ZNKL_t)ChdBMbqd9BK3Z6Q6h#lWLLT_GnDX~ZCLB!3%FKaVQdhZcj@fx2moylQumBxwUJyc zJp|PSOHTWhroA*D+7HJVR3%{E1u|D&y3UEx@=<}KYMV?a%j_*jNkgyxxDYgXVdN|9r!b!`&&Nvfe-QMBabo;4C}|YLgO(708R0+ zu^!6Xq~*kTizx;%Oz>q>tXs229@(|4hFBpYP3u0KZz1Fgg%qQHc`-DN<@M9qvWD6q zbF%)7)nF#{zZYF{KA--}PjJqbHvrI^EBNd`{g{9K^Pe#LT%RQujFC%0Nl76ESuX5y z2qB@bJy5kCT^id4)SjrUd1hK46|B=3P`@BKm-YsAYe#Y9vX<63o@t(xY*vTY%ocN5 zI&G-k)P=sPz&gS~Z7bS+z|8VnXt#a6WH6UQ39v`}g%r;2jiO!XyzZq;s(n=X_BT-N z1gY-^(4^)a(>C^zFV(K*vT>k#me%m(UPj@TWqonfZcxz@Og%e8HYK^_gB$tKZ=cQT zRmxFq&+eD_$nSofFMi>(KwT@bHHYq2t8j;>PG)v| ztbIfX+xWGEeNt3!13MQOSzjATZ8ypW114r0I1^SAG5}DsBW1#Bk09)pvVDXMtzl*$ z`dHADxq94e>QIk~2d3C?-ZFmw|Gbu8e*amFj|~HG+Z}iCtMC0U-1YUZ1F(3cgJ=zb z$dF|*Zw$wTF(em6;$i^e4go(;s*Dssq~y-0UHk1mmL4iRhJ=HnoXc!VV@YW~E{zcV zSeh{4v{CO7LNUCYtSAxvLpo2JN&W4rH($;F{KG%t)HAlIY<FU@pjFW`WGpyA}prThgd3AcJ;}sM2qxn`) z+{h&KpHd?Avc>du7Og=D8wz@?=tc)LpyCY&N;W)$DLw&B$I9sS%tFbq` zX);n^pRu&hYkFI&NVA$znt!ttllFg9um4pVSJlL_0!2ZsKJFN*UtOu}BO(*( z4X0cn+8IT!Waj%*&@DLs*EaIeKY1P3Ub~smu^|Aybp7?b>mBdlu5W$|fW;$A$of#| zNyr_We(>eR{}uz6&{!9dZ%t*G_VDS4(uL&F=P4-1#)d-Rqsg3Fd!>-fudEwV$Qw!* z<0k|xFu&~TZ>6F54XeJZcVjcgk>niVFaU3O;~V(c@B9H5U-Gjy{e9ot$>+ZCV;=s; z?X-aLbH|WvZFqDv2<26&mmh_&0uI=jT*-C{@ zv>Ov&YHiECjJtMsjB8Vp#?eiA0hd`uDJ4@c%_5)gvia&&y!S(A@UvHJv}HW|) z^7)_e_*Zt5EpE}-GOBLr@5#z=YL)|LdEyu#&3&k7_k63l$VyW&!fC+4-jMG+rD;N` zjjO^1El^v;Qew^**?gH6aF;LZ^HP;*oZzg1)wG=vUdNcK=w@Vv)Zn0w3>X`TyNokH zgl;F{#2LO!dFG8}>G0&XtD#|orh%>#x;{cw%d+VgXXtP5bIj$-dF!v9%A2p2Q4})kVO_lS@i8WxTY`+}YZX>cK(C<|?lza?|9)cW6i)>^L z$}UnYV`5GXs8_veJsqi;ssOxd&X8YWD>sG${FHiF9ZM(^jZ8Ns6Ln{|h zNPVw}n%%7iVxFSVLVFYIzow4a8_Z4#?QH(i(()hQnE|)NB$|!VAo^_0-y{ zth5K|EZ?dl{}oRb9EDoal#U(40Hq6P(%HQ-{24$rwifAtf~$RDc9=A;Ler2`+KJU_ z9D7Ly6jE|zPmlgHvuwC%DObLC3)ftAJS$cX+cx<8KYxM0`rm)S!$1BppbqtAj8PyE ztwLR#4(f6*(T3jPsCMp$ChfzGkEQo%#o}V1u@Jg3nGJzmbjg#N&6^5w(=9YlsB$5G z{0hbR^z*xM8H*_?fl06I4x$D0XLQUsPHs9=Q!Ob^q z<<2iX$+Nfb269HuA0um_b`c!IW2phdKJG3J;7DsMwYQWRW2Vt6Oq$Hp!w8N8BBl)- zp;t!-904^uDbm>zcD8!mCo!yWdP@!|q}nnzj6kJPSVq)e)qS-Z_zYl}rHNy#7Cr3U zyi!W~E%gF{C=K9Lyh&Vat9$xp1qe#WGfLpVi?gu3&k2{0^RsV1nYUbfBFmOmKyt^e zxADnO{V(qR-aR(XT!a*z_4BcL50?+3kvC}qZWsg*-24jxfhIXk@!;p1=Z7)~(=pKT z8IGkNROo-2MrcwE7mE5OZ1WrnzKJz6S0T-q}nwRdMgwZ0MQb`wi7N0cy%*zlCox_aP243 z)j9&pmrM(_bO6n27+RZeB)2I7Tmki0;Ygci}l^c2Yn~r02UG-}45AVH~KmX*Pal^V-1!_g-}DrZ{$MZt$L1J4rA=pih<>K7 z3^X&oSwWOS-OHNy)B|N%sZPa8p}k=pL#5Ripjrx;rHpgmNzKM#WLT%MPH&FGo$DiF zji*LS0xQ&*d|LW1zmB-GeOCTVvKvBC4f}{x6r3p`N4=P`1?0j0Cm& zQ%Xc%l1mA>P?}7s_???7nEvrB`KC6TE?mvEZ`{CJuHFQrLzaaf+;=yB{nvlPE&p;W z)7o~XmN#w9QniB}sq3P9D70YT9( z=}i^PJ~B(2j1%6riVLpTz$KS#V8e!`wd#N6mRtD8fA~ATcKe++ZjrW;F;qgK5An$y z@(kvtlClt+>{1hOOjAk4yT9EqNO>@y?-1`ar1fcre%Cx@2T^H4g@p=@KWy86(U+<*Tr zzH{FTJoKM0vE!i$x-a$_+T3PjMVo9GWWSn;T|PtxrR#y}?7CQ^rfb{KM$F7fD-2y{ zX9g-DahEhg)NMD`i&yg^3xUYxd?T(4Y{tmz*gb4{r9|YJ0w^iT3MJ1J+6z`nN};~X zT)|1vm-P1b=|3~a@VcDkXDs3DOON5gbJubH`A5@oT>TI2J;E2h_&Kh>@dobw{`YMB zB06Lgkmr>8#=qKF7-}PX-Nt2wACL2WP%S2;k@z%I0F)a0Az&FqYYC+b$!%?H#59zJ z6p$)7MkiJ&KaKw_#9Jy)3Z(}HvN#xy!|)Ky9gL@?8b{+4$?wy=>;dwPa z_8jVR_uV^q;NBf<{qZjL-hLQKM*iv+*?30Q&dGB@Sx9vYyb(~dW$f8ctTP-04YAeD z@d`NXfj-AGwsH(J+r@RQ$K8r`-S}0Z-ZBQNEn?$KV)&KXKSc<0-K{Dj1A3ZPrtH|g z*#hPy-CaGzA<611$JxAP6&Ia%3}>Fdjy0>tYVCU85AWyS|K%obz3FD2e(4E78Cr8X zl;p@(fiT;@w$D0e-1|%1G2w=kaHZtI%^#wl(kx>61_iGWos?GOr%%an<1UY1 zXp<1eP|W}CGnAqcV!SC&2pl2ZfrA3heEJ>K5xc2cdXu(CwJQYh`qy2=HE+9)Yu<7- z#~-_~MrrTCDIUFl7Z2RMlZPML&Hk5Xn0$B!aa2b8*b#;Oa^;Gq@nay`|{>RXhI&F#G%|Wr$ z>lJigoI~s^>73bN#jzc>oU)4ZU%#Hy&RWTe6^n4g?!CLY{)=Dcw%c##TmSK`+P5Wu z$U9Kv^qK#jw*+V{RTq@^yS1(0SE4cdzZaqf$9|i*lt!}w5n2T^>chSYCAaI zzY;3%Rp&Ya_q(-mm{Y~(5S~L{U9YG?!qJ56Zju9Z0Dbh^(o)jx74#lz*)^h5Zt64f)x71EeO>yU4-{kf?Z{r(Z|2jKf*kQjd0SelvBNqi( z4nhRSJ^P2Nt!zGtr%!!*{4YX=$dce+IGd%goZg##r!OoYCu>F~X?0R~V zse@gL>5}eTNpGJdUn0oHbFvYE=w#}2G+=BUZvE@`($)dTt*->_q*k?!>{p(@y-ZSe zB}_`nxe~drfJsSfxnO8nMmE}_vn*%R=5f|+Ud4(vqr7VUVm6$Fp0v z@wKmglLsESm+yY}yFCBGi?uY>;-`bU47zK1uKL62OLGpV-6iXGYiS@ob{C?}4mzG* zseBD0?4f+IdNhGo3M?1oDLbfo)YO;@rRUT2{|?cQX*8iUO&vK1-6kz6ls6RDrEYIo zy?QmrZ`#c3Uw<*@oqG;Hi`=*(i?lO5` zhKc=MCU?y-`*>G9X|W_jj_UVtMo`xZ{R#K{ z@CSVRTi;>(i_f!b_a6Iw81+0#ETlAoP?}H}RCq&wyXB=OvnINJT+=vxC6lHfQs9-6 zo0<(}kj9HKJxE2OYEtB1KTRn7w7|6x^|7grDPSd#K1N@l%p30Zvk7b0uj7;xPvZDZ zCvx6veui_-I*oPf*0F5)%0TKW963D8kpnaA+dad+!?PTk=y7DC$KeBWOilNgIy}q7 z#2nq3KE0Vfy}6RU)=*?wDo|;us}%EgMtdluJv79~c#H9+BaAK@W^8Hq8$tFfnJk$(o3^y#d20HTgy3ToXH8BH?scN^_+0xNo?47 z3~P>A$9z}QbSU~z_Ms?CN(suV)m(P1jHM#W$TPK-oh^(!^h$Q_+{M;spJ40LPqFQ# z7kTWdCwS~9k8xnn0S+8ESW9ls)0no13AF!r=)3t1&0{UpM@^F-k>5>xgns*ZVq+>* z)*utO9|i$3pH_|kLAH&3X8ky~68`T&)TE}y4wW$o(1rL4(MthVQ=X>TiH2`Y+MLkN zRiWV9UQ8IJ!`cn2Sh;c~BTL75^+~62!g0s5X4O#~b<`@BEM3gX<;z*Vas}gKW8}ka zd>hTeLrHgbj>(A$_U+!sp~FYme|SH;_wD4Ry}Q}^%vQEPzKw|^Q|v!@kZmtK7o{{# z2SE;W)tW|hk-7;&{Tk~FKduS*7cyDJ#!O1^U&+{wmFI>ONHk4ggMv;<^Ks)Fmpmy| zY!EG=iH2VZzwAL9FGVwzrwM^wdMO?j0)nA12!Pe;wDs@mrmzfU=J2%`KP(>Uuyn-= zR;*dgilvJg9UEn|(_w6MjFI7C+QV&z+CyZSAkT8LJV%x#r7V$sWvl7+`posZ3Ph%+ znVOzvVtR^$hYz!R$1bLi9A;u}D#^zpT@QCx%&)s?n}ui&etth+Oruz6-a&Zt`E>IP zGA8|UVt|^`9zuLHX-iESPAqS2$rCFyB?vCD7~_Lz5QEOxG2RAI$71PHWu?k)D&H;h zr{QBhtv2eE%gnqyRo-zjB!a1dK<58<7^OqrZb4Vwh*#B3UAyUq+PGK zl_t7_R-_4VV)SD?HKq6Ix@|WI=(u#7W-d3M`nP^5vRi(pXZ(`M8ZYBsde8@Z^|p3l z)6N&}YC9aY)e2DbbVRpi>j}+_DsBe4p?(j8i3)8b!#bvZ)+Qz3sR_kT6AGd6H;C2{ z;xATisDB3m6G)GzCe0;8KNM1QLTL@%mLHj#{hMZKyfiV@DMZtc^E=WPsuZ%u1UJQR zsC>UZAzGo(1d^$8Al$yOwpVc-#Bh#8z?=YvQ1_D+l+Kb!YVd#@TFL-h<(mlBP2d`a z+em#ml%m%KdvAze=kPKnRcAj=(1m^*IV_NKq3@w`>mfC>#{_v$0rvR`rT61wt!eDG@FEB89QSu@Ai9kf6XFnng?MP{q)@*3Gkdx-LTOV2(k3>W z>0&da<*Ah;`<17$1+BUGgyQnz^V~G?gyKV!Xb8mpv=F8fn?wiILVR9BaejScle)`m zs0=?YB@dypK?BO5gkuC_9ra3Q{8*)%=!N13LG#$G7b}}UKEJFKZIeI7e;hbs_2^oF zhzV`#@nKs9P~ku3(!ja9h*dAvvNq_@#0hc9nwT% zV|>IW!cbhS{1gDWb!qvTe5OLbo0#zn3=NLhpbS;QO&{ynrdd1` zLRvu#(S5#r8a|Jy{BD{Qgw(rHRJNPqgg3^GxK=rsvHWW(fX`3g1ST%Op}*aKo7y(TcT;E@ zBTc{<8=r&F8w8wF{T`aAW0TuLfILPAAoCe&LZXz=_-S2cLv(!Y0Oxl|V@VBOH+^h| zaru3v8jT$%iWpBRQ1rjY zCc+S(e)+M#WBi3C*-$z+E(WTxHVFYqQ~D;rb$`eDI#g~e)+nil3uy=b?@*dh1yh}z z3ZaH*(g;F%L$gCnKti*n|2vd6ls?8+YIaBoacU-Mnt4+7^7(Y@6PsBFEz2(>CfM%e zmFm}+Fve#5&;%3%IzObqz%Mt|ud#MgrGQu}RA3ImBBE*h68SABx|gF)(PF z2~uH@25Qm<2Kg2noT-kE(M!!7DV{0i*m&}J2=VCW9kl&Y;2TOCDu0kM?B@6Rb$^?G?L`zZ zrhP_29TIDVrVcUx4l)@0PLBat2&GeX3zg~f(y%Vqh{zT!_9;uSwuSZ4l~1|63}r8`m`Uo9Z8$ctW5f2=hHiNcDYe zjQIWO#tS?RB{ZY@MBKC?#zJwSPD%~#&@7QE%Z(2S6U^^$ym&W{-adX4TZh;q&POr~hxP+*Es}fFU%7{d6G! zBJe#_r`Wd?Zwr}td>X0#@&68uGn2P=RaVo0_P@m{;t#-(aEBV6$ag=a1U)tgQXL(l zAJaTyGi=lE7~uHnn+8b}AjZDM1l{L#kb1-h{2=Y#)bD;7vGQX=8ls)b6Du<%)FHkM z4fDN;N7?Xi6YUVse!9@u_0zZ^r9=z@eu97>N@^B%3B*t^Hmf#OB1AVPOsUz`AMl}> z#0NJ2ds8F&<%R}-NRXNa>_Pz`HcJjtcb~_me)Ho)<)mi!)J(XLu@wTCRM{b(Q{Ws+ zmy!)Xe{53o^M%UxX@u%Eh|Glea=*vgD^!lpcdVTx=2gi+#u$^aiiHF{ls^>L)KQ@j z8nnIug$7ngh(qPY;!`06Si*~o4X{)j#DLTfe%(`P7aE$tu4!gX(TxdBQypT!6D#MH z@(~It`G|pWiXUI7L-hQzQxio~e>Am6DBmFc(h3QIUvR2%V@T?!iRDYtGGP!9XwoJ^ zX+s)A3J7Bz7%L;yCZY110Fed6HT`z^@@K}TJbsxmjU~k6AiT!t``_KXO?~4FLyDKC zvYU8`(Q6tHem$1yCe%ow1{;K?%Y&ab zG7^Y_!(p{x%oo;`ZPiU5bDejJ^y=?kcB3N z5MMF6sqx^0uus84ldz#dCo%$0jX7S)QO#*HAj2(i8RQ?HD;?iysJJkN7JiiRbs@3y~RWu2=} zeJ2^tXp2M?j8p{PcmJ6iiZ_l8jR=tJe(4tQv7Pk38>306NKY134ITA!T*{oJ8u>L+ zTV$cJtrIuGBc1s4i~LRk@T`(x`KIZ{TkuWY(|OdAgZb#f=wU+AIhn{!w@?P}oA|JP zoh3?o(f0FBh}v`c0zA11@mflXU#IaAy&nGu~Uo4QWysn}<2 zZf)t?6@ZpH;Oj2nXe*Z3^+Y=Hm^MzYj#@#Gjl_c5(*V8G9A;>hjd zS%43?%8hO}IMns8r2?DnDb!Nbf*P0Kh{N7RGs0yx|6Z!@4Ovmek{xij`gAY(G?v}E za-?9pi2sh4{oLbt*F;r;kNLF7*&k6(sfWjeOX&7kZTC%}X~)X6*t&7)BD^Y~u3t>D zg6-)?W}7teNG$O#xmpBy(iEpwd{<_UOk=#{Pr|b>zc=KckT3={iYsDp{yn_0nHga; z9{=JPPs)R8vH2|BE^45q_VGY>P}^H{I#GB0r6C+*;2+j+Qj2K8bKP=sE1DZZEye#n zEvT`1NwTg_JSsjp@ROynm^T(b7Hw^0j(f`5p0AEhqoQ2%qD?-%TF`#*sGd}1w&}F| zOuFzFN;-WU2XA|(&2aophfU>RMx>6XeE)gbU`Dyh!ji|L)p)UcPRH3_n2jb5@|6s) zi$O0{Aw?I6q_nh}c+*k#P{tgkXN$NIYF$ruf~+ATY0kQU^q}mR4WOCV1)UNNnZ2Lg=;oCfN*!?@&yzwdV_S6dt`~ zdxaWr`wAp<^M3pQ{90<*+oO0Cb@h~!UC9;TTP=yJJVe%!hG=uRlzm#SG1C4ur=nTy zjhvQLPzh6tf&Js2$YTH!+x{rFT$SVAyZg*8JCTKiyDt6X-$KGg#C5NQ9FE^NVE5&E ztF#8QfItqg%nc_M@V0`o!6+h`rCONP&dgt$Mh}}nr<7z2s?-YWeXW(X@2cOSpyFRDo z6QSKyh4}^9lrmsHW?#~iv+7H+LajVlhK@41qNO0&9SlD(TmhpCL@Wp;{=V7aMmXck6PS5AsmS|q2l>|`?FM+5O+gFnDx}?tI6AD?e*8KC@7@2@GDIi7> zKi>Vav(EcbNwZq{Mv%i6XrhpnGd|5pPwUJ@XCHlO%m!r3 zjs6=q0_6dG2YU{W1T-ZTrC~HM7Ts)d_L~ig&7vY!Q#a_V#qq&@X1^)J8HuFlZCB}P zE}V~KnsMoXdU0$3glw`p}D5h!K7?l?oY z9}Rvn7s^I{xA5;r=k2V#5Kma@T>uUnHvjB$Z(YwnU|Z$OMt-b+WL*!-gc?c~ttTKl z4<@K~JyOdwN}0}Q>mzKa;wv;N+YA9`U%)JlN+UbpX4vVxt&&bt3Vfl>v zkFU!$$!_v<7VHCUs8C(Cx#<+`{b0`JTky{kMe0B`q|gvpagkWO&4GdFaJ+UXf0ETm zxF`V@&1+g{C?P8G`2L&Aa!pDr*Zdx*=rCT>ar9J&7{?8ZT~bt}ox=n3#CNti>b@&I z8dw3l?A>@&I;J{=2LHcg9_U~Sp^!#;N z72X^+OSH|TYUqso=zV*;|9xG$1;$vUS+5?}mfH2s!x-*xbC4ofDZ-DWp4PJND3f3` zdGi~kXOG+oj~6`Jyj*A5>PG%Xu5aRH-Wj*Q3np82L^5AWjHt1tki1INhj!vrY3y7&z@}RG3eV#8omfJB=y|P)_TXBdAxbxt)#0 zE~5~4%4yUttO^uYXmxut0yHqo&aki2PtPm07|o3sUNabtc=PPnkF*~31#1nHEnGk| z2orGdi)-fZ$F_ggI*T)*isRdDHW)TTi2N4$fLT(3NsY1r+K!)9U9NdpZ2Dx+ct7wP z)%d)s3joGYuhP%O6kQ%p(0Trv{2(A#i@^=}W-Ddfl3qcwssQIF3#IEB+_yHw=lDhA z{4$lnSID#*llqE$J|KnPWaq|fJKvOQLu}Ny5NQjgQ7gCXU!~MrP^GXQe@A2}2B%zA zel{0)2=xuwVYMsGPwt5tM%4ArfUgBKx9UAw`7Y?)#{(s%PMHOXe*Cl8@ftj|@ozFt znx&g)`cckPKOLQlUFPj(H8NtiSfGYVD^Gm-`kR{3w}J#71Bwov%nzz!^Nds)sK+mb zV<|#tt8dLtPoA?G4+4@>q(%#hf7D&k(7H|hIR=6h^d*Rlg-B`P39Q^sJ03g;Kfm## z59kDoG`a7OFzR%&b<|xI9l2fqBC(zOQ>`BJ<9@I*qRg?hAE_zDg2GcxrOA9Ona2*X z+}r2*idtjlx4Rm9MJ^5r^ng_r4to$%@7SBv`8`u%AuiG+CN#L8+m9Ze^655 zvjGIni$=NJeLgS|km>@S)b9_(bYcKSp5k^_WiqJm$ooCyHvn!)S?% zbo;DByNt9n>TB3E@?;Ri)2Bx61utY+jC`!X0soWM>bT9Ik%^@0p*WNYztj4&{;7$RSbN#wLnluV zSEd>D)<=4k+m%J6f&{q(56@n071;7<+iTt^ zl;0Kkm71bxLzWJnc!p9-V)}&U0M&^-9ZV^OQr=r5OxJiLTq^OHB^?G)P+?*}fD$?C zeR(*VQ%R(*Y_XC(&K{=U7nYNvPFH!;hy3D53E4!cBN!Fv>5HeSojF;Nd0V zK-7|`vKLhx2UnzLj7xy4YesQNzy0sx!f~8 zLx(;a|G=(M-Tqmf-Hs9EF038WkDaU3iwS{Rw8$q@?27j?;F#N*U6Mo>d&cGNF)NuA z`~1me&@38+PJdap7WA$|!Gq$>v$yH}K)?`ZgatRprgj%p5rH6~0LUGm<~}D{YJ5fm z6ueE?8`&g(AkNV0FWr`V`*KY2=T%59s;^9j06#7B+$UH(=wWh%M2}Wiz!yH)l(uOW z@T-IgAf3%jsZQB2SK%3Tn>EMIIi5^vmAZ{+oUDdL4$blu7iJyM7h8F|hDTX;?8ElW&|kRhO& z{qKSLJbd=+Eh_PC+D#IsYf%jH4btWUSmpeh?QjxwgvoDu>grf=0IlH(uS+jP&92%t z6%}$e)V+z%cZVKcLIlk!$M#K1wdBh{_C09_$F@$#*M*``jqQgSd1)ds@gIMvG2s1S z5u#2qY5DOyjkPGR|01ZqMQ6%2-FPDW>CutN^UCk-2|D9K*L*d9K|XDB@1yu`K|Dbw z`F6Lg|BQS3T^eiDqGX!&Z-d@*(7ZrQr1_$Q3$LjTj_4v=3RNBc%-Ko~%zg?(YkooH zJ}cBZuj6NQ?P9sJOvMcuhIjwJ=Yzj?(8;aFSZmKpSTmkqh`Ug=;BiO zC_y+S(U8_Okxqg3SSbCg1vAIBo@yKuROJJZ0RqvtIze;Zizj;a5!=2uTl5VNRoFMP z`akY0&bYAGe>Jga5XBL;8pq&HX;vGzrH3Bl1HY#iAt)8~35fG2Om)fOsJ9MQfS5p@ z|GzYwFbEAByCnnoMwdMiM729%q4%>Gr9%$5L3E7V(Zyfw-!wcae%%)TTmg}`GEKX_ ztl$q}N@!w3e+l=E$FdZO3OKdhpbypq(wH`E0X;rw3dJg%!&911S|91yB-g7&|UZV)o>F;nAskn!O-bY>TgG(_xe~$5u;L2}}RWApE2r+)JV?gb+xc(|Ft=ALx8%ah=4_GSpi@eE+XJk&yOV* z$G)xaqQw#$G`G}^#NxC4nbs?3+3gReeVVQBRGQ4H6=Iyg)d@lx`LX<^pc@1bRunf8 z{ed1Dsv|ORUrfW*TWTXI5msgo*V`_5&a@7FZN@PUXAPsRB01-A5N#zYVooHkoj<|> z@l(a(%v19o?c0CA_197k>Rm{6wMV_WtPE`zAEXI1q%{!lKzr{umr{g3>vO!h>o{m) z5|4JW^p`_%`I-%V!^pi^FV;(RZLap2>9;!>Uaruz+xa8(rSC9AK_cK|)W<~R9cN>m zO}1)7g41M<5Uzf|Hc z3n|jB65WEGkKMq&-?cIfnl^@v9j&t{Xh-|sBBO>VxLHHele%Lrw;B;Q?LnU?UF_ajgD9a>l`a^p+P9~iqsd`O)T5l3yMlXywa#HlX(F_>&N-XC(!+6 zYA=j*d~P_}bI^x93YLz84uZ1Dv@Dlzq)BQ?SdQLWwSwk4;-9v(aQewvh={%jq*Il^c>p{pI3e;+=< zS_2qY2t!n>&_EJse$2d>pKz?}UI~LBpG~Pw%+f(XI3znA_$@mSVy6%~+UL{= z*+Tc_d&K}m7`{5v1dPjg4Pbddg(~bud99|g%_$S>vi^(Cvb(kjgb2R=dZq#*pq{m_ zGRhT~|H~INd}r%uhzU2Kl>5CYa7D}c*3tX-e(W3d?ypX^%H#)e`PYlNbBLuD1CWY> zT=ci+@yG=o@@1OGgN$!~(nVda(1f+m^ZL3Iqmj)3$~4QX>mT}CZ}BPE(;xXf}ijcMDq{Hm+vG)M|e-t1+U#aq-?-nIOhS7 zEmawgaN6rv>lS2hwkr)8?|DYaddiPmb6J$VH4E+`Q>qZ$@ z!XWJsqYe*i-lk}sykfUk78)_)JF%u*n&&XX7>B-F&6O9Iu^Zv1StnF1i8+ZYcl4J* zg&xL;I~nFUqoLv_HQg>b+m@;&t9^Kyn3jY91bw1@*a}A+b;f^6sC9_)F#J~_gOS{=> zRa0}nUe^2{gpDUYp&!(VH|ckz$?HDG&qvaI#gYHAr4e;k)aD%sLXNm2cnda| z7DT@%qIva)^}ylU@#I#M~f#v=0_XZkBp;BIz%#gtiYi|!tk5+fN%{IwQoTb9E55=N=WSGGD~B^7Qe3 zUB$&5=+Ppxpr$dQmF0aLKa}?Mh*`O2!E>MQ4@l{gN{EZZVSEwB5%49uc2E2I2g!O0 zA11PsJxjEmkLvr<;}&JkoepD!ma)?1y9(j<+tXBcfRww=g%Chgt2_nvhT8T!4$muv z{jE}?x<8&sfWgDj1wmi>qz5eoH7*c075{>0Wm=J>^Q_%6&D5rZBk zmn*xOr@PSRwX2(L`%OuFR9!n+Mc}xr$ADk~Hcn*<48U$r8^dbsIO%@L*GSS0)5vuE zU=C6ff;FmD6`1n>;AE*82ap_87b0EX6(h=?V-F6d$0Db&M?w1?K5FGPVTGogaT;sI z|0^Wo{t)hdcOS+8MhBU}%>?@A*s4TyNpL`x>D4A-HAV+B9_r|3PNxsabPwx?H# z1)e?`?+Qv?;sx9~euc{z`Mu(=x7ZhAt;5aC>KiFTX#u7(AF!T|F4#}@J!(?n9gD4gy1qKAA~jk|1ilDA{V ziF1_#e?aZ)w|fNP(oBZ%nsTIICtWPs5!Us0w$$TlV!0h(W^TDiHy%N;7SmB3ZyY(kd{kjhNpS3;j-xC{dL^65J z_A~cBUJQ#r9F=MHR560dZ>$y-d&v~Ei=RLn1?M2-_tjB04f@{>n=pxtn?}vPWburu z{z~oN#60@~KMfoTt!d1BxK@Y+ymPO$OGC)vo;@ZsFSUz^l#P@qDdVXK%!mp%B}TkxC`qHAdy;+7caD^Xc)st4Z9I zp6*VK379dAT#=7Xvjw%4fe4T=sZRhrV-Mdobvx(yZM|w>eGmlsM2Qqlfc@p*PEcuBSn{yP)BW)p^wB#3 zymHiHNE>K69R=Dk$GK;algpbMlmJ%x0c83Mnu?T*P(=R2apZ)rBLe4vX7Dq8p9bMc zH=&#VFnc`I8*1VHr9OOQO}d{8DtkY%00(JzUV<4nS=x=|D5-GlTJ3c8I%q5yRqr1N z)a-okZuOkkCFpC~?og}z2mAg2;wO2@tZnpqnIKOGr!}U)SZsugqusNv#gmg%G#FRh zlMq{SI-imnDVBUulE`?vjS-*eVhs+MO!{$T^k5NDrS)VSSSrKDFt}~D{44>*$T8o8 zgN_YqbVr@cmcV7QykOi#E}p@R=+Rc-jhJ3T|5IS~E&Dmi`bP{Tc8%(WQ4s6WdEL+Y z334~or?p?U6q#49m>P{^+^88=NCaJ#5t8sreN3-@9H8m(OrvIZK8GvP7H^708NMSwWjZqvc@(G8 zqEB-0hnZF3w=*tw2xgkpk?Z;jgHppY&#DtxXr>jERK%9YGmavVC0)|3%Hb0I=MN<~ zVhg<%L-OUHLa9@q#pK3?C@`4s-0*esXedZdS_b!}iRQtiJzu&@V@^m}1DK5zS0s4? zNiMsZ3hQJP1rjj}V|~}(1uWvE!(=s_Qj$o5M8HrFMrl~5aN|+i4(e;dj?Jz;(-@Rn z80Pn=WfM)<8XJrm;b=crL}qEBaCLIWpp(uE!U_gLY4EU|tQJ~A9+sK~FDHL%nj6p9 zZ+3`y`_$FWK3!%J$N9qrS`4QsIZ)TahnAaHF4$i`0%Y?)*Y4F^7;6c$1zI;ae+<1o zOli5SzJF!a=uRu2hLtin-E-P*gX0Sv(OZhjt5UK zhStDZeB(!(R$mp3+DVld7oell`6c!wbZD%CGejf!dLl5r${W2e>ls`w*})72--wZ` zHg=1KauF9L-mQ@3YeSL^9R+bNTL+w-W8velcdy`2AD_(p2#=*{f>6v((u!~pjU?V7 zy01&!ZNtem-f<4kff5mojNhy#N`aP??d^st7yu~$>1#=0)N7$K;T1zr``MvcUUzk5 zd7kFR@D&EjXlcO>@9-sO7|BO^&Qs@BMS+(8M2Rqj;vPn`yVW8dI31~+nM#k-I2NBnUiPtgN^)KH74n3BW zVdM4QAEuMU;avuOWDEeWeZG1ZR%?45G^)u?o||}^4a7NED9X<&m?n5OVH%z+T}`Bo z>iA@#LZ%xmpB3A!o;dJRPFS4YP3@sgSj!uv^>8Yo*VzFgKj64~jOB6=mSHELwJk*- zxI=M56j-@X2A?wZDD4me2@XGC!$IY-ijyYPAwMIzvQsx|kT6HfU0BbVfk_` zBMSO4VEiyFk6}F#soh5~Uh9gkRjW&fYrR}!$TWf8zpLD-x%nGuhrh*m-GFIDwCs$_ ziUBw$&ah&N?(?yh>Rb)AE3RE9@y`fo1H?Q!)Rzre8-P1Zvjy@-8Sp*D&u&i3bo<;t z226-D@AmC*zpV+$rM|S`kl;1@qasKmEVA{=`BQOzLZbW+o z_S++$T@N%`LpLvd567vTTbdv=vRJ-T{y7Xq&jp(`u>mI0BIk5IBn>QfN$8!Li^0VJ z5nQX(C9zT2sAEkocoxcC9C_IKb@pbm1}4o?&mCd)9nDrukHV$?^Qe-yMDfnh&a^l8 zl-reu<{S2Cg2HAE{ld$Zek5MLuT3b;e!$nJ?sUXb6bw>>)70ER?al!E36!35k0&rR z;|MrXj*~=e4u3_ZI??3@91_@w(@}T5vf2G2E;t{w82AzFWFj}tffiw5A9yBKmxPAV zXtitS6^AwyH6wc5>>9J+q21$4?sGnMOtGXQW;O;abVTh$+!-aE%Ga6jZatS{?hUdV zO}lHO2&E~nIRg)2LM7BCLDWv#>hX)o7PxtV=L@7VcH71kT-5CF(aUqkvE3*t&W2Xa zDU?E;$aza{Huga%*Hy^MrK5z{F&ya@7UzK}y5nWDsLyhAn{X;JW_efeb5B0(mMD_2 zc-qVWm=m7DySKbRrJCl9!tcVv8R$@O|&E^ zdvPU^y@rjo@GYCLpcyEH3nG}oKn97Npon@7fEP%dD6V$cW0UjKmbVN;5TUY$G#SvG z_VabhIofa~(c!Z4<=m-@XoRLC@Ntt_!Y9psPY8XE=uWF3XMHhrnj{;)w_9irRd=MUlA?KfCuje`FR!{&3nnD%}KnYv8^awS6f zDSGXEmw}2AMMCQ9L5y_{Q?e}{*GzdqN>3OFX+;#y{b}lq3@c9;pzTE9^|wWX1F;3| zN>CI`7{B*(w=&4m5xC8QVf*|K%2u zhlbfT;@1j^RTR51>>Lg@YVWh4!|8frAmQxf4+zg(t@=djO9g46(&eVaB(aKz+c96z zA1DnbK(p`f<)3k?V|OY{f%F_?O|X-TK3{{v(ieaq6tN700i* z`sKPoR=YB++N+LhRUGHSq6ccXywY4O7&RzZSH(fI_{^#LK$>^yHMydhcexK7+}Dbf zk_+k)*Fuw-R~$Q^acI4jwC`uvvMw@Nv}u{;U-@$8u}0izFHu#h^t(d@8*V?pZ1BMg z!b%}-%RL`Y-kX0K)cMb^YpJ7K&uQDYYWQtK1e6=K_lQ4X zuQ&RPRjA?i~9yXWd%TMz;ZS(!3$i86@)h-p*oDI!spf8$P(0N40pnb#%8=6PoP9R9Zt zJ!nSS?Rc=Z*Dfh(eK!y+oA|&GMmpWo^637~BLeblZH4d?$9;qjWNXVpA)PloVTeX4 z@|Fh?x$R9d?bMtB*ke1CTqPLn5 z`&;S`2f(i_2E!H9CoGS|C4B`NZ%1|jF824js72s;Uv{WeI*hbBx6qa(J(P7IiIo!Km+_fUWDPh$g$7uI{Fa#TwBK^{52uyLoPC zi(q?c+LtT(QydVrDc)#8(P6KhEJJcjJJaOLh*DDgJ;VI zUIDc+2d)Q?d+zRjPR6n<>|GxS^1B+CiXbLP!u+P#1c&(M(MKsp7>0~)7Y+2K!L|MI z-p3g4tX!As%eUi4-|d68p>07eu6VK5uFwq8Z%Q{mYLxS-Jv78UL~fYpmR>!T+I(Xr zDy&N4E|J2w<3{>z@V1^zr&|}{wX{frK2n zj+wzA0%x{u0D+3rfw$t(w)sf{anp^}_;6lc$RFIlGpB3Sy)!9V%>b-#Gy-0uq1Iy7 z4a$?m@>%`rG63X^>wG3r*mG^p!0Vr{eK zIiMDLv8T4{Ml}%)N>mW4q1)u8&aiS%Y0I`F`n?ht5sj9+hzyut`9o4Ju(IR12yAT# z*tqBJJak9xbUNW+CE!Kxr0+xSF&TWWz~;j>;^q8C-_(#FcI+9h4po&(_VZ!whet!_ zsKA&*mlr>u;|=!3;*w=J4xT(K8qvzHRBT3m8no}(K^sI>g?*K7GcTpuOA629(355e znB(#WJZA~1x=w*OxtMru1?ZQtZ?pa;$1fARN#p=Z6K~xLFGYCFY=XLevbs^owe^zvA<~b)X%uF|JpaL!(@Wm51Fi$E zehFgh%Mny{39QdPr1UajjmwIqB6igbo8?q=)W0(#-_dPq$rWosftq;%lum>S{P6%c z-p*r0_rCYNebIKMqnLE+=w+AMAM*6@BDYC)r$pA3lf(UP)M%` zmd07nZ7OQ4!;Rj&8m<$M8nu^Lj0Y68n|wT*#X(FL^@502Z5I(h&fY;zEB_uxS!YBd^f(z&8fq;^_ znd50yn*D+y(5)J+z{{R$>U)yU)X#cKA9J!PJobBM(r6M9|_QF#>3E1efYoPD<2Z=cfn6f&Y8TOYogmFQ=qJt zbb2iVssqYP{tK7hs^xC?<9}t@*s!O9r@-%*(B%2f`%4E?9Qo!NA59tc_!@uJNYB#- zU}DFW4D326Z8e=%pyU3U;`a}wzm$CY(yAz*E24A!sC(+eawFo3hf5e`dsGfjHxlhI zdy(BHP#C_?biy{|`ZpiC%Pl*(ahZ#J7Dxu)3VCyslPUQ9 zH?FcO*&405Kjuvy=0Ng6Rz*5HAcH(eL?u=UY2jtNWn15+L^0>A%>XkB)|7Efj z{*=w$WNSNh)>ck+Yg`%2yP9U#PJBmCAO~0KuA2LnBTLS&cGcbEpJc*7UBF|I10jT{ zB}1BE+3{fz$DRtJr7g48c&7amveidD zd_6};gM*%U7=~~>%ro38CcypJOz^-x!M?yy7J-(T-{Cp#QCg!@lT&$bSwkI`BiuZt zu^`38fmfpkCo+Z2rdY+k5PI(7>NYdr=N5plZR}d3l%80>4)KufryI}ym+@9pTyFM7 z?*wj&@VE!kOj{LVSic1#wZBQt6eEAG7ZtbA51Mm6?=xZC8(j~>Ph0Ne(VUbpQB=Ou z(MwEr;n!(N)J-^Vy`YC%m~U-ALAmayRuVaI$vA>T-bVX4P@*o}xUWF%Wk`7m6oszBJxLzif1b?YU&~#-HQO$}B>4Eca~V3H?Jo+(DQ4ks{ekxU zXbZa6lfLv-Zx-#_5m8ds`ulV*;9I*AakVP)_T^QPd51@(CpCACvhiEC4tWyj++qU_ zhV3{XIvJmvJtH}7s$8(I~@5N9GzMV&~m@ zJQPTn90Utc1}ViS&#>VqRJ^;WL)$iYB(;ug=FChDKjW^t{^{6oR$?V0^GD|vahk#s zq@E#!%sd^K?UIa2453e>6ggkGiKf?%K~LoreS^^h@V4LR z6}z&@7|HVDUudaR`;lU`8*~oO#bt3KaIW@2w*PZQ%d8snp{sr6P8g4{M= z4w+T|&v2TwkQClgo3;qBbugXt6l@bNK`?2j^(f7km1OTpQ{GnGqQ)8u8&6bN^mtg( zuivjoM3di>Dz|LgWiukTk;~(%EHy^RRq{*4`_b<i1O$yhLRR&9vV=Xd>B z%63(8nwi`ypA#J|gV`{{876Z^_ZThQvT&T*nzkI;qt(Hi=0xrA>llZ>6wus0WZd*!6J)dQqKwsrJq4HW}{_`@3%7(p6%2JEkBsvK8nDh03J35FMHa9 zd>J#?3%R&fR9O$wJx45!BGAYmqp7~9S+m}H*X_(cz5&>iaPY9INX*uoORim%KT=fn zgGVpt1>M0_kqCIM3zF{rfxi<)0tzji``JNVAgnQ^_SrgaKU0H{LCMBSqvv3nw!V8Tvd9CwoN z&^Guf_AfKHmi)aC5&!7;9^?L82GfCi;`zrd8xKvRecg_-q3fbw3 zu~Pj0#P0>aNuL#HCI%ETYiZ>`^d@yLMCO*~g+T=L@XBNLCPh0%V@@M@C_Z7LDFc7Q z^?&Y;O$2Cjh&d_!?Fn13V$N6@4n-fvIr&3VuFC3!F+02}CGhqGh=j^jxe)k^l~|+H z)_{&EF!piz)L*|E;5j&jd4DGt;w-?U(>ibYPmkm9xLQ|FTj<4m&Trt4yOELH=O!vU zW%%X{jtw#Vg`6uM|KHk`?pli(tFGz?uZ%HBoWN5y=HeM&B@X)(0Grb7(zHl0_oG#($Fj7Nacj z=C8fbiu-N$)gNM32)&kMXrf<^qNBKlsCPmQ&G0=d7+EtSnf-d^@*O7h_59D*b9Ng+ zv4qimuUYjvoo-873jlg6`E?K1xxDxIQ?o2jGSkcc8MpbZ1bHM+#i?b6cN*L@WDRXEwoF{n{SrICi=y*GNVg*R_+RnbtiCI zB{pwx^R<{rG#{V19V{7lA5|2DWDXJF_`P|l29L04n)AKa>I!lvd?q4~C_wq|4>?bB z9=tLfa<>O&pCT+I`GyGTmF+^ff7t|Gu;7)gkH780Pxk{vlqi28ow&Hq9%ugnV6+vt zx8eohl4T6Zcfh{1KFo}RP8vM1i?h!fYNB6GxGvb7E;c{67qh&O&{=iirngig;4SAv ztFA4-$0{{@_3Wz)KZ(fcu=_*woDzF~n({_f-~b@3bEbP30NdTaqi4!zwqu~aJ!G6E})J_(N~VfggcRd#o2hIH)+P9qx(ix&(Ng= zNL-!4B0?!ql|JkG_F>PT8;q8^!9>e(|C?pG2(915&VC+hG{+0W?~?=63H0!aMUTai z`Iw12UFecdeY6tc&pB3_tM+J3xu)G|7>N2%lQ>dV;X2jvRFU&2I7G$-5U)DsXjD?s z^P(0cLeAkV2vQAA12LxPM4k`w{i6Dxt{>aKRGoy!;ZRp0yJeIc)Elu>wSv{`F{Pq{ z$^}{QQt#7Gzve0t`#o(1B)DoKY{Gi zaSv`?8`~a-#-I;z(1Ip1J~!cj>Nl&0VH6^PrkahiEy-&$kopIGJCdtqFjCU+yCOC} zHdC$5FlRXgVK(#qU}It-KyBDyhmISdrU38P!!?D(p7;}-hqB+6*JPJJ1tvkLTyulS ztsbowhfTsbGFkzJi18Il6p}`&DJqh^(^Q1p*u5D4!prRhFU6%{T?G{(WpQ-7+wl%@ zLSyiUs;K9gdTrDk4@)%;-0iFwszPJxJQ`)T&q8kDwX$6EM;FyHvt8f-)i>XSG7DN) z2SS0&9!-31AE;q*b$UYx(VvN(&TScmYswq^|85>a>dmez!p6b&b87lgRwOD;;XF1u zS|s5y*-l6_)k?oT=nN0&Ik(#I%7!5((9qnYoN@Qtk{a{LRg&-&&XZd$j*h=c^rWFq z@;+>T1IEIG;M;uhXTcS;@U_=(i$J+DwoYKV>Pbnd%aQl~r%w%Xd{rd;V#bD;!h@o;cBC_sGn zc~k|QYl>}KTwLR@O)?>Ai&he~wa%cy@K8L$E{ZZL1t6$=*T;`vt7q31n1)8hWBJzb zU3$c?;*cAgnt%3Ifw}~CohLf;stbbQHx<@%Xw?sDTK=#JlnO$h|Lb@BakD^VrXSHL!nih)KCKf5a?S)xc1rEF8lbdwu42bgs5Kp zY5{6-p1ZrjcHr!=gDh;sV~mZUh#O?H>E25fuC!Gy5)Jo5VJm#PN>36oY*{|fFVVD! z*rn55UfwBhuHocfNG-OH5*l;2w7O;W$yakrZ(&z3UNo-Bn{y^neu}tlyj|)%`CcjN zqSu1+SFr~DkN?Okz$+}O>=0~*D$_6v#NLf6@Nw&YQ6HK05-2)-3qIc9dX;Fm%KDy6 z$N&9Rty6L;^&9K19nr?gAQO`$caEnfP7!$CYR!@UTiwk9k0t6tl~zZG0f{!)p`o{s z>eymA*a=rPR?VJ@TB#zk47TJRVK>R2mSiw>dXpntu5DkJvNKEY@|fef2xw2lp#IQ8 zhnu@ZL%CWHl8?xxGj;q}z3dElP=>9gR)xbJ-oOCLKU{d(HJrwAEu! zouSojDx0v=Qv|EK zCdIDV;FelAbnhV0hPjSsVWceJK!H^i#{AN{*#jVVaIcA;xt9|00OJs2DHtDt3 zh_?)K>+B3T1{(rYUzD*875HHAdr}cGp1sFCbBMtv zCS1lU%Jo`pvS??&S%Bss8tEc~9S~+Q>1Z8@RE;S-8*%Oa%e`RpQf^)j;XGrKXhxKa z6ERSbCa;*7DD7fg48GYb)RuBdX+V;aa*Ay5{L*#%z;|6F{V;inXsfo)x@X8x{84d| zz704XoWp{k;>*n9ng?YA>==l-WRR{%ZZ+51(;}kV)6yyS59n>Vfj{FQFA!Ty`iq3A zMdjQngT=)TJzC?ttjoah0)1@SU}7)Dd2rC(G&MY2{9veg7?>apWakoEA5#ypf`1>( z0U3(2ct(n(2WnYR>kMr#whf%I1Jl2#Cf{?u?$IkmxqQ7lPTwrM%E1}}^Cp^Ox87O0 z88?Ss0x(xmNM{XBg(ZK@SjqM$j~|q*bEA)<5sB5+g9s|uK@7Z^^E7g)S7uN@Wm`pM z*C^98Ga!-AzM2;k*QOr({YR>K{Y^Asp~9FVR6k6`{$x(C=}aHE!SgJ(K+Lb7L@p{c zS^CD-V0=>>uMs?!>cMx)VaG#ZUYqtR$I8jVJy(P%UpP0HfvA}O}=qo>jpV9rG` z7h>I^l8iZJBVOI^%vP+#$YjENH=5nOWKj*lJEU>`#)RA#0xDGcL6om)vTVUvTh96K zLa@(STKY79v^0G;8UGcLH1jc!r(iEC^)u5r$&)uNWHTu25a$*A27Di8(610;k?CU3 z;oqr02@A49n>H-IR&ZIbxe*g=D;>Y$$;}Vh4G!^mUhd5nCOZd#m-L%frZJu$94jVk z7L*wGFvHv$Zo5hOJD5?`GkMyxrGHxlvvmp*qiUBC7$t@z);3#aaJnVlIohSTRfOP}+rJU2dbAbro^eRO;n<{J8Ka&I92 zXUX%Wh&?XDSP-r*8%lX`W?aS2&w-q*1VlEcE(NPF$L!>9@?eaOb#I$~G4iP#@zAdOs~PMnY(kkd~c?^-YOt|H;W zc7oW)CyoB@juIxmQ{gXVsVaYm$)68f^9{d42vtm^I3wVeFEU4Vpe8%1Y@8)hor@_-vtk0l-boyeU`6( z4d=|fhQ84QrZAUH%*lSOYzUZpLe@?6VPBw6(7!99KGBl;#*=lb*Q7p?6(&VIc7nI% zc7ktcG%X!PR8;l!Ps>43A&Dt({)+0?_l9z|4f65J~S}>lU2!(GhVzTG@l1d$Sqh; zKkNaz__Yji(6VN;6{Lz?OTA&GVHnuGpkaqIss~K(H8MD|3#(Hnm|ZrZ4Wa52^9r(J zNpiCS`76}%A0#2&MAQB#zu*8=6rGrxe}m=cm^H@G|2tzQ2~vB6Coli0vKh1_>>irQ zgo}BvD4UN1^(MnC9zg@dVN(VRw9bnafB@!8j^Q;yKMQPKJIzID@utZTOwgO~4> zXb>yt`!4qiGoc%IVV5_NmM-gM)3uX(oz||F4sD}4&G7G+RnegGJJlyZ!i5JIrrHOe zhG+R4C76bN(=K~YZ8g5tG>`4VEJ-)El5iDM7aEzU$Z40^suw*qql@)i%=)s44krp( znuu6S05%ET{GrrYKbnyHVsJ(&QzdR^((mk#`VhXeK4_F(MJnMeQmr1usH;xL4ZZKx z^#5;j^74P8p7|dAj?q3fx_s!jKqDAWzo(yPeAcmzfD=NR{7%$Y=;NqWQi8pRyd>`xH?BYunv0jjRBRlx3|)K7CT9=IV*ce} z@*z+s{SVK5*#Vn@g+mIn_pqFe4I$>@dEEUk?WWE$k*;UQBA06&YVEr-A(8 zG}<7~p7i?J)cr5WzeC5`m^O~mo4C-v9Dq#ph_}+&f^Jw}I zwc&}Q(f(=bG=P~$VY7Y9u_la>z+I8s<#2Ky^LHLG2{ zChCDlgl0NYKlwZUhiQtirI_6lvfjmGVov5q+`IKBy2dCd`KFoHqBMh+RN`C`{442; z{6^R0zGHpjre^9-;>K~|p&xPF4jEy9yf4r+R{i~uxOzfNA8|1xCl)-E}ugr z5Fu4%LNS#d&dGiYk7@WT02x6#J6TIa)smwgdMadI9%h@3*dP@MLbBIoxQ^o5*Q<5l z44T=N(*1zbChEjS)G&}j!P(vDxTPw57=-CPTew7B{{w|o)JuT~M%o5F81Fy=eKI$V zOX%KT?eTa5cAub`ZzkC|?MaA+k`T@J^$G8Cq>!sWi3`VthknfG^g}ovp4|MC=(&$O zcN$6{(M!?eH&*GwUrMvqa{1sc%s?3=m?NZG5sE-%8yavvuu?x$;Lt4_m7)oTr-&w{&mbilRuva_f!mV`KM z$^kYAsc~+4&#?xU9UKBB%jmZ*;GB=gezxkgC2Ar0H@Yc7TTa>|C56XltfJT-{{WsR z8ih9dA4iJPUZX!LQfdVv2f9rhpY?d~OyqWFH=!r84Mf}}n0%|`;w4f&hPo$YhZJWg z+wRuf@mT={*8RAIfy$ysXf$~0?z?Xe*q0PWtb2TB>F(c#FtC?RedaAjO*lF{M&m}s zsNdFtZdh15z>iu3!-zb9zH=wv+1N0-7)71(_iekz!@0&{RMb+fYv8Nk>ZTMS4%HBmsEup$?&|$5aL7n+^W>cM$%(QG2;;4kZ_&}xzBI%jL*7- z{&rf`^y2U6_x{^pVheT9Gm038;2d$guX`Dbm{{|fNbgOZ^HzFpN4DatCO5rschk9{ zbkqN9x>}aIw+*Q@pOHcR4$T};z2M@H8Wa-Y-ouCnnHjD)J>4@bsGhH!Hc@Y}kJ@;i zaan&AMudOk<#*Ec2@Z4G8!k-Bk7r8$GB^V0+GI_dkoj-5fP5a!_;)gIjmxR86ws)& z!4RyuDDmDxgKjZ1Mc9IsvEuN|!y(bptlnZn*e#^Pccu|JC>(=dM0#;Qdi_UcR1MgA zyc9#cj*+omox*-}VIQF53#g;PF3BNPo3WWAh z5$j8%C&Fn+f95Zda89MaYet_rCejUd=jFdBgg|H8OgDK73HYn@eg8oM@nJf)$uCm~ z{)e@NnPiyXN!O+oeb)2z-uWbWuyw|5-#{-*IjzV_uNDDZj%pq*pTV`T^LZ^tZ3czZbl0k;1*| zJrH&i*dGGQ4Tt$G;1c8L{CZOua+e5rU+Lalh(1Am!Hqsa?J4wrTbb| - + + + @@ -20,10 +22,10 @@ - + - + use_indices: false @@ -35,7 +37,17 @@ + + + + + + + + + + @@ -62,10 +74,54 @@ force_to_flip_z_axis: false - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + trashbin_l: 0.34 @@ -73,6 +129,34 @@ trashbin_h: 0.49 - + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 7b40053990..9031016111 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -36,6 +36,8 @@ switchbot_ros tf2_ros voice_text + tf2 + tf2_geometry_msgs amcl diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp new file mode 100644 index 0000000000..a26a02593d --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp @@ -0,0 +1,126 @@ +#include + +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +const float FLOAT_MIN = std::numeric_limits::min(); +const float FLOAT_MAX = std::numeric_limits::max(); + +class ContainerOccupancyDetector{ +private: + ros::Subscriber _containerBoxesSub; + ros::Subscriber _pointCloudSub; + ros::Publisher _debugPointPub; + ros::Publisher _occupancyPub; + geometry_msgs::Quaternion defaultOrientation; + jsk_recognition_msgs::BoundingBoxArray _containerBoxes; + sensor_msgs::PointCloud2 _transformedCloudMsg; + tf2_ros::Buffer _tfBuffer; + tf2_ros::TransformListener* _tfListener; + // geometry_msgs::TransformStamped _transformStamped; + +public: + // constructor + ContainerOccupancyDetector(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ + this->_tfListener = new tf2_ros::TransformListener(_tfBuffer); + this->_containerBoxesSub = _nh.subscribe("trashbin_occupancy_detector/trashbin/boxes", 10, &ContainerOccupancyDetector::CalculateOccupancyCB, this); + this->_pointCloudSub = _nh.subscribe("head_camera/depth_registered/points", 10, &ContainerOccupancyDetector::PointCloudTransformCB, this); // TODO: rename topic name + this->_debugPointPub = _nh.advertise("debug_pointcloud", 10); + this->_occupancyPub = _nh.advertise("container_occupancy", 10); + // init default orientation const + this->defaultOrientation.w = 1.0; + this->defaultOrientation.x = 0.0; + this->defaultOrientation.y = 0.0; + this->defaultOrientation.z = 0.0; + + }; + // destructor + ~ContainerOccupancyDetector(){ + delete this->_tfListener; + ROS_INFO("Killing node..."); + }; + + void PointCloudTransformCB(const sensor_msgs::PointCloud2::ConstPtr& msg){ + geometry_msgs::TransformStamped transformStamped; + try { + transformStamped = _tfBuffer.lookupTransform("base_link", msg->header.frame_id, msg->header.stamp, ros::Duration(10.0)); + tf2::doTransform(*msg, this->_transformedCloudMsg, transformStamped); + this->_debugPointPub.publish(this->_transformedCloudMsg); + } catch(tf2::TransformException &ex) { + ROS_WARN("Failed to transform tf"); + ROS_WARN("%s", ex.what()); + } + }; + + void CalculateOccupancyCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ + const sensor_msgs::PointCloud2 inputCloud = _transformedCloudMsg; + pcl::PCLPointCloud2 pclPC2; + pcl::PointCloud::Ptr pclCloud(new pcl::PointCloud); + std_msgs::Float32MultiArray occupancy; + occupancy.data.resize(msg.boxes.size()); + if (!inputCloud.data.empty()){ + // convert to PCL cloud + pcl_conversions::toPCL(inputCloud, pclPC2); + pcl::fromPCLPointCloud2(pclPC2, *pclCloud); + for (int i=0; i filter; + pcl::CropBox boxFilter; + pcl::PointCloud::Ptr boxFilteredCloud (new pcl::PointCloud); + pcl::PointXYZ minPt, maxPt; + boxFilter.setMin(Eigen::Vector4f( + (msg.boxes.at(i).pose.position.x - msg.boxes.at(i).dimensions.x / 2.0), + (msg.boxes.at(i).pose.position.y - msg.boxes.at(i).dimensions.y / 2.0), + FLOAT_MIN, + 1.0f)); + boxFilter.setMax(Eigen::Vector4f( + (msg.boxes.at(i).pose.position.x + msg.boxes.at(i).dimensions.x / 2.0), + (msg.boxes.at(i).pose.position.y + msg.boxes.at(i).dimensions.y / 2.0), + FLOAT_MAX, + 1.0f)); + boxFilter.setInputCloud(pclCloud); + boxFilter.filter(*boxFilteredCloud); + pcl::getMinMax3D (*boxFilteredCloud, minPt, maxPt); + ROS_INFO_STREAM("maxPt.z: " << maxPt.z << std::endl); + if(maxPt.z > msg.boxes.at(i).pose.position.z + msg.boxes.at(i).dimensions.z / 2.0){ + // if some point clouds in boundingbox over bounding height + // TODO publish occupancy instead + occupancy.data.push_back(1.0); + } else { + occupancy.data.push_back(0.0); + } + } + this->_occupancyPub.publish(occupancy); + } else { + ROS_WARN("No input point clouds."); + } + + }; +}; + +int main(int argc, char **argv){ + ros::init(argc, argv, "container_occupancy_detector"); + ros::NodeHandle nh; + ros::NodeHandle pnh("~"); + ContainerOccupancyDetector node(nh, pnh); + ros::spin(); +} diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp similarity index 53% rename from jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp rename to jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp index 0f8d93bddb..633b40f495 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/src/trashbin_occupancy_detector.cpp +++ b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp @@ -1,30 +1,30 @@ -#include #include #include #include -#include - -#include #include #include #include #include +#include -class TrashbinOccupancyDetector{ +class TrashbinsPoseEstimator{ private: double _trashbinL, _trashbinW, _trashbinH; // trashbin size param ros::Subscriber _trashbinHandleSub; + ros::Subscriber _pointCloud; ros::Publisher _virtualTrashbinContainerPub; + jsk_recognition_msgs::BoundingBoxArray _trashbins; // trashbin object geometry_msgs::Quaternion defaultOrientation; - + public: // constructor - TrashbinOccupancyDetector(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ + TrashbinsPoseEstimator(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ _pnh.getParam("trashbin_l", this->_trashbinL); _pnh.getParam("trashbin_w", this->_trashbinW); _pnh.getParam("trashbin_h", this->_trashbinH); - this->_trashbinHandleSub = _nh.subscribe("trashbin_handle/boxes", 10, &TrashbinOccupancyDetector::CheckOccupancyCB, this); + this->_trashbinHandleSub = _nh.subscribe("trashbin_handle/boxes", 10, &TrashbinsPoseEstimator::DrawVirtualTrashbinContainerCB, this); + // this->_pointCloud = _nh.subscribe("points", 10, &TrashbinOccupancyDetector::CalculateOccupancyCB, this); this->_virtualTrashbinContainerPub = _nh.advertise("trashbin/boxes", 10); // init default orientation const this->defaultOrientation.w = 1.0; @@ -33,25 +33,30 @@ class TrashbinOccupancyDetector{ this->defaultOrientation.z = 0.0; }; // destructor - ~TrashbinOccupancyDetector(){ + ~TrashbinsPoseEstimator(){ + ROS_INFO("Killing node..."); }; // draw virtual trashbin container and publish for debugging - void DrawVirtualTrashbinContainer(const jsk_recognition_msgs::BoundingBoxArray& handleCandidates){ - // Expected get non empty array - boost::shared_ptr handles(new jsk_recognition_msgs::BoundingBoxArray), trashbins(new jsk_recognition_msgs::BoundingBoxArray); - boost::shared_ptr handle(new jsk_recognition_msgs::BoundingBox), trashbin(new jsk_recognition_msgs::BoundingBox); - boost::shared_ptr handleCenterPosition(new geometry_msgs::Point), trashbinCenterPosition(new geometry_msgs::Point); - - *handles = handleCandidates; // TODO: Do not use all boundingboxes, use most likely trashbins + void DrawVirtualTrashbinContainerCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ + boost::shared_ptr handles(new jsk_recognition_msgs::BoundingBoxArray), trashbins(new jsk_recognition_msgs::BoundingBoxArray); + boost::shared_ptr handle(new jsk_recognition_msgs::BoundingBox), trashbin(new jsk_recognition_msgs::BoundingBox); + boost::shared_ptr handleCenterPosition(new geometry_msgs::Point), trashbinCenterPosition(new geometry_msgs::Point); - for(int i=0; iboxes.size(); i++){ + if (msg.boxes.empty()) { + ROS_DEBUG("No handle candidates"); + } else { + ROS_DEBUG_STREAM(msg.boxes.size() << " handle candidates" << std::endl); + *handles = msg; + for (int i = 0; i < handles->boxes.size(); i++) { *handle = handles->boxes.at(i); // decide trashbin center position *handleCenterPosition = handle->pose.position; - trashbinCenterPosition->x = handleCenterPosition->x + this->_trashbinL/2.0; + trashbinCenterPosition->x = + handleCenterPosition->x + this->_trashbinL / 2.0; trashbinCenterPosition->y = handleCenterPosition->y; - trashbinCenterPosition->z = handleCenterPosition->z - this->_trashbinH/2.0; + trashbinCenterPosition->z = + handleCenterPosition->z - this->_trashbinH / 2.0; // make BoundingBox trashbin trashbin->header = handle->header; trashbin->pose.position = *trashbinCenterPosition; @@ -60,28 +65,19 @@ class TrashbinOccupancyDetector{ trashbin->dimensions.y = this->_trashbinW; trashbin->dimensions.z = this->_trashbinH; trashbin->label = i; - // push to array trashbins->boxes.push_back(*trashbin); } trashbins->header = handles->header; this->_virtualTrashbinContainerPub.publish(*trashbins); - }; - - // main callback - void CheckOccupancyCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ - if (msg.boxes.empty()) { - ROS_DEBUG("No handle candidates"); - } else { - ROS_DEBUG_STREAM(msg.boxes.size() << " handle candidates" << std::endl); - this->DrawVirtualTrashbinContainer(msg); - }; - }; + this->_trashbins = *trashbins; + } + } }; int main(int argc, char **argv){ - ros::init(argc, argv, "trashbin_occupancy_detector"); + ros::init(argc, argv, "trashbin_pose_estimator"); ros::NodeHandle nh; ros::NodeHandle pnh("~"); - TrashbinOccupancyDetector node = TrashbinOccupancyDetector(nh, pnh); + TrashbinsPoseEstimator node = TrashbinsPoseEstimator(nh, pnh); ros::spin(); } From e4ff7388117c166bef07727820453b418014bb5c Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Tue, 7 Dec 2021 17:30:13 +0900 Subject: [PATCH 086/433] change output message type, use boundingboxarray --- .../src/container_occupancy_detector.cpp | 58 ++++++++++--------- 1 file changed, 30 insertions(+), 28 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp index a26a02593d..ac63579adc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp +++ b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp @@ -9,7 +9,6 @@ #include #include -#include #include #include #include @@ -45,13 +44,12 @@ class ContainerOccupancyDetector{ this->_containerBoxesSub = _nh.subscribe("trashbin_occupancy_detector/trashbin/boxes", 10, &ContainerOccupancyDetector::CalculateOccupancyCB, this); this->_pointCloudSub = _nh.subscribe("head_camera/depth_registered/points", 10, &ContainerOccupancyDetector::PointCloudTransformCB, this); // TODO: rename topic name this->_debugPointPub = _nh.advertise("debug_pointcloud", 10); - this->_occupancyPub = _nh.advertise("container_occupancy", 10); + this->_occupancyPub = _nh.advertise("container_occupancy", 10); // init default orientation const this->defaultOrientation.w = 1.0; this->defaultOrientation.x = 0.0; this->defaultOrientation.y = 0.0; - this->defaultOrientation.z = 0.0; - + this->defaultOrientation.z = 0.0; }; // destructor ~ContainerOccupancyDetector(){ @@ -75,41 +73,45 @@ class ContainerOccupancyDetector{ const sensor_msgs::PointCloud2 inputCloud = _transformedCloudMsg; pcl::PCLPointCloud2 pclPC2; pcl::PointCloud::Ptr pclCloud(new pcl::PointCloud); - std_msgs::Float32MultiArray occupancy; - occupancy.data.resize(msg.boxes.size()); + jsk_recognition_msgs::BoundingBoxArray boxOccupancy = msg; if (!inputCloud.data.empty()){ // convert to PCL cloud pcl_conversions::toPCL(inputCloud, pclPC2); pcl::fromPCLPointCloud2(pclPC2, *pclCloud); - for (int i=0; i filter; pcl::CropBox boxFilter; - pcl::PointCloud::Ptr boxFilteredCloud (new pcl::PointCloud); + pcl::PointCloud::Ptr boxFilteredCloud( + new pcl::PointCloud); pcl::PointXYZ minPt, maxPt; - boxFilter.setMin(Eigen::Vector4f( - (msg.boxes.at(i).pose.position.x - msg.boxes.at(i).dimensions.x / 2.0), - (msg.boxes.at(i).pose.position.y - msg.boxes.at(i).dimensions.y / 2.0), - FLOAT_MIN, - 1.0f)); - boxFilter.setMax(Eigen::Vector4f( - (msg.boxes.at(i).pose.position.x + msg.boxes.at(i).dimensions.x / 2.0), - (msg.boxes.at(i).pose.position.y + msg.boxes.at(i).dimensions.y / 2.0), - FLOAT_MAX, - 1.0f)); + float occupancy; + boxFilter.setMin(Eigen::Vector4f((msg.boxes.at(i).pose.position.x - + msg.boxes.at(i).dimensions.x / 2.0), + (msg.boxes.at(i).pose.position.y - + msg.boxes.at(i).dimensions.y / 2.0), + FLOAT_MIN, 1.0f)); + boxFilter.setMax(Eigen::Vector4f((msg.boxes.at(i).pose.position.x + + msg.boxes.at(i).dimensions.x / 2.0), + (msg.boxes.at(i).pose.position.y + + msg.boxes.at(i).dimensions.y / 2.0), + FLOAT_MAX, 1.0f)); boxFilter.setInputCloud(pclCloud); boxFilter.filter(*boxFilteredCloud); - pcl::getMinMax3D (*boxFilteredCloud, minPt, maxPt); - ROS_INFO_STREAM("maxPt.z: " << maxPt.z << std::endl); - if(maxPt.z > msg.boxes.at(i).pose.position.z + msg.boxes.at(i).dimensions.z / 2.0){ - // if some point clouds in boundingbox over bounding height - // TODO publish occupancy instead - occupancy.data.push_back(1.0); - } else { - occupancy.data.push_back(0.0); - } + pcl::getMinMax3D(*boxFilteredCloud, minPt, maxPt); + ROS_INFO_STREAM( + "box_id: " << i << " box_pos: " << msg.boxes.at(i).pose.position + << " box_height: " + << msg.boxes.at(i).pose.position.z + + msg.boxes.at(i).dimensions.z / 2.0 + << " maxPt.z: " << maxPt.z); // TODO Move to debug stream + occupancy = maxPt.z / (msg.boxes.at(i).pose.position.z + + msg.boxes.at(i).dimensions.z / 2.0); + // if some point clouds in boundingbox over bounding height + // TODO publish occupancy instead + boxOccupancy.boxes.at(i).value = occupancy; } - this->_occupancyPub.publish(occupancy); + this->_occupancyPub.publish(boxOccupancy); } else { ROS_WARN("No input point clouds."); } From fe7fd47149cd58650c871cb62137044a26b53c90 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Tue, 7 Dec 2021 18:31:15 +0900 Subject: [PATCH 087/433] modify name space --- .../launch/trashbin_occupancy_detector.launch | 6 ++++++ .../src/container_occupancy_detector.cpp | 20 +++++++++---------- .../src/trashbins_pose_estimator.cpp | 5 ++--- 3 files changed, 17 insertions(+), 14 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index 34e45e4e0b..94ab593d4c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -128,12 +128,18 @@ trashbin_w: 0.24 trashbin_h: 0.49 + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp index ac63579adc..9203bfe01a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp +++ b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp @@ -26,25 +26,23 @@ const float FLOAT_MAX = std::numeric_limits::max(); class ContainerOccupancyDetector{ private: - ros::Subscriber _containerBoxesSub; - ros::Subscriber _pointCloudSub; - ros::Publisher _debugPointPub; - ros::Publisher _occupancyPub; + std::string _inputBoxes, _inputCloud, _debugCloud, _outputBoxes; + ros::Subscriber _containerBoxesSub, _pointCloudSub; + ros::Publisher _debugPointPub, _occupancyPub; geometry_msgs::Quaternion defaultOrientation; jsk_recognition_msgs::BoundingBoxArray _containerBoxes; sensor_msgs::PointCloud2 _transformedCloudMsg; tf2_ros::Buffer _tfBuffer; tf2_ros::TransformListener* _tfListener; - // geometry_msgs::TransformStamped _transformStamped; public: // constructor ContainerOccupancyDetector(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ this->_tfListener = new tf2_ros::TransformListener(_tfBuffer); - this->_containerBoxesSub = _nh.subscribe("trashbin_occupancy_detector/trashbin/boxes", 10, &ContainerOccupancyDetector::CalculateOccupancyCB, this); - this->_pointCloudSub = _nh.subscribe("head_camera/depth_registered/points", 10, &ContainerOccupancyDetector::PointCloudTransformCB, this); // TODO: rename topic name - this->_debugPointPub = _nh.advertise("debug_pointcloud", 10); - this->_occupancyPub = _nh.advertise("container_occupancy", 10); + this->_containerBoxesSub = _nh.subscribe("input_boxes", 10, &ContainerOccupancyDetector::CalculateOccupancyCB, this); + this->_pointCloudSub = _nh.subscribe("input_cloud", 10, &ContainerOccupancyDetector::PointCloudTransformCB, this); + this->_debugPointPub = _nh.advertise("debug_cloud", 10); + this->_occupancyPub = _nh.advertise("output_boxes", 10); // init default orientation const this->defaultOrientation.w = 1.0; this->defaultOrientation.x = 0.0; @@ -99,12 +97,12 @@ class ContainerOccupancyDetector{ boxFilter.setInputCloud(pclCloud); boxFilter.filter(*boxFilteredCloud); pcl::getMinMax3D(*boxFilteredCloud, minPt, maxPt); - ROS_INFO_STREAM( + ROS_DEBUG_STREAM( "box_id: " << i << " box_pos: " << msg.boxes.at(i).pose.position << " box_height: " << msg.boxes.at(i).pose.position.z + msg.boxes.at(i).dimensions.z / 2.0 - << " maxPt.z: " << maxPt.z); // TODO Move to debug stream + << " maxPt.z: " << maxPt.z); occupancy = maxPt.z / (msg.boxes.at(i).pose.position.z + msg.boxes.at(i).dimensions.z / 2.0); // if some point clouds in boundingbox over bounding height diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp index 633b40f495..0adecd9ffb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp +++ b/jsk_fetch_robot/jsk_fetch_startup/src/trashbins_pose_estimator.cpp @@ -23,9 +23,8 @@ class TrashbinsPoseEstimator{ _pnh.getParam("trashbin_l", this->_trashbinL); _pnh.getParam("trashbin_w", this->_trashbinW); _pnh.getParam("trashbin_h", this->_trashbinH); - this->_trashbinHandleSub = _nh.subscribe("trashbin_handle/boxes", 10, &TrashbinsPoseEstimator::DrawVirtualTrashbinContainerCB, this); - // this->_pointCloud = _nh.subscribe("points", 10, &TrashbinOccupancyDetector::CalculateOccupancyCB, this); - this->_virtualTrashbinContainerPub = _nh.advertise("trashbin/boxes", 10); + this->_trashbinHandleSub = _nh.subscribe("input", 10, &TrashbinsPoseEstimator::DrawVirtualTrashbinContainerCB, this); + this->_virtualTrashbinContainerPub = _nh.advertise("output", 10); // init default orientation const this->defaultOrientation.w = 1.0; this->defaultOrientation.x = 0.0; From d9a9a66fc27db02638fbc8f309cd0f58aa455c83 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 8 Dec 2021 00:02:05 +0900 Subject: [PATCH 088/433] Publish CO2 concentration in go-to-kitchen app --- .../apps/go_to_kitchen/go_to_kitchen.xml | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 60d62199ec..e79815ba02 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -19,6 +19,15 @@ + + + + + port: /dev/rfcomm0 + baud: 115200 + + + From 7c85113178224e802d5181c4e134a27705441bfe Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 9 Dec 2021 20:11:56 +0900 Subject: [PATCH 089/433] add TODO --- .../launch/trashbin_occupancy_detector.launch | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index 94ab593d4c..b249e560b4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -123,9 +123,15 @@ + + + + + + - trashbin_l: 0.34 - trashbin_w: 0.24 + trashbin_l: 0.3 + trashbin_w: 0.2 trashbin_h: 0.49 From fc53ff41881bcd50bbf3552baafd1c20a0ff04f9 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 19 Dec 2021 17:25:47 +0900 Subject: [PATCH 090/433] [jsk_fetch_startup] Add take-photo function --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index df0f96174d..19a3d7ff92 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -10,6 +10,7 @@ (ros::load-ros-manifest "jsk_robot_startup") (ros::load-ros-manifest "jsk_recognition_msgs") (ros::load-ros-manifest "power_msgs") +(ros::load-ros-manifest "sensor_msgs") (defparameter *dock-action* nil) (defparameter *undock-action* nil) From 78ac7129ea079e886e7c7553d86148556d2f00fe Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 19 Dec 2021 17:26:18 +0900 Subject: [PATCH 091/433] [jsk_fetch_startup] Add trashcan_inside picture --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index f2d6f083bd..0fed92f1ea 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -112,6 +112,7 @@ plugins: - /tmp/go_to_kitchen_rviz.avi - /tmp/go_to_kitchen_audio.wav - /tmp/go_to_kitchen_rosbag.bag + - /tmp/trashcan_inside.jpg upload_file_titles: - go_to_kitchen_result.yaml - go_to_kitchen_head_camera.avi @@ -120,6 +121,7 @@ plugins: - go_to_kitchen_rviz.avi - go_to_kitchen_audio.wav - go_to_kitchen_rosbag.bag + - trashcan_inside.jpg upload_parents_path: fetch_go_to_kitchen upload_server_name: /gdrive_server - name: tweet_notifier_plugin From e4e6a429247eb41ee6c0a8724e96a8b7f100989a Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 19 Dec 2021 18:06:35 +0900 Subject: [PATCH 092/433] Add trashcan occupancy detection to navigation-utils.l --- .../euslisp/navigation-utils.l | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 19a3d7ff92..a8c6272b6f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -402,6 +402,25 @@ Args: location (format nil "CO2 concentration is ~A ppm" (send msg :data)))))) +(defun notify-trashcan-occupancy (&key (location "kitchen")) + (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detect/trashbin/occupancy" + jsk_recognition_msgs::BoundingBoxArray + :timeout 3000)) + (occupancy (send msg :boxes :value)) + (notify-text nil)) + (when occupancy + (ros::ros-info + (format nil "Notify app that the occupancy of trash can is measured.")) + (if (> occupancy 1.0) + (setq notify-text "Trashcan occupancy is full.") + (setq notify-text "Trashcan occupancy is not full.")) + (notify-app "trashcan occupancy" + (ros::time-now) + location + (format nil "~A Trashcan occupancy is ~A%." + notify-text + (* 100 occupancy)))))) + (defun inspect-kitchen (&key (tweet t)) (report-move-to-sink-front-success) (if tweet @@ -572,6 +591,7 @@ Args: (ros::publish "/photo_taken" img)) (take-photo "trashcan_inside.jpg") (notify-recognition :location "trash cans inside") + (notify-trashcan-occupancy :location "trash can") (send *ri* :go-pos-unsafe -0.2 0 0)) (progn (notify-recognition :location "trash cans")))) From 4c4b1ce4728534578b83f391c0a978f365d6928f Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 19 Dec 2021 18:07:08 +0900 Subject: [PATCH 093/433] Add trashcan occupancy detection to go_to_kitchen.xml --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index e79815ba02..09c9f3cf28 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -28,6 +28,9 @@ + + + From 998736439038e8861ebe7ea050b147107a56788b Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 21 Dec 2021 17:33:57 +0900 Subject: [PATCH 094/433] not displaying burnable_trashbin_label_extractor window as default --- .../jsk_fetch_startup/launch/trashbin_occupancy_detector.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index b249e560b4..cdae23dda3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -161,6 +161,7 @@ + From 56bd23fbe3d62dbb30c497fe695a95e975822140 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 21 Dec 2021 17:37:02 +0900 Subject: [PATCH 095/433] fix topic name and topic method --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index a8c6272b6f..51d4cfd57f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -403,10 +403,10 @@ Args: (format nil "CO2 concentration is ~A ppm" (send msg :data)))))) (defun notify-trashcan-occupancy (&key (location "kitchen")) - (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detect/trashbin/occupancy" + (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/trashbin/occupancy" jsk_recognition_msgs::BoundingBoxArray :timeout 3000)) - (occupancy (send msg :boxes :value)) + (occupancy (send (elt (send msg :boxes) 0) :value)) (notify-text nil)) (when occupancy (ros::ros-info From a07281c5eb1fe1575b4fe5d43a203ce16395c092 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 21 Dec 2021 17:37:25 +0900 Subject: [PATCH 096/433] update notify text --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 51d4cfd57f..825f6180f0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -412,14 +412,14 @@ Args: (ros::ros-info (format nil "Notify app that the occupancy of trash can is measured.")) (if (> occupancy 1.0) - (setq notify-text "Trashcan occupancy is full.") - (setq notify-text "Trashcan occupancy is not full.")) + (setq notify-text "Trashcan is full.") + (setq notify-text "Trashcan is not full.")) (notify-app "trashcan occupancy" (ros::time-now) location - (format nil "~A Trashcan occupancy is ~A%." + (format nil "~A Trashcan occupancy is ~A" notify-text - (* 100 occupancy)))))) + occupancy))))) (defun inspect-kitchen (&key (tweet t)) (report-move-to-sink-front-success) From 72789616aef24ee78c9f0411ec6dc5881b5a5c40 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 22 Dec 2021 16:33:37 +0900 Subject: [PATCH 097/433] [jsk_fetch_startup] Auto-dock when failing to move to sink front --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 825f6180f0..d57cbd6c1f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -700,7 +700,7 @@ Args: (:move-to-sink-front -> :inspect-kitchen) (:move-to-sink-front !-> :report-move-to-sink-front-failure) ;;(:inspect-kitchen -> :auto-dock) - ;;(:report-move-to-sink-front-failure -> :auto-dock) + (:report-move-to-sink-front-failure -> :auto-dock) (:inspect-kitchen -> :move-to-trashcan-front) (:move-to-trashcan-front -> :inspect-trashcan) (:move-to-trashcan-front !-> :report-move-to-trashcan-front-failure) From 7fea24fd6a7694d6ae310063ab078ab587ac898b Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 22 Dec 2021 17:06:59 +0900 Subject: [PATCH 098/433] [jsk_fetch_startup] Add behavior when auto-dock fails --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index d57cbd6c1f..90222611c9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -707,6 +707,8 @@ Args: (:inspect-trashcan -> :auto-dock) (:report-move-to-trashcan-front-failure -> :auto-dock) (:auto-dock -> :room-light-off) + (:auto-dock !-> :auto-dock-failure) + (:auto-dock-failure -> :room-light-off) (:room-light-off -> :finish) (:finish -> t) (:finish !-> nil)) From 6894260621eb7599025a4563728e0cff8cdc4885 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sat, 25 Dec 2021 22:03:34 +0900 Subject: [PATCH 099/433] [jsk_fetch_startup] Fix the process for no recognition result of trashcan occupancy --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 90222611c9..9896013ed3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -406,9 +406,10 @@ Args: (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/trashbin/occupancy" jsk_recognition_msgs::BoundingBoxArray :timeout 3000)) - (occupancy (send (elt (send msg :boxes) 0) :value)) + (occupancy nil) (notify-text nil)) - (when occupancy + (when msg + (setq occcupancy (send (elt (send msg :boxes) 0) :value)) (ros::ros-info (format nil "Notify app that the occupancy of trash can is measured.")) (if (> occupancy 1.0) From 202e2a6fef272528910838bb0a224b80ed16c5b7 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sat, 25 Dec 2021 22:39:32 +0900 Subject: [PATCH 100/433] [jsk_fetch_startup] Remove setq in notify-trashcan-occupancy --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 9896013ed3..983fff752b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -406,15 +406,13 @@ Args: (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/trashbin/occupancy" jsk_recognition_msgs::BoundingBoxArray :timeout 3000)) - (occupancy nil) - (notify-text nil)) - (when msg - (setq occcupancy (send (elt (send msg :boxes) 0) :value)) + (occupancy (if msg (send (elt (send msg :boxes) 0) :value))) + (notify-text (if occupancy (if (> occupancy 1.0) + "Trashcan is full." + "Trashcan is not full.")))) + (when occupancy (ros::ros-info (format nil "Notify app that the occupancy of trash can is measured.")) - (if (> occupancy 1.0) - (setq notify-text "Trashcan is full.") - (setq notify-text "Trashcan is not full.")) (notify-app "trashcan occupancy" (ros::time-now) location From 05a6f96bdc7f4dd52edc272955a61d2481c02907 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sat, 25 Dec 2021 22:40:03 +0900 Subject: [PATCH 101/433] [jsk_fetch_startup] Add occupancy value to ros-info --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 983fff752b..c672b8254c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -412,7 +412,7 @@ Args: "Trashcan is not full.")))) (when occupancy (ros::ros-info - (format nil "Notify app that the occupancy of trash can is measured.")) + (format nil "Notify app that the occupancy of trash can is measured. ~A." occupancy)) (notify-app "trashcan occupancy" (ros::time-now) location From f5cc4e6937409bbc024d373e663cf93ff879c52f Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 7 Jan 2022 08:17:05 +0900 Subject: [PATCH 102/433] [jsk_fetch_startup] catkin clean libcmt before build in daily update_workspace.sh --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index f27e401366..bd90be1d83 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -13,7 +13,7 @@ wstool foreach --git 'git stash' wstool update --delete-changed-uris WSTOOL_UPDATE_RESULT=$? cd $HOME/ros/melodic -catkin clean aques_talk collada_urdf_jsk_patch -y +catkin clean aques_talk collada_urdf_jsk_patch libcmt -y catkin init catkin config -DCMAKE_BUILD_TYPE=Release catkin build From 546df451f60df01840d55e4514f1d4c4d0016a15 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 24 Jan 2022 18:33:53 +0900 Subject: [PATCH 103/433] [jsk_fetch_startup] storage warning --- .../scripts/storage_warning.sh | 35 +++++++++++++++++++ 1 file changed, 35 insertions(+) create mode 100755 jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh new file mode 100755 index 0000000000..30d6a7a038 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh @@ -0,0 +1,35 @@ +#!/usr/bin/env bash + +MAIL_BODY="" + +# Check storage percentage +STORAGE_PERCENTAGE=`df -h / | awk 'NR==2 {print $5}' | sed -e 's/\%//g'` + +# If storage_percentage greater than 80% +if [ $STORAGE_PERCENTAGE -gt 80 ]; then + MAIL_BODY=$MAIL_BODY"Storage usage is ${STORAGE_PERCENTAGE}. Please remove unnecessary files.\n" + + # In root directory + ROOTDIR_STORAGE=`du -h -d 0 /* 2>/dev/null | sort -hr` + MAIL_BODY=$MAIL_BODY"In root directory:\n" + MAIL_BODY=$MAIL_BODY"${ROOTDIR_STORAGE}\n" + + # In home directory + HOMEDIR_STORAGE=`du -h -d 0 /home/* 2>/dev/null | sort -hr` + MAIL_BODY=$MAIL_BODY"In home directory:\n" + MAIL_BODY=$MAIL_BODY"${HOMEDIR_STORAGE}\n" +fi + +if [ -n "$MAIL_BODY" ]; then + rostopic pub -1 /email jsk_robot_startup/Email "header: + seq: 0 + stamp: {secs: 0, nsecs: 0} + frame_id: '' +subject: 'Storage warning' +body: '$MAIL_BODY' +sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' +receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' +smtp_server: '' +smtp_port: '' +attached_files: ''" +fi From 0ec117699f87bc95918cd27cbff8fc3b13edaa02 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 24 Jan 2022 20:06:13 +0900 Subject: [PATCH 104/433] [jsk_fetch_startup] fix change line bug --- .../scripts/storage_warning.sh | 30 ++++++++++--------- 1 file changed, 16 insertions(+), 14 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh index 30d6a7a038..76af2e39ed 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh @@ -1,35 +1,37 @@ #!/usr/bin/env bash -MAIL_BODY="" - # Check storage percentage STORAGE_PERCENTAGE=`df -h / | awk 'NR==2 {print $5}' | sed -e 's/\%//g'` # If storage_percentage greater than 80% if [ $STORAGE_PERCENTAGE -gt 80 ]; then - MAIL_BODY=$MAIL_BODY"Storage usage is ${STORAGE_PERCENTAGE}. Please remove unnecessary files.\n" - + SEND_EMAIL=1 # In root directory - ROOTDIR_STORAGE=`du -h -d 0 /* 2>/dev/null | sort -hr` - MAIL_BODY=$MAIL_BODY"In root directory:\n" - MAIL_BODY=$MAIL_BODY"${ROOTDIR_STORAGE}\n" - + ROOTDIR_STORAGE=`du -h -d 0 /* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` # In home directory - HOMEDIR_STORAGE=`du -h -d 0 /home/* 2>/dev/null | sort -hr` - MAIL_BODY=$MAIL_BODY"In home directory:\n" - MAIL_BODY=$MAIL_BODY"${HOMEDIR_STORAGE}\n" + HOMEDIR_STORAGE=`du -h -d 0 /home/* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` fi -if [ -n "$MAIL_BODY" ]; then +if [ -n "$SEND_EMAIL" ]; then rostopic pub -1 /email jsk_robot_startup/Email "header: seq: 0 stamp: {secs: 0, nsecs: 0} frame_id: '' subject: 'Storage warning' -body: '$MAIL_BODY' +body: 'Storage usage is ${STORAGE_PERCENTAGE}%. Please remove unnecessary files. + + +In root directory: + +${ROOTDIR_STORAGE} + + +In home directory: + +${HOMEDIR_STORAGE}' sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' smtp_server: '' smtp_port: '' -attached_files: ''" +attached_files: []" fi From a056b93743f69631610297a8be56e4f503113243 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 24 Jan 2022 20:15:32 +0900 Subject: [PATCH 105/433] [jsk_fetch_startup] add storage_warn to cron job --- jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf index 839bc9e138..a4a6893521 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf @@ -1 +1,2 @@ 0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh &> /home/fetch/ros/melodic/update_workspace.log" +0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup storage_warning.sh &> /home/fetch/ros/melodic/storage_warning.log" From f9195aab1606d896e7d9a3e46fb5bb695bc571b2 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 26 Jan 2022 14:39:07 +0900 Subject: [PATCH 106/433] std output, fix cron schedule --- jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf | 2 +- jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf index a4a6893521..03fadaf878 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_fetch.conf @@ -1,2 +1,2 @@ 0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup update_workspace.sh &> /home/fetch/ros/melodic/update_workspace.log" -0 3 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup storage_warning.sh &> /home/fetch/ros/melodic/storage_warning.log" +0 5 * * * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup storage_warning.sh &> /home/fetch/ros/melodic/storage_warning.log" diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh index 76af2e39ed..697a396c71 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh @@ -34,4 +34,5 @@ receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' smtp_server: '' smtp_port: '' attached_files: []" + echo -e "Storage percentage: $STORAGE_PERCENTAGE\n Root directory: $ROOTDIR_STORAGE\n Home directory: $HOMEDIR_STORAGE\n" fi From 59b474069bf5e45eb030911c3f7e518f3f0f57be Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Tue, 1 Feb 2022 14:58:10 +0900 Subject: [PATCH 107/433] [jsk_fetch_startup] echo storage percentage even not greater than 80 --- jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh index 697a396c71..10f059f0b4 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/storage_warning.sh @@ -10,6 +10,8 @@ if [ $STORAGE_PERCENTAGE -gt 80 ]; then ROOTDIR_STORAGE=`du -h -d 0 /* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` # In home directory HOMEDIR_STORAGE=`du -h -d 0 /home/* 2>/dev/null | sort -hr | awk '{print $2 " " $1}'` +else + echo -e "No problem with the storace capacity. Storage percentage: $STORAGE_PERCENTAGE" fi if [ -n "$SEND_EMAIL" ]; then From ec87fde813dcb5c09ed7180f439d163cf8c953c2 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Mon, 21 Mar 2022 13:19:48 +0900 Subject: [PATCH 108/433] [fetch] Use run instead of launch in single node apps --- jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app | 2 +- .../jsk_fetch_startup/apps/call_k_okada/call_k_okada.app | 2 +- jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app | 2 +- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 +- .../jsk_fetch_startup/apps/hello_world/hello_world.app | 2 +- jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app | 2 +- jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app | 2 +- .../apps/software_runstop/software_runstop.app | 3 ++- .../jsk_fetch_startup/apps/speak_battery/speak_battery.app | 2 +- .../jsk_fetch_startup/apps/time_signal/time_signal.app | 2 +- jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app | 2 +- jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app | 2 +- .../jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app | 3 ++- 13 files changed, 15 insertions(+), 13 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app index d628e8e57a..fd09baa3eb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/auto_dock/auto_dock.app @@ -1,5 +1,5 @@ display: Fetch auto dock platform: fetch -launch: jsk_fetch_startup/auto_dock.xml +run: jsk_fetch_startup/auto-dock.l interface: jsk_fetch_startup/auto_dock.interface icon: jsk_fetch_startup/auto_dock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app b/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app index acfcb25162..4577ac55ae 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/call_k_okada/call_k_okada.app @@ -1,5 +1,5 @@ display: Call k-okada platform: fetch -launch: jsk_fetch_startup/call_k_okada.xml +run: jsk_fetch_startup/call-k-okada.l interface: jsk_fetch_startup/call_k_okada.interface icon: jsk_fetch_startup/call_k_okada.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app index 916d8fb34c..6c034bd9aa 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/dock/dock.app @@ -1,5 +1,5 @@ display: Fetch dock platform: fetch -launch: jsk_fetch_startup/dock.xml +run: jsk_fetch_startup/dock.l interface: jsk_fetch_startup/dock.interface icon: jsk_fetch_startup/dock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 0fed92f1ea..c9fc5515ff 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -1,6 +1,6 @@ display: Go to kitchen platform: fetch -launch: jsk_fetch_startup/go_to_kitchen.xml +run: jsk_fetch_startup/go-to-kitchen.l interface: jsk_fetch_startup/go_to_kitchen.interface icon: jsk_fetch_startup/go_to_kitchen.png timeout: 1200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app b/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app index 7b9b90ea81..a2dc73bd13 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/hello_world/hello_world.app @@ -1,5 +1,5 @@ display: Fetch hello world platform: fetch -launch: jsk_fetch_startup/hello_world.xml +run: jsk_robot_startup/boot_sound.py interface: jsk_fetch_startup/hello_world.interface icon: jsk_fetch_startup/hello_world.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app b/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app index daf7f86708..f8aeb69c3c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/light_off/light_off.app @@ -1,6 +1,6 @@ display: Fetch light off platform: fetch -launch: jsk_fetch_startup/light_off.xml +run: jsk_fetch_startup/light-off.l interface: jsk_fetch_startup/light_off.interface icon: jsk_fetch_startup/light_off.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app b/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app index ef63123502..eb66297f74 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/light_on/light_on.app @@ -1,6 +1,6 @@ display: Fetch light on platform: fetch -launch: jsk_fetch_startup/light_on.xml +run: jsk_fetch_startup/light-on.l interface: jsk_fetch_startup/light_on.interface icon: jsk_fetch_startup/light_on.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app b/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app index 6c86c77347..ed4a25c745 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/software_runstop/software_runstop.app @@ -1,5 +1,6 @@ display: Fetch software runstop platform: fetch -launch: jsk_fetch_startup/software_runstop.xml +run: rostopic/rostopic +run_args: "pub -1 /enable_software_runstop std_msgs/Bool 'data: true'" interface: jsk_fetch_startup/software_runstop.interface icon: jsk_fetch_startup/software_runstop.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app index cb4d371e00..2dc162d470 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/speak_battery/speak_battery.app @@ -1,6 +1,6 @@ display: Speak battery platform: fetch -launch: jsk_fetch_startup/speak_battery.xml +run: jsk_fetch_startup/speak-battery.l interface: jsk_fetch_startup/speak_battery.interface icon: jsk_fetch_startup/speak_battery.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index 07c42622d4..6137ee226b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -1,6 +1,6 @@ display: Speak time signal platform: fetch -launch: jsk_fetch_startup/time_signal.xml +run: jsk_fetch_startup/time_signal.py interface: jsk_fetch_startup/time_signal.interface icon: jsk_fetch_startup/time_signal.png timeout: 120 diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app index e95306664e..28d7cc4bf1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/tweet/tweet.app @@ -1,6 +1,6 @@ display: Fetch tweet platform: fetch -launch: jsk_fetch_startup/tweet.xml +run: jsk_fetch_startup/tweet.l interface: jsk_fetch_startup/tweet.interface icon: jsk_fetch_startup/tweet.png plugins: diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app b/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app index da845f0a25..78a4b30891 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/undock/undock.app @@ -1,5 +1,5 @@ display: Fetch undock platform: fetch -launch: jsk_fetch_startup/undock.xml +run: jsk_fetch_startup/undock.l interface: jsk_fetch_startup/undock.interface icon: jsk_fetch_startup/undock.png diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app b/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app index ded1914d18..210ba6e4bd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app @@ -1,6 +1,7 @@ display: Welcome to jsk platform: fetch -launch: jsk_fetch_startup/welcome_to_jsk.xml +run: welcome_to_jsk_fetch/welcome-to-jsk.l +run_args: '"(progn (init) (give-bag))"' interface: jsk_fetch_startup/welcome_to_jsk.interface icon: jsk_fetch_startup/welcome_to_jsk.png plugins: From 5bedcc2006bdacd4b9e2d8c00ef3aec75484c841 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Wed, 23 Mar 2022 14:21:01 +0900 Subject: [PATCH 109/433] [fetch] Update luminance threshold --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 5fd2e74b38..4708d29734 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -253,6 +253,9 @@ + + luminance_threshold: 40 + From 645fec3fcf633804084c977a475f595833af14f9 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Fri, 25 Mar 2022 17:52:13 +0900 Subject: [PATCH 110/433] [fetch] Update luminance threshold (again) --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 4708d29734..b2fcf24d38 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -254,7 +254,7 @@ - luminance_threshold: 40 + luminance_threshold: 70 From 10dd0b3416585145f386d220bdd77a8593fc549f Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Tue, 5 Apr 2022 16:03:51 +0900 Subject: [PATCH 111/433] Suppress warnings when using :fast in :angle-vector --- jsk_fetch_robot/fetcheus/fetch-interface.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l index 5dd33840df..78f80f62fa 100644 --- a/jsk_fetch_robot/fetcheus/fetch-interface.l +++ b/jsk_fetch_robot/fetcheus/fetch-interface.l @@ -131,8 +131,8 @@ Example usage: (subseq args (+ (position :use-torso args) 2)))))) (return-from :angle-vector (send* self :angle-vector-raw av tm ctype start-time args))) ;; - (when (not (numberp tm)) - (ros::warn ":angle-vector tm is not a number, use :angle-vector av tm args")) + (when (and (not (numberp tm)) (not (eql tm :fast))) + (ros::warn ":angle-vector tm is not a number, use :angle-vector av tm args~%")) (send* self :angle-vector-motion-plan av :ctype ctype :move-arm :rarm :total-time tm :start-offset-time (if start-offset-time start-offset-time start-time) :clear-velocities clear-velocities :use-torso use-torso args))) From e12b745ac3fec5bdef3da2d16b097afc8810c7d7 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Tue, 5 Apr 2022 22:28:59 +0900 Subject: [PATCH 112/433] Add :use-base to fetch-utils :inverse-kinematics --- jsk_fetch_robot/fetcheus/fetch-utils.l | 34 ++++++++++++++++++++++---- 1 file changed, 29 insertions(+), 5 deletions(-) diff --git a/jsk_fetch_robot/fetcheus/fetch-utils.l b/jsk_fetch_robot/fetcheus/fetch-utils.l index ea4a1d27e2..67932a47fe 100644 --- a/jsk_fetch_robot/fetcheus/fetch-utils.l +++ b/jsk_fetch_robot/fetcheus/fetch-utils.l @@ -5,16 +5,40 @@ (defmethod fetch-robot (:inverse-kinematics - (target-coords &rest args &key link-list move-arm (use-torso t) move-target &allow-other-keys) + (target-coords &rest args &key link-list move-arm (use-torso t) + use-base (start-coords (send self :copy-worldcoords)) + (base-range (list :min #f(-30 -30 -30) + :max #f( 30 30 30))) + move-target &allow-other-keys) (unless move-arm (setq move-arm :rarm)) (unless move-target (setq move-target (send self :rarm :end-coords))) (unless link-list (setq link-list (send self :link-list (send move-target :parent) (unless use-torso (car (send self :rarm)))))) - (send-super* :inverse-kinematics target-coords - :move-target move-target - :link-list link-list - args)) + (cond + (use-base + (let ((diff-pos-rot + (concatenate float-vector + (send start-coords :difference-position self) + (send start-coords :difference-rotation self)))) + (send self :move-to start-coords :world) + (with-append-root-joint + (ll self link-list + :joint-class omniwheel-joint + :joint-args base-range) + (send (caar ll) :joint :joint-angle + (float-vector (elt diff-pos-rot 0) + (elt diff-pos-rot 1) + (rad2deg (elt diff-pos-rot 5)))) + (send-super* :inverse-kinematics target-coords + :move-target move-target + :link-list ll ;; link-list + args)))) + (t + (send-super* :inverse-kinematics target-coords + :move-target move-target + :link-list link-list + args)))) (:go-grasp (&key (pos 0)) ;; pos is between 0.0 and 0.1 (send self :l_gripper_finger_joint :joint-angle (/ (* pos 1000) 2)) ;; m -> mm From 1216a9f61aa509ba29487bde63006cda8e6571b1 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 7 Apr 2022 15:00:24 +0900 Subject: [PATCH 113/433] [jsk_fetch_startup] Fix go-to-kitchen launch app --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index c9fc5515ff..0fed92f1ea 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -1,6 +1,6 @@ display: Go to kitchen platform: fetch -run: jsk_fetch_startup/go-to-kitchen.l +launch: jsk_fetch_startup/go_to_kitchen.xml interface: jsk_fetch_startup/go_to_kitchen.interface icon: jsk_fetch_startup/go_to_kitchen.png timeout: 1200 From ab9fb893efe97b745733d994a389e6ddd4aba76e Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 14 Apr 2022 19:22:29 +0900 Subject: [PATCH 114/433] [jsk_fetch_robot] Update README.md --- jsk_fetch_robot/README.md | 29 +++++++++++++++++++++-------- 1 file changed, 21 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 9aab1b786d..732edbd5a6 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -33,21 +33,17 @@ ## How to Run +### Setup Environment (For Remote PC) -### Setup Environment - -First, you need to install ros. For ros indigo, please refer to install guide like [here](http://wiki.ros.org/indigo/Installation/Ubuntu) +First, you need to install ROS. For ROS melodic, please refer to install guide like [here](http://wiki.ros.org/melodic/Installation/Ubuntu). +Please make sure your ROS Distribution is indigo, kinetic or melodic. ```bash mkdir -p catkin_ws/src cd catkin_ws/src wstool init . wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -y -if [[ $ROS_DISTRO =~ ^(indigo|kinetic|melodic)$ ]]; then - wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO -else - echo "Your ROS distribution $ROS_DISTRO is not supported." -fi +wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO wstool update -t . source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src @@ -56,6 +52,23 @@ catkin build fetcheus jsk_fetch_startup source devel/setup.bash ``` +#### Setup Environment (For Robot Internal PC, only for advanced developer) + +```bash +mkdir -p catkin_ws/src +cd catkin_ws/src +wstool init . +wstool set --git jsk-ros-pkg/jsk_robot https://github.com/knorth55/jsk_robot.git -v fetch15 -y +wstool update -t . +wstool merge -t . jsk-ros-pkg/jsk_robot/jsk_fetch_robot/jsk_fetch.rosinstall.$ROS_DISTRO +wstool update -t . +source /opt/ros/$ROS_DISTRO/setup.bash +rosdep install -y -r --from-paths . --ignore-src +cd ../ +catkin build +source devel/setup.bash +``` + ### Connecting to Fetch You need to install `ros-indigo-jsk-tools` to use `rosset*` tools, otherwise use setenv command From 5d145b5e6629c06b5c93f2d682e54bf77d756e43 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 15 Apr 2022 10:01:15 +0900 Subject: [PATCH 115/433] [jsk_fetch_startup] update README.md --- jsk_fetch_robot/jsk_fetch_startup/README.md | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index a509050a34..e7baff4793 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -8,12 +8,22 @@ rosrun jsk_fetch_startup install_udev.sh ``` #### For realsense -udev rule have to be manually installed according to [this issue](https://github.com/IntelRealSense/realsense-ros/issues/1426) when using realsense-ros from ROS repository. + +Before start this, remove `librealsense2` and `realsense2-ros` from ROS repository and set not to be installed. + +```bash +sudo apt purge ros-melodic-librealsense2* ros-melodic-realsense* +sudo apt-mark hold ros-melodic-librealsense2 ros-melodic-realsense2-camera +``` + +After that, please add Intel repository and install `librealsense2` packages. (see [this page](https://github.com/IntelRealSense/librealsense/blob/master/doc/distribution_linux.md#installing-the-packages)) ```bash -wget https://github.com/IntelRealSense/librealsense/raw/master/config/99-realsense-libusb.rules -sudo mv 99-realsense-libusb.rules /etc/udev/rules.d/ -sudo udevadm control --reload-rules && sudo udevadm trigger +sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE || sudo apt-key adv --keyserver hkp://keyserver.ubuntu.com:80 --recv-key F6E65AC044F831AC80A06380C8B3A55A6F3EFCDE +sudo add-apt-repository "deb https://librealsense.intel.com/Debian/apt-repo $(lsb_release -cs) main" -u +sudo apt install librealsense2=2.45.0-0~realsense0.4551 +sudo apt install librealsense2-dev=2.45.0-0~realsense0.4551 +sudo apt-mark hold librealsense2 librealsense2-dev ``` ### supervisor From 8bff8ace3d1b47ce0bff0a79c06ee3158855e24f Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 15 Apr 2022 18:15:21 +0900 Subject: [PATCH 116/433] [jsk_fetch_startup] update workspace script --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index bd90be1d83..a81e23d1c0 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -8,10 +8,14 @@ LOGFILE=$HOME/ros/melodic/update_workspace.txt set -x # Update workspace cd $HOME/ros/melodic/src +if [ -e $HOME/ros/melodic/src/.rosinstall]; then + rm $HOME/ros/melodic/src/.rosinstall +fi ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $HOME/ros/melodic/src/.rosinstall wstool foreach --git 'git stash' wstool update --delete-changed-uris WSTOOL_UPDATE_RESULT=$? +# Build workspace cd $HOME/ros/melodic catkin clean aques_talk collada_urdf_jsk_patch libcmt -y catkin init From 3eb20610eae63f1f67911738305f8e91b9c6da37 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sat, 16 Apr 2022 20:32:32 +0900 Subject: [PATCH 117/433] [jsk_fetch_startup] update update_workspace.sh --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index a81e23d1c0..58ed7b710b 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -14,6 +14,8 @@ fi ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $HOME/ros/melodic/src/.rosinstall wstool foreach --git 'git stash' wstool update --delete-changed-uris +wstool foreach --git 'branch-name=$(git rev-parse --abbrev-ref HEAD) && git reset --hard HEAD && git checkout origin/$branch-name && git branch -D $branch-name && git checkout $branch-name' # Forcefully checkout specified branch +wstool update WSTOOL_UPDATE_RESULT=$? # Build workspace cd $HOME/ros/melodic From 4bd9532406feb7ec7fdc4215bcbe8d3697ca79b4 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sat, 16 Apr 2022 20:34:21 +0900 Subject: [PATCH 118/433] [jsk_fetch_startup] remove redundant section --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 3 --- 1 file changed, 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 58ed7b710b..4035e45eb6 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -8,9 +8,6 @@ LOGFILE=$HOME/ros/melodic/update_workspace.txt set -x # Update workspace cd $HOME/ros/melodic/src -if [ -e $HOME/ros/melodic/src/.rosinstall]; then - rm $HOME/ros/melodic/src/.rosinstall -fi ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $HOME/ros/melodic/src/.rosinstall wstool foreach --git 'git stash' wstool update --delete-changed-uris From ddfc97f77ed1468c30a72041e11cffa857a51ac0 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Mon, 18 Apr 2022 14:46:32 +0900 Subject: [PATCH 119/433] set lower battery charge warning threshold --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index b2fcf24d38..3d3e47950c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -34,7 +34,7 @@ respawn="true" output="screen" if="$(arg battery_warning)"> duration: 180 - charge_level_threshold: 80.0 + charge_level_threshold: 65.0 shutdown_level_threshold: 60.0 charge_level_step: 10.0 volume: 1.0 From d195222d66db676cd5aa892bf582005214e54c3b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 18 Apr 2022 14:39:53 +0900 Subject: [PATCH 120/433] [jsk_fetch_startup] parameterize workspace path and make it as argument --- .../scripts/update_workspace.sh | 35 ++++++++++++++++--- 1 file changed, 30 insertions(+), 5 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 4035e45eb6..a2d9892cf5 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -1,21 +1,46 @@ #!/usr/bin/env bash -. $HOME/ros/melodic/devel/setup.bash +function usage() +{ + echo "Usage: $0 [-w workspace_directory] [-h]" +} + +WORKSPACE=$HOME/ros/melodic/ + +while getopts hw: OPT +do + case $OPT in + w) + WORKSPACE=$(cd $(dirname $OPTARG) && pwd)/$(basename $OPTARG) + ;; + h) + usage + exit 1 + ;; + esac +done + +if [ ! -e $WORKSPACE ]; then + echo "No workspace $WORKSPACE" + exit 1 +fi + +. $WORKSPACE/devel/setup.bash # Filename should end with .txt to preview the contents in a web browser -LOGFILE=$HOME/ros/melodic/update_workspace.txt +LOGFILE=$WORKSPACE/update_workspace.txt { set -x # Update workspace -cd $HOME/ros/melodic/src -ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $HOME/ros/melodic/src/.rosinstall +cd $WORKSPACE/src +ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall wstool foreach --git 'git stash' wstool update --delete-changed-uris wstool foreach --git 'branch-name=$(git rev-parse --abbrev-ref HEAD) && git reset --hard HEAD && git checkout origin/$branch-name && git branch -D $branch-name && git checkout $branch-name' # Forcefully checkout specified branch wstool update WSTOOL_UPDATE_RESULT=$? # Build workspace -cd $HOME/ros/melodic +cd $WORKSPACE catkin clean aques_talk collada_urdf_jsk_patch libcmt -y catkin init catkin config -DCMAKE_BUILD_TYPE=Release From bc8cb557475ca2778ecf117f12784c6b4d71762b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 18 Apr 2022 15:02:37 +0900 Subject: [PATCH 121/433] [jsk_fetch_startup] update update_workspace.sh --- .../jsk_fetch_startup/scripts/update_workspace.sh | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index a2d9892cf5..5a5041c424 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -32,12 +32,12 @@ LOGFILE=$WORKSPACE/update_workspace.txt { set -x # Update workspace -cd $WORKSPACE/src +wstool -t $WORKSPACE/src foreach --git 'git stash' +wstool -t $WORKSPACE/src update jsk-ros-pkg/jsk_robot ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall -wstool foreach --git 'git stash' -wstool update --delete-changed-uris -wstool foreach --git 'branch-name=$(git rev-parse --abbrev-ref HEAD) && git reset --hard HEAD && git checkout origin/$branch-name && git branch -D $branch-name && git checkout $branch-name' # Forcefully checkout specified branch -wstool update +wstool -t $WORKSPACE/src update --delete-changed-uris +wstool -t $WORKSPACE/src foreach --git 'branch-name=$(git rev-parse --abbrev-ref HEAD) && git reset --hard HEAD && git checkout origin/$branch-name && git branch -D $branch-name && git checkout $branch-name' # Forcefully checkout specified branch +wstool -t $WORKSPACE/src update WSTOOL_UPDATE_RESULT=$? # Build workspace cd $WORKSPACE From 5073da52549dbcad82ac83db360666543414a8c2 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 18 Apr 2022 15:08:08 +0900 Subject: [PATCH 122/433] [jsk_fetch_startup] fix --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 5a5041c424..fe716ed534 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -36,7 +36,7 @@ wstool -t $WORKSPACE/src foreach --git 'git stash' wstool -t $WORKSPACE/src update jsk-ros-pkg/jsk_robot ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall wstool -t $WORKSPACE/src update --delete-changed-uris -wstool -t $WORKSPACE/src foreach --git 'branch-name=$(git rev-parse --abbrev-ref HEAD) && git reset --hard HEAD && git checkout origin/$branch-name && git branch -D $branch-name && git checkout $branch-name' # Forcefully checkout specified branch +wstool -t $WORKSPACE/src foreach --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout $branchname' # Forcefully checkout specified branch wstool -t $WORKSPACE/src update WSTOOL_UPDATE_RESULT=$? # Build workspace From da9d73876829618a29940790fb8ebe3ed3a3e239 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 09:44:46 +0900 Subject: [PATCH 123/433] [jsk_fetch_startup] update workspace script --- .../jsk_fetch_startup/scripts/update_workspace.sh | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index fe716ed534..c7e9545551 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -5,14 +5,17 @@ function usage() echo "Usage: $0 [-w workspace_directory] [-h]" } +SEND_MAIL=true WORKSPACE=$HOME/ros/melodic/ -while getopts hw: OPT +while getopts hl:w: OPT do case $OPT in w) WORKSPACE=$(cd $(dirname $OPTARG) && pwd)/$(basename $OPTARG) ;; + l) + SEND_MAIL=false h) usage exit 1 @@ -55,8 +58,8 @@ if [ $CATKIN_BUILD_RESULT -ne 0 ]; then MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." fi set +x -} > $LOGFILE 2>&1 -if [ -n "$MAIL_BODY" ]; then +} 2>&1 | tee $LOGFILE +if [ -n "$MAIL_BODY" ] && "${SEND_MAIL}"; then rostopic pub -1 /email jsk_robot_startup/Email "header: seq: 0 stamp: {secs: 0, nsecs: 0} From 327f5e3fec4b81cfc2d9b6ceb12d8fe312ab8bd0 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 11:48:27 +0900 Subject: [PATCH 124/433] [jsk_fetch_startup] update workspace script --- .../scripts/update_workspace.sh | 65 ++++++++++++++++--- 1 file changed, 57 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index c7e9545551..9a18b41195 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -2,7 +2,13 @@ function usage() { - echo "Usage: $0 [-w workspace_directory] [-h]" + echo "Usage: $0 [-w workspace_directory] [-h] [-l] + +optional arguments: + -h show this help + -w WORKSPACE_PATH specify target workspace + -l do not send a mail +" } SEND_MAIL=true @@ -16,10 +22,15 @@ do ;; l) SEND_MAIL=false + ;; h) usage exit 1 ;; + *) + usage + exit 1 + ;; esac done @@ -35,13 +46,47 @@ LOGFILE=$WORKSPACE/update_workspace.txt { set -x # Update workspace -wstool -t $WORKSPACE/src foreach --git 'git stash' -wstool -t $WORKSPACE/src update jsk-ros-pkg/jsk_robot +wstool foreach -t $WORKSPACE/src --git 'git stash' +wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall -wstool -t $WORKSPACE/src update --delete-changed-uris -wstool -t $WORKSPACE/src foreach --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout $branchname' # Forcefully checkout specified branch -wstool -t $WORKSPACE/src update +wstool update -t $WORKSPACE/src --delete-changed-uris +wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout $branchname' # Forcefully checkout specified branch +wstool update -t $WORKSPACE/src WSTOOL_UPDATE_RESULT=$? +# Rosdep Install +sudo apt-get update -y +rosdep update +rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r \ + --skip-keys="\ + baxter_core_msgs + baxter_description + baxter_moveit_config + baxter_tools + cobotta_teleop + denso_cobotta_descriptions + dynamixel_controllers + face_recognition + gen3_lite_gen3_lite_2f_moveit_config + json_prolog + kinova_teleop + librealsense2 + linux_hardware + magni_nav + mjpeg_server + nao_bringup + nao_description + nao_interaction_launchers + naoqi_msgs + pepper_bringup + pepper_description + pr2eus_openrave + ps4eye + python3-pykdl + realsense2-camera + rqt_pr2_dashboard + snap_map_icp + " +ROSDEP_INSTALL_RESULT=$? # Build workspace cd $WORKSPACE catkin clean aques_talk collada_urdf_jsk_patch libcmt -y @@ -54,13 +99,17 @@ MAIL_BODY="" if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " fi +if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then + MAIL_BODY=$MAIL_BODY"Please install dependencies manually. " +fi if [ $CATKIN_BUILD_RESULT -ne 0 ]; then MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." fi set +x } 2>&1 | tee $LOGFILE -if [ -n "$MAIL_BODY" ] && "${SEND_MAIL}"; then - rostopic pub -1 /email jsk_robot_startup/Email "header: +if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" = "true" ]; then + echo "Sent a mail" + rostopic pub -1 /email jsk_robot_startup/Email "header: seq: 0 stamp: {secs: 0, nsecs: 0} frame_id: '' From d7c51a7c35aa5f1de1f3220d35f22421e68efc53 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 14:14:44 +0900 Subject: [PATCH 125/433] [jsk_fetch_startup] update update-workspace.sh --- .../scripts/update_workspace.sh | 52 ++++++------------- 1 file changed, 17 insertions(+), 35 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 9a18b41195..4cfcb89217 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -5,16 +5,16 @@ function usage() echo "Usage: $0 [-w workspace_directory] [-h] [-l] optional arguments: - -h show this help - -w WORKSPACE_PATH specify target workspace - -l do not send a mail + -h show this help + -w WORKSPACE_PATH specify target workspace + -l do not send a mail " } SEND_MAIL=true WORKSPACE=$HOME/ros/melodic/ -while getopts hl:w: OPT +while getopts hlw: OPT do case $OPT in w) @@ -56,43 +56,25 @@ WSTOOL_UPDATE_RESULT=$? # Rosdep Install sudo apt-get update -y rosdep update -rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r \ - --skip-keys="\ - baxter_core_msgs - baxter_description - baxter_moveit_config - baxter_tools - cobotta_teleop - denso_cobotta_descriptions - dynamixel_controllers - face_recognition - gen3_lite_gen3_lite_2f_moveit_config - json_prolog - kinova_teleop - librealsense2 - linux_hardware - magni_nav - mjpeg_server - nao_bringup - nao_description - nao_interaction_launchers - naoqi_msgs - pepper_bringup - pepper_description - pr2eus_openrave - ps4eye - python3-pykdl - realsense2-camera - rqt_pr2_dashboard - snap_map_icp - " +# jsk_footstep_planner is not released for melodic +# jsk_footstep_controller is not released for melodic +# librealsense2 should not be installed from ROS repository +# realsense-ros should not be installed from ROS repository +rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys \ +"\ +jsk_footstep_controller \ +jsk_footstep_planner \ +librealsense2 \ +realsense2_camera \ +realsense2_description \ +" ROSDEP_INSTALL_RESULT=$? # Build workspace cd $WORKSPACE catkin clean aques_talk collada_urdf_jsk_patch libcmt -y catkin init catkin config -DCMAKE_BUILD_TYPE=Release -catkin build +catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail MAIL_BODY="" From dea6c53eda2f783120ce1b7fd9a14ca4ee1e5cb3 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 16:27:59 +0900 Subject: [PATCH 126/433] [jsk_fetch_startup] fix --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 4cfcb89217..d0ce39357f 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -89,7 +89,7 @@ if [ $CATKIN_BUILD_RESULT -ne 0 ]; then fi set +x } 2>&1 | tee $LOGFILE -if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" = "true" ]; then +if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then echo "Sent a mail" rostopic pub -1 /email jsk_robot_startup/Email "header: seq: 0 From afa42c16470672d63e6a926af2002fce722597ba Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 15:17:30 +0900 Subject: [PATCH 127/433] [jsk_fetch_startup] update jsk fetch models --- .../jsk_fetch_startup/robots/head_l515.urdf.xacro | 10 ++++++++-- .../robots/insta360_stand.urdf.xacro | 15 +++++++++++++++ .../jsk_fetch_startup/robots/jsk_fetch.urdf.xacro | 8 ++++++-- 3 files changed, 29 insertions(+), 4 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro index 8361f9dc20..dd2f9b7a5e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro @@ -22,10 +22,16 @@ - + + + + + + + - + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro new file mode 100644 index 0000000000..690742cfa6 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/insta360_stand.urdf.xacro @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro index 460086a8da..ede62cbb2c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro @@ -1,10 +1,11 @@ + - + - + @@ -21,4 +22,7 @@ + + + From c9477910d2530d67dee984ea2ac6fcc722ba2cbc Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 19 Apr 2022 15:19:07 +0900 Subject: [PATCH 128/433] [jsk_fetch_startup] add view_model launch and config --- .../jsk_fetch_startup/config/view_model.rviz | 426 ++++++++++++++++++ .../launch/view_model.launch | 17 + 2 files changed, 443 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz new file mode 100644 index 0000000000..e8978465a4 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/view_model.rviz @@ -0,0 +1,426 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 728 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 0.5 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_camera_mount: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bellows_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bellows_link2: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + d435_front_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + d435_front_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + estop_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + gripper_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_box_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_camera_depth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_rgb_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_camera_rgb_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + head_l515_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l515_head_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l_gripper_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_fixed_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + upperarm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base_camera_mount: + Value: true + base_link: + Value: true + bellows_link: + Value: true + bellows_link2: + Value: true + d435_front_left_link: + Value: true + d435_front_right_link: + Value: true + elbow_flex_link: + Value: true + estop_link: + Value: true + forearm_roll_link: + Value: true + gripper_link: + Value: true + head_box_link: + Value: true + head_camera_depth_frame: + Value: true + head_camera_depth_optical_frame: + Value: true + head_camera_link: + Value: true + head_camera_rgb_frame: + Value: true + head_camera_rgb_optical_frame: + Value: true + head_l515_mount_link: + Value: true + head_l515_virtual_mount_link: + Value: true + head_pan_link: + Value: true + head_tilt_link: + Value: true + insta360_link: + Value: true + l515_head_link: + Value: true + l_gripper_finger_link: + Value: true + l_wheel_link: + Value: true + laser_link: + Value: true + r_gripper_finger_link: + Value: true + r_wheel_link: + Value: true + shoulder_lift_link: + Value: true + shoulder_pan_link: + Value: true + torso_fixed_link: + Value: true + torso_lift_link: + Value: true + upperarm_roll_link: + Value: true + wrist_flex_link: + Value: true + wrist_roll_link: + Value: true + Marker Scale: 0.5 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + base_link: + base_camera_mount: + {} + d435_front_left_link: + {} + d435_front_right_link: + {} + estop_link: + {} + l_wheel_link: + {} + laser_link: + {} + r_wheel_link: + {} + torso_fixed_link: + {} + torso_lift_link: + bellows_link: + {} + bellows_link2: + {} + head_pan_link: + head_box_link: + {} + head_tilt_link: + head_camera_link: + head_camera_depth_frame: + head_camera_depth_optical_frame: + {} + head_camera_rgb_frame: + head_camera_rgb_optical_frame: + {} + head_l515_virtual_mount_link: + head_l515_mount_link: + l515_head_link: + {} + insta360_link: + {} + shoulder_pan_link: + shoulder_lift_link: + upperarm_roll_link: + elbow_flex_link: + forearm_roll_link: + wrist_flex_link: + wrist_roll_link: + gripper_link: + l_gripper_finger_link: + {} + r_gripper_finger_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 4.618305206298828 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.564796507358551 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.5854246616363525 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1025 + Hide Left Dock: false + Hide Right Dock: false + QMainWindow State: 000000ff00000000fd00000004000000000000015600000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000050f0000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1920 + X: 0 + Y: 27 diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch new file mode 100644 index 0000000000..4f8ef6e3f9 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/view_model.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + From 857971145002a84b828b261d5f9ce944f4585909 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Tue, 19 Apr 2022 17:08:12 +0900 Subject: [PATCH 129/433] Use VOICEVOX by default --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 8 ++++---- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 3d3e47950c..3a39eafeb0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -4,7 +4,8 @@ - + + @@ -73,9 +74,8 @@ - - - + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 8d5fe6f077..11dedc0a6b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ -d /usr/vt ]; then VOICE_TEXT=true; else VOICE_TEXT=false; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true use_voice_text:=$VOICE_TEXT --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From eaddb29618f054931a37a121459406529ec6980c Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 20 Apr 2022 09:11:59 +0900 Subject: [PATCH 130/433] [jsk_fetch_startup] fix default workspace path --- .../jsk_fetch_startup/scripts/update_workspace.sh | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index d0ce39357f..4c29ddd17f 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -11,14 +11,19 @@ optional arguments: " } +function get_full_path() +{ + echo "$(cd $(dirname $1) && pwd)/$(basename $1)" +} + SEND_MAIL=true -WORKSPACE=$HOME/ros/melodic/ +WORKSPACE=$(get_full_path $HOME/ros/melodic) while getopts hlw: OPT do case $OPT in w) - WORKSPACE=$(cd $(dirname $OPTARG) && pwd)/$(basename $OPTARG) + WORKSPACE=$(get_full_path $OPTARG) ;; l) SEND_MAIL=false From 1afec5db84955913a73f32e0ab4245f85e3cef26 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 20 Apr 2022 09:31:50 +0900 Subject: [PATCH 131/433] [jsk_fetch_startup] fix --- .../jsk_fetch_startup/scripts/update_workspace.sh | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 4c29ddd17f..17ec206128 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -55,7 +55,15 @@ wstool foreach -t $WORKSPACE/src --git 'git stash' wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall wstool update -t $WORKSPACE/src --delete-changed-uris -wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout $branchname' # Forcefully checkout specified branch +# Forcefully checkout specified branch +wstool foreach -t $WORKSPACE/src --git --shell \ +'\ +branchname=$(git rev-parse --abbrev-ref HEAD); +git fetch --all --prune; +git reset --hard HEAD; +git checkout origin/$branchname; +git branch -D $branchname; +git checkout -b $branchname origin/$branchname' wstool update -t $WORKSPACE/src WSTOOL_UPDATE_RESULT=$? # Rosdep Install From 06f7385e18cf53b97df1a913566a18b6fda48b10 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 20 Apr 2022 10:15:08 +0900 Subject: [PATCH 132/433] [jsk_fetch_startup] update --- .../jsk_fetch_startup/scripts/update_workspace.sh | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 17ec206128..7786444579 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -51,19 +51,14 @@ LOGFILE=$WORKSPACE/update_workspace.txt { set -x # Update workspace + wstool foreach -t $WORKSPACE/src --git 'git stash' +wstool foreach -t $WORKSPACE/src --git 'git fetch --all --prune' wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall wstool update -t $WORKSPACE/src --delete-changed-uris # Forcefully checkout specified branch -wstool foreach -t $WORKSPACE/src --git --shell \ -'\ -branchname=$(git rev-parse --abbrev-ref HEAD); -git fetch --all --prune; -git reset --hard HEAD; -git checkout origin/$branchname; -git branch -D $branchname; -git checkout -b $branchname origin/$branchname' +wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' wstool update -t $WORKSPACE/src WSTOOL_UPDATE_RESULT=$? # Rosdep Install From 161ca98ebad0c144980c1e2297b79ceaf753c50e Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Wed, 20 Apr 2022 10:31:28 +0900 Subject: [PATCH 133/433] run coral_usb in default ws --- .../supervisor_scripts/jsk-human-pose-estimator.conf | 6 ++++-- .../supervisor_scripts/jsk-object-detector.conf | 6 ++++-- .../jsk-panorama-human-pose-estimator.conf | 6 ++++-- .../supervisor_scripts/jsk-panorama-object-detector.conf | 6 ++++-- 4 files changed, 16 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index 8021ee6ce4..dfcb5d522b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -1,8 +1,10 @@ [program:jsk-human-pose-estimator] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" +; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" stopsignal=TERM -directory=/home/fetch/ros/coral_ws +; directory=/home/fetch/ros/coral_ws +directory=/home/fetch/ros/melodic ; You can set "autostart=true" if "autostart=false" in jsk-panorama-human-pose-estimator.conf autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index 2e8e147a9e..d543cf6ea5 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -1,8 +1,10 @@ [program:jsk-object-detector] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM -directory=/home/fetch/ros/coral_ws +; directory=/home/fetch/ros/coral_ws +directory=/home/fetch/ros/melodic ; You can set "autostart=true" if "autostart=false" in jsk-panorama-object-detector.conf autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index 48b5fc4dc3..46f6e6516e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,8 +1,10 @@ [program:jsk-panorama-human-pose-estimator] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM -directory=/home/fetch/ros/coral_ws +; directory=/home/fetch/ros/coral_ws +directory=/home/fetch/ros/melodic ; You can set "autostart=true" if "autostart=false" in jsk-human-pose-estimator.conf autostart=false autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index 434ab2fe48..fb849e0a5e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,8 +1,10 @@ [program:jsk-panorama-object-detector] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM -directory=/home/fetch/ros/coral_ws +; directory=/home/fetch/ros/coral_ws +directory=/home/fetch/ros/melodic ; You can set "autostart=true" if "autostart=false" in jsk-object-detector.conf autostart=false autorestart=false From 440839181288f753e5226c6862b2a9e743e80a9b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 20 Apr 2022 16:35:08 +0900 Subject: [PATCH 134/433] [jsk_fetch_startup] support other hotword in dialogflow task executive --- .../config/dialogflow_hotword.yaml | 2 + .../launch/dialogflow_task_executive.launch | 55 +++++++++++++++++++ .../supervisor_scripts/jsk-dialog.conf | 2 +- 3 files changed, 58 insertions(+), 1 deletion(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml new file mode 100644 index 0000000000..359c385b3e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml @@ -0,0 +1,2 @@ +- やあ +- <ロボット名に置き換えてください> diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch new file mode 100644 index 0000000000..ba9c76ac6c --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + use_audio: $(arg use_audio) + use_tts: $(arg use_tts) + language: $(arg language) + soundplay_action_name: $(arg soundplay_action_name) + volume: $(arg volume) + project_id: $(arg project_id) + google_cloud_credentials_json: $(arg credential) + enable_hotword: $(arg enable_hotword) + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 8e8aa85903..80e2b1366d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch dialogflow_task_executive dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 2b7a2de9ee412470bb14220f7b53082dcef246ab Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 20 Apr 2022 18:32:47 +0900 Subject: [PATCH 135/433] compile dialogflow hotword with robot name --- .../jsk_fetch_startup/CMakeLists.txt | 17 +++++++++++++++++ .../jsk_fetch_startup/config/.gitignore | 1 + .../config/dialogflow_hotword.yaml | 2 -- .../config/dialogflow_hotword.yaml.in | 5 +++++ 4 files changed, 23 insertions(+), 2 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/.gitignore delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index 9b98af04b1..29683126ba 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -86,8 +86,25 @@ macro(configure_icon_files icol iname) endif() endmacro(configure_icon_files) +macro(configure_dialogflow_hotword_yaml dname) + set(FETCH_NAME ${dname}) + if (${FETCH_NAME} STREQUAL "fetch15") + set(ROBOT_NICKNAME_KANA "ヘンゼル") + set(ROBOT_NICKNAME_HIRA "へんぜる") + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/dialogflow_hotword.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_dialogflow_hotword.yaml) + elseif (${FETCH_NAME} STREQUAL "fetch1075") + set(ROBOT_NICKNAME_KANA "グレーテル") + set(ROBOT_NICKNAME_HIRA "ぐれーてる") + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/dialogflow_hotword.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_dialogflow_hotword.yaml) + endif() +endmacro(configure_dialogflow_hotword_yaml) + configure_icon_files(blue fetch15) configure_icon_files(red fetch1075) +configure_dialogflow_hotword_yaml(fetch15) +configure_dialogflow_hotword_yaml(fetch1075) ############# ## Testing ## diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore new file mode 100644 index 0000000000..97ed018fbb --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore @@ -0,0 +1 @@ +fetch*_dialogflow_hotword.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml deleted file mode 100644 index 359c385b3e..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml +++ /dev/null @@ -1,2 +0,0 @@ -- やあ -- <ロボット名に置き換えてください> diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in new file mode 100644 index 0000000000..73714a65a9 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/dialogflow_hotword.yaml.in @@ -0,0 +1,5 @@ +- ねえねえ +- こんにちわ +- やあ +- @ROBOT_NICKNAME_KANA@ +- @ROBOT_NICKNAME_HIRA@ From 4a0a25767ab4b0575c643fa6de6a856764f39e18 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 20 Apr 2022 18:33:16 +0900 Subject: [PATCH 136/433] include dialogflow_task_executive.launch and use own yaml --- .../launch/dialogflow_task_executive.launch | 55 ------------------- .../fetch_dialogflow_task_executive.launch | 32 +++++++++++ 2 files changed, 32 insertions(+), 55 deletions(-) delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch deleted file mode 100644 index ba9c76ac6c..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/dialogflow_task_executive.launch +++ /dev/null @@ -1,55 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - use_audio: $(arg use_audio) - use_tts: $(arg use_tts) - language: $(arg language) - soundplay_action_name: $(arg soundplay_action_name) - volume: $(arg volume) - project_id: $(arg project_id) - google_cloud_credentials_json: $(arg credential) - enable_hotword: $(arg enable_hotword) - - - - - - - - - - - - - - - - - diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch new file mode 100644 index 0000000000..17f7aa0995 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 866823e9e64c8a8dcd8eb102e4f84c33cf4a242d Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Wed, 20 Apr 2022 18:41:56 +0900 Subject: [PATCH 137/433] update jsk-dialog.conf --- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 80e2b1366d..f4b9db6078 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 73633f7b2fd5ac79cfc2957b8626b975fdb8e84c Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 6 Jan 2022 15:45:35 +0900 Subject: [PATCH 138/433] add cron scripts for update ssl key --- .../jsk_fetch_startup/cron_scripts/cron_certbot.conf | 1 + .../jsk_fetch_startup/scripts/certbot_renewhook.sh | 7 +++++++ 2 files changed, 8 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf create mode 100755 jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf new file mode 100644 index 0000000000..387f504041 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf @@ -0,0 +1 @@ +0 0 1 Jan,Apr,Jul,Oct * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && certbot renew -v --standalone --renew-hook \"$(rospack find jsk_fetch_startup)/scripts/certbot_renewhook.sh\" >> /var/log/certbot_renewal.log" \ No newline at end of file diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh new file mode 100755 index 0000000000..d37fe27421 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/certbot_renewhook.sh @@ -0,0 +1,7 @@ +#!/bin/sh + +SITE=dialogflow.$(hostname).jsk.imi.i.u-tokyo.ac.jp + +cd /etc/letsencrypt/live/$SITE +cat fullchain.pem privkey.pem > /etc/haproxy/certs/$SITE.pem +systemctl restart haproxy From 2b9fdd3b73780f7a34d658f1a770390d205ceae1 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 21 Apr 2022 10:10:52 +0900 Subject: [PATCH 139/433] [jsk_fetch_startup] update ssl key from letsencrypt --- .../jsk_fetch_startup/cron_scripts/cron_certbot.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf index 387f504041..8c7cc3ea3b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/cron_scripts/cron_certbot.conf @@ -1 +1 @@ -0 0 1 Jan,Apr,Jul,Oct * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && certbot renew -v --standalone --renew-hook \"$(rospack find jsk_fetch_startup)/scripts/certbot_renewhook.sh\" >> /var/log/certbot_renewal.log" \ No newline at end of file +0 0 1 Jan,Apr,Jul,Oct * bash -c ". /home/fetch/ros/melodic/devel/setup.bash && systemctl stop haproxy && certbot renew -v --standalone --renew-hook \"$(rospack find jsk_fetch_startup)/scripts/certbot_renewhook.sh\" >> /var/log/certbot_renewal.log" From f1f2b40363b7a3f9ecce35909f70db700892beb9 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 18 Apr 2022 13:34:21 +0900 Subject: [PATCH 140/433] [jsk_fetch_startup] Use image hz convert for recording kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.app | 6 +++--- .../apps/go_to_kitchen/go_to_kitchen.xml | 21 +++++++++++++++++++ 2 files changed, 24 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 0fed92f1ea..a924c0648f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -19,7 +19,7 @@ plugins: audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /head_camera/rgb/image_rect_color + video_topic_name: /head_camera/rgb/image_rect_color/hz_converted video_height: 480 video_width: 640 video_framerate: 30 @@ -34,10 +34,10 @@ plugins: audio_sample_rate: 16000 audio_format: wave audio_sample_format: S16LE - video_topic_name: /edgetpu_object_detector/output/image + video_topic_name: /edgetpu_object_detector/output/image/hz_converted video_height: 480 video_width: 640 - video_framerate: 10 + video_framerate: 30 video_encoding: RGB - name: panorama_video_recorder_plugin type: app_recorder/video_recorder_plugin diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 09c9f3cf28..7b599f21b6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -19,6 +19,27 @@ + + + + + + desired_topic_hz: 30 + + + + + + + + desired_topic_hz: 30 + + + From fe2451f00a0e29b521324503f89fc16f5b8c23a4 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 21 Apr 2022 08:49:11 +0900 Subject: [PATCH 141/433] [jsk_fetch_startup] update rviz config --- .../jsk_fetch_startup/config/jsk_startup.rviz | 47 ++++++++++++------- 1 file changed, 31 insertions(+), 16 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz index ab198412bf..7d8d6777a8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz @@ -5,7 +5,7 @@ Panels: Property Tree Widget: Expanded: ~ Splitter Ratio: 0.4187380373477936 - Tree Height: 1319 + Tree Height: 479 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -138,6 +138,10 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false head_pan_link: Alpha: 1 Show Axes: false @@ -148,6 +152,10 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false l515_head_link: Alpha: 1 Show Axes: false @@ -339,12 +347,12 @@ Visualization Manager: Class: rviz/Map Color Scheme: costmap Draw Behind: false - Enabled: false + Enabled: true Name: SafeCostMap Topic: /safe_teleop_base/local_costmap/costmap Unreliable: false Use Timestamp: false - Value: false + Value: true - Alpha: 0.3499999940395355 Class: rviz/Map Color Scheme: costmap @@ -396,9 +404,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: BaseScan Position Transformer: XYZ Queue Size: 10 @@ -426,9 +432,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: XtionPointCloud Position Transformer: XYZ Queue Size: 10 @@ -454,6 +458,19 @@ Visualization Manager: top: 10 transport hint: raw width: 320 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: PanoramaImage + Topic: /dual_fisheye_to_panorama/quater/output + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -469,9 +486,7 @@ Visualization Manager: Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 - Max Intensity: 4096 Min Color: 0; 0; 0 - Min Intensity: 0 Name: HeadL515PointCloud Position Transformer: XYZ Queue Size: 10 @@ -536,13 +551,13 @@ Visualization Manager: Saved: ~ Window Geometry: CancelAction: - collapsed: true + collapsed: false Displays: - collapsed: true - Height: 1865 - Hide Left Dock: true + collapsed: false + Height: 1025 + Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001f8000006abfc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000005b2000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e00000005f5000000f30000007f00ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f5000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003f5000006ab00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f800000363fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000026a000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e01000002ad000000f30000007f00ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005820000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -551,6 +566,6 @@ Window Geometry: collapsed: false Views: collapsed: true - Width: 1013 - X: 67 + Width: 1920 + X: 0 Y: 27 From f2b698f4c353004873f0f1875662f71face58005 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 21 Apr 2022 14:12:51 +0900 Subject: [PATCH 142/433] [jsk_fetch_startup] add panorama image and detection results to rviz config --- .../jsk_fetch_startup/config/jsk_startup.rviz | 134 +++++++++++++----- 1 file changed, 97 insertions(+), 37 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz index 7d8d6777a8..c8dd4f9418 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup.rviz @@ -5,7 +5,7 @@ Panels: Property Tree Widget: Expanded: ~ Splitter Ratio: 0.4187380373477936 - Tree Height: 479 + Tree Height: 477 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -445,32 +445,6 @@ Visualization Manager: Use Fixed Frame: true Use rainbow: true Value: true - - Class: jsk_rviz_plugin/OverlayImage - Enabled: true - Name: XtionRGB - Topic: /head_camera/rgb/quater/image_rect_color - Value: true - alpha: 0.800000011920929 - height: 128 - keep aspect ratio: true - left: 10 - overwrite alpha value: false - top: 10 - transport hint: raw - width: 320 - - Class: jsk_rviz_plugin/OverlayImage - Enabled: true - Name: PanoramaImage - Topic: /dual_fisheye_to_panorama/quater/output - Value: true - alpha: 0.800000011920929 - height: 128 - keep aspect ratio: true - left: 340 - overwrite alpha value: false - top: 10 - transport hint: raw - width: 480 - Alpha: 1 Autocompute Intensity Bounds: true Autocompute Value Bounds: @@ -483,7 +457,7 @@ Visualization Manager: Color: 255; 255; 255 Color Transformer: RGB8 Decay Time: 0 - Enabled: true + Enabled: false Invert Rainbow: false Max Color: 255; 255; 255 Min Color: 0; 0; 0 @@ -498,7 +472,93 @@ Visualization Manager: Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: true + Value: false + - Class: rviz/Group + Displays: + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: XtionRGB + Topic: /head_camera/rgb/quater/image_rect_color + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: XtionRGBHumanPoseEstimator + Topic: /edgetpu_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: XtionRGBObjectDetector + Topic: /edgetpu_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 10 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 320 + Enabled: true + Name: XtionRGB + - Class: rviz/Group + Displays: + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: PanoramaImage + Topic: /dual_fisheye_to_panorama/quater/output + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: PanoramaHumanPoseEstimator + Topic: /edgetpu_panorama_human_pose_estimator/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + - Class: jsk_rviz_plugin/OverlayImage + Enabled: false + Name: PanoramaObjectDetector + Topic: /edgetpu_panorama_object_detector/output/image + Value: false + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 340 + overwrite alpha value: false + top: 10 + transport hint: raw + width: 480 + Enabled: true + Name: PanoramaImage Enabled: true Global Options: Background Color: 48; 48; 48 @@ -529,25 +589,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 10.471776962280273 + Distance: 10 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: -0.00829183217138052 - Y: 0.022624600678682327 - Z: -0.003759089857339859 - Focal Shape Fixed Size: true + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: false Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5747973322868347 + Pitch: 0.7853981852531433 Target Frame: base_link Value: Orbit (rviz) - Yaw: 1.745403528213501 + Yaw: 0.7853981852531433 Saved: ~ Window Geometry: CancelAction: @@ -557,7 +617,7 @@ Window Geometry: Height: 1025 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001f800000363fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000026a000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e01000002ad000000f30000007f00ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005820000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f800000361fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003e00000269000000ca00fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e01000002ad000000f20000008200ffffff000000010000010f00000463fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000463000000a600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000026200fffffffb0000000800540069006d00650100000000000004500000000000000000000005820000036100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: From 433f4e645a43fed03c5f74a618cb3e8f58d03a82 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 25 Apr 2022 15:13:14 +0900 Subject: [PATCH 143/433] [jsk_fetch_startup] fix format, remove old document, and add TOC --- jsk_fetch_robot/jsk_fetch_startup/README.md | 120 ++++++++++++++------ 1 file changed, 84 insertions(+), 36 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index e7baff4793..0c65fb347d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -1,5 +1,28 @@ # jsk_fetch_startup +- [jsk_fetch_startup](#jsk_fetch_startup) + - [SetUp (Running following commands in the first time)](#setup-running-following-commands-in-the-first-time) + - [Install a udev rule](#install-a-udev-rule) + - [For realsense](#for-realsense) + - [supervisor](#supervisor) + - [cron](#cron) + - [mongodb](#mongodb) + - [Teleoperation](#teleoperation) + - [Maintenance](#maintenance) + - [re-roslaunch jsk_fetch_startup fetch_bringup.launch](#re-roslaunch-jsk_fetch_startup-fetch_bringuplaunch) + - [re-roslaunch fetch_bringup fetch.launch](#re-roslaunch-fetch_bringup-fetchlaunch) + - [Clock Synchronization](#clock-synchronization) + - [Network](#network) + - [General description](#general-description) + - [Case description](#case-description) + - [Access point](#access-point) + - [Log](#log) + - [Apps](#apps) + - [Note](#note) + - [Add fetch to rwt_app_chooser](#add-fetch-to-rwt_app_chooser) + - [Execute demos](#execute-demos) + - [Administration](#administration) + ## SetUp (Running following commands in the first time) ### Install a udev rule @@ -7,7 +30,7 @@ rosrun jsk_fetch_startup install_udev.sh ``` -#### For realsense +### For realsense Before start this, remove `librealsense2` and `realsense2-ros` from ROS repository and set not to be installed. @@ -27,70 +50,70 @@ sudo apt-mark hold librealsense2 librealsense2-dev ``` ### supervisor + Important jobs for fetch operation are managed by supervisor. Here is a list of jobs that are managed by supervisor. - - roscore +- roscore Start roscore - - robot +- robot Launch Minimum ROS programs to run fetch - - jsk-fetch-startup +- jsk-fetch-startup Launch ROS programs extended by JSK - - jsk-network-monitor +- jsk-network-monitor Restart the network manager automatically if ping does not work. - - jsk-log-wifi +- jsk-log-wifi Monitor network condition - - jsk-app-scheduler +- jsk-app-scheduler Scheduler to launch [app](https://github.com/knorth55/app_manager_utils/tree/master/app_scheduler) at a fixed time - - jsk-object-detector +- jsk-object-detector Object detection using fetch's head camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-panorama-object-detector: +- jsk-panorama-object-detector: Object detection using fetch's 360 camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-human-pose-estimator +- jsk-human-pose-estimator Human pose estimation using fetch's head camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-panorama-human-pose-estimator +- jsk-panorama-human-pose-estimator Human pose estimation using fetch's 360 camera and [coral_usb_ros](https://github.com/knorth55/coral_usb_ros) - - jsk-dialog +- jsk-dialog Launch [dialogflow_task_exective](https://github.com/jsk-ros-pkg/jsk_3rdparty/tree/master/dialogflow_task_executive) - - jsk-gdrive +- jsk-gdrive Launch [app](https://github.com/knorth55/app_manager_utils/tree/master/app_uploader) to upload data to Goole Drive - - jsk-dstat +- jsk-dstat Monitor fetch's resource using dstat command - - jsk-lifelog +- jsk-lifelog Launch program to save fetch's [lifelog](https://github.com/jsk-ros-pkg/jsk_robot/tree/master/jsk_robot_common/jsk_robot_startup/lifelog) - Install supervisor config files. e.g. `robot.conf`, `jsk_fetch_startup.conf` ... -``` +```bash su -c 'rosrun jsk_fetch_startup install_supervisor.sh' ``` @@ -100,17 +123,17 @@ Previously, upstart was used, but it has been moved to supervisor. This is becau ![supervisor_status](https://user-images.githubusercontent.com/19769486/119499716-f142c000-bda1-11eb-9b96-0cfa7e04a1b2.png) - ### cron + Install cron jobs for root user and fetch user. e.g. `shutdown`, `update_workspace`. -``` +```bash su -c 'rosrun jsk_fetch_startup install_cron.sh' ``` ### mongodb -``` +```bash sudo mkdir -p /var/lib/robot/mongodb_store/ # to see the db items from http://lcoalhost/rockmongo @@ -122,11 +145,7 @@ sudo mv rockmongo-1.1.7 /var/www/html/rockmongo # $MONGO["servers"][$i]["control_auth"] = false; // true;//enable control users, works only if mongo_auth=false ``` -### Coral Edge TPU -Create ROS workspace for Coral Edge TPU. Please see: -https://github.com/knorth55/coral_usb_ros - -### Teleoperation +## Teleoperation For the JSK safe teleop system, please see [data flow diagram of safe_teleop.launch](https://github.com/jsk-ros-pkg/jsk_robot/tree/master/jsk_robot_common/jsk_robot_startup#launchsafe_teleoplaunch) @@ -138,19 +157,22 @@ The numbers assigned to the joystick are as follows. ## Maintenance ### re-roslaunch jsk_fetch_startup fetch_bringup.launch -``` + +```bash sudo supervisorctl restart jsk-fetch-startup ``` ### re-roslaunch fetch_bringup fetch.launch -``` + +```bash sudo supervisorctl restart robot ``` ### [Clock Synchronization](https://github.com/fetchrobotics/docs/blob/0c1c63ab47952063bf60280e74b4ff3ae07fd914/source/computer.rst) install `chrony` and add ```server `gethostip -d fetch15` offline minpoll 8``` to /etc/chrony/chrony.conf, restart chronyd by `sudo /etc/init.d/chrony restart` and wait for few seconds, if you get -``` + +```bash $ chronyc tracking Reference ID : 133.11.216.145 (fetch15.jsk.imi.i.u-tokyo.ac.jp) Stratum : 4 @@ -166,21 +188,22 @@ Root dispersion : 0.018803 seconds Update interval : 2.1 seconds Leap status : Normal ``` -it works, if you get `127.127.1.1` for `Reference ID`, something wrong +it works, if you get `127.127.1.1` for `Reference ID`, something wrong ## Network + ### General description + Fetch has wired and wireless network connections. If we use both of wired and wireless connections as DHCP, DNS holds two IP addresses for same hostname (fetch15 in this case). This cause problems in network such as ROS communication or ssh connection. -The solution we take now (2016/11/01) is using wired connection as static IP. -By doing so, DNS holds only one IP adress (for wireless connection) for fetch hostname. - ### Case description + If you see the following result, it is OK. -``` + +```bash $ nslookup fetch15.jsk.imi.i.u-tokyo.ac.jp Server: 127.0.1.1 Address: 127.0.1.1#53 @@ -190,24 +213,28 @@ Address: 133.11.216.145 ``` If two or more IP addresses apper, something is wrong. -Please connect display, open a window of network manager, and check that wired connection uses static IP. +Please connect display, open a window of network manager. ### Access point + Define access point setting, such as ssid: -``` + +```bash cd /etc/NetworkManager/system-connections ``` -### Log +## Log tmuxinator makes it easy to check the important logs of fetch from command line. Currently, it shows the logs of the supervisor jobs. Install tmuxinator config. + ```bash rosrun jsk_fetch_startup install_tmuxinator.sh ``` Show logs + ```bash tmuxinator log ``` @@ -244,6 +271,7 @@ tmuxinator log You can not run this on Firefox. Please use Google Chrome. ### Add fetch to rwt_app_chooser + 1. Access [http://tork-a.github.io/visualization_rwt/rwt_app_chooser](http://tork-a.github.io/visualization_rwt/rwt_app_chooser "website"). - Be careful to access the site via http, not https, to to enable websocket communication. - Modern browsers may automatically redirect from http to https. @@ -254,7 +282,27 @@ You can not run this on Firefox. Please use Google Chrome. 1. Click `ADD ROBOT` button ### Execute demos + 1. Click `fetch15` at `Select Robot` window 1. Select task which are shown with icons. ![select_app](https://user-images.githubusercontent.com/19769486/40872010-7d21d2bc-6681-11e8-8c0b-621f199638dd.png) + +## Administration + +- 2016/10/26 add `allow 133.11.216/8` to /etc/chrony/chrony.conf +- 2018/08/26 add `0 10 * * 1-5 /home/fetch/ros/indigo_robot/devel/env.sh rosservice call /fetch15/start_app "name: 'jsk_fetch_startup/go_to_kitchen'"` to crontab + - `fetch` goes to 73B2 kitchen at 10:00 AM from Monday to Friday. +- 2019/04/19: add `fetch` user in `pulse-access` group. +- 2019/04/19: set `start on runlevel [2345]` in `/etc/init/pulseaudio.conf`. + - this modification is needed for starting `pulseaudio` in boot. + - `pulseaudio` is required to register USB speaker on head in boot. +- 2019/04/19: set `env DISALLOW_MODULE_LOADING=0` in `/etc/init/pulseaudio.conf`. + - this modification is needed for overriding default speaker setting in `/etc/init/jsk-fetch-startup.conf` + - overriding default speaker setting to use USB speaker on head is done with `pactl set-default-sink $AUDIO_DEVICE` in `/etc/init/jsk-fetch-startup.conf` +- 2019/04/19: launch `jsk_fetch_startup/fetch_bringup.launch` by `fetch` user in `/etc/init/jsk-fetch-startup.conf` + - some nodes save files by `fetch` user +- 2019/04/19: add arg `launch_teleop` in `/etc/ros/indigo/robot.launch`. + - We sent PR to upstream [fetchrobotics/fetch_robots PR#40](https://github.com/fetchrobotics/fetch_robots/pull/40). +- 2019/04/19: run `/etc/ros/indigo/robot.launch` with `arg` `launch_teleop:=false`. + - `teleop` in `/etc/ros/indigo/robot.launch` nodes were conflicted with `teleop` nodes in [jsk_fetch_startup/launch/fetch_teleop.xml](https://github.com/jsk-ros-pkg/jsk_robot/blob/master/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_teleop.xml) From 738b534b20bdc633c9cb748efb73bfe7f14809ec Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 28 Apr 2022 12:44:10 +0900 Subject: [PATCH 144/433] [jsk_fetch_startup] enable to change robot_description according to config.bash --- .../jsk_fetch_startup/config/config.bash | 5 +++++ .../jsk_fetch_startup/launch/fetch.launch | 15 ++++++++------- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index ea364d3b12..ea2ca482dd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -1,6 +1,11 @@ # This file is bash configuration for robot.conf # This file must be at /var/lib/robot/config.bash +export USE_BASE_CAMERA_MOUNT=true +export USE_HEAD_BOX=true +export USE_HEAD_L515=true +export USE_INSTA360_STAND=true + export RS_SERIAL_NO_T265="" export RS_SERIAL_NO_D435_FRONTRIGHT="" export RS_SERIAL_NO_D435_FRONTLEFT="" diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 72826157ec..5157fc18a8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -3,14 +3,15 @@ - - - - - + + + + + - + + @@ -136,7 +137,7 @@ command="$(find xacro)/xacro $(find jsk_fetch_startup)/robots/jsk_fetch.urdf.xacro ros_distro:=$(env ROS_DISTRO) use_fetch_description:=$(arg use_fetch_description) base_camera_mount:=$(arg use_base_camera_mount) head_box:=$(arg use_head_box) - head_l515:=$(arg use_head_l515)" /> + head_l515:=$(arg use_head_l515) insta360_stand:=$(arg insta360_stand)" /> From 40271501e73e9b11d9bebe03829725adfccb199e Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 27 Apr 2022 17:24:14 +0900 Subject: [PATCH 145/433] [jsk_fetch_startup] rename update_workspace.sh to update_workspace_main.sh and call it from update_workspace.sh --- .../scripts/update_workspace.sh | 113 +----------------- .../scripts/update_workspace_main.sh | 113 ++++++++++++++++++ 2 files changed, 115 insertions(+), 111 deletions(-) create mode 100755 jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 7786444579..868f0cd1b2 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -1,113 +1,4 @@ #!/usr/bin/env bash -function usage() -{ - echo "Usage: $0 [-w workspace_directory] [-h] [-l] - -optional arguments: - -h show this help - -w WORKSPACE_PATH specify target workspace - -l do not send a mail -" -} - -function get_full_path() -{ - echo "$(cd $(dirname $1) && pwd)/$(basename $1)" -} - -SEND_MAIL=true -WORKSPACE=$(get_full_path $HOME/ros/melodic) - -while getopts hlw: OPT -do - case $OPT in - w) - WORKSPACE=$(get_full_path $OPTARG) - ;; - l) - SEND_MAIL=false - ;; - h) - usage - exit 1 - ;; - *) - usage - exit 1 - ;; - esac -done - -if [ ! -e $WORKSPACE ]; then - echo "No workspace $WORKSPACE" - exit 1 -fi - -. $WORKSPACE/devel/setup.bash -# Filename should end with .txt to preview the contents in a web browser -LOGFILE=$WORKSPACE/update_workspace.txt - -{ -set -x -# Update workspace - -wstool foreach -t $WORKSPACE/src --git 'git stash' -wstool foreach -t $WORKSPACE/src --git 'git fetch --all --prune' -wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot -ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall -wstool update -t $WORKSPACE/src --delete-changed-uris -# Forcefully checkout specified branch -wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' -wstool update -t $WORKSPACE/src -WSTOOL_UPDATE_RESULT=$? -# Rosdep Install -sudo apt-get update -y -rosdep update -# jsk_footstep_planner is not released for melodic -# jsk_footstep_controller is not released for melodic -# librealsense2 should not be installed from ROS repository -# realsense-ros should not be installed from ROS repository -rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys \ -"\ -jsk_footstep_controller \ -jsk_footstep_planner \ -librealsense2 \ -realsense2_camera \ -realsense2_description \ -" -ROSDEP_INSTALL_RESULT=$? -# Build workspace -cd $WORKSPACE -catkin clean aques_talk collada_urdf_jsk_patch libcmt -y -catkin init -catkin config -DCMAKE_BUILD_TYPE=Release -catkin build --continue-on-failure -CATKIN_BUILD_RESULT=$? -# Send mail -MAIL_BODY="" -if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " -fi -if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please install dependencies manually. " -fi -if [ $CATKIN_BUILD_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." -fi -set +x -} 2>&1 | tee $LOGFILE -if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then - echo "Sent a mail" - rostopic pub -1 /email jsk_robot_startup/Email "header: - seq: 0 - stamp: {secs: 0, nsecs: 0} - frame_id: '' -subject: 'Daily workspace update fails' -body: '$MAIL_BODY' -sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' -receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' -smtp_server: '' -smtp_port: '' -attached_files: ['$LOGFILE']" -fi +cp $(rospack find jsk_fetch_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh +/tmp/update_workspace.sh $@ diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh new file mode 100755 index 0000000000..74eb47693b --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh @@ -0,0 +1,113 @@ +#!/usr/bin/env bash + +function usage() +{ + echo "Usage: $0 [-w workspace_directory] [-h] [-l] + +optional arguments: + -h show this help + -w WORKSPACE_PATH specify target workspace + -l do not send a mail +" +} + +function get_full_path() +{ + echo "$(cd $(dirname $1) && pwd)/$(basename $1)" +} + +SEND_MAIL=true +WORKSPACE=$(get_full_path $HOME/ros/melodic) + +while getopts hlw: OPT +do + case $OPT in + w) + WORKSPACE=$(get_full_path $OPTARG) + ;; + l) + SEND_MAIL=false + ;; + h) + usage + exit 1 + ;; + *) + usage + exit 1 + ;; + esac +done + +if [ ! -e $WORKSPACE ]; then + echo "No workspace $WORKSPACE" + exit 1 +fi + +. $WORKSPACE/devel/setup.bash +# Filename should end with .txt to preview the contents in a web browser +LOGFILE=$WORKSPACE/update_workspace.txt + +{ +set -x +# Update workspace + +wstool foreach -t $WORKSPACE/src --git 'git stash' +wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' +wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot +ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall +wstool update -t $WORKSPACE/src --delete-changed-uris +# Forcefully checkout specified branch +wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' +wstool update -t $WORKSPACE/src +WSTOOL_UPDATE_RESULT=$? +# Rosdep Install +sudo apt-get update -y +rosdep update +# jsk_footstep_planner is not released for melodic +# jsk_footstep_controller is not released for melodic +# librealsense2 should not be installed from ROS repository +# realsense-ros should not be installed from ROS repository +rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys \ +"\ +jsk_footstep_controller \ +jsk_footstep_planner \ +librealsense2 \ +realsense2_camera \ +realsense2_description \ +" +ROSDEP_INSTALL_RESULT=$? +# Build workspace +cd $WORKSPACE +catkin clean aques_talk collada_urdf_jsk_patch libcmt -y +catkin init +catkin config -DCMAKE_BUILD_TYPE=Release +catkin build --continue-on-failure +CATKIN_BUILD_RESULT=$? +# Send mail +MAIL_BODY="" +if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then + MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " +fi +if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then + MAIL_BODY=$MAIL_BODY"Please install dependencies manually. " +fi +if [ $CATKIN_BUILD_RESULT -ne 0 ]; then + MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." +fi +set +x +} 2>&1 | tee $LOGFILE +if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then + echo "Sent a mail" + rostopic pub -1 /email jsk_robot_startup/Email "header: + seq: 0 + stamp: {secs: 0, nsecs: 0} + frame_id: '' +subject: 'Daily workspace update fails' +body: '$MAIL_BODY' +sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' +receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' +smtp_server: '' +smtp_port: '' +attached_files: ['$LOGFILE']" +fi From f518d3cd93c6d9f9e55dbdf12cf41e7224a1b897 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 28 Apr 2022 15:25:14 +0900 Subject: [PATCH 146/433] [jsk_fetch_startup] fix bugs --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 5157fc18a8..3d8fa4f0c2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -7,8 +7,8 @@ - - + + From 3f99b74673037191a89d477d2ee2751453acb1ee Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 12 May 2022 22:20:29 +0900 Subject: [PATCH 147/433] [jsk_fetch_startup] Remove duplicated diagnostics aggregator --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 3d8fa4f0c2..230ed6656c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -2,6 +2,7 @@ + From c5e7e1185b04e6f6568fb07f5e9705c76e34050d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sat, 14 May 2022 00:42:50 +0900 Subject: [PATCH 148/433] set fetch default english speaker --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 5 ++++- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 3a39eafeb0..6b696ff277 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -6,6 +6,7 @@ + @@ -67,7 +68,9 @@ + respawn="true" if="$(arg launch_sound_play)"> + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 11dedc0a6b..e418fcd627 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 8e3ce3fd588d3ce77057052b2e73c9258e888716 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 17 May 2022 23:17:48 +0900 Subject: [PATCH 149/433] [jsk_fetch_startup] add --profile and --interface args to network_monitor.py --- .../scripts/network_monitor.py | 40 ++++++++++--------- 1 file changed, 22 insertions(+), 18 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py index 1f67266a30..782f5479a5 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/network_monitor.py @@ -47,21 +47,21 @@ TOUCH_FILE = "/home/fetch/.Network_Monitor_Restarted_Robot" -def ping(use_arping, hosts): +def ping(use_arping, hosts, network_interface='wlan0'): for host in hosts: for _ in xrange(5): print(datetime.now(),"Sending ping request") if use_arping: - response = os.system("arping -I wlan0 -c 1 " + host) + response = os.system("arping -I {} -c 1 {}".format(network_interface, host)) else: - response = os.system("ping -c 1 -q " + host) + response = os.system("ping -c 1 -q {}".format(host)) if response == 0: return True sleep(5) return False -def get_sanshiro(): - return [['sanshiro', 'sanshiro']] +def get_sanshiro(network_profile_id): + return [[network_profile_id, 'sanshiro']] def get_saved_networks(filepaths=None): # NetworkManager has its own ID for networks, often multiple for the same @@ -90,19 +90,19 @@ def get_saved_networks(filepaths=None): # for reconnecting to 'sanshiro' -def reconnect_to_wlan(): - if call(["nmcli", "d", "disconnect", "iface", "wlan0"]) == 0: +def reconnect_to_wlan(network_interface='wlan0', network_profile_id='sanshiro'): + if call(["nmcli", "d", "disconnect", "iface", network_interface]) == 0: sleep(0.3) - print("disconnect from wlan0") + print("Network disconnected with interface \"{}\"".format(network_interface)) else: - print("'nmcli d disconnect iface wlan0' do not work correctly!") + print("'nmcli d disconnect iface {}' do not work correctly!".format(network_interface)) - if call(["nmcli", "c", "up", "id", "sanshiro"]) == 0: + if call(["nmcli", "c", "up", "id", network_profile_id]) == 0: sleep(0.3) - print("connect to sanshiro") + print("Network connected with profile \"{}\"".format(network_profile_id)) return True else: - print("'nmcli c up id sanshiro' do not work correctly!") + print("'nmcli c up id {}' do not work correctly!".format(network_profile_id)) return False @@ -150,13 +150,13 @@ def connect_by_nmcli_id(nid, ssid="SSID not given"): return False -def attempt_reconnect_to_network(): +def attempt_reconnect_to_network(network_interface, network_profile_id): # First, try to connect to sanshiro - if connect_by_nmcli_id('sanshiro', 'sanshiro'): + if connect_by_nmcli_id(network_profile_id, 'sanshiro'): return True # Get list of stored 'wireless' connections; [id, ssid] - known = get_saved_networks() # alternative : known = get_sanshiro() + known = get_saved_networks() # alternative : known = get_sanshiro(network_profile_id) # Get list of unique available wifi network ssids and their strongest signal avail = get_avail_networks_by_strength() @@ -170,7 +170,7 @@ def attempt_reconnect_to_network(): for ntwk in to_try: if connect_by_nmcli_id(*ntwk): return True - if reconnect_to_wlan(): + if reconnect_to_wlan(network_interface, network_profile_id): return True return False @@ -249,12 +249,12 @@ def main(args): while True: try: # Check if we can ping the access point - if not ping(args.arping, hostnames): + if not ping(args.arping, hostnames, args.interface): print(datetime.now(), "Cannot connect to", ', '.join(hostnames)) sound_goal.goal.sound_request.arg = "ピングが通りません" pub.publish(sound_goal) # Try to connect to any known network - if not attempt_reconnect_to_network(): + if not attempt_reconnect_to_network(args.interface, args.profile): # TODO use check_output instead of Popen and handle truly # bad issues with computer restarts or notification. print(datetime.now(), "Restarting network-manager") @@ -302,6 +302,10 @@ def main(args): help="One or more comma delimited hostname(s) to ping. Hostnames will " "be tried in order supplied until one is successfully contacted. Default: " "Looks for NETWORK_MONITOR_HOSTNAMES in environment.") + parser.add_argument('-I', '--interface', default='wlan0', + help='Network interface to be used.') + parser.add_argument('--profile', default='sanshiro', + help='Network profile to be used.') parser.add_argument("-a", "--arping", action='store_true', help="Use arping instead of ping.") parser.add_argument("--enable-reboot-option", action='store_true', From 192dc3954933082df0f5a1b2d7af5fbd2a749d07 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 17 May 2022 23:18:07 +0900 Subject: [PATCH 150/433] [jsk_fetch_startup] add interface arg to log-wifi-link.sh --- .../scripts/log-wifi-link.sh | 20 ++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index 9de64ee353..c888d2a903 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -7,9 +7,9 @@ INTERVAL=10 wifi_status(){ local ssid=$(iw $IFACE link | grep SSID | cut -d: -f2) local freq=$(iw $IFACE link | grep freq | cut -d':' -f2) - local signal=$(cat /proc/net/wireless | grep wlan0 | awk '{print $3}') - local level=$(cat /proc/net/wireless | grep wlan0 | awk '{print $4}') - local noise=$(cat /proc/net/wireless | grep wlan0 | awk '{print $5}') + local signal=$(cat /proc/net/wireless | grep $IFACE | awk '{print $3}') + local level=$(cat /proc/net/wireless | grep $IFACE | awk '{print $4}') + local noise=$(cat /proc/net/wireless | grep $IFACE | awk '{print $5}') local bitrate=$(iw $IFACE link | grep bitrate | cut -d':' -f2) echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate" } @@ -19,6 +19,20 @@ if [ ! -d $OUTDIR ]; then mkdir -p $OUTDIR fi +print_help(){ + echo "Usage: $0 [-i INTERVAL (default: 10)] [-I IFACE (default: wlan0)]" + exit 1 +} + +while getopts hi:I: o +do + case "$o" in + i) INTERVAL=$OPTARG;; + I) IFACE="$OPTARG";; + h) print_help;; + esac +done + while true; do wifi_status >> $OUTPATH sleep $INTERVAL From 7c2e613ce64440d1392cc38ca89a46e4689aa3fb Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 18 May 2022 00:02:48 +0900 Subject: [PATCH 151/433] [jsk_fetch_startup] support network profile and interface configuration in supervisor jobs --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 3 +++ .../jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf | 2 +- .../supervisor_scripts/jsk-network-monitor.conf | 2 +- 3 files changed, 5 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index ea2ca482dd..9ab4ab44f1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -10,3 +10,6 @@ export RS_SERIAL_NO_T265="" export RS_SERIAL_NO_D435_FRONTRIGHT="" export RS_SERIAL_NO_D435_FRONTLEFT="" export RS_SERIAL_NO_L515_HEAD="" + +export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0" +export NETWORK_DEFAULT_PROFILE_ID="sanshiro" diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf index cdb54b8638..a9723545b8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf @@ -1,5 +1,5 @@ [program:jsk-log-wifi] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup log-wifi-link.sh" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index bf05c87a6b..843e376569 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup network_monitor.py" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false From fe39d2d83893c9b3f6f3c51dcc37d691053289e9 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Thu, 19 May 2022 20:54:46 +0900 Subject: [PATCH 152/433] Set unregister_timeout in rosbridge_websocket for rosbridge_suite/#138 --- jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch index f1f90dc1e3..ad67c18d90 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch @@ -44,6 +44,7 @@ delay_between_messages: 0 max_message_size: None fragment_timeout: 600 + unregister_timeout: 100000000 Date: Wed, 18 May 2022 02:25:39 +0900 Subject: [PATCH 153/433] [jsk_fetch_startup] add rossetip with --- .../supervisor_scripts/jsk-app-scheduler.conf | 7 ++++++- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 7 ++++++- .../jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf | 6 +++++- .../supervisor_scripts/jsk-fetch-startup.conf | 8 +++++++- .../jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf | 6 +++++- .../supervisor_scripts/jsk-human-pose-estimator.conf | 6 +++++- .../supervisor_scripts/jsk-log-wifi.conf | 5 ++++- .../supervisor_scripts/jsk-network-monitor.conf | 5 ++++- .../supervisor_scripts/jsk-object-detector.conf | 6 +++++- .../jsk-panorama-human-pose-estimator.conf | 6 +++++- .../supervisor_scripts/jsk-panorama-object-detector.conf | 6 +++++- .../supervisor_scripts/jsk-rfcomm-bind.conf | 6 +++++- .../supervisor_scripts/jsk-shutdown.conf | 6 +++++- .../jsk_fetch_startup/supervisor_scripts/robot.conf | 7 ++++++- .../jsk_fetch_startup/supervisor_scripts/roscore.conf | 4 +++- 15 files changed, 76 insertions(+), 15 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index 57944374f6..adeb6148d6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -1,5 +1,10 @@ [program:jsk-app-scheduler] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup wait_app_manager.bash && \ +roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index f4b9db6078..92975a9248 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,10 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup wait_app_manager.bash && \ +roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf index 4fcf56a3e3..90530aec0a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -1,7 +1,11 @@ ; Install dstat ; sudo apt install dstat [program:jsk-dstat] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup dstat.bash" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup dstat.bash" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index e418fcd627..a080e1502b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,11 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup setup_audio.bash && \ +if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && \ +roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index dc30c03ea9..12d9a271b1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,5 +1,9 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index dfcb5d522b..be215f27d7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -1,6 +1,10 @@ [program:jsk-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf index a9723545b8..b094e4b0f4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf @@ -1,5 +1,8 @@ [program:jsk-log-wifi] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index 843e376569..9d3c638715 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,5 +1,8 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index d543cf6ea5..ae6910f422 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -1,6 +1,10 @@ [program:jsk-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index 46f6e6516e..84de837d4c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,6 +1,10 @@ [program:jsk-panorama-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index fb849e0a5e..7c55eb7e24 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,6 +1,10 @@ [program:jsk-panorama-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 16f10c4710..d090411fdb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -1,5 +1,9 @@ [program:jsk-rfcomm-bind] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +roslaunch jsk_robot_startup rfcomm_bind.launch --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index bdc0bd78eb..ee776ce4d4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,5 +1,9 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_robot_startup shutdown.py --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf index 0862a3af71..9c27f452e7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf @@ -1,5 +1,10 @@ [program:robot] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ +. /home/fetch/ros/melodic/devel/setup.bash && \ +if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ +rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ +rosrun jsk_fetch_startup link_calibration_files.bash && \ +roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf index 7d8b14bbc7..f2dfdb5474 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf @@ -1,5 +1,7 @@ [program:roscore] -command=/bin/bash -c ". /opt/ros/roscore_prestart.bash && . /opt/ros/melodic/setup.bash && roscore" +command=/bin/bash -c ". /opt/ros/roscore_prestart.bash && \ +. /opt/ros/melodic/setup.bash && \ +roscore" stopsignal=TERM autostart=true autorestart=unexpected From 14570b96e04bfc7728282aa3e9d4a3cd99924cc8 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 18 May 2022 22:03:06 +0900 Subject: [PATCH 154/433] [jsk_fetch_startup] fix --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 3 ++- .../supervisor_scripts/jsk-app-scheduler.conf | 7 +------ .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 7 +------ .../jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf | 6 +----- .../supervisor_scripts/jsk-fetch-startup.conf | 8 +------- .../jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf | 6 +----- .../supervisor_scripts/jsk-human-pose-estimator.conf | 6 +----- .../supervisor_scripts/jsk-log-wifi.conf | 5 +---- .../supervisor_scripts/jsk-network-monitor.conf | 5 +---- .../supervisor_scripts/jsk-object-detector.conf | 6 +----- .../jsk-panorama-human-pose-estimator.conf | 6 +----- .../supervisor_scripts/jsk-panorama-object-detector.conf | 6 +----- .../supervisor_scripts/jsk-rfcomm-bind.conf | 6 +----- .../supervisor_scripts/jsk-shutdown.conf | 6 +----- .../jsk_fetch_startup/supervisor_scripts/robot.conf | 7 +------ .../jsk_fetch_startup/supervisor_scripts/roscore.conf | 4 +--- 16 files changed, 17 insertions(+), 77 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 9ab4ab44f1..54f6ee0893 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -11,5 +11,6 @@ export RS_SERIAL_NO_D435_FRONTRIGHT="" export RS_SERIAL_NO_D435_FRONTLEFT="" export RS_SERIAL_NO_L515_HEAD="" -export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0" +export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1" export NETWORK_DEFAULT_PROFILE_ID="sanshiro" +export NETWORK_DEFAULT_ROS_INTERFACE="wlan0" diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index adeb6148d6..73b49933f8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -1,10 +1,5 @@ [program:jsk-app-scheduler] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup wait_app_manager.bash && \ -roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 92975a9248..b33947240b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,10 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup wait_app_manager.bash && \ -roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf index 90530aec0a..da03912699 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -1,11 +1,7 @@ ; Install dstat ; sudo apt install dstat [program:jsk-dstat] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup dstat.bash" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup dstat.bash" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index a080e1502b..92ca6033dc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,11 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup setup_audio.bash && \ -if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && \ -roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index 12d9a271b1..2a3e6bbc22 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,9 +1,5 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index be215f27d7..d9a69b7774 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -1,10 +1,6 @@ [program:jsk-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf index b094e4b0f4..fdf3741b6a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf @@ -1,8 +1,5 @@ [program:jsk-log-wifi] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index 9d3c638715..f9949696b0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,8 +1,5 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index ae6910f422..d5a6794621 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -1,10 +1,6 @@ [program:jsk-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index 84de837d4c..f07778b651 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,10 +1,6 @@ [program:jsk-panorama-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index 7c55eb7e24..dd7111436d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,10 +1,6 @@ [program:jsk-panorama-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index d090411fdb..9bf1a76169 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -1,9 +1,5 @@ [program:jsk-rfcomm-bind] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -roslaunch jsk_robot_startup rfcomm_bind.launch --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index ee776ce4d4..95539f2543 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,9 +1,5 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf index 9c27f452e7..b4db414f79 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf @@ -1,10 +1,5 @@ [program:robot] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && \ -. /home/fetch/ros/melodic/devel/setup.bash && \ -if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && \ -rossetip $NETWORK_DEFAULT_WIFI_INTERFACE && \ -rosrun jsk_fetch_startup link_calibration_files.bash && \ -roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf index f2dfdb5474..7d8b14bbc7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/roscore.conf @@ -1,7 +1,5 @@ [program:roscore] -command=/bin/bash -c ". /opt/ros/roscore_prestart.bash && \ -. /opt/ros/melodic/setup.bash && \ -roscore" +command=/bin/bash -c ". /opt/ros/roscore_prestart.bash && . /opt/ros/melodic/setup.bash && roscore" stopsignal=TERM autostart=true autorestart=unexpected From 96891ecc117981fdabd373be976d0663ae3c4fcf Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 18 May 2022 22:03:28 +0900 Subject: [PATCH 155/433] [jsk_fetch_startup] add fetchctl script --- .../jsk_fetch_startup/scripts/fetchctl.sh | 63 +++++++++++++++++++ 1 file changed, 63 insertions(+) create mode 100755 jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh new file mode 100755 index 0000000000..87fb0d3133 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh @@ -0,0 +1,63 @@ +#!/bin/bash + +function usage() { + echo "Usage: $0 " + exit 1 +} + +function start_jobs() { + sudo supervisorctl start roscore + sudo supervisorctl start robot + sudo supervisorctl start jsk-shutdown + sudo supervisorctl start jsk-rfcomm-bind + sudo supervisorctl start jsk-object-detector + sudo supervisorctl start jsk-network-monitor + sudo supervisorctl start jsk-log-wifi + sudo supervisorctl start jsk-human-pose-estimator + sudo supervisorctl start jsk-gdrive + sudo supervisorctl start jsk-fetch-startup + sudo supervisorctl start jsk-dstat + sudo supervisorctl start jsk-dialog + sudo supervisorctl start jsk-app-scheduler +} + +function restart_jobs() { + sudo supervisorctl restart roscore + sudo supervisorctl restart robot + sudo supervisorctl restart jsk-shutdown + sudo supervisorctl restart jsk-rfcomm-bind + sudo supervisorctl restart jsk-object-detector + sudo supervisorctl restart jsk-network-monitor + sudo supervisorctl restart jsk-log-wifi + sudo supervisorctl restart jsk-human-pose-estimator + sudo supervisorctl restart jsk-gdrive + sudo supervisorctl restart jsk-fetch-restartup + sudo supervisorctl restart jsk-dstat + sudo supervisorctl restart jsk-dialog + sudo supervisorctl restart jsk-app-scheduler +} + +function stop_jobs() { + sudo supervisorctl stop roscore + sudo supervisorctl stop robot + sudo supervisorctl stop jsk-shutdown + sudo supervisorctl stop jsk-rfcomm-bind + sudo supervisorctl stop jsk-object-detector + sudo supervisorctl stop jsk-network-monitor + sudo supervisorctl stop jsk-log-wifi + sudo supervisorctl stop jsk-human-pose-estimator + sudo supervisorctl stop jsk-gdrive + sudo supervisorctl stop jsk-fetch-stopup + sudo supervisorctl stop jsk-dstat + sudo supervisorctl stop jsk-dialog + sudo supervisorctl stop jsk-app-scheduler +} + +command=$1 + +case "$command" in + start) start_jobs;; + restart) restart_jobs;; + stop) stop_jobs;; + *) usage;; +esac From 2c396050d6e53c92c87655346ba6d346629b34bc Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 18 May 2022 23:54:14 +0900 Subject: [PATCH 156/433] [jsk_fetch_startup] fix fetchctl.sh --- jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh index 87fb0d3133..ec5d8f0b84 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/fetchctl.sh @@ -31,7 +31,7 @@ function restart_jobs() { sudo supervisorctl restart jsk-log-wifi sudo supervisorctl restart jsk-human-pose-estimator sudo supervisorctl restart jsk-gdrive - sudo supervisorctl restart jsk-fetch-restartup + sudo supervisorctl restart jsk-fetch-startup sudo supervisorctl restart jsk-dstat sudo supervisorctl restart jsk-dialog sudo supervisorctl restart jsk-app-scheduler @@ -47,7 +47,7 @@ function stop_jobs() { sudo supervisorctl stop jsk-log-wifi sudo supervisorctl stop jsk-human-pose-estimator sudo supervisorctl stop jsk-gdrive - sudo supervisorctl stop jsk-fetch-stopup + sudo supervisorctl stop jsk-fetch-startup sudo supervisorctl stop jsk-dstat sudo supervisorctl stop jsk-dialog sudo supervisorctl stop jsk-app-scheduler From dc6cfb51efe9a8a37e86f6299c2c2f1d5f2eebdb Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 20 May 2022 11:01:21 +0900 Subject: [PATCH 157/433] [jsk_fetch_startup] add README.md --- jsk_fetch_robot/jsk_fetch_startup/README.md | 47 +++++++++++++++++++++ 1 file changed, 47 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index 0c65fb347d..1406e4f6ef 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -49,6 +49,53 @@ sudo apt install librealsense2-dev=2.45.0-0~realsense0.4551 sudo apt-mark hold librealsense2 librealsense2-dev ``` +### Install config.bash + +JSK fetch system uses some enviroment variables. To set them, copy `config.bash` to `/var/lib/robot/config.bash` and modify it. + +```bash +roscd jsk_fetch_startup +sudo cp config/config.bash /var/lib/robot/config.bash +``` + +descriptions of each variable are below. + +- `USE_BASE_CAMERA_MOUNT` + + Flag for robot model +- `USE_HEAD_BOX` + + Flag for robot model +- `USE_HEAD_L515` + + Flag for robot model +- `USE_INSTA360_STAND` + + Flag for robot model +- `RS_SERIAL_NO_T265` + + Serial number of Realsense T265 for visual odometry. + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_D435_FRONTRIGHT` + + Serial number of Realsense D435 on the base + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_D435_FRONTLEFT` + + Serial number of Realsense D435 on the base + + realsense will not be launched when this is blank. +- `RS_SERIAL_NO_L515_HEAD` + + Serial number of Realsense L515 on the head + + realsense will not be launched when this is blank. +- `NETWORK_DEFAULT_WIFI_INTERFACE` + + Wi-Fi network interface for network management scripts (e.g. `network_monitor.py` and `network-log-wifi.sh`) +- `NETWORK_DEFAULT_PROFILE_ID` + + Network manager profile ID for network management scripts (`network_monitor.py`) ++ `NETWORK_DEFAULT_ROS_INTERFACE` + + Network interface which is used for ROS connection. + + `ROS_IP` is set to the IP address of this interface in supervisor jobs. + +It is also recommended to add lines below to each users's bashrc in the robot PC. + +```bash +source /var/lib/robot/config.bash +rossetmaster localhost +rossetip $NETWORK_DEFAULT_ROS_INTERFACE +``` + ### supervisor Important jobs for fetch operation are managed by supervisor. From d2e7729e8a1a9bf5816c3f129019ed8e93a6b085 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 20 May 2022 11:14:03 +0900 Subject: [PATCH 158/433] [jsk_fetch_startup] add network connection descriptions --- jsk_fetch_robot/jsk_fetch_startup/README.md | 46 ++++++++++++++++++++- 1 file changed, 44 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index 1406e4f6ef..fe6aac39b8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -262,14 +262,56 @@ Address: 133.11.216.145 If two or more IP addresses apper, something is wrong. Please connect display, open a window of network manager. -### Access point +### Network configuration -Define access point setting, such as ssid: +Ubuntu 18.04 uses [NetworkManager](https://wiki.archlinux.jp/index.php/NetworkManager) for network configuration. +Network manager's profiles are in `/etc/NetworkManager/system-connections`. ```bash cd /etc/NetworkManager/system-connections ``` +You can also see profiles with `nmcli`, `nmtui` or `nm-connection-editor` (GUI) command. + +To see available connection profiles. + +```bash +fetch@fetch1075:~$ nmcli connection +NAME UUID TYPE DEVICE +netplan-eth1 433e484b-3493-3640-9368-395c0c752304 ethernet eth1 +sanshiro-73B2 1f0f9db6-e448-41ef-9d27-e1ed4e48a4f5 wifi wlan1 +Wired connection 1 eb557bda-e1bf-3ab7-89e9-1f839cd6b88a ethernet -- +fetch1075-hotspot b85c6a8f-9d28-4cf3-95a0-6dc37229863d wifi -- +sanshiro-outside d7ee2165-c93a-4050-862d-d0c381a546ab wifi -- +fetch@fetch1075:~$ nmcli c show sanshiro-73B2 +``` + +To activate some connection. + +```bash +fetch@fetch1075:~$ sudo nmcli c up sanshiro-outside +[sudo] password for fetch: +Connection successfully activated (D-Bus active path: /org/freedesktop/NetworkManager/ActiveConnection/5) +fetch@fetch1075:~$ sudo nmcli c up sanshiro-73B2 +Connection successfully activated (D-Bus active path: /org/freedesktop/NetworkManager/ActiveConnection/6) +``` + +To edit connection profiles, use `nmtui` or `nm-connection-editor` + +### Default connection profiles + +fetch15 and fetch1075 has `sanshiro-73B2` and `sanshiro-outside` connections by default. (If not, please make them) + +- `sanshiro-73B2` (Connect `sanshiro` with fixed BSSID) +- `sanshiro-outside` (Connect `sanshiro` without fixed BSSID) + +By default, `sanshiro-73B2` is activated for stable connection in 73B2. +If you want to use fetch outside of 73B2, it is recommended to activate `sanshiro-outside`. + +```bash +sudo nmcli c up sanshiro-outside +``` + ## Log tmuxinator makes it easy to check the important logs of fetch from command line. Currently, it shows the logs of the supervisor jobs. From 0cb8de60d78ef15ddb2ad4e7eb9303e0c6671550 Mon Sep 17 00:00:00 2001 From: iory Date: Thu, 19 May 2022 22:48:16 +0900 Subject: [PATCH 159/433] [jsk_fetch_startup] Add audible warning --- .../config/warning_blacklist.yaml | 12 ++++++++++++ .../jsk_fetch_startup/launch/fetch_bringup.launch | 14 ++++++++++++++ 2 files changed, 26 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml new file mode 100644 index 0000000000..ed684b0de8 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml @@ -0,0 +1,12 @@ +blacklist: + - name: "/CPU/CPU Usage/my_machine CPU Usage" + - name: "/Other/amcl: Standard deviation" + - name: "/Other/jsk_joy_node: Joystick Driver Status" + - name: "/Other/l515_head l515_head_realsense2_camera_.*: Frequency Status" + - name: "/Peripherals/PS3 Controller" + - name: "/Sensors/IMU/IMU.*" + - name: "/SoundPlay/sound_play.*" +run_stop_blacklist: + - name: "\\w*_(mcb|breaker)" + - name: "Mainboard" + message: "Runstop pressed" diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 6b696ff277..78b02bf50d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -293,6 +293,20 @@ + + + + + run_stop_topic: robot_state + run_stop_condition: "m.runstopped is True" + seconds_to_start_speaking: 60 + speak_interval: 600 + + + From dd6a4c391c1dcaca4f6624802a02b56d69431bb1 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 13 May 2022 03:16:52 +0900 Subject: [PATCH 160/433] [jsk_fetch_startup] Remove diagnostics speak function from warning.py --- .../jsk_fetch_startup/scripts/warning.py | 67 ------------------- 1 file changed, 67 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py index decf7e9d1d..029e8b281c 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/warning.py @@ -9,7 +9,6 @@ from sound_play.libsoundplay import SoundClient from actionlib_msgs.msg import GoalStatus, GoalStatusArray -from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus from fetch_driver_msgs.msg import RobotState from geometry_msgs.msg import Twist from power_msgs.msg import BatteryState, BreakerState @@ -36,40 +35,6 @@ def terminate_thread(thread): ctypes.pythonapi.PyThreadState_SetAsyncExc(thread.ident, None) raise SystemError("PyThreadState_SetAsyncExc failed") -class DiagnosticsSpeakThread(threading.Thread): - def __init__(self, error_status): - threading.Thread.__init__(self) - self.volume = rospy.get_param("~volume", 1.0) - self.error_status = error_status - self.start() - - def run(self): - global sound - for status in self.error_status: - # ignore error status if the error already occured in the latest 10 minites - if status.message in error_status_in_10_min: - if rospy.Time.now().secs - error_status_in_10_min[status.message] < 600: - continue - else: - error_status_in_10_min[status.message] = rospy.Time.now().secs - else: - error_status_in_10_min[status.message] = rospy.Time.now().secs - # we can ignore "Joystick not open." - if status.message == "Joystick not open." : - continue - if status.name == "supply_breaker" and status.message == "Disabled." : - continue - # - text = "Error on {}, {}".format(status.name, status.message) - rospy.loginfo(text) - text = text.replace('_', ', ') - sound.say(text, 'voice_kal_diphone', volume=self.volume) - time.sleep(5) - - def stop(self): - terminate_thread(self) - self.join() - class Warning: def __init__(self): time.sleep(1) @@ -77,22 +42,13 @@ def __init__(self): self.battery_state_msgs = BatteryState() self.twist_msgs = Twist() # - self.diagnostics_speak_thread = {} self.auto_undocking = False - self.diagnostics_list = [] - if rospy.get_param("~speak_warn", True): - self.diagnostics_list.append(DiagnosticStatus.WARN) - if rospy.get_param("~speak_error", True): - self.diagnostics_list.append(DiagnosticStatus.ERROR) - if rospy.get_param("~speak_stale", True): - self.diagnostics_list.append(DiagnosticStatus.STALE) # self.base_breaker = rospy.ServiceProxy('base_breaker', BreakerCommand) # self.battery_sub = rospy.Subscriber("battery_state", BatteryState, self.battery_callback, queue_size = 1) self.cmd_vel_sub = rospy.Subscriber("base_controller/command_unchecked", Twist, self.cmd_vel_callback, queue_size = 1) self.robot_state_sub = rospy.Subscriber("robot_state", RobotState, self.robot_state_callback, queue_size = 1) - self.diagnostics_status_sub = rospy.Subscriber("diagnostics", DiagnosticArray, self.diagnostics_status_callback, queue_size = 1) self.undock_sub = rospy.Subscriber("/undock/status", GoalStatusArray, self.undock_status_callback) # self.cmd_vel_pub = rospy.Publisher("base_controller/command", Twist, queue_size=1) @@ -140,29 +96,6 @@ def cmd_vel_callback(self, msg): ## self.twist_msgs = msg - def diagnostics_status_callback(self, msg): - ## - self.diagnostic_status_msgs = msg.status - ## - ## check if this comes from /robot_driver - callerid = msg._connection_header['callerid'] - if callerid not in self.diagnostics_speak_thread: - self.diagnostics_speak_thread[callerid] = None - error_status = filter(lambda n: n.level in self.diagnostics_list, msg.status) - # when RunStopped, ignore message from *_mcb and *_breaker - if self.robot_state_msgs.runstopped: - error_status = filter(lambda n: not (re.match("\w*_(mcb|breaker)",n.name) or (n.name == "Mainboard" and n.message == "Runstop pressed")), error_status) - if not error_status : # error_status is not [] - if self.diagnostics_speak_thread[callerid] and self.diagnostics_speak_thread[callerid].is_alive(): - self.diagnostics_speak_thread[callerid].stop() - return - # make sure that diagnostics_speak_thread is None, when the thread is terminated - if self.diagnostics_speak_thread[callerid] and not self.diagnostics_speak_thread[callerid].is_alive(): - self.diagnostics_speak_thread[callerid] = None - # run new thread - if self.diagnostics_speak_thread[callerid] is None: - self.diagnostics_speak_thread[callerid] = DiagnosticsSpeakThread(error_status) - if __name__ == "__main__": global sound # store error status and time of the error in the latest 10 minites From f162fde84a9479b5ae0c438d50b371fe61de1ac8 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 23 May 2022 13:50:01 +0900 Subject: [PATCH 161/433] [jsk_fetch_startup] update README --- jsk_fetch_robot/jsk_fetch_startup/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index fe6aac39b8..8978b82201 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -85,8 +85,8 @@ descriptions of each variable are below. - `NETWORK_DEFAULT_PROFILE_ID` + Network manager profile ID for network management scripts (`network_monitor.py`) + `NETWORK_DEFAULT_ROS_INTERFACE` - + Network interface which is used for ROS connection. - + `ROS_IP` is set to the IP address of this interface in supervisor jobs. + + Network interface or IP address which is used for ROS connection. + + `rossetip $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP`. It is also recommended to add lines below to each users's bashrc in the robot PC. From 891afed2b9e4f7319a61b076373d2d6d14ac2aa3 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Mon, 23 May 2022 13:58:32 +0900 Subject: [PATCH 162/433] [jsk_robot_startup] Set mongodb_store logerr period 3600[s] --- jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index 13c62d42f4..e7b6b684d8 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -34,6 +34,7 @@ + From f2a510362b21be9a05fb794425d91026cdd9e644 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 13:59:48 +0900 Subject: [PATCH 163/433] change warning voice from default voice in fetch1075 --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 6 +++++- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 78b02bf50d..4c9b1f7133 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -69,7 +69,10 @@ - + + default_voice: $(arg default_english_speaker) + plugin: sound_play/flite_plugin + @@ -304,6 +307,7 @@ run_stop_condition: "m.runstopped is True" seconds_to_start_speaking: 60 speak_interval: 600 + language: cmu_us_slt.flitevox diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 92ca6033dc..9feb78d71c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=voice_cmu_us_slt_arctic_hts; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=cmu_us_ljm.flitevox; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 3c17acdedc8bec29dd4f90dac50c2115d402c127 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 14:35:08 +0900 Subject: [PATCH 164/433] update voice for fetch15 --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 7 ++++--- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 4c9b1f7133..15451f4cc4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -6,7 +6,8 @@ - + + @@ -302,12 +303,12 @@ output="screen" > - + run_stop_topic: robot_state run_stop_condition: "m.runstopped is True" seconds_to_start_speaking: 60 speak_interval: 600 - language: cmu_us_slt.flitevox + language: $(arg default_warning_speaker) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 9feb78d71c..1f0c842e10 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=voice_us2_mbrola; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=cmu_us_ljm.flitevox; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=cmu_us_bdl.flitevox DEFAULT_WARNING_SPEAKER=cmu_us_fem.flitevox; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox DEFAULT_WARNING_SPEAKER=cmu_us_lnh.flitevox; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 3714d152c2988ff7b44377b1e4a24f48fd9d4218 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 15:47:46 +0900 Subject: [PATCH 165/433] update config/config.bash to support fetch15 and fetch1075 --- .../jsk_fetch_startup/config/config.bash | 46 ++++++++++++++----- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 36 insertions(+), 12 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 54f6ee0893..55d1fdc33c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -1,16 +1,40 @@ # This file is bash configuration for robot.conf # This file must be at /var/lib/robot/config.bash -export USE_BASE_CAMERA_MOUNT=true -export USE_HEAD_BOX=true -export USE_HEAD_L515=true -export USE_INSTA360_STAND=true +if [ $(hostname) = 'fetch15' ]; then + export DEFAULT_SPEAKER=13; + export DEFAULT_ENGLISH_SPEAKER=cmu_us_bdl.flitevox; + export DEFAULT_WARNING_SPEAKER=cmu_us_fem.flitevox; -export RS_SERIAL_NO_T265="" -export RS_SERIAL_NO_D435_FRONTRIGHT="" -export RS_SERIAL_NO_D435_FRONTLEFT="" -export RS_SERIAL_NO_L515_HEAD="" + export USE_BASE_CAMERA_MOUNT=true; + export USE_HEAD_BOX=true; + export USE_HEAD_L515=true; + export USE_INSTA360_STAND=true; -export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1" -export NETWORK_DEFAULT_PROFILE_ID="sanshiro" -export NETWORK_DEFAULT_ROS_INTERFACE="wlan0" + export RS_SERIAL_NO_T265="925122110450"; + export RS_SERIAL_NO_D435_FRONTRIGHT=""; + export RS_SERIAL_NO_D435_FRONTLEFT=""; + export RS_SERIAL_NO_L515_HEAD="f0211890"; + + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; + export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.217"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; +elif [ $(hostname) = 'fetch1075' ]; then + export DEFAULT_SPEAKER=2; + export DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox; + export DEFAULT_WARNING_SPEAKER=cmu_us_lnh.flitevox; + + export USE_BASE_CAMERA_MOUNT=false; + export USE_HEAD_BOX=false; + export USE_HEAD_L515=true; + export USE_INSTA360_STAND=true; + + export RS_SERIAL_NO_T265=""; + export RS_SERIAL_NO_D435_FRONTRIGHT=""; + export RS_SERIAL_NO_D435_FRONTLEFT=""; + export RS_SERIAL_NO_L515_HEAD="f0232270"; + + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; + export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.218"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; +fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 1f0c842e10..a16f190835 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && if [ $(hostname) = 'fetch15' ]; then DEFAULT_SPEAKER=13; DEFAULT_ENGLISH_SPEAKER=cmu_us_bdl.flitevox DEFAULT_WARNING_SPEAKER=cmu_us_fem.flitevox; elif [ $(hostname) = 'fetch1075' ]; then DEFAULT_SPEAKER=2; DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox DEFAULT_WARNING_SPEAKER=cmu_us_lnh.flitevox; fi && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 010349d6466c89718a2136d7fb6ebf4348e77dcf Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 16:15:37 +0900 Subject: [PATCH 166/433] add config_outside.bash --- .../jsk_fetch_startup/config/config_outside.bash | 13 +++++++++++++ 1 file changed, 13 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash new file mode 100644 index 0000000000..3302f5c258 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash @@ -0,0 +1,13 @@ +# This file is bash configuration for robot.conf +# This file must be at /var/lib/robot/config.bash + +SCRIPT_DIR="$( cd -- "$( dirname -- "${BASH_SOURCE[0]:-$0}"; )" &> /dev/null && pwd 2> /dev/null; )"; +. $SCRIPT_DIR/config.bash + +if [ $(hostname) = 'fetch15' ]; then + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; +elif [ $(hostname) = 'fetch1075' ]; then + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; + export NETWORK_DEFAULT_ROS_INTERFACE="wlan0"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; +fi From 984e40b7a65c493c9d265504cd36af589e8d9d66 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 16:17:48 +0900 Subject: [PATCH 167/433] update install_supervisor.sh to copy config.bash --- .../jsk_fetch_startup/config/install_supervisor.sh | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index 63f1be57ac..ea7c2fe262 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -23,9 +23,7 @@ fi # Enable jsk_dstat job to save the csv log under /var/log ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv -# copy config.bash to /var/lib/robo if not exists -if [ ! -e /var/lib/robot/config.bash ]; then - sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -fi +sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash +sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash set +x From 9bb6b515d5e21de6f39e327e46b488f2bb9f3f75 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 16:24:43 +0900 Subject: [PATCH 168/433] use symbolic link instead of copying to install supervisor --- .../jsk_fetch_startup/config/install_supervisor.sh | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index ea7c2fe262..dfab54c6ff 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -8,11 +8,8 @@ current_prefix_path="${prefix_paths[0]}" set -x cd $jsk_fetch_startup/supervisor_scripts -for file in $(ls ./*.conf); do - sudo cp $file /etc/supervisor/conf.d/ - sudo chown root:root /etc/supervisor/conf.d/$file - sudo chmod 644 /etc/supervisor/conf.d/$file - echo "copied $file to /etc/supervisor/conf.d" +for file in $(ls *.conf); do + sudo ln -s $jsk_fetch_startup/supervisor_scripts/$file /etc/supervisor/conf.d/$file done # copy config.bash to /var/lib/robo if not exists @@ -23,7 +20,7 @@ fi # Enable jsk_dstat job to save the csv log under /var/log ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv -sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash +sudo ln -s $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash +sudo ln -s $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash set +x From a1801919b99eb4095e08abae43693a60a6c2c367 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 16:35:02 +0900 Subject: [PATCH 169/433] add network_interface arg in fetch_bringup.launch --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 15451f4cc4..b4b5b78457 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -16,6 +16,7 @@ + @@ -52,7 +53,7 @@ - + From 869bde9131cf802510c737f939644b2f07d60cae Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 16:35:32 +0900 Subject: [PATCH 170/433] add network_interface in jsk-fetch-startup.conf --- .../jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index a16f190835..1cdd2ed50d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 329112a6cbab6e8c3c2a104b9a5c6700077ee9cc Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 26 May 2022 22:33:16 +0900 Subject: [PATCH 171/433] fix config_outside.bash --- jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash | 1 - 1 file changed, 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash index 3302f5c258..011a2f64c1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash @@ -7,7 +7,6 @@ SCRIPT_DIR="$( cd -- "$( dirname -- "${BASH_SOURCE[0]:-$0}"; )" &> /dev/null && if [ $(hostname) = 'fetch15' ]; then export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; elif [ $(hostname) = 'fetch1075' ]; then - export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="wlan0"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; fi From a88862ad8b60028f42475c4e50375beb263c50f3 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 26 May 2022 22:53:46 +0900 Subject: [PATCH 172/433] remove unnecessary lines --- .../jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf index da03912699..4fcf56a3e3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dstat.conf @@ -1,7 +1,7 @@ ; Install dstat ; sudo apt install dstat [program:jsk-dstat] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup dstat.bash" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && rosrun jsk_fetch_startup dstat.bash" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf index fdf3741b6a..a9723545b8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-log-wifi.conf @@ -1,5 +1,5 @@ [program:jsk-log-wifi] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rosrun jsk_fetch_startup log-wifi-link.sh -I $NETWORK_DEFAULT_WIFI_INTERFACE" stopsignal=TERM autostart=true autorestart=false From 6145e813fa556054da5469efde74291ef1f2702b Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 26 May 2022 23:12:38 +0900 Subject: [PATCH 173/433] merge serveral supervisor into one --- .../launch/fetch_bringup.launch | 77 +++++++++++++++++++ .../supervisor_scripts/jsk-app-scheduler.conf | 3 +- .../supervisor_scripts/jsk-dialog.conf | 3 +- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- .../supervisor_scripts/jsk-gdrive.conf | 3 +- .../jsk-human-pose-estimator.conf | 4 +- .../jsk-network-monitor.conf | 3 +- .../jsk-object-detector.conf | 4 +- .../supervisor_scripts/jsk-rfcomm-bind.conf | 3 +- .../supervisor_scripts/jsk-shutdown.conf | 3 +- 10 files changed, 94 insertions(+), 11 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index b4b5b78457..b9f6126ec7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -4,6 +4,17 @@ + + + + + + + + + + + @@ -17,6 +28,7 @@ + @@ -129,6 +141,58 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -321,4 +385,17 @@ + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index 73b49933f8..91d9ceac86 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -2,7 +2,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-app-scheduler.log stderr_logfile=/var/log/ros/jsk-app-scheduler.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index b33947240b..16bf25a1b1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -2,7 +2,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-dialog.log stderr_logfile=/var/log/ros/jsk-dialog.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 1cdd2ed50d..abc1b97481 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE network_profile_id:=$NETWORK_DEFAULT_PROFILE_ID --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index 2a3e6bbc22..0325da1b22 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -2,7 +2,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-gdrive.log stderr_logfile=/var/log/ros/jsk-gdrive.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index d9a69b7774..cd794862c7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -5,8 +5,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM ; directory=/home/fetch/ros/coral_ws directory=/home/fetch/ros/melodic -; You can set "autostart=true" if "autostart=false" in jsk-panorama-human-pose-estimator.conf -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-human-pose-estimator.log stderr_logfile=/var/log/ros/jsk-human-pose-estimator.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index f9949696b0..ab050efd86 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,7 +1,8 @@ [program:jsk-network-monitor] command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-network-monitor.log stderr_logfile=/var/log/ros/jsk-network-monitor.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index d5a6794621..5688491b3c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -5,8 +5,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM ; directory=/home/fetch/ros/coral_ws directory=/home/fetch/ros/melodic -; You can set "autostart=true" if "autostart=false" in jsk-panorama-object-detector.conf -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-object-detector.log stderr_logfile=/var/log/ros/jsk-object-detector.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 9bf1a76169..8cf6f5788a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -3,7 +3,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-rfcomm-bind.log stderr_logfile=/var/log/ros/jsk-rfcomm-bind.log diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index 95539f2543..fc31e3ac66 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -3,7 +3,8 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM directory=/home/fetch/ros/melodic -autostart=true +; autostart=true +autostart=false autorestart=false stdout_logfile=/var/log/ros/jsk-shutdown.log stderr_logfile=/var/log/ros/jsk-shutdown.log From eb5c7e35b7673f2c17418e4f7c52c27d0a624241 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 26 May 2022 23:16:17 +0900 Subject: [PATCH 174/433] add robot and jsk-fetch-startup supervisor for outside --- .../supervisor_scripts/jsk-fetch-startup-outside.conf | 11 +++++++++++ .../supervisor_scripts/robot-outside.conf | 11 +++++++++++ 2 files changed, 22 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf new file mode 100644 index 0000000000..9c30a69ea2 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf @@ -0,0 +1,11 @@ +[program:jsk-fetch-startup-outside] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE network_profile_id:=$NETWORK_DEFAULT_PROFILE_ID --wait" +stopsignal=TERM +directory=/home/fetch/ros/melodic +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-fetch-startup.log +stderr_logfile=/var/log/ros/jsk-fetch-startup.log +user=fetch +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo",PYTHONUNBUFFERED=1 +priority=100 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf new file mode 100644 index 0000000000..bb16165155 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf @@ -0,0 +1,11 @@ +[program:robot] +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +stopsignal=TERM +directory=/home/fetch/ros/melodic +autostart=false +autorestart=unexpected +stdout_logfile=/var/log/ros/robot.log +stderr_logfile=/var/log/ros/robot.log +user=ros +environment=ROS_LOG_DIR=/var/log/ros,ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",FETCH_CALIBRATED_URDF=/etc/ros/melodic/calibrated_2020_12_04_02_08_34.urdf,FETCH_CALIBRATED_RGB=/etc/ros/melodic/rgb_2020_12_04_02_08_34.yaml,FETCH_CALIBRATED_DEPTH=/etc/ros/melodic/depth_2020_12_04_02_08_34.yaml,PYTHONUNBUFFERED=1 +priority=10 From 0d19f41d4949dd667c01506b3e2d4125209a357a Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:24:53 +0900 Subject: [PATCH 175/433] fix typo --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index b9f6126ec7..566cd2f8c1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -151,7 +151,7 @@ - + From 0468a83f658970fb52502473e0dc3620a73d8298 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:25:02 +0900 Subject: [PATCH 176/433] move coral file --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 566cd2f8c1..81c084efc4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -180,8 +180,8 @@ file="$(find coral_usb)/launch/edgetpu_object_detector.launch"> - - + + @@ -189,8 +189,8 @@ file="$(find coral_usb)/launch/edgetpu_panorama_object_detector.launch"> - - + + From 177f7c65753220f3856aff04bacbe162dcdbf05a Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:47:01 +0900 Subject: [PATCH 177/433] add default path for dialogflow json --- .../launch/fetch_dialogflow_task_executive.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch index 17f7aa0995..a236629a55 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_dialogflow_task_executive.launch @@ -2,8 +2,8 @@ - - + + From b82a0c234081ae6f9e9d50e0ff328272e7d4ea70 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:47:30 +0900 Subject: [PATCH 178/433] update dialogflow credential path --- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 16bf25a1b1..cd93a425b1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -8,5 +8,5 @@ autorestart=false stdout_logfile=/var/log/ros/jsk-dialog.log stderr_logfile=/var/log/ros/jsk-dialog.log user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",GOOGLE_APPLICATION_CREDENTIALS=/var/lib/robot/dialogflow/JSK-Fetch-a384d3498680.json,DIALOGFLOW_PROJECT_ID=fetch-kiedno,PYTHONUNBUFFERED=1 +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",GOOGLE_APPLICATION_CREDENTIALS=/var/lib/robot/dialogflow/fetch-credential.json,DIALOGFLOW_PROJECT_ID=fetch-kiedno,PYTHONUNBUFFERED=1 priority=200 From 218f96143e273747146945adf038d1a205440699 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:47:43 +0900 Subject: [PATCH 179/433] add gdrive yaml path --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 81c084efc4..ac4f97495b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -158,6 +158,7 @@ + From 67be975273678a8c7501e31c0d101429e107a258 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Thu, 26 May 2022 23:56:12 +0900 Subject: [PATCH 180/433] fix typo in robot-outside.conf --- .../jsk_fetch_startup/supervisor_scripts/robot-outside.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf index bb16165155..f5a6196858 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf @@ -1,4 +1,4 @@ -[program:robot] +[program:robot-outside] command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic From be12702180440794338c419948f38bfa58ec5b59 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Fri, 27 May 2022 00:13:40 +0900 Subject: [PATCH 181/433] move jsk-network-monitor because it requires root user to run --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 7 ------- .../supervisor_scripts/jsk-fetch-startup-outside.conf | 2 +- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- .../jsk-network-monitor-outside.conf | 10 ++++++++++ .../supervisor_scripts/jsk-network-monitor.conf | 3 +-- 5 files changed, 13 insertions(+), 11 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index ac4f97495b..a4c6fcfb25 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -7,7 +7,6 @@ - @@ -28,7 +27,6 @@ - @@ -386,11 +384,6 @@ - - - diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf index 9c30a69ea2..616e824d5f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup-outside] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE network_profile_id:=$NETWORK_DEFAULT_PROFILE_ID --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index abc1b97481..1cdd2ed50d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE network_profile_id:=$NETWORK_DEFAULT_PROFILE_ID --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf new file mode 100644 index 0000000000..e27f9645ed --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf @@ -0,0 +1,10 @@ +[program:jsk-network-monitor-outside] +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-network-monitor.log +stderr_logfile=/var/log/ros/jsk-network-monitor.log +user=root +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",NETWORK_MONITOR_HOSTNAMES="google.com",PYTHONUNBUFFERED=1 +priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index ab050efd86..f9949696b0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,8 +1,7 @@ [program:jsk-network-monitor] command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM -; autostart=true -autostart=false +autostart=true autorestart=false stdout_logfile=/var/log/ros/jsk-network-monitor.log stderr_logfile=/var/log/ros/jsk-network-monitor.log From 177ad4fde98ec56e674b90a3a59a1a23644d9895 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Fri, 27 May 2022 00:23:02 +0900 Subject: [PATCH 182/433] update tmuxinator log.yml --- .../jsk_fetch_startup/tmuxinator_yaml/log.yml | 21 +++++++++---------- 1 file changed, 10 insertions(+), 11 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml index 99a36f2a0e..85062f575d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml +++ b/jsk_fetch_robot/jsk_fetch_startup/tmuxinator_yaml/log.yml @@ -36,15 +36,14 @@ windows: - jsk-fetch-startup: tail -f -n 1000 /var/log/ros/jsk-fetch-startup.log - jsk-network-monitor: tail -f -n 1000 /var/log/ros/jsk-network-monitor.log - jsk-log-wifi: tail -f -n 1000 /var/log/ros/jsk-log-wifi.log - - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log - # - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log - - jsk-object-detector: tail -f -n 1000 /var/log/ros/jsk-object-detector.log - - jsk-panorama-object-detector: tail -f -n 1000 /var/log/ros/jsk-panorama-object-detector.log - - jsk-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-human-pose-estimator.log - - jsk-panorama-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-panorama-human-pose-estimator.log - - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log - - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log - - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log - - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log - jsk-dstat: tail -f -n 1000 /var/log/ros/jsk-dstat.log - - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log + # - jsk-app-scheduler: tail -f -n 1000 /var/log/ros/jsk-app-scheduler.log + # - jsk-coral: tail -f -n 1000 /var/log/ros/jsk-coral.log + # - jsk-object-detector: tail -f -n 1000 /var/log/ros/jsk-object-detector.log + # - jsk-panorama-object-detector: tail -f -n 1000 /var/log/ros/jsk-panorama-object-detector.log + # - jsk-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-human-pose-estimator.log + # - jsk-panorama-human-pose-estimator: tail -f -n 1000 /var/log/ros/jsk-panorama-human-pose-estimator.log + # - jsk-dialog: tail -f -n 1000 /var/log/ros/jsk-dialog.log + # - jsk-gdrive: tail -f -n 1000 /var/log/ros/jsk-gdrive.log + # - jsk-shutdown: tail -f -n 1000 /var/log/ros/jsk-shutdown.log + # - jsk-rfcomm-bind: tail -f -n 1000 /var/log/ros/jsk-rfcomm-bind.log From a2d67c4d32c994e51cd24be5ff6175dd00f008df Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 27 May 2022 10:07:50 +0900 Subject: [PATCH 183/433] Update jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh Co-authored-by: Koki Shinjo --- .../jsk_fetch_startup/config/install_supervisor.sh | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index dfab54c6ff..f1229d57a2 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -11,12 +11,7 @@ cd $jsk_fetch_startup/supervisor_scripts for file in $(ls *.conf); do sudo ln -s $jsk_fetch_startup/supervisor_scripts/$file /etc/supervisor/conf.d/$file done - -# copy config.bash to /var/lib/robo if not exists -if [ ! -e /var/lib/robot/config.bash ]; then - sudo cp $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -fi - +sudo supervisorctl reread # Enable jsk_dstat job to save the csv log under /var/log ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv From 054c82e22526d73a0aa218b1e896744040489194 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 27 May 2022 12:38:10 +0900 Subject: [PATCH 184/433] add fetch_coral.launch --- .../launch/fetch_bringup.launch | 38 ++----------- .../launch/fetch_coral.launch | 56 +++++++++++++++++++ 2 files changed, 62 insertions(+), 32 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index a4c6fcfb25..b5d337f535 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -11,8 +11,6 @@ - - @@ -160,36 +158,12 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch new file mode 100644 index 0000000000..025807d971 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch @@ -0,0 +1,56 @@ + + + + + + + + + + + edgetpu_node_manager: + nodes: + - name: edgetpu_human_pose_estimator + type: human_pose_estimator + - name: edgetpu_panorama_human_pose_estimator + type: panorama_human_pose_estimator + default: edgetpu_human_pose_estimator + edgetpu_human_pose_estimator: + input_image: $(arg input_image) + image_transport: raw + device_id: 0 + edgetpu_panorama_human_pose_estimator: + input_image: $(arg input_panorama_image) + image_transport: raw + device_id: 0 + + + + + + + edgetpu_node_manager: + nodes: + - name: edgetpu_object_detector + type: object_detector + - name: edgetpu_panorama_object_detector + type: panorama_object_detector + default: edgetpu_object_detector + edgetpu_object_detector: + input_image: $(arg input_image) + image_transport: raw + device_id: 0 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + edgetpu_panorama_object_detector: + input_image: $(arg input_panorama_image) + image_transport: raw + device_id: 0 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + + + + From 1fb91caa8cb7c56ab957f33dc2e93f4a7a50e3be Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Fri, 27 May 2022 14:48:58 +0900 Subject: [PATCH 185/433] fix typo --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch index 025807d971..191fd8d51f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch @@ -29,7 +29,7 @@ + name="edgetpu_object_node_manager" pkg="coral_usb" type="edgetpu_node_manager.py"> edgetpu_node_manager: nodes: From 170e1a4308d65f61f44e31fe13b4c967c274ecbb Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Fri, 27 May 2022 15:15:50 +0900 Subject: [PATCH 186/433] fix typo in fetch_coral.launch --- .../launch/fetch_bringup.launch | 2 +- .../launch/fetch_coral.launch | 78 +++++++++---------- 2 files changed, 40 insertions(+), 40 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index b5d337f535..a7b598e41a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -163,7 +163,7 @@ - + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch index 191fd8d51f..237ef48534 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_coral.launch @@ -3,54 +3,54 @@ - + - - edgetpu_node_manager: - nodes: - - name: edgetpu_human_pose_estimator - type: human_pose_estimator - - name: edgetpu_panorama_human_pose_estimator - type: panorama_human_pose_estimator - default: edgetpu_human_pose_estimator - edgetpu_human_pose_estimator: - input_image: $(arg input_image) - image_transport: raw - device_id: 0 - edgetpu_panorama_human_pose_estimator: - input_image: $(arg input_panorama_image) - image_transport: raw - device_id: 0 - + + edgetpu_human_node_manager: + nodes: + - name: edgetpu_human_pose_estimator + type: human_pose_estimator + - name: edgetpu_panorama_human_pose_estimator + type: panorama_human_pose_estimator + default: edgetpu_human_pose_estimator + edgetpu_human_pose_estimator: + input_topic: $(arg input_image) + image_transport: raw + device_id: 0 + edgetpu_panorama_human_pose_estimator: + input_topic: $(arg input_panorama_image) + image_transport: raw + device_id: 0 + - - edgetpu_node_manager: - nodes: - - name: edgetpu_object_detector - type: object_detector - - name: edgetpu_panorama_object_detector - type: panorama_object_detector - default: edgetpu_object_detector - edgetpu_object_detector: - input_image: $(arg input_image) - image_transport: raw - device_id: 0 - model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite - label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt - edgetpu_panorama_object_detector: - input_image: $(arg input_panorama_image) - image_transport: raw - device_id: 0 - model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite - label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt - + + edgetpu_object_node_manager: + nodes: + - name: edgetpu_object_detector + type: object_detector + - name: edgetpu_panorama_object_detector + type: panorama_object_detector + default: edgetpu_object_detector + edgetpu_object_detector: + input_topic: $(arg input_image) + image_transport: raw + device_id: 1 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + edgetpu_panorama_object_detector: + input_topic: $(arg input_panorama_image) + image_transport: raw + device_id: 1 + model_file: /etc/ros/jsk_data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite + label_file: /etc/ros/jsk_data/coral_usb/73b2_kitchen_labels.txt + From ceba184ffdb52ffe39f7f041715d06305585fb38 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 27 May 2022 13:03:12 +0900 Subject: [PATCH 187/433] [jsk_fetch_startup] Set vital_rate 0.1 in go-to-kitchen demo --- .../launch/trashbin_occupancy_detector.launch | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index cdae23dda3..6926af55a3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -44,6 +44,7 @@ + @@ -57,6 +58,7 @@ tolerance: 0.02 min_size: 100 + vital_rate: 0.1 From c4781574cbe440494d18a0e063af962a3207be73 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 27 May 2022 13:08:14 +0900 Subject: [PATCH 188/433] [jsk_fetch_startup] Set small hz vital_rate to suppress audible diagnostics --- .../jsk_fetch_startup/launch/fetch_insta360_indigo.launch | 1 + .../jsk_fetch_startup/launch/fetch_insta360_melodic.launch | 1 + 2 files changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch index 5cd5374aa4..2835f972fd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_indigo.launch @@ -1,6 +1,7 @@ + diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch index c8af2a9b22..d7b863ae23 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch @@ -2,6 +2,7 @@ + From 1ff33702eb048e53efe3f7423faaf12ad29854aa Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Mon, 30 May 2022 18:36:10 +0900 Subject: [PATCH 189/433] [jsk_fetch_startup] Use smaller size images for trashbin occupancy detector --- .../launch/trashbin_occupancy_detector.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index 6926af55a3..97d02e1a22 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -1,6 +1,6 @@ - - + + From acac67b28648a91ee09a3be35a3dfdccc3fbec47 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 31 May 2022 11:45:27 +0900 Subject: [PATCH 190/433] [jsk_fetch_startup] Launch rfcomm bind job as root --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 5 ----- .../supervisor_scripts/jsk-rfcomm-bind.conf | 3 +-- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index a7b598e41a..58461df152 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -7,7 +7,6 @@ - @@ -358,10 +357,6 @@ - - - diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 8cf6f5788a..9bf1a76169 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -3,8 +3,7 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM directory=/home/fetch/ros/melodic -; autostart=true -autostart=false +autostart=true autorestart=false stdout_logfile=/var/log/ros/jsk-rfcomm-bind.log stderr_logfile=/var/log/ros/jsk-rfcomm-bind.log From 7edbf60059aa211a1c8647efb15467c64b152311 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 31 May 2022 11:47:18 +0900 Subject: [PATCH 191/433] [jsk_fetch_startup] Launch shutdown node as root --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 5 ----- .../jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf | 3 +-- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 58461df152..76ab2aa8b1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -7,7 +7,6 @@ - @@ -357,8 +356,4 @@ - - - diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index fc31e3ac66..95539f2543 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -3,8 +3,7 @@ command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/mel stopsignal=TERM directory=/home/fetch/ros/melodic -; autostart=true -autostart=false +autostart=true autorestart=false stdout_logfile=/var/log/ros/jsk-shutdown.log stderr_logfile=/var/log/ros/jsk-shutdown.log From 40feb882815f387971d35ea7057023e95f570f23 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Wed, 1 Jun 2022 13:03:22 +0900 Subject: [PATCH 192/433] [jsk_fetch_startup] Disable L515 to reduce CPU usage --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 55d1fdc33c..2fbacb8d1f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -14,7 +14,10 @@ if [ $(hostname) = 'fetch15' ]; then export RS_SERIAL_NO_T265="925122110450"; export RS_SERIAL_NO_D435_FRONTRIGHT=""; export RS_SERIAL_NO_D435_FRONTLEFT=""; - export RS_SERIAL_NO_L515_HEAD="f0211890"; + # Disable L515 to reduce fetch's CPU usage + # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport + # export RS_SERIAL_NO_L515_HEAD="f0211890"; + export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.217"; @@ -32,7 +35,10 @@ elif [ $(hostname) = 'fetch1075' ]; then export RS_SERIAL_NO_T265=""; export RS_SERIAL_NO_D435_FRONTRIGHT=""; export RS_SERIAL_NO_D435_FRONTLEFT=""; - export RS_SERIAL_NO_L515_HEAD="f0232270"; + # Disable L515 to reduce fetch's CPU usage + # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport + # export RS_SERIAL_NO_L515_HEAD="f0232270"; + export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.218"; From e43ef88099d1b2fa75b146b1bd69bb0365dfef48 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 2 Jun 2022 18:10:49 +0900 Subject: [PATCH 193/433] [jsk_robot_startup] Add sigint and sigterm timeout arg for app_manager --- jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch index ad67c18d90..1e7a5be105 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/app_manager.launch @@ -2,6 +2,8 @@ + + @@ -64,6 +66,8 @@ + + From 7886fe7beb705e1be4576d3bf270b4232f97876d Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 2 Jun 2022 18:11:40 +0900 Subject: [PATCH 194/433] [jsk_fetch_startup] Add sigint_timeout for fetch's app_manager --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 76ab2aa8b1..098bc0e8fa 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -133,6 +133,7 @@ + From f8e83c1c6fa4b0499786ea2da1572c6b6d42c0f6 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 2 Jun 2022 18:12:51 +0900 Subject: [PATCH 195/433] [jsk_fetch_startup] Replace audio/vidoe recorder with rosbag converter in go-to-kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.app | 136 +++++++++--------- 1 file changed, 67 insertions(+), 69 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index a924c0648f..3aef562056 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -9,57 +9,6 @@ plugins: type: app_notification_saver/service_notification_saver - name: smach_notification_saver_plugin type: app_notification_saver/smach_notification_saver - - name: head_camera_video_recorder_plugin - type: app_recorder/audio_video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_head_camera.avi - audio_topic_name: /audio - audio_channels: 1 - audio_sample_rate: 16000 - audio_format: wave - audio_sample_format: S16LE - video_topic_name: /head_camera/rgb/image_rect_color/hz_converted - video_height: 480 - video_width: 640 - video_framerate: 30 - video_encoding: RGB - - name: object_detection_video_recorder_plugin - type: app_recorder/audio_video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_object_detection.avi - audio_topic_name: /audio - audio_channels: 1 - audio_sample_rate: 16000 - audio_format: wave - audio_sample_format: S16LE - video_topic_name: /edgetpu_object_detector/output/image/hz_converted - video_height: 480 - video_width: 640 - video_framerate: 30 - video_encoding: RGB - - name: panorama_video_recorder_plugin - type: app_recorder/video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_panorama.avi - video_topic_name: /dual_fisheye_to_panorama/output - video_fps: 1.0 - - name: rviz_video_recorder_plugin - type: app_recorder/video_recorder_plugin - launch_args: - video_path: /tmp - video_title: go_to_kitchen_rviz.avi - video_topic_name: /rviz/image - video_fps: 30.0 - - name: respeaker_audio_recorder_plugin - type: app_recorder/audio_recorder_plugin - launch_args: - audio_path: /tmp - audio_title: go_to_kitchen_audio.wav - audio_topic_name: /audio - audio_format: wave - name: rosbag_recorder_plugin type: app_recorder/rosbag_recorder_plugin launch_args: @@ -86,6 +35,8 @@ plugins: - /move_base/global_costmap/costmap - /particlecloud - /base_scan/throttled + - /dual_fisheye_to_panorama/quater/output/compressed + - /edgetpu_object_detector/output/image/compressed - /head_camera/rgb/throttled/camera_info - /head_camera/depth_registered/throttled/camera_info - /head_camera/rgb/throttled/image_rect_color/compressed @@ -96,6 +47,53 @@ plugins: - /server_name/smach/container_structure - /audio - /rviz/throttled/image/compressed + - name: head_camera_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /head_camera/rgb/throttled/image_rect_color/compressed + image_fps: 5 + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + video_path: /tmp/go_to_kitchen_head_camera.mp4 + - name: object_detection_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /edgetpu_object_detector/output/image/compressed + image_fps: 30 + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + video_path: /tmp/go_to_kitchen_object_detection.mp4 + - name: panorama_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /dual_fisheye_to_panorama/quater/output/compressed + image_fps: 1 + video_path: /tmp/go_to_kitchen_panorama.mp4 + - name: rviz_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /rviz/throttled/image/compressed + image_fps: 5 + video_path: /tmp/go_to_kitchen_rviz.mp4 + - name: respeaker_audio_converter_plugin + type: app_recorder/rosbag_audio_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + audio_topic_name: /audio + audio_sample_rate: 16000 + audio_channels: 1 + audio_path: /tmp/go_to_kitchen_audio.wav - name: result_recorder_plugin type: app_recorder/result_recorder_plugin plugin_args: @@ -106,19 +104,19 @@ plugins: plugin_args: upload_file_paths: - /tmp/go_to_kitchen_result.yaml - - /tmp/go_to_kitchen_head_camera.avi - - /tmp/go_to_kitchen_object_detection.avi - - /tmp/go_to_kitchen_panorama.avi - - /tmp/go_to_kitchen_rviz.avi + - /tmp/go_to_kitchen_head_camera.mp4 + - /tmp/go_to_kitchen_object_detection.mp4 + - /tmp/go_to_kitchen_panorama.mp4 + - /tmp/go_to_kitchen_rviz.mp4 - /tmp/go_to_kitchen_audio.wav - /tmp/go_to_kitchen_rosbag.bag - /tmp/trashcan_inside.jpg upload_file_titles: - go_to_kitchen_result.yaml - - go_to_kitchen_head_camera.avi - - go_to_kitchen_object_detection.avi - - go_to_kitchen_panorama.avi - - go_to_kitchen_rviz.avi + - go_to_kitchen_head_camera.mp4 + - go_to_kitchen_object_detection.mp4 + - go_to_kitchen_panorama.mp4 + - go_to_kitchen_rviz.mp4 - go_to_kitchen_audio.wav - go_to_kitchen_rosbag.bag - trashcan_inside.jpg @@ -163,12 +161,12 @@ plugin_order: - move_base_cancel_plugin - service_notification_saver_plugin - smach_notification_saver_plugin - - head_camera_video_recorder_plugin - - object_detection_video_recorder_plugin - - panorama_video_recorder_plugin - - rviz_video_recorder_plugin - - respeaker_audio_recorder_plugin - rosbag_recorder_plugin + - head_camera_converter_plugin + - object_detection_converter_plugin + - panorama_converter_plugin + - rviz_converter_plugin + - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin - tweet_notifier_plugin @@ -179,12 +177,12 @@ plugin_order: - move_base_cancel_plugin - service_notification_saver_plugin - smach_notification_saver_plugin - - head_camera_video_recorder_plugin - - object_detection_video_recorder_plugin - - panorama_video_recorder_plugin - - rviz_video_recorder_plugin - - respeaker_audio_recorder_plugin - rosbag_recorder_plugin + - head_camera_converter_plugin + - object_detection_converter_plugin + - panorama_converter_plugin + - rviz_converter_plugin + - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin - tweet_notifier_plugin From 7989d4cf99689bfb27a36c66b51d1e0cf977c40c Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 2 Jun 2022 19:20:00 +0900 Subject: [PATCH 196/433] [jsk_fetch_startup] Remove unused topic_hz_converter --- .../apps/go_to_kitchen/go_to_kitchen.xml | 21 ------------------- 1 file changed, 21 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 7b599f21b6..09c9f3cf28 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -19,27 +19,6 @@ - - - - - - desired_topic_hz: 30 - - - - - - - - desired_topic_hz: 30 - - - From 4e068a9cf94e018829c5b30d9c515f1ada675f13 Mon Sep 17 00:00:00 2001 From: iory Date: Fri, 3 Jun 2022 19:21:54 +0900 Subject: [PATCH 197/433] [jsk_fetch_startup] Use ROS_HOSTNAME and ROS_MASTER_URI=http://localhost:11311 --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 4 ++-- .../supervisor_scripts/jsk-app-scheduler.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 2 +- .../supervisor_scripts/jsk-fetch-startup-outside.conf | 2 +- .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf | 2 +- .../supervisor_scripts/jsk-human-pose-estimator.conf | 2 +- .../supervisor_scripts/jsk-network-monitor-outside.conf | 2 +- .../supervisor_scripts/jsk-network-monitor.conf | 2 +- .../supervisor_scripts/jsk-object-detector.conf | 2 +- .../supervisor_scripts/jsk-panorama-human-pose-estimator.conf | 2 +- .../supervisor_scripts/jsk-panorama-object-detector.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/robot-outside.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/robot.conf | 2 +- 16 files changed, 17 insertions(+), 17 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 2fbacb8d1f..43ae1bbf35 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -20,7 +20,7 @@ if [ $(hostname) = 'fetch15' ]; then export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; - export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.217"; + export NETWORK_DEFAULT_ROS_INTERFACE="localhost"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; elif [ $(hostname) = 'fetch1075' ]; then export DEFAULT_SPEAKER=2; @@ -41,6 +41,6 @@ elif [ $(hostname) = 'fetch1075' ]; then export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; - export NETWORK_DEFAULT_ROS_INTERFACE="133.11.216.218"; + export NETWORK_DEFAULT_ROS_INTERFACE="localhost"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index 91d9ceac86..8de89e02e4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -1,5 +1,5 @@ [program:jsk-app-scheduler] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index cd93a425b1..79cd2be0f0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf index 616e824d5f..e9966ce881 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup-outside] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 1cdd2ed50d..2a43de39d4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index 0325da1b22..b44ebd55cf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,5 +1,5 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf index cd794862c7..25fa60f0a8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf @@ -1,6 +1,6 @@ [program:jsk-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf index e27f9645ed..1058ba57af 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor-outside] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=false autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index f9949696b0..7d8a4b6621 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf index 5688491b3c..516e1caa80 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf @@ -1,6 +1,6 @@ [program:jsk-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf index f07778b651..139af6c42f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf @@ -1,6 +1,6 @@ [program:jsk-panorama-human-pose-estimator] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf index dd7111436d..bc320c5486 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf @@ -1,6 +1,6 @@ [program:jsk-panorama-object-detector] ; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" stopsignal=TERM ; directory=/home/fetch/ros/coral_ws diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 9bf1a76169..05377f460c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -1,5 +1,5 @@ [program:jsk-rfcomm-bind] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index 95539f2543..0cf97a4327 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,5 +1,5 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_robot_startup shutdown.py --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf index f5a6196858..0ce0afc615 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf @@ -1,5 +1,5 @@ [program:robot-outside] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf index b4db414f79..11ca006f09 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf @@ -1,5 +1,5 @@ [program:robot] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && rossetip $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 099479d05ff3bd1715d372ca0d433b8474c76c4d Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 7 Jun 2022 17:18:38 +0900 Subject: [PATCH 198/433] [jsk_fetch_startup] Use launch instead of single roseus in welcome_to_jsk app --- .../jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app b/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app index 210ba6e4bd..ded1914d18 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/welcome_to_jsk/welcome_to_jsk.app @@ -1,7 +1,6 @@ display: Welcome to jsk platform: fetch -run: welcome_to_jsk_fetch/welcome-to-jsk.l -run_args: '"(progn (init) (give-bag))"' +launch: jsk_fetch_startup/welcome_to_jsk.xml interface: jsk_fetch_startup/welcome_to_jsk.interface icon: jsk_fetch_startup/welcome_to_jsk.png plugins: From cdd7bc886a2d17ec097ce3115f6b7e2831be7229 Mon Sep 17 00:00:00 2001 From: Guilherme Affonso Date: Tue, 7 Jun 2022 10:54:06 +0900 Subject: [PATCH 199/433] Add roseus_resume interrupt and resume apps --- .../jsk_robot_startup/apps/robot_apps.installed | 4 ++++ .../roseus_resume_interrupt.app | 6 ++++++ .../roseus_resume_interrupt.interface | 2 ++ .../roseus_resume_interrupt.png | Bin 0 -> 3470 bytes .../roseus_resume_resume.app | 6 ++++++ .../roseus_resume_resume.interface | 2 ++ .../roseus_resume_resume.png | Bin 0 -> 3760 bytes 7 files changed, 20 insertions(+) create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.app create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.interface create mode 100644 jsk_robot_common/jsk_robot_startup/apps/roseus_resume_resume/roseus_resume_resume.png diff --git a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed index e142d9282c..378c08693f 100644 --- a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed +++ b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed @@ -3,3 +3,7 @@ apps: display: Personal use - app: jsk_robot_startup/check_use_sim_time display: Check /use_sim_time param + - app: jsk_robot_startup/roseus_resume_interrupt + display: Interrupt + - app: jsk_robot_startup/roseus_resume_resume + display: Resume diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app new file mode 100644 index 0000000000..d6ea2dad0f --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.app @@ -0,0 +1,6 @@ +display: Interrupt +platform: all +run: rostopic/rostopic +run_args: "pub -1 /roseus_resume/interrupt std_msgs/Empty" +interface: jsk_robot_startup/roseus_resume_interrupt.interface +icon: jsk_robot_startup/roseus_resume_interrupt.png diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface new file mode 100644 index 0000000000..044105d644 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} diff --git a/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png b/jsk_robot_common/jsk_robot_startup/apps/roseus_resume_interrupt/roseus_resume_interrupt.png new file mode 100644 index 0000000000000000000000000000000000000000..352d08ee47ecaf8e17c5eaf96dc93327205a7b21 GIT binary patch literal 3470 zcmX9>X*?9%8@)5u5F$(VG_v>N&CX;uV`MFa5S4waiDGENM2ofTy9T{vjg%}yn6Yb8 zh>T^B>>2y^SN{+9IUnwM&iUQ*dpyQc)TRa$-_k0{T5ZQlin6jDj_i4wfd1jw0}L zKPV4j2M*-OB)?R2Cf-3pTYTR6uA40pE8V|Pm^3as&xR~Uge2qn_%a3_N@&Z^%OF#c zyEwc%>t_M{=zq|OvZTHj=n{M*)8v&)i4PI=R%Bd~NQoBjzdO>92~K1xLStN>GTX^M zfc2$@Al*^*4?##Ltb-lf2)jPP-!-mX7;ypO(w|D}uVTl%0r#Kby(NS-Y&y;m?^WQr zCA58fY#Vlm!73c7iuhi!-Lt^C{T4qBJ7{3vS-L`mVuO*pRrsNJoFb067KM*DsjpBF z_TQ?7tg;|gQB&QNC%EJZ4`lyf2Iewwgv~#zJr7r^rzD{LVimsvg65cr-QK=aBxS+F z)!ap5zc+zSPypEV!!@b&l86P(z7loPKs1!#4bv9$%+0<7 z%-#H%u!Kz(LrRh$SfY{?2D6bCV<{4>r%h54PZBShN2Ry2f5d`K1RW3hiS1FZY#`~eey2bOyUPFPh&TJ~XPr*x>jvVIafJ$<+L>8y%8a*!vFx|U{r`l~^%TfFIZfXw5 zLPmWSgI48Y{NO-%CypLZU2+wbSAN~QzjTrAj^ps#2tw0*$g5vrm} zvM^8Q3n#$hn~nSOv)9j^sT+`MHzU|ot5CJ*L6*7O)MnLc;6KgDX!e9+u?|<#uPT)b zElj{~abL!D-(&YDt7dP5U`t8f`Lx)PA-A~b6{ldjPA2Rn1E(QzO`=)gB0W+;U*fc9 zK~@=#xkQzwY|n(XTZdiv5j0JdDXQF+3Q{bmIvHYw0rOJzIQiE6oY|4%!Ojg=8C%u| ziQa^Io&ec&i)!CO4lw-7jhvlF>y=L`&QhBWF*;))UBgTM<w{r;?P><$M`>}}s~tEKxQZQrs0=NB}IbL%I59Hv!W z_Sm=*)*4J+i+!bX(6n|SB~IO6NNQ>ro|Kv8^z^z+y1A*p_r7U0)E6>XL?M=>y=S}7 zG37fZ*A2vYGL?N#?0sfpgVx%V$z#9MhSnB};V8<}4*o3_>tT7iiRk6sWJ3i1855_W zlD~w`2yYMm1v#9zx9Ez1937VbZcki3?x$F3nOMzAxzit$m1#bA4C*xJ>`t#*q#+0} zqdGMfVp?ZRDv4y}hPG3#aEbFV;Mj1J0^Sp1U1&FF8>4 zrF4Yg>r<}=*n8II@`Wp2+d6>S`RMAt5a-A!``mee)v21r@%FSkpD4?+tN3eti(;GF z+mQ1(DtqM%1Y0=96)7SVETXZiyzy7ug4ce<*JXW#8zg-Fw3`QMia5LZ@VxV1U8tB5 z$1p2cRd&cxovcYX$7A}l?f*@1%lJXX6pws;Kq!WV_3Pkzc(J!%Tm9*B*zWnN{VrnQ zw3xa1BM^4d&12j6W-&0RGV~j z1pnJ5$#dH0K!C@FLu-^)*$IK(q(Y^Dmw#QwGF3{h#nS|vfDb9_tbTWb3h21<_laG& z5E}==T|f|Eh-$Ayvk|87-p84Tv4WVBl{eYLM1YtnN&#YEmF}8;MMl1R%qF(<__jjh z!Q*!i@*#x&k`cN*U&w;4f&?(|gn=QP<+xE4>lX7QXtXzPsTLGs^-tg1}cL zLQh&=t|7PA8lr=?Q?vHx(=Xz{;-8&e@*1W=641(TuCr&W0N2eU`BeSUja5%Nv7HdL zFa9UQZ6aM*OkD0nFc*zmwV85*5v#TunB^CGop&%xQ;LA_Ah~U)_u_wwPv9&z{(k-$ zYRt6;iK8Rhw}r(*3rHz4LH2-@Ba<>;ck{D@uEIB-JVdoe(Kxx?oDQ^;+v}LlVZ3Y) zD9_;hEwt}16gO}Ue)NX9&mRSZUi4}J{M644QZJ$Cn{}h-lwSni={P>BGFfYWZ@@nNIoo6z0;=|AZ$eBxVmZ{i}DzhXEYePxtc?q0F29vbq)bw|^g{iDA~Q;ff$; zP5&Q%rfq=?vq~PO#hrMV+#cba|l@SPevQCP2yDS*y4rM4t%B(-d-d& zupR}h6ulf3Ix5&jFaQJ57igW+8%L^o>eRFy57$f9o^fu`#ldnbdv7vEr;`SR3sCGJ zz{YS7W_Zo(!|=5VD>_AMqGgHpen&}&86(tueK}WAou*Q)4s?qDb02DdR3#8Fl2~@b z3|E*_mtx%ikpLPq|y!FC~o4v(q_THE#^$IisO3KU`@KNcU`$ z$P$}>;y5NZ$T3t~{vwL+qPy;-{(~AV=E*{5C=mWEWZZU@n{YbpcndN{qp67CYJ9iE z(!xxAqaNAPU-&~3!1}SfSyHyurN^e(#Om0#Qvy{*$kjqKv-j;7GfgO3uVS^%s>z-N z9SNU&gp~MB56C(eJY!-7&_|++4f)0DhH^I@rSBE=eB_PL2iUbdPHhFwFZDZjv)Vqi zhW7-u$vleaqB}!1q~>7U{jnT!)6D6xG%0(`4?C&Pn(SR@3~Ta9m-FkYev<{aqyYK_ z;)$eGSIntG=H1l10S}B3fOPz5HKv;B`&Of2X*|+0# zfw@t|w35NmO~LVDFmU;KTFdcjo#9(_PqW^Z{3J=FT=V(TAdv;@hsT$G&>@d3W8f-> zWr7@=k5RDfm1SD|okce$g7_E24JQ5gV53Y$rPI^o4fe{d_&{v8TLu^4C7RifuEVl5 zprO#YEm?`{QuF!J%wd7gtr-YYLNP|-$1|ot?Ump?yJ?ba9{%2StPC|9AnZN9xtE!dgfF1x#$2npM&9porT$WbL>p!rA@zmX0?~^Q{!cMouT14 hIZHJO`ZJ?*N5GJ=KrqPS@t@xoKpL7ElPx@YDq*vRCr$PoptPOM-j)rMOq|ia0^bc1S>7>4#f&df#T320g43(QW8RN3liMY z65OSDv9`Dtx8jr#B)I0&?#;XJ_q+F=nc3YV_w4-j-tVr=&d%x0G&N3jEw=#Dd}iQw;C0d z$|3VXNq3j@hjK&ajWiYp0FV1hda?emxI-}j^ByVb*-~-8MD+Qel=P0I!ez73?MDE{;01z8`OcDV zAnELpfj0C(U+|dp%q={0_i#fn0Pp%YN;=#U&js>E220 z92;eKuVW($vT&_IIeR}`qL!+HfNxMeUTNOAnCycWCpB{$VR;wnfhV?EOuX#w0{QC`BuI@ z$qs+a7^h}e^cc@iS9uO?Q6*o!4<^V#(n?6KeJo~IvUXU}?#q%6>EZjHf#P0WkrUn~ z>1r7RauZW2|*v_Nhe7tmyNCI94EeGp*A4xAu-bWE6kO}Z{sAf>A%>bx% zqtZU!H@B4Z%LwI0)aOEyK9q3-zA34Xt1PJ|17Hs2ogaZ$CV^^OeDZi9yj0QyBE(3h zWn_!uP>TVOVm}*D@*wCzB=qFl2)M1iB1o5O*U%W&U;uRcCrk3GcRB61mh_Qr-1((7 z;oS1RfZhPL@kLA94oWis`E^rg@iF|b_LX~6ylpt8xJobFP`AGWPe(kT@FD!wmvpxI3ZHeWw zh*ODY;x4AcE!ykJbN?+C_`2w|_&suK!Zf(WXG19lKx1`+6C0#qlsvhB)97W_48jew zX^s4j{{F|gNM!cMw&8su^3p=Xngyj80H?=GIWR%VgC(uRJO2WbnE$Mf`InpW*#h^! z2m6=khMoY6rbk`QnzP;HOE3Vg+c;lX0rl=B3v2kUn*^%pdT=1|zFe&9wYJ0YE)X!n+6H4Jn;wF_=v?~HaX(2xBf;M8M9M0tj-Ap|)LK;LgUZ2SmZ zd~0jEY~jQA^^9*L&L+ekaup8+IHNMZb#L$;0OwFFqIHs0#2^O$YYr;m%z=5dHtHW1>qlJ4ao6nnv8bVCjU;P8N7y9IE~KCh&{Jb7-IRISnV;lps#=&7<0 zq@xW=HQe2-VeiCM+$Az^ltB3Rp^360NW{;>A_!*m!PWYi8U2SA3SZ!$83zm_oZF8u z$^dZNn~lWftc=pGZ>MSpeY|M^ZCH2twk9 zdl+Xx2z$J-ZS7`{PTIccJkLnMAJP8Ne$4w=V`oC{JkQ6_i9r3xskQ(*|C)*)3l7U| za)rV>rbJNQd2`yM82X`c0E9-|#?0Wo0r2zty-_knPB@ntlYSZ^x1c$LF(ZIbcm>CX zMCMr4hbOlsDw!A8xjo4&y$paG(`SsU8dCb-gd)!??EeU}5kM$JrR{!mMsNI!Qw zWB==<7)(=hF9UciZiG)GFN_f&62g*q{fo6=KE{c)FX5K&I_hByut(+?0xtpHm69}C z5aE;z?P;?KPqK`XdoT)pY6?Aa0J;OS^2^Hr2qPfV1-wb|(1~W|=o-J&?{7^e;OKaL z358fW|6 z-Oj@R2uWhw->w~&5 z9ntT(LLmYrTDY1(zzr^A7Qmd$VeJGD1CX}$yPYGR*5Ju0g^RKID4IRoBR#Lc_&E-Z zU1Y&elJrz#N4$mc8tw!S17Os#`k~iy{Onv%W&=#zA;*d|FAg%ilxhIpRMwC%;xtS~ zBo704lt2V968tzdK-wl|A)2Hbmv{X0tg2fNeb75tL+CIIn_?|J48S)Ii<$*+r?R%S zjMrxyByF5Bqe3Aspc+1f#4UW(NC?`Ztm=fu0J}-l7+?+Cv`;|ic{;W9+}3^qnh@B{ z05yd`Y%A8(IaP$f_6*$209*eIY>J@u3@{5tP*Vl3W&r#HW}ymh#-QB{fVFcr#vqp8 z%)xsz!K}=|EWJ5|>|uaeI)pq@64I^(noF34O13uGRw!0&0o>oso=zT3Ad?dgMp&2y znp3ESO13th5HYhIfT_I<(A>gj?iLQyw7?MCsV&vY;}FW;Q1;FY-Wz~{TWFY>yhR#% zLc`oySRxF7ub;`(D5(X9=J5dggL#=?77O$e9NNOeEn88h4TYn~8fF2MQuqS8B9!c#}kt(3w!I zK4I!fqM#XN<}DDq{uwyR0QB{QRS~QJM_c0xEQ{XMW^QTXNZCh{C^zIV0GX}H%4r4i z1EbQc4cm|?5?WD6+6sdtiiCM^p~f6)ftD)PLZ#D!Z#}7Ezn#*|heFkJZUC0kl11A# z)!K^vpvLl5tQ}INwLy|agCptU$pJ*Jdn*v%W=(cr9g}vRgKTV8rU}=Mdp=Lv)fA1}_+~K$M_SPdHU88MF5m<8JrW6jNZ`{Lz$* z0pUo|D8ii&x2|?WJ8JT-D;i}Po?=Zyr?QC@jXKbwCSFU2Tp@6I;8r%y!fw0Uc)$CM z@Bv2-;f+|8WPoVlNL~^jj?r%Ny{IG1W_tF4!ja@ZE>e5JGqHu*5pHg!V=a{3(`K}# zV?hyyYQ>|wH#Ay2nw$%in++*_R-sk;24Iey^6`{I-S*GHR+o=oFc}gm87jOC24_Fe zkqV{ztc|M$wUUweBXr@`II;9{yoh+__rwtF9G52|HGNIF?mS2h)RuQX&sA@I;03xa zUw_XUYcc?M94+Zk4?;_AQ5I1Y5l`1C0~$W6eUmsM0?_cVNJmSb+6;iLfLuY*q>(r} zkZ%y%K{3I{LYM+=pe^QaPQFLIyF4{v=j8hd>-xLaQJVpnf4`Jo4x4opsH}a+2sCz9 z{0SGwNyB5++c`GA7RXY(`>R183;^-~ z6$(bVJbb;#(mn@C?|d-936gSd0_McMjBEAj1Jxp2wQk(qo+#-EV@B^ywBzIxgIRs^ z`(}W}=it~3nP8c4ybutsNS{hsy1r!u4iAa5o+632y(Niu*P-E?&sbHj{beNjya5*T zA{cU&->r)pj^BwuA}oqGc5TZZE?ZbJ34gan>{ym^O!5P)Ch)C7Vh9FU;K8??Tmz+X zAWJqUi3(xIrDtTca0Svk&p0G;9ABtEXer)g+3-ahZZ2HdDf80zEmoZPo`usEKLTtA zmLe41u@~);8BR$x0jL;uvLsxoh`C!Z1{;kxF(ucCuEo)nlTO8RYlYMZeiU~=w_jYt zXGNy;>9fwe+>R5)Y2}p73DA#_Skjc&zZPM}zyJ$j6r~Ae=FuB$Ga%p*@k7?n-mmguB&^lFM`nz5FT~Vt+vG%p0D}ooxQ( zHhpg}=)#h*` z?3+AuC>4wL5rq?f0|;0}L4#I~6VBDn-?qgkaV^8ng#ota#Fk!2V}Q~Wo!EGd0VcL# zrO|B+P@19>8?Q0I#5Sxnx{U!!Q*>hEH3pd2hLuLQF+gdGPHeo!02AA=(&#n@C{59c ajrV^DLAIYaTMJVF0000 Date: Tue, 7 Jun 2022 23:07:16 +0900 Subject: [PATCH 200/433] [jsk_fetch_startup] Add hz_measure node to monitor rgb/depth topics --- .../config/fetch_analyzers.yaml | 14 +------------- .../config/sanity_targets.yaml | 2 -- .../jsk_fetch_startup/launch/fetch_sensors.xml | 18 ++++++++++++++++++ 3 files changed, 19 insertions(+), 15 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml index f4847a4cba..d6b18c8111 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch_analyzers.yaml @@ -102,7 +102,7 @@ analyzers: path: Head Camera timeout: 5.0 startswith: 'head_camera' - num_items: 2 + num_items: 4 imu: type: diagnostic_aggregator/GenericAnalyzer path: IMU @@ -154,18 +154,6 @@ analyzers: contains: '/audio' timeout: 100 discard_stale: true - head_depth_image: - type: diagnostic_aggregator/GenericAnalyzer - path: HeadDepthImage - contains: '/head_camera/depth/image_raw' - timeout: 100 - discard_stale: true - head_rgb_image: - type: diagnostic_aggregator/GenericAnalyzer - path: HeadRGBImage - contains: '/head_camera/rgb/image_raw' - timeout: 100 - discard_stale: true nodes: type: diagnostic_aggregator/AnalyzerGroup path: Nodes diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml index 6b8ce4ff93..24a3521055 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/sanity_targets.yaml @@ -2,8 +2,6 @@ topics: - /audio - /edgetpu_human_pose_estimator/output/image/compressed - /edgetpu_object_detector/output/image/compressed - - /head_camera/depth/image_raw - - /head_camera/rgb/image_raw nodes: - /head_camera/head_camera_nodelet_manager diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml index 43d79040b6..2649c370e9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml @@ -16,6 +16,15 @@ + + + + + warning_hz: 5 + + + + + + + warning_hz: 5 + + Date: Tue, 7 Jun 2022 23:29:14 +0900 Subject: [PATCH 201/433] [jsk_fetch_startup/sanity_diagnostics] Make clear_params true --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 098bc0e8fa..241e07c758 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -350,7 +350,8 @@ - + duration: 60 From ae9d5b578eee1238dc11e35f875b36b040ca5379 Mon Sep 17 00:00:00 2001 From: iory Date: Tue, 7 Jun 2022 23:32:41 +0900 Subject: [PATCH 202/433] [jsk_fetch_startup/diagnostics_aggregator] Make clear_params true --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 241e07c758..9b73014607 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -105,7 +105,8 @@ + name="diag_agg" args="CPP" output="screen" + clear_params="true" > From 3e8bbc1ae0e41fe38c16ccf144465103ed489c15 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 8 Jun 2022 18:58:59 +0900 Subject: [PATCH 203/433] [jsk_fetch_startup] enable google chat --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 11 +++++++++++ jsk_fetch_robot/jsk_fetch_startup/package.xml | 4 ++++ 2 files changed, 15 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 9b73014607..555c1f45ba 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -6,6 +6,7 @@ + @@ -151,6 +152,16 @@ + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 9031016111..5e2944ee70 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -67,6 +67,10 @@ julius_ros respeaker_ros + + dialogflow_task_executive + google_chat_ros + robot_pose_publisher From f7964164b97983a0ffa4a24596b9ef0a0eca1edb Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 8 Jun 2022 22:54:34 +0900 Subject: [PATCH 204/433] [jsk_fetch_startup] fix typo in google_chat_ros --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 555c1f45ba..00b5e78d56 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -156,10 +156,10 @@ - + - + From 9a410977ba55437adffeae9fd1c5ef51dc15dea6 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 16 Jun 2022 10:05:52 +0900 Subject: [PATCH 205/433] [jsk_fetch_startup] add use_audible_warning arg and make args in supervisor_job to be loaded from roslaunch --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 14 ++++++++------ .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 00b5e78d56..71eb804551 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -12,18 +12,18 @@ - - - + + + - + - + @@ -34,6 +34,7 @@ + @@ -349,7 +350,8 @@ + output="screen" + if="$(arg use_audible_warning)" > diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 2a43de39d4..4005efea8d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From cbef38272b916263fbf3a72e24ac4cbf80eab207 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 16 Jun 2022 10:08:44 +0900 Subject: [PATCH 206/433] [jsk_fetch_startup] fix --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 71eb804551..91d712f490 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -12,9 +12,9 @@ - - - + + + @@ -23,7 +23,7 @@ - + From 94cd988ee18c9515840307516c36e7be987a92b5 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 15 Jun 2022 11:40:12 +0900 Subject: [PATCH 207/433] [jsk_fetch_startup] Wait for a certain time in get-battery-charge-state --- .../euslisp/navigation-utils.l | 25 ++++++++++++++++--- 1 file changed, 22 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index c672b8254c..20918f735f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -135,11 +135,30 @@ (send (send *undock-action* :get-result) :undocked)) -(defun get-battery-charging-state (&key (timeout 1500)) +(defun get-battery-charging-state (&key (timeout 1500) (dock nil)) + """ + Get battery charging state + Args: + - key + timeout: Set waiting time for topic. + dock: Set t when docking to get right result. + """ (let* ((msg (one-shot-subscribe "/battery_state" power_msgs::batterystate :timeout timeout)) - (is-charging (if msg (send msg :is_charging)))) + (is-charging (if msg (send msg :is_charging))) + (start-get-state-time (send (ros::time-now) :sec)) + (duration 0)) ;; You may fail to subscribe /battery_state ;; because of message md5 difference between melodic and indigo. + ;; If /battery_state is subscribed before /battery_state becomes true + ;; while dock succeeds, the result will not be correct, + ;; so wait for a certain time when docking. + (when dock + (while (and (< duration (/ timeout 1000)) (not is-charging)) + (setq msg (one-shot-subscribe "/battery_state" + power_msgs::BatteryState + :timeout timeout)) + (if msg (setq is-charging (send msg :is_charging))) + (setq duration (- (send (ros::time-now) :sec) start-get-state-time)))) (if (not msg) (return-from get-battery-charging-state nil)) (if is-charging :charging :discharging))) @@ -652,7 +671,7 @@ Args: ;; change the inflation_radius (restore-params) (send-kitchen-mail) - (setq success-battery-charging (equal (get-battery-charging-state) :charging)) + (setq success-battery-charging (equal (get-battery-charging-state :dock t) :charging)) (and success-go-to-kitchen success-auto-dock success-battery-charging))) From be3ed0c10220de89b16db3c1dfb460a448766ddc Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 15 Jun 2022 15:25:03 +0900 Subject: [PATCH 208/433] [jsk_fetch_startup] split method into two; add wait-until-is-charging --- .../euslisp/navigation-utils.l | 40 +++++++++++-------- 1 file changed, 23 insertions(+), 17 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 20918f735f..aec6cca5e7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -134,35 +134,40 @@ (return-from undock nil)) (send (send *undock-action* :get-result) :undocked)) +(defun wait-until-is-charging (&key timeout 10) + """ + Wait for updating battery charging state especially when robots dock. + Args: + - key + timeout [sec]: Set waiting time for updating /battery_state topic -(defun get-battery-charging-state (&key (timeout 1500) (dock nil)) + ;; If /battery_state is subscribed before /battery_state becomes true + ;; while dock succeeds, the result will not be correct, + ;; so wait for a certain time when docking. + """ + (let ((msg nil) + (is-charging nil) + (duration 0) + (start-time (send (ros::time-now) :sec))) + (while (and (< duration timeout) (not is-charging)) + (setq msg (one-shot-subscribe "/battery_state" power_msgs::BatteryState)) + (if msg (setq is-charging (send msg :is_charging))) + (setq duration (- (send (ros::time-now) :sec) start-time))))) + +(defun get-battery-charging-state (&key (timeout 1500)) """ Get battery charging state Args: - key timeout: Set waiting time for topic. - dock: Set t when docking to get right result. """ (let* ((msg (one-shot-subscribe "/battery_state" power_msgs::batterystate :timeout timeout)) - (is-charging (if msg (send msg :is_charging))) - (start-get-state-time (send (ros::time-now) :sec)) - (duration 0)) + (is-charging (if msg (send msg :is_charging)))) ;; You may fail to subscribe /battery_state ;; because of message md5 difference between melodic and indigo. - ;; If /battery_state is subscribed before /battery_state becomes true - ;; while dock succeeds, the result will not be correct, - ;; so wait for a certain time when docking. - (when dock - (while (and (< duration (/ timeout 1000)) (not is-charging)) - (setq msg (one-shot-subscribe "/battery_state" - power_msgs::BatteryState - :timeout timeout)) - (if msg (setq is-charging (send msg :is_charging))) - (setq duration (- (send (ros::time-now) :sec) start-get-state-time)))) (if (not msg) (return-from get-battery-charging-state nil)) (if is-charging :charging :discharging))) - (defun go-to-spot (name &key (relative-pos nil) (relative-rot nil) (undock-rotate nil) (clear-costmap t)) "Move the robot to the spot defined in /spots_marker_array topic. The reason for using relative-pos and relative-rot instead of relative-coords is that it is easier to understand if relative-pos and relative-rot are specified in the different coords (specifically, world (map) and local (spot) coords respectively). For detail, see https://github.com/jsk-ros-pkg/jsk_robot/pull/1458#pullrequestreview-1039654868 Args: @@ -671,7 +676,8 @@ Args: ;; change the inflation_radius (restore-params) (send-kitchen-mail) - (setq success-battery-charging (equal (get-battery-charging-state :dock t) :charging)) + (setq success-battery-charging (progn (wait-until-is-charging) + (equal (get-battery-charging-state) :charging)) (and success-go-to-kitchen success-auto-dock success-battery-charging))) From 5d49386d67669695f09635e95d6a4468e9cbd5a8 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 15 Jun 2022 16:15:13 +0900 Subject: [PATCH 209/433] [jsk_fetch_startup] Fix about keyword argument --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index aec6cca5e7..fa37442072 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -134,7 +134,7 @@ (return-from undock nil)) (send (send *undock-action* :get-result) :undocked)) -(defun wait-until-is-charging (&key timeout 10) +(defun wait-until-is-charging (&key (timeout 10)) """ Wait for updating battery charging state especially when robots dock. Args: @@ -677,7 +677,7 @@ Args: (restore-params) (send-kitchen-mail) (setq success-battery-charging (progn (wait-until-is-charging) - (equal (get-battery-charging-state) :charging)) + (equal (get-battery-charging-state) :charging))) (and success-go-to-kitchen success-auto-dock success-battery-charging))) From f889a65ef076747b22ee11041808fa2be0d1b480 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 15 Jun 2022 16:16:21 +0900 Subject: [PATCH 210/433] [jsk_fetch_startup] Return charging state in wait-until-is-charging --- .../euslisp/navigation-utils.l | 19 ++++++++++++------- 1 file changed, 12 insertions(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index fa37442072..5b50f58774 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -145,14 +145,19 @@ ;; while dock succeeds, the result will not be correct, ;; so wait for a certain time when docking. """ - (let ((msg nil) - (is-charging nil) - (duration 0) - (start-time (send (ros::time-now) :sec))) - (while (and (< duration timeout) (not is-charging)) - (setq msg (one-shot-subscribe "/battery_state" power_msgs::BatteryState)) + (let* ((msg nil) + (is-charging nil) + (duration 0) + (start-time (send (ros::time-now) :sec))) + (while (not is-charging) + (when (> duration timeout) + (ros::ros-warn "Skip waiting for charging state because of timeout") + (return-from wait-until-is-charging :timeout)) + (setq msg (one-shot-subscribe "/battery_state" power_msgs::BatteryState + :timeout 1000)) (if msg (setq is-charging (send msg :is_charging))) - (setq duration (- (send (ros::time-now) :sec) start-time))))) + (setq duration (- (send (ros::time-now) :sec) start-time))) + :charging)) (defun get-battery-charging-state (&key (timeout 1500)) """ From 7ba0e00ec4039253210b74e5270c12a17220614d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 16 Jun 2022 17:36:53 +0900 Subject: [PATCH 211/433] [jsk_fetch_startup] enable l515 for fetch1075 --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 43ae1bbf35..db9f9eb944 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -37,8 +37,8 @@ elif [ $(hostname) = 'fetch1075' ]; then export RS_SERIAL_NO_D435_FRONTLEFT=""; # Disable L515 to reduce fetch's CPU usage # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport - # export RS_SERIAL_NO_L515_HEAD="f0232270"; - export RS_SERIAL_NO_L515_HEAD=""; + export RS_SERIAL_NO_L515_HEAD="f0232270"; + #export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="localhost"; From 49bafaec7a73f8b661bd4228db1781cf34329fd9 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 17 Jun 2022 17:08:07 +0900 Subject: [PATCH 212/433] [jsk_fetch_startup] Use jsk_pcl_ros/container_occupancy_detector in kithchen demo --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- .../launch/trashbin_occupancy_detector.launch | 16 +++++++--------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 5b50f58774..0112a5fc24 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -432,7 +432,7 @@ Args: (format nil "CO2 concentration is ~A ppm" (send msg :data)))))) (defun notify-trashcan-occupancy (&key (location "kitchen")) - (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/trashbin/occupancy" + (let* ((msg (one-shot-subscribe "/trashbin_occupancy_detector/container/occupancies" jsk_recognition_msgs::BoundingBoxArray :timeout 3000)) (occupancy (if msg (send (elt (send msg :boxes) 0) :value))) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index 97d02e1a22..d889ecc2f2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -3,7 +3,7 @@ - + @@ -142,14 +142,12 @@ - - - - - - + + + + + + Date: Fri, 17 Jun 2022 17:29:33 +0900 Subject: [PATCH 213/433] [jsk_fetch_startup] Update minimum euclidean cluster to support quater pointcloud --- .../jsk_fetch_startup/launch/trashbin_occupancy_detector.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch index d889ecc2f2..76030da7cd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/trashbin_occupancy_detector.launch @@ -57,7 +57,7 @@ tolerance: 0.02 - min_size: 100 + min_size: 20 vital_rate: 0.1 From 50cef85885e8aa60256cd572c07719c12d63aaf9 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Sat, 25 Jun 2022 15:12:31 +0900 Subject: [PATCH 214/433] [jsk_fetch_startup] move container occupancy detector to jsk_pcl_ros --- .../jsk_fetch_startup/CMakeLists.txt | 11 -- jsk_fetch_robot/jsk_fetch_startup/package.xml | 3 + .../src/container_occupancy_detector.cpp | 126 ------------------ 3 files changed, 3 insertions(+), 137 deletions(-) delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index 29683126ba..20cade468e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -21,11 +21,8 @@ find_package(catkin REQUIRED COMPONENTS tf2_ros tf2_eigen tf2_msgs - pcl_ros - pcl_conversions ) find_package(Boost REQUIRED COMPONENTS) -find_package(PCL 1.8 REQUIRED) ################################### ## catkin specific configuration ## @@ -41,18 +38,10 @@ catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh include_directories( ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS} - ${PCL_INCLUDE_DIRS} ) add_executable(trashbins_pose_estimator src/trashbins_pose_estimator.cpp) target_link_libraries(trashbins_pose_estimator ${catkin_LIBRARIES} - ${PCL_LIBRARIES} -) -add_executable(container_occupancy_detector src/container_occupancy_detector.cpp) -target_link_libraries(container_occupancy_detector - ${catkin_LIBRARIES} - ${PCL_LIBRARIES} - ${Boost_LIBRARIES} ) ############# diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 5e2944ee70..0a031ea04e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -74,6 +74,9 @@ robot_pose_publisher + + jsk_pcl_ros + rostest diff --git a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp b/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp deleted file mode 100644 index 9203bfe01a..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/src/container_occupancy_detector.cpp +++ /dev/null @@ -1,126 +0,0 @@ -#include - -#include - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -const float FLOAT_MIN = std::numeric_limits::min(); -const float FLOAT_MAX = std::numeric_limits::max(); - -class ContainerOccupancyDetector{ -private: - std::string _inputBoxes, _inputCloud, _debugCloud, _outputBoxes; - ros::Subscriber _containerBoxesSub, _pointCloudSub; - ros::Publisher _debugPointPub, _occupancyPub; - geometry_msgs::Quaternion defaultOrientation; - jsk_recognition_msgs::BoundingBoxArray _containerBoxes; - sensor_msgs::PointCloud2 _transformedCloudMsg; - tf2_ros::Buffer _tfBuffer; - tf2_ros::TransformListener* _tfListener; - -public: - // constructor - ContainerOccupancyDetector(ros::NodeHandle &_nh, ros::NodeHandle &_pnh){ - this->_tfListener = new tf2_ros::TransformListener(_tfBuffer); - this->_containerBoxesSub = _nh.subscribe("input_boxes", 10, &ContainerOccupancyDetector::CalculateOccupancyCB, this); - this->_pointCloudSub = _nh.subscribe("input_cloud", 10, &ContainerOccupancyDetector::PointCloudTransformCB, this); - this->_debugPointPub = _nh.advertise("debug_cloud", 10); - this->_occupancyPub = _nh.advertise("output_boxes", 10); - // init default orientation const - this->defaultOrientation.w = 1.0; - this->defaultOrientation.x = 0.0; - this->defaultOrientation.y = 0.0; - this->defaultOrientation.z = 0.0; - }; - // destructor - ~ContainerOccupancyDetector(){ - delete this->_tfListener; - ROS_INFO("Killing node..."); - }; - - void PointCloudTransformCB(const sensor_msgs::PointCloud2::ConstPtr& msg){ - geometry_msgs::TransformStamped transformStamped; - try { - transformStamped = _tfBuffer.lookupTransform("base_link", msg->header.frame_id, msg->header.stamp, ros::Duration(10.0)); - tf2::doTransform(*msg, this->_transformedCloudMsg, transformStamped); - this->_debugPointPub.publish(this->_transformedCloudMsg); - } catch(tf2::TransformException &ex) { - ROS_WARN("Failed to transform tf"); - ROS_WARN("%s", ex.what()); - } - }; - - void CalculateOccupancyCB(const jsk_recognition_msgs::BoundingBoxArray& msg){ - const sensor_msgs::PointCloud2 inputCloud = _transformedCloudMsg; - pcl::PCLPointCloud2 pclPC2; - pcl::PointCloud::Ptr pclCloud(new pcl::PointCloud); - jsk_recognition_msgs::BoundingBoxArray boxOccupancy = msg; - if (!inputCloud.data.empty()){ - // convert to PCL cloud - pcl_conversions::toPCL(inputCloud, pclPC2); - pcl::fromPCLPointCloud2(pclPC2, *pclCloud); - for (int i = 0; i < msg.boxes.size(); i++) { - // calculate each bounding boxes - // pcl::PassThrough filter; - pcl::CropBox boxFilter; - pcl::PointCloud::Ptr boxFilteredCloud( - new pcl::PointCloud); - pcl::PointXYZ minPt, maxPt; - float occupancy; - boxFilter.setMin(Eigen::Vector4f((msg.boxes.at(i).pose.position.x - - msg.boxes.at(i).dimensions.x / 2.0), - (msg.boxes.at(i).pose.position.y - - msg.boxes.at(i).dimensions.y / 2.0), - FLOAT_MIN, 1.0f)); - boxFilter.setMax(Eigen::Vector4f((msg.boxes.at(i).pose.position.x + - msg.boxes.at(i).dimensions.x / 2.0), - (msg.boxes.at(i).pose.position.y + - msg.boxes.at(i).dimensions.y / 2.0), - FLOAT_MAX, 1.0f)); - boxFilter.setInputCloud(pclCloud); - boxFilter.filter(*boxFilteredCloud); - pcl::getMinMax3D(*boxFilteredCloud, minPt, maxPt); - ROS_DEBUG_STREAM( - "box_id: " << i << " box_pos: " << msg.boxes.at(i).pose.position - << " box_height: " - << msg.boxes.at(i).pose.position.z + - msg.boxes.at(i).dimensions.z / 2.0 - << " maxPt.z: " << maxPt.z); - occupancy = maxPt.z / (msg.boxes.at(i).pose.position.z + - msg.boxes.at(i).dimensions.z / 2.0); - // if some point clouds in boundingbox over bounding height - // TODO publish occupancy instead - boxOccupancy.boxes.at(i).value = occupancy; - } - this->_occupancyPub.publish(boxOccupancy); - } else { - ROS_WARN("No input point clouds."); - } - - }; -}; - -int main(int argc, char **argv){ - ros::init(argc, argv, "container_occupancy_detector"); - ros::NodeHandle nh; - ros::NodeHandle pnh("~"); - ContainerOccupancyDetector node(nh, pnh); - ros::spin(); -} From 8b1888866dd1d83f0e30d0ee80bb9542577533fd Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 27 Jun 2022 14:17:20 +0900 Subject: [PATCH 215/433] [jsk_fetch_startup] add -f to ln in install_supervisor.sh --- .../jsk_fetch_startup/config/install_supervisor.sh | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index f1229d57a2..d97642994f 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -9,13 +9,13 @@ set -x cd $jsk_fetch_startup/supervisor_scripts for file in $(ls *.conf); do - sudo ln -s $jsk_fetch_startup/supervisor_scripts/$file /etc/supervisor/conf.d/$file + sudo ln -sf $jsk_fetch_startup/supervisor_scripts/$file /etc/supervisor/conf.d/$file done sudo supervisorctl reread # Enable jsk_dstat job to save the csv log under /var/log -ln -s /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv +ln -sf /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv -sudo ln -s $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -sudo ln -s $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash +sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash +sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash set +x From 88b1af6d50581d665af4d3129d69447aaa5150d7 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 19:40:50 +0900 Subject: [PATCH 216/433] [jsk_fetch_startup] remove unused supervisor conf --- .../jsk-human-pose-estimator.conf | 15 --------------- .../supervisor_scripts/jsk-object-detector.conf | 15 --------------- .../jsk-panorama-human-pose-estimator.conf | 15 --------------- .../jsk-panorama-object-detector.conf | 15 --------------- 4 files changed, 60 deletions(-) delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf delete mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf deleted file mode 100644 index 25fa60f0a8..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-human-pose-estimator.conf +++ /dev/null @@ -1,15 +0,0 @@ -[program:jsk-human-pose-estimator] -; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_human_pose_estimator.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color device_id:=0 --screen --wait" - -stopsignal=TERM -; directory=/home/fetch/ros/coral_ws -directory=/home/fetch/ros/melodic -; autostart=true -autostart=false -autorestart=false -stdout_logfile=/var/log/ros/jsk-human-pose-estimator.log -stderr_logfile=/var/log/ros/jsk-human-pose-estimator.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf deleted file mode 100644 index 516e1caa80..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-object-detector.conf +++ /dev/null @@ -1,15 +0,0 @@ -[program:jsk-object-detector] -; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_object_detector.launch INPUT_IMAGE:=/head_camera/rgb/image_rect_color model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" - -stopsignal=TERM -; directory=/home/fetch/ros/coral_ws -directory=/home/fetch/ros/melodic -; autostart=true -autostart=false -autorestart=false -stdout_logfile=/var/log/ros/jsk-object-detector.log -stderr_logfile=/var/log/ros/jsk-object-detector.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf deleted file mode 100644 index 139af6c42f..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-human-pose-estimator.conf +++ /dev/null @@ -1,15 +0,0 @@ -[program:jsk-panorama-human-pose-estimator] -; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_panorama_human_pose_estimator.launch nodename:=edgetpu_human_pose_estimator INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output device_id:=0 --screen --wait" - -stopsignal=TERM -; directory=/home/fetch/ros/coral_ws -directory=/home/fetch/ros/melodic -; You can set "autostart=true" if "autostart=false" in jsk-human-pose-estimator.conf -autostart=false -autorestart=false -stdout_logfile=/var/log/ros/jsk-panorama-human-pose-estimator.log -stderr_logfile=/var/log/ros/jsk-panorama-human-pose-estimator.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf deleted file mode 100644 index bc320c5486..0000000000 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-panorama-object-detector.conf +++ /dev/null @@ -1,15 +0,0 @@ -[program:jsk-panorama-object-detector] -; command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/coral_ws/devel/setup.bash && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch coral_usb edgetpu_panorama_object_detector.launch nodename:=edgetpu_object_detector INPUT_IMAGE:=/dual_fisheye_to_panorama/quater/output model_file:=/home/fetch/.ros/data/coral_usb/mobilenet_v2_ssd_73b2_kitchen_finetuning_20200528.tflite label_file:=/home/fetch/.ros/data/coral_usb/73b2_kitchen_labels.txt device_id:=1 --screen --wait" - -stopsignal=TERM -; directory=/home/fetch/ros/coral_ws -directory=/home/fetch/ros/melodic -; You can set "autostart=true" if "autostart=false" in jsk-object-detector.conf -autostart=false -autorestart=false -stdout_logfile=/var/log/ros/jsk-panorama-object-detector.log -stderr_logfile=/var/log/ros/jsk-panorama-object-detector.log -user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 -priority=200 From 407dbef67dc5d398e7abdbfebf0cd8e45dd5a617 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 23:11:35 +0900 Subject: [PATCH 217/433] [jsk_fetch_startup] update supervisor conf to use rossetclient instead of setting ROS_HOSTNAME directory --- .../jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf | 2 +- .../supervisor_scripts/jsk-fetch-startup-outside.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf | 2 +- .../supervisor_scripts/jsk-network-monitor-outside.conf | 2 +- .../supervisor_scripts/jsk-network-monitor.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf | 2 +- .../jsk_fetch_startup/supervisor_scripts/robot-outside.conf | 2 +- jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf | 2 +- 11 files changed, 11 insertions(+), 11 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf index 8de89e02e4..23dcfcb3be 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-app-scheduler.conf @@ -1,5 +1,5 @@ [program:jsk-app-scheduler] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch app_scheduler app_scheduler.launch yaml_path:=/var/lib/robot/app_schedule.yaml --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf index 79cd2be0f0..50db8b9ed5 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-dialog.conf @@ -1,5 +1,5 @@ [program:jsk-dialog] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup wait_app_manager.bash && roslaunch jsk_fetch_startup fetch_dialogflow_task_executive.launch run_app_manager:=false webhook_server:=true hostname:=$(hostname) --wait --screen " stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf index e9966ce881..463ddf138e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup-outside.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup-outside] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) boot_sound:=true default_speaker:=$DEFAULT_SPEAKER default_english_speaker:=$DEFAULT_ENGLISH_SPEAKER default_warning_speaker:=$DEFAULT_WARNING_SPEAKER network_interface:=$NETWORK_DEFAULT_WIFI_INTERFACE --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 4005efea8d..69eb29af34 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -1,5 +1,5 @@ [program:jsk-fetch-startup] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup setup_audio.bash && roslaunch jsk_fetch_startup fetch_bringup.launch hostname:=$(hostname) --wait" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf index b44ebd55cf..dd8e281cda 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-gdrive.conf @@ -1,5 +1,5 @@ [program:jsk-gdrive] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch gdrive_ros gdrive_server.launch --wait --screen respawn:=true" stopsignal=TERM directory=/home/fetch/ros/melodic ; autostart=true diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf index 1058ba57af..2dbd597ae2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor-outside.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor-outside] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=false autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf index 7d8a4b6621..30e1578f91 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-network-monitor.conf @@ -1,5 +1,5 @@ [program:jsk-network-monitor] -command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" +command=/bin/bash -c ". /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup network_monitor.py --interface $NETWORK_DEFAULT_WIFI_INTERFACE --profile $NETWORK_DEFAULT_PROFILE_ID" stopsignal=TERM autostart=true autorestart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf index 05377f460c..b80954f2ab 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-rfcomm-bind.conf @@ -1,5 +1,5 @@ [program:jsk-rfcomm-bind] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && roslaunch jsk_robot_startup rfcomm_bind.launch --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index 0cf97a4327..7eceb2ba5b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,5 +1,5 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py --wait" stopsignal=TERM directory=/home/fetch/ros/melodic diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf index 0ce0afc615..90f32f5811 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot-outside.conf @@ -1,5 +1,5 @@ [program:robot-outside] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config_outside.bash ];then . /var/lib/robot/config_outside.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=false diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf index 11ca006f09..0b33af1409 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/robot.conf @@ -1,5 +1,5 @@ [program:robot] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && export ROS_HOSTNAME=$(hostname) && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_fetch_startup link_calibration_files.bash && roslaunch jsk_fetch_startup fetch.launch launch_teleop:=false --wait --screen" stopsignal=TERM directory=/home/fetch/ros/melodic autostart=true From 5a4159a201f0653cb4b5b9fc3f8b28fc025c4fb8 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 23:11:53 +0900 Subject: [PATCH 218/433] [jsk_fetch_startup] update NETWORK_DEFAULT_ROS_INTERFACE --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 4 ++-- jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index db9f9eb944..7795bd4834 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -20,7 +20,7 @@ if [ $(hostname) = 'fetch15' ]; then export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; - export NETWORK_DEFAULT_ROS_INTERFACE="localhost"; + export NETWORK_DEFAULT_ROS_INTERFACE="fetch15"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; elif [ $(hostname) = 'fetch1075' ]; then export DEFAULT_SPEAKER=2; @@ -41,6 +41,6 @@ elif [ $(hostname) = 'fetch1075' ]; then #export RS_SERIAL_NO_L515_HEAD=""; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; - export NETWORK_DEFAULT_ROS_INTERFACE="localhost"; + export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash index 011a2f64c1..007560b460 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config_outside.bash @@ -7,6 +7,6 @@ SCRIPT_DIR="$( cd -- "$( dirname -- "${BASH_SOURCE[0]:-$0}"; )" &> /dev/null && if [ $(hostname) = 'fetch15' ]; then export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; elif [ $(hostname) = 'fetch1075' ]; then - export NETWORK_DEFAULT_ROS_INTERFACE="wlan0"; + export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075.local"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; fi From 9a898da7170178ea9e86f657cb1cc8e34bbd1a08 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 23:47:16 +0900 Subject: [PATCH 219/433] [jsk_fetch_startup] update description of NETWORK_DEFAULT_ROS_INTERFACE --- jsk_fetch_robot/jsk_fetch_startup/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index 8978b82201..d7dcfcd4a4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -85,8 +85,8 @@ descriptions of each variable are below. - `NETWORK_DEFAULT_PROFILE_ID` + Network manager profile ID for network management scripts (`network_monitor.py`) + `NETWORK_DEFAULT_ROS_INTERFACE` - + Network interface or IP address which is used for ROS connection. - + `rossetip $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP`. + + Network interface or IP address or hostname which is used for ROS connection. + + `rossetclient $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP`. It is also recommended to add lines below to each users's bashrc in the robot PC. From 73c9b57dc9e7c4011addd665818f98c4837ada75 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 23:47:26 +0900 Subject: [PATCH 220/433] [jsk_fetch_startup] update description of NETWORK_DEFAULT_ROS_INTERFACE --- jsk_fetch_robot/jsk_fetch_startup/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/README.md b/jsk_fetch_robot/jsk_fetch_startup/README.md index d7dcfcd4a4..d23cac2634 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/README.md +++ b/jsk_fetch_robot/jsk_fetch_startup/README.md @@ -86,7 +86,7 @@ descriptions of each variable are below. + Network manager profile ID for network management scripts (`network_monitor.py`) + `NETWORK_DEFAULT_ROS_INTERFACE` + Network interface or IP address or hostname which is used for ROS connection. - + `rossetclient $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP`. + + `rossetclient $NETWORK_DEFAULT_ROS_INTERFACE` is executed to set `ROS_IP` or `ROS_HOSTNAME`. It is also recommended to add lines below to each users's bashrc in the robot PC. From 0d5d61083e43c3220393e187b053fc41f8c98e74 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 28 Jun 2022 23:57:26 +0900 Subject: [PATCH 221/433] [jsk_fetch_startup] add sudo to install_supervisor.sh --- jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index d97642994f..b4a73ddaf9 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -13,7 +13,7 @@ for file in $(ls *.conf); do done sudo supervisorctl reread # Enable jsk_dstat job to save the csv log under /var/log -ln -sf /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv +sudo ln -sf /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash From 67f9eac242d5f74143946e4bb884518078bc9d9b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 29 Jun 2022 00:19:18 +0900 Subject: [PATCH 222/433] [jsk_fetch_startup] fix symlink --- jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh index b4a73ddaf9..6a35d559c0 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_supervisor.sh @@ -16,6 +16,6 @@ sudo supervisorctl reread sudo ln -sf /home/fetch/Documents/jsk_dstat.csv /var/log/ros/jsk-dstat.csv sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config.bash -sudo ln -sf $jsk_fetch_startup/config/config.bash /var/lib/robot/config_outside.bash +sudo ln -sf $jsk_fetch_startup/config/config_outside.bash /var/lib/robot/config_outside.bash set +x From b47a09a12fe19d02336958d323d7b22dab8a786c Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 29 Jun 2022 00:29:55 +0900 Subject: [PATCH 223/433] [fetcheus] remove headbox collision objects methods --- jsk_fetch_robot/fetcheus/fetch-interface.l | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l index 78f80f62fa..fe47bc9b49 100644 --- a/jsk_fetch_robot/fetcheus/fetch-interface.l +++ b/jsk_fetch_robot/fetcheus/fetch-interface.l @@ -43,10 +43,8 @@ (setq moveit-robot (instance fetch-robot :init)) (send self :set-moveit-environment (instance fetch-moveit-environment :init :robot moveit-robot)) (when (and (boundp '*co*) default-collision-object) - (send self :delete-headbox-collision-object) (send self :delete-keepout-collision-object) (send self :delete-ground-collision-object) - (send self :add-headbox-collision-object) (send self :add-keepout-collision-object) (send self :add-ground-collision-object)) (setq fetch-controller-action @@ -257,18 +255,6 @@ Example: (send self :gripper :position) => 0.00" (:delete-workspace () (send *co* :delete-attached-object-by-id "workspace") (send *co* :delete-object-by-id "workspace")) - (:add-headbox-collision-object () - (let () - ;; fetch must be :reset-pose when we run this method - (setq *fetch-headbox* (make-cube 100 201 120)) - (send *fetch-headbox* :move-coords (send robot :head_pan_link_lk :worldcoords) - (send robot :base_link_lk :worldcoords)) - (send *fetch-headbox* :translate #f(33.75 0 150) (send robot :head_pan_link_lk :worldcoords)) - (send *co* :add-attached-object *fetch-headbox* "head_pan_link" - :frame_id "head_pan_link" - :object_id "fetchheadbox"))) - (:delete-headbox-collision-object () - (send *co* :delete-attached-object-by-id "fetchheadbox")) (:add-keepout-collision-object () (let ((cube (make-cube 200 350 10)) (keepout (make-cylinder 300 10))) From 2af2525749b43cd197ef7d38530e4686384f516d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 29 Jun 2022 00:32:44 +0900 Subject: [PATCH 224/433] [jsk_fetch_startup] disable head box of fetch15 --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 7795bd4834..4463923467 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -7,7 +7,7 @@ if [ $(hostname) = 'fetch15' ]; then export DEFAULT_WARNING_SPEAKER=cmu_us_fem.flitevox; export USE_BASE_CAMERA_MOUNT=true; - export USE_HEAD_BOX=true; + export USE_HEAD_BOX=false; export USE_HEAD_L515=true; export USE_INSTA360_STAND=true; From ac071449c70130a6a7f125fd43d162b3790f9600 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 1 Jul 2022 04:16:39 +0900 Subject: [PATCH 225/433] [jsk_fetch_startup] Remove rosserial in go_to_kitchen demo --- .../apps/go_to_kitchen/go_to_kitchen.xml | 9 --------- 1 file changed, 9 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 09c9f3cf28..e8eec07635 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -19,15 +19,6 @@ - - - - - port: /dev/rfcomm0 - baud: 115200 - - - From 05457e2cc5c0f142a7a28b6e15c217096f179713 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 4 Jul 2022 11:36:53 +0900 Subject: [PATCH 226/433] [jsk_fetch_startup] update default network config temporaliry --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 4463923467..5f0013d276 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -21,7 +21,9 @@ if [ $(hostname) = 'fetch15' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch15"; - export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + # Comment out until Access point is back + #export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; elif [ $(hostname) = 'fetch1075' ]; then export DEFAULT_SPEAKER=2; export DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox; @@ -42,5 +44,7 @@ elif [ $(hostname) = 'fetch1075' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; - export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + # Comment out until Access point is back + #export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; fi From 1c2eb857b7dddb3a4592db579854d4c4fcb2980d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 4 Jul 2022 13:13:56 +0900 Subject: [PATCH 227/433] [jsk_fetch_startup] enable low resolution mode of insta360 air --- .../launch/fetch_insta360_melodic.launch | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch index d7b863ae23..16968689af 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch @@ -7,11 +7,13 @@ - - + + + + @@ -23,8 +25,8 @@ - scale_width: 0.25 - scale_height: 0.25 + scale_width: 0.5 + scale_height: 0.5 From 6c92cd8ecf1a4f7439659f78e065360abcd59873 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 4 Jul 2022 14:26:54 +0900 Subject: [PATCH 228/433] [jsk_fetch_startup] increase insta360 rate --- .../jsk_fetch_startup/launch/fetch_insta360_melodic.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch index 16968689af..9958ed71f2 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_insta360_melodic.launch @@ -10,7 +10,7 @@ - + From 7eceea2239df4a7190ae3ac26ea393fe783ec7be Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 4 Jul 2022 19:05:33 +0900 Subject: [PATCH 229/433] [jsk_fetch_startup] remove /tmp/update_workspace.sh after updating --- jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 868f0cd1b2..5646eb2875 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -2,3 +2,4 @@ cp $(rospack find jsk_fetch_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh /tmp/update_workspace.sh $@ +rm /tmp/update_workspace.sh From e3424f7fbc6a8a0e1d502800c9f6ca9da74122f5 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 5 Jul 2022 05:21:18 +0900 Subject: [PATCH 230/433] [jsk_fetch_startup] Ignore rosserial audible warning because it automatically reconnects --- jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml index ed684b0de8..d095743c69 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml @@ -3,6 +3,7 @@ blacklist: - name: "/Other/amcl: Standard deviation" - name: "/Other/jsk_joy_node: Joystick Driver Status" - name: "/Other/l515_head l515_head_realsense2_camera_.*: Frequency Status" + - name: "/Other/rosserial_python" - name: "/Peripherals/PS3 Controller" - name: "/Sensors/IMU/IMU.*" - name: "/SoundPlay/sound_play.*" From e068e54d170fab55a86247edebedbcdc0fd1b9de Mon Sep 17 00:00:00 2001 From: iory Date: Wed, 6 Jul 2022 18:28:56 +0900 Subject: [PATCH 231/433] [jsk_fetch_startup/go_to_kitchen.app] Increase the speed of bag_to_video.py by setting compress to false. --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 3aef562056..df73e9a083 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -14,7 +14,7 @@ plugins: launch_args: rosbag_path: /tmp rosbag_title: go_to_kitchen_rosbag.bag - compress: true + compress: false rosbag_topic_names: - /rosout - /tf From b6a424a4c501e0399b6f7a60372edba064f4e74f Mon Sep 17 00:00:00 2001 From: iory Date: Wed, 6 Jul 2022 18:30:38 +0900 Subject: [PATCH 232/433] [jsk_fetch_startup/go_to_kitchen.app] Speed up bag_to_video.py by setting fps to 5. --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index df73e9a083..48e797cb66 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -64,7 +64,7 @@ plugins: rosbag_path: /tmp rosbag_title: go_to_kitchen_rosbag.bag image_topic_name: /edgetpu_object_detector/output/image/compressed - image_fps: 30 + image_fps: 5 audio_topic_name: /audio audio_sample_rate: 16000 audio_channels: 1 From 4aa0fafdb5af386e4ae532ce64fbd9a397760267 Mon Sep 17 00:00:00 2001 From: iory Date: Fri, 8 Jul 2022 03:49:54 +0900 Subject: [PATCH 233/433] [jsk_fetch_startup/audible_warning] Tweet audible warning with image --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 91d712f490..37432460a0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -363,6 +363,19 @@ + + + + + + From 6c5589ad181de7db923f3b254d4ab5d3380475a4 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Mon, 18 Jul 2022 17:14:03 +0900 Subject: [PATCH 234/433] [jsk_fetch_startup] Add option to change L515 resolution --- .../launch/fetch_realsense_bringup.launch | 21 +++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index afbedb15e5..f7cc7bf4cf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -7,6 +7,19 @@ + + + + + + + + + + + + + @@ -91,10 +104,10 @@ - - - - + + + + From 2a83e733220a58583c84ab582d5296175d137176 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Mon, 18 Jul 2022 17:14:19 +0900 Subject: [PATCH 235/433] [jsk_fetch_startup] Use L515 high resolution by default --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 230ed6656c..95b8c91777 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -17,6 +17,7 @@ + @@ -40,6 +41,7 @@ + From 7a335ff63de95a66a8c4c51268a5d51d8ea3d243 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Mon, 18 Jul 2022 17:14:34 +0900 Subject: [PATCH 236/433] [jsk_fetch_startup] Use L515 low resolution mode for fetch1075 because of USB 2 connection --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 5f0013d276..a2afa74855 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -41,6 +41,8 @@ elif [ $(hostname) = 'fetch1075' ]; then # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport export RS_SERIAL_NO_L515_HEAD="f0232270"; #export RS_SERIAL_NO_L515_HEAD=""; + # Currently, fetch1075 uses USB 2 for L515, so high resolution mode is not available. + export L515_HIGH_RESOLUTION=false; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; From 0d64a095eb777ed2de050b51679d2068877da6af Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 20 Jul 2022 16:44:11 +0900 Subject: [PATCH 237/433] [jsk_fetch_robot] add eus10 catkinize script to readme --- jsk_fetch_robot/README.md | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 732edbd5a6..71e62c2de0 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -45,6 +45,9 @@ wstool init . wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -y wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO wstool update -t . +# To use eus10, furuschev script is required. +wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh +bash /tmp/setup_upstream.sh -w . -p jsk-ros-pkg/geneus -p euslisp/jskeus source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src cd ../ From 56ca69f4ddee0145d471d0f6bc29d79043f00e44 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 21 Jul 2022 09:52:46 +0900 Subject: [PATCH 238/433] [jsk_fetch_robot] update README.md --- jsk_fetch_robot/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 71e62c2de0..9a838c5d6f 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -47,7 +47,7 @@ wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master wstool update -t . # To use eus10, furuschev script is required. wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh -bash /tmp/setup_upstream.sh -w . -p jsk-ros-pkg/geneus -p euslisp/jskeus +bash /tmp/setup_upstream.sh -w ../ -p jsk-ros-pkg/geneus -p euslisp/jskeus source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src cd ../ From 3135e97e68a1ebf302fa2f93621b3647ecf2c11c Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Sat, 30 Jul 2022 17:29:01 +0900 Subject: [PATCH 239/433] [jsk_fetch_startup] Use symbolic link for udev rules file, as well as supervisor configs --- .../jsk_fetch_startup/config/install_udev.sh | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh index b079e114a4..f3cec97ba1 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh @@ -4,14 +4,6 @@ jsk_fetch_startup=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`"/.. > /dev/null && cd $jsk_fetch_startup/udev_rules for file in $(ls *.rules); do - if [ -e /etc/udev/rules.d/$file ]; then - file_bk=$file.$(date "+%Y%m%d_%H%M%S") - sudo cp /etc/udev/rules.d/$file /etc/udev/rules.d/$file_bk - echo "backup /etc/udev/rules.d/$file to /etc/udev/rules.d/$file_bk" - fi - - sudo cp $file /etc/udev/rules.d/ - sudo chown root:root /etc/udev/rules.d/$file - sudo chmod 644 /etc/udev/rules.d/$file - echo -e "copied jsk_fetch_startup/udev_rules/$file to /etc/udev/rules.d/$file\n" + sudo ln -sf $jsk_fetch_startup/udev_rules/$file /etc/udev/rules.d/$file + echo -e "Create symbolic link from jsk_fetch_startup/udev_rules/$file to /etc/udev/rules.d/$file\n" done From 7c02da540f603bce59b41b970f14b6c53432bad7 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Sat, 30 Jul 2022 17:52:24 +0900 Subject: [PATCH 240/433] [jsk_fetch_startup] Use L515 high resolution for fetch1075 because USB3 is used now --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 2 -- 1 file changed, 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index a2afa74855..5f0013d276 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -41,8 +41,6 @@ elif [ $(hostname) = 'fetch1075' ]; then # Use L515 after finding a way to reduce L515 CPU usage like ConnectionBasedTransport export RS_SERIAL_NO_L515_HEAD="f0232270"; #export RS_SERIAL_NO_L515_HEAD=""; - # Currently, fetch1075 uses USB 2 for L515, so high resolution mode is not available. - export L515_HIGH_RESOLUTION=false; export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; From 5d97ac13ad757c23c5e0a56e902515ab26400cd9 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Sat, 30 Jul 2022 18:04:01 +0900 Subject: [PATCH 241/433] [jsk_fetch_startup] Add commit about udev files installed by apt --- jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh index f3cec97ba1..5e8e1cec43 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/config/install_udev.sh @@ -1,5 +1,8 @@ #!/bin/bash +# 99-edgetpu-accelerator.rules and 99-realsense-libusb.rules are not tracked in jsk_fetch_startup +# because they are installed by apt + jsk_fetch_startup=$(builtin cd "`dirname "${BASH_SOURCE[0]}"`"/.. > /dev/null && pwd) cd $jsk_fetch_startup/udev_rules From 7ddef13dc4d4182f17e31ba4616efe6ff4299bcd Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Sat, 30 Jul 2022 23:26:16 +0900 Subject: [PATCH 242/433] [jsk_fetch_startup] Remove pointcloud from filters to disable publishing pointcloud --- .../jsk_fetch_startup/launch/fetch_realsense_bringup.launch | 3 --- 1 file changed, 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index f7cc7bf4cf..95a60d8a5c 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -69,7 +69,6 @@ - @@ -86,7 +85,6 @@ - @@ -103,7 +101,6 @@ - From 54fcba549b7392755985e3732654b31a01356e74 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 01:03:20 +0900 Subject: [PATCH 243/433] [jsk_fetch_startup] Use nodelet for RealSenseNodeFactory --- .../launch/devices/realsense_nodelet.launch.xml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml index a72dd3f2d1..c5993ed682 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/devices/realsense_nodelet.launch.xml @@ -3,6 +3,8 @@ This launch file is copied from realsense2_camera in realsense_ros https://github.com/IntelRealSense/realsense-ros and then modified And it is originally distributed under Apache-2.0 License --> + + @@ -10,6 +12,7 @@ + @@ -101,11 +104,12 @@ + From 87a3aae97687c4b57d1c2b932ce52c9c1996ac5e Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 02:03:55 +0900 Subject: [PATCH 244/433] [jsk_fetch_startup] Create L515 pointcloud with depth_image_proc --- .../launch/fetch_realsense_bringup.launch | 28 +++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index 95a60d8a5c..237629f164 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -1,6 +1,7 @@ + @@ -20,6 +21,11 @@ + + + + + @@ -94,6 +100,8 @@ + + @@ -115,6 +123,26 @@ /l515_head/l500_depth_sensor/global_time_enabled: true /l515_head/rgb_camera/global_time_enabled: true + + + + + + + + + + + + + + + + From 0ae17ad02e411d05251251105bce142de0588ede Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 02:38:51 +0900 Subject: [PATCH 245/433] [jsk_fetch_startup] Create L515 points from throttled rgb and depth images --- .../launch/fetch_realsense_bringup.launch | 45 +++++++++++++++++-- 1 file changed, 42 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index 237629f164..755995ad96 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -25,6 +25,8 @@ + + @@ -135,12 +137,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + - - - + + + + + + From 3225c2d8a183c514c31b3bfc98c5ef93c9deb560 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 02:40:29 +0900 Subject: [PATCH 246/433] [jsk_fetch_startup] Add option to create L515 points --- .../launch/fetch_realsense_bringup.launch | 107 +++++++++--------- 1 file changed, 55 insertions(+), 52 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index 755995ad96..eac50fe952 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -22,6 +22,7 @@ + @@ -82,7 +83,7 @@ - + @@ -98,7 +99,7 @@ - + @@ -130,58 +131,60 @@ This launch file is copied from realsense2_camera in realsense_ros https://github.com/IntelRealSense/realsense-ros and then modified And it is originally distributed under Apache-2.0 License --> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - From 40d51da223cdcb7a66c43e9fa36fff7c482dacfa Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 02:41:09 +0900 Subject: [PATCH 247/433] [jsk_fetch_startup] Publish resized L515 pointcloud --- .../launch/fetch_realsense_bringup.launch | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index eac50fe952..e30aa74dac 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -184,6 +184,17 @@ + + + + + step_x: 4 + step_y: 4 + + From b919e9c4e8d3d4945adda56d8b5326f328d99812 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Tue, 2 Aug 2022 02:42:13 +0900 Subject: [PATCH 248/433] [jsk_fetch_startup] Fix indent --- .../jsk_fetch_startup/launch/fetch_realsense_bringup.launch | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch index e30aa74dac..1e0ab40556 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_realsense_bringup.launch @@ -122,9 +122,9 @@ - /l515_head/motion_module/global_time_enabled: true - /l515_head/l500_depth_sensor/global_time_enabled: true - /l515_head/rgb_camera/global_time_enabled: true + /l515_head/motion_module/global_time_enabled: true + /l515_head/l500_depth_sensor/global_time_enabled: true + /l515_head/rgb_camera/global_time_enabled: true From 6e8556646d8105dd8673eb4319bf7feae7f4bcd9 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 4 Aug 2022 22:44:30 +0900 Subject: [PATCH 250/433] [jsk_fetch_startup] Extend audible warning blacklist to nodelet version realsense2_camera --- jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml index d095743c69..d5ff0adfcc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml @@ -2,7 +2,7 @@ blacklist: - name: "/CPU/CPU Usage/my_machine CPU Usage" - name: "/Other/amcl: Standard deviation" - name: "/Other/jsk_joy_node: Joystick Driver Status" - - name: "/Other/l515_head l515_head_realsense2_camera_.*: Frequency Status" + - name: "/Other/l515_head .*realsense2_camera_.*: Frequency Status" - name: "/Other/rosserial_python" - name: "/Peripherals/PS3 Controller" - name: "/Sensors/IMU/IMU.*" From 5cb9a9629ac43446e92839f1f2bb516285ec8481 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Fri, 5 Aug 2022 21:19:27 +0900 Subject: [PATCH 251/433] [jsk_fetch_startup] Fix L515 head mount link pose --- jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro index dd2f9b7a5e..24885a8324 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/head_l515.urdf.xacro @@ -37,7 +37,7 @@ - + From baf3dcf549e6a7561197978632c565f7d2e4e742 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Tue, 16 Aug 2022 22:50:52 +0900 Subject: [PATCH 252/433] [jsk_fetch_startup] add rate arg to rosbag play --- jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch index 1fdab69f5f..725e006ada 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch @@ -12,6 +12,7 @@ + @@ -104,7 +105,7 @@ + args="$(arg rosbag) $(arg loop_flag) --clock --start $(arg start_time) $(arg duration) -r $(arg rate)" output="screen" /> From d20b0df4d474e051b11d9f6d1786e1aad8e958b6 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 15 Aug 2022 14:37:00 +0900 Subject: [PATCH 253/433] [fetcheus] add :point-head method --- jsk_fetch_robot/fetcheus/fetch-interface.l | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l index fe47bc9b49..495da3df23 100644 --- a/jsk_fetch_robot/fetcheus/fetch-interface.l +++ b/jsk_fetch_robot/fetcheus/fetch-interface.l @@ -22,7 +22,7 @@ (defclass fetch-interface :super robot-move-base-interface - :slots (gripper-action moveit-robot fetch-controller-action) + :slots (gripper-action moveit-robot fetch-controller-action point-head-action) ) (defmethod fetch-interface @@ -51,6 +51,10 @@ (instance ros::simple-action-client :init "/query_controller_states" robot_controllers_msgs::QueryControllerStatesAction)) + (setq point-head-action + (instance ros::simple-action-client :init + "/head_controller/point_head" + control_msgs::PointHeadAction)) )) (:state (&rest args) "We do not have :wait-until-update option for :state :worldcoords. @@ -203,6 +207,17 @@ Example usage: (:stop-grasp (&rest args &key &allow-other-keys) (send* self :go-grasp :pos 0.1 args)) + (:point-head (pos &key (frame-id "base_link") (wait t)) + (let ((goal (instance control_msgs::PointHeadGoal :init))) + (send goal :target :header :stamp (ros::time-now)) + (send goal :target :header :frame_id frame-id) + (send goal :target :point (ros::pos->tf-point pos)) + (if wait + (send point-head-action :send-goal goal) + (send point-head-action :send-goal-and-wait goal) + ) + ) + ) (:go-grasp (&key (pos 0) (effort 50) (wait t)) (when (send self :simulation-modep) From 3243d66c3a1767adc3f373eff4ab2536b2e436b9 Mon Sep 17 00:00:00 2001 From: Aoi Nakane Date: Thu, 18 Aug 2022 03:00:29 +0900 Subject: [PATCH 254/433] [jsk_robot_startup] Speak when shut down or reboot --- .../jsk_robot_startup/scripts/shutdown.py | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py b/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py index ff05431dbc..97bab6c60f 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/shutdown.py @@ -1,9 +1,11 @@ #!/usr/bin/env python +# -*- coding: utf-8 -*- import os from importlib import import_module import rospy +from sound_play.libsoundplay import SoundClient from std_msgs.msg import Empty @@ -32,7 +34,7 @@ class Shutdown(object): def __init__(self): rospy.loginfo('Start shutdown node.') - + self.client_jp = SoundClient(sound_action='/robotsound_jp', blocking=True) self.condition = rospy.get_param( '~input_condition', None) if self.condition is not None: @@ -51,6 +53,11 @@ def __init__(self): '~shutdown_command', '/sbin/shutdown -h now') self.reboot_command = rospy.get_param( '~reboot_command', '/sbin/shutdown -r now') + self.volume = rospy.get_param('~volume', 1.0) + + def speak(self, client, speech_text, lang='jp'): + client.say(speech_text, voice=lang, volume=self.volume, replace=False) + return client.actionclient.get_result() def callback(self, msg): if isinstance(msg, rospy.msg.AnyMsg): @@ -81,6 +88,7 @@ def shutdown(self, msg): return rospy.loginfo('Shut down robot.') + self.speak(self.client_jp, 'シャットダウンします。') ret = os.system(self.shutdown_command) if ret != 0: rospy.logerr("Failed to call '$ {}'. Check authentication.".format( @@ -88,6 +96,7 @@ def shutdown(self, msg): def reboot(self, msg): rospy.loginfo('Reboot robot.') + self.speak(self.client_jp, '再起動します。') ret = os.system(self.reboot_command) if ret != 0: rospy.logerr("Failed to call '$ {}'. Check authentication.".format( From 25bbbfb0c2a7476466d9b668ff9a91d4744160f9 Mon Sep 17 00:00:00 2001 From: Naoya Yamaguchi <708yamaguchi@gmail.com> Date: Thu, 18 Aug 2022 16:39:07 +0900 Subject: [PATCH 255/433] [jsk_fetch_startup] Supervisor save the log-wifi-link.sh log --- .../jsk_fetch_startup/scripts/log-wifi-link.sh | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index c888d2a903..2c10f5d0c4 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -1,7 +1,6 @@ #!/bin/bash IFACE=wlan0 -OUTPATH=/var/log/wifi.log INTERVAL=10 wifi_status(){ @@ -14,11 +13,6 @@ wifi_status(){ echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate" } -OUTDIR=$(dirname $OUTPATH) -if [ ! -d $OUTDIR ]; then - mkdir -p $OUTDIR -fi - print_help(){ echo "Usage: $0 [-i INTERVAL (default: 10)] [-I IFACE (default: wlan0)]" exit 1 @@ -34,6 +28,6 @@ do done while true; do - wifi_status >> $OUTPATH + wifi_status sleep $INTERVAL done From e16b973bf1c1db3a18644ac5d0a090458aab75cf Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sun, 14 Aug 2022 18:05:35 +0900 Subject: [PATCH 256/433] [fetcheus] update args --- jsk_fetch_robot/fetcheus/fetch-interface.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/fetcheus/fetch-interface.l b/jsk_fetch_robot/fetcheus/fetch-interface.l index 495da3df23..238d964a7f 100644 --- a/jsk_fetch_robot/fetcheus/fetch-interface.l +++ b/jsk_fetch_robot/fetcheus/fetch-interface.l @@ -26,7 +26,7 @@ ) (defmethod fetch-interface - (:init (&key (default-collision-object t) &rest args) + (:init (&rest args &key (default-collision-object t) &allow-other-keys) (prog1 (send-super* :init :robot fetch-robot :base-frame-id "base_link" :odom-topic "/odom_combined" :base-controller-action-name nil args) (send self :add-controller :arm-controller) (send self :add-controller :torso-controller) From 3a268caca51fae66edacc2df45de7b8edc994609 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 18 Aug 2022 10:16:54 +0900 Subject: [PATCH 257/433] [jsk_fetch_startup] make sanshiro-73B2 default --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 5f0013d276..4463923467 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -21,9 +21,7 @@ if [ $(hostname) = 'fetch15' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch15"; - # Comment out until Access point is back - #export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; - export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; elif [ $(hostname) = 'fetch1075' ]; then export DEFAULT_SPEAKER=2; export DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox; @@ -44,7 +42,5 @@ elif [ $(hostname) = 'fetch1075' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; - # Comment out until Access point is back - #export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; - export NETWORK_DEFAULT_PROFILE_ID="sanshiro-outside"; + export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; fi From 97f910184981ee9ce341e99f48b2ee2cba202971 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 22 Aug 2022 17:57:11 +0900 Subject: [PATCH 258/433] [jsk_fetch_startup] update log-wifi-link.sh --- .../jsk_fetch_startup/scripts/log-wifi-link.sh | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index 2c10f5d0c4..ef42c3e5e0 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -2,6 +2,9 @@ IFACE=wlan0 INTERVAL=10 +PING_COUNT=3 +PING_TIMEOUT=1 +PING_TARGET="www.google.com" wifi_status(){ local ssid=$(iw $IFACE link | grep SSID | cut -d: -f2) @@ -10,7 +13,13 @@ wifi_status(){ local level=$(cat /proc/net/wireless | grep $IFACE | awk '{print $4}') local noise=$(cat /proc/net/wireless | grep $IFACE | awk '{print $5}') local bitrate=$(iw $IFACE link | grep bitrate | cut -d':' -f2) - echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate" + local ping_result_raw=$(ping -I $IFACE $PING_TARGET -c $PING_COUNT -W $PING_TIMEOUT | tail -n 1) + if [ -z "$ping_result_raw" ]; then + local ping_result_duration=999 + else + local ping_result_duration=$(echo $ping_result_raw | cut -d " " -f 4 | cut -d "/" -f 2) + fi + echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate,$ping_result_duration" } print_help(){ @@ -18,11 +27,14 @@ print_help(){ exit 1 } -while getopts hi:I: o +while getopts hi:I:c:W:t: o do case "$o" in i) INTERVAL=$OPTARG;; I) IFACE="$OPTARG";; + c) PING_COUNT=$OPTARG;; + W) PING_TIMEOUT=$OPTARG;; + t) PING_TARGET="$OPTARG";; h) print_help;; esac done From 98360af92abe727f70ea48e5e4479d7a36e769d7 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 4 Oct 2022 00:32:54 +0900 Subject: [PATCH 259/433] [jsk_fetch_startup] Fixed warning blacklist when runstop is enabled --- .../jsk_fetch_startup/config/warning_blacklist.yaml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml index d5ff0adfcc..54dc6a28f6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/config/warning_blacklist.yaml @@ -8,6 +8,8 @@ blacklist: - name: "/Sensors/IMU/IMU.*" - name: "/SoundPlay/sound_play.*" run_stop_blacklist: - - name: "\\w*_(mcb|breaker)" - - name: "Mainboard" + - name: "/Motor Control Boards/.*_(mcb|breaker)" + - name: "/System/Mainboard/Mainboard" message: "Runstop pressed" + - name: "/Breakers/.*" + message: "Disabled." From 7f72bea7d032273ea0def24b6c8150c9f93d8d18 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 4 Oct 2022 00:33:04 +0900 Subject: [PATCH 260/433] [jsk_fetch_startup] Set ignore_time_(before|after)_runstop_is_enabled param to avoid warning when runstop is enabled --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 37432460a0..a587c70d13 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -359,7 +359,9 @@ run_stop_condition: "m.runstopped is True" seconds_to_start_speaking: 60 speak_interval: 600 - language: $(arg default_warning_speaker) + language: $(arg default_warning_speaker) + ignore_time_after_runstop_is_enabled: 5.0 + ignore_time_after_runstop_is_disabled: 5.0 From c6be79114ca821f62765ab0377607a76786bbb6f Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 22 Aug 2022 12:12:51 +0900 Subject: [PATCH 261/433] [jsk_fetch_startup] Add description tag for kitchen-demo userdata --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 0112a5fc24..ebf86afabe 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -770,6 +770,7 @@ Args: (:report-light-on '(lambda (userdata) (report-light-on) + (set-alist 'description "電気がついていたよ" userdata) t)) (:room-light-on '(lambda (userdata) From 281bab84420e007a7e0b2b61b6049e930556de4e Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 22 Aug 2022 13:13:08 +0900 Subject: [PATCH 262/433] [jsk_fetch_startup/kitchen-demo] Add image tag for kitchen-demo userdata --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index ebf86afabe..389bff2cf4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -771,6 +771,7 @@ Args: '(lambda (userdata) (report-light-on) (set-alist 'description "電気がついていたよ" userdata) + (set-alist 'image "" userdata) t)) (:room-light-on '(lambda (userdata) From 898e6f166bbcb9227253c5630c83338c34567833 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 24 Aug 2022 10:12:51 +0900 Subject: [PATCH 263/433] [jsk_fetch_startup] change NETWORK_DEFAULT_INTERFACE **temporarily** --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 4463923467..4f7057cc68 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -40,7 +40,7 @@ elif [ $(hostname) = 'fetch1075' ]; then export RS_SERIAL_NO_L515_HEAD="f0232270"; #export RS_SERIAL_NO_L515_HEAD=""; - export NETWORK_DEFAULT_WIFI_INTERFACE="wlan1"; + export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; fi From fc7c3836850f90f6b160775f11531f045d71a31b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 23 Aug 2022 11:36:25 +0900 Subject: [PATCH 264/433] [jsk_fetch_startup] update help and output format --- .../jsk_fetch_startup/scripts/log-wifi-link.sh | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index ef42c3e5e0..e8f1eefcc2 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -19,11 +19,16 @@ wifi_status(){ else local ping_result_duration=$(echo $ping_result_raw | cut -d " " -f 4 | cut -d "/" -f 2) fi - echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate,$ping_result_duration" + echo "$(date -Iseconds),$ssid,$freq,$signal,$level,$noise,$bitrate, $ping_result_duration" } print_help(){ - echo "Usage: $0 [-i INTERVAL (default: 10)] [-I IFACE (default: wlan0)]" + echo "Usage: log-wifi-link.sh [-h]" + echo " [-i INTERVAL (default: 10)]" + echo " [-I IFACE (default: wlan0)]" + echo " [-c PING_COUNT (default: 3)]" + echo " [-W PING_TIMEOUT (default: 1)]" + echo " [-t PING_TARGET (default: \"www.google.com\")]" exit 1 } From db277b10268986af1f90198d4713492dcde69d2d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 24 Aug 2022 11:12:06 +0900 Subject: [PATCH 265/433] [jsk_fetch_startup] redirect error print of ping to /dev/null and change ping result duration when fails --- jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh index e8f1eefcc2..3afeeb5c6d 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/log-wifi-link.sh @@ -13,9 +13,10 @@ wifi_status(){ local level=$(cat /proc/net/wireless | grep $IFACE | awk '{print $4}') local noise=$(cat /proc/net/wireless | grep $IFACE | awk '{print $5}') local bitrate=$(iw $IFACE link | grep bitrate | cut -d':' -f2) - local ping_result_raw=$(ping -I $IFACE $PING_TARGET -c $PING_COUNT -W $PING_TIMEOUT | tail -n 1) + local ping_result_raw=$(ping -I $IFACE $PING_TARGET -c $PING_COUNT -W $PING_TIMEOUT 2> /dev/null | tail -n 1) if [ -z "$ping_result_raw" ]; then - local ping_result_duration=999 + # minus ping indicates ping fails + local ping_result_duration=-1000 else local ping_result_duration=$(echo $ping_result_raw | cut -d " " -f 4 | cut -d "/" -f 2) fi From e4e6d3bf911f1601dd1db22c08e3a5da6471a3ce Mon Sep 17 00:00:00 2001 From: iory Date: Tue, 23 Aug 2022 23:29:15 +0900 Subject: [PATCH 266/433] [jsk_robot_startup] Enable shutdown_unchecked --- .../jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf index 7eceb2ba5b..37feca3d06 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-shutdown.conf @@ -1,5 +1,5 @@ [program:jsk-shutdown] -command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py --wait" +command=/bin/bash -c ". /opt/ros/roscore_poststart.bash && . /home/fetch/ros/melodic/devel/setup.bash && if [ -e /var/lib/robot/config.bash ];then . /var/lib/robot/config.bash ;fi && export ROS_MASTER_URI=http://localhost:11311 && rossetclient $NETWORK_DEFAULT_ROS_INTERFACE && rosrun jsk_robot_startup shutdown.py ~input:=/battery_state _input_condition:='m.is_charging is False' --wait" stopsignal=TERM directory=/home/fetch/ros/melodic From e2796ea2469857dbbf27eef6bf05b39e6be7b1ac Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Wed, 31 Aug 2022 14:34:58 +0900 Subject: [PATCH 267/433] [jsk_fetch_startup] add rviz config arg to use original .rviz file --- jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch index 725e006ada..20abc5d53a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/rosbag_play.launch @@ -13,6 +13,7 @@ + @@ -108,5 +109,5 @@ args="$(arg rosbag) $(arg loop_flag) --clock --start $(arg start_time) $(arg duration) -r $(arg rate)" output="screen" /> + args="-d $(arg rviz_config)" /> From 6f70918c6de7c707e8190de1e01407a2735c2a4a Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 24 Aug 2022 16:28:50 +0900 Subject: [PATCH 268/433] [jsk_fetch_startup/kithcen] Change description dependent on success or not --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 -- 1 file changed, 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 389bff2cf4..0112a5fc24 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -770,8 +770,6 @@ Args: (:report-light-on '(lambda (userdata) (report-light-on) - (set-alist 'description "電気がついていたよ" userdata) - (set-alist 'image "" userdata) t)) (:room-light-on '(lambda (userdata) From 04a4b3206374baa4a8910fda4a16807fcb7a0a05 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Tue, 13 Sep 2022 20:58:51 +0900 Subject: [PATCH 269/433] add new arduino udev rules --- jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules index 4606864732..d422d6fd00 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules @@ -1,3 +1,4 @@ # You can access arduino attached to fetch via /dev/arduino # https://github.com/start-jsk/jsk_apc/blob/16c004c511e864478aa6581a04c5a023e5fde391/jsk_arc2017_baxter/udev/90-rosserial.rules SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", SYMLINK+="arduino", MODE="0666" +SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="arduino", MODE="0666" From f9476b5468b8a9658549a7a66dfbd68caf781ede Mon Sep 17 00:00:00 2001 From: Aoi Nakane Date: Wed, 14 Sep 2022 09:20:57 +0900 Subject: [PATCH 270/433] Add description on new arduino udev rules --- .../jsk_fetch_startup/udev_rules/80-arduino.rules | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules index d422d6fd00..ef16f14591 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules @@ -1,4 +1,7 @@ # You can access arduino attached to fetch via /dev/arduino # https://github.com/start-jsk/jsk_apc/blob/16c004c511e864478aa6581a04c5a023e5fde391/jsk_arc2017_baxter/udev/90-rosserial.rules SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", SYMLINK+="arduino", MODE="0666" -SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="arduino", MODE="0666" + +# The following device is for arduino nano every in nakane hand version 1 +# Please update idVendor and idProduct if you use a different microcontroller +SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="nakane_hand", MODE="0666" From 927280ebf618e405608e46299e02969c27843703 Mon Sep 17 00:00:00 2001 From: iory Date: Thu, 15 Sep 2022 21:29:30 +0900 Subject: [PATCH 271/433] [jsk_fetch_startup] Set AUDIO_DEVICE environment variable to select speaker --- jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 4 ++++ .../supervisor_scripts/jsk-fetch-startup.conf | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 4f7057cc68..4ce9b16dc8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -22,6 +22,8 @@ if [ $(hostname) = 'fetch15' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch15"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + + export AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo" elif [ $(hostname) = 'fetch1075' ]; then export DEFAULT_SPEAKER=2; export DEFAULT_ENGLISH_SPEAKER=cmu_us_slt.flitevox; @@ -43,4 +45,6 @@ elif [ $(hostname) = 'fetch1075' ]; then export NETWORK_DEFAULT_WIFI_INTERFACE="wlan0"; export NETWORK_DEFAULT_ROS_INTERFACE="fetch1075"; export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; + + export AUDIO_DEVICE="alsa_output.usb-SEEED_ReSpeaker_4_Mic_Array__UAC1.0_-00.analog-stereo" fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf index 69eb29af34..5efe6fb1be 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-fetch-startup.conf @@ -7,5 +7,5 @@ autorestart=false stdout_logfile=/var/log/ros/jsk-fetch-startup.log stderr_logfile=/var/log/ros/jsk-fetch-startup.log user=fetch -environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",AUDIO_DEVICE="alsa_output.usb-1130_USB_AUDIO-00.analog-stereo",PYTHONUNBUFFERED=1 +environment=ROSCONSOLE_FORMAT="[${severity}] [${time}] [${node}:${logger}]: ${message}",PYTHONUNBUFFERED=1 priority=100 From 177bab8c7a4d83d4ad4db070ad9b4a380089e8c4 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 15 Sep 2022 14:07:56 +0900 Subject: [PATCH 272/433] [jsk_fetch_startup] fix mailbody in update_workspace script --- .../jsk_fetch_startup/scripts/update_workspace_main.sh | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh index 74eb47693b..041c18fd5d 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh @@ -48,6 +48,8 @@ fi # Filename should end with .txt to preview the contents in a web browser LOGFILE=$WORKSPACE/update_workspace.txt +MAIL_BODY="" + { set -x # Update workspace @@ -85,7 +87,6 @@ catkin config -DCMAKE_BUILD_TYPE=Release catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail -MAIL_BODY="" if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " fi @@ -97,6 +98,7 @@ if [ $CATKIN_BUILD_RESULT -ne 0 ]; then fi set +x } 2>&1 | tee $LOGFILE + if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then echo "Sent a mail" rostopic pub -1 /email jsk_robot_startup/Email "header: From 5a3462a31f68148c3aa4036dad00c198a479525a Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 15 Sep 2022 14:17:35 +0900 Subject: [PATCH 273/433] [jsk_fetch_startup] fix mailbody in update_workspace script --- .../scripts/update_workspace_main.sh | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh index 041c18fd5d..abb10dc24e 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh @@ -48,7 +48,7 @@ fi # Filename should end with .txt to preview the contents in a web browser LOGFILE=$WORKSPACE/update_workspace.txt -MAIL_BODY="" +TMP_MAIL_BODY_FILE=/tmp/update_workspace_mailbody.txt { set -x @@ -87,18 +87,22 @@ catkin config -DCMAKE_BUILD_TYPE=Release catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail +echo "" > $TMP_MAIL_BODY_FILE if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please wstool update workspace manually. " + echo "Please wstool update workspace manually.\n" >> $TMP_MAIL_BODY_FILE fi if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please install dependencies manually. " + echo "Please install dependencies manually.\n" >> $TMP_MAIL_BODY_FILE fi if [ $CATKIN_BUILD_RESULT -ne 0 ]; then - MAIL_BODY=$MAIL_BODY"Please catkin build workspace manually." + echo "Please catkin build workspace manually.\n" >> $TMP_MAIL_BODY_FILE fi set +x } 2>&1 | tee $LOGFILE +MAIL_BODY=$(cat $TMP_MAIL_BODY_FILE) +echo "MAIL_BODY: $MAIL_BODY" + if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then echo "Sent a mail" rostopic pub -1 /email jsk_robot_startup/Email "header: From 9ced3e49fcd6d973539812cd11867bb7cc1b7e17 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 15 Sep 2022 22:17:02 +0900 Subject: [PATCH 274/433] [jsk_fetch_startup] Fix email body topic by jsk_robot_startup/EmailBody --- .../jsk_fetch_startup/scripts/update_workspace_main.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh index abb10dc24e..ccae05598c 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh @@ -110,7 +110,8 @@ if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then stamp: {secs: 0, nsecs: 0} frame_id: '' subject: 'Daily workspace update fails' -body: '$MAIL_BODY' +body: +- {type: 'text', message: '${MAIL_BODY}', file_path: '', img_data: '', img_size: 0} sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' smtp_server: '' From a979f381af3b042996adea4bd7ae50b9bded20e0 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sun, 18 Sep 2022 11:23:43 +0900 Subject: [PATCH 275/433] [jsk_fetch_startup] add comment to update_workspace_main.sh --- .../jsk_fetch_startup/scripts/update_workspace_main.sh | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh index ccae05598c..fd02428eee 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh @@ -100,6 +100,9 @@ fi set +x } 2>&1 | tee $LOGFILE +# MAIL_BODY variable cannot be set directly in a subshell. So it is set from temporary mail body text file. +# The mail body text is put as $TMP_MAIL_BODY_FILE. +# See https://github.com/jsk-ros-pkg/jsk_robot/issues/1569 MAIL_BODY=$(cat $TMP_MAIL_BODY_FILE) echo "MAIL_BODY: $MAIL_BODY" From f045a93b61367041a759d7a99c24285a3e039523 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Mon, 19 Sep 2022 23:32:16 +0900 Subject: [PATCH 276/433] [jsk_fetch_robot] update wstool info in readme --- jsk_fetch_robot/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 9a838c5d6f..8a69d14fc1 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -61,7 +61,7 @@ source devel/setup.bash mkdir -p catkin_ws/src cd catkin_ws/src wstool init . -wstool set --git jsk-ros-pkg/jsk_robot https://github.com/knorth55/jsk_robot.git -v fetch15 -y +wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y wstool update -t . wstool merge -t . jsk-ros-pkg/jsk_robot/jsk_fetch_robot/jsk_fetch.rosinstall.$ROS_DISTRO wstool update -t . From db853cd13d4bc4ffe8277a194d9f763c0cb773ac Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 13 Sep 2022 16:48:19 +0900 Subject: [PATCH 277/433] add jsk-switch-wifi supervisor conf --- .../supervisor_scripts/jsk-switch-wifi-73b2.conf | 8 ++++++++ .../supervisor_scripts/jsk-switch-wifi-outside.conf | 8 ++++++++ 2 files changed, 16 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf create mode 100644 jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf new file mode 100644 index 0000000000..52656f1761 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-73b2.conf @@ -0,0 +1,8 @@ +[program:jsk-switch-wifi-73b2] +command=nmcli c up sanshiro-73B2 +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-switch-wifi.log +stderr_logfile=/var/log/ros/jsk-switch-wifi.log +user=root diff --git a/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf new file mode 100644 index 0000000000..d892d5be10 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/supervisor_scripts/jsk-switch-wifi-outside.conf @@ -0,0 +1,8 @@ +[program:jsk-switch-wifi-outside] +command=nmcli c up sanshiro-outside +stopsignal=TERM +autostart=false +autorestart=false +stdout_logfile=/var/log/ros/jsk-switch-wifi.log +stderr_logfile=/var/log/ros/jsk-switch-wifi.log +user=root From f72c51dd6eb9d465623832efda30724a1a39f422 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 17:29:04 +0900 Subject: [PATCH 278/433] [jsk_fetch_startup, jsk_robot_startup] move update_workspace_main.sh to jsk_robot_startup --- .../scripts/update_workspace.sh | 8 +++- .../scripts/update_workspace_main.sh | 48 +++++++++++-------- 2 files changed, 35 insertions(+), 21 deletions(-) rename {jsk_fetch_robot/jsk_fetch_startup => jsk_robot_common/jsk_robot_startup}/scripts/update_workspace_main.sh (76%) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh index 5646eb2875..6fd0ba00d2 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace.sh @@ -1,5 +1,9 @@ #!/usr/bin/env bash -cp $(rospack find jsk_fetch_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh -/tmp/update_workspace.sh $@ +cp $(rospack find jsk_robot_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh +# jsk_footstep_planner is not released for melodic +# jsk_footstep_controller is not released for melodic +# librealsense2 should not be installed from ROS repository +# realsense-ros should not be installed from ROS repository +/tmp/update_workspace.sh -r $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO -t fetch -s "jsk_footstep_controller jsk_footstep_planner librealsense2 realsense2_camera realsense2_description" rm /tmp/update_workspace.sh diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh similarity index 76% rename from jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh rename to jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index fd02428eee..0dc6176331 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -2,11 +2,14 @@ function usage() { - echo "Usage: $0 [-w workspace_directory] [-h] [-l] + echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-l] optional arguments: -h show this help -w WORKSPACE_PATH specify target workspace + -r ROSINTALL_PATH rosinstall path + -t ROBOT robot type + -s SKIP_KEYS rosdep install skip keys -l do not send a mail " } @@ -17,14 +20,23 @@ function get_full_path() } SEND_MAIL=true -WORKSPACE=$(get_full_path $HOME/ros/melodic) +WORKSPACE=$(get_full_path $HOME/ros/$ROS_DISTRO) -while getopts hlw: OPT +while getopts w:r:t:s:lh OPT do case $OPT in w) WORKSPACE=$(get_full_path $OPTARG) ;; + r) + ROSINSTALL=$(get_full_path $OPTARG) + ;; + t) + ROBOT_TYPE=$OPTARG + ;; + s) + SKIP_KEYS=$OPTARG + ;; l) SEND_MAIL=false ;; @@ -39,11 +51,20 @@ do esac done -if [ ! -e $WORKSPACE ]; then - echo "No workspace $WORKSPACE" +if [ "$WORKSPACE" = "" ]; then + echo "Please set valid workspace -w $WORKSPACE" + exit 1 +fi +if [ "$ROSINSTALL" = "" ]; then + echo "Please set valid rosinstall -r $ROSINSTALL" + exit 1 +fi +if [ "$ROBOT_TYPE" = "" ]; then + echo "Please set valid robot type -t $ROBOT_TYPE" exit 1 fi + . $WORKSPACE/devel/setup.bash # Filename should end with .txt to preview the contents in a web browser LOGFILE=$WORKSPACE/update_workspace.txt @@ -57,7 +78,7 @@ set -x wstool foreach -t $WORKSPACE/src --git 'git stash' wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot -ln -sf $(rospack find jsk_fetch_startup)/../jsk_fetch.rosinstall.$ROS_DISTRO $WORKSPACE/src/.rosinstall +ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall wstool update -t $WORKSPACE/src --delete-changed-uris # Forcefully checkout specified branch wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' @@ -66,18 +87,7 @@ WSTOOL_UPDATE_RESULT=$? # Rosdep Install sudo apt-get update -y rosdep update -# jsk_footstep_planner is not released for melodic -# jsk_footstep_controller is not released for melodic -# librealsense2 should not be installed from ROS repository -# realsense-ros should not be installed from ROS repository -rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys \ -"\ -jsk_footstep_controller \ -jsk_footstep_planner \ -librealsense2 \ -realsense2_camera \ -realsense2_description \ -" +rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys $SKIP_KEYS ROSDEP_INSTALL_RESULT=$? # Build workspace cd $WORKSPACE @@ -116,7 +126,7 @@ subject: 'Daily workspace update fails' body: - {type: 'text', message: '${MAIL_BODY}', file_path: '', img_data: '', img_size: 0} sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' -receiver_address: 'fetch@jsk.imi.i.u-tokyo.ac.jp' +receiver_address: '$ROBOT_TYPE@jsk.imi.i.u-tokyo.ac.jp' smtp_server: '' smtp_port: '' attached_files: ['$LOGFILE']" From dbe8b77e9614231bf90dabf663f42e1fc42e19c4 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 17:31:16 +0900 Subject: [PATCH 279/433] [jsk_pr2_startup] add update_workspace.sh for pr2 --- jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh | 5 +++++ 1 file changed, 5 insertions(+) create mode 100755 jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh diff --git a/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh new file mode 100755 index 0000000000..a1ebc5cfc0 --- /dev/null +++ b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh @@ -0,0 +1,5 @@ +#!/usr/bin/env bash + +cp $(rospack find jsk_robot_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh +/tmp/update_workspace.sh -w $HOME/ros/indigo -r $(rospack find jsk_pr2_startup)/jsk_pr2.rosinstall -t pr2 +rm /tmp/update_workspace.sh From 65d793d9a9a90ac5370c21a98bc0c309560239e5 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 17:55:01 +0900 Subject: [PATCH 280/433] [jsk_robot_startup] add option to disable rosdep install --- .../scripts/update_workspace_main.sh | 21 +++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 0dc6176331..2443db885a 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -2,7 +2,7 @@ function usage() { - echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-l] + echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-u] [-l] optional arguments: -h show this help @@ -10,6 +10,7 @@ optional arguments: -r ROSINTALL_PATH rosinstall path -t ROBOT robot type -s SKIP_KEYS rosdep install skip keys + -u do not run apt-get upgrade and rosdep install -l do not send a mail " } @@ -19,10 +20,11 @@ function get_full_path() echo "$(cd $(dirname $1) && pwd)/$(basename $1)" } +ROSDEP_INSTALL=true SEND_MAIL=true WORKSPACE=$(get_full_path $HOME/ros/$ROS_DISTRO) -while getopts w:r:t:s:lh OPT +while getopts w:r:t:s:ulh OPT do case $OPT in w) @@ -37,6 +39,9 @@ do s) SKIP_KEYS=$OPTARG ;; + u) + ROSDEP_INSTALL=false + ;; l) SEND_MAIL=false ;; @@ -85,10 +90,14 @@ wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abb wstool update -t $WORKSPACE/src WSTOOL_UPDATE_RESULT=$? # Rosdep Install -sudo apt-get update -y -rosdep update -rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys $SKIP_KEYS -ROSDEP_INSTALL_RESULT=$? +if [ "${ROSDEP_INSTALL}" == "true" ]; then + sudo apt-get update -y; + rosdep update; + rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys $SKIP_KEYS; + ROSDEP_INSTALL_RESULT=$?; +else + ROSDEP_INSTALL_RESULT=0; +fi # Build workspace cd $WORKSPACE catkin clean aques_talk collada_urdf_jsk_patch libcmt -y From f13866a42f008d0c86c98ff5cfc4b8e4a2165317 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 17:56:50 +0900 Subject: [PATCH 281/433] [jsk_pr2_startup] do not run rosdep in pr2 --- jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh index a1ebc5cfc0..3dbf85dd09 100755 --- a/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh +++ b/jsk_pr2_robot/jsk_pr2_startup/scripts/update_workspace.sh @@ -1,5 +1,5 @@ #!/usr/bin/env bash cp $(rospack find jsk_robot_startup)/scripts/update_workspace_main.sh /tmp/update_workspace.sh -/tmp/update_workspace.sh -w $HOME/ros/indigo -r $(rospack find jsk_pr2_startup)/jsk_pr2.rosinstall -t pr2 +/tmp/update_workspace.sh -w $HOME/ros/indigo -r $(rospack find jsk_pr2_startup)/jsk_pr2.rosinstall -t pr2 -u rm /tmp/update_workspace.sh From 0b060bbcb78f38a40244a30f61439ba326d49f5d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 19:09:36 +0900 Subject: [PATCH 282/433] Apply suggestions from code review Co-authored-by: Koki Shinjo --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 2443db885a..f653cd8934 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -82,7 +82,7 @@ set -x wstool foreach -t $WORKSPACE/src --git 'git stash' wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' -wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot +wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall wstool update -t $WORKSPACE/src --delete-changed-uris # Forcefully checkout specified branch From 498c4b9530549d5064828cb4b42f67c9c96fc913 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 22:29:59 +0900 Subject: [PATCH 283/433] [jsk_robot_startup] fix typo in update_workspace_main.sh --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index f653cd8934..053f0fcfd3 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -93,7 +93,7 @@ WSTOOL_UPDATE_RESULT=$? if [ "${ROSDEP_INSTALL}" == "true" ]; then sudo apt-get update -y; rosdep update; - rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys $SKIP_KEYS; + rosdep install --from-paths $WORKSPACE/src --ignore-src -y -r --skip-keys "$SKIP_KEYS"; ROSDEP_INSTALL_RESULT=$?; else ROSDEP_INSTALL_RESULT=0; From b1b1f6eb641ee2f47af69dd6d93fd3a1164538cb Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 20:30:20 +0900 Subject: [PATCH 284/433] add smach_image_publisher in fetch_bringup.launch --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index a587c70d13..5e4f56444a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -342,6 +342,14 @@ + + + + duration: 0.5 + + + From 2fdf917e2f66c9039d688c074b110ac0de5786be Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 30 Sep 2022 20:35:34 +0900 Subject: [PATCH 285/433] add smach video recorder in go_to_kitchen app --- .../apps/go_to_kitchen/go_to_kitchen.app | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 48e797cb66..a67ee96593 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -47,6 +47,7 @@ plugins: - /server_name/smach/container_structure - /audio - /rviz/throttled/image/compressed + - /smach_image_publisher/image/compressed - name: head_camera_converter_plugin type: app_recorder/rosbag_video_converter_plugin plugin_args: @@ -85,6 +86,14 @@ plugins: image_topic_name: /rviz/throttled/image/compressed image_fps: 5 video_path: /tmp/go_to_kitchen_rviz.mp4 + - name: smach_converter_plugin + type: app_recorder/rosbag_video_converter_plugin + plugin_args: + rosbag_path: /tmp + rosbag_title: go_to_kitchen_rosbag.bag + image_topic_name: /smach_image_publisher/image/compressed + image_fps: 2 + video_path: /tmp/go_to_kitchen_smach.mp4 - name: respeaker_audio_converter_plugin type: app_recorder/rosbag_audio_converter_plugin plugin_args: @@ -108,6 +117,7 @@ plugins: - /tmp/go_to_kitchen_object_detection.mp4 - /tmp/go_to_kitchen_panorama.mp4 - /tmp/go_to_kitchen_rviz.mp4 + - /tmp/go_to_kitchen_smach.mp4 - /tmp/go_to_kitchen_audio.wav - /tmp/go_to_kitchen_rosbag.bag - /tmp/trashcan_inside.jpg @@ -117,6 +127,7 @@ plugins: - go_to_kitchen_object_detection.mp4 - go_to_kitchen_panorama.mp4 - go_to_kitchen_rviz.mp4 + - go_to_kitchen_smach.mp4 - go_to_kitchen_audio.wav - go_to_kitchen_rosbag.bag - trashcan_inside.jpg @@ -166,6 +177,7 @@ plugin_order: - object_detection_converter_plugin - panorama_converter_plugin - rviz_converter_plugin + - smach_converter_plugin - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin @@ -182,6 +194,7 @@ plugin_order: - object_detection_converter_plugin - panorama_converter_plugin - rviz_converter_plugin + - smach_converter_plugin - respeaker_audio_converter_plugin - result_recorder_plugin - gdrive_uploader_plugin From fb980f16b0575727df6ad221b9d4281e00585147 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 4 Oct 2022 15:57:38 +0900 Subject: [PATCH 286/433] [jsk_fetch_startup] Generate fetch_email_topic.yaml when building workspace --- jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt | 14 ++++++++++++++ .../jsk_fetch_startup/config/email_topic.yaml.in | 2 ++ 2 files changed, 16 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index 20cade468e..96d03f10ea 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -90,10 +90,24 @@ macro(configure_dialogflow_hotword_yaml dname) endif() endmacro(configure_dialogflow_hotword_yaml) +macro(configure_email_topic_yaml rname) + cmake_host_system_information(RESULT FETCH_NAME QUERY HOSTNAME) + if (${FETCH_NAME} MATCHES ^${rname}) + set(RECEIVER_MAIL ${rname}) + set(EMAIL_SENDER_ADDRESS ${FETCH_NAME}@jsk.imi.i.u-tokyo.ac.jp) + set(EMAIL_RECEIVER_ADDRESS ${RECEIVER_MAIL}@jsk.imi.i.u-tokyo.ac.jp) + configure_file(${CMAKE_CURRENT_SOURCE_DIR}/config/email_topic.yaml.in + ${CMAKE_CURRENT_SOURCE_DIR}/config/${FETCH_NAME}_email_topic.yaml) + endif() +endmacro(configure_email_topic_yaml) + + configure_icon_files(blue fetch15) configure_icon_files(red fetch1075) configure_dialogflow_hotword_yaml(fetch15) configure_dialogflow_hotword_yaml(fetch1075) +configure_email_topic_yaml(fetch) + ############# ## Testing ## diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in b/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in new file mode 100644 index 0000000000..a087a38abb --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/email_topic.yaml.in @@ -0,0 +1,2 @@ +sender_address: @EMAIL_SENDER_ADDRESS@ +receiver_address: @EMAIL_RECEIVER_ADDRESS@ From ee57c1e3c4d12006683e2d3f332d27ff59d431f5 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 4 Oct 2022 16:12:12 +0900 Subject: [PATCH 287/433] [jsk_fetch_startup/config] Ignore email config from git tracking --- jsk_fetch_robot/jsk_fetch_startup/config/.gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore index 97ed018fbb..dd8bb6cb6a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore +++ b/jsk_fetch_robot/jsk_fetch_startup/config/.gitignore @@ -1 +1,2 @@ fetch*_dialogflow_hotword.yaml +fetch*_email_topic.yaml From 66f86073f7622500d9da4ca4f40b6a14ff8982f3 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 2 Oct 2022 23:01:49 +0900 Subject: [PATCH 288/433] [jsk_fetch_startup] Load rosparam for smach_to_mail as yaml --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 5e4f56444a..05522de9bc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -337,9 +337,8 @@ - - email_info: /var/lib/robot/email_topic.yaml - + From 0fd9051670e117bf674353b8bac5b58010dde02c Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 7 Oct 2022 12:29:52 +0900 Subject: [PATCH 289/433] [jsk_robot_startup] Use /email_topic/mail_title for email title --- jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py index ac911446b0..8f804b3380 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py @@ -257,6 +257,8 @@ def _send_mail(self, subject, state_list): if subject: email_msg.subject = subject + elif rospy.has_param("/email_topic/mail_title"): + email_msg.subject = rospy.get_param("/email_topic/mail_title") else: email_msg.subject = 'Message from {}'.format(rospy.get_param('/robot/name', 'robot')) From 9ca49b3e8fee50fbdd5fc0fbaa851db21f700ade Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 7 Oct 2022 12:30:53 +0900 Subject: [PATCH 290/433] [jsk_fetch_startup] Use email title set by mail_notifier --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index a67ee96593..2577fa0141 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -149,6 +149,7 @@ plugins: plugin_args: mail_title: Fetch kitchen patrol demo use_timestamp_title: true + use_app_start_time: true plugin_arg_yaml: /var/lib/robot/fetch_mail_notifier_plugin.yaml - name: move_base_cancel_plugin type: app_publisher/rostopic_publisher_plugin From 06f0a4222b0aadb895645fc1cad5cf383839dbaf Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 7 Oct 2022 14:20:01 +0900 Subject: [PATCH 291/433] update time_signal schedule --- .../jsk_fetch_startup/scripts/time_signal.py | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py index ca5781dc44..5e555dc93f 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py @@ -56,10 +56,8 @@ def speak_jp(self): speech_text += 'そろそろ輪講です。' if self.day == 'Tue' and self.now_hour == 15: speech_text += '掃除の時間です。' - if self.day == 'Fri' and self.now_hour == 14: + if self.day == 'Fri' and self.now_hour == 15: speech_text += '創造輪講の時間です。' - if self.day == 'Fri' and self.now_hour == 16: - speech_text += '掃除の時間です。' # weather forecast if self.now_hour in [0, 7, 12, 19]: @@ -80,6 +78,14 @@ def speak_en(self): speech_text += " Let's go to lunch." if self.now_hour == 19: speech_text += " Let's go to dinner." + if self.day == 'Mon' and self.now_hour == 12: + speech_text += ' The lab meeting will start soon.' + if self.day == 'Tue' and self.now_hour == 12: + speech_text += ' The lab meeting will start soon.' + if self.day == 'Tue' and self.now_hour == 15: + speech_text += ' It is cleaning time now.' + if self.day == 'Fri' and self.now_hour == 15: + speech_text += ' Rinko will start soon. ' # weather forecast if self.now_hour in [0, 7, 12, 19]: From 7ccac41488cfdf6802468e4fb60577bb1d6b2226 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 7 Oct 2022 14:21:16 +0900 Subject: [PATCH 292/433] update time text --- .../jsk_fetch_startup/scripts/time_signal.py | 39 +++++++++++++------ 1 file changed, 27 insertions(+), 12 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py index 5e555dc93f..d7999aef68 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py @@ -20,6 +20,7 @@ def __init__(self): '/robotsound_jp', SoundRequestAction) self.now_time = datetime.now() self.now_hour = self.now_time.hour + self.now_minute = self.now_time.minute self.day = self.now_time.strftime('%a') reload(sys) sys.setdefaultencoding('utf-8') @@ -43,7 +44,8 @@ def speak(self, client, speech_text, lang=None): def speak_jp(self): # time signal - speech_text = str(self.now_hour) + 'じです。' + speech_text = self._get_time_text( + self.now_hour, self.now_minute, lang='ja') if self.now_hour == 0: speech_text += '早く帰りましょう。' if self.now_hour == 12: @@ -70,7 +72,8 @@ def speak_jp(self): self.speak(self.client_jp, speech_text, lang='jp') def speak_en(self): - speech_text = self._get_text(self.now_hour) + speech_text = self._get_time_text( + self.now_hour, self.now_minute, lang='en') # time signal if self.now_hour == 0: speech_text += " Let's go home." @@ -97,18 +100,30 @@ def speak_en(self): rospy.logdebug(speech_text) self.speak(self.client_en, speech_text) - def _get_text(self, hour): - if hour == 0: - text = 'midnight' - elif hour == 12: - text = 'noon' + def _get_time_text(self, hour, minute, lang='en'): + if lang == 'ja': + if hour == 0 and minute == 0: + time_text = '正午' + else: + time_text = '{}時'.format(hour) + if minute != 0: + time_text += '{}分'.format(minute) + time_text += 'です。' else: - if hour > 12: - text = str(hour % 12) + ' P.M.' + if hour == 0 and minute == 0: + time_text = 'midnight' + elif hour == 12 and minute == 0: + time_text = 'noon' else: - text = str(hour % 12) + ' A.M.' - text = "It's " + text + "." - return text + time_text = str(hour % 12) + if minute != 0: + time_text += ' {}'.format(minute) + if hour > 12: + time_text += ' P.M.' + else: + time_text += ' A.M.' + time_text = "It's {}.".format(time_text) + return time_text def _get_weather_forecast(self, lang='en'): url = 'http://api.openweathermap.org/data/2.5/weather?q=tokyo&lang={}&units=metric&appid={}'.format(lang, self.appid) # NOQA From ec59072541932832ceef140505c39963c2e6b255 Mon Sep 17 00:00:00 2001 From: MiyabiTane Date: Mon, 10 Oct 2022 15:08:48 +0900 Subject: [PATCH 293/433] update README for develop/fetch branch --- jsk_fetch_robot/README.md | 38 ++++++++++++++++++++++++++++++++++++-- 1 file changed, 36 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 8a69d14fc1..bef719c8c4 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -50,8 +50,42 @@ wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstr bash /tmp/setup_upstream.sh -w ../ -p jsk-ros-pkg/geneus -p euslisp/jskeus source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src -cd ../ -catkin build fetcheus jsk_fetch_startup +cd jsk_robot +git fetch origin +git checkout -b develop/fetch origin/develop/fetch +``` + +Next, you need to install `roseus_resume` package. For more information, please check [Affonso-Gui/roseus_resume](https://github.com/Affonso-Gui/roseus_resume). +``` +cd ../../ # catkin_ws/src +# clone euslisp +wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh +bash /tmp/setup_upstream.sh -w .. + +# clone roseus +wstool set jsk-ros-pkg/jsk_roseus --git https://github.com/jsk-ros-pkg/jsk_roseus.git -v master -u -y +cd euslisp/Euslisp/ + +# checkout euslisp/eus-handler +git remote add Affonso-Gui https://github.com/Affonso-Gui/EusLisp.git +git fetch Affonso-Gui +git checkout eus10 + +# checkout roseus/eus-handler +cd ../../jsk-ros-pkg/jsk_roseus/ +git remote add Affonso-Gui https://github.com/Affonso-Gui/jsk_roseus.git +git fetch Affonso-Gui +git checkout eus10 +cd ../../ # catkin_ws/src + +# clone roseus_resume +git clone https://github.com/Affonso-Gui/roseus_resume.git +``` + +Finally, build the packages +``` +cd ../ # catkin_ws +catkin build euslisp roseus_resume fetcheus jsk_fetch_startup source devel/setup.bash ``` From 72bcf717aaf7325019aeb61b28e32ea00abbf594 Mon Sep 17 00:00:00 2001 From: MiyabiTane Date: Tue, 11 Oct 2022 13:27:14 +0900 Subject: [PATCH 294/433] more simple install --- jsk_fetch_robot/README.md | 44 +++++---------------------------------- 1 file changed, 5 insertions(+), 39 deletions(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index bef719c8c4..4333451423 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -41,52 +41,18 @@ Please make sure your ROS Distribution is indigo, kinetic or melodic. ```bash mkdir -p catkin_ws/src cd catkin_ws/src -wstool init . -wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -y +wstool init . +wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO +wstool merge -t . https://gist.githubusercontent.com/Affonso-Gui/25518fef9dc7af0051147bdd2a94b116/raw/e3fcbf4027c876329801a25e32f4a4746200ddae/guiga_system.rosinstall wstool update -t . # To use eus10, furuschev script is required. wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh bash /tmp/setup_upstream.sh -w ../ -p jsk-ros-pkg/geneus -p euslisp/jskeus source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src -cd jsk_robot -git fetch origin -git checkout -b develop/fetch origin/develop/fetch -``` - -Next, you need to install `roseus_resume` package. For more information, please check [Affonso-Gui/roseus_resume](https://github.com/Affonso-Gui/roseus_resume). -``` -cd ../../ # catkin_ws/src -# clone euslisp -wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh -bash /tmp/setup_upstream.sh -w .. - -# clone roseus -wstool set jsk-ros-pkg/jsk_roseus --git https://github.com/jsk-ros-pkg/jsk_roseus.git -v master -u -y -cd euslisp/Euslisp/ - -# checkout euslisp/eus-handler -git remote add Affonso-Gui https://github.com/Affonso-Gui/EusLisp.git -git fetch Affonso-Gui -git checkout eus10 - -# checkout roseus/eus-handler -cd ../../jsk-ros-pkg/jsk_roseus/ -git remote add Affonso-Gui https://github.com/Affonso-Gui/jsk_roseus.git -git fetch Affonso-Gui -git checkout eus10 -cd ../../ # catkin_ws/src - -# clone roseus_resume -git clone https://github.com/Affonso-Gui/roseus_resume.git -``` - -Finally, build the packages -``` -cd ../ # catkin_ws -catkin build euslisp roseus_resume fetcheus jsk_fetch_startup -source devel/setup.bash +cd ../ +catkin build fetcheus jsk_fetch_startup roseus_resume ``` #### Setup Environment (For Robot Internal PC, only for advanced developer) From b3510d08147b3325c064f04b7a5322807338857b Mon Sep 17 00:00:00 2001 From: MiyabiTane Date: Tue, 11 Oct 2022 13:33:32 +0900 Subject: [PATCH 295/433] fix --- jsk_fetch_robot/README.md | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index 4333451423..c8daa71043 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -41,7 +41,7 @@ Please make sure your ROS Distribution is indigo, kinetic or melodic. ```bash mkdir -p catkin_ws/src cd catkin_ws/src -wstool init . +wstool init . wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO wstool merge -t . https://gist.githubusercontent.com/Affonso-Gui/25518fef9dc7af0051147bdd2a94b116/raw/e3fcbf4027c876329801a25e32f4a4746200ddae/guiga_system.rosinstall @@ -53,6 +53,7 @@ source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src cd ../ catkin build fetcheus jsk_fetch_startup roseus_resume +source devel/setup.bash ``` #### Setup Environment (For Robot Internal PC, only for advanced developer) From c16436517e71379f9f99ff6eb1c4662a5431310b Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 12 Oct 2022 15:58:26 +0900 Subject: [PATCH 296/433] add eus10 and roseus_resume as optional --- jsk_fetch_robot/README.md | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/README.md b/jsk_fetch_robot/README.md index c8daa71043..51c6144640 100644 --- a/jsk_fetch_robot/README.md +++ b/jsk_fetch_robot/README.md @@ -44,15 +44,21 @@ cd catkin_ws/src wstool init . wstool set --git jsk-ros-pkg/jsk_robot https://github.com/jsk-ros-pkg/jsk_robot.git -v develop/fetch -y wstool merge -t . https://raw.githubusercontent.com/jsk-ros-pkg/jsk_robot/master/jsk_fetch_robot/jsk_fetch_user.rosinstall.$ROS_DISTRO + +# (optional): the two lines below are necessary when you want to use roseus_resume wstool merge -t . https://gist.githubusercontent.com/Affonso-Gui/25518fef9dc7af0051147bdd2a94b116/raw/e3fcbf4027c876329801a25e32f4a4746200ddae/guiga_system.rosinstall wstool update -t . -# To use eus10, furuschev script is required. + +# (optional): the two lines below are necessary when you want to use eus10 wget https://raw.githubusercontent.com/jsk-ros-pkg/jsk_roseus/master/setup_upstream.sh -O /tmp/setup_upstream.sh bash /tmp/setup_upstream.sh -w ../ -p jsk-ros-pkg/geneus -p euslisp/jskeus + source /opt/ros/$ROS_DISTRO/setup.bash rosdep install -y -r --from-paths . --ignore-src cd ../ -catkin build fetcheus jsk_fetch_startup roseus_resume +# (optional): if you want to use roseus_resume, build roseus_resume, too. +catkin build fetcheus jsk_fetch_startup + source devel/setup.bash ``` From ab0e56b739b17fd9a83047253655c0207ba15b98 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Wed, 12 Oct 2022 16:46:44 +0900 Subject: [PATCH 297/433] speak date when midnight --- .../jsk_fetch_startup/scripts/time_signal.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py index d7999aef68..321714985a 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py @@ -19,6 +19,7 @@ def __init__(self): self.client_jp = actionlib.SimpleActionClient( '/robotsound_jp', SoundRequestAction) self.now_time = datetime.now() + self.now_date = self.now_time.date() self.now_hour = self.now_time.hour self.now_minute = self.now_time.minute self.day = self.now_time.strftime('%a') @@ -45,7 +46,8 @@ def speak(self, client, speech_text, lang=None): def speak_jp(self): # time signal speech_text = self._get_time_text( - self.now_hour, self.now_minute, lang='ja') + self.now_date, self.now_hour, self.now_minute, + lang='ja') if self.now_hour == 0: speech_text += '早く帰りましょう。' if self.now_hour == 12: @@ -73,7 +75,8 @@ def speak_jp(self): def speak_en(self): speech_text = self._get_time_text( - self.now_hour, self.now_minute, lang='en') + self.now_date, self.now_hour, self.now_minute, + lang='en') # time signal if self.now_hour == 0: speech_text += " Let's go home." @@ -100,9 +103,12 @@ def speak_en(self): rospy.logdebug(speech_text) self.speak(self.client_en, speech_text) - def _get_time_text(self, hour, minute, lang='en'): + def _get_time_text(self, date, hour, minute, lang='en'): if lang == 'ja': if hour == 0 and minute == 0: + time_text = '{}年{}月{}日'.format( + date.year, date.month, date.day) + elif hour == 12 and minute == 0: time_text = '正午' else: time_text = '{}時'.format(hour) @@ -111,7 +117,7 @@ def _get_time_text(self, hour, minute, lang='en'): time_text += 'です。' else: if hour == 0 and minute == 0: - time_text = 'midnight' + time_text = date.strftime('%Y %B %d') elif hour == 12 and minute == 0: time_text = 'noon' else: From 418633514cd556b533268772d9e2885acb83e672 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 11 Oct 2022 16:20:22 +0900 Subject: [PATCH 298/433] [jsk_robot_startup] Add timeout for smach notification --- jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py index 8f804b3380..cbe1d93b63 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py @@ -148,6 +148,7 @@ def _status_cb(self, msg): # If we received START/INIT status, restart storing smach_state_list if status_str in ["START", "INIT"]: + self.smach_start_time[caller_id] = rospy.Time.now() self.smach_state_list[caller_id] = [] # DESCRIPTION of START is MAIL SUBJECT if 'DESCRIPTION' in local_data_str: From 16605a71d8acb7fff6e41dc74187367ff78d3f1e Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Mon, 17 Oct 2022 19:49:06 +0900 Subject: [PATCH 299/433] add smach_image_view in jsk_startup_record.rviz --- .../config/jsk_startup_record.rviz | 57 ++++++++++++------- 1 file changed, 35 insertions(+), 22 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz index 8b162425f0..6ab7883d78 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz +++ b/jsk_fetch_robot/jsk_fetch_startup/config/jsk_startup_record.rviz @@ -3,9 +3,10 @@ Panels: Help Height: 78 Name: Displays Property Tree Widget: - Expanded: ~ + Expanded: + - /OverlayImage1 Splitter Ratio: 0.4187380373477936 - Tree Height: 624 + Tree Height: 618 - Class: rviz/Selection Name: Selection - Class: rviz/Tool Properties @@ -65,11 +66,6 @@ Visualization Manager: Expand Link Details: false Expand Tree: false Link Tree Style: Links in Alphabetic Order - base_camera_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true base_link: Alpha: 1 Show Axes: false @@ -85,14 +81,6 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true - d435_front_left_link: - Alpha: 1 - Show Axes: false - Show Trail: false - d435_front_right_link: - Alpha: 1 - Show Axes: false - Show Trail: false elbow_flex_link: Alpha: 1 Show Axes: false @@ -113,11 +101,6 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true - head_box_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true head_camera_depth_frame: Alpha: 1 Show Axes: false @@ -138,6 +121,15 @@ Visualization Manager: Alpha: 1 Show Axes: false Show Trail: false + head_l515_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_l515_virtual_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false head_pan_link: Alpha: 1 Show Axes: false @@ -148,6 +140,14 @@ Visualization Manager: Show Axes: false Show Trail: false Value: true + insta360_link: + Alpha: 1 + Show Axes: false + Show Trail: false + l515_head_link: + Alpha: 1 + Show Axes: false + Show Trail: false l_gripper_finger_link: Alpha: 1 Show Axes: false @@ -455,6 +455,19 @@ Visualization Manager: Name: RvizScenePublisher Value: true topic_name: /rviz/image + - Class: jsk_rviz_plugin/OverlayImage + Enabled: true + Name: OverlayImage + Topic: /smach_image_publisher/image + Value: true + alpha: 0.800000011920929 + height: 128 + keep aspect ratio: true + left: 650 + overwrite alpha value: false + top: 10 + transport hint: compressed + width: 300 Enabled: true Global Options: Background Color: 48; 48; 48 @@ -513,7 +526,7 @@ Window Geometry: Height: 1052 Hide Left Dock: true Hide Right Dock: true - QMainWindow State: 000000ff00000000fd0000000400000000000001f800000382fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003b000002f9000000c700fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e000000033a000000830000007900ffffff000000010000010f00000382fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000382000000a000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f50000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000003f50000038200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000001f80000037efc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003d000002f5000000c900fffffffb00000018004b0069006e00650063007400430061006d0065007200610000000373000000160000000000000000fb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb00000018004e006100720072006f007700430061006d0065007200610000000244000001460000000000000000fb0000001800430061006e00630065006c0041006300740069006f006e0000000338000000830000007f00ffffff000000010000010f00000382fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003b00000382000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000780000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000003f50000003efc0100000002fb0000000800540069006d00650100000000000003f5000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003f50000037e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: @@ -524,4 +537,4 @@ Window Geometry: collapsed: true Width: 1013 X: 67 - Y: 180 + Y: 134 From 78332597841b251efb81f24077edcf919dd1d4ea Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 13 Oct 2022 15:56:39 +0900 Subject: [PATCH 300/433] refactor and add launch_* args in fetch_bringup --- .../launch/fetch_bringup.launch | 253 +++++++++++------- 1 file changed, 153 insertions(+), 100 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 05522de9bc..0235c6627d 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -1,40 +1,66 @@ - + - + + + + + + + + - + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - @@ -43,7 +69,7 @@ + respawn="true" output="screen" if="$(arg launch_battery_warning)"> duration: 180 charge_level_threshold: 65.0 @@ -53,13 +79,15 @@ - + lang: japanese volume: 0.5 - + @@ -74,25 +102,30 @@ - - - - - - default_voice: $(arg default_english_speaker) - plugin: sound_play/flite_plugin - - + + + + + + + default_voice: $(arg default_english_speaker) + plugin: sound_play/flite_plugin + + + - - - - - - - - + + + + + + + + + + + @@ -100,7 +133,8 @@ - + @@ -123,18 +157,23 @@ - + - + - + + + @@ -179,13 +218,15 @@ - + - + @@ -197,16 +238,18 @@ - + - + interface_name: wlan0 - + @@ -255,14 +298,15 @@ - + vital_rate: 0.1 - + @@ -304,12 +348,13 @@ + output="screen" if="$(arg launch_build_map)" > - + luminance_threshold: 70 @@ -317,7 +362,8 @@ - + map_frame: /map base_frame: /base_link @@ -325,64 +371,71 @@ - + - - - - email_info: /var/lib/robot/email_topic.yaml - - - - - - - + + + + + email_info: /var/lib/robot/email_topic.yaml + + + + + + + + - + duration: 0.5 - - + + + + - - - - - run_stop_topic: robot_state - run_stop_condition: "m.runstopped is True" - seconds_to_start_speaking: 60 - speak_interval: 600 - language: $(arg default_warning_speaker) - ignore_time_after_runstop_is_enabled: 5.0 - ignore_time_after_runstop_is_disabled: 5.0 - - - - - - + + + + + + run_stop_topic: robot_state + run_stop_condition: "m.runstopped is True" + seconds_to_start_speaking: 60 + speak_interval: 600 + language: $(arg default_warning_speaker) + ignore_time_after_runstop_is_enabled: 5.0 + ignore_time_after_runstop_is_disabled: 5.0 + + + + + + + From 8024600fbeefd65ff2218cdc697359607c17afde Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Thu, 13 Oct 2022 15:57:06 +0900 Subject: [PATCH 301/433] update fetch_gazebo_bringup.launch --- .../launch/fetch_gazebo_bringup.launch | 49 +++++++++++++++++-- 1 file changed, 45 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch index 62ec7167f5..0d48cab9e7 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_gazebo_bringup.launch @@ -4,6 +4,9 @@ + + + @@ -31,13 +34,51 @@ + + + + + + + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 9df1b47044070f5a90438bffe289320e7fa099bf Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sun, 25 Sep 2022 12:15:33 +0900 Subject: [PATCH 302/433] [jsk_fetch_startup] update move_base parameter for recovery behavior --- .../fetch_move_base_common_params.yaml | 37 ++++++++++++++++++- 1 file changed, 35 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml index b7eabb9a39..f521ba7e1e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml @@ -1,9 +1,17 @@ move_base: recovery_behavior_enabled: true recovery_behaviors: + - name: "update_inflation_layer_local0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_local0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" + - name: "update_inflation_layer_global0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_global0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" - name: "conservative_reset" type: "clear_costmap_recovery/ClearCostmapRecovery" - - name: "rotate_recovery0" + - name: "rotate_recovery" type: "rotate_recovery/RotateRecovery" - name: "speak_and_wait0" type: "speak_and_wait_recovery/SpeakAndWaitRecovery" @@ -19,16 +27,41 @@ move_base: type: "rotate_recovery/RotateRecovery" - name: "move_slow_and_clear" type: "move_slow_and_clear/MoveSlowAndClear" + update_inflation_layer_local0: + parameter_name: "/move_base/local_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_local0: + parameter_name: "/move_base/local_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + update_inflation_layer_global0: + parameter_name: "/move_base/global_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_global0: + parameter_name: "/move_base/global_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + conservative_reset: + reset_distance: 3.0 + force_updating: true speak_and_wait0: - speak_text: "とおれません、みちをあけてください" + speak_text: "とおれません、ちょっとみちをあけてください" duration_wait: 5.0 duration_timeout: 1.0 sound_action: /robotsound_jp + aggressive_reset: + reset_distance: 1.0 + force_updating: true speak_and_wait1: speak_text: "とおれません、みちをあけてください" duration_wait: 5.0 duration_timeout: 1.0 sound_action: /robotsound_jp + all_reset: + reset_distance: 0.0 + force_updating: true move_slow_and_clear: planner_namespace: TrajectoryPlannerROS max_trans_param_name: max_vel_x From 01e16cde3ab1eea1b85553daf8986fa134654498 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sun, 25 Sep 2022 12:17:10 +0900 Subject: [PATCH 303/433] [jsk_fetch_startup] add update_move_base_parameter_recovery to dependencies --- jsk_fetch_robot/jsk_fetch_startup/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 0a031ea04e..70d3f9eda9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -51,6 +51,7 @@ librealsense2 realsense2_camera realsense2_description + update_move_base_parameter_recovery app_manager From dc8064db0503190c120b33fe75efeabe8da74f4f Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 26 Sep 2022 10:16:15 +0900 Subject: [PATCH 304/433] [jsk_fetch_startup] update timeout duration for update_move_base_parameter_recovery --- .../navigation/fetch1075/fetch_move_base_common_params.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml index f521ba7e1e..b4f55df760 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml @@ -30,15 +30,15 @@ move_base: update_inflation_layer_local0: parameter_name: "/move_base/local_costmap/inflater" inflation_radius: 0.1 - duration_dealline: 15.0 + duration_dealline: 30.0 update_costmap_local0: parameter_name: "/move_base/local_costmap" footprint_padding: 0.1 - duration_dealline: 15.0 + duration_dealline: 25.0 update_inflation_layer_global0: parameter_name: "/move_base/global_costmap/inflater" inflation_radius: 0.1 - duration_dealline: 15.0 + duration_dealline: 20.0 update_costmap_global0: parameter_name: "/move_base/global_costmap" footprint_padding: 0.1 From b43c5a426442d09af241cdbd39dc138cbbc6f2ff Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Sat, 24 Sep 2022 09:46:25 +0900 Subject: [PATCH 305/433] [jsk_fetch_startup] update recovery behavior conf for fetch1075 --- .../fetch_move_base_common_params.yaml | 73 +++++++++++-------- 1 file changed, 42 insertions(+), 31 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml index b4f55df760..440655c9e9 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml @@ -1,18 +1,10 @@ move_base: recovery_behavior_enabled: true recovery_behaviors: - - name: "update_inflation_layer_local0" - type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" - - name: "update_costmap_local0" - type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" - - name: "update_inflation_layer_global0" - type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" - - name: "update_costmap_global0" - type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" - - name: "conservative_reset" - type: "clear_costmap_recovery/ClearCostmapRecovery" - - name: "rotate_recovery" - type: "rotate_recovery/RotateRecovery" + - name: "complex_conservative_recovery" + type: "complex_recovery/SequentialComplexRecovery" + - name: "complex_rotate0" + type: "complex_recovery/SequentialComplexRecovery" - name: "speak_and_wait0" type: "speak_and_wait_recovery/SpeakAndWaitRecovery" - name: "aggressive_reset" @@ -27,25 +19,44 @@ move_base: type: "rotate_recovery/RotateRecovery" - name: "move_slow_and_clear" type: "move_slow_and_clear/MoveSlowAndClear" - update_inflation_layer_local0: - parameter_name: "/move_base/local_costmap/inflater" - inflation_radius: 0.1 - duration_dealline: 30.0 - update_costmap_local0: - parameter_name: "/move_base/local_costmap" - footprint_padding: 0.1 - duration_dealline: 25.0 - update_inflation_layer_global0: - parameter_name: "/move_base/global_costmap/inflater" - inflation_radius: 0.1 - duration_dealline: 20.0 - update_costmap_global0: - parameter_name: "/move_base/global_costmap" - footprint_padding: 0.1 - duration_dealline: 15.0 - conservative_reset: - reset_distance: 3.0 - force_updating: true + complex_conservative_recovery: + recovery_behaviors: + - name: "update_inflation_layer_local0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_local0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" + - name: "conservative_reset" + type: "clear_costmap_recovery/ClearCostmapRecovery" + update_inflation_layer_local0: + parameter_name: "/move_base/local_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_local0: + parameter_name: "/move_base/local_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + update_inflation_layer_global0: + parameter_name: "/move_base/global_costmap/inflater" + inflation_radius: 0.1 + duration_dealline: 15.0 + update_costmap_global0: + parameter_name: "/move_base/global_costmap" + footprint_padding: 0.1 + duration_dealline: 15.0 + conservative_reset: + reset_distance: 3.0 + force_updating: true + complex_rotate0: + recovery_behaviors: + - name: "speak_and_wait" + type: "speak_and_wait_recovery/SpeakAndWaitRecovery" + - name: "rotate_recovery" + type: "rotate_recovery/RotateRecovery" + speak_and_wait: + speak_text: "リカバリのためにまわります。" + duration_wait: 0.0 + duration_timeout: 1.0 + sound_action: /robotsound_jp speak_and_wait0: speak_text: "とおれません、ちょっとみちをあけてください" duration_wait: 5.0 From d441427aad5e22132256665b3e5f166bf06f0b3e Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 20 Oct 2022 15:07:48 +0900 Subject: [PATCH 306/433] [jsk_fetch_startup] add global config update recovery to complex recovery --- .../navigation/fetch1075/fetch_move_base_common_params.yaml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml index 440655c9e9..d34d1b345a 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/navigation/fetch1075/fetch_move_base_common_params.yaml @@ -25,6 +25,10 @@ move_base: type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" - name: "update_costmap_local0" type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" + - name: "update_inflation_layer_global0" + type: "update_move_base_parameter_recovery/UpdateInflationLayerParameterRecovery" + - name: "update_costmap_global0" + type: "update_move_base_parameter_recovery/UpdateCostmapParameterRecovery" - name: "conservative_reset" type: "clear_costmap_recovery/ClearCostmapRecovery" update_inflation_layer_local0: From eb0126b1366f3e6e7aa289c6c2ee7f3fecdf327b Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 21 Oct 2022 14:58:49 +0900 Subject: [PATCH 307/433] change node name to smach_to_mail --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 0235c6627d..1e45e923ad 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -384,7 +384,8 @@ - + + From 5b9cdf4353aec7f4e50a4d3ec1b4259845994316 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 21 Oct 2022 14:59:06 +0900 Subject: [PATCH 308/433] add smach_to_mail param --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 1e45e923ad..2be8f75811 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -388,6 +388,12 @@ + + use_mail: true + use_twitter: $(arg launch_tweet) + use_google_chat: $(arg launch_google_chat) + google_chat_space: spaces/AAAARE9CrfA + From 50734d8c24f1c59d9ccfcc95e656160aafdcaeb5 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 13 Oct 2022 11:47:52 +0900 Subject: [PATCH 309/433] [jsk_fetch_startup] add side hook to fetch model --- .../robots/jsk_fetch.urdf.xacro | 4 ++ .../robots/side_hook.urdf.xacro | 38 +++++++++++++++++++ 2 files changed, 42 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro index ede62cbb2c..dd4b46c989 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro @@ -6,6 +6,7 @@ + @@ -25,4 +26,7 @@ + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro new file mode 100644 index 0000000000..0c3c726933 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 352279f28ab40a6f432bd9c403f703ce8da1f97d Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 13 Oct 2022 12:45:37 +0900 Subject: [PATCH 310/433] [jsk_fetch_accessories] add finger_tip_collision --- .../finger_tip_collision/finger_tip_collision.STL | Bin 0 -> 684 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL diff --git a/jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL b/jsk_fetch_robot/jsk_fetch_accessories/finger_tip_collision/finger_tip_collision.STL new file mode 100644 index 0000000000000000000000000000000000000000..ff1925fd32ac06c72c1795ec3e8fcdcd4df4344f GIT binary patch literal 684 zcmaKp%?-jZ425&z#1Nf?svUs^QVD1k5hYd2jZ4-*48R7xG6ZWd1c{xLmr{{Se(cZB zei^M+$3n|)PR4)%!Yc(osia%>B(sIvus`u?wPUEZccRIfx zo1G91zEdg@ZV~w*n2xpmMigX;`hL4ssIf+{dW>Ymmu3xDMlHx<4W6mNcS+QIN%6tr84~K(I!v1&-$KCTB@2)4&elpV-x?gPri?$+tixcW0kGh3=vY Ri>`vRjzut%6QM(%?*oQ>!Z-i` literal 0 HcmV?d00001 From 046390130f1e2c8af8b745d80d05496626fe4b92 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 13 Oct 2022 12:51:45 +0900 Subject: [PATCH 311/433] [jsk_fetch_startup] add finger_tip to fetch model --- .../robots/finger_tip.urdf.xacro | 72 +++++++++++++++++++ .../robots/jsk_fetch.urdf.xacro | 4 ++ 2 files changed, 76 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro new file mode 100644 index 0000000000..03942ed007 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro index dd4b46c989..6cbb4f2840 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/jsk_fetch.urdf.xacro @@ -7,6 +7,7 @@ + @@ -29,4 +30,7 @@ + + + From d75afd1cad5eb06ca243475dd809ac598a71b5e6 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 13 Oct 2022 13:37:31 +0900 Subject: [PATCH 312/433] [jsk_fetch_startup] fix parameters of finger_tip.urdf.xacro --- .../jsk_fetch_startup/robots/finger_tip.urdf.xacro | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro index 03942ed007..0e1002ac0e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/finger_tip.urdf.xacro @@ -29,7 +29,7 @@ - + @@ -64,7 +64,7 @@ - + From 21a135334f077bafafc249e9f76dc22a551d18c6 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Thu, 13 Oct 2022 13:57:05 +0900 Subject: [PATCH 313/433] [jsk_fetch_startup] update parameter of side_hook.urdf.xacro --- jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro index 0c3c726933..c8206ecdc5 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro @@ -23,7 +23,7 @@ - + From d8758e022119da47828dcf0c92688d2ea0b9186d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Sat, 22 Oct 2022 22:01:39 +0900 Subject: [PATCH 314/433] add spin-once before image set-alist --- .../euslisp/navigation-utils.l | 30 +++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 0112a5fc24..c048537e38 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -762,6 +762,7 @@ Args: '(lambda (userdata) (let ((light-on (get-light-on))) (setf (cdr (assoc 'initial-light-on userdata)) light-on) + (ros::spin-once) (if light-on (set-alist 'description "電気がついていたよ" userdata) (set-alist 'description "電気がついていなかったよ" userdata)) @@ -776,6 +777,7 @@ Args: (let ((control-switchbot (cdr (assoc 'control-switchbot userdata)))) (report-light-off) (room-light-on :control-switchbot control-switchbot) + (ros::spin-once) (set-alist 'description "電気をつけたよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t))) @@ -784,6 +786,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) (success (move-to-dock-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) + (ros::spin-once) (if success (set-alist 'description "ドックの前に移動したよ" userdata) (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -792,12 +795,14 @@ Args: (:inspect-dock-front '(lambda (userdata) (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "ドックの前の様子を見たよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-dock-front-failure '(lambda (userdata) (report-move-to-dock-front-failure) + (ros::spin-once) (set-alist 'description "ドックの前に移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -806,6 +811,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) (success (move-to-tv-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) + (ros::spin-once) (if success (set-alist 'description "テレビの前に移動したよ" userdata) (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -814,12 +820,14 @@ Args: (:inspect-tv-front '(lambda (userdata) (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "テレビの前の様子を見たよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-tv-front-failure '(lambda (userdata) (report-move-to-tv-front-failure) + (ros::spin-once) (set-alist 'description "テレビの前に移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -828,6 +836,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) (success (move-to-tv-desk :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) (if success (set-alist 'description "机の前に移動したよ" userdata) (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -836,12 +845,14 @@ Args: (:inspect-tv-desk '(lambda (userdata) (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "机の様子を確認したよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-tv-desk-failure '(lambda (userdata) (report-move-to-tv-desk-failure) + (ros::spin-once) (set-alist 'description "机の前に移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -850,6 +861,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) (success (move-to-desk-back :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) + (ros::spin-once) (if success (set-alist 'description "部屋の後ろに移動したよ" userdata) (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) @@ -858,12 +870,14 @@ Args: (:inspect-desk-back '(lambda (userdata) (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "部屋の後ろを確認したよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-desk-back-failure '(lambda (userdata) (report-move-to-desk-back-failure) + (ros::spin-once) (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -872,6 +886,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) (success (move-to-desk-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) + (ros::spin-once) (if success (set-alist 'description "部屋の前に移動したよ" userdata) (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -880,12 +895,14 @@ Args: (:inspect-desk-front '(lambda (userdata) (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "部屋の前を確認したよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-desk-front-failure '(lambda (userdata) (report-move-to-desk-front-failure) + (ros::spin-once) (set-alist 'description "部屋の前に移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -894,6 +911,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) (success (move-to-kitchen-door-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) (if success (set-alist 'description "ドアの前に移動したよ" userdata) (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -902,12 +920,14 @@ Args: (:inspect-kitchen-door-front '(lambda (userdata) (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-kitchen-door-front-failure '(lambda (userdata) (report-move-to-kitchen-door-front-failure) + (ros::spin-once) (set-alist 'description "ドアの前に移動できなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -916,6 +936,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) (success (move-to-sink-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) + (ros::spin-once) (if success (set-alist 'description "キッチンに移動したよ" userdata) (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) @@ -926,12 +947,14 @@ Args: (let* ((label-names (notify-recognition :location "kitchen")) (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-sink-front-failure '(lambda (userdata) (report-move-to-sink-front-failure) + (ros::spin-once) (set-alist 'description "キッチンに行けなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -940,6 +963,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) (success (move-to-trashcan-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) + (ros::spin-once) (if success (set-alist 'description "ゴミ箱の前に移動したよ" userdata) (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) @@ -948,12 +972,14 @@ Args: (:inspect-trashcan '(lambda (userdata) (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) (:report-move-to-trashcan-front-failure '(lambda (userdata) (report-move-to-trashcan-front-failure) + (ros::spin-once) (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -963,6 +989,7 @@ Args: (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) (success (auto-dock :n-trial n-trial :clear-costmap nil))) (setf (cdr (assoc 'success-auto-dock userdata)) success) + (ros::spin-once) (if success (set-alist 'description "帰ってきたよ" userdata) (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) @@ -971,6 +998,7 @@ Args: (:auto-dock-failure '(lambda (userdata) (report-auto-dock-failure) + (ros::spin-once) (set-alist 'description "帰ってこられなかったよ" userdata) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) t)) @@ -982,6 +1010,7 @@ Args: (if (and success-auto-dock (not initial-light-on)) (progn (room-light-off :control-switchbot control-switchbot) + (ros::spin-once) (set-alist 'description "電気を消したよ" userdata) (set-alist 'image "" userdata)))) t)) @@ -994,6 +1023,7 @@ Args: (success-go-to-kitchen (cdr (assoc 'success-go-to-kitchen userdata)))) (restore-params) + (ros::spin-once) (set-alist 'description "キッチンデモを終えるよ" userdata) (set-alist 'image "" userdata) (and success-go-to-kitchen success-auto-dock success-battery-charging))))) From 74bd9b4fde7928da11145705e5df4a52791ae545 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 25 Oct 2022 00:47:55 +0900 Subject: [PATCH 315/433] use jsk_recognition for vital check --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 2ecfc0bdfb..cc1f06db8e 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -65,11 +65,12 @@ local-name: jsk-ros-pkg/jsk_pr2eus uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git version: master -# we need to use the development branch until the next release. +# we need this PR for fisheye vital check +# https://github.com/jsk-ros-pkg/jsk_recognition/pull/2734 - git: local-name: jsk-ros-pkg/jsk_recognition - uri: https://github.com/jsk-ros-pkg/jsk_recognition.git - version: master + uri: https://github.com/knorth55/jsk_recognition.git + version: fisheye-vital-check # we need to use the development branch (fetch15 branch in knorth55's fork) # until it is merged to master - git: From 154eca08c2ca90aa0e231c19ed026a3e004e9db5 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Mon, 31 Oct 2022 20:45:01 +0900 Subject: [PATCH 316/433] fix udev for playstation --- jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules index 113b5af453..05f7eb15b3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/99-jsk-ps3joy.rules @@ -3,3 +3,4 @@ # https://github.com/fetchrobotics/fetch_robots/blob/8e144f9a193129a0de5254075bbe5eb8245e1603/fetch_system_config/root/lib/udev/rules.d/99-ps3joy.rules # Current 99-ps3joy.rules in fetchrobotics/fetch_robots is for PS4 controller, but we still use PS3 controller. KERNEL=="js?", SUBSYSTEM=="input", ATTRS{name}=="Sony PLAYSTATION(R)3 Controller", SYMLINK+="ps3joy" +KERNEL=="js?", SUBSYSTEM=="input", ATTRS{name}=="PLAYSTATION(R)3 Controller", SYMLINK+="ps3joy" From 3840458297e56b24c60995e45ed7765e8cb3dfb9 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 10 Nov 2022 14:45:27 +0900 Subject: [PATCH 317/433] [jsk_robot_startup] Support manual setting of the name of database and collection --- .../src/lightweight_logger_nodelet.cpp | 21 ++++++++++++++++--- 1 file changed, 18 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp index c357e44273..cf6929b476 100644 --- a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp +++ b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp @@ -49,8 +49,23 @@ namespace jsk_robot_startup jsk_topic_tools::StealthRelay::onInit(); // settings for database - nh_->param("/robot/database", db_name_, "jsk_robot_lifelog"); - nh_->param("/robot/name", col_name_, std::string()); + if (ros::param::has("~database")) + { + pnh_->param("~database", db_name_, "jsk_robot_lifelog"); + } + else + { + pnh_->param("/robot/database", db_name_, "jsk_robot_lifelog"); + } + if (ros::param::has("~collection")) + { + pnh_->param("~collection", col_name_, std::string()); + } + else + { + pnh_->param("/robot/name", col_name_, std::string()); + } + if (col_name_.empty()) { NODELET_FATAL_STREAM("Please specify param 'robot/name' (e.g. pr1012, olive)"); @@ -123,7 +138,7 @@ namespace jsk_robot_startup // The message store object is initialized here, since the object waits for connection // until the connection to the server is established. - msg_store_.reset(new mongodb_store::MessageStoreProxy(*nh_, col_name_, db_name_)); + msg_store_.reset(new mongodb_store::MessageStoreProxy(*pnh_, col_name_, db_name_)); initialized_ = true; // After message store object is initialized, this thread is re-used for From 07a5db667a7d5b79f87fd76bff2933b5963a1c23 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 10 Nov 2022 14:46:11 +0900 Subject: [PATCH 318/433] [jsk_robot_startup] Add database and collection rospram --- .../src/jsk_robot_startup/lifelog/action_logger.py | 5 ++++- .../src/jsk_robot_startup/lifelog/base_trajectory_logger.py | 6 +++++- .../src/jsk_robot_startup/lifelog/mongo_record.py | 6 +++++- .../jsk_robot_startup/lifelog/object_detection_logger.py | 6 +++++- .../src/jsk_robot_startup/lifelog/tf_logger.py | 5 ++++- 5 files changed, 23 insertions(+), 5 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py index d42e5d89f4..8fe84131a3 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/action_logger.py @@ -22,7 +22,10 @@ class ActionLogger(LoggerBase): subscribers = {} # topicname:subscriber def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(ActionLogger, self).__init__(db_name=db_name, col_name=col_name) self.queue_size = rospy.get_param("~queue_size", 30) self.action_regex = re.compile(".*Action(Result|Goal|Feedback)$") diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py index 664f8fac94..c870cab227 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/base_trajectory_logger.py @@ -31,7 +31,11 @@ def diff_pose(p1, p2): class BaseTrajectoryLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(BaseTrajectoryLogger, self).__init__(db_name=db_name, col_name=col_name) + self.update_rate = rospy.get_param("~update_rate", 1.0) self.use_amcl = rospy.get_param("~use_amcl", True) self.persistent = rospy.get_param("~persistent", True) diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py index 71803288c1..eed8897950 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/mongo_record.py @@ -20,6 +20,7 @@ def __init__(self, argv=None): self.queue_size = rospy.get_param("~queue_size", 1) self.update_rate = rospy.get_param("~update_rate", 1.0) subst_param = rospy.get_param("~subst_param", False) + database = rospy.get_param("~database", 'jsk_robot_lifelog') collection = rospy.get_param("~collection", None) else: args = self.parse_args(argv) @@ -28,6 +29,7 @@ def __init__(self, argv=None): self.queue_size = args.queue_size self.update_rate = args.update_rate subst_param = args.subst_param + database = args.database collection = args.collection self.subscribers = {} @@ -42,7 +44,7 @@ def __init__(self, argv=None): topics.append(str().join(splitted)) self.topics = topics - LoggerBase.__init__(self, col_name=collection) + LoggerBase.__init__(self, db_name=database, col_name=collection) def parse_args(self, argv): p = argparse.ArgumentParser() @@ -57,6 +59,8 @@ def parse_args(self, argv): help="Enable substring param (e,g, '$(param robot/name)/list')") p.add_argument("-r", "--update-rate", type=float, default=1.0, help="Update rate for checking topics") + p.add_argument("-d", "--database", type=str, default=None, + help="Database name to record data") p.add_argument("-c", "--collection", type=str, default=None, help="Collection name to record data") return p.parse_args(argv) diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py index 4b607dade1..f8623ba2cd 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/object_detection_logger.py @@ -16,7 +16,11 @@ class ObjectDetectionLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(ObjectDetectionLogger, self).__init__(db_name=db_name, col_name=col_name) + self.update_rate = rospy.get_param("~update_rate", 1.0) self.map_frame = rospy.get_param('~map_frame', 'map') self.robot_frame = rospy.get_param('~robot_frame', 'base_footprint') diff --git a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py index 38192b7737..42f0fdbe5e 100644 --- a/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py +++ b/jsk_robot_common/jsk_robot_startup/src/jsk_robot_startup/lifelog/tf_logger.py @@ -13,7 +13,10 @@ class TFLogger(LoggerBase): def __init__(self): - LoggerBase.__init__(self) + db_name = rospy.get_param('~database', 'jsk_robot_lifelog') + col_name = rospy.get_param('~collection', None) + + super(TFLogger, self).__init__(db_name=db_name, col_name=col_name) self.tf_buffer = tf2_ros.Buffer() self.tf_listener = tf2_ros.TransformListener(self.tf_buffer) From 5512a75c732e406fb5257023c3e5a45f147a8d79 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 10 Nov 2022 14:47:01 +0900 Subject: [PATCH 319/433] [jsk_robot_startup] Support multi-client of mongo_record --- .../lifelog/common_logger.launch | 34 +++++++++++++++++-- 1 file changed, 31 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index b99511f06d..3b1ff3785e 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -1,4 +1,8 @@ + + + + @@ -36,8 +40,9 @@ + - + @@ -56,7 +61,7 @@ pkg="nodelet" type="nodelet" args="manager" machine="$(arg machine)" output="screen" respawn="$(arg respawn)" launch-prefix="$(arg launch-prefix)"/> - + @@ -135,6 +140,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) @@ -147,6 +154,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) @@ -161,6 +170,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) @@ -173,6 +184,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) @@ -187,6 +200,8 @@ respawn="$(arg respawn)" if="$(arg save_tf)"> + database: $(arg database) + collection: $(arg collection) update_rate: $(arg log_rate) @@ -208,6 +223,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg joint_states_topic) vital_check: $(arg vital_check) @@ -288,6 +305,8 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) update_rate: $(arg log_rate) map_frame: $(arg map_frame_id) robot_frame: $(arg base_frame_id) @@ -301,6 +320,8 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) map_frame: $(arg map_frame_id) robot_frame: $(arg base_frame_id) @@ -311,7 +332,12 @@ name="action_logger" pkg="jsk_robot_startup" type="action_logger.py" machine="$(arg machine)" - respawn="$(arg respawn)" /> + respawn="$(arg respawn)"> + + database: $(arg database) + collection: $(arg collection) + + + database: $(arg database) + collection: $(arg collection) subst_param: true topics: - /${param /robot/name}/app_list From 8929bfdde6ea82cc970e7f95553d9ee23a076138 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 10 Nov 2022 15:02:23 +0900 Subject: [PATCH 320/433] [jsk_robot_startup] Fix private namespae in lightweight_logger --- .../jsk_robot_startup/src/lightweight_logger_nodelet.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp index cf6929b476..7ee9ab569d 100644 --- a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp +++ b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp @@ -51,7 +51,7 @@ namespace jsk_robot_startup // settings for database if (ros::param::has("~database")) { - pnh_->param("~database", db_name_, "jsk_robot_lifelog"); + pnh_->param("database", db_name_, "jsk_robot_lifelog"); } else { @@ -59,7 +59,7 @@ namespace jsk_robot_startup } if (ros::param::has("~collection")) { - pnh_->param("~collection", col_name_, std::string()); + pnh_->param("collection", col_name_, std::string()); } else { From 47f6b3179692a08a83455d16c3f9bae1f60916fe Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 13:38:13 +0900 Subject: [PATCH 321/433] [jsk_robot_startup] Add database and collection param to missing node --- .../jsk_robot_startup/lifelog/common_logger.launch | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 3b1ff3785e..8dcdebda15 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -214,6 +214,8 @@ respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) periodic_rate: $(arg log_rate) @@ -238,6 +240,8 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) topics: - /server_name/smach/container_init - /server_name/smach/container_status @@ -251,6 +255,8 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) + collection: $(arg collection) topics: - /Tablet/voice From c8b75d76b0e8ce3bf273194051597a291271182a Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 14:40:34 +0900 Subject: [PATCH 322/433] [jsk_robot_startup] Fix to support null collection argument --- .../lifelog/common_logger.launch | 52 ++++++++++++++----- 1 file changed, 39 insertions(+), 13 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 8dcdebda15..7d15c029a4 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -1,7 +1,7 @@ - + @@ -141,11 +141,13 @@ database: $(arg database) - collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + database: $(arg database) - collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg rgb_ns)/$(arg rgb_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -171,11 +175,13 @@ database: $(arg database) - collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + database: $(arg database) - collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg camera_ns)/$(arg depth_ns)/$(arg depth_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -201,9 +209,11 @@ if="$(arg save_tf)"> database: $(arg database) - collection: $(arg collection) update_rate: $(arg log_rate) + + collection: $(arg collection) + @@ -215,9 +225,11 @@ database: $(arg database) - collection: $(arg collection) periodic_rate: $(arg log_rate) + + collection: $(arg collection) + database: $(arg database) - collection: $(arg collection) enable_monitor: $(arg enable_monitor) monitor_topic: /$(arg joint_states_topic) vital_check: $(arg vital_check) + + collection: $(arg collection) + @@ -241,12 +255,14 @@ respawn="$(arg respawn)"> database: $(arg database) - collection: $(arg collection) topics: - /server_name/smach/container_init - /server_name/smach/container_status - /server_name/smach/container_structure + + collection: $(arg collection) + database: $(arg database) - collection: $(arg collection) topics: - /Tablet/voice + + collection: $(arg collection) + @@ -312,11 +330,13 @@ respawn="$(arg respawn)"> database: $(arg database) - collection: $(arg collection) update_rate: $(arg log_rate) map_frame: $(arg map_frame_id) robot_frame: $(arg base_frame_id) + + collection: $(arg collection) + @@ -327,10 +347,12 @@ respawn="$(arg respawn)"> database: $(arg database) - collection: $(arg collection) map_frame: $(arg map_frame_id) robot_frame: $(arg base_frame_id) + + collection: $(arg collection) + @@ -341,6 +363,8 @@ respawn="$(arg respawn)"> database: $(arg database) + + collection: $(arg collection) @@ -353,11 +377,13 @@ respawn="$(arg respawn)"> database: $(arg database) - collection: $(arg collection) subst_param: true topics: - /${param /robot/name}/app_list + + collection: $(arg collection) + From d19290519ed33c4fa56a191907ef9af311fe8295 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 19 Oct 2022 15:01:16 +0900 Subject: [PATCH 323/433] [jsk_fetch_startup] Fix description report-light-on --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index c048537e38..c6155c7acf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -771,6 +771,8 @@ Args: (:report-light-on '(lambda (userdata) (report-light-on) + (set-alist 'description "" userdata) + (set-alist 'image "" userdata) t)) (:room-light-on '(lambda (userdata) From bc22050eda0257db8e87f7c33e4d5e2772290bd0 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 19 Oct 2022 15:02:11 +0900 Subject: [PATCH 324/433] [jsk_fetch_startup] Fix indent --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index c6155c7acf..a0c3547e63 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -744,7 +744,7 @@ Args: '((:init '(lambda (userdata) (fetch-init) - (undock) + (undock) (send *ri* :clear-costmap) (store-params) (inflation-loose) @@ -770,7 +770,7 @@ Args: light-on))) (:report-light-on '(lambda (userdata) - (report-light-on) + (report-light-on) (set-alist 'description "" userdata) (set-alist 'image "" userdata) t)) From df2b0490167e47e3ed864313d604a3390eb7a642 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 19 Oct 2022 15:20:55 +0900 Subject: [PATCH 325/433] [jsk_fetch_startup] remove dependency on switchbot in navigation-utils --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index a0c3547e63..41917c30c0 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -1,10 +1,11 @@ (load "package://jsk_robot_startup/lifelog/tweet_client.l") (load "package://jsk_fetch_startup/euslisp/notify-app.l") -(load "package://switchbot_ros/scripts/switchbot.l") (require :state-machine "package://roseus_smach/src/state-machine.l") (require :state-machine-ros "package://roseus_smach/src/state-machine-ros.l") (require :state-machine-utils "package://roseus_smach/src/state-machine-utils.l") (require :base64 "lib/llib/base64.l") +(if (ros::rospack-find "switchbot_ros") + (load "package://switchbot_ros/scripts/switchbot.l")) (ros::load-ros-manifest "fetch_auto_dock_msgs") (ros::load-ros-manifest "jsk_robot_startup") From 3bedeb9ffeaa44b8230c0fac27988be3a31150ed Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 19 Oct 2022 15:21:50 +0900 Subject: [PATCH 326/433] [jsk_fetch_startup] Move function specific to kitchen-demo from navigation-utils to go-to-kitchen.l --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 402 ++++++++++++++++++ .../euslisp/navigation-utils.l | 401 ----------------- 2 files changed, 402 insertions(+), 401 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index d610d09c00..e8ad1cb0b9 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -1,8 +1,410 @@ #!/usr/bin/env roseus (require :fetch-interface "package://fetcheus/fetch-interface.l") +(require :state-machine "package://roseus_smach/src/state-machine.l") +(require :state-machine-ros "package://roseus_smach/src/state-machine-ros.l") +(require :state-machine-utils "package://roseus_smach/src/state-machine-utils.l") +(require :base64 "lib/llib/base64.l") + (load "package://jsk_fetch_startup/euslisp/navigation-utils.l") +(ros::advertise "/photo_taken" sensor_msgs::Image 1) + +(defun image-cb (msg) + (setq *image* msg)) + +(defun go-to-kitchen (&key (tweet t) (n-dock-trial 1) (n-kitchen-trial 1) + (control-switchbot :api)) + ;; go to kitchen + (unless (boundp '*ri*) + (require :fetch-interface "package://fetcheus/fetch-interface.l") + (fetch-init)) + (report-start-go-to-kitchen) + ;; Check if the lights are on in the room + (let ((initial-light-on (get-light-on)) + (success-go-to-kitchen nil) + (success-go-to-trashcan nil) + (success-auto-dock nil) + (success-battery-charging nil)) + (store-params) + ;; turn on light + (if initial-light-on + (report-light-on) + (progn + (report-light-off) + (room-light-on :control-switchbot control-switchbot))) + ;; change the inflation_radius + (inflation-loose) + ;; go to kitchen sink + (setq success-go-to-kitchen (move-to-sink-front :n-trial n-kitchen-trial)) + ;; report result to go to kitchen + (if success-go-to-kitchen + (inspect-kitchen :tweet tweet) + (report-move-to-sink-front-failure)) + ;; go to kitchen trash can + (setq success-go-to-trashcan (move-to-trashcan-front :n-trial n-trashcan-trial)) + ;; report result to go to trash can + (if success-go-to-trashcan + (inspect-trashcan :tweet tweet) + (report-move-to-trashcan-front-failure)) + ;; go back from dock + (report-auto-dock) + (setq success-auto-dock (auto-dock :n-trial n-dock-trial :clear-costmap nil)) + ;; turn off light + (if (and success-auto-dock (not initial-light-on)) + (room-light-off :control-switchbot control-switchbot)) + ;; change the inflation_radius + (restore-params) + (send-kitchen-mail) + (setq success-battery-charging (progn (wait-until-is-charging) + (equal (get-battery-charging-state) :charging))) + (and success-go-to-kitchen success-auto-dock success-battery-charging))) + +(defun go-to-kitchen-state-machine () + (setq *sm* + (make-state-machine + '((:init -> :report-start-go-to-kitchen) + (:report-start-go-to-kitchen -> :get-light-on) + (:get-light-on -> :report-light-on) + (:get-light-on !-> :room-light-on) + (:report-light-on -> :move-to-dock-front) + (:room-light-on -> :move-to-dock-front) + + (:move-to-dock-front -> :inspect-dock-front) + (:move-to-dock-front !-> :report-move-to-dock-front-failure) + (:inspect-dock-front -> :move-to-tv-front) + (:report-move-to-dock-front-failure -> :move-to-tv-front) + + (:move-to-tv-front -> :inspect-tv-front) + (:move-to-tv-front !-> :report-move-to-tv-front-failure) + (:inspect-tv-front -> :move-to-tv-desk) + (:report-move-to-tv-front-failure -> :move-to-tv-desk) + + (:move-to-tv-desk -> :inspect-tv-desk) + (:move-to-tv-desk !-> :report-move-to-tv-desk-failure) + (:inspect-tv-desk -> :move-to-desk-back) + (:report-move-to-tv-desk-failure -> :move-to-desk-back) + + (:move-to-desk-back -> :inspect-desk-back) + (:move-to-desk-back !-> :report-move-to-desk-back-failure) + (:inspect-desk-back -> :move-to-desk-front) + (:report-move-to-desk-back-failure -> :move-to-desk-front) + + (:move-to-desk-front -> :inspect-desk-front) + (:move-to-desk-front !-> :report-move-to-desk-front-failure) + (:inspect-desk-front -> :move-to-kitchen-door-front) + (:report-move-to-desk-front-failure -> :move-to-kitchen-door-front) + + (:move-to-kitchen-door-front -> :inspect-kitchen-door-front) + (:move-to-kitchen-door-front !-> :report-move-to-kitchen-door-front-failure) + (:inspect-kitchen-door-front -> :move-to-sink-front) + (:report-move-to-kitchen-door-front-failure -> :move-to-sink-front) + + (:move-to-sink-front -> :inspect-kitchen) + (:move-to-sink-front !-> :report-move-to-sink-front-failure) + ;;(:inspect-kitchen -> :auto-dock) + (:report-move-to-sink-front-failure -> :auto-dock) + (:inspect-kitchen -> :move-to-trashcan-front) + (:move-to-trashcan-front -> :inspect-trashcan) + (:move-to-trashcan-front !-> :report-move-to-trashcan-front-failure) + (:inspect-trashcan -> :auto-dock) + (:report-move-to-trashcan-front-failure -> :auto-dock) + (:auto-dock -> :room-light-off) + (:auto-dock !-> :auto-dock-failure) + (:auto-dock-failure -> :room-light-off) + (:room-light-off -> :finish) + (:finish -> t) + (:finish !-> nil)) + '((:init + '(lambda (userdata) + (fetch-init) + (undock) + (send *ri* :clear-costmap) + (store-params) + (inflation-loose) + (clear-app-notification) + (ros::subscribe "/edgetpu_object_detector/output/image/compressed" + sensor_msgs::CompressedImage #'image-cb) + t)) + (:report-start-go-to-kitchen + '(lambda (userdata) + (report-start-go-to-kitchen) + (set-alist 'description "キッチンを見に行くよ" userdata) + (set-alist 'image "" userdata) + t)) + (:get-light-on + '(lambda (userdata) + (let ((light-on (get-light-on))) + (setf (cdr (assoc 'initial-light-on userdata)) light-on) + (ros::spin-once) + (if light-on + (set-alist 'description "電気がついていたよ" userdata) + (set-alist 'description "電気がついていなかったよ" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + light-on))) + (:report-light-on + '(lambda (userdata) + (report-light-on) + (set-alist 'description "" userdata) + (set-alist 'image "" userdata) + t)) + (:room-light-on + '(lambda (userdata) + (let ((control-switchbot (cdr (assoc 'control-switchbot userdata)))) + (report-light-off) + (room-light-on :control-switchbot control-switchbot) + (ros::spin-once) + (set-alist 'description "電気をつけたよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t))) + (:move-to-dock-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) + (success (move-to-dock-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ドックの前に移動したよ" userdata) + (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-dock-front + '(lambda (userdata) + (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドックの前の様子を見たよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-dock-front-failure + '(lambda (userdata) + (report-move-to-dock-front-failure) + (ros::spin-once) + (set-alist 'description "ドックの前に移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-tv-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) + (success (move-to-tv-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "テレビの前に移動したよ" userdata) + (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-tv-front + '(lambda (userdata) + (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "テレビの前の様子を見たよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-tv-front-failure + '(lambda (userdata) + (report-move-to-tv-front-failure) + (ros::spin-once) + (set-alist 'description "テレビの前に移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-tv-desk + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) + (success (move-to-tv-desk :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "机の前に移動したよ" userdata) + (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-tv-desk + '(lambda (userdata) + (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "机の様子を確認したよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-tv-desk-failure + '(lambda (userdata) + (report-move-to-tv-desk-failure) + (ros::spin-once) + (set-alist 'description "机の前に移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-desk-back + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) + (success (move-to-desk-back :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "部屋の後ろに移動したよ" userdata) + (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-desk-back + '(lambda (userdata) + (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の後ろを確認したよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-desk-back-failure + '(lambda (userdata) + (report-move-to-desk-back-failure) + (ros::spin-once) + (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-desk-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) + (success (move-to-desk-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "部屋の前に移動したよ" userdata) + (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-desk-front + '(lambda (userdata) + (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の前を確認したよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-desk-front-failure + '(lambda (userdata) + (report-move-to-desk-front-failure) + (ros::spin-once) + (set-alist 'description "部屋の前に移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-kitchen-door-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) + (success (move-to-kitchen-door-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ドアの前に移動したよ" userdata) + (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-kitchen-door-front + '(lambda (userdata) + (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-kitchen-door-front-failure + '(lambda (userdata) + (report-move-to-kitchen-door-front-failure) + (ros::spin-once) + (set-alist 'description "ドアの前に移動できなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-sink-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) + (success (move-to-sink-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "キッチンに移動したよ" userdata) + (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-kitchen + '(lambda (userdata) + (let* ((label-names (notify-recognition :location "kitchen")) + (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) + (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-sink-front-failure + '(lambda (userdata) + (report-move-to-sink-front-failure) + (ros::spin-once) + (set-alist 'description "キッチンに行けなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:move-to-trashcan-front + '(lambda (userdata) + (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) + (success (move-to-trashcan-front :n-trial n-trial))) + (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "ゴミ箱の前に移動したよ" userdata) + (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:inspect-trashcan + '(lambda (userdata) + (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:report-move-to-trashcan-front-failure + '(lambda (userdata) + (report-move-to-trashcan-front-failure) + (ros::spin-once) + (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:auto-dock + '(lambda (userdata) + (report-auto-dock) + (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) + (success (auto-dock :n-trial n-trial :clear-costmap nil))) + (setf (cdr (assoc 'success-auto-dock userdata)) success) + (ros::spin-once) + (if success + (set-alist 'description "帰ってきたよ" userdata) + (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + success))) + (:auto-dock-failure + '(lambda (userdata) + (report-auto-dock-failure) + (ros::spin-once) + (set-alist 'description "帰ってこられなかったよ" userdata) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + t)) + (:room-light-off + '(lambda (userdata) + (let ((success-auto-dock (cdr (assoc 'success-auto-dock userdata))) + (initial-light-on (cdr (assoc 'initial-light-on userdata))) + (control-switchbot (cdr (assoc 'control-switchbot userdata)))) + (if (and success-auto-dock (not initial-light-on)) + (progn + (room-light-off :control-switchbot control-switchbot) + (ros::spin-once) + (set-alist 'description "電気を消したよ" userdata) + (set-alist 'image "" userdata)))) + t)) + (:finish + '(lambda (userdata) + (let ((success-battery-charging + (progn (wait-until-is-charging) + (equal (get-battery-charging-state) :charging))) + (success-auto-dock (cdr (assoc 'success-auto-dock userdata))) + (success-go-to-kitchen + (cdr (assoc 'success-go-to-kitchen userdata)))) + (restore-params) + (ros::spin-once) + (set-alist 'description "キッチンデモを終えるよ" userdata) + (set-alist 'image "" userdata) + (and success-go-to-kitchen success-auto-dock success-battery-charging))))) + '(:init) + '(t nil)))) (defun main (&key (tweet t) (n-dock-trial 3) (n-kitchen-trial 3) (n-trashcan-trial 3) (n-dock-front-trial 3) (n-tv-front-trial 3) (n-tv-desk-trial 3) (n-desk-back-trial 3) (n-desk-front-trial 3) (n-kitchen-door-front-trial 3) (control-switchbot :api)) (when (not (boundp '*sm*)) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 41917c30c0..56baff7ec8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -1,9 +1,5 @@ (load "package://jsk_robot_startup/lifelog/tweet_client.l") (load "package://jsk_fetch_startup/euslisp/notify-app.l") -(require :state-machine "package://roseus_smach/src/state-machine.l") -(require :state-machine-ros "package://roseus_smach/src/state-machine-ros.l") -(require :state-machine-utils "package://roseus_smach/src/state-machine-utils.l") -(require :base64 "lib/llib/base64.l") (if (ros::rospack-find "switchbot_ros") (load "package://switchbot_ros/scripts/switchbot.l")) @@ -18,8 +14,6 @@ (defparameter *spots* nil) (defparameter *tfl* (instance ros::transform-listener :init)) -(ros::advertise "/photo_taken" sensor_msgs::Image 1) - (let ((robot-name (ros::get-param "/robot/name"))) (defparameter *dock-spot* (cond @@ -636,399 +630,4 @@ Args: (send *ri* :go-pos-unsafe 0 0 -80) ;; face the front against the trash can success-move-to-trashcan-front)) -(defun image-cb (msg) - (setq *image* msg)) -(defun go-to-kitchen (&key (tweet t) (n-dock-trial 1) (n-kitchen-trial 1) - (control-switchbot :api)) - ;; go to kitchen - (unless (boundp '*ri*) - (require :fetch-interface "package://fetcheus/fetch-interface.l") - (fetch-init)) - (report-start-go-to-kitchen) - ;; Check if the lights are on in the room - (let ((initial-light-on (get-light-on)) - (success-go-to-kitchen nil) - (success-go-to-trashcan nil) - (success-auto-dock nil) - (success-battery-charging nil)) - (store-params) - ;; turn on light - (if initial-light-on - (report-light-on) - (progn - (report-light-off) - (room-light-on :control-switchbot control-switchbot))) - ;; change the inflation_radius - (inflation-loose) - ;; go to kitchen sink - (setq success-go-to-kitchen (move-to-sink-front :n-trial n-kitchen-trial)) - ;; report result to go to kitchen - (if success-go-to-kitchen - (inspect-kitchen :tweet tweet) - (report-move-to-sink-front-failure)) - ;; go to kitchen trash can - (setq success-go-to-trashcan (move-to-trashcan-front :n-trial n-trashcan-trial)) - ;; report result to go to trash can - (if success-go-to-trashcan - (inspect-trashcan :tweet tweet) - (report-move-to-trashcan-front-failure)) - ;; go back from dock - (report-auto-dock) - (setq success-auto-dock (auto-dock :n-trial n-dock-trial :clear-costmap nil)) - ;; turn off light - (if (and success-auto-dock (not initial-light-on)) - (room-light-off :control-switchbot control-switchbot)) - ;; change the inflation_radius - (restore-params) - (send-kitchen-mail) - (setq success-battery-charging (progn (wait-until-is-charging) - (equal (get-battery-charging-state) :charging))) - (and success-go-to-kitchen success-auto-dock success-battery-charging))) - - -(defun go-to-kitchen-state-machine () - (setq *sm* - (make-state-machine - '((:init -> :report-start-go-to-kitchen) - (:report-start-go-to-kitchen -> :get-light-on) - (:get-light-on -> :report-light-on) - (:get-light-on !-> :room-light-on) - (:report-light-on -> :move-to-dock-front) - (:room-light-on -> :move-to-dock-front) - - (:move-to-dock-front -> :inspect-dock-front) - (:move-to-dock-front !-> :report-move-to-dock-front-failure) - (:inspect-dock-front -> :move-to-tv-front) - (:report-move-to-dock-front-failure -> :move-to-tv-front) - - (:move-to-tv-front -> :inspect-tv-front) - (:move-to-tv-front !-> :report-move-to-tv-front-failure) - (:inspect-tv-front -> :move-to-tv-desk) - (:report-move-to-tv-front-failure -> :move-to-tv-desk) - - (:move-to-tv-desk -> :inspect-tv-desk) - (:move-to-tv-desk !-> :report-move-to-tv-desk-failure) - (:inspect-tv-desk -> :move-to-desk-back) - (:report-move-to-tv-desk-failure -> :move-to-desk-back) - - (:move-to-desk-back -> :inspect-desk-back) - (:move-to-desk-back !-> :report-move-to-desk-back-failure) - (:inspect-desk-back -> :move-to-desk-front) - (:report-move-to-desk-back-failure -> :move-to-desk-front) - - (:move-to-desk-front -> :inspect-desk-front) - (:move-to-desk-front !-> :report-move-to-desk-front-failure) - (:inspect-desk-front -> :move-to-kitchen-door-front) - (:report-move-to-desk-front-failure -> :move-to-kitchen-door-front) - - (:move-to-kitchen-door-front -> :inspect-kitchen-door-front) - (:move-to-kitchen-door-front !-> :report-move-to-kitchen-door-front-failure) - (:inspect-kitchen-door-front -> :move-to-sink-front) - (:report-move-to-kitchen-door-front-failure -> :move-to-sink-front) - - (:move-to-sink-front -> :inspect-kitchen) - (:move-to-sink-front !-> :report-move-to-sink-front-failure) - ;;(:inspect-kitchen -> :auto-dock) - (:report-move-to-sink-front-failure -> :auto-dock) - (:inspect-kitchen -> :move-to-trashcan-front) - (:move-to-trashcan-front -> :inspect-trashcan) - (:move-to-trashcan-front !-> :report-move-to-trashcan-front-failure) - (:inspect-trashcan -> :auto-dock) - (:report-move-to-trashcan-front-failure -> :auto-dock) - (:auto-dock -> :room-light-off) - (:auto-dock !-> :auto-dock-failure) - (:auto-dock-failure -> :room-light-off) - (:room-light-off -> :finish) - (:finish -> t) - (:finish !-> nil)) - '((:init - '(lambda (userdata) - (fetch-init) - (undock) - (send *ri* :clear-costmap) - (store-params) - (inflation-loose) - (clear-app-notification) - (ros::subscribe "/edgetpu_object_detector/output/image/compressed" - sensor_msgs::CompressedImage #'image-cb) - t)) - (:report-start-go-to-kitchen - '(lambda (userdata) - (report-start-go-to-kitchen) - (set-alist 'description "キッチンを見に行くよ" userdata) - (set-alist 'image "" userdata) - t)) - (:get-light-on - '(lambda (userdata) - (let ((light-on (get-light-on))) - (setf (cdr (assoc 'initial-light-on userdata)) light-on) - (ros::spin-once) - (if light-on - (set-alist 'description "電気がついていたよ" userdata) - (set-alist 'description "電気がついていなかったよ" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - light-on))) - (:report-light-on - '(lambda (userdata) - (report-light-on) - (set-alist 'description "" userdata) - (set-alist 'image "" userdata) - t)) - (:room-light-on - '(lambda (userdata) - (let ((control-switchbot (cdr (assoc 'control-switchbot userdata)))) - (report-light-off) - (room-light-on :control-switchbot control-switchbot) - (ros::spin-once) - (set-alist 'description "電気をつけたよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t))) - (:move-to-dock-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) - (success (move-to-dock-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "ドックの前に移動したよ" userdata) - (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-dock-front - '(lambda (userdata) - (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "ドックの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-dock-front-failure - '(lambda (userdata) - (report-move-to-dock-front-failure) - (ros::spin-once) - (set-alist 'description "ドックの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-tv-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) - (success (move-to-tv-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "テレビの前に移動したよ" userdata) - (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-tv-front - '(lambda (userdata) - (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "テレビの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-tv-front-failure - '(lambda (userdata) - (report-move-to-tv-front-failure) - (ros::spin-once) - (set-alist 'description "テレビの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-tv-desk - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) - (success (move-to-tv-desk :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "机の前に移動したよ" userdata) - (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-tv-desk - '(lambda (userdata) - (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "机の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-tv-desk-failure - '(lambda (userdata) - (report-move-to-tv-desk-failure) - (ros::spin-once) - (set-alist 'description "机の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-desk-back - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) - (success (move-to-desk-back :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "部屋の後ろに移動したよ" userdata) - (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-desk-back - '(lambda (userdata) - (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "部屋の後ろを確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-desk-back-failure - '(lambda (userdata) - (report-move-to-desk-back-failure) - (ros::spin-once) - (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-desk-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) - (success (move-to-desk-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "部屋の前に移動したよ" userdata) - (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-desk-front - '(lambda (userdata) - (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "部屋の前を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-desk-front-failure - '(lambda (userdata) - (report-move-to-desk-front-failure) - (ros::spin-once) - (set-alist 'description "部屋の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-kitchen-door-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) - (success (move-to-kitchen-door-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "ドアの前に移動したよ" userdata) - (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-kitchen-door-front - '(lambda (userdata) - (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-kitchen-door-front-failure - '(lambda (userdata) - (report-move-to-kitchen-door-front-failure) - (ros::spin-once) - (set-alist 'description "ドアの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-sink-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) - (success (move-to-sink-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "キッチンに移動したよ" userdata) - (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-kitchen - '(lambda (userdata) - (let* ((label-names (notify-recognition :location "kitchen")) - (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) - (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-sink-front-failure - '(lambda (userdata) - (report-move-to-sink-front-failure) - (ros::spin-once) - (set-alist 'description "キッチンに行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:move-to-trashcan-front - '(lambda (userdata) - (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) - (success (move-to-trashcan-front :n-trial n-trial))) - (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "ゴミ箱の前に移動したよ" userdata) - (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:inspect-trashcan - '(lambda (userdata) - (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:report-move-to-trashcan-front-failure - '(lambda (userdata) - (report-move-to-trashcan-front-failure) - (ros::spin-once) - (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:auto-dock - '(lambda (userdata) - (report-auto-dock) - (let* ((n-trial (cdr (assoc 'n-dock-trial userdata))) - (success (auto-dock :n-trial n-trial :clear-costmap nil))) - (setf (cdr (assoc 'success-auto-dock userdata)) success) - (ros::spin-once) - (if success - (set-alist 'description "帰ってきたよ" userdata) - (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) - (:auto-dock-failure - '(lambda (userdata) - (report-auto-dock-failure) - (ros::spin-once) - (set-alist 'description "帰ってこられなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) - (:room-light-off - '(lambda (userdata) - (let ((success-auto-dock (cdr (assoc 'success-auto-dock userdata))) - (initial-light-on (cdr (assoc 'initial-light-on userdata))) - (control-switchbot (cdr (assoc 'control-switchbot userdata)))) - (if (and success-auto-dock (not initial-light-on)) - (progn - (room-light-off :control-switchbot control-switchbot) - (ros::spin-once) - (set-alist 'description "電気を消したよ" userdata) - (set-alist 'image "" userdata)))) - t)) - (:finish - '(lambda (userdata) - (let ((success-battery-charging - (progn (wait-until-is-charging) - (equal (get-battery-charging-state) :charging))) - (success-auto-dock (cdr (assoc 'success-auto-dock userdata))) - (success-go-to-kitchen - (cdr (assoc 'success-go-to-kitchen userdata)))) - (restore-params) - (ros::spin-once) - (set-alist 'description "キッチンデモを終えるよ" userdata) - (set-alist 'image "" userdata) - (and success-go-to-kitchen success-auto-dock success-battery-charging))))) - '(:init) - '(t nil)))) From 0bc1b1098f78adf848a5afee7ad8124aae28b5d1 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 15 Nov 2022 11:52:23 +0900 Subject: [PATCH 327/433] [jsk_fetch_startup] Send image when objects recognize --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 229 +++++++++++------- 1 file changed, 146 insertions(+), 83 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index e8ad1cb0b9..c662fa065d 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -150,173 +150,232 @@ t)) (:room-light-on '(lambda (userdata) - (let ((control-switchbot (cdr (assoc 'control-switchbot userdata)))) + (let ((control-switchbot (cdr (assoc 'control-switchbot userdata))) + (label-names (notify-recognition :location "on the way to kitchen"))) (report-light-off) (room-light-on :control-switchbot control-switchbot) (ros::spin-once) (set-alist 'description "電気をつけたよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-dock-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-dock-front-trial userdata))) - (success (move-to-dock-front :n-trial n-trial))) + (success (move-to-dock-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-dock-front userdata)) success) (ros::spin-once) (if success (set-alist 'description "ドックの前に移動したよ" userdata) (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-dock-front '(lambda (userdata) - (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "ドックの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドックの前の様子を見たよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) (:report-move-to-dock-front-failure '(lambda (userdata) - (report-move-to-dock-front-failure) - (ros::spin-once) - (set-alist 'description "ドックの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-dock-front-failure) + (ros::spin-once) + (set-alist 'description "ドックの前に移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) (:move-to-tv-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) - (success (move-to-tv-front :n-trial n-trial))) + (success (move-to-tv-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) (ros::spin-once) (if success (set-alist 'description "テレビの前に移動したよ" userdata) (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-tv-front '(lambda (userdata) - (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "テレビの前の様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "テレビの前の様子を見たよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:report-move-to-tv-front-failure '(lambda (userdata) - (report-move-to-tv-front-failure) - (ros::spin-once) - (set-alist 'description "テレビの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-tv-front-failure) + (ros::spin-once) + (set-alist 'description "テレビの前に移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:move-to-tv-desk '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-tv-desk-trial userdata))) - (success (move-to-tv-desk :n-trial n-trial))) + (success (move-to-tv-desk :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) (ros::spin-once) (if success (set-alist 'description "机の前に移動したよ" userdata) (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-tv-desk '(lambda (userdata) - (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "机の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "机の様子を確認したよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:report-move-to-tv-desk-failure '(lambda (userdata) - (report-move-to-tv-desk-failure) - (ros::spin-once) - (set-alist 'description "机の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* (label-names (notify-recognition :location "on the way to kitchen")) + (report-move-to-tv-desk-failure) + (ros::spin-once) + (set-alist 'description "机の前に移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) (:move-to-desk-back '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) - (success (move-to-desk-back :n-trial n-trial))) + (success (move-to-desk-back :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-desk-back userdata)) success) (ros::spin-once) (if success (set-alist 'description "部屋の後ろに移動したよ" userdata) (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-desk-back '(lambda (userdata) - (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "部屋の後ろを確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の後ろを確認したよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:report-move-to-desk-back-failure '(lambda (userdata) - (report-move-to-desk-back-failure) - (ros::spin-once) - (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-desk-back-failure) + (ros::spin-once) + (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t)) (:move-to-desk-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) - (success (move-to-desk-front :n-trial n-trial))) + (success (move-to-desk-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to desk-front"))) (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) (ros::spin-once) (if success (set-alist 'description "部屋の前に移動したよ" userdata) (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-desk-front '(lambda (userdata) - (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "部屋の前を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "部屋の前を確認したよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:report-move-to-desk-front-failure '(lambda (userdata) - (report-move-to-desk-front-failure) - (ros::spin-once) - (set-alist 'description "部屋の前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to kitchen"))) + (report-move-to-desk-front-failure) + (ros::spin-once) + (set-alist 'description "部屋の前に移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:move-to-kitchen-door-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) - (success (move-to-kitchen-door-front :n-trial n-trial))) + (success (move-to-kitchen-door-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) (ros::spin-once) (if success (set-alist 'description "ドアの前に移動したよ" userdata) (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - success))) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + success))) (:inspect-kitchen-door-front '(lambda (userdata) - (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) - (ros::spin-once) - (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "kitchen-door-front"))) + (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) + (ros::spin-once) + (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) + t))) (:report-move-to-kitchen-door-front-failure '(lambda (userdata) - (report-move-to-kitchen-door-front-failure) - (ros::spin-once) - (set-alist 'description "ドアの前に移動できなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* (label-names (notify-recognition :location "on the way to kitchen")) + (report-move-to-kitchen-door-front-failure) + (ros::spin-once) + (set-alist 'description "ドアの前に移動できなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata)) + t))) (:move-to-sink-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) - (success (move-to-sink-front :n-trial n-trial))) + (success (move-to-sink-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-kitchen userdata)) success) (ros::spin-once) (if success (set-alist 'description "キッチンに移動したよ" userdata) (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-kitchen '(lambda (userdata) @@ -325,15 +384,19 @@ (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t)) (:report-move-to-sink-front-failure '(lambda (userdata) - (report-move-to-sink-front-failure) - (ros::spin-once) - (set-alist 'description "キッチンに行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - t)) + (let* ((label-names (notify-recognition :location "on the way to sink-front"))) + (report-move-to-sink-front-failure) + (ros::spin-once) + (set-alist 'description "キッチンに行けなかったよ" userdata) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata)) + t))) (:move-to-trashcan-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) From c9300323268fbe09ab419758c72450f6db4275e0 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 15 Nov 2022 14:04:06 +0900 Subject: [PATCH 328/433] [jsk_fetch_startup] Fix parenthesis correspondence --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 21 +++++++++++-------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index c662fa065d..9b4786b89b 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -183,7 +183,7 @@ (if label-names (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) - t)) + t))) (:report-move-to-dock-front-failure '(lambda (userdata) (let* ((label-names (notify-recognition :location "on the way to kitchen"))) @@ -193,7 +193,7 @@ (if label-names (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) - t)) + t))) (:move-to-tv-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) @@ -261,7 +261,7 @@ (if label-names (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) - t)) + t))) (:move-to-desk-back '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-desk-back-trial userdata))) @@ -295,7 +295,7 @@ (if label-names (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) - t)) + t))) (:move-to-desk-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) @@ -383,10 +383,10 @@ (notify-text (if label-names (format nil "~Aがあったよ" label-names) ""))) (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) - (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata)) + (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata) (if label-names (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata))) t)) (:report-move-to-sink-front-failure '(lambda (userdata) @@ -400,13 +400,16 @@ (:move-to-trashcan-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-trashcan-trial userdata))) - (success (move-to-trashcan-front :n-trial n-trial))) + (success (move-to-trashcan-front :n-trial n-trial)) + (label-names (notify-recognition :location "on the way to kitchen"))) (setf (cdr (assoc 'success-go-to-trashcan userdata)) success) (ros::spin-once) (if success (set-alist 'description "ゴミ箱の前に移動したよ" userdata) - (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) + (if label-names + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-trashcan '(lambda (userdata) From 30ab9f09a86609a905056d0b832468218328d60f Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Tue, 15 Nov 2022 14:08:54 +0900 Subject: [PATCH 329/433] [jsk_fetch_startup] Remove image when robot moved --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 49 ++++++------------- 1 file changed, 15 insertions(+), 34 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index 9b4786b89b..9698c2fe59 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -197,16 +197,13 @@ (:move-to-tv-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-tv-front-trial userdata))) - (success (move-to-tv-front :n-trial n-trial)) - (label-names (notify-recognition :location "on the way to kitchen"))) + (success (move-to-tv-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-tv-front userdata)) success) (ros::spin-once) (if success (set-alist 'description "テレビの前に移動したよ" userdata) (set-alist 'description "テレビの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-tv-front '(lambda (userdata) @@ -238,9 +235,7 @@ (if success (set-alist 'description "机の前に移動したよ" userdata) (set-alist 'description "机の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-tv-desk '(lambda (userdata) @@ -272,9 +267,7 @@ (if success (set-alist 'description "部屋の後ろに移動したよ" userdata) (set-alist 'description "部屋の後ろに移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-desk-back '(lambda (userdata) @@ -299,16 +292,13 @@ (:move-to-desk-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-desk-front-trial userdata))) - (success (move-to-desk-front :n-trial n-trial)) - (label-names (notify-recognition :location "on the way to desk-front"))) + (success (move-to-desk-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-desk-front userdata)) success) (ros::spin-once) (if success (set-alist 'description "部屋の前に移動したよ" userdata) (set-alist 'description "部屋の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-desk-front '(lambda (userdata) @@ -333,16 +323,13 @@ (:move-to-kitchen-door-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-kitchen-door-front-trial userdata))) - (success (move-to-kitchen-door-front :n-trial n-trial)) - (label-names (notify-recognition :location "on the way to kitchen"))) + (success (move-to-kitchen-door-front :n-trial n-trial))) (setf (cdr (assoc 'success-go-to-tv-desk userdata)) success) (ros::spin-once) (if success (set-alist 'description "ドアの前に移動したよ" userdata) (set-alist 'description "ドアの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-kitchen-door-front '(lambda (userdata) @@ -356,13 +343,11 @@ t))) (:report-move-to-kitchen-door-front-failure '(lambda (userdata) - (let* (label-names (notify-recognition :location "on the way to kitchen")) - (report-move-to-kitchen-door-front-failure) - (ros::spin-once) - (set-alist 'description "ドアの前に移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata)) - t))) + (report-move-to-kitchen-door-front-failure) + (ros::spin-once) + (set-alist 'description "ドアの前に移動できなかったよ" userdata) + (set-alist 'image "" userdata) + t)) (:move-to-sink-front '(lambda (userdata) (let* ((n-trial (cdr (assoc 'n-kitchen-trial userdata))) @@ -373,9 +358,7 @@ (if success (set-alist 'description "キッチンに移動したよ" userdata) (set-alist 'description "キッチンに移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-kitchen '(lambda (userdata) @@ -407,9 +390,7 @@ (if success (set-alist 'description "ゴミ箱の前に移動したよ" userdata) (set-alist 'description "ゴミ箱の前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (set-alist 'image "" userdata) success))) (:inspect-trashcan '(lambda (userdata) From 2717c2b076a1e4d3a4facb67510439fe02376d0c Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 14 Oct 2022 11:12:55 +0900 Subject: [PATCH 330/433] [jsk_fetch_startup] add rightsidehook to side_hook.urdf.xacro --- .../robots/side_hook.urdf.xacro | 48 ++++++++++++++++--- 1 file changed, 42 insertions(+), 6 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro index c8206ecdc5..61696e7f55 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro @@ -1,6 +1,6 @@ - + @@ -25,14 +25,50 @@ - + - - + + - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 638407207a4a12df3b363507328544fcd357a1f9 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Fri, 14 Oct 2022 13:48:16 +0900 Subject: [PATCH 331/433] [jsk_fetch_startup] fix torso-side_hook joint names --- jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro index 61696e7f55..f373bc6110 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro +++ b/jsk_fetch_robot/jsk_fetch_startup/robots/side_hook.urdf.xacro @@ -22,7 +22,7 @@ - + @@ -58,7 +58,7 @@ - + From 01db7d1c54a567ca9c79e7458c0f5653c1c7e191 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 11 Nov 2022 22:05:17 +0900 Subject: [PATCH 332/433] ad volume key in tweet-string func --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index a4308622ec..b4079f68fa 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -7,7 +7,7 @@ (load "package://pr2eus/speak.l") (defun tweet-string (twit-str &key (warning-time) (with-image) (image-wait 30) (speak t) - (tweet-topic-name "/tweet")) + (tweet-topic-name "/tweet") (volume 1.0)) (if (null (ros::get-num-subscribers tweet-topic-name)) (ros::advertise tweet-topic-name std_msgs::String 1)) (let (prev-image-topic img) @@ -28,7 +28,8 @@ (8 "はち") (9 "きゅう") (10 "じゅう") - (t "じゅういじょう"))))) + (t "じゅういじょう"))) + :volume volume)) (unix::sleep warning-time)) (cond @@ -64,5 +65,5 @@ (ros::service-call "/tweet_image_mux/select" (instance topic_tools::muxselectrequest :init :topic prev-image-topic))) (t (ros::publish tweet-topic-name (instance std_msgs::String :init :data twit-str)))) - (when speak (speak-jp "ついーとしました" :wait t)))) + (when speak (speak-jp "ついーとしました" :wait t :volume volume)))) From 5a6db1cd5fc1da47ecfc65084b560d08a7065201 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 11 Nov 2022 23:04:58 +0900 Subject: [PATCH 333/433] control volume by dynamic reconfigure --- .../lifelog/tweet_client_tablet.l | 15 ++++++++++++++- .../lifelog/tweet_client_uptime.l | 16 +++++++++++++++- .../lifelog/tweet_client_warning.l | 14 +++++++++++++- .../lifelog/tweet_client_worktime.l | 16 +++++++++++++++- 4 files changed, 57 insertions(+), 4 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l index ed1be21a4e..cf1464575f 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l @@ -3,13 +3,26 @@ (ros::roseus "twitter_client_tablet") (ros::roseus-add-msgs "roseus") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (ros::ros-warn "Volume changed to: ~A" *volume*) + cfg))) + (defun twit-cb (msg) (let ((twit-str (send msg :data))) (tweet-string twit-str :warning-time nil - :with-image "/tablet/marked/image_rect_color"))) + :with-image "/tablet/marked/image_rect_color" + :volume *volume*))) (ros::advertise "/tweet" std_msgs::String 1) (ros::subscribe "/pr2twit_from_tablet" roseus::StringStamped #'twit-cb) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l index d49af0e6e4..3df9d85626 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l @@ -2,6 +2,7 @@ (ros::roseus "twitter_client_uptime") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") (setq *src-lines* nil) @@ -37,6 +38,17 @@ (t (setq *waking-target-second* *waking-tweet-second*))) +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (ros::ros-warn "Volume changed to: ~A" *volume*) + cfg))) + (ros::advertise "/tweet" std_msgs::String 1) (ros::rate 0.1) (do-until-key @@ -81,8 +93,10 @@ (incf pos (length s)) (if (< pos (- ln 2)) (setf (elt dt pos) 10)) (incf pos)) - (tweet-string dt :warning-time 1 :with-image t) + (tweet-string dt :warning-time 1 :with-image t + :volume *volume*) )) )))) + (ros::spin-once) (ros::sleep) ) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l index 7ec7e3dceb..d40a055d4a 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l @@ -2,9 +2,21 @@ (ros::roseus "twitter_client_warning") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") (ros::load-ros-manifest "diagnostic_msgs") +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (ros::ros-warn "Volume changed to: ~A" *volume*) + cfg))) + (defun diagnostics-cb (msg) (let ((diagnostics (make-hash-table :test #'equal)) (tm (ros::time-now)) @@ -34,7 +46,7 @@ (setq id (random (length status))) (when (= (mod (round (send tm :sec)) 1000) 0) (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) - :warning-time 1 :with-image t) + :warning-time 1 :with-image t :volume *volume*) )) ;; when )) ;; let diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l index dac8769842..5b18959e52 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l @@ -2,6 +2,7 @@ (ros::roseus "twitter_client_worktime") +(load "package://roseus/euslisp/dynamic-reconfigure-server.l") (load "package://jsk_robot_startup/lifelog/tweet_client.l") (defvar *robot-name* "robot") @@ -34,6 +35,17 @@ (t (setq *waking-target-second* *waking-tweet-second*))) +(setq *volume* (ros::get-param "~volume" 1.0)) +(setq *reconfigure-server* + (def-dynamic-reconfigure-server + ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + ;; use lamda-closure to avoid memory error + '(lambda-closure nil 0 0 (cfg level) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (ros::ros-warn "Volume changed to: ~A" *volume*) + cfg))) + (ros::advertise "/tweet" std_msgs::String 1) (ros::rate 0.1) (do-until-key @@ -75,8 +87,10 @@ postsubstr ", Got some rest?"))) (tweet-string (format nil "~A~A~A" presubstr mainstr postsubstr) - :warning-time 1 :with-image t) + :warning-time 1 :with-image t + :volume *volume*) )) + (ros::spin-once) (ros::sleep) ) From 24fca8ede186458276f41b947fee63f44fc7042e Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 18 Nov 2022 16:42:46 +0900 Subject: [PATCH 334/433] add enable and speak-enable dynamic reconfigure --- .../lifelog/tweet_client_tablet.l | 32 +++-- .../lifelog/tweet_client_uptime.l | 110 ++++++++++-------- .../lifelog/tweet_client_warning.l | 82 +++++++------ .../lifelog/tweet_client_worktime.l | 104 ++++++++++------- 4 files changed, 195 insertions(+), 133 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l index cf1464575f..aa168feb11 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_tablet.l @@ -7,22 +7,38 @@ (load "package://jsk_robot_startup/lifelog/tweet_client.l") (setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) (setq *reconfigure-server* (def-dynamic-reconfigure-server ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) - (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) ;; use lamda-closure to avoid memory error '(lambda-closure nil 0 0 (cfg level) - (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) - (ros::ros-warn "Volume changed to: ~A" *volume*) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) cfg))) (defun twit-cb (msg) - (let ((twit-str (send msg :data))) - (tweet-string twit-str - :warning-time nil - :with-image "/tablet/marked/image_rect_color" - :volume *volume*))) + (if *enable* + (let ((twit-str (send msg :data))) + (tweet-string twit-str + :warning-time nil + :with-image "/tablet/marked/image_rect_color" + :speak *speak-enable* + :volume *volume*)))) (ros::advertise "/tweet" std_msgs::String 1) (ros::subscribe "/pr2twit_from_tablet" roseus::StringStamped #'twit-cb) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l index 3df9d85626..1dc3caed3c 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l @@ -39,64 +39,80 @@ (setq *waking-target-second* *waking-tweet-second*))) (setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) (setq *reconfigure-server* (def-dynamic-reconfigure-server ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) - (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) ;; use lamda-closure to avoid memory error '(lambda-closure nil 0 0 (cfg level) - (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) - (ros::ros-warn "Volume changed to: ~A" *volume*) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) cfg))) (ros::advertise "/tweet" std_msgs::String 1) (ros::rate 0.1) (do-until-key - (setq *user-name* (ros::get-param "/active_user/launch_user_name") - *elapsed-time* (ros::get-param "/active_user/elapsed_time")) - ;; tweet depend on up time - (let ((st (ros::get-param "/active_user/start_time"))) - (when st - (let ((waking-time (- (send (ros::time-now) :to-sec) st))) - (ros::ros-debug "~A waking ~A sec (~A)" *robot-name* waking-time *waking-target-second*) - (when (> waking-time *waking-target-second*) - (incf *waking-target-second* *waking-tweet-second*) - ;; tweet source of robot-interface - (unless *src-lines* - (let* ((dirname (ros::rospack-find "pr2eus")) - (fname (format nil "~A/robot-interface.l" dirname)) - str) - (with-open-file (f fname) - (while (setq str (read-line f nil nil)) - (push str *src-lines*))) - (setq *src-lines* (nreverse *src-lines*)) - )) + (if *enable* + (progn + (setq *user-name* (ros::get-param "/active_user/launch_user_name") + *elapsed-time* (ros::get-param "/active_user/elapsed_time")) + ;; tweet depend on up time + (let ((st (ros::get-param "/active_user/start_time"))) + (when st + (let ((waking-time (- (send (ros::time-now) :to-sec) st))) + (ros::ros-debug "~A waking ~A sec (~A)" *robot-name* waking-time *waking-target-second*) + (when (> waking-time *waking-target-second*) + (incf *waking-target-second* *waking-tweet-second*) + ;; tweet source of robot-interface + (unless *src-lines* + (let* ((dirname (ros::rospack-find "pr2eus")) + (fname (format nil "~A/robot-interface.l" dirname)) + str) + (with-open-file (f fname) + (while (setq str (read-line f nil nil)) + (push str *src-lines*))) + (setq *src-lines* (nreverse *src-lines*)) + )) - (let* ((len (length *src-lines*)) - (start-n (floor (random (float len) *random-state*))) - (spos 0) (str-len 0) lines) - (push (format nil "I am running ~A min." (round (/ waking-time 60.0))) - lines) - (incf str-len (length (car lines))) - (while (< (+ start-n spos) len) - (let ((str (elt *src-lines* (+ start-n spos)))) - (incf str-len (length str)) - (if (> str-len 140) (return)) - (push str lines)) - (incf spos)) - (let* ((ln (apply #'+ (length lines) - (mapcar #'(lambda (x) (length x)) lines))) - (dt (make-string (1- ln))) - (pos 0)) - (dolist (s (nreverse lines)) - (replace dt s :start1 pos) - (incf pos (length s)) - (if (< pos (- ln 2)) (setf (elt dt pos) 10)) - (incf pos)) - (tweet-string dt :warning-time 1 :with-image t - :volume *volume*) - )) - )))) + (let* ((len (length *src-lines*)) + (start-n (floor (random (float len) *random-state*))) + (spos 0) (str-len 0) lines) + (push (format nil "I am running ~A min." (round (/ waking-time 60.0))) + lines) + (incf str-len (length (car lines))) + (while (< (+ start-n spos) len) + (let ((str (elt *src-lines* (+ start-n spos)))) + (incf str-len (length str)) + (if (> str-len 140) (return)) + (push str lines)) + (incf spos)) + (let* ((ln (apply #'+ (length lines) + (mapcar #'(lambda (x) (length x)) lines))) + (dt (make-string (1- ln))) + (pos 0)) + (dolist (s (nreverse lines)) + (replace dt s :start1 pos) + (incf pos (length s)) + (if (< pos (- ln 2)) (setf (elt dt pos) 10)) + (incf pos)) + (tweet-string dt :warning-time 1 :with-image t + :speak *speak-enable* + :volume *volume*) + )))))))) (ros::spin-once) (ros::sleep) ) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l index d40a055d4a..7fa754e89a 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l @@ -7,48 +7,62 @@ (ros::load-ros-manifest "diagnostic_msgs") (setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) (setq *reconfigure-server* (def-dynamic-reconfigure-server ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) - (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) ;; use lamda-closure to avoid memory error '(lambda-closure nil 0 0 (cfg level) - (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) - (ros::ros-warn "Volume changed to: ~A" *volume*) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) cfg))) (defun diagnostics-cb (msg) - (let ((diagnostics (make-hash-table :test #'equal)) - (tm (ros::time-now)) - status id) - (ros::ros-debug (format nil "~0,3f diagnostics_msgs~%" (send tm :to-sec))) - (dolist (status (send msg :status)) - ;; diagnostic_msgs::DiagnosticStatus::*WARN* - (when (>= (send status :level) diagnostic_msgs::DiagnosticStatus::*WARN*) ;; diagnostic_msgs::DiagnosticStatus::*ERROR*) - (cond ((substringp "/Motors" (send status :name)) - t) ;; skip motors - ((substringp "/Other/Accelerometer" (send status :name)) t) - ((substringp "/Other/Pressure" (send status :name)) t) - ((and (string= "/Computers/Network/Wifi Status (ddwrt)" (send status :name)) - (string= "Updates Stale" (send status :message))) t) - ((and (string= "/Computers/Network" (send status :name)) - (string= "Error" (send status :message))) t) - ((substringp "/Peripherals/PS3 Controller" (send status :name)) t) ;; fetch joystick warning - ((position #\/ (send status :name) :count 2) ;; check depth of name - (setq key (subseq (send status :name) 0 (position #\/ (send status :name) :count 2))) - (when (> (length (send status :name)) (length (gethash key diagnostics))) - (setf (gethash key diagnostics) (cons (send status :name) (send status :message))) - ) ;; when - )) - )) ;; when / dolist - (maphash #'(lambda (k v) (ros::ros-debug (format nil "Warnings ~A ~A~%" (length status) v)) (push v status)) diagnostics) - (when status - (setq id (random (length status))) - (when (= (mod (round (send tm :sec)) 1000) 0) - (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) - :warning-time 1 :with-image t :volume *volume*) - )) ;; when - )) ;; let + (if *enable* + (let ((diagnostics (make-hash-table :test #'equal)) + (tm (ros::time-now)) + status id) + (ros::ros-debug (format nil "~0,3f diagnostics_msgs~%" (send tm :to-sec))) + (dolist (status (send msg :status)) + ;; diagnostic_msgs::DiagnosticStatus::*WARN* + (when (>= (send status :level) diagnostic_msgs::DiagnosticStatus::*WARN*) ;; diagnostic_msgs::DiagnosticStatus::*ERROR*) + (cond ((substringp "/Motors" (send status :name)) + t) ;; skip motors + ((substringp "/Other/Accelerometer" (send status :name)) t) + ((substringp "/Other/Pressure" (send status :name)) t) + ((and (string= "/Computers/Network/Wifi Status (ddwrt)" (send status :name)) + (string= "Updates Stale" (send status :message))) t) + ((and (string= "/Computers/Network" (send status :name)) + (string= "Error" (send status :message))) t) + ((substringp "/Peripherals/PS3 Controller" (send status :name)) t) ;; fetch joystick warning + ((position #\/ (send status :name) :count 2) ;; check depth of name + (setq key (subseq (send status :name) 0 (position #\/ (send status :name) :count 2))) + (when (> (length (send status :name)) (length (gethash key diagnostics))) + (setf (gethash key diagnostics) (cons (send status :name) (send status :message))) + ) ;; when + )) + )) ;; when / dolist + (maphash #'(lambda (k v) (ros::ros-debug (format nil "Warnings ~A ~A~%" (length status) v)) (push v status)) diagnostics) + (when status + (setq id (random (length status))) + (when (= (mod (round (send tm :sec)) 1000) 0) + (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) + :warning-time 1 :with-image t :volume *volume* :speak *speak*))) + ))) (ros::advertise "/tweet" std_msgs::String 1) (ros::subscribe "/diagnostics_agg" diagnostic_msgs::DiagnosticArray #'diagnostics-cb) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l index 5b18959e52..52baa59aaf 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_worktime.l @@ -36,61 +36,77 @@ (setq *waking-target-second* *waking-tweet-second*))) (setq *volume* (ros::get-param "~volume" 1.0)) +(setq *speak-enable* (ros::get-param "~speak_enable" t)) +(setq *enable* (ros::get-param "~enable" t)) (setq *reconfigure-server* (def-dynamic-reconfigure-server ;;; ((name type level description (default) (min) (max) (edit_method)) ... ) - (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0)) + (("volume" double_t 0 "tweet speak volume" 1.0 0.0 1.0) + ("speak_enable" bool_t 0 "tweet speak enable" t) + ("enable" bool_t 0 "tweet enable" t)) ;; use lamda-closure to avoid memory error '(lambda-closure nil 0 0 (cfg level) - (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) - (ros::ros-warn "Volume changed to: ~A" *volume*) + (let ((prev-volume *volume*) + (prev-speak-enable *speak-enable*) + (prev-enable *enable*)) + (setq *volume* (cdr (assoc "volume" cfg :test #'equal))) + (setq *speak-enable* (cdr (assoc "speak_enable" cfg :test #'equal))) + (setq *enable* (cdr (assoc "enable" cfg :test #'equal))) + (if (null (equal *volume* prev-volume)) + (ros::ros-warn "Volume changed to: ~A" *volume*)) + (if (null (equal *enable* prev-enable)) + (ros::ros-warn "Enable changed to: ~A" *enable*)) + (if (null (equal *speak-enable* prev-speak-enable)) + (ros::ros-warn "Speak enable changed to: ~A" *speak-enable*))) cfg))) (ros::advertise "/tweet" std_msgs::String 1) (ros::rate 0.1) (do-until-key - (setq *user-name* (ros::get-param "/active_user/launch_user_name") - *elapsed-time* (ros::get-param "/active_user/elapsed_time")) - (ros::ros-debug "user -> ~A, time -> ~A (~A) " - *user-name* *elapsed-time* *target-second*) - ;; tweet depend on working time - (when (> *elapsed-time* *target-second*) - (incf *target-second* *tweet-second* ) - (ros::ros-info "tweet ~A ~A" *user-name* *elapsed-time*) - (let ((mainstr (format nil "~A has used ~A for ~d minutes" - ;; why delete *user-name* after space ? - ;;(subseq *user-name* 0 - ;;(or (position #\space *user-name*) - ;;(length *user-name*))) - *user-name* - *robot-name* - (round (/ *elapsed-time* 60)))) - presubstr postsubstr) - (cond - ((< *elapsed-time* 600) ;; 5 min - (setq presubstr "Congratulations! " - postsubstr ", Let's get started!")) - ((< *elapsed-time* 910) ;; 15 min - (setq presubstr "Gooood! " - postsubstr ", Go ahead!")) - ((< *elapsed-time* 1820) ;; 30 min - (setq presubstr "So Nice! " - postsubstr ", Go ahead!")) - ((< *elapsed-time* 2730) ;; 45 min - (setq presubstr "Fantastic! " - postsubstr ", Keep going!")) - ((< *elapsed-time* 3640) ;; 60 min - (setq presubstr "Amazing! " - postsubstr ", I'm not tired!")) - (t - (setq presubstr "Awesome! " - postsubstr ", Got some rest?"))) + (if *enable* + (progn + (setq *user-name* (ros::get-param "/active_user/launch_user_name") + *elapsed-time* (ros::get-param "/active_user/elapsed_time")) + (ros::ros-debug "user -> ~A, time -> ~A (~A) " + *user-name* *elapsed-time* *target-second*) + ;; tweet depend on working time + (when (> *elapsed-time* *target-second*) + (incf *target-second* *tweet-second* ) + (ros::ros-info "tweet ~A ~A" *user-name* *elapsed-time*) + (let ((mainstr (format nil "~A has used ~A for ~d minutes" + ;; why delete *user-name* after space ? + ;;(subseq *user-name* 0 + ;;(or (position #\space *user-name*) + ;;(length *user-name*))) + *user-name* + *robot-name* + (round (/ *elapsed-time* 60)))) + presubstr postsubstr) + (cond + ((< *elapsed-time* 600) ;; 5 min + (setq presubstr "Congratulations! " + postsubstr ", Let's get started!")) + ((< *elapsed-time* 910) ;; 15 min + (setq presubstr "Gooood! " + postsubstr ", Go ahead!")) + ((< *elapsed-time* 1820) ;; 30 min + (setq presubstr "So Nice! " + postsubstr ", Go ahead!")) + ((< *elapsed-time* 2730) ;; 45 min + (setq presubstr "Fantastic! " + postsubstr ", Keep going!")) + ((< *elapsed-time* 3640) ;; 60 min + (setq presubstr "Amazing! " + postsubstr ", I'm not tired!")) + (t + (setq presubstr "Awesome! " + postsubstr ", Got some rest?"))) - (tweet-string (format nil "~A~A~A" presubstr mainstr postsubstr) - :warning-time 1 :with-image t - :volume *volume*) - - )) + (tweet-string (format nil "~A~A~A" presubstr mainstr postsubstr) + :warning-time 1 :with-image t + :speak *speak-enable* + :volume *volume*) + )))) (ros::spin-once) (ros::sleep) ) From 1ad65b9da8ba63aa85e70d6d397531f70c7c0c85 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 18 Nov 2022 18:52:26 +0900 Subject: [PATCH 335/433] [jsk_robot_startup] Use checking node status for timeout --- jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py | 1 - 1 file changed, 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py index cbe1d93b63..8f804b3380 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py @@ -148,7 +148,6 @@ def _status_cb(self, msg): # If we received START/INIT status, restart storing smach_state_list if status_str in ["START", "INIT"]: - self.smach_start_time[caller_id] = rospy.Time.now() self.smach_state_list[caller_id] = [] # DESCRIPTION of START is MAIL SUBJECT if 'DESCRIPTION' in local_data_str: From 30092b4f8074b522efd03920136277dee6cbcc7a Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 18 Nov 2022 18:22:52 +0900 Subject: [PATCH 336/433] camera sound only when speak is t --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index b4079f68fa..16838cb9eb 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -36,8 +36,9 @@ (with-image (unix::system (format nil "rm -f /tmp/tweet_image.jpg")) ;; camera shot sound - (play-sound (pathname (ros::resolve-ros-path "package://jsk_pr2_startup/jsk_pr2_lifelog/camera.wav")) - :topic-name "robotsound_jp" :wait t) + (when speak + (play-sound (pathname (ros::resolve-ros-path "package://jsk_pr2_startup/jsk_pr2_lifelog/camera.wav")) + :topic-name "robotsound_jp" :wait t)) ;; specify camera (when (stringp with-image) (ros::wait-for-service "/tweet_image_mux/list") From dd4f33e950703a7d1f3f0cd56c874fa2b18f1b8e Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 18 Nov 2022 18:27:03 +0900 Subject: [PATCH 337/433] set volume for play-sound --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index 16838cb9eb..e945665402 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -38,7 +38,7 @@ ;; camera shot sound (when speak (play-sound (pathname (ros::resolve-ros-path "package://jsk_pr2_startup/jsk_pr2_lifelog/camera.wav")) - :topic-name "robotsound_jp" :wait t)) + :topic-name "robotsound_jp" :wait t :volume volume)) ;; specify camera (when (stringp with-image) (ros::wait-for-service "/tweet_image_mux/list") From 0a72315a0daa3b5a130cd329fc0dca3778faab68 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 14:02:43 +0900 Subject: [PATCH 338/433] check if *image* is nil or not --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 110 ++++++++++-------- 1 file changed, 61 insertions(+), 49 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index 9698c2fe59..bbfc171821 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -9,6 +9,7 @@ (load "package://jsk_fetch_startup/euslisp/navigation-utils.l") (ros::advertise "/photo_taken" sensor_msgs::Image 1) +(setq *image* nil) (defun image-cb (msg) (setq *image* msg)) @@ -140,7 +141,9 @@ (if light-on (set-alist 'description "電気がついていたよ" userdata) (set-alist 'description "電気がついていなかったよ" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) light-on))) (:report-light-on '(lambda (userdata) @@ -156,9 +159,9 @@ (room-light-on :control-switchbot control-switchbot) (ros::spin-once) (set-alist 'description "電気をつけたよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-dock-front '(lambda (userdata) @@ -170,9 +173,9 @@ (if success (set-alist 'description "ドックの前に移動したよ" userdata) (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:inspect-dock-front '(lambda (userdata) @@ -180,9 +183,9 @@ (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "ドックの前の様子を見たよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-dock-front-failure '(lambda (userdata) @@ -190,9 +193,9 @@ (report-move-to-dock-front-failure) (ros::spin-once) (set-alist 'description "ドックの前に移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-tv-front '(lambda (userdata) @@ -211,9 +214,9 @@ (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "テレビの前の様子を見たよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-tv-front-failure '(lambda (userdata) @@ -221,9 +224,9 @@ (report-move-to-tv-front-failure) (ros::spin-once) (set-alist 'description "テレビの前に移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-tv-desk '(lambda (userdata) @@ -243,9 +246,9 @@ (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "机の様子を確認したよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-tv-desk-failure '(lambda (userdata) @@ -253,9 +256,9 @@ (report-move-to-tv-desk-failure) (ros::spin-once) (set-alist 'description "机の前に移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-desk-back '(lambda (userdata) @@ -275,9 +278,9 @@ (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "部屋の後ろを確認したよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-desk-back-failure '(lambda (userdata) @@ -285,9 +288,9 @@ (report-move-to-desk-back-failure) (ros::spin-once) (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-desk-front '(lambda (userdata) @@ -306,9 +309,9 @@ (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "部屋の前を確認したよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-desk-front-failure '(lambda (userdata) @@ -316,9 +319,9 @@ (report-move-to-desk-front-failure) (ros::spin-once) (set-alist 'description "部屋の前に移動できなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-kitchen-door-front '(lambda (userdata) @@ -337,9 +340,9 @@ (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:report-move-to-kitchen-door-front-failure '(lambda (userdata) @@ -367,18 +370,19 @@ (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata) - (if label-names + (if (and *image* label-names) (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) - (set-alist 'image "" userdata))) - t)) + (set-alist 'image "" userdata)) + t))) (:report-move-to-sink-front-failure '(lambda (userdata) (let* ((label-names (notify-recognition :location "on the way to sink-front"))) (report-move-to-sink-front-failure) (ros::spin-once) (set-alist 'description "キッチンに行けなかったよ" userdata) - (if label-names - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata)) + (if (and *image* label-names) + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t))) (:move-to-trashcan-front '(lambda (userdata) @@ -397,14 +401,18 @@ (inspect-trashcan :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "ゴミ箱の様子を確認したよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t)) (:report-move-to-trashcan-front-failure '(lambda (userdata) (report-move-to-trashcan-front-failure) (ros::spin-once) (set-alist 'description "ゴミ箱の前に行けなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t)) (:auto-dock '(lambda (userdata) @@ -416,14 +424,18 @@ (if success (set-alist 'description "帰ってきたよ" userdata) (set-alist 'description "帰ってこようとしたけど,迷子になっちゃった" userdata)) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) success))) (:auto-dock-failure '(lambda (userdata) (report-auto-dock-failure) (ros::spin-once) (set-alist 'description "帰ってこられなかったよ" userdata) - (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (if *image* + (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) + (set-alist 'image "" userdata)) t)) (:room-light-off '(lambda (userdata) From 096062341f6ef6a7fe43b8bb0d88bf8e27046cef Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 14:10:17 +0900 Subject: [PATCH 339/433] load 73b2 env in kinematics simulation --- jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index bbfc171821..f862a7cc67 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -119,6 +119,11 @@ '((:init '(lambda (userdata) (fetch-init) + (if (send *ri* :simulation-modep) + (progn + (load "models/room73b2-scene.l") + (room73b2) + (send *ri* :objects (send *room73b2* :objects)))) (undock) (send *ri* :clear-costmap) (store-params) From 5399a7dc4d602314c76a03906fe48ffa8c124895 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 14:23:32 +0900 Subject: [PATCH 340/433] set timeout for notify-recognition --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 56baff7ec8..ca702463de 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -405,8 +405,9 @@ Args: (defun notify-recognition (&key (location "kitchen")) (let* ((msg (one-shot-subscribe "/edgetpu_object_detector/output/class" - jsk_recognition_msgs::ClassificationResult)) - (label-names (send msg :label_names))) + jsk_recognition_msgs::ClassificationResult + :timeout 3000)) + (label-names (if msg (send msg :label_names)))) (when label-names (ros::ros-info (format nil "Notify app that ~A is found." label-names)) (notify-app "object recognition" From 9312289bf29f50e7adee23d33ad5cbf1607ea03e Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 16:00:33 +0900 Subject: [PATCH 341/433] add advertise /tweet in go-to-kitchen.l --- jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index f862a7cc67..823dc26bb1 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -8,6 +8,7 @@ (load "package://jsk_fetch_startup/euslisp/navigation-utils.l") +(ros::advertise "/tweet" std_msgs::String 1) (ros::advertise "/photo_taken" sensor_msgs::Image 1) (setq *image* nil) From 6f889453f4c414b99a4da5df47c53178a372afb8 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 16:02:48 +0900 Subject: [PATCH 342/433] wait-for-service timeout in tweet_client.l --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index e945665402..0dce467b52 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -40,8 +40,8 @@ (play-sound (pathname (ros::resolve-ros-path "package://jsk_pr2_startup/jsk_pr2_lifelog/camera.wav")) :topic-name "robotsound_jp" :wait t :volume volume)) ;; specify camera - (when (stringp with-image) - (ros::wait-for-service "/tweet_image_mux/list") + (when (and (stringp with-image) + (ros::wait-for-service "/tweet_image_mux/list" 1)) (let ((current-image-list (send (ros::service-call "/tweet_image_mux/list" (instance topic_tools::muxlistrequest :init)) :topics))) (unless (find with-image current-image-list :test #'string=) From a0ae78c8adc063ad4be35424cddf3241436a645d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 16:10:17 +0900 Subject: [PATCH 343/433] check if prev-image-topic exists or not --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index 0dce467b52..4053c0c081 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -48,8 +48,6 @@ (ros::service-call "/tweet_image_mux/add" (instance topic_tools::muxaddrequest :init :topic with-image))) (setq prev-image-topic (send (ros::service-call "/tweet_image_mux/select" (instance topic_tools::muxselectrequest :init :topic with-image)) :prev_topic)))) - (unless prev-image-topic - (setq prev-image-topic (send (one-shot-subscribe "/tweet_image_mux/selected" std_msgs::String) :data))) ;; retrieve image ;; (call-empty-service "/tweet_image_saver/save" :wait t) @@ -63,7 +61,8 @@ :data (format nil "~A ~A" twit-str (format nil "/tmp/tweet_image.jpg"))))) (ros::ros-error "fail saving image and tweeting")) - (ros::service-call "/tweet_image_mux/select" (instance topic_tools::muxselectrequest :init :topic prev-image-topic))) + (if prev-image-topic + (ros::service-call "/tweet_image_mux/select" (instance topic_tools::muxselectrequest :init :topic prev-image-topic)))) (t (ros::publish tweet-topic-name (instance std_msgs::String :init :data twit-str)))) (when speak (speak-jp "ついーとしました" :wait t :volume volume)))) From 2bdcb7d9267840e0fd395f4452e0eec4ffc95e6d Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 16:15:12 +0900 Subject: [PATCH 344/433] add timeout in one-shot-subscribe --- .../jsk_fetch_startup/euslisp/navigation-utils.l | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index ca702463de..9a021cb943 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -459,7 +459,7 @@ Args: ;; sink (tweet-string "I took a photo at 73B2 Kitchen sink." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img)) (take-photo "kitchen_sink.jpg") (notify-recognition :location "kitchen sink")) @@ -532,7 +532,7 @@ Args: (progn (tweet-string "I took a photo in front of the dock." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-tv-front (&key (tweet t)) @@ -544,7 +544,7 @@ Args: (progn (tweet-string "I took a photo in front of the tv." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-tv-desk (&key (tweet t)) @@ -556,7 +556,7 @@ Args: (progn (tweet-string "I took a photo in front of the tv." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-desk-back (&key (tweet t)) @@ -568,7 +568,7 @@ Args: (progn (tweet-string "I took a photo of desks." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-desk-front (&key (tweet t)) @@ -580,7 +580,7 @@ Args: (progn (tweet-string "I took a photo of desks." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-kitchen-door-front (&key (tweet t)) @@ -592,7 +592,7 @@ Args: (progn (tweet-string "I took a photo of kitchen." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img))))) (defun inspect-trashcan (&key (tweet t)) @@ -611,7 +611,7 @@ Args: (send *ri* :wait-interpolation) (tweet-string "I took a photo of 73B2 trash can inside." :warning-time 3 :with-image "/edgetpu_object_detector/output/image" :speak t) - (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image))) + (let ((img (one-shot-subscribe "/head_camera/rgb/image_rect_color" sensor_msgs::Image :timeout 1000))) (ros::publish "/photo_taken" img)) (take-photo "trashcan_inside.jpg") (notify-recognition :location "trash cans inside") From 9ec50c736de7ce649f2fa902e4bde673422da2ba Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:01:47 +0900 Subject: [PATCH 345/433] load jsk_maps scene for kinematics simulation --- jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index 823dc26bb1..5641e22cd0 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -123,8 +123,14 @@ (if (send *ri* :simulation-modep) (progn (load "models/room73b2-scene.l") + (load "package://jsk_maps/src/eng2-scene.l") (room73b2) - (send *ri* :objects (send *room73b2* :objects)))) + (setq *base-spot* "/eng2/7f/room73B2-base") + (setq *scene* (make-eng2-7f-scene)) + (send *ri* :objects (send *room73b2* :objects)) + (send (send *ri* :robot) + :newcoords (car (get-spot-coords "/eng2/7f/room73B2-center"))) + )) (undock) (send *ri* :clear-costmap) (store-params) From 6161a6d16a082924134b3aea25eee885bf41c0e5 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:02:06 +0900 Subject: [PATCH 346/433] use jsk_maps scene for kinematics simulation --- .../euslisp/navigation-utils.l | 35 ++++++++++++------- 1 file changed, 23 insertions(+), 12 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 9a021cb943..8355a98543 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -58,17 +58,26 @@ (defun get-spot-coords (name) - (unless *spots* - (setq *spots* (one-shot-subscribe "/spots_marker_array" visualization_msgs::MarkerArray))) - (let ((spot-coords nil) (frame-id nil)) - (dolist (x (send *spots* :markers)) - (if (equal (send x :text) name) - (progn - (setq spot-coords (send x :pose)) - (setq frame-id (send (send x :header) :frame_id))))) - (send (send spot-coords :position) :z 0) - (setq spot-coords (ros::tf-pose->coords spot-coords)) - (cons spot-coords frame-id))) + (if (send *ri* :simulation-modep) + (let ((base-coords (send *scene* :spot *base-spot*)) + (spot-coords (send *scene* :spot name)) + (goal-coords nil)) + (if (and base-coords spot-coords) + (setq goal-coords (send base-coords :transformation spot-coords))) + (cons goal-coords nil)) + (progn + (unless *spots* + (setq *spots* (one-shot-subscribe "/spots_marker_array" visualization_msgs::MarkerArray))) + (let ((spot-coords nil) (frame-id nil)) + (dolist (x (send *spots* :markers)) + (if (equal (send x :text) name) + (progn + (setq spot-coords (send x :pose)) + (setq frame-id (send (send x :header) :frame_id))))) + (send (send spot-coords :position) :z 0) + (setq spot-coords (ros::tf-pose->coords spot-coords)) + (cons spot-coords frame-id)) + ))) (defun simple-dock (&key (use-pose t)) @@ -210,7 +219,9 @@ Args: (setq goal-pose (send goal-pose :translate relative-pos :world))) (when relative-rot (setq goal-pose (send goal-pose :rotate relative-rot :z :local))) - (send *ri* :move-to goal-pose :frame-id frame-id))) + (if frame-id + (send *ri* :move-to goal-pose :frame-id frame-id) + (send *ri* :move-to goal-pose)))) (defun auto-dock (&key (n-trial 1) (clear-costmap t)) From 44565f9a7c4c2730ec1ea3a2dd3608367e599ab8 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 15:58:04 +0900 Subject: [PATCH 347/433] use go-to-spot for move func --- .../euslisp/navigation-utils.l | 30 +++++++++++++------ 1 file changed, 21 insertions(+), 9 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 8355a98543..62278dd0a1 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -487,10 +487,13 @@ Args: success-move-to-sink-front)) (defun move-to-dock-front (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-dock-front nil)) + (let ((success-move-to-dock-front nil) + (goal-coords (make-coords :pos (float-vector 5077.8 6763.237 30000.0) + :rpy (float-vector 0.059 0 0)))) (dotimes (i n-trial) (setq success-move-to-dock-front - (send *ri* :move-to (make-coords :pos (float-vector 5077.8 6763.237 30000.0) :rpy (float-vector 0.059 0 0)) :relative-pos offset)) + (go-to-spot *dock-spot* + :relative-pos offset :undock-rotate t)) (when success-move-to-dock-front (return))) success-move-to-dock-front)) @@ -498,15 +501,19 @@ Args: (let ((success-move-to-tv-front nil)) (dotimes (i n-trial) (setq success-move-to-tv-front - (send *ri* :move-to (make-coords :pos (float-vector 5082.057 6800.628 30000.0) :rpy (float-vector 3.109 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-tv-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-tv-front (return))) success-move-to-tv-front)) (defun move-to-tv-desk (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-tv-desk nil)) + (let ((success-move-to-tv-desk nil) + (goal-coords (make-coords :pos (float-vector 4035.759 7343.818 30000.0) + :rpy (float-vector 1.753 0 0)))) (dotimes (i n-trial) (setq success-move-to-tv-desk - (send *ri* :move-to (make-coords :pos (float-vector 4035.759 7343.818 30000.0) :rpy (float-vector 1.753 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-tv-desk" + :relative-pos offset :undock-rotate t)) (when success-move-to-tv-desk (return))) success-move-to-tv-desk)) @@ -514,7 +521,8 @@ Args: (let ((success-move-to-desk-back nil)) (dotimes (i n-trial) (setq success-move-to-desk-back - (send *ri* :move-to (make-coords :pos (float-vector 4324.417 6121.184 30000.0) :rpy (float-vector -0.845 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-desk-back" + :relative-pos offset :undock-rotate t)) (when success-move-to-desk-back (return))) success-move-to-desk-back)) @@ -522,15 +530,19 @@ Args: (let ((success-move-to-desk-front nil)) (dotimes (i n-trial) (setq success-move-to-desk-front - (send *ri* :move-to (make-coords :pos (float-vector 4318.808 6108.146 30000.0) :rpy (float-vector -2.231 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-desk-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-desk-front (return))) success-move-to-desk-front)) (defun move-to-kitchen-door-front (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-kitchen-door-front nil)) + (let ((success-move-to-kitchen-door-front nil) + (goal-coords (make-coords :pos (float-vector 1558.69 7230.57 30000.0) + :rpy (float-vector 2.296 0 0)))) (dotimes (i n-trial) (setq success-move-to-kitchen-door-front - (send *ri* :move-to (make-coords :pos (float-vector 1558.69 7230.57 30000.0) :rpy (float-vector 2.296 0 0)) :relative-pos offset)) + (go-to-spot "/eng2/7f/room73B2-kitchen-door-front" + :relative-pos offset :undock-rotate t)) (when success-move-to-kitchen-door-front (return))) success-move-to-kitchen-door-front)) From 1b857e0f7cbeb7977ffd72922943bb09c25a3b01 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:02:19 +0900 Subject: [PATCH 348/433] set dock-spot for kinematics simulation --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 62278dd0a1..6fe5e46ad6 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -21,7 +21,7 @@ "/eng2/7f/room73B2-fetch-dock-front") ((equal robot-name "fetch1075") "/eng2/7f/room73B2-fetch-dock2-front") - (t nil)))) + (t "/eng2/7f/room73B2-fetch-dock2-front"))) (defun store-params () From 1e85f397c215cfe920ffd0345c7af47af3657ebb Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:19:56 +0900 Subject: [PATCH 349/433] fix typo in navigation-utils.l --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 6fe5e46ad6..665f1145bd 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -87,7 +87,7 @@ "/dock" fetch_auto_dock_msgs::DockAction))) (unless (send *dock-action* :wait-for-server 5) (ros::ros-error "/dock action server is not started") - (return-from dock nil)) + (return-from simple-dock nil)) (let ((dock-action-goal (instance fetch_auto_dock_msgs::DockActionGoal :init))) (when use-pose (let* ((timestamp (ros::time-now)) From 337cc34f5f06b4fbb0acbb04fbdd7c4dbe8fecc1 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:30:26 +0900 Subject: [PATCH 350/433] check if dynamic reconfigure server is up ot not --- .../euslisp/navigation-utils.l | 20 +++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 665f1145bd..fb906fb115 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -33,14 +33,18 @@ (defun restore-params () - (if (boundp '*global-inflation-radius*) - (ros::set-dynamic-reconfigure-param - "/move_base/global_costmap/inflater" "inflation_radius" - :double *global-inflation-radius*)) - (if (boundp '*local-inflation-radius*) - (ros::set-dynamic-reconfigure-param - "/move_base/local_costmap/inflater" "inflation_radius" - :double *local-inflation-radius*)) + (let ((global-costmap-server "/move_base/global_costmap/inflater") + (local-costmap-server "/move_base/local_costmap/inflater")) + (if (and (boundp '*global-inflation-radius*) + (ros::wait-for-service (format nil "~A/set_parameters" global-costmap-server) 1)) + (ros::set-dynamic-reconfigure-param + "/move_base/global_costmap/inflater" "inflation_radius" + :double *global-inflation-radius*)) + (if (and (boundp '*local-inflation-radius*) + (ros::wait-for-service (format nil "~A/set_parameters" local-costmap-server) 1)) + (ros::set-dynamic-reconfigure-param + "/move_base/local_costmap/inflater" "inflation_radius" + :double *local-inflation-radius*))) t) From 6a0d01c30afacadce68c810515489d7ad7bfe235 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:30:46 +0900 Subject: [PATCH 351/433] skip dock in kinematics simlation --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index fb906fb115..587c6d152f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -235,7 +235,7 @@ Args: :relative-pos #f(-800 0 0) :clear-costmap clear-costmap) (ros::ros-info "arrived at the dock.") - (setq success (dock)) + (setq success (if (send *ri* :simulation-modep) t (dock))) (when success (return-from auto-dock success)))) success)) From 37aaa45ccb27cc0f44fa0950bf68339266045819 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Tue, 22 Nov 2022 18:51:55 +0900 Subject: [PATCH 352/433] skip battery checking in kinematics simulation --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 587c6d152f..b367e5e254 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -153,6 +153,7 @@ ;; while dock succeeds, the result will not be correct, ;; so wait for a certain time when docking. """ + (if (send *ri* :simulation-modep) (return-from wait-until-is-charging nil)) (let* ((msg nil) (is-charging nil) (duration 0) @@ -174,6 +175,7 @@ - key timeout: Set waiting time for topic. """ + (if (send *ri* :simulation-modep) (return-from get-battery-charging-state nil)) (let* ((msg (one-shot-subscribe "/battery_state" power_msgs::batterystate :timeout timeout)) (is-charging (if msg (send msg :is_charging)))) ;; You may fail to subscribe /battery_state From fe0c572f26c424eedd9e09b8f84464e87628dbc4 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 28 Nov 2022 19:11:51 +0900 Subject: [PATCH 353/433] fix typo --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index b367e5e254..52a7c065cf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -21,7 +21,7 @@ "/eng2/7f/room73B2-fetch-dock-front") ((equal robot-name "fetch1075") "/eng2/7f/room73B2-fetch-dock2-front") - (t "/eng2/7f/room73B2-fetch-dock2-front"))) + (t "/eng2/7f/room73B2-fetch-dock2-front")))) (defun store-params () From 901633d1a61404cca6023c5a1b2fc8c7d3c2fd27 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 28 Nov 2022 19:21:46 +0900 Subject: [PATCH 354/433] fix func name --- jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index 52a7c065cf..a9e4410df3 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -328,7 +328,7 @@ Args: (ros::ros-info "start going back to the dock.") (send *ri* :speak-jp "ドックに戻ります。" :wait t)) -(defun report-move-to-sink-front-success () +(defun report-move-to-sink-front () (ros::ros-info "arrived at the kitchen stove.") (send *ri* :speak-jp "キッチンのコンロの前につきました。" :wait t)) @@ -463,7 +463,7 @@ Args: occupancy))))) (defun inspect-kitchen (&key (tweet t)) - (report-move-to-sink-front-success) + (report-move-to-sink-front) (if tweet (progn ;; stove From 4c8f0958d352fa89ba7391fe951c02452a3e6eec Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 28 Nov 2022 20:33:08 +0900 Subject: [PATCH 355/433] fix typo in move-to functions --- .../euslisp/navigation-utils.l | 24 +++++++------------ 1 file changed, 9 insertions(+), 15 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index a9e4410df3..aa4be969f5 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -492,10 +492,8 @@ Args: (when success-move-to-sink-front (return))) success-move-to-sink-front)) -(defun move-to-dock-front (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-dock-front nil) - (goal-coords (make-coords :pos (float-vector 5077.8 6763.237 30000.0) - :rpy (float-vector 0.059 0 0)))) +(defun move-to-dock-front (&key (n-trial 1) (offset #f(0 0 0))) + (let ((success-move-to-dock-front nil)) (dotimes (i n-trial) (setq success-move-to-dock-front (go-to-spot *dock-spot* @@ -503,7 +501,7 @@ Args: (when success-move-to-dock-front (return))) success-move-to-dock-front)) -(defun move-to-tv-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-tv-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-tv-front nil)) (dotimes (i n-trial) (setq success-move-to-tv-front @@ -512,10 +510,8 @@ Args: (when success-move-to-tv-front (return))) success-move-to-tv-front)) -(defun move-to-tv-desk (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-tv-desk nil) - (goal-coords (make-coords :pos (float-vector 4035.759 7343.818 30000.0) - :rpy (float-vector 1.753 0 0)))) +(defun move-to-tv-desk (&key (n-trial 1) (offset #f(0 0 0))) + (let ((success-move-to-tv-desk nil)) (dotimes (i n-trial) (setq success-move-to-tv-desk (go-to-spot "/eng2/7f/room73B2-tv-desk" @@ -523,7 +519,7 @@ Args: (when success-move-to-tv-desk (return))) success-move-to-tv-desk)) -(defun move-to-desk-back (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-desk-back (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-desk-back nil)) (dotimes (i n-trial) (setq success-move-to-desk-back @@ -532,7 +528,7 @@ Args: (when success-move-to-desk-back (return))) success-move-to-desk-back)) -(defun move-to-desk-front (&key (n-trial 1) (offset #f(400 -500 0))) +(defun move-to-desk-front (&key (n-trial 1) (offset #f(0 0 0))) (let ((success-move-to-desk-front nil)) (dotimes (i n-trial) (setq success-move-to-desk-front @@ -541,10 +537,8 @@ Args: (when success-move-to-desk-front (return))) success-move-to-desk-front)) -(defun move-to-kitchen-door-front (&key (n-trial 1) (offset #f(400 -500 0))) - (let ((success-move-to-kitchen-door-front nil) - (goal-coords (make-coords :pos (float-vector 1558.69 7230.57 30000.0) - :rpy (float-vector 2.296 0 0)))) +(defun move-to-kitchen-door-front (&key (n-trial 1) (offset #f(0 0 0))) + (let ((success-move-to-kitchen-door-front nil)) (dotimes (i n-trial) (setq success-move-to-kitchen-door-front (go-to-spot "/eng2/7f/room73B2-kitchen-door-front" From 9e72dfc300f3f9a82cf23d73a078ab265247789a Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 15:01:28 +0900 Subject: [PATCH 356/433] [jsk_robot_startup] Support replication client in addition to robot/type --- jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index e7b6b684d8..f21316309b 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -10,6 +10,7 @@ + @@ -18,6 +19,9 @@ + + extra_collections: $(arg extra_collections) + From 2949658f0534ac8c33cd5c02e9d10176438fc646 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 15:02:33 +0900 Subject: [PATCH 357/433] [jsk_fetch_startup] Add extra_collections argument --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index 7d630a5d66..5314211d42 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -2,6 +2,7 @@ + @@ -11,11 +12,13 @@ + + From 92dc40d6d5665479a8701f9195197312085c5c73 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 15:03:00 +0900 Subject: [PATCH 358/433] [jsk_fetch_startup] Add extra collection argument to fetch_bringup.launch --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 2be8f75811..206a047988 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -49,6 +49,7 @@ + @@ -137,6 +138,7 @@ if="$(arg launch_fetch_lifelog)"> + From 9352a7c270ebb93e57afcbfb0f6bf123d0e1a448 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 15:06:22 +0900 Subject: [PATCH 359/433] [jsk_fetch_startup] Logging go_to_kitchen --- .../apps/go_to_kitchen/go_to_kitchen.xml | 27 +++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index e8eec07635..564d431302 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -28,4 +28,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + From 50c637b84c3f7aec93fa6f37e3831f607a9f0cb0 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 17:55:23 +0900 Subject: [PATCH 360/433] [jsk_robot_startup] Add human_pose logger --- .../lifelog/common_logger.launch | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 7d15c029a4..f2728912cd 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -15,6 +15,7 @@ + @@ -355,6 +356,22 @@ + + + + database: $(arg database) + topics: + - /edgetpu_human_pose_estimator/output/poses + + + collection: $(arg collection) + + + Date: Fri, 11 Nov 2022 17:58:08 +0900 Subject: [PATCH 361/433] [jsk_fetch_startup] Logging speech in go_to_kitchen and save human_pose, save_base_trajectory --- .../apps/go_to_kitchen/go_to_kitchen.xml | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 564d431302..8fb8a8f668 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -42,17 +42,26 @@ - + + + + + + topics: + - /sound_play/goal + - /speech_to_text + + From c87728153bb09a45228fe185b76af4810ef36e79 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 11 Nov 2022 17:58:45 +0900 Subject: [PATCH 362/433] [jsk_fetch_startup] Save human pose as default in fetch --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index 5314211d42..ab52d40cc4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -31,6 +31,7 @@ + From 6f921c67912ab0d3ef731e52ba861d9cb0b5ec20 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 14:18:28 +0900 Subject: [PATCH 363/433] [jsk_robot_startup] Fix private name space resolution --- .../jsk_robot_startup/src/lightweight_logger_nodelet.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp index 7ee9ab569d..2d497f925f 100644 --- a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp +++ b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp @@ -49,7 +49,7 @@ namespace jsk_robot_startup jsk_topic_tools::StealthRelay::onInit(); // settings for database - if (ros::param::has("~database")) + if (ros::param::has(pnh_->resolveName("database"))) { pnh_->param("database", db_name_, "jsk_robot_lifelog"); } @@ -57,7 +57,7 @@ namespace jsk_robot_startup { pnh_->param("/robot/database", db_name_, "jsk_robot_lifelog"); } - if (ros::param::has("~collection")) + if (ros::param::has(pnh_->resolveName("collection"))) { pnh_->param("collection", col_name_, std::string()); } From 9c8a81809052251f4b7996d73d099dff892dc157 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 14:19:56 +0900 Subject: [PATCH 364/433] [jsk_robot_startup] not calling vital_checker_ until initializing --- .../src/lightweight_logger_nodelet.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp index 2d497f925f..e16b176b6c 100644 --- a/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp +++ b/jsk_robot_common/jsk_robot_startup/src/lightweight_logger_nodelet.cpp @@ -198,7 +198,9 @@ namespace jsk_robot_startup const boost::shared_ptr& msg = event.getConstMessage(); jsk_topic_tools::StealthRelay::inputCallback(msg); - vital_checker_->poke(); + if (vital_checker_ != nullptr) { + vital_checker_->poke(); + } bool on_the_fly = initialized_ && buffer_.empty(); if (!wait_for_insert_ && msg_store_->getNumInsertSubscribers() == 0) { @@ -246,7 +248,7 @@ namespace jsk_robot_startup } else if (!initialized_) { stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, getName() + " is taking too long to be initialized"); - } else if (vital_check_ && !vital_checker_->isAlive()) { + } else if (vital_checker_ != nullptr && vital_check_ && !vital_checker_->isAlive()) { jsk_topic_tools::addDiagnosticErrorSummary(getName(), vital_checker_, stat); } else if (insert_error_count_ != prev_insert_error_count_) { stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, @@ -259,7 +261,9 @@ namespace jsk_robot_startup stat.add("Inserted", inserted_count_); stat.add("Insert Failure", insert_error_count_); - vital_checker_->registerStatInfo(stat, "Last Insert"); + if (vital_checker_ != nullptr) { + vital_checker_->registerStatInfo(stat, "Last Insert"); + } } } // lifelog } // jsk_robot_startup From 19424854c99d6aad12eaa3dbd13ecfcf741999c5 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 15:57:07 +0900 Subject: [PATCH 365/433] [jsk_robot_startup] Add database and collection param to dialogflow and aws logger --- .../jsk_robot_startup/lifelog/common_logger.launch | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index f2728912cd..be227e116d 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -288,10 +288,14 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) topics: - /aws_auto_checkin_app/class - /aws_detect_faces/attributes + + collection: $(arg collection) + @@ -301,10 +305,14 @@ machine="$(arg machine)" respawn="$(arg respawn)"> + database: $(arg database) topics: - /dialogflow_client/text_action/goal - /dialogflow_client/text_action/result + + collection: $(arg collection) + From 010dfa96e170485cbee3f9998e634fa9ef22a277 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 15:57:40 +0900 Subject: [PATCH 366/433] [jsk_robot_startup] Save human pose class --- jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index be227e116d..3d2a453ff1 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -373,6 +373,7 @@ database: $(arg database) topics: + - /edgetpu_human_pose_estimator/output/class - /edgetpu_human_pose_estimator/output/poses From a280898bf0116a428d15f57302c08e49aa0bb9d0 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 15:58:08 +0900 Subject: [PATCH 367/433] [jsk_robot_startup] Add option to save_edgetpu_object_detector --- .../lifelog/common_logger.launch | 45 +++++++++++++------ 1 file changed, 31 insertions(+), 14 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 3d2a453ff1..72f525653b 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -15,6 +15,7 @@ + @@ -349,20 +350,36 @@ - - - database: $(arg database) - map_frame: $(arg map_frame_id) - robot_frame: $(arg base_frame_id) - - - collection: $(arg collection) - - + + + + database: $(arg database) + topics: + - /edgetpu_human_pose_estimator/output/class + + + collection: $(arg collection) + + + + + database: $(arg database) + map_frame: $(arg map_frame_id) + robot_frame: $(arg base_frame_id) + + + collection: $(arg collection) + + + Date: Wed, 30 Nov 2022 15:58:47 +0900 Subject: [PATCH 368/433] [jsk_robot_startup] Save edgetpu object detection in go-to-kitchen --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index 8fb8a8f668..be357db5b8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -43,7 +43,8 @@ - + + From 6a02c2cf5b39e61fff35593c96ff713639501e7c Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 16:12:21 +0900 Subject: [PATCH 369/433] [jsk_fetch_startup] Save depth in kitchen-demo --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index be357db5b8..bc08d9e064 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -39,7 +39,7 @@ - + From 82a41f079b2499ac42d3171cd4bbbe5868a919ff Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 16:30:13 +0900 Subject: [PATCH 370/433] [jsk_fetch_startup] Set depth topic name --- .../apps/go_to_kitchen/go_to_kitchen.xml | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml index bc08d9e064..095dd2a6cb 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.xml @@ -35,11 +35,13 @@ - + - - + + + + From 93e0ba3c6725ece843a0fe8439c022b550131c1c Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 16:47:13 +0900 Subject: [PATCH 371/433] [jsk_robot_startup] Fix typo; human_pose_estimator --> object_detector --- jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 72f525653b..30ba32c146 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -359,7 +359,7 @@ database: $(arg database) topics: - - /edgetpu_human_pose_estimator/output/class + - /edgetpu_object_detector/output/class collection: $(arg collection) From dcba1e4c77ec7216074a545f0018edae1e72862b Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 16:47:51 +0900 Subject: [PATCH 372/433] [jsk_robot_startup] Save rects of human pose estimator and object detector --- jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch index 30ba32c146..9af0e43968 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/common_logger.launch @@ -360,6 +360,7 @@ database: $(arg database) topics: - /edgetpu_object_detector/output/class + - /edgetpu_object_detector/output/rects collection: $(arg collection) @@ -392,6 +393,7 @@ topics: - /edgetpu_human_pose_estimator/output/class - /edgetpu_human_pose_estimator/output/poses + - /edgetpu_human_pose_estimator/output/rects collection: $(arg collection) From 9fd5d34e0a5c01ad8bbe3eb630acbf78bdecd958 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 30 Nov 2022 16:50:20 +0900 Subject: [PATCH 373/433] [jsk_robot_startup] set rosparam in node section Co-authored-by: Shingo Kitagawa --- .../jsk_robot_startup/lifelog/mongodb.launch | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index f21316309b..489da6e5ec 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -19,12 +19,14 @@ - - extra_collections: $(arg extra_collections) - + + output="screen" machine="$(arg machine)"> + + extra_collections: $(arg extra_collections) + + From dd9cf578bb13f06e3270961cdb8c1070c9f3b24e Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 2 Dec 2022 17:27:49 +0900 Subject: [PATCH 374/433] [jsk_robot_startup] Fix variable name; *speak* -> *speak-enable* --- .../jsk_robot_startup/lifelog/tweet_client_warning.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l index 7fa754e89a..0f0c1d1b03 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_warning.l @@ -61,7 +61,7 @@ (setq id (random (length status))) (when (= (mod (round (send tm :sec)) 1000) 0) (tweet-string (format nil "Warning!! ~A is ~A at ~0,3f" (car (elt status id)) (cdr (elt status id)) (send tm :to-sec)) - :warning-time 1 :with-image t :volume *volume* :speak *speak*))) + :warning-time 1 :with-image t :volume *volume* :speak *speak-enable*))) ))) (ros::advertise "/tweet" std_msgs::String 1) From 63cc527235acd900e328cb239e4a5f120b490083 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Fri, 2 Dec 2022 17:39:02 +0900 Subject: [PATCH 375/433] [jsk_fetch_startup] Change smach image topic --- jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index 5641e22cd0..ce19d61d15 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -136,7 +136,7 @@ (store-params) (inflation-loose) (clear-app-notification) - (ros::subscribe "/edgetpu_object_detector/output/image/compressed" + (ros::subscribe "/head_camera/rgb/image_rect_color/compressed" sensor_msgs::CompressedImage #'image-cb) t)) (:report-start-go-to-kitchen From 969b6b3d58382509f6b6c4f231b99ff89df69771 Mon Sep 17 00:00:00 2001 From: Kanazawa Naoaki Date: Thu, 3 Nov 2022 18:20:09 +0900 Subject: [PATCH 376/433] Add nodes to adjust the volume of the speaking --- .../jsk_pr2_warning/pr2_speak_volume_lower.l | 9 +++++++++ .../jsk_pr2_warning/pr2_speak_volume_reset.l | 9 +++++++++ .../jsk_pr2_warning/pr2_speak_volume_zero.l | 9 +++++++++ 3 files changed, 27 insertions(+) create mode 100755 jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_lower.l create mode 100755 jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_reset.l create mode 100755 jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_zero.l diff --git a/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_lower.l b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_lower.l new file mode 100755 index 0000000000..e3efe68518 --- /dev/null +++ b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_lower.l @@ -0,0 +1,9 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_lower") +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.2) +(exit) diff --git a/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_reset.l b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_reset.l new file mode 100755 index 0000000000..89685bfb3b --- /dev/null +++ b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_reset.l @@ -0,0 +1,9 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_reset") +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 1.0) +(exit) diff --git a/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_zero.l b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_zero.l new file mode 100755 index 0000000000..6f89b26903 --- /dev/null +++ b/jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_zero.l @@ -0,0 +1,9 @@ +#!/usr/bin/env roseus + +(ros::roseus "speak_volume_zero") +(ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.0) +(exit) From 6957a160f016250a83e97278414beace178dbd01 Mon Sep 17 00:00:00 2001 From: Kanazawa Naoaki Date: Sun, 13 Nov 2022 18:03:13 +0900 Subject: [PATCH 377/433] Add volume adjust apps --- .../apps/robot_apps.installed | 8 +++++++- .../apps/volume_lower/volume_lower.app | 6 ++++++ .../apps/volume_lower/volume_lower.interface | 2 ++ .../apps/volume_lower/volume_lower.png | Bin 0 -> 571776 bytes .../apps/volume_reset/volume_reset.app | 6 ++++++ .../apps/volume_reset/volume_reset.interface | 2 ++ .../apps/volume_reset/volume_reset.png | Bin 0 -> 81525 bytes .../apps/volume_zero/volume_zero.app | 6 ++++++ .../apps/volume_zero/volume_zero.interface | 2 ++ .../apps/volume_zero/volume_zero.png | Bin 0 -> 69298 bytes .../lifelog/auto_speak_volume_lower.l | 0 .../lifelog/auto_speak_volume_reset.l | 0 .../lifelog/auto_speak_volume_zero.l | 0 13 files changed, 31 insertions(+), 1 deletion(-) create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.app create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.interface create mode 100644 jsk_robot_common/jsk_robot_startup/apps/volume_zero/volume_zero.png rename jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_lower.l => jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l (100%) rename jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_reset.l => jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l (100%) rename jsk_pr2_robot/jsk_pr2_startup/jsk_pr2_warning/pr2_speak_volume_zero.l => jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l (100%) diff --git a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed index 378c08693f..1350da5b19 100644 --- a/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed +++ b/jsk_robot_common/jsk_robot_startup/apps/robot_apps.installed @@ -1,9 +1,15 @@ apps: - app: jsk_robot_startup/personal_use - display: Personal use + display: Personal use - app: jsk_robot_startup/check_use_sim_time display: Check /use_sim_time param - app: jsk_robot_startup/roseus_resume_interrupt display: Interrupt - app: jsk_robot_startup/roseus_resume_resume display: Resume + - app: jsk_robot_startup/volume_lower + display: Volume lower + - app: jsk_robot_startup/volume_reset + display: Volume reset + - app: jsk_robot_startup/volume_zero + display: Volume zero diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app new file mode 100644 index 0000000000..e9648c034f --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.app @@ -0,0 +1,6 @@ +display: Volume Lower +description: robot speaks lower volume +platform: all +run: jsk_robot_startup/auto_speak_volume_lower.l +interface: jsk_robot_startup/volume_lower.interface +icon: jsk_robot_startup/volume_lower.png \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface new file mode 100644 index 0000000000..5cb4ae9816 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png b/jsk_robot_common/jsk_robot_startup/apps/volume_lower/volume_lower.png new file mode 100644 index 0000000000000000000000000000000000000000..d79825e859a8a9d75244f5a959421076cc5b5bc1 GIT binary patch literal 571776 zcmYg&1yod9`}d)T5Rg_%LOMmIYor_jVL)jq2}Qa)WTcdkl68uyBm@aTLZqZ~ zXudtZSO4EytXWsrVmxQ>XFt!c_6^feSH47al?Z~MOLtWikPw8+13`EY3?KYWAa#WR zgatu&738%&zOS9RCowF#ZiHevvYi_OX1>~8~T>mr!JZ+ zqvJDUgnbmYuiMScpFRJGKRThrKB-_D9eh_wk4rWBrf0sEtE+UgY<_=EfsL0E#qY~2 zJ|#9KD;h>WjEorjjnH*uEkY#ijVaO48l}2etIWw-Me)gI^Nhq?Fy%AoHq@FD;z@5p z$fBX6qjT%Y*W8HQIDaa5CC(@8anji$1=j7V#l=Oo>>;jTaxw6`{L{}!+QAoMem41V zl{!L=Xu=wcl4?9;J4cGN$nduCprLgSFiFgbc@^k z9w`!CYrZ)5PZqVGKGVuqJ>m$6^*fzsj^d%aVreX5(G!PCu;7LeuowajXx3aIb?dpT z4lFB}9DyjJ2h79X)@&EYT@3q-@4 z0Gl?1g|U$eel>e zo3_95_qC_@El#}z#kM=9WZ^PT$vm$@0?nsR0>?>&^E>^^kf{D|(!xHw%(x@AKXl+*hwcYHW|fH+b^mM%=edY=Jm ziK9A*O6eC{JYqnJf551t>d%N075 zxntvrhX|02+U#;z{;zv(#?de_yw~@d2Oihk!_?8A>XfH#eyK=5nU2@X)O#M3(mC z2=3FvZdv?*Dvw<~p6i@rkjJg0)7BH7f6Hy4dl;5z>~{r97tm_H;IdK_il2Ml>RVnB zQ{bR42qt( zW1Vs2_(3+l_sBe)5m(ah-|tN0sudiWkIfZw1RT6=Hec8QQ6fxM01IpQ_3 z-1XSc%s4F<=bIPh9$o)l>tRk@+kO9IEol7Z4pXrJ_d{INqA}JiZSx^YFZ4zq7pcT@ zW+;*QZ>_q0G=;mcXcIZjx= zfB$YW)1x7#R=w-D6Puv|)$V=0$4Sf*7gzr5goV%v92+Yvsf4(H-(k!7kSlL_dEYtd zkcM2Ai{^o|^DZYe+b1&c%LmF29afk8f*$}H-E))X&)JP;daVx6KIs16BHX@%-EvRx zBW`c`BW3H#W!zJ0mG=$|OJ{+)t#iq$F%ClB2hU(E#~P2e`zYasD(pLXvrW&Yr~dEl z&C9a$^SkgrFfM$-r5n@3GI@JMmxPv5pLIKw{!#NA4SVXm)SPpLmMB_k7#)5etO1@smZUip`jM>rPOxT|NA{jh=R!SD@wo*MI*|pRCl7wMOSz}4+~-dQ-AmxZqLtiK>z7#Nqle7O#-ngzvJLIR8!hxe`=pi| zTGm=rgHh$vE5foaNXCoX{(h0C_)2bU;iX?a6j!^0_g`egN)pMIaH`ySEe(@!Tm|dozj^|xnU5fd&8ZVj~$>E)5WqVe#Cwfo9 zS^G8|CoB^6T0*^lw&0LG!`q_&-h@ObW{|bctU@yF2Cx1rnWQkdegew+=CNlmhnq=| zA$8!j8*H`y)zQt$8VEwD@csK!wK^0LciwB{IWE*MHcv8L;Ksb3ZEa_#WMQ$euH<$} z{E^}OK*6f*q~Bh{%$WcooKND$e-$CZa+)}VeM8d>MH@=}rl$u1frpW5QS5I>%{cwV zNdftRz6Z5xdc_GVXu+~rV^nx)zjy~vtAG3U?F7f8ot&bAu7R2_%0yp-onoc&;JXdp z2dz-EzlWWhz-+SG*5%mh7h_MPmATI{C7-i`Sr1y8@(a!d7a?P zorhqjp#5IW*yO+X1II#1RngN~g9wVV(0d+1!_QMiCW3F3?wQ}eQCL)TL=|3eb~rAn zOg!-1;=fn4Z2JJ2jK0_VTK+!Oc9L@C{T7P6r`q-wKn-|*szCRYqOn1@(W8v9lFsll zRhQkHgN$c`a2HyL&#*T72bKBOP?X;YmBYCSu4TfVP1 zmuuuu!=n<_!0pISqj>0E<<6NjlKX?OsX7F=&riyX*(c07mlF-02-DI9gH=oma`FsI z@7(q|%;5dG@!-z{dH4I!YVjNk`U49J{Z>n+!| z-dmWiyhIHZdPp^Caw}#fL?rX}d&ztN6e(t=trKOx%K`6Gr7=oi3sz3Z0v9c#CRAzq9 zmBsrLOUQ>;r)jUK;BqiWgRSHQo9_hTxHA2U+x@m`oIJd|g7L_=gnk*3UISfb!mce? z1UI+6|DvEIUwzoEn>Tf1R35`}INekg#EhSQuYBTiF@?X=563lqFBFV&S`*A?!)f(x z9Al&=MTHTu_&vc*P#-yQ<_qZ+3FuEWO(gz%f+z>xSf$^^@+DY%e)pOS`yn;tF&juw zd+2E;uRIbZ=UG8+2)(VVJ5tU%@hoM9OaKfe2xxA?V?}uy(-K5+w>8NA{i>6f^O2H~ zsh6x0Y)07KhR~$51(3t>N^0JW0b0I5=n9w=H{#;CC5Y0I~4+=aG= zGtT2?GX74&Mpu;eAnk<^$AL--nVeoi9@Iz%sY|ZkB)#wBJrBvby6zL;D67^HEgNdk z&0s;B-ZLlJo7?L?H+fXAT0?aqW2}ISql^pFn4rH0p@zy6pz-0A5<(i@9VEg+ zZ*(vSkC+`g-AQczmA!1+lfZAl2Sp>#U*f*Fv4$g4b(P<+*1;e0*lH!1u{jA412gKA zyjk_5bsJ7plWe!+x!~sZzh}19Eq@$_2ie-%ehWPFZsQDu4s9G}Aaq+Zf5a20b|pV0 zAWc1~T=fJ-w5v`2{y2TI#461-!Eg17Y4wTJO_AEob%+!@pjWUt747x6PNyG^BM~Db zBR(d~s@Pfk{?}{m-5xZ4sXg84wS_>}6X*8$*i$7~3x_R;_3J!o_7)7I>RP!ctlv0E z>+i{eyP$cRnV+9OVs8HTD0xmge#WJ}*JSE0yCbdpp@}jS3b37&C7PnrixbwSZV8(8 zOGUp{G1a31<6HFA*-Up++V8B~xaY_oGWw`jDEPleYw8>sQf5|De&`<*b_va^!W~cE zb^$QhW1K%@3U7F_u<(34%AaJiS`<&wbt2yv(j|t-WDYZ%O3`fxE(`<@9z2-oP*)z3 zq2wk>9AT!vdX*J&_+g~TG zV;~Kf3+8HHRV#TZ3C%{|Aq{KPQ3zLI4+7}VU>ZAyHOk~|h=pE8Ho<;bl>N?Zf zl(uXdiF3Zxh9XWuG&cVqeTz{XJs&5?@`uA7=;*k|>2ZnJi>LG+)@$AFY%y~GaqDfg ze@&Br98zvji5mCy1~I21lO!rD<4cAtGvqL;XQkJ8PvpNR+l^d&U(x>>B9G|oujaF1 z*fi3dhoUp%2u10J8$$ao0aJf*w*}b__Wz;tWhUY>?h1A+)!6Q zl<45u+Um~t@83PP=*Hta{sOiJ8lx>3iv-7@-kiBrL+j^OBPZjtrgr>*`(U0vh>wp~ zEG6s_TEBxhvVjg0{f`pe^HP3-MPuDwi0u*^40A&+?-R3Zr$Cjcuv?TO>IN(%baK=NJr zKL2%A)i@RT&CdGz`chby8V}#bU(B*QeVG?B+4=REIZT1|yORtSUJ`AvdsDs33X;Kf zMAMSxlPbA=!9q&VfR(cQX!fo}tMK%}5G-1NZh$0TL zcEx5<68T@cnT6~B`t{;Ry+Ld_b_zX83Tlqun{l%O6JKTIrM6mdC@^ic^6vN>N+fBG z>LVC9=*(pLl+$Xq%rubC{yXF1S4uf{*QV6=yjw5fUM6cfha5UCD?2d#BNLmR&!8kg z7cMC=iwmw&kJBdRLAHRR#im^WIjDs|W(x~i=9<4f zxv)nCr9n@R&M>;upC5Bf9qK|RdZQs4(`;MjVbrDA0Z0UGnCg+(ZlB0qIS;Av=>@L( z-PZbtXMnPJihgukboO94;fQ68iiw`^_d8oPPK35rjW3ej4gYqkBn?O2VDiG^;*V@} z-C~;6?gQ1fc(ZQM;h6uK4h>HaF=KoUL=soF)sGMFw1pf17EqYJM89gze3Aq~+zZ96 ze&R#J(x2{@op#aN=Z3VdGyU5nbLv{4N?`@)2swIETe5g$Yif%u1b&x^Bn(EC_CzN5~%z2+TF*|7qmAR1ay{B&R1J~VW(`Z%gi(92Q?AX?*G2CPs~iwz`(!| zakq0N_}7DI>!GPBRrHts@EZ=(o=X$*23_Ce=hArRSMxTSPBz?oR~6yCCqiWte5Rb8 zGyVq^8AIkKfsy})wT_|NgoR5mnrh8OPBoY@ed=lyF6veUwFT>Vx-Z>l`ia$_20%W` zTjP`n5{g4w?TUjx@d-^6w_KuW?{YM(s_%470`Bh6-Q2 zc(IE$o9f&@$JXcFdWN16#F~xMQV%n;YETka$mfGVLqrq)VQe#>kEp<`J-r?&@tX_A zGK$aIsSwHX?F|*Jv5#Yn#@}W_(!Lg`yB%SCik%{Aj~_7BtGgAMsH3TdVz)mR?OrL! z*ns4Geb1~kn;zmb2bA;O19OCtd@6od{YR-_;}%@v>?Ar`h^4ix^}=H2;vC(2BKo%h z_D#!6pAxS1i6_Cl8)+H7`JH1P$M2}u7<+S$hCDA0mVS|P6oLQF^V)dz!l!~vxL-Sv zDZZE)sJ6@mJAvwqR&khheaWIE~@M9!YmaPMlPblo)i^EHn1187BL;GF7X*FpkbpvB8}=_ z6)epDLA;Gvl+WVH^i>y|e{=wy40iFcv(u|c_Gx$0%df?^yd}5i*G$g(C%5W05#xg= zugT3kg4#u-U*bkvLL(sx6o1bET|P-D*vR(7CD{u?AW)EmH-?e_K|zylGonq~mwdp2 zPc4~sPHG2?7dLzEE-GTphO$M95qIU1uAOy|C5K}{ha2wAy!Qx2?aePMW0M0JOdL9O z3+lYBbt*Qy&Qbff9RdwG)2#P~z8pt(a|Y2zNvxKn*BUgf3+p>I@8B0-PJcM{@{>Z9 z)z#A!FcPrHT)6N~rSGAMMs9CXL%W+L{q3E+V^ijKyJT*gwtkTB?cV+~BFp}v0uqrx zU1)G{(1D?6QeS9vhL9!Z7bBbM+A8*Wc7(udd0jT>8L_@~&(Qa1YIq?SU;I$**}-I5 z4I`HA6#hF{voTv=Vy-i9Q!AE?oF`rWEZ50*q9+p1h4<`S> zM~o=SpWRNJw{FUd3yRwjh7P~j`nVsFi zM%@xqF0!bZfYzIGui-PnwRmKrdG1FAsq@2mKL?{C--p}XgqTYHAMc9G^1C?O^e+Vj z_j#T3lHZk<&j}X%d{jhuaiV-0Jb6TLm;v{`Boq}M4S1q7v==b(BXmFzzukIJEipfd!OMb*ZZh&fJhB%OHT5GUv_mV zxh|!-gWtTsmji$>BXdR-k0lsy)(TOSQa1cWcslaBZY5>`r`JCeW3;)6#Bl_7X?1mV zd2_SB1}rcWmKyEn(_7xpOGSh>ef&Kb?MBXW(1CS1Okr;Z_ZfZ1yyKMDYH>`lL5(HW zDN&0!onw{)+G!tX>-bysnodIa)|Gnn4#2Hfakqw(R3T)X-PZ%Ys}F=R!^@jfpg; zGpxHL^ja{Bt6PZqOcKHzK)a?ROQ_bE+w}mK`uWJio!?=c>4!}oQjuEf;)()#<&UF? zs-#`z;*O04gyFD2pqz$DQ}aj-4Ermv#$eRS$M(~W;)yEk999(*{PHZuC8K09svHCK zOiWGofWr!2F;SEaPz97kx`oe`Oy+iOFN|A+VKmy zyl$g68i<0=RV5_Q6jW3=M={7Q(A?1d{~mjK^^;sGU>xnB?%>?FOchP}Xioemo*fv7 zSoK$qmKtwvmI##7ll-AoESJ--(1Ixmi7(~79k%v%y9-++;=3j>sn^qu_%OQa%jOCeOKC4Kjtf7 zK_l?L;{MR(}wnC@ZB3S zuZ}ouih^fpxLknOT}-imVWFqOPT^)@VX;vld-jAnAkd^a36@A^o5Bnoo;G^!zCYSs zG6xcZj=9<$!XR0!|qypM+|Rgb?u<81df=>v83E*wH8>V2%yQ-w~AB3|~Ke zRflZRQ_f`I1jypSO1>S+`VG|jJjN3xtHTOGN8iUz)WHQErP!@WM z*h=G?+dx$hm3GyRrhDErh`~tKj5_LyB~*K@;{lJ ziQEW_hjZs$xSillUsCQA?q)tF5gJ-r=8WL1@?;D|9gVkVWh`2FO9WLJW}}Yu%d9bM^MeNFvvIOXi#;gd z9!rN(-iV8;ssN;>TT9$xRd7GU4%0vOw2HJf18W;d37t5jh2~DqxzNw`sFDRjePqC* zLo?`ZYR2jJ4siblv-R&)KQVH$jP5Ae_gg)4)>%a?%y?TTU=Wr5Je-emcjwFqQb4^C zvD(l~S}f^!g@l8>;-VrNuXW5hlfBrL)q^r9;8W7_TGrNS0!nQnAD@%Si0y0w@8yv| z;_yj(x~c^Ct-4?V{|G!18Ue6RbTk;tD9QZ*{b^^RcfmA-@gXF{*wRJlm1=prg#bET zpJ%@C*vouQ+7s&`*Yn-1#*`V6g?%Q}fIQ7BwPE4#K zICqU7Z0So@zsp`64TvZ+`|h1CrF(DeXAaI7WVJP(`9SY5HQC|V&6qetnPtW|6evJu zPmnia7e9?J7l^@Xq^Dr}Y=@_!@Y`t%oQ60QeDYh5whz+xI6jq*P=7X%~7iX*m89X7|E*R%e13rmGX z;UPD5^J+=MRhr;>D&7Jx#C62BsIoAp;``=d_XQ{7 z9fT8BSsVM(!>=rSYM4#9{BLG0+Hz}<&m4A%b{L=U&|cKeN48guJvyNXc+Qb+tq`pf zcujULQgY)1EuU^Cz~`0kSov;5(`Rc>c9!V#_mOvRr;-K^;}oQO{Z4`_a$mj!3*28F zi%P+Rn-Pay4b;fO9OsU7pl!22XzWAw9+7P}!C(izUawEPjsDW0XY$^c+U}T2SC_vM z@xwMo17Qk4$lEv#`B<5BAkBQjSh?D)F^3u)u}8bOYDbv~Is48_{b^?auQ1OX^}A<- znWr)b@Fm^#+VSdQMSkwi^=MjN;x6<$RdAC58l?Ruw1w& z9c5Hy1!MVO_d_Bp?&=t!d|QVHOA_d^m*;*u>A+z|w2$n$yXBRYLo!d02-DTk;vI~k zsRY};51nL5MG_@nb)pWS7pR>L>ao808>wq8Zf#?uHMg$$`zY$04DcBr`JcJ2638CP zF9H>+mEOK_h&YpGVL)lZh*(fe3VQBIU*Gud-Mu({x5lwAXkXxgkn=u#4?(~$&$Kp>1ylIo zhx<$#1)Lq)Gh;t3XP6+7fu2krWTh{i%>y{(rg-Ph^BPW;n1=SAcwQ_y+3qsjOow}+ zaTH++*kGy4&i4vr^RP~JuDw-N2;kkmz}b@RW^^}v2F8!z;~Q6gv>|`rVjp^^%|WOp znB~UW?PxN2yX516zM<>42V1_z#B_^(3jFMOxG#TD3j!F8_E7yj9ZJ(>MM+Ex&^zBB zkN@<|#iC-^2ZNw%j@cuw+Hy)cnvFX>ygy@E95upm%a?4 zv5AQZ@r}x8B%Z*>$QTs`fLaC4fs|dz+@c8&wTeeBjCb)QF$4kQnEx2Kd;MqM$C@6p z~~~waxiIsUoYXCHWyX3+MxHV>Lp*OUlNR1 zHZWaVetnLmuA-Gb-D*Fs%6mxGTOOXD9*jyrVz8Owyv}DV1%BnqK2Syg=HGaF@}`b< zK8(g(jV|lrWYD#>4I|oISYzBV-OO?6Kr_A?T0NuNQ+@&AizTNum#;y`a z!Lxj0*Ug;p+M=!7z84|O;N&F89Ke;8mDd6Zn3i$2oeV@o3Uj;toL%=BI*_D=ucd|uEW#i$COg>)hd(%U86G15QtL2(b z6t`it2GF&ESH{(i5;xO96ct3pQTV!DH^VIftNU->Bz>f1FZ7s>rzuoEy z=yjQ6Oiz|aef2+I@@LH$mu}r$u-OZ z-;{NFkQA%d=ld%wgsCk=W{-u>sJ>EV_L^yzi|Na65@yu_7*H9WP{Bt$X5`KY9;|d0 zq*qYl9Pw>Z?%kfk>Rp|7RS`*>yVBIcFDJ_aFd*s=J>6BO;c^Qxs=MBnt>D4arFCEW zdf}ijDx9~Z7EXH?iC`1}XcF)b_H>_}yW0Q;EMT3&TJX5;zi87n>lB52&Kh_7-zAAy zsZXPQ8D;J&uM~yyEdWAxaNuTYM_fUE=}wS5_mJsyqbD7&qyj8U@g*|5+k@rxo>YB9 zLnlUM+-xHj?6aL|l4gccEx`D{V1+(>@WAM%n3%^T=!!bB{^zGI?(Q{H!)N7S{ZJX* zx&smEDdInJN2*shHxor?e0H~T@5T-e4aLyH$0=t=SX!47A(`zwL0|6MPrkB`jE(X3 ze9gqpNWXXQUc?QwaDBfIKZ;!O4Nbnr_EtNY4NIUMAT7kySTIFK|vv_8xl>x!oeHlpaW=nogIlX}))TYRmwz;v9&-VNKI=Mh&VG`4Q7g&hb*L8e+{4OA<^(6@}+VJOf zfFdrYx2rY%ke`p=-rn9bMe1G0cqX?e&d{>se^TTBE<@JeFY*yu+VMe>S?2~#CB3K} z!)`rDC{&qulb!&)H+L<78T*j0C&L$hl26uxM9hKSQYyCdiR~k1|A;QfrO1~G3Q>?h z-Oz%=K!S~e$+iUgX zu|C9q0PkV90BC8uOjKN5PUPJk~LCrM~foga`%KOd$xPoZHT@ zv~P-|!07P16&YuI^J4ucJ~RGx8eD~hhv(VY&hf~n%>XVayScb17>?noVF{yfoPR61 zyQ8_XOwUh`a)JqF&=I&Vx4hc$bp8FCAK7PVw7k3`0zu&QJJu#Dlw|`mh1S;Bspmf~ z%Hsz)f4Mcbhb2bSqP0Nf1I>aGx7Dw6ve+z;*)Qq=!4p8zsJ9HC{Ylnp&epB9{I!SJl&PhCSNSj>Iq%%IY4 z3?94NtHNDo+Kw-c#|Byi{LR+ zYg|^oJ{@z_eDEO8P3IY%&6^+8;;NiIqs0cMMABzxXFEU$J%R#eu*5DckPYT8U7YAV z@?6Mq|KX}rUR?ZTz_Q}l5t!n%(osO7p_1M_KK7!vOS!>F%>FQGAhv_VYqP4lnx_Jf zolimI9Cc-!JFf$b9qevLB{imPsZy@o;qfShrP1KAUF{scLe9|ZE41@<0$rbLO|~)T z+#iOq`!;h27M(2Bg3~DBFg`$-tyDD}=RBE8>VNapmJn;byjByuQUYthFAUXha4XJK z#e&54N3`~1Cg52CqoWVYo=w~!At4C`r)CiZFSaq%&<3k79V%-hxW?ZLK!Hg4#2S4; zhM(6r%$m%UnTH7BDBr`gJlNkS++9BCdn0n0hVuCMc+c&oan07j6%f1iI(yExkrS>{ zf2k_yW#WDL-X$mTGJqb(OMx6=3!Rh9-hm9En2%F_AgGZYcYG;8q+j;pGyzm}<>rZ* zJ9;iWJp478RO81kFT1&QT_dAn$YeNQEoReaNfIWFApBrgv%{~tZRTFVUn`9<#QxV{ z`H%Ug)68t#%Q?CzI8-HTCc5O8c8{dukRXe~8NPG9t(aj?cdXcevygn-ml=eOzM}8< zzSpZzNg}wz6Y589oa*LAV#Bo|9+I4 zum-)7E+356*)m4r=1uJpRyZllS^D{NfCpkM7DhE`>p6>{R=G{yDjlL~@ zqwj?OmPPOlf#q95-KT)|>>nS!E-aI5O|`#08HB>nwf_kb(ub#vHs$S)s9eneUs25N zP#~hTBo5KLmYj{t-(WqIoz40pn2@Jmwd{GmZBmWwVv_k*x9s^)-NpGy2-d0WOVt&w z8sCg?N~~F8sL3C2nQx;bBej4@DuUj5;|*2HZCf6mAW%a}ubA^}g*|s3laP{zX9g$$ z&^fefO+@;OOC=9^vx_1vEzSDL6D){?jEva%hxxiB)!v)Wj}>Z7R@c@lo4~q|_=8Y+ z>2$fpJ)N!OIIS&lL++|mFmj*9AT8sO4cE1A-o9RBD>oe}g za!}WCs48~?q)1)mG88%@d$w|4krL6SrPTM3{5$89`p}63#cVu6N_NAw$a&UZmE(CI z$orEgVh0SEJbV5kGylbnbS^9tG^fkU_*?RL0ju@3Kf`%vJs)Y7(b90VtuxHMBm^_! zcTvIbww7|fKUE)lqc7cyf@2xB1(FZ@wjim|0aVeqn+?s)#ux)-10ZCgF+=As_>c&P z+qPL*H<;`#isq@d$fS7sp5NWBY zG!$X4H#!v<7+3|=lf+d3d*(< zNF?G11%*HhNaeXW-X|q7$?Xhgdd^L9+!O^undFjgYZ`Fad)=~Z>olsZE9p*m`ol3` zW>^t}1XojulZD`LC9%Xd7eidEQVm3FwJk>c^?Dm>JK4}zJ)UAn-2cZp`9t+(ZF;#h zpqAIy@3|~0aBH?n^=zKV06j)eek>%7a`7>#h!yKvQl_hB7cL_fUI5Vg@s4~R(Ne6A zmC}x2!{IN;v5kz36iwp*t>OCZ%{j+vn1tQJTiQr*1SD2zuHbQF*tWhy%16dx@dVv6 zl9nM1UR0FHs9}u>{k^#7{kZgHR?`dY#mML=jfLK`soKi`LsVBkL=}V$o?A-@JuKG0h3FHiVF}aC zOQo&kpZxxvijWXjoWt@YQ^IejF|Nc*e$nlccjLlszS=U&i< zPtibo3YT|Xr!UoXD!^#?9{$yacl(bG`Q7hzZ>X;TOrE*I05CbP@evV5pYU1WH4fZ7 zF;`y{a^?tPtN$)6uPnoD-Ud#OL5=#Lrk2-6f<;zEg_edU+$?ydD|1yX!W}amuJnNb z(7T7lZ9s_6jDy?Tmx7qW1F((mb|5w&57l7n28F%BhDYtr_{=n;dw5Hq0cor5?OPtx zde(rnxx_i)Jdi0dJ2_Yfnc}X4^~s@;5$(s)q6Xs2k9hjY+^@p+SAc{Ux^Awu+uYJ=o zmOcXN$&+5oiX)0ir;&3e8U}zFfTpgsqh3Do{ss>B>guX8A#G*U$MfUW(e;{{>6wv{ zIGpHq6(EyUa9d~a_N9u8IIb4g9AnO_nwD0qa#UyEHz5THP(Ke4CfN%F`1lI0u2rlo zIpyU@O%t9l#yDq9#3?I*(g!jwuYsc`V|MLE@a@Oa9C;)C5nJaYU%zHUv!KVe01gz1 z@lwTp7v}68*gbioIfrf{$F8s%c-XW#Kj42ZLc^~g42D;Ni(&9C|8m6|NGxmY9m%gY zfgL9Y*5l2XFb9Li37X4xWB?+VV$R^A(Y9wj?@~v)`U*LGwx}TeE9EtnLa^;{n6%6m zaM|dbZve$X{^KubZ(Kv<@T-g6;N_8$5`iBAF5S z3fDeKYrcKJ!W2c!Qvy0~cw}QD1!JFC*hW;fk*)1|p)YsJm+&nM%X|Plt7y9e+B1 zaf$vXU~Xih#4JtNvsYCOBL=OY(`7)SQ*Zhn@44{A0~rs#K3;Z5P(}Qznwr{pldpG- zkbLj6$!fLc5OAP!03!{bj{Q{)xk(87%#8hfv7#%)NJoGB**MDFfnz3Bw1H6%U{Z}Wwo6CSp8+9s3{R{zIRYLhd{&HjrHhE=GFVs`y&Ds z9G|Ytc}^!q67rBNHx;QpH>9leV+jV6PMNczp+RwQz9dmpkx)Oq%QJaiW~Iyyj2o|E zHPLXqO9`}Z|h5xUkeV)8etO2LeHE}qfK8thz2 zHH4e8i~EbdW22*y6dZl7TzRu%kc^2txk6`hp)X+Tfi4 zbnLIcd;2!-=={LfxF#*yLw@o-&_3S05#Hb5SDbX&|NSi*ncdX%=su4yqapww^>`MY z;ne!LPk`2KnUsGtamS9>gncqdA@s+WY9Tzy$!f>lFQTi4#7=rIIrSUg5VB4&VRAee z4XCeSqr%yKiqhOdT?$;x`u;>2(nxnxJU1g5*O7b6g@u<)M8)NwFOBmy?0FV7|I>JDENo$oW30t46A>J*N{Ba+! zadP;waHi!wSQux?YPg|*)eH!k_`*Xoxbx00Eig+Kff{E94XpVih#vr@cFP4fL znPv_SAC@I}9`7FcxXiVoCYeA&`}fT0qG+0YR!t3Fqvr`*JktN72B;-h0QYfT@dP$@ zRYM(b9vz@q60)PmZ{NNJ|Asa|MyD8VXS4?bc7eVVVqs(`E7b!pC2O$S@!520+nJ^ zIUDDPB``4{x9Ye-V_#oi&HnbTSM;s{1>);>U|AIc!Q}Odxj8v^7{QYtOWzN|LfHc= z0az(m#Iyn(#Da|h0B>?@6=rtJfatz(1wY6POwjCIc^oN!Ns`~Jj1H4LSZ5W%`z9(Z zAB^`8^iTU{#4jX|mc8o>19$^TyV1~-^1-%&%cjlMNII>(F|vcWex|=)-S-IClP?x} z6X!vzQ?{}y5bCDHW>Y8Rfph7Axw*HuN2PXUWqtjdV*N_owZNd!d#&*|pFAfD2G9|R zxL|e_JNJuQEfX6b2BCo^_}mG`k&A~LkbJ`eaSHy-wgI96_22~g@X=7dIKkQWFzhfB zwy0+`D@*$H_{Lk138*tv*GRHwqq@&TQHfB+w#}X_jkjU$#5zWRz{;bj& zWoJX973eGv#Ql<=K*Zmu2Z8E#Fs{-ChpV$)bHUvJ`g64Zh3Gj*9oE-pWo5~s%I3ww zaq%f0xz&vGev{GC(_0z#>O-ggPkq8fI><2T#VbCGZ>(<6J-N$0DP#KB>r|iHb+K+K zUDESlZK7me41`&DKx0?s$oVu!5!FpCZp&rP7Nf#t(h*1*)g4cc{o}`v!oot0B5j1W zwl>%Blgn-|bBCWOqP(@VD8H^$-ax+sQ%sTcK3*@h~eR=8c&IG$~9Pft&F&h+AX*LQ-v zxTo`7uP_(ktcuBhvO+Wb&e4nXh@vYIw1Vl60BZxpo+yg!daIc`Ubr?--u)Ey%rXY* zZI7uLV3zMRUz{|L!B|Ql2b>;}Zwj)PSb~9O)%Eg9F+f=6o4}J#dHVF}4uU(aU0(0X zqRc(5ySZ@^Q*qxP!YDX`(CR}sEQzU6j!07cAIuoxYEnr;QgZ0~_i(^fvcs4xAEB;% zeO429BVg@0Mk-tWC|pVt@hD+}zB?poItv48#()=%G6EunxlKk45BF z!oGg}ik<19uf$H#3Z~e51G~CBW!SbPRFHMr8s;_05&IeM&Ye4gk3ghVD{*LC(_Mv8gW&zE7&J%;&BO-Et*RaIQX&%3ga#Ds)bT+T4`9}gR+QY^6f|fiLDJ4`R+;wykp@4QWSq2bI!tU-eB8XrtL+ z@oKUmNgUR@addQaiPF;6@X z&p8hd&*_K4;pu6n1|ar5ykZw#j&DuG@_6v7W&_aZPr<#8Z@Ld2#B;_38M1>6GI*B& za_os`4*`l;^?jZIa%V~anb;8!64QhBqd%TG%0eNmn#Go;POH`ji=d2)7#bWD$`6p& zy9$t6PHVqq%d1+fZN3y2=G{Bg;00ewY*j0R2sQwriIL`d~cr}Q@G=*z39 zr$kg#J$Hu{mPI0_Xu6sGLCS41pEU-?0PlM%0mgk%vokEWB1P zP*VGoXgw7Q;7s>`2M_PuO{KFz5J2yZn;#`9<9^|0XxgMzTUuUQqgvENJY4{|tcU?z zt1ttVa=gs;p~9lQFG&bRG=m-*8{-5Ofz5)8k@v-)1oVrFiqfVPbVnod6o3YNo|U0q z5E1UU>y<}U{cPfO?QXwh4J1a}a-kZaVH(a%%bRC+Hnk)pY6EhLdOS(51`+&n(a{=D zElO62^t-4SyYz2!4Jz~EH8^O2wh*IUPz*G4cTfxl&FGJt#RNiC43jFbIqXoeNN0J0 z#D)_PIsYjSE^xJjyymu-d%-RC@x*1{yq9P4)s>ZxnZ4J_A_0rchdMN-9Uf3fmuMl3 zd|UBo`_hEXm6Q-+z^;a|RGJ4LXeB>|&*jf?bAn8Oqu3Xs@b6*?R{OXCdmUc<98EL zoZ(6Eb)ces1Ci7y6fv#Y(au6N^63!k8j&Q%`yCp}3b$ycqBf zyP3S-^H33C1di=4`UqTNFDambJl3?tC!|@t2y@VPNC05{lr0TVU)hrbMDBQO7~|X& zVP>UsTlG5Y7%u<4V#dAa?nBv%pO$u^fGV4@-|vYa3GE7y6#1@1a^)NAupNu2r|zza1H+>XCul+#_n zZ7G==v(9imKyQk)c`WGX*}mzbl8>5tEGz609bldOKXavQJ29-Cq zY?d!bUP-L4tZ-jlL4ars=uFgAX4(%Ptk^c$PTpRx73xkVV(I!)3uY~V9$UWtaS=hO zG&ePa4-&z8C~ks?nrj3|(D3S%jAVrTY7t7K8DTP0zsyZVU(X{+x>Nv%{&?eD?q>TcLf)1UK$@-+-0-aqQm6Yq z-~z;`tV_3(I-q5KXI@!xaG8v5AbNy@djAQu*R8@vaBJWLcw*3xF!cviU5ulNr}jq3 zKb1fWANPZ^wzaXbv8D<~9Zx{aXNHk;`PD06#}V8=x-c`I9~lh^yKfj)dF?+P8Xe8| z-yC1UfIyLs!@6U{asUw~NMRHL~xjg6zGryl{1C?6PqlR5`@asEJxHlsCi(Hz6L z-ME7~C1z6EkE!C2Gy%$S$O6Abk&HJYpl#}KUoRALHPQi+lGhs8Ml%nO+FT9!#5^ST zN`1)<#Sj+>{wHZ5inQW#6?_8te1jqkTo1VYb{5!uId*Kp8bHPk{Q-iE^ugrHSRPah zpSK4m4}Qho_nZ0I8Q~4?hmOXnayYk+yw2`k^h}58Un$HyXlE0@*`JRCdjTBxI|sMIw}BEuv+N>|0HukR@A5ktK>ErBFzvk|f!pC~2WO&+9(t`}^ZL z*LCVFU5uH}{a#+%2YsY6eAfHhj~~l;bZmC-zSh#h9d#_Tqo%sL6kT@wlNEEZ z;XX?Ez9-pbY&)eK@!YYq+0sF80^7rDy#1gHW!-|1J2xo$59lFK#2m zkV^gfmgydcmBZ3D+WI;3#4p9}DPm`lvkpfoIQYg9Y&!0z?$L_6U%jIFtOP8*5eyEN z-}IZLBrcEBp7Ph-6N$po7GOO}=F2S@)6mhO`nXbgDWJIdFd?9!n1JyC+FM^Q3BvtZ zfr-l5<aX`6wwSeyGx2?inQT^`5-RJaEhJVb>Dc$+= zDd5hVH*X@tRL(X87^Hu(+V~_XmoSs6q5tgvG(DZ#_w1RdMNJ;H2mqvL{Ia1*sW#hZ zO%%bm+AAeTLly1715V6-``tO&a#aD#>)iM6DSV^a_Y8e?wFV1HN=nQ-^U|zH7@QVL z=hAiPSLHvv)40}uJN$-`)m8rw*9p?%AkSKEUL?8fYINpbUTxev8{qG+)?Pz0YtfmQ zO>gBY5{2jM3iM6*X$%UC#Q5~OS~@@HuNMw-X03|Nv`!2v!(yuJt#-1g%%n9O_2c%VrF&JE4#kY{#32 zhNxp)E4OQ}3Q4n}w`{U0C(ChRp5Z1%X!5uj<8vnF!aNDe=+X$kVGZus>p$Nu9J3{l zIu>y83SxA?x^BwJA5YPyMMIBJP*qjs6FJu1jRc`HG1rd&nap9to#VK@bR>Wy|9xoN z$hqBbMdMA1JrqmmG2GF3yxVPsRPLJoTwlbBwfh{;$k!;g@lapG+87WJFm-yXdU!Z& zo*OuClD&MAHQp#)2&f;)@P+IpHaz!Spw#A+RqK=b-mlHI@n{exV`}N|-|q%H{F<&D z{U1ssp0it6y!`gN!47?a4dHJZz?!8av*BC16bxcmt#J-2>n?kFsjh7~Ai|p{5#pwo z^WuFh%^_{FrSp26S)rf1d*1lhyCVe_Rx@8>nJGX7wTH`CqR_8C(btH(buAbRiFV4QF z1su4bpO6YdybUP)Mc1Q{t=%7lBC_fFBL8AH)e@^a_CWjLDMKg%|HZr;#f3Lxf)L0ADQA9@Ejy9iHf&zfYe)7F|M*mZrhRVd z;M+GN)ajGOk&qpiKEEgMwY7eYrvf&TezI3{N7E-c`Ip^MpH;}!_zrwI@c;WHurs>}A-|uxb&l(6<7ybOEcYiqWVy=kWSVILl zA;Pe+HPo$f$>~QQN;_z6^5hF@lnvC*U>~1SbE&m1<^UirmzS$H$WYXoKQ0K4fepG0 zZA4979lzEAtsLt~UU|`W-lPxqQ!gtQHP1eG5 zRB>Z>1NN!Jsx|O>i;XyAqd!5v=tjUme$7rzk>R#01g;*1w7Xq2>zuk9W_I|^1-xog zx?6?75aZpV4*u}yU;lq-V8)^oo~edAvIcn|28m@x@bIl3O-9WST@)E3mA(g+C)6W3k!a2>sct7d<< zCSc46#^&x0^~k|C*s5mmRme0Y%RUn!hghg|;_`m1ASEatwizD*cF+wXEF_2KfRR!d zxG5G!V7+N%Vb-MYDsy0hm5!EPnv%lFW~K(xI~Ofl^fXes$A`_g!Q=PLGQwegFcBh~ zp`oFlhnr?|o-^VCNI#ELw<$-*tAAUuV#PiXCCA6_z-(5G0cHd&7z_pLFPwEaWFxmV zB^Cnj1O4J3lCJx^=%y%8Cl#_RpQgLht@-nm{11&-|auMPWrE+Ta%bQoIjNFN|2=W};!FP~dfSw23uByml%=Z^_Jib_k0 zK#*;k5PfXo_{)5cUDjh|bBagqps+qI`LVbr=|hn2c0bK6=$_gqFO`*TxxZ)a^PV0# zund}Rk^oJO7u%PkCaauz6bH7QdPM6`9M!K+b|>Jyo0-ZIr_R!UmDR`g- zS58UUO7HzxOu@kFi;&($%lww*i{Zp+R_M$SoKJ5ghFR8K=ovxKZz$5tlZ zXVn||4IuI9Ssi~1nVZx-^6V|$)9`WO=h4!xNTW5_0?Xl_tSc(=>fm1HdR_eP6tC#& z+ySiXYwHHW`kNVXk+SBzH%6js{dLZ?7|0x4h`YbX^pkw?{ub9$2VFikz6;Myv%72} z?*aX9<5w8l^gTs2k1ni`U3wRg$FhLIray15fr*~Q@w_3rOaH~ugXKTU!yU3+<*Ost zUr>AgT@JI|tACKr@s0rK>_=0VMfht0@)>;w)nq+d@;Wh`{FoU<5sH+hFeD15`T4~w zS_89f&rK$0bzPYmNf}ORza?=kiuKyeNB{hu#k`W9BhEG}czTGnR z_yFJXSPMkf#i9$?Y6o5dr3*dyt5@+z<|~B&lq?6z6-dy>z|!gf0*994f(s$_^=oG} z6)t8zh2j4Ae7ajR`e3*i_Hhe~cpPV83mQDb;>kOdY)=-)Vo^c7g4&+Us{ut{VZV(F zbDHwaxIZ(aaq!ls^73j#d&K#;Rh_HJcjIm`--v|lX6xp&TaXR&E%j+dMMc4PzVk1L-DTjt$KN>Ya>5w8 zsT7%Up0AifGSO>#LP;T~xN3q~YXbcImY+2yU>%ix^2?JG@=Bk5=F|FiI%Vp70c#>9 zuVYJ^#C~TpM*#Pw8?i5?+W^D+{p87$R<*h}RkalrpNX2Ytiv%c75nb*evt8h0L@P{ z0|b=psOnUhWb!$;1)7xVi1ql0-i=d`ca2M1M9>0#p{Ql)9V2Enr@Dji|6&*?Q(6mc zsBs6@@3%UyP5U!-qs#j<;GK0|Zv>@Dx2meXDiAK7t(fDwIw4WdX4}Oi{?Z6h%);*E zT>5Bimfco>6JbOyyE~Q~mR-dwR_nj}T-Vq?cK|6$L7T;% zGuUQYXd6)u{yle$H;4t!W$%qw1!K8gW7`d+WkTx#CHBWwXsy{0Y&ia{B1pYcV_U<4 zBS#$dRXPQh%zj5zULqjiGt?|~ZuyfNvO~c32}nx3tw+%l7gDjhg?XDST?!$q2?BidT?P6 zXT12=JGI+1Q9R#L%;}RPlj?h-D%#e$i6357#E-8Z23}8WwSB&n#sTIuRB7YoQ zl`o%VNl@x_w466w#zUTS+Ec zW#qQTEV`uK$!=RkziwZ@Wi+LbZm%rM2O$T3J~;ZIYiyRu#X}LnM!l6!tYT8UUc>T> z$Du<)_*Q<{P3JXxy*lz!iuyp|qeCnesau>#CKmV*y$lc#9t&c}1HEp4oK46AQcG zfP;m{lWg6DDpm71*%I!76fSc6jWj#xm%0xNoLI}vZ(mK_nGy3P(uq)j5dziBs6S3M zw|ezSNfUYCK9A*{KFUl<;ZS%b5^}-LULREKXI|24L;5Fz+!u*qaKuVSluGN)Bkgrk zCP&fIhG>5s;2|)|N7%(qq>N8a_EzxruJou4#ym7Y06Y-foyZXci={*~GLwV@>sR~j z-#_Oinp?(Z;LR4N2GwVmR#X)4`Y!Lm)KvDVx3iAltEsCJEgvaaPZ)Gad4a4FB5SjLExnQuBi1ZpAt2!uWR`FKY?6U_>Na{-e$&+P(7 z@MpdVLqOH8eWr>O$fsIFpYz2q^Ct02nw?5}*deLd+U=mz>)ylQ=yDtm`HR(l&o9dq z8XV;FE3_@i341Lpv+%O*H-Lj3N|gBD7o0ZC{j_i1*3Zhl81LnD?C{~k?-2+QF#?L& z_|C0c3woZMTXd+n=B-FaOEhKD;UUv!QR+_52PHPPT?3SD&bu&z7!pr(~*me<96QFv&g;O+7 z>?z@nmu2sxUtEC1_4(K%-?cBE3GrDNeZDy?N_ul-IQg|lwmyh&!kPRlG!Zi_PcA$bXY>WOsQ!f&@}0%sm1 zowwI-aS{O@K`lyq>|Nu-LHbaf_i5u3vfsc%?;8auX#8S|>oY6j^JJg4MAs+L+__@d z8hkDo!9zPX*~r?a%VIEg5c1Z{`iYMBwaUN$A|fk(u$GU86>D!0l9n!5&{4vZ!Qk&~6yNz<8=+(^nM$8ntp`dw}p0= zZHE$i_11VnV(wy%!X$qg=T<#vSC%4g(>T6w*U_u%vn)rKG@D}@f^oz|KEKoEv8#IQ zp%rlx8D!>;IZ;uHsLzEXxg`c&B8nHuj?uKrpNmp0;>8sW(lmsP0`ycm zJE9Lrs41gC8j7EFwy#<@VdQBgKnqUcCh(qr2W&0j zi(3PfkG6=?4)i|=?lRoTHY6Z{lPPRN;Nhma6zv*M;MU9_8R}7nMOlsr{dl9`y-PCL zK+09mzxPO3A{zIqzyAvV5ir~*bl3X7);{pMx(tQzN9((Hd1U1SrBK4iuZrneRIyUT zd;ck#9T)cN}FuiNc6p<@dnnHkU zswyh1v!3u$R61$PfbPOtciQaG`7?;IlhDjcy5zeeW!R=N7L4%x6rkB_pD5Yk}wUFGDVnTj>`0?apFTiot zf8W(?$2WM?6*;Qa@uNTB&Lk-k5#&TE)(7pmUc4M05Fc8_XU{mM%?1k$es%0)8{?W%vvN+V2+G>;ogspZN&BG3^+>_G%v=AFAIc zU+6D8&aGKP(HuW|LTUvn*>*x(U+L2$Zvg*SgkRiPxLyadX&beJVG$2v)%upI&z^@6 zn3frI^>0tPpUGULPnaJe9JkkvHtEGHBnCa}hch&HIrS^oVEHPL*JK#ETC zgcD-*vX$R9oy~ySSoA}K4iKB6g{CLDq%i9#OjJfhQDATJu$~;Bp6>HFuV~Xv?ZH_P zmI@c`uM6n&$gGZ3J|nEH$NszlYb}@;lD>-}&J8)DGcn`J)vM3_rBT#T8{~AJUe;1H zzn$kR^{m(;1%GG1rK#Sb{W42zj0_oKLB}$4~TjQxPyA)y#C;u zo0>;*locJdvMhI1292~I{Y=oZ#ByIT>1=j#Ydwc4XN+!vg9WYgOLmCc&oJeo-+YvH z%r9x_sgWNPuKn$}^Sh&wl(PDU&6midM;BrPAXzSi_O^GlHMLSh<_hhAL`x#yn*F=h z!^h!Pwf9jw;K;$n?^HLrQdbbk4Lpdkx$Oy+-{T%1?SKX)oT6uboBU;-J)koeH||ih z>#iz}W@Tu_kV#Er;VrH*@f>WYq3~SIRfWLIUq)iF zyAz9^5rV|Aa7-J{ca9m7#$}(lUry&dL0Erk5=i>9s-$rt>+^~Xc`jWQme3I(aC1iM zc4Tn#iX$PVZ};&=>7#t4HmTsw%w9&=hBoG^nE#U=avc}{w3;U-Yp3wbQ`~=U68ghA zy}oj%O{T~L!g#$5Lla6A)*92#yne%^6G*%gvzh^2iWA*%H9A{V(Tpso0ahsoGA386 zSgv?}wywu1j|anF3M}IftiR%7W?9mDq=iMJvf5auVtAd6R9!y=)fY_CT#&ZVtr(Mc z;%Ud{C%-B)Y%M(C9Qo3Z#WY;5RgKid`g%*Hdge=3SEToyMS?oAkUTg^Cf-LpdLH|y zyPism>F*NYxxRZ*F@>jQQFpOeA-2cJ4BUG$7v;al%t4 z8F9>CFUOnk3Qs)k$6I&r$D9mjoxoWrYey3Vy^$ z6F_%b_D#|iW3-D2wYNoJNU?{>T1=r4UYBiWqW3(#w8i;)Uf(Sw*{A10z>045EtoJ2 zhWu34ownc=Z~l7<1Lm$Mz5$W3Bu*Qzgx)X?M}UJ= z8!)&l1hVR@MuWtU!TR{oF9+{OI*F)~TC3pXd0FYngWvLG9%{deeywj=$HhxQ?c_4u z_^7+XRecpx<_E-tY>IM=6NNq`pDfcOPl+eD1v=>EWYCA~o>h7D*UI+DpLyhyPbbUy zaxT_g)j3N)c_~MXe(k0>jmc@XIE%xMrsP@asCVYkfq%Z&-DwmQktoLrIkxb0>zb%h zLNLm7R2@zKWAL!6yMh-{pSp^QZr)BA=rG;Bq^AbwWefr&Rc4gjHschfK0321;BO0% z>7ArG>LxR8FUHH-Kf`x^kF2RP`1vlH=h^e;$rGjIdd6=zmBsp|IR##^r%qvKKl=GR z6zQ}792jVryVIVvK^}58S|!X`$G;Qoco3$E8|dCa^uWt4oP4~zm5$|9<9m_IiAw3< z@UwY82cLmbkNmj~V23}OXXm1C3mcPn%(?YF2Qh#q&9LRSK$6X#*ogx2+ZD$gH)<3| z`|RV^HSG+=STrbAzx+v?Y|lw9e*3t*S^Cy*tPnK#!>h{W1fmJy%@5=$ShIytMxJ zm!4ZwY}T13x{WwqcZBbqn3*(+xMLd+e$j!_3QMHP%%=Li=EW1axP}VTN2yWDU!wV;&4{TYFmJsta36S;Q47McY z)q<%f+=0lQ;SxXQp*YOnejYuS#4CoTUyz^A0r6cyMMVl@vbwMUo|w8AD4IWo$a)ZC zdE)X9ad}Dc*KLGzn?T}_Rfi}fN<5cqpP1+o--cD3fqU3K5M6_+*&*cjg*-oh-?1X$ z&}1z8G)wGA?y`l}RYqUtkr0r-6kNmLru)9ShXdyixPbf8315e4>4z{Q0eSf5@ zgHEP(oXvw)>Z+KmKuqaSI&)cxlZjFW#kY}oqW?c#|NQR4kepa(U~e2r3IYY!_Xdp4 zo#SAh_F=|54D6CtJe4vjuPV^3hfW-f4D6<_kG38AN+1QU4;&ZTE38ycv}JGtW}ntKj;S!#bNVt){jTg6Erg~C93#K^_% z4{5f|Kb=Mvnq~~TI%{XtIw;LeSHZBz+=iW`@qG!HgT(v4ujhG;x^PX)_&t(Pa^T`z zY|v%jyb$rMRk$sXji<(h_o9hOU+8vtFQywR!0EMjHejax3Qdn3z82W~8AajOW~dOL z8|a?4y%W_q$K47xk0<0#`q+u?`M6+&^3B%$EJ}jRsldhbM9wE!Sb#Pogje*! zaa`efaNu-yI`-(tbB>sOCW$-NRZB?#_>TE`776@U@Q=(hcv&c4h~cfDtk1x<`bm z#i-erlfnXSPaM(x&-F%FIDR|LDs%H8=#lXx#3nPG(vhJi^3C&csN27ap)w$4Ih9X|1N0OH!oK!Qpwq8yE3agv z*fC;s&la+8d6bu>fGBczA}gk?(pPxvq(YXnm9XvLsEu1U2tXnA( z^2>1#OPB6>xZM0Wkz^ zgOvp8O8O>? zCBGq>ajH&H*EdL@+5WapPLKda_>sjvKNGjZ)OJ4_hS;2aL>Q0g-7ofho#TH6{k``1oKKO+Hl24 zy7t}QzSE8Sqs(zw@43`AABU&`uvJ}NTC}`DV<9Xm#($wU%Y!NDHt?Hy9=DtKJ>hr6 zN&oxz*r)3_|Kf;Sd_ZW7g$QeqB88XGLb~X|!2sClKDglOcN?GZlIE+x6s(MMvbQhn z*B+11Is+kc!m&$yz3b?ExO7*Umr88Q)L1D}Y_s+)m!SP!@~(YbCixSxZJ*$DB^=!3 zFF?1B)^HQi=D2rYF0WQN$R<<4a8dtl9NL)N+}s2roNhI&N;A(x^!^m_9^kOu{j+6R z$^}H&5dO?Z=8Eq*t|uwXv{0o-9M9PYenj7iy69>I1i5aD%}tB;ZI!AWU3)dtA#%LA z06S(jp*;JmantHm(?56q&RzTGB9awe-o3l=O_l2LR3j;tO|gzG#QB zYPkC4O@b6ZIqPZQiP!$&E5GyXl;yubL_-JjeF~?+RVy&i)Wc%S3|i`lZfee{7VTq4#xid z`)y~Gnt(}!RP(F9R zeOm#TnF!)&G$2VG|NX^t)baYg{~@SDT^V&7^9T!k^~NvH?6>hQpI!grTZ*i!&3B~E2nr2`k&Q4empU&zW?}<2#b_29UiPU#P_}!$}A3+Cm$DSPWAqj zt)Zptqq!N70)*cf;{=)ojy>EzB&TYGZuF_(<@WC;FW0Wk5L#;{XxcM@5KCx>F_q!T zgu=TtMp=a^T2SUMh7r33xaHdISGUh!Jg%xgjOauUa9 zTDVy%uyqt!g%f|UKeep$63wW-^&u0Q(|?dz{d5#$Z6!@SapZ9uwa6iNOw2G$js*oW zwMNQnn#?ay^kUN!vi;sX1A+FN8t0bO1!Yc_cp<#tmyY{QYG<1D;E%bWl;QEYt+eeh zV)^~i;3hB6clLX2esf)`sF8Vh-rRY)Y>yr$SMrScvv#Aq9+O7S zRe`UZcM81VI+*Qi-eGP%1aD)n&l@*uzM-CCq=V+9-{zG#MZ2-FvSaspZIud9uz|u* zsA-fOvC;7ci7~8m1bMjJHQ_eqqebU-@%4ow-Hp&qft$tGtBxjOK^s;QkvSkd92+BQ zq}TX4iGy4+g#`{$IXQ84*EsB_bTt_U8KJa%G$mXxn2H~WzWFxMEJ5C3UnNU=Z6l&C z0Ab-9VB3K*bOq#}64KJ*qDj0PcV}3an98RMVd}(_1)>XPMnds|29f^Qdk#FA8U8z7 z5i~2$kB^4;*K%{aj0WlA4C3)dN=An)i4e`7ezwT`MwY|xl>L3kFw(|J~Y8*#s*I(b-L>?zd6v7rVP;c=5=knjZfZdF+{25%l|}n9wooExEMn>=#;?(wQy0 zX`{P z<}wcZN$E{9I^Xsqj`~_q`Y;GajNM^iIrb+5Vr}vF2EP%l8j1QB{ z`$A2HT31iZJ_>aM4uKCFY?1LT=0#V}o?#y2rJS9(5#i%w4$q7jV*Ks{#RqBzG`!&2wQZfbhAW_@Vlqx2jfgNooB@Ho z5(gM_>!qF#y&*gSM9tX=JQo z(i`eVAa~5-*tA13aWBzn;d#4za!{MVwAxw+7X*@h@I)>ydC2;1JwYC6vg)_PE*j@R8!O4BSD7B8V${rVqWnz`2V z)WKO)eRubb*tdA0{n2}=dDbExKta^r1Xr>D919<1Ai81PQaq6^oUfP$#gy>Dxx5{M zeqT_(nJsE%Irl={h%qWaM6gldmMSr;i~rSLpo17h$!A)Ynpz(kGx@ZBDXF*)JC+zw_%NsjAm{?x-4Vz zYt+TJn+PdK7^Z=WdbB;GUmver%MGxsdpSAgU~60X6&rP91Z2uusvRnIG}~-x?>p z5v|TCJIg9Q?hq$6Hi6xr>-Y?jq2;@V>M;Iee z`>cUjr1j6@S$T5zb{H~CRQa_QMKji8=1A030bR>|5-Rg^9WbNn>Lp9|<&hqN_MkI~W>Q zx1_G(HggpR;n6oe31G%_aJ!vFXO8|(9Bz0g{QB-=Q%+EhF{jO45^DHVp&T>ynVn{s z^TI3c#Qy>eX21UykSsYOj9!8fK9iHX#y?ZU0B{wB>fDUT)3>6s*BF?afhHB7on|N6+%)Fn{UkkV@yL2xON^5Vo}AUolUu6FTe`b#h#2kNbI%dXz$7RpnKfr@5C=U4 zk=gHGr&b*N`5A=e2IF+|y%XW5@2?%uEZ%c|C|kQ{6M5*&O|uTbaK<^-{93~VGpC4BcU7vb z=f}RUfEI zmX1_9B32`cHNNKfudO`}f)pwgd)LnGuJ#cozPkZ+3*Ip|si22)-=foA8&S%UNYbH#0-_stbCGa1_YlQ3M{oNwHsm8nM4&+ANBjoK1jwRWJ_in58dJtN z6Sj?nh>gXlwBW?!(Hw3Zl97_&B-aescx)w z_=|kyT?4CY!DSu8Uv3K22KUTA;(ou-l(jZLMv#Ps#HW&(QPMFnWcR}C-R*99ey@XR zh0O9{MH8+9K2jPLyck0$!lzbg;-5-K0bp?fxvOZ_11jVqjR3{2(01$lusUx0vYlg;vT{ zec3crH^_c_9dw+mlX3=(aJeM@#x0}faYBqVg^kN5?JRZ^H(4hzHbm3p3QUAAvF$W< zRHl#Sj#*wbikiViIDd_cZL0d#Sf&NTEvj_&pL^uMWs9|f}YRL)x1dQ{ZS-n~nTmykcS184HxY+uMOs1mPSViOSuKi`}Z zVqh4>3=@;?axx`Fkfdpd;a-fe8!-%a=w&+%xno0+6xqX5 zCXB@p`tE62N<5JzB$PXr+b<{2fQ|Jkm`zYm>)!W-SJJuLvF>1wk=>G{Z`^BKZ`$l0eEwXC zn%;Tzy!=odw6Qs1X=gTR<(bfG5~GzLV#T#)5ZsplGe z%YCpR;0@EGo{#KkLUz`ze(9m7h~@BkJN^Ex zwSgy<-OQ`rDM&bdY^V@O{c%ZLsG|xXo6F++;)cgpQ{s=HnOrblc-8fncjF>uAJ++Z zQ;&xs&-=}fx;uaTaX+H#YjwIhr&UWDPBKjiqhx^7j<;2+yDcVQlY&fiu&SIXRN(Hk z1CPb#LfbV|BP?Ie?=V7r$5F05_CZ0W{vdEg8S3W!{Jh+7H~)SN(C*zL;^w7d2t&LK zyUsLCZ9 zCg%yng}9io?I1*VIO%@%5*q-u9e5!{_wjdD^Ka2qU>bssRE4GlCH$hnAHeiV9_yq2 zMwEXf=&w@yAYzJl;pTYg*bqWv+hyto7fau;uxAkBRZ}N1#3J8#(oFi->5<+mZ$M+c z5rcqzMXEMzM1*+pZPfc#=(l!j-}l@pDGKSOE)|yo_|pH>dB4ldq6;UT7TIR>>(bvZ zd%dlt!d`lekB`e@}U+{UJ5$m)= zIJStC7_&wZn8;gy{wbXqqiZBe0uM=82BT$O!Y8!-oKA&XR(+&@!&+>q-w`gkBf8CPuZ1W z9V?R>9&Yo~96>lq{JoDo-ae`IhoJc(sH(a-+*AMPH|*6@g7&V|-lOJqXCjAJ4C;&_ z=YRPDEI-x$`rDkiUmd6g|Alqqn0w4QtZknsCdx2IRaz>G5NTewDpqVQ>8(7lenrPf zP(1!4yr@0+H{8Hu?S11_=Jdjje48{28lJelz+RS-%rho*X-QJ+b~)|b*#}*9VWp$0 z$iM1=o3;L9F+#t<48N+)IV`mbim9`33w6S+?BL}!V&m!Qsh4j4;jGCNxt_p;`d<6wR671j31vg_RhSt?)E30yB>gH%sURAn%sV6=pL8|3GcrAB>XBq9$7 zp#cGdDbT-MK}^)9f8F_bMilqj>?e!;fN0JSsfDo5Ls-^Zod&^=nl%nv8R3KtEO|y@ zOkP;GKLfedm2J||{{2VU9>P=hh0ujx@TmM>U^1bP>vUOTNBZ|Bw9}9F_QZH6wh@NW zg0+RikeT}Y;38#1SOzKyG409HkIWTJm#MpwNdPdH!TFNVG`LbfZ2WgTX81q9v3|Cq zMOBMQNIbd-$NXu*4n-bQB#YaA=Tf?N#+_s8z*+LKH-61b=33uQAMNF8?fJ6cSJxp; z8-z!!`*}~ZEo_h@$fmNDm5cYN|Qtlpm%j1o80P?2OJ|E$nWaaShimY+ciC+s9V&dgW$2r@p2;=yvk4OY)C zgM&TO2m7}4Di)PmR9@AX&YZ)7WN;M8M*nyN>pp{VHVBqA@Uj~&^-j#Ys-JVPP$D^S z#@+5Pb`d>6Zwovn)g}pCAv)ed*puz#lZ^Dzb6Nh5hQPud}FWoru+Z8G=7 z&Eq!pH-)(7YbX}i^Q{_ zvIG{gg%%oSif|O^Xp3KBF0}`GhOLkj`V5IK5L!ds^yCUgS_f>51=AW);fO!rBvDi! zhT`)%^vrg1KD5EFYLlVQa;S^${=v&DUZkmtn5rk&b?{Wa{pM&N=J-EdQ^2pWdl#}k z*s4VDDW^%p)M7y+P8hko%5*3Sj{~MQcR*w|7R1-gl=A`}zDJdZ8z!c?tU}Z1yV^O4 z^a{R)Bq>n>#(+o+5v)3NdtK}fHHGjvJ=8n6SIg%QC&hJj@ApumLt|b+pRGZcH~3~0!^MQrihte&kI{}{(*4V zR#uL9$ZJuR7A6<3kRpQ>vxH*Gwj)1S?OZXb2kR1Iws&G2(?90@JM)LH=iPm*z?3h@HB-ct z8h1uH8C(<8PKn@^h~#@U^X_np7Im}2&$rzL_mQF>s!!H4phTLEO&coH!@n3~5YR9)O(`v;5@uGScZ4@Hyo`v!z;b4!oSM2`^{ zU<|7MxM^2-UHd+_WcE4F+jVb~2cKUyp%1UCY4 zpzESkQGt;cAPof5nAG48h)2R~rWTsVw#Z40l`##3jfLKajPmj>_6W>puV7kV_$*Mw zE)Xup?JA>xASMA|!O6?re3W6k>(pcebkGO-zn49y`iOm5^u;#KzU7E|lkWCbjEv;3 zQn(In=x&I2W()r0v2MQNha+?b!Qr~~srmiN%jRG1vOLV@u8$IL(CTkDpWclbvajW? ziD9i=F)HyQ(rCA~6YHxgB%|A5Xa)EM#z;jv^$K`2D5gH$l&y==rLn419|qFLz@Tjh z^DZ55-nwM_(WCkp3LzB$RcZ!VMK9x_7ornNSH+~c|963UcW-YY^3}`wH;o_F%hW6= zVF?lLs0Axp^LwCsy`K|?Q;m0J6*k|qXD|g4PZ!+FP0}6-1TFG!BQzn4?m@^mRmmo8 zW}~jCq74RNWQOtmij>}F{O4PyrZ$#9`8ba0rZ0v|FMWr+c zQMHJ~E<}3DJ}Vry#4`Jmk1vw#QsU8`2O8)nGwm#}DAKP=L10EA@d}~sWnPui9)Xd` zmdVm(Xj5Hlg5@RVN=gE{eS0}Pa+mH7;1e93s}?AlgP8JR8HVUEQ!aW0@FV%=lf?lx z$}#nk*OzvSk{dtgEp<*i%FHNyAxJBdc4ySdolW54-xQbDymUN0^PltsOSW40@)U5f z?NBNRT&1q5$*BL$o9ypVcaW&M28OP3G7{@4hKPFOe=9@sT2IFcH3 zc-<=#`7gNU?H;mcE}+pp)x{+wYOoWIra5s>I|cNr-$gRMAnO@ z&106G3ic-m()IRSWp?p^AE;g=uk-pU=gCkQT21wX<5d$6{cUwT2f%j5DQ{pYn74uT zZ|30%OsHCI?y8ZqoE=Ed5*u15G2qvlZ8>1Nw%>u7AxI?EufKp|$8NKIN*5MaY3Vo% z(Me3aY=~psF`I+j+<|8D!f?n4pyby?x9+JdcyZdD0mCJ>%&4~l0|G`}XQvnDBjK8| zput}BsT4rHAAWe#{0qdOMMTv>L4D5FCC-iy>$;x7nV{7;YQWdJky1xZgnZ9}W-vcq zm}a+!aGU@5Q;?B{hG5Ne#O|lJ#(4$VqRLbB-8XXD>Xww{i8Zc^GrTRedv)sq40>`zQT;Hx_G{wo>D{ z_~z9bIei)kk@*&u&m5C7B_9; ztPSu;9lBeKD8MB>FFQcc?bFP1gl$m%!eg`OAC3rFe_896W;b7Kzeja5x7+TIdVF6l z^~WklL0C4B0X6UsQ;zHpDtTU8#`C-$cTlr?4{)q?G4AvdZqLn=wd$`;d_kYo?lV0@ zT$~bf^863~x4XzgJWtd9OO!Ttv;((``-tUTqIFXLkvo{TL zAM+D=28khhS4-yzFh2I6@|i6)Q43)>UX4{K0l{UQUE$Jh7OC3d2r=(#MY5GoZ$XE|>_a+H9~- zN049e&EEfQty1*qzZb+;g>8st9(#!51)Q_vHQmG82Fw&BRf+CWDf0Va8WZS zfX;u%_{Q(cA*for7We$9Ii%@u5Ld`Eb9s0vApYkcE&WffNk~$jKj$XlxnQ=&y^AeH zpOrWFB0Qd`VfwU({vHV;5C-R3E1v=SF|VzwZ25zwYsWS@2~rH63xZ0@5hhFVdr$JH zZDX9&EkcM~BAjU4JPnPyi=TC-$u2WhKGQRFuK1yc_g2Jp^w-W+FQFCT8)@o1Rk_5L zceG9vYF6YtnI2fmEH*rn8=IGGihO+Eh?vO+EIL@3K0p|I1J7sHUd@U5rrp?4e?ehG z_`+XcPtiU&*wp9?OHnYWy-_py^afY;or`2^uM7-4JSsFI@O1CnT$yN0ek4bBpr*84 zyCsw+-=mBNUcS8f5h}3$m&n5zc>1);AKI%%(o}9v0C(yd_ zh8K%3$^+H0`ol6lZsS7+Vx={$qBP6Cn2F0|6ABoki@9fLCTUvtvSm*{_MXs$8jZ_o z{W0z3&p9`~G~J`8PVKH82oVxx1*-f(yGTHuw<7^M zfuR#zpDi6=!I7=#+$}2Heidpq1OA4js?}ifiO;I@ofW!Bpr4*<=}dr+j}1nDrVwMF zOZShXkgMPtAf-#}LMd@=B_xtbb0ml6uJ=D5W|e8rxWpzx+G>0%SI3&B?Ot0ve*M-R zuFy%*-XGK7q-eFZCVkM%UAP} z;0mRJtO`x!i5G^mcoS@xj<`prDH282xf&teR3B%a7c>o2uT?f1EzSmdVJs+QGt<04p>XbQ68%?vi_VD*0TEkEIhFXEfO_~Z&^yTW$qzb<$TcaY*Mp<8 zC5HObZ*Dx-6Om+FY}&EHf4Rz$1EwvEm+L$hAC`YuuQ9!0s+C+9LYA}OTb|)X>n)Nk zQnjI$OuW??5Px+563{m#>(lIhZ1tCih6-2@>@!FWEQCJstVI#ja&x}zRp3GxiWFPu zq<8}CGBEyu_Ii%cG^8HWoy5VCByc4H)gWyD6h-svWL9Vm;=K&lDGI%Nj(5lgHFAyC zs+de&aeQui_n1=R&FcwM1)EJtHT<3l!pT3~d+S3YGZePI#~TLA?@XVp+_a&?KyI&P zbM*hLr6>1v=5^*d61KlprRSa_=_%-uQXv-~Me7pV@y@ZvCxkc(dKNHs5bZuoK_;QN zmmRg}8`n}fE+S83dcnCmlelb#D;2d{jsK@9LjePkEze5IiNABQPPIxB&Ord745XM?j5M4u6rMR z`yaFPfE13i#WwU5zToAX4?WvyL5oU~YCJU-{&dy=HqBNNwWI1Q6lVurTwIE4Yr`Zq z9vf%~MdIl&abuMWA>@^Q`u6Ryyy=Cjq~fGoH-p;1-<9oY5qP0Eq>$~8!3-O_+2D6xZqg&2=#(>O=)d=KqcYt^a7$;b3Z~03VaFHfpfV>zv!-f2B>}8;gUf z<~~H)m=I$sY%#Z?I$vA%hJanRi@7zPzK1voPbkJ6{5r=Hbl)d|ta~jmdm5|4&=l29 z;g_5ZsJJ2G+*VU)eTAQ1(M~;;kK&* z;z=)c*G1py&#ZH8mDuN;1XR`47?&bE#wytlt?+*x4wXMERBAH-%KMyU|_@-d@}JXR|C3wZ|w`$GTZMbY_JRvS5&4C|;&Rmgfon`NCoBpm5|1u|dc z^MIP*bMmMyRk3X_kF4COGqMv3R$xjMM_DMgjD|5{NCUDp8q+|IgfgtbDHUU zf3N$xKHDYzOej5HUX0F3gia~kO}}9Ia5`yg7pZq%p=I1YeCc=v z#QtQKv-evNs#%OeHgZ214Ns#zc;9NV7<(KB4QW>v;6o!qL~3ElyI&M!iOMuzD(b&E{3oNp4W8QFvf7h21{r7yOhfdvGE(H8py0D=eT?kF1+nRAp2yrBe?z!q^M=<@$U!(sh<7x_^DlS0 zF=-JZVNtrpP(gqDRK5`V*ox|UQ@|k)vg%Ao%eZ)v8BST5zTmWo);%qf9lbgRsG0i^ z=`%e&y)FxD%)sSZv#3S>sgyhnR_5i&M}qaD&0&DQgO))9(-1WAuiK75@k5+B%Wu@KBkVMZD z2S-W)VM2J#HEN~`ktE_ID<1-MzBWJSApHpZq5hQO1)69ceF=}xurUK5+A|U`57Ke~ z?D;6j_+wO%YX0b#5%6)Igf=69(`8QFo{kkx1Ry!-j@te6q{+^dn#$WnA>o;d{7Lac z!Tkx*NdA~-UXMx+g*C~;6yKs;#9SITDHH$Dnk9-g`M58(=gN>R?>WOT2W(CD@M)ND zAc@=>dYJoNU8)LT4Dbhxco%jE`1}IMP8}{2&!^st?Na6jN%K8|l|O;s-)EONIE)WE zMaLN)X_zc%<5dh%ZRgFZ4CfUgWBnDxtF=FYd0-Yc6Y_$I96Hl|;AhleUaidFPZ&^J zY^T50zAMD@@$}55!P_NkW*zyn@zTs7aN4Dee(FOnH$Z0As8Qogaf0W#fjA}RLK zf-h_w2|$T{u31_M6fBcEebI%B`9o#7|&&2rR9LtH^9T=AC@dL zfu#u;c+d-%&K%?IpiL~c?fdrMu((j$Y@-r^Ta-!Mj5N;bko1c$X?&O#84D~h3Ec!< z9eNH3s*0G=?PLX9G|ZF^VDE^Jec+);02e|8C0#HNRC5RL>_K2EJBVoa_BPN!3BZI; z(*2SQbiFzc7SE8va~c|S!DXV!{n%$umX{4iG0@5j<&Vx1Al~Cnj=j0H}ptbqX4&N&_ge^5jLElC>c0Pgg zy;^*s%x&Kp?Dz6<7A=Cc^e4ayuZW+3qAL%lqBbilD`Qn9H}j;W1>6~m=b&-FVFTHc zcen4{H7zyHkso9>efzBM0`14M2c=JLEHDiE0nFF5+3vmf3eqPt0gwwdf)4Kp95lhO z)`bX1p$wJ+EG;h=BdaLaDl=@p2jP`Vffay7Zh!AuKBHp){+LC2@b@)UB}iHE;~A>9 zK!ei(zw`4a3tk$&`EWCx=3zeH4FhrlS1;GADvdZv`d}Vm^YI^#Az4ALhOGl?EQ!T~ z;#blR5uD`^EReBv2o+dWrS{D1Iu4IX)t_*!wn_YCxA zjj%ZVxMd@BhVAL5q`lnX&X-BQ_;Kg1`58DiIS~UUy1YsTjdO)x=}0bLdT!FjY6JqD z4J?VLMpsGOn8*jR!N7VJWJvW_Pr6y0X`E8>g~i<93V~uIWlHk%9_)PDV2Fniwlw1z zFl!oIZ17<)obw`hJRX+%hJ&OTFk~zYJy5j708<6GA7pZ$0x}U01uUG53=^oGRB=Ki zwb5Uq>NQ9dwgQ&QLKX8p1|;NApi@F_)AQQ(lql=-l<|IMM$V-)+oU?Ojn{?{f#Tcd`I9ed-UB zq)*Gb_3tniA+dAlIrP$c(! z0c1wy`nvEevIO=C^wO~eQq_f3EKMKIUzFOqaip@_eg8%m6+Vq}Hw5MS;Qo!@l9!;3 zU*0)X$~SWCrG>q9F`jMQum-@!%1X9YaNaBH!E1@Vy*)=CAEq{ZQn*Ed+Y=jCcbYWj zN^^;(KnuxF_7kuni`XAQkX2M9Vx7XGIj_gq6QGH9aB+#*dU_P9P(+}h4@YlDp}2Gr zBr@t1(n`1yQ(KW9XJo2>B7oN71M79=uobFBH4q2LQHT+RSygt0Q{2ACy?CKNRptA4 zcecEtAq9f6wz#MUfF@+DL0kwl24!3xWy-(+4)%GpnOw{mcIJj2uGSn=$#(y>M4eR= zd8R=$_N<^cKZ}gSCNDtDB2OZ77g^4zl0|HEnb(?|yS{M?>HKv5^LqDJuNGK+DVAw) z-%3(TL;H!1=y0=P{@{yr72^8T-kmAT(^=XF_1e&i#Mw~EI8SUO@8okeC?3UeW zW$OR#A5P^Upb0+pdk0v79}m`l_7D!QO1e&REykE!Cu}?aIdDF$Pm^Yzrc-Vo7WL*r z^_1jbfhLNxMDT^+HsN*0WLXPNxW0GY5d8wwsr5A|V=|4$^}{2H9&I2aZ=kZn4vAi< zH08NSgXT}b*9~H$tfhx`gWn<&4JsYj*fR|VYNS5+d3lW>=(Zbkii=$<*>dKIdGam# zwCGC%OHXcVVy!y;D&bf6j9do)?k!)#YpEJ3W}in+;Ex~02cGC9J$eHToT)wt@P}N} zKWbvDM$6~Dxb-x#-uiqP(X%1@*YlZiYA-0l^nZ-w9~~GIA{o%YK8v9%dn!|(2hY3W6>~SL<$@%IOvErKLv4XlytNMN9##Bd%ijf$I+I%Sf`Nen zIK2kCb{Jy=U)4gUS8V3~?NL$oNcX4fic4P=H>dF}t12SgN_=F zQk_eNp6uA0p0*6`Dy&Z-IOF?p5I+ zmn$KK?`*t7({sG%sx2wqIZ+9?oSa;_vuC~4q*fZWR*Y6@1tyuAf#AKzg!#VeL@Vgf zD=sRf-KenUy=L9i3 zf?)o{CKi#fe&_u#F4hx2qYP>VihfPdVp?aY%~5G44sLZ25+GKDHaQTzE_z=yrLhne9E_~j1uh}Z5q!z^d4X5V$LB-Cd5Xm$%!+# zQDO03r##$Ry86NE`}!1V>!$8f=;e5S)zLM-c?6@}A^?dZmnv);Zh$`pK2tdB_6FPx zxm=#J^=qp`DdqUOW@63-LqiR7PRM8o`S2W#^}hFJYN~%ipBid*vzP?J?&#lNh!#3E z4(gj!GP|v%C(x(DkNvWg3Xagc=H%tA9Bw`3PhJfpG~V1?aAwt#9G3sbE|bB88DHr+ z{I;qP&5mX;2!kSWqJ&gWx~xJURo^c`X$Wo}Up{zs%kZ{N_iG^r?eenJ5&v+uYalg4 z#|XkxurpOdaNaNsXG?!8y~GM(3_<`6GCRbdR#l~|YlGijF_Fk*2uW>al6xVUJv_a< zoFb%~Y^+{}+5034ont1m-3_R1WY7&6T#yxSLU;mk7=TaV)x^CRb zpO%h6lAmM}r^L(duxOv(P6B=7i<^!*+1}y;h2nfxO9EzLao~4?LsS@|&JUYMX8{Dc z58~(A*l_*cSuR>@spV%h1Ry88j4fpxDLA_WH=wX@=GTVTKAXEy@o z+DCmaMF(0FzQB6AdUFX8DJ)*=L)*}lCf1o0)LB2fAt_g-@n8+kfINai@gfj-sgxGNndamYP*Z9XIE_gQz^j**mQJX% zP4s%i#jmXLAE`tL$WrH#%VTlA^89pigKwIh=?Tw!>0Ff6*;-m!KK68Wp62G_k_%-s z`I$$?hA<7qCLFgLa) zq?*!cqQu5_Cha**)rqxwRD49gG*86!Fh&O{bJ#BBh!Hz``zCLsuN@oA~>C==Z z3al@;>o?kiRbC0!5KJ|GigVtQer)*Wp;@;i@lXq|uUcjjP<;$=Unup1M6<+GRQ|*% z&5-5nPl~A@4i=1wEkJCv26+&tv{p*A5ISl~*mSM3RRjcmaM%I=v6y(OWnOZ~OslH8 z8r`PmS8D8LX2q6(Q}_FT1U!2*rKh?&mYG*I3V;R*xiX@3d86G&*d?F>!?2!=L{o$A}48&cN+j^R!6Z4*Q<($vypho!jGV^50-p`-YBBG)#VD-(O0W9oo|I>1%|qWFO8Uyliff>q;X#QuSM2 zAN*rxX1;q3CVb#t7JvN(Q&8|LNT^g&x+Ixt(5X|diDj!Yt(A>eV9d>3k>abSka#9L zopwZIVI5U5f5$3gdaFGV>pN0)hr&dau+c?rN4&(jjZN#|2bvR)KezHiu(=K?8#O^( z$RQ|mGp?2je$4Z2!|}8uzY_Z6@pUnQX9%k*)?#e_oz^juCsEoZIEl=ajz>6uFL^1! z6?-7VatX$D7N_$^{ru&_hS!=qFJPg~{&*ghqWBu`XlEA|hXln-E7>tbBLoYDg3T`R zF7D4GHF^1G*rm{`mq(<_@u0yi$ znEb@5`4chtnq?&fky$t%zU7csH}voC;bPY1SFu{tEC|q^T>QcP>ElN?U}B*2Z8en5 zG}Y0BXvA96+MG=wO{P}RG^~@8O^uBuL`emo_{)+UK;$K!cCHq$f)ij)WJ5zkG>(4& z?e#RetfbL9KWDzxi_jI3dx=sAwU@uH*qK3O>>LZYN`Zs$o6r7vtut(UHH2$2+(a%% z!*Eu-=i>=C6)X`Ng;DSwjkwnxKiu281*6ix*^p0XmV@fH4jVuxa*;^R!mtv;oA9hBjQ5^Fy77-*Ie$6u8{z6 z$VZVIe|G>*wycuUfbHSJtli}- zeVWfd>#y_BKq_T*;;jL{f9$>i0GR8m>iu6Uz$Q3AA7rAJr~4*B%abG&&G1@`>A1zO z>i=9)w2qI4nNQJ%ZJ0DwXr-%t2rx*GePbz+=>~6+m6cVAn8heIi3JUvO&oWf#RDBp z=t{-qIbg!L0I#%&3mc+hRNIFFh196unDi6L1;>>`qIex&yZ58E+tV8X6jGC)74t@` zz;6t)V~Hhd%$GQo9KuO{N}K(j21xI%-iivNHSr*5L3?u2WstV64VnP&6PVSM4`j+@o@D4O)l$AxTSv|> zEfGuyt&v)SDc|ZPyAp!fx^9H!Ye{GKed)7dVER?^;AD!SNOWSpmhzTB;RT^=zqA+C zY5I?!S4=&3vUXCCo}6cRlfgL0f$+>NMGQ%k2_(L9jYU2|*i6OF{+vLD?1v(szAyiF z`+L5i+Olr>XZxE~Q7={#RMZtxaz6(d8jh8l-w*dE=u{?~*2egC#`v|x7<49kOr2ZZ zt8U{rJO7WINvXA$;iD6WUra1NW)h3Vd%oU&VoO@DcPlA5nUA!YM*-f5_ah^Q9zH(x zRuY*!7>C(_v+jK;J5(&YoY=GB@c0f1ZN4q*h8wqG{dHh7LGqX-o+wD=K%H0UTjk4% z-fJhEl!0rjNSZ}l+@HtzxgWW}hfsZVP|71+AP32xGj*qRSI!q1 zG*>%Ge5y6b`Pw7%MkkMg0-&?|kXi>i^pOz&Mc3RU$EzAqcS&OR#+ij2ZxYTr{M+*R zzT>A?g`B*+cb0CV@@fka^(ePet!H9cTnY zDh%4y6B8y=D^Qp;vajCcf_H|I5}fof0gG`PbL|+0qhWeLy~bASSBVM3{F4qGkU?x1 z2tgO#Vc&3?rJq@e$t@hrC6^~kno)1#Js;d*3LrNm&_p9>^w-y|FMMO|5QL*jL?Kvk z1XVEe!xA+~cs9}iCk8>zm}ThU;_}i@Sfy}SH|nxOhd9d{*a0sMfya z#&U;Fa|hgiJ$02hZYQIh_;4^!>5kRJY*OaQF4@MiugEZL7Hzpu8a$LG2})GTXJAFBT5A9_mrg?P&3mzMAzsLB2X zw5@tckqg}Xd9nWS#66|5*(J(xZ21zl?Ttp~*K%|BlI}Tdzl@OA$ouCCW`V!vY1M8x z(Zv=QK5J^?k{ppKGrd+cb9-qayH+_s$Mb1!jr@gUc&u>?Bjl<;5BBX_|FxjuD>q?N z$l9uqkPv;*r?q6hvw5(9{Ij_PY5xe(oP~$7k3NEK`yt_^_yuZ-6}rSVjRC(+5nn1C zXG~Qlw8uNDs--ax9WQg-E~-|@O(a8a-%J-H8)!|2Cc2uX8e+^qdIK>F8jNHdW%p6I zXff#(-)djxg!R9QX8*|L#Kw@Nuwsau3{A7&pbc)xm5s*Nl%ZR5f*!PFZ0+7=3NNy8uo={m82Mk!!pe}7-9>GB8qL3WX7 zq?Yjq3eArU%e8?b6<+iwX}XNXoYIC}eFxTMXX>9aJdkopt_DyV%_RoNPgu`7Z#NPcYLZ+* z%J~T(0|38adU#h`D-QZ85)of#u?lmH=7J_jcotc-K*1Om9ZeMqMaYOKj`))jpR}Tk&66o1;$F#WIp7(su95y_Un;K+MeXvZPSeRsq~&BIgk?E<|j?V zFpkDtomayy8la`y&t9J9V>S9Ss&1&@fAU2Wm0j5(r<*2I()!Y)R?`!|JvxnP%`T0WMXE(5Y)zh5%A~1o} zzQAxU`(KsT{Mf*`fZ^sZCoLZCFI|D<7}u`BqV0!Pl0Sa_^uOun*Id#jGUQ7>+)Q4X zL6FFzVo%d5tsB*z)XX|hr>Uz-@Lp6c`i)M}NWyC^nBp*D_IA;MHiQ=<4ln6U4Bugi z_kXD|L%xhkBdSEOK~sEy~6YTv{3k=wAb(zp}YfQx5%KRA7fH>2Xv`~SL$ zpP>oWUvTJ)I|7)m3vCGz0==*Xgb{)$+mxjQwiTJ(cRK$5S}biFgt12-F-Rm*y4R7m zSt5Erd=Ms+t>b|TDBS$&;2;POhHJT(FekRc;3ca7nEGoEB>+z=Jm);9$+~v}_BDEPAhuaQh+{4G4Z(WqR2=IVd}HEVn~c zCr?=F;`YyEz0-~voMqjFBHf@OS1{v$*g3ck<;V<@VlqkV2v7DvR@>9xKvH&f;_G^R za%m|}NbwfZ#mxvSAdC2Q{MSr7LPiZ9c7<@lUEFanxH}iTs$<>bD}P81_2W4@gSJp@C-GDdqfjM8`sqylCwey{>c$#&Efg|Jy|~l% zu$+1yXce_&S$pXi$R)$<`r6swnA1J4CUX)hDJ?stny5acn#}hmW$WwdsI9N+VSi~- z?7qyI@SIgn+FnfF^X+6_X~2*7@1q)`U%x+L+y!z}{;qFb8=>E0PIbSx zg2Bth#pMT}O_vd+B(Rm1Nbk_u&RCg|+}=s)_I$U7Q9Dt&QuJk5e4v**r5+`U)6r;b zX90n&*2Pty!tr=KmoKY=eUaXO1&}H*a=En7UOol?hG_)vS@^;!@g>HijZ9$!^x*kM zQ$H%GEU>OeYn_Sdm?8#@PQD+Enw-X<7*k;qE3-JCteaOgHw zgiRLP@B5|pXWzaZ9q~d8jEp3bahKK1J-*do0!>Gg&s$X&AZnulowD=ypU#Oba#z(` zxeAq(wuVG*NK2MjS>PseKMLyP!uH$P|HfbZ&VPDvyrX_G>!V;8=B2@@P0Oqs{TlNdisjC!RODBA3uJqF_)P5{=G5oI8~Tmry(4ZLCzZk@$5B# z+%RD2$ZqOgV%}20BXR*agRd!X!bD3VRQCPmiHD%7$Rz}xDKIfr$@Zd=my)Tp|C*Z)^=|= z#muRm?WB#TaA)>BfnzD5?3qPoiPCSh%{ufuD5A@;6QS&T!N`3oxqdKaH`{S)P^shF z%i*SfUy|03TP0XNd=dFZEi6P)y$&Hpu`BWJ0Qm=DkHVmKsnB}jRvenRP1CYqw@eRj z9kM`8?NKMSkl&RKw=Xir;|g>X1Ss*^u~N27nBI0a$;AlgD;h7!CNCqR*Ndr2s7oSp zYbC0xKFQtk=P&y6PhtNXb8+9jb1G41Z|@cJ*jUkJnU1470z0ek6-a6d7mrkbjW9>iE zIhR+k{cz;mg_^vtIGFaY`|?tf@eI+D2_VUN_gV=hG~@EGrYEy7y&%Zl4B`Vhi&#uy z;b5Uk>5ARhj=w~v{B>}cD6>-`cypD9t{9NEpb+y6815tJ;hI5MK*znp5`~QzNX!mw>a*7hd4ewM%B1G9ZOnJY=JKt)pCYLPRGHxC=`ftbk7pq2XCC!9cZ=~1xu4%b0ciYE7?YTk#Kj*U7e`xOV&`J*JHQU? z1jfV|YW9+v4%W)rx&pQ-+CifWtTQ+XORc5N>MY8kfXXVsH-R$gn3ro%x!|C?vD-z) zR+b8QGPMqND}_8uLPGV5YEi>LxlO~#?T4sTlsJzHum(Mn3yxaom{RsTI)e!q014{T z*R84n4olQV>SeHS zASp)^1sE=<4lOs{WS@D+*ZbgF2McWApq;gT!gojeDk6YFtSrFg33Ulm6k~~vZp%d2 z?9Y;Mc|Wr(#%BByok3`QyoSl}vjeWjA`~k({=GGk;x{3>29{FitM4HmlAX-dl33HK zG}AB`IgiUUp}5Y|;+PQlgN9~%m!>E3?BlypajQG~@27N2ifJn5+u85f+O%&9k+Ux> zjKhk*UsrF8Dy6_WKktjS@KXZB8Cm;6V`^Jx!3$|Zi|yLm=_>5FXlvV7)#P%{kg|+l z(74c^w7+`+2LPq_eIyy36bmE?46K!B&IpEz24FNtr$@Lv808xx^ zx{(SrLW-HrMW@M1ag&clNuq}hD7of&Nx2piBjOdcu&lf?n}$biHwgAsVTAREhH5Wc zMukDx02e$IR%(ss&7u^?2q&%+w6uyuznw)}8WPh_GZdr_q0eu_Z0dZOZQyU()?xD2 zp^rqSN6(MUh61Mk#+&=!-}k_hji=q4P%^Jg;%z77a)Rf@MTJAtkw`VhJL#Y8R5J&E zo$~5iT>8QN@Ua60KmyOcI}5o{6=7u~HZ)q2OYpIulzQ@&J^`*!7 zPV`1Q6@>KsBC@sZG*WXi@WzafjE8zA>yKZ5!&VT&q4x>F5|&17Jn(D;{pb3!+(`1p zclpb25*pq-r8#8gJN?;gp*?!0XU&;L`a%}pWMp_xsWCyFd^zW#bhfltgsE2> zgY|?YCcRpp+IOtm%6Q8W&VB0b*C?)Z7M5%1ZM77IT!yjHQNepJ{6z?y zJ(dq%@3S`qQe8AM3MYW-r_)+G-y#VbNVtp#AFPa*YNrO8xeP+^Pr|L})|()|+xZUw zI@7$w?rSHA0ygoD|CEt~PW;%NZ#Uv@{U7leEEjr9^ms?;S4aMG*gWneFFH9C%O9Ep zjbX#l?*^gto|V#AK6wec)2OZGr^T=wi|K~IITCID!L55#h`WMROT)5!t7=HvumqsQ zC`7>U;y9v^Fn~d$g?$u@$IL2C^dF*Wrx$&{cnbcH<^zO!7uo@b&B0?fw1zf5GAZOgdU2qd*(lo>Ee3`@2Rbn&DA< zBFA@?PJ(ZA*w~?h3IlO-%^r zHm>2cUr2oRsSAQzG_lES?2#XVD@Y%M4oN|VSgq0(t}I4 z9309XSUi}=66-gpCz&SQs}8hE96CA8I;Erp@f)%~nCVuFIEHhsf9YTWgb40SxPJ%2 z6nc8TI zj{dy4=?t69KYlbkjOqn0?jgP{9w->K?Wj0;#(tDNr-Q$L2Be&UWRg@?vVNs>bgi^C z+>u&rzcaJMuAk`s-x_Aq9w5BUV)bku?9jSKjFf9hTfrORahPzL;%Tk9# zMMT`d+B%Lut^o=WBP@vvT!5wAK*W8fZ_E$>p-jy5)XuNr!^Czv9Zw(_67Hbt&D3fr~nDkDGl%@%QM*u z5Gq&Y51z-6!+3Q$E%+HC{=yBzI;DXpV$Wn-y%u#)l;D?}_VaUcX@~ry{Lv~rb=4{=59D_p*iOI2YynbZ2SXC*)h9 zpSD4Q1Lt&W67e;D!c6`qLGxEhDK;hOJoMbaGDyn?q7k!DZ#Pdb4??*~x3Rx8h&_A3qscIhi9Bhef?SL5WS8TuvzxglC_e3q!RWy3hfz{Uj(4}n2Go0#ys=OVTO`(EI?=F;R`VtXAG*3+9TEG&K|t|2SD zYU}VNX(ha?osQS($2JX*q4dM9v$d~~hL=o`mfq&$kX=jSq)t4AK^U2OO3ijmzJ0kE`(}WvzJxY zl&L{Mi=5EYng=I(S1PUO7#KHcklOs?++L^ksudc$6cE9_&-Th9wp~-+HT?UPANcP0 zQA9aS%F1U~k?gZkD#=vjs3`7{-<2NIodw0X>rmtF+<{|uvFBSr!|~$${PQU(DYss4 z1Prxr_BKC!XWlJB%ux7oUlt+A7aOnl8HFQoui^e|uM40J-qftBs2c1d6pkYxJJ&}! zzp7Gu#fVDPzdf9I4@>++&g)xK)(HG*zpNslgyP;ppjc8c3g-gRf|ShNyNWSZ=^U7U z5FwifoimiRLrXYu_fQxc4wJ596m@K=fI5T53jli;%ro$|J5FjsP)HvHb7*Jq%utK1 z{9{jN(!$Pl-l&#a$Y`4KTVgMUeFaIkaMjIP_f2d6qa-P}NY$&&{pxk^zuL5B3btWx zm%&SHBoz@7kvA$r+TtRJBv`&L|_gKo7Y z71{)(1|aN%;dh$U)`Wnvh7?HE^SSun=i((x>1V^9r*9`HL?!9tkws5K z=!O^@y6Cn-7mYf$+fJ>1v8=~kTwZglJ>i158dE<#{_qqWf-L9!C`KHmg+bSl%!h(6 zxOddYID3TyvPLilci(5pV;IPzdZ^Q4@^9L^-q29xC+j2+xKeH-n}+7MQMoo1k1d`*vz-mH%95x2K1PM0Lg_WMH3R zj~uyR9Dc8rfPKNwGf*8faXCoJrNGx%kS^i*pB5=PrTSLFqd2Q9cDjeCyNT=jUhP7u zT84_5rlsDCBHzpn&zv2blH;cjDx^+FmLMZ~Ya~`mF!f!j6{v8IgoFgBoAOc^jq|<} z?j5`TwQGvp`3{jq-z#ehP$_Y;*1+0LI(*2Fs_1B60y_3Mxe(@DysS^2xVxa+fdOK(j?epLTn?sRIKp2& zTO-bG@#DYsC$fu~8@^*8ew5l28Jxl}DN-bbP0wcQ!`AHZi<|4 zxn4k4ecRa3E}wX3T1y1>6bn2CkQz|6mRj9eLFEW0A^?nwKs4246wu3nZ?RrM${1Rp7ghM{(;7An`l#m0}DwT64+hv4&=fP|;d>ja(PCfZ-H23IQagY?8Z%V}M)mywdT&t_AY+P5- zh=*295g;P90*1&TG_(i^W%s~9PHdEEEf%P72+vE3Z~)*91Q4^cG}{FN7{&b2_8F#D zHcC2^%JFR7hH1f>Yw1z7)>H z=M5*qn6B&?>xy?=4H9_E+DCs}gLZlO@v+;tj*v%xWp2HDuN&IvbfbL}@y>beTeeE$ zIO5^HT&tBNA1RS=f0VR)P@~isDJm-Z7~tDUEDx#ZnL2YlGxkP28z`G0Q5<6URJU+-ALL^Bv z1v}>PI7$OOPozSAMJfOh^&8xkI36qL^g%*NZH2A10qu3C#RIwVcsZ%;VI33TeGOIh zz-dC{q7eP<)_*+-PiUghePAbJ={nf|BRWkm+>$>nnVZVb3kWifU zyeikjmVQ>9%H8n0o+KKq_ov2`4tnHP_bCz9(-7Zq9{hwL(Z?n0+^GhYs^JH)hg1Xh zRbB)7Ufnti1r1E_lZ+QmAe}dDvcjrO2rYdS1R%!DskH{Y8C5yt+@Q2+_Ra^>j1J)j^$}Rg?njkY$cL!7yJaU_kC&hqzwgnF87qIXr z&w40@yr;MAcn|AL?&@}0_nc6!p>0x(-p4T2z@juz9TeodP zi*{MN^i{Ha*;VZoB(Ql6kzKyIajaY>{8tkF?w>yn|IWVPJj5LKwY|fk1d!b`>P3Gr@T)&`WpK6P6%_);a}HmvSV~uiFoXjpI2~YEwhC-9GMU_v)woQ z^xy9CV<@937Yz;BlKIcs5E#VoRI=R)zT~fy&0@kCBUt8ymeMI?`70>F0JOj#jNM{; z4PQwH-RjuHcF5p0ExghSOpW3)E2(8I(Uej<=XsOF6Q61IMq%&Kc@cCA$fdMj0sOzQ zs|xvY95;;OWOmh3Rv($wvYp~)q&NwBm`np-k$dl8V3YuK0&n?=;z0B z5K@#dP_|u$Unfkm!x8nn;fVJ-xN2T(`b z^^ly_5H#wUcx}K{eTPe7unXqkg|NX|;mH5kd;UYUW?L5;lnv=42Abpe>cZD(TVM=> z6c3ilVIT9D32aokZpvf~<8crh)=sz?gZCDzDQHX%4V=rB{MfC-!P{B_ z(W@%LzGdV>h??Lh$q+EzvvvF~a7%EUc~5M9uVj+S+G&0_4A!`~Q$S!W_W&oA5@nwQx?H{NPeBIa z>?+Bu@pOVqzXbQ(>yqRJ*P#$))qx){rR3PGixrv*;Q}erri4YrNs-4C9N|bRDiy>)I?cLHlw-R@^(*H zD3Wt|yYr!Y?dsaDG|ax$Dt&hqm<2PC&b%f8e6#S{?G+BC@ZUY}^{&~AxKw$HA2XK~ zZO7FR$9@Ob{Uy(&`;+Yx+G}?=lz%?#=FvD77F5z1Hn>9G%4Bz0I)fP5laWKDDxNN; zck4U$emQe`K4XTvlwTuOy}+N&r|J0hctkKl($4pbSkJHBxBHKu&c|*2{m#YnRgb;N z>o^D5zsfD|CgLz`k=gqW5(>VMp)*U{Z0LzJA>CkjRU8*@LWRN!hW|28QND}pOeV zT=Vt7cq2?8mSU~lNji~Q^N4+OI87#}-1O-#TUlv9G_Z@yw1<)i23jv0NaQiG2FXhD zAa}^mbrWc(01tcbW%)JMti*y;*kXC73UZ_&v?_>T!04k zB1H#A*=k}UY`VwkDbYlWW@2)Eyf5?b{#@)*((IdHiguqT9K8|7!$-E`_TRBCVs6!t;eY$)m_@~?0 z*RNhL+c(F33j~Vjnt5sn8LSSCFGjq&C4pZo$1=5qhFqC6h_Lz%xn!lEg1kTqoK2;$ zabYaprG=FHZ1LcdlYFl1zXjDRS}URKzH{hnhp8LnqN@C?#^}G^-f30j5+B;d!~w2x zXGH4>E&-0PASRQ;1@~PF|G8u^HNsEBYx1mVAf{_|hYN$`C}02lSq@zZ&S%op=h)3P zaR2xg9T{Uf6Ul?}^eB{cjD#Z#Mjo#m*n#XAMzsDrdv9-v^kU}iMgGT+@@0~Yo&Rud zNUV75xXQMc4I3n*$lI_v2n6hZx5t#7h~q=Zs;gfBZMIxYF8KU|gY!sCj^V|N^a60$ zWk$!wSQSjl~sWZ@`!#^Z%QJkST`f9aaG|iKvdM?NL4C86%Cn^;v&Ty+> zs6(?8zL$sn(vC8dwd0Y48q*wwjiBw~ZW;X_bRFcuW3OJp-RAq|F~mFPJAt&vp>=+7 zaTo+XKIf^)>=KpxWr@(hETn5vdVq;9ISvUX^C<7d^W7(f2hF=rR)D>aqa{hD5g^eH z*ctt5`qBS)a>}ULhJTw7BA&H-uYzKj#N1%QISXyrM!Yb3;aTy(1DdmuE5b~&Fe3k7 z7X#>&Nis_RfPl1_h2A)T6`(pgX1o{yVlQKOtp;Cb3Wo{+e{-h_97u#g<8BPs3|w{Q zD`y4cktUY1Ef@?K7Y)R>a}b!Pac&4_5KY2@3CEq!tUB4SDs#vep)rsokFFKZxlHS? zQIVMHEHzvYRu60$+c`-^&N089Xnc)`M2^!H<>4h8DEWY*6@2V zn84EZMi@K%B<#4I@H_uOKt-NIg*Cm!Et!%SL{v`k>6mLFo5%Mjv-t;X|EAEW{^F%; zuPalS%wBTkA&UycBS`|@+e=V%)H|Gqv%u|~8w4CV7_d?yOV%khPL^SD8eRA?Z(9-N z-x~fLBxVr;NHGxX4-<`)*S0(EMu#zVCe^eF7x7>W7&^Zl_5`|w5x~>{=*X13!(uy` z;JR@N_6vgm$E^i7#Z<6FF{u8>Pf6X$_hd*l(_njL1)SrGw~Jg8m8tNAVjPdTUTbY@ z1Rw(8LZDiC1L6j36rknG4e{WlNxVf8G~V9(MunJSD$95V?QGysGOs{cJLlAMfyG|X za(~Yq3!!fJE}nj*wV?UR_-fi$;r}9+0q;X)hBf2Y9CWEPI_f<~=Iipe5cBh14mJw)=ous*QOjpxY!thb9om!`_R|^~h6X z9^1)iy#p18f=6vkp{bNyXr&RuB;m04!te?hR6rH-?EClc|G~cxqh&(g{~)aq+A1h0 z`12y0yr6M&W^ZIq3GX;>5#W5a``7NNcacwnMVG!;T^ax4%1m~bCFy{r^_Ts;^h2?a zvbFT5e|^|_l(a)GnZ7k#X4kNv6S{0V9B$Mtnwbsg`)%!^`qe6*^YDT|fS5>?XAQq&ejS>`v zfh18&SN(%>B9r%`@?p;yxe%oxVmwKwzcn1WPB^r9UP;UjE*b)a8#t(%W33SQ8eDkd zrGIEBAN(G;>tL>hEC98$XBk~|l=IgBsH`-Nv#i5Md$hfTlc8;Cc?_alZYVOzZwkPr zCHaMJyB_4<9tm=|jZwK50+V!Sz(`e=2MTU5h?Z~HgLet>KTd^{dWt%##{+Q9k%s@H zhnY?|I`f&Q@hpEyqa=Nb`fo8ZDO3JaBOwsrX7m8ot^lqsN}vR{{R2) zwL@HcWM{9;NHVW2O66>pox4*JIvcA%*~gTH&}34xmM=(|2*1wyLu}~I_)KMyZp?@ z_J`*RnVg%dgEDT=XuX!5!zt{p@(s+|nUl_pjNA2-&6tx`=5Zwp;+dYBk@dOsH)w6I zoOSQyIFPuD&mmJOj-!b?Ozq)5ysw$s)*C0-f_tw`{hG9XUXc&-+qR{MaWn&{y(Fj`m>Xr!#SO5jQM zJLS_J4t=(_GylV?v9+XRup|FFpCrFX_BC#!TyQ+2;d zOFpzshJ;XK`l5>DktF8^XJd$Mh=3M9S&1WiE(s@&C<<0*qpL^*U70jEZ)>Vpv8@k5 zUg>H^4~dmwU^FTIhAI9Cj+XKId*1>!Ue~ytx%T4LLeq1RblhnA|JhsQHXdBE zS2(MLek4CwEa_vcD|wHj9q2X3J_$JT_SuNU(*p>T8R%G*2kz7Yl96>0m=msZK|s|X zu0w>XA@>8RWNTYn0_=Ub67|qkQk3Gow)QY3Z8Eao+b;K{oaG${k(7~KE-xy%$53kv zvH<2}i8O_Ug<+QSIuCElb8#&kD8NwyZt_-~vr3=TJ&qcfQob#KMDlaik8o>~ZWSkY zP&SJub1}Q}Ywbj5cmf%0RB7A*3+z*jgV_gw}RBmzo zlJ%Nh^O-$~1Ov=01OtWYJ@KvzWVC+=wf6>PeU=0Ep0vGW57}8dAy)h*(@0?MUO~02 zLwrY_Bh0${$1g;#M?AGtefQE7e5m<;i`jW#Sk-Xn#B3Hc*mHfRHWb`cv5dfJyHt65 zIn9I%kEY;JW4mo)V29tah z2W-RKQJQ$sp``XBFl%5Dj@HcVwS${uCPIlcMvTrK;cor?TRygNu`f#wLd~@`KkpxD55D=Ul!|&gAU&_5Z3!mLuizwW?Y?6^cBu+Tt z#~Ha2YWXDp-vQcfOBhOEZE!mSKl$^5u}OjRXLVljgJ&DI<=lQQxHg+^K zsh`2|?Y%3)NI zf$#Z6-{|Wz|Ewh6KL;5Ix-x{u(OdTNbl73K&lGqlP@X_;kcJK2 z10Y~wokq-yU%bfVVZw&0fdQ#M?~-YQGo7Sl{RkN8?6}@STnuF?Er32_ zyFta(O`w9G=sSPb=GNSGs%M_bLSKCIpn;{W++*U;I?4iN=kCPZV17E5v2itA_<;5b&HKXd zvyA$`2rW*$CR9@!lQX^4oXOh82_)Zn47vX`DOiwRn+phFf46bC)b{4+<}p3J3tvHm zT|;76rglJ&gaUm7(5^vqe8IDPY!F@JhFF2hEkrLix<$dS6ukaDQ?JIzj?*%o#o^I! z_3YHheWS0IH!D^bMXOR8s&u>o4Q9)rBZM?8ipPj1yokhVUGuo2w(Q3?f6RX>0#?o< z#;ZerA*r|oADW4849=F)2>?=mDSC0Fp2;FifN> zLtsEcs>(1OEHS^DEg=j7v`HqwOy!UmaY?-AfXmPpvqgQ-=b$iT|4QIPtY;P+1`Ki- z65uds5%ZM~uXxmAlYr46%M~P@!9Iq$?`yc%nuLhqxcrt=O(?Z?5SkU3`U@Adu=fEk z!AJ4(@{)vtD7PXD)FCM;RDB;mrr=0{CmsftHTB!`I}6&V_N}?@bbbL8M`rKfV6lck zW-p|wGr%*v6emzzSxeEpUfL zL#=wDB&`-uKuCT73U4vnP>0woLk)|CK%vwFDAmbZs^lQSRj>Xgh5tAg4j{H5GE z!;JP|C|Cc%io#&0=vX2PeXh&c+Rs^W#&BS1)nf^_<%?dCyc?+Z)-=~l!z*I#7LO(M z!e(_ni?VV&CK@*(JKuncYA4mAtQ=iM6%75T_qm>lxNZ`C<)SwZKpq~D*A3n&3&C^{ zf|u%)QgeSYrdFPHFKGk5rbQx58f@EmPTKdVSv;Cs0>!27kglp zB9eUJhd9JyAG#&R$7k7M%JC%#PV11j5GZoit{^|vV3BN zN`D7-XGC%IR;&XkvYtja{?b0>Rgfok^!?8T=>SV@726h;GK?0ev9353YYo``E@(ak zB8oSR7Q!St62W$XTtbdg+*DY|s8UM3l*ROU5j1V5Yhd!gx~x2m`TU2|iA_A|)SQmt zv(a>U`r8{M?~)0`NPIC3SosX&KtXFac9iA0@(Pl7VskCkZGPK}TR?*Zt{CNiJuU{6 z^6KE7hzG&*I@Z$~Sa(;lJod)Rv(>L>@4Py?^kQyQ;n#znKk@Z!+k6HOAL55uUc5!X zC%Sm{!+zkw{v%Nz57js_wD6~n=m#Dt!TegeakmSJ@TT!y5?t@1d#X_esNamoTN`Z= ziu-dR9iMJr8bph%@i>&6`+VdMP_OR}p!7R;+YTmQLZQd?5C}B!|FBS-t6dsSqRBz7 zD)IrI+f+$n>#kevxb*vm=GakH@zFFXDyQj9`6Qcu8^mKraz7fKU|@a`f@qTBqSRQ- zIm#M2xF%f%oa*7&CiiHp$Tf5!3j#j|kyTf$&S^C(JG(I9jEpq^e!{(PzkOp#h>urtNr1PL zwLRe2Q2t3!A1^7C9&4xvNcWr?m|OrO7~I>FMNSO$CG2I+WUi?xFxgng{_tbd%8BZT ziL}y8P*+{p_H*)nUP8xB!N;v`EbxV%ojI})f|oGl#-wZWEVNWl zL0u%&dry@s9{m`-1l|F5l)ITL5iMTRG96T8$(}F#(Qu#_czAE4Gaz_z9X{IIsAN2M zmN#osIeC%mriN+D7xY#OGA9b>T&?BL(TBb{H`@~Pma9_FaZsD`Io;VW6Zo=0C{kI4 zL4P)=Wp=zJ*}E zYW4g~)@V1FvBW|^{v`ag_jv0&DQ z{eW>{d%y8i*&)8=*Nfa=<`8}M^J40_FQ)|NXP_C*c9;e<8n$Ni5Uk?_y?dxo;5`jh zk~`{jlhw@sv`HAAK1@!0?9LTeU4pZ@P(+2st|y9A_yciS1~3K;BaFz zd{seLbsJtr2+S9qgay5|Umk>w(PpQ@h4ZwhCiZE@l?xD>KJ}CHah#^|ck_%02=~4W zUihyNx)d<+bMj?~07-a?qgcV%K#O&TI*_`SML2=gAb=#hQiRc%)K1 zb>B|FG|}_ckR1O7?4xm(oSS`o0aT5iqG1s~_txEI)Oc-o;!v7JoO`1 zCGAR#kyi4bXnV0ar1hAjIJjrL2WS5mlNz350~YEpW(*j~Z(?_+5qfcVd^y(=-(TSpghoHh=|`f<%)iadM9|5+4;B4Y$MNi>gL1Mj!2)pK1e`(888{yG;OV??6%7fQIBhE*pNwb{Ac5+w z-VuS7Y2q7^Uj1Fj?hVU^(mce2A58)wO4yVSx=NPNzEfykr4A5q#pvq19~)hq8kk5- zAx3;NC?9f5wjN;&I8%yd!31&z97lx8O0dim=wh8o-#^*VT^I8x(iVt|))mqW93K-_ z2Zy~=)ev?bapVe;gs-q4e`min(cm(A-F)?`S6}pS=OLjnwubf0jXv=ZaLMg8yqu1D z(Yn39%<4-R%4={jQoWh0w&D#mpG5?FI$B!EYUkpx6SS9kYw7&g@=PyW+TJH8SE zG#@?y3$r(UO@CLOAoM0L7ku2=^~s1t1LA+^=B^bsoL7H{>~9`GlR}{9-no;7wyftf zWP2vU6oPRH0zdK1dy<3>(th2+x1$l*`Q($6+3kq=K6gx8x zE?qr69AhN%tnvU`6c-mP%Y$@REzl_0;6qtht7T+HGgd&J=w^QD!-537K&dU^A(hGP zF9kXjL0FjKsC5j<6DUAGhh|(A9*v7;5vtJeGGr zSEN+C{xIfbC?-a{llOgX9+Oe+8dmPEAnRFu*6ZKx6t0<>w0^K!yRFFN7^6Ry9{4>Y zJaoBXsFo#3ZtA8twYvxJ+^U`?HzquvIC(9VGS#kGF|eGHky% z^Or5WU8CB7fK(Orx#Ap4$Frbc{hN0~j;`o_%;@`E?E-X{^Et8@f^_y+gfJZqUMUY= zxd;J6z@+?u1zGUHd#U0*+zkrNp65dJo?nTiO6<7tsED*XUhtecYsKi?Tl+Otqlj_H z;1$1Z?t!Z?abRHI7EPvqW5*rx}ZqLWxJf^OeYNeyUtEp&EvwiSxV^q(?li1ag)O$(eo zBxfYdxc07DpGXI>v6bPvIX71Te{7E%VLPSwz>(FQj zCyE*c230~BXjm-CI}FHeJNkfBm5j^=cxTZE$&@qhFp@_V0F4E&aj2xGz6b(pgJ+|a zkQnR8nXF<7UBMlF+PV@knw>QAvz36HoA0;YCYOS@hI&?p9hIa|RYQp%KPq|kSCgHY z@v~8|vRu{`Fn1=^QGyq~K8&#I03tug)-Cgz1~Rt>q9;PmM1C(DQ$8&EQ{Z^o@#`0w zOOtAci_cEvVLnVJguOY9DhulrFn)4+ton3sbvLzMybD8x za)lbNQWJb8FuiZ$`h@Nc;mZc{3svu5-Rh<`puNZVyzU^@T6J|(sw-VWKygdvdGm+z z3+ERW*hhr!0hd7Lul&qAy&68eV7 z{QjV-75OIj=B!%&cbC)8zMsu)wA|SN@vT@?$nin$UefL%58LF?*}A88*DOCWh}0|_ zn~pWU_Ju~~>65(OS4%M*B;OqJgBpc$hKW4bPoc?jgXzp&8r`lH>3_WAaW2mHn-hk> z)og@%Gc3!QE1Zg#3L7XA&M^a}%f5Nt8Fn7DxwnQHGVGpLh=NWn7o*xIJtxBPJU1Go zjQsR*7EivAS77o5t|F)( zywn(nAj_|Hr0#aJ_}I<87MpC4-cj01a?rSB71~n^=(Ad5oJt z{s+vUr~|k&X72C4rZIkH@Fa>Qbat>kh~@CFE-B3vA0@&@FH?+*w8`F0UNp{Xk$C#R9K!uE;j7hpUokyBu6R<>Q%4= zVRWg>pbV*a@`S7ur^Tg`5Xwu7BQ?}~v7DG0CyHEly$;VyWt#qC0dZfTp&-Ax!zW?i8v}pnUhNvS#pWM2-?emK)<#J$ ze-IxQf?U`Nz8kvy9)&(9&P7S`lpNNEoJr(octX_y)_vjOv>$n@i zMW~L!XVrRb+G&OAr~Lkvz`+vJjtVtfJN$gKH(!2Cn$&4bKRX%raU6w4p|r5d#&#a! zkA=BNtXkzet+#sgkLUG+y#e#l04SK$$jHd76jIe+o;DROuTc^fA?PiM<}dx4Q75cp zjs@K`tDliOh9D>UttRW6TuZp895hP^(yhyS_pOqN% z*2AK`R!_HLxs-&@*p-X1-uSd&>Y@wYQ_Zac7ECFs)_k2&Gc1j!;bzBcQmKqaY2orn zgK|nLuyQ{-Yx-t=cPkq&X(>RYoIvOkhJ4ekIwW?ZH}3iC2W`8Kec z{$)Glz_yl?^^oJa*T^vCm0X+oojZ<#C+WvGK zN!6HbUdmfFv#`*;ma(8gRSXgz_qXzO>pta_gw~{_Ro?vTJa`Ilbqq6adAm;B+Aaau zJd^@WTfM5S69p9tZXLIYl{q{rXVxqG(`M+$Hg7QXP3l5oKGew61UR`PD# zsHs2%G&2s7O32B5fX3I&c6=aOq>-sr>%D5yC`<+~{AWyxdA9^L|79toA-8aP%Z{`2 zz4@itVA|YJuDq44KFNNJqz&-@0EHrt+e#o^;6jG)5djKxvxpf0o{$(6gl(Tsf_E>f zy`$s4wLNT!;FdIiwGAvTEQ-Mvkd38;0s{+gLHbW%0y+{@EU}Q%Sjz1WUpjK>&M3T; z78Rw4`a8p`JLkm)D@!ox_vOnPc>A}x^M;)-ueo*h(RQYn!L5&YCtGW3WDdSZjj2=gGqM~_q1yOqL}sFTW3dKgxMh?ZQI^|=;hsEAr;(qe{!ZU< zwo1&be<=i;Vsgw1Xed~506~f@#aux&$OYiEg1Tqk#UvXgN*4tNp z5R2U}5RXwj*$(Nr9rR0IOhNi~MuQufGUi4gehP)9xP-*7$^3)n{D}(^6198ZJo|S5 z{R4lc(lB|iS`M}0wI>?iR`J%|Sjsw!jSR!Gtjf6)G_S?Dp3|l|RZKE;o+kpn>o%7~ zdab)X0J2z=)$_hF6ib zpWSx`UHmlJ7_(J{LXCQF{m>6#HvHY%qf1lge^;^>*w=Xi7zBafZX_s)}MfYUcgW!{y zg$3JeQ3mJ*=x9+K58fx&2VhT~!3^o58LC$yg3U0+9}h-U21OVh)E_`tJZ|uy7_7q4 zY1Ht)0B~c)bsxB0pyr0oQ@ahRM_mQGTTvaUN%5dNYqudNAS5A;ysm8@l8bDBk3J>| z{T|0;AiSg~UTY6J;Er=MS5GDb(B$YWtfxPzxz3%a3bJMDiHLK%@{d{hmGU=3Yg|Lu zGq_ajP#;2PP#HtvR3vED#;;NtC6dD1f#vew6{3<}JJ!s4eO3AtII(2^vV5B@*M+WQ z+;uy`TuIOS8dZso%yK^r>R+Bb+<_XVl;9(8mPj5Y-la~ z!h+U}SzA|7GK$(JHY=ulwZ#fUpl(>0MhXum1IV~HckyBAPU^z6+;}EQ74t&vVL3og zkF-kxM_mATRn07{=Os{_zzdg&V0F(E8ffA)hwpI3oaODRA9NHOkoXP_0qR$vYpwuo z2`L0%gc}C?8Qdop!t{QwuH;D2dK0j~NH#bS_0XPS`uuH2mV_jD!81z2QSJYyd*cEH z<)=LpsKDsohOFQJKTze0hhP;)%o}^$d#q?>$&JYA)dh}DVuejKlvW2RE5;%n_v%_y z`y%zF{$7p#7{iBFWhMUPeYVAM| z3@t2R^py6I75or4u-~em+608AG;=~vItKnz=m(j*2+R$1%9q}0e#&L=dC?AREMnv$ z5ah=bRIz8HEdcndQ&pA!>%8W}U%g9+-)&3r@SS4dg5vR<;?&2!hc@^vai3!INorsV zF?jkq5EJtIrb47l>yaA@r?kzuvc1jG8@Z0XLCUcH^RIE^8JXC498LYLQhSuhxl`#e z1z2V*MZvd`IXMc+*6SFEc=(6%hbOSqhpI`$ zw}`c?xDb3Kl4xcz9(6`J$?wnG?CGEM=g(}k{a%k_H6`IsW_8(Ke0ck~tN-M%|AY)B z=LG^sw+XP;wlZGtx+F-Tr@2CGEyDVlI^1qn`>dst@X9;SVrFvnV#_rT(PB!}5 zL>3H7_n;MHEOoKSU#Zqd_0b>&1i$2%2MfMnhi#pOs3-8JaJ6Ae=BDWHjE_@r8Jx`{ zudS&Gg_4QSc%Lh)f%XvQ%Y^*U_!h*P`10jTGt?Uh%yX#%FJgBp>8}nNea7O;^;6{k zGERSf8!xLyByN*lG%i(zX(~Xl+CS{gcIB<&fP$f4gAUL&?i7> zJ`R$CG!?;gU>pEY<=TJwUus?$KCvc+=;xoD$<_d>!k_nLHvr9AJBTv`978}O!It9) zz0SPhY1vm`80qq=f`$OHA)z#|5Oz0k2uAUXsiU8FPohHh;Fpg56bozezO|7d|Cd+>yT~xwXA?dmY=?_M zvWIKn9$w$TdpuWh`3M!^m)ZAwG=g`a9hC7kV48eTo1L@ce`(1tueXn$%B;^7U9-?) zXQnMs8r{Rir6W-4I?*_<&|8~!_`nYS*1Gp$h>6g%VIs?G8Fql^xKzPUZ^18*6@H)u zVXTUIXXOMS&A+Olv1tAr>AL}(w%L{)=)YLH4Z-I%?kXt01ZYAkfw&d}49>?EqSwq_ zI{O}*SAEC|NAZt(zxQDAX%E1Cp}dtB53S2QF|>7alW*97FB7M~A}F`Uyu z*b;#*67NYHp%nj^hVNB3UIJ@AR1UJbv@A3lq)Jec z(^UOr;8&ButPYqowTAhrVm9tKEB-X%oTATLDh1W^wEMf$8X<7o%jF-fIfVEG1|Bl> zMR`y$+lh|OZXM?b(HuX!d7}2TZPp$YHxqHTLI&y;CbdgLTa{i~%e^a|(_(4)l2OP= zB3)pSoKDD(UmFLPRL?ViSdMMNn7Zw{1=AT0J+HJn)QL zE{Z+B{`(mt3(L2YXD2&t#~&6yK6IdDlOKaPw@C`atTAm-b+Z112g{s|p)mapY+oHORZ^8Zo~ZPlpIeCqwJ-KQ z;w0bp`vkOrFnzPJV777cyC}+Hn2jG_sF*8Px2y<)6RELM=szu0Z>{^u(XOgM1aL9T z3-?F-wc>xg*FAr!{~Zv|fRMEUTU=>tooS3aXJnuZ0*6s*9v~H~S7*ORv7ax?9t@l0 z4j@regs12v2smNgM>hZafq{XK;4qVez(zyf-wT9ySxkz5Y!o9Q1Pwz~Xetb~CgmW> z%Ypk-9sU+Hm5C51h0Mrk5^5R2b+%cx!SNLkTp5F9#cjgvaja&LRVeoLjjKS8C=t%D zfzDZ4gnjV5v2CE!r$?IKDk=m@PIKeY513CtP9xxwP?&P*r>x$-5mW$NgLG>4AX+5_ zxxL82@uIjg05t3)6RG7b2oHa?`LQd&^WgNiH96F_BMUozO5{S>xlPe5J1Lc|*H zi6s7%N+}5>r(Z<#&fd9ue^9J~M*ERSwCu<3eGAuJsh=U@mW27_`j5_5xa(b0(jyLi zByiZ2^-A!DWq@0|XeF8Ks>ZS($vwH(4XMqv^n#M$;7OxpTz*~EK@HIYwxoFEir9iVSs(*3GL zZJP40g=dADh!&N>?2y+dWduRW->fFiQ-Is@#dPpRh$4f~@b|UC9Y_2SZxIf$EqI|n zemFf?f#^Pf`2p`Q25BJF_(>Pxb3>38aNJldDAi#`k!Jx`3?M3adWF$6oz_%qfDx_DoeNkSnl5pU!}&l=fTML|B5@9d zO7C5;2nh+a1;xe0RXVs)f1E1rRJ~fyvjk|8RQY&SQD|82YtnqB$i>r9cp)?cKa9UWLs zi5KL+&3+(3)2Uw%GiBD)^`H_Zmg5Sw#3@;fp0*~9b4r$w}g5}MMv1r^COf_yGLOJx)xOqKndO>? zSEK2J{jcXs)T<%!g_n8qtnF4Yc%+~Wl@qlb&z`_LxmTJ0SKu(}WRpGKX%Rwqehg}` zLvCSKRu+f7Itvb^1ZnvoqZxn&5B5GlN<@T(F(`moVHE_=6ov}C`PErW0Mq>!s6rzn zn5^!j3Cc7VS3-(93xj_!y%D;=oiN_(+ zk}2UywP}L>;n#C>4#zt$(X?oV*eXzWmH%yZ zKUlRr$7Ft8w-iMog*UAM>76^|`24d60qk$1Hd+~`eK)o0mene1#M-SbEoXWHrVpl` zP5Q4^Y5Y^6gLE3UfDNgxHDitF82cp&h_!32?#PNomoYkaDHB_hp01LfXk_gerqjh* zm2@c)NUBsx6Dzl8>+%A*3m>h9dTunD8d48iOrB&Lr!*CTc?>F)#pLuJ)&qem`tpPHRxKWL>Nd3kP?)#${nN#b4xsdVA!@^p5QStZ_BMud^FI9VT-~sq zo*qhIpL`u41Fmtn9nSz;4+WkWEg`^CWPLX|#F2gu3i~ePfpEwV;eK92G= z)coxTM@o%is2&z9sGe2^4LbNP$R#0_0nER}MG%vSERE&m#C=brN#L6VMcQP@Z>GX< z>~ks%N4X$|c}yEUV?)C~O^9aeIUOwrJi}M|LGNkclx*Z!ddHLyH4@`!;Ix$dC-KwzBPwB8 zeWlq5wu?5DkwX?sYKA6{n)3S>d@>{GmRbnsalaqS(p~8!6SzVWI*k+I@gAgeIX%5? zb&>Sei5;qCYnYP#?X#e@q|K1lKNV&_t#KeQz6UPa;QnWaAD+n%KsUEM$a!viz1n>q z??7n1&gQXzU3D+_9v&I=32{AYY{WQyiGD{Y{D6Wwgl(%W*#u*Fqv!9e1E)J)=+Bjv z&j6!?D~-N~6LMwG&VSwwf(^+Whv?E(3JZkNNdu>spw<-pRa*@hP0lJFiNR+OCEW#4 z(#+lw9a(Ib{Ar=C64avRF8@FN&P~Tnt_nTKk-I-9;{emNw~xLJ><>5`OxuEAJ5ikq zN4=Qx7rK@afqa>hX)p9|XViy3;(4kGrG)=tvEzOm1i%d8fNmC z*!Y3oYuqlmM`3kM`d;APHO!KB8S%^{{oWZ1a?@*0Hz-v8dB|xhbZh$ z>l9lALP>C1g!(*=Q6%fJAljdWZUAQj&^=ve0$vJPBN%{{IUk>z-mTK*#gE}gU}=E~ zRRd|9^}!^L?$;R_%sC*%WD1Z_n(9ob!AaeJEM5V+3^#DK|LKQoZik)B>j;~d*?8K*(4+ZZPQK%UC_k-Yv zZ_48J^+!lk`Gr!odHn&%pc>7t_kZ=jrbD}H2tdz%ve*6nzsz7f%R_z&Ryk~6{KcP5 z_y}IxuLv>k=9fU^UO{7^Nn5#xP>M)fat!lzV3e|$09u9kci6b_c~OivNt@Gp2I2KL ztDFKLhOuBJgo5oELVGTN4%J;2u|QP!ic`4u`z*nSI5wyt40Ya7F| z^wwzBLOE_5^vdWo->Fj@7sfsb=vC;4;2q)Z<{Q~{HoK0S-U>Ju`Fzpr)hI8TJ9hiB zQYVktp`Gt#_Glf|c$LU&Gg~Dy~Fc_}9-Tr3*ldE~z zIXNpi5PGO17hS2JQ_UTO|ZOYGr_a|aM(!S3JUbl zV3$Zv#}S!oUhD?sbPphuP~2m96wchAlimAWuISeFxag@Vk%{ojvq)p=zu}}qf7KB0(ENN(^4UOq0|j{o%wiK_pVE~c*if?aALmamk9q-Qs1PMlMWtE|YeSNDZ* z9D#{gU2%gCv?te&L%2=g3OGGqY>d4Q*li;o_;R75Wx#HN)QSXq%4w`VnC^I}Tp{u9 zVaH1p!OUkWsfVY>Zmr0#N%RvIK!GdPJsho#_7TNhp1)R>RY=4i|B6>HoiZ04Eql9W z*447>$J^NLNuoRA^`Wnfl{znco7#SxR2L(d5d0*ja*^k1;fAW@*}6NYL)ln@{bdyH z?7rTczL|hecE-wg(ASiN=^Zc^A)9e+dvP~e+1PHe$az)Bkl?}WVDIG@oHZ}aHY(f8{A;=@cd?>j-_4!rw+L3z{Jr`KOXhx=n_ zxP&Uh=Koc4!praH#)bn5F~mT}PIk69y!&7j!Ic9P57;;iO`_kI?U`r_^?=f09D>ck z1WIJ`4HEXs$%PQzAi@@|a2>YhRXag`e&FUkb}V?y;ht-*4!~)0u0l@e5F|JyfsO|R zssKfC$vDQgv1J$B{c8v?#^W!}P_0XeNC%ss0ZIvy!d7DbrGKfZQC+lwDNf#OZGqlxd5CJlvO=M+Q103petUL(Bk&B0tmU`xN`o9u zfWcq{IBqY!yH(}S9u0)v!qW|XKx8Om$#89*^;b^mI)4069Qh?3Mi0T>t!&phi+8b} z1QdE_OdhQhoHCKL$@81xkz&YT?E zgoK{#q(|Ab&(0c{dOaf91oL^wVgB@P>u%6pdwbrC($eWK+$OGSH&hBidL_B)R;8nn z66B`#%;CwT;eaphNM|s2VU1$PljIt@T-87kG_5i3O~s*2k+J~hy^?#_8dZ(1ht`jr z%vF%=ZGAO)CTMJSi4jll=IJsvX2@M3MFaHCWRs&;-fX}xMpX!If7pw?%EEu|?1)n# zp(N=zw-2OYbbawVtD|8117kd~x`u|C%OsHy!oAH*1#G}^k@@ESj=DbuBkW--C?BL%SpeNVYB2JEbSA;JNnoHGhfQt0YTRsyY$8o0tclA++V zF$AEcWayv({erf<0AQ72v@lmXhh(8O31~mO0{9D{zIX+&Qb$-h!Y{wPa)5u+aP+8& zZTW4=P}Y4Dc*lL0VovBobXXAgbays0WIyv{J>&@Bz!1_B$0I*o24>t?W0tMNTZ6e@ z()fF;ZGSJtCn$!!XxqN7w9gL~KF(oIT(fY&utfKU@nEpC)cCt;vpPT`gj;$Phig z{%hatXOUu6>Z4shfwYHu%4YOA4{RLuLfEgmGIySU(eG{D!7-a+aJLJpU5WHUmqi7& zCe^;7EHp@GPH&}vq1K_itgQA~;DS&&TDEngJbRprOXyd6EqIY@=Lra@%zhw= zj`gWWAgwnHy5Q2aJNIJ2nu1q=WKbe0PZrM;{N+RC^I2t^<>xc?p)P|zrIVL@rC>54Sv*=v7VBZm3}D`GoZo|d_IN=DRvzuBQh5+>$Em3A9A{3VSz0kv=sje(gofYQ1NX+S0;S90e#BL z$${omc>T4*W6eeKYuZQ>1X3d9aX?9PkQ#yLn36v%gI2GV{EtI~mPvKD#gpu9`c5SJG`&`*J~0D{86TxxOC)RY4SF&9z_3W=c1p^=so6GNdu zXb4+1k9}m812jSZ{0SOufUS`FobYI47F-V#2=gn=s{~P?bLPnaF|{YJic1xcSNnlC zV#2x1yPc(&O>{3<88cR|3L1j#b;Ca|Gx(#+jctoc$gu{BP<&w>NkxchILJp zzr-;&rKY`)UX|wAl8HxySJsp9N;-~nhkTPibYF^;4_s3v!NH?lpg=kYR z-5&*9>1q=miY;!vN6Hvk(0dg1Dd}W8b<;7LyLetAS2Z-N0D|7W5mF)G7oY(V8SEM0 zg}cMj9WRNs;I86Q8RIe~N>CYs0t$!UDIrD^{yh&J%h@}jL$|`)W#d3mo1K6*mBP6ow9(?kU5&6x=%wz_l6Cw+5h<2q#zx5>-(Bl`W zv55b1XSMq__@5;_F_*h0^3LUPacz}UuR6o%!o|K5o7Xg>l9{uGS=L+Iq52kE2(0j& z8EinKtKLx0UMpTUdj%XZfT-8|n!vp^XU2Jo6Wmn}_V!|+mg#&_1OenQJhTXy&YW?P z9AAU34ix0*-ZnCc&anpM9JKKEC`KkGD^!>5_CB>T@G~%nFQ;mLvmM%&hxzio_28#Y zAm9Z^EBbYEz{$(9e{BGxSH?l&4movDIW7NtK($QYK)`NR?GCztp|&vME2TAr%dl-D0`tU}A?4!}~Is_ez8Dg&UA!}XE#q|6Iad|ULs=*mT>#wau>3{qP8Bh7Y``wY0`UqHjc}0( zyKzQ$MsvkdCMXeV%oMsc`^H6&w750%OJR%YXq?+M7$d)WPu75mMUzS`Eypb&j~L0Z zqYe017aSv%;1&h1LHI{nN713!nS)k9V9d>xv&<$MMFh^m65POjuc^AX?feYzZXaBF8a)15-;#{nf&SH9a-fh;GD>}>dZ|iMpWrf}5{#>b6TBN59$#qe9 ze|Ofe`^(@GaLNC$1y8gTh_usBopt>X2Z z${Xk&W)7uvM}?mrd(BaPrhuz}A9sb|`KkWO)`q~ytk8b(rkT2s!+2}m{?e9Nd48c! zf88qWZOJ&#+MRBcG&9e=s zEmW#vXz!&GpSW{6Ir@&CG*z}21p1CQy3yD$yD4I$Rv?EPB}Ee;?Y#@N<7S}F z^t8CX1pt&tj2J*1i%nVwP}7th&7nYV{mSq0R%uKv*S}inVKs8V42#EIXAvhWYG}pE zEQ5uFpIr47)PBlzWhc&A{--E#O``>3k(Sj`GxZY0H-M2x1LzT?niN&V_*wJ2rMY}G z30R)*G_!zg3RHfb;2T7K19_GpeVnDe8WvPzq=xeq_5PrrPUHsO&XbW@Byj2EEBCo=4u(9FshsF*KP;|{(^B>c9A z)<}oEa>)-5Q$LaeNp>hzmyg<&25A^PG3*s8rrXTLAH~Qolr;@}UZEnUMR}cn_+`hR zHP;<4W!(Oi^n6DWGeQExtq@Jig>mQPeTe8gQ<9kA-34<97#VAOpyVi_`|SA$GsL;* zViAz(@87?^08^qZ;T8jqBi-<3e0+Qj?n6grqtBP5~Bgk-PZb?(pi@%!gKcaP+8IIs8hx~}K-92pCcOxMm=2}Uy%S7DuV91fMh zgDOjLAWS)Jfa}XOD1^XT2YW3e7P$SvvjPxNARy&cet86L5==$GDgDWWM+9p1c>Ko! z^V717WOT3s{VT7>m|*L04D6S{9$eJG0BFk|zb^*NT>M^jt2bMZT%+UUFxyo%74Y^6 z8s}L?haeL&_C#%z0{K<}|%hlZtDR?!4f4jw3lIw>J zbLVE1c6_Rt=Zs_CmgZK-8ji0FW4)C`-!iwoqbry;O)s$5dyM5XN6GwCOB|0DO@oF zw*QB5N4%Z=KaAUS+5&s)vjR8KvXo#$Q)<79ficQdTM%3G2P)|cSD~(t*XHj%75`~({)zW zASAX^{mpwCGoC0(zU$gS?`2-Pmdex+6QuoKRcCK)T^YIbf+I$~;d7^VPH&--l$F&r zs|l-ni$jK!TfSBL3Aotw`a9z_U0eQ8xG`3X!A54`cxNuNT(u|(dhqmttcrx6DIeD5 z1r2_3?=6}%$*q>h`TxETDlxi$U+F}i&Z-!_W6t*%+Vzxi+xs!TS~t0U0m0gm_Ceo( zeu3|JvX}s~v>@Iw7>zKZXA-|2H>4$RS7SV!+age%ZQMcg?W>X7$Y#}L-6}JK>4#_$ za~6@5&6hvCOYip6ZLY_^F#YRi<@O>3v6-02&>uYWW;|Qt14k^jwd6;cIm30t|HB^bOtZ+e+&bbVh7 z4jlw~9N_1{?Vz~UM|zHZRa{CJvwC11JPx3AU$QkYu$WPoZJF^IcX~?-N=H7Hcb$xEElCC z5qC@tSr+i|0yEn0&Y0BR3nREK{qfs~U`E`5T;##NzCQWEo-xhI7BJq>*4$?$iBZAA z3it>a()PTeBpQ_yG%eR1X0E8*pRt?IGK^?F99e7shNk%lwzny z6bvD)b)nRPn`@8udf!o@AsppIuseb6()xgc7pi!v4#5MeI2`D^F>8H{mQK0YBqk>t zS`0s+Gy?%Fa-USAPB{^5A;zzR3yv}62 z^Gl-MmL?@b$D8;|K*-DYiV?GrZBU7Iv-t_Q7ZYj7xdi8Sy#r#t)!2V7qq>t(lWSII z%il#fer_@K%d0%=a@%~o@|(|-l~0zJc&_!Am{7jtlQZ?|*q?AP|FQGhmB#NU7Qqy_ z8L0=AcDtjnLmbP47n!@2sMuk1=RGAu)6@y~?KohVtw7xeEHw;YkQ~^W=|hW4U;S(&(UB?blo_;in`&Z+c1JAh@(b!XlW^-_S9G_FDXj7CmCDGVj%^ zxbVl1At3bwFiL;I^e=$EdiCn-s;H?=L0Awyc?@4ZzKR@Xc|rI>wUxn`k3IAy~l}t zYtI2jC%U|9VD;cUoruo*oeC`P(bG`aFns=}J&!<>Pq~eMc_AA!&e! z1p#sEs#Ih|wTeTzDQZjzz97O(_g3f>zNF7MC=Z0(|BHOHDr+71;RN+ZKaYc>u@eY&V$p<+X+n8Q zWXb~w^Qa|3Wr2fP_rJg0;pp{g?*bCV;;q-h} zHa4H@H2=b_^J)c)TS$^a0hH&ib$K#npm8v&C3ta$3qK*i1B$~z#U8jRi@;{&6n^T5 ztT<~sKoUvJNZ}_%aKb{7|540ue|3|+@-X&ARaI> zzON94Bw|>V;!$d=@(e%@U3+D3=3v(0(Kk5w2;5Ho1dqDv6%8xg^&a=F?){>T7Zu$C zP9BNj0u*zFt#7J`*#s2qMZ}(Rkk-Pk1;u*DNreYdFho+#LjiGwz$y)Add)op$m9bU zm(;q$|3QlmDw*3_atLL?2NIP~Hy_RU3RJ6R*e$*^0V9U=a7AB`b|oagpw1%cNWskk zEO_>d3WR`{ezld(@DJnTDGrb4T{HlSeG3i_{tK2PYhO=X{I)s(v7_@7U5I0jB>{QM zpDJ|s^nX7Xc6hkh`#tKG!k#&BHuW+Qp_EQ$IxEgYUKfR&+0F`UuDpJLaAE1>ptwFV zP5pNC?@40gZc2EzSZ~vt9Q(`EQLK*CZtJ^?4|2SdgGHO(I_zmF%Pn8?h}}75ZF71+ zGv(VP+jC(r&SK|PpZV{Z4_{m`rWK}-=ineKiP=8%xB0MSePsP`FZj`|%spef>nZ2Q zzX3_?*wJ3#(aJl{jw!goZX=cX@}u!pp}efpR=Emd(!L1=5>GGHh<3Lo6)1?jewNG! zUXs&jUK!c7qKGpcmmZb%b!%a6Iy_DuNDkl|q%Tbnz{L9)i9Rel(#voz(2RmzTfRR8 zY+e3P3&FDDsonL!d^4nN>FM(*0H-sOWN!wfd2)b`2mDO9LL&M0+}0x5n!F^!Ex`O- z%-Ej&Z@mZKj{N6y!w(VFm$}!p2&vv^MVtYB$8p8Ygvs~!xwhTqmqt@tGPY0d7aPWN z+^575S_84y$WAJID+wKW>Hk^axrNfFFVYI}uN}*0N{KOY{O1Rh<7HNFF=zYd=D%}` zPE4G>@VaX#Wx2pRfTK#(D$r$;Ol+h^tb$XpO95;uzq;z}zK=u3yRjbjh`tcyZkF;^ zVBY$Eq_)2!7|8av#2!aGZk=|$G(FJall&UEgN^OXLXwXTNOf1zNrW0fFqxO2Kg0Jg zq=0V#+}+i1=Lu+4eMef=q4Qv6ldREHP)y$t8yeJyd#sEN%JZ&li?)Y#p0pEhXnc?8 zv}}qBGD3nLRvA!VRLzC*|J7mMPMrm}gq!DdUN|dBxZ0L=nJ8Fy&#i+wUt%vWELMOd z1PB!PMUi4sBP7nB4*}~bpcCCa>+&i60*u}O5;`61Zfs961UkA!e1cFE5Nzq_>JC7Q zPHzPU8@i+2%y#F(nYja=I?ds8*r;9Ot{z@f4Rpmt-Qz zp7Dfc`K?~AR*z^XUWv&}kyrRgTVtoes~CRWOj(sw>jxNc*y85C*g3Jf`g*hmsJ#F4 z!vbCtI7>4k90z-n1oa3IV8ttD>=;LYF95AFwT>y#AM>wEwJ|uLAm}C)%<3hH zW83FrZ-QT^M5W|lm8(Uo$5pN3e>9e0S;U0ZpT5Ey83A=k2RA+D@@nEJnBn2|k^fSv zVfFeq!9=wGQ3OxE#G|T_{a2}gd-+}btKjm!?V!l`p{!fM0$tWHlYAbZwNX$>Zu(K^ zlVi!`$g<{<_U_l5BjrEeUcG4XHshOaMc$cgrdt_JhO_Bn547)88nx~Ggifdy*D&5+ zQarn`V|qV>lh0rIU005qUqx;6dO~+ybF%}*chq;!8SbgGIs1Z$pk#{t*R~5havSuB z?2VFJ6MLX&&9H$ixwN&lHEU3*jMsobCAUE+BI1HhaH|G$VHeGC0LyLy@loa%qLk#2 zU57`HCjbYo{AOY|P9IjHP&#c~#%ND089)9aG&u zRl1XPRmX}$8Tk0QopQ;G&&SHf(p1aA1cvYWx1^CDh%>O;Y0MdY<1zCO^tgi1#}`aO zzy9?^*PLlNE-uXDdFpMeIK9BxxI3eFUy<(;vS#!VZD zpCPOr>}|yf^ylV^AJa^IM7(-ouA!hUs!i+4KhIrv_QxMRGG(dBlm3+7dHcqpC13j@ zh|P`0LJb8UQS;hje#w)mM)7CQL7(B^a8D)|E+G~*#>=rEpr#WaL!_FHY{Kmv5_x>5m(W=IM+Yo zmpx+VPWHURhqQS{u#{ROYK5*>sg;4B02VC?! zgp=%p(B!j6rg9R>gHr_R#!sx`aDToQMmLGAS~%X+X$@QWm`HIPgsuYI(?W!v`h`{` z#{MdfQ!T;#>Axx2Sa805{0z`mF_iEfxv?Q?Hacb%Rsw5J37EbWT$ZI*1%~W3(Dopb zb;%&6MZKtR5I`V3*wgcp+`{#;95WbTlX7My)^~tM;lrVSahDE=8)tD}o){|(bMz@wf5&Lpn?t2{<%S4TBX|`9K zS4H^db7)%J1J*O%_pIXxXRpK}8E?Rd{kTyh2_=_wisTUO2+kL?3b3Se1Xfg)@9gfz z64}s41!+x4W+gycDp&>xOnkU!1@|K;mLR2Bl@v?n8c!o;JUY1mB2jZMm`7fPBTUGULY0i@E#_xE z$Ac)Exs<0CP|?O*QH}R6yNsURC~*8{62h7>z&IJ^UEt@{?2>mTCsJ-B!!SdM`QB`b z`n#>u=CL;g*GioB8tJ@NPAlBYs1oZepTE{9TLHV)7v8ja zETdOKH_Nt3l_U=mBX+(3^souq$-?JC6=WI?DJk|aGnMj1_TaTh!_%_O`<@zb(x3T? zO{8Y(D8I*=LmQQ5k5V(9KF6E50}~dXYb)sI(Q73dg;~&cBngKMHl7MeJK;+B*&f%p z19D6V0&~1CC15enJ-gS)(F+oN5D!A~L!#2d$wF8W4g82bb6Fj>6_8!*fhNg~Xd!b1 zHuwMxAQ>UrZ)0nVnUQ3hNs3z*nubbUn0=y3C{h;eUrEuYBu_{wc@eMH zcPo2vP7F|4Q)XnDo26eXZ|T)CFV?J=-MjzM%_8C8r9mQ=+GE&`K@2Y;1^?<436qBJ z<1tMkDFxp(3^q&xc+WXGDw_6B^G}-CH-`AI)iG z=nd@eM(nd67AGNVjxkkCSw*HV4kY>-QQt9L&$?s$==apv8+FPeMwCd=j7)Uw#i|O{ z*~?Tn-k;$U`Yh9Mvymn1Z%I*Y&-L^s6T70#j!%W4DvX6K216U1610`fIXkaLkZDt^YbTg z)bF)04fTn5Pxi;)*r0(i)8ep5VWH!NYYccFf8`l^O1u`XaCSfg1Ku^*A|7gBR$p;? zMLW55iC%TnKL^^9xo6dTQ+}806Z-;CDfYn;cNX$fZ6OeP!1v4U3UtvYPMqimF#5l2!K?f8mDwAj z2ykVUq2b=m^%ts&P{x7w;je!V(AbqhiEf*|%yyxn`wKN~;z^-*Z&QBUcvY5W_kz~A z&%!H`;VZ3g|L4}QyHB6s1?!^j#xr>}dfgCd_}(`8D8+TsajRn4vh2(fo(@NN5Zmow z=u)>8pIvcGkoWqnN@_a$ZNZffo3~us?gwt?Y=78l$n_S#M$6Ol?rdYpxXE*oc@i+J z9k2zKd2?5;Te zsp9=7{$|qn8{W4`eLJ-&IK4(FX`IJ#mym8x> zv|uNtsXm5xLxTX$zT-sQJ#alCRT(HRQfG5|L1M;xFtRQW2cZg%D!dTeB4JPhv$$El z{O1~E)Eyq36{1>6%mygUk$bs%0XROU^R`@xMgBssn>7Y&TysxIUoe>R&3@-G)86&| z{rgc1h_~AX|I7x=C7Ks}?JlDha%_jcnpUx3Qor({xliEPL+U4Zn%E52gO)eBQA@8` z1%)2)W=b}nDtU5W=-gWbW0uXx z5Mb&B1?RKGC?^NU6!hXZK^>dM0S)o5y_F_zlJ}*9I!f&;}x#>QI>u``*Kx3 zi`eXZZ0bX+EiYLIB(zjGyK|^X9^bQixL~97_%ehGNJ=D!-Cul1{pi`rgb@9}p?UmL zd=LRq79@1c^P=ic@#DYAg8Y@QCEa~#y4tw>FV^&S!_b&>%67K7JZ{NyWq;)KR+*#2 zUdmJJtusrkjW1*S(92A1DKiRV4S~4_if4xYxEA7w5qI2pVp4Xh-TVeFI>@>mzkzyx zdF@yU*XgzfhKG!ShlTD`{Bx$)cNS>HASsfNS9AnZ#oh)fNWFJIGG{xo%Tkmd-UI3~OLN?*0-Tyi z96|~N)RZjACpLtVKCg=Janfe}@0ks1?^)b0gf7O0Sk#d;eVeZhOt~DP`;Ex!j6kIm z-^`}F%u^|ClOe#zX^hVgfD?UaqJXZ0C`v$qRQowNJtVfTcsX6k$4lC&$$1(H`hkAn z{kpuZ17NxEGr=(;4}x_Q@NeRoP2>OM>iJ-);jfTt{bpSd2{Fg-&!c7ud{y%lmP7Ej zZFz6fwEIQr;9w>2C=SsXn)mF9Y~$d4AM3rv)E~V{2jM)U3>PZ71L(ij4EBi+J@lm_ z)4w2fH6i%*2>B+pvN2YFm6=HQQ{a~CeR2(v&^El6T1FQ^%|?-XUwAP_)wR~7ZQtqJ z;;!7EYvuB5c^kSnjS=Cu76i?szq)oej=AdPvr>|s=b(~)%_3zO_hZ*)Pho#Bbu-K3 zkJYe>4PmVQM+n`2?YT`No&b^Ko0npld7jMPFf)#BHL>O8&wYMnW4(0}ZCq_}KpUjV z!iW`uC#6HOkcPfNaoHu;P>Ho5gvh;n;ml0{GyBKKPXn##Yt1KYgsEUKkDAf^(FNE4 znPZp~ui(g(kredG;N1^;X=pL@fho`TXkI!V);bq1U5d06FJ$mm!#ys!PV(COJ2W)J zVMnRIUgGm3m`WK3ku5VqgxBB`FMxiy({0lZ$gY=h1*jx&2B8pn-O|URt(Gc~Q?7F? z)orOJ-+~0|vM^%w3kBO+whhoEk5VB58la4i3SNb8@6PEuCfEYjFW$88srAZlraeZT z2yp&$*f8`%CKn{u=z}$qot>Tam6EJXn7Qgb2VjfN4^V0-3bOo<@)}Vn z4M$oB*3sL>8W>;}x}0y3uL^n9fEkD#mizMDRCE@;8EvYiXIGrf-^A4V1Bie>FS0jmtz09UF6$%{MX=^^ zG9D19Fp;Zvrk}qN0h=N(d?d6U0{wr^Cv{Qtw$^)CR-3ax_|cr)2|j>$4JlM$-PaY* z8aty8c2hjmMYXjfPhSfbyMl}$#=UKRzG%l99A+e?Kmt*$FZ49SHNE6%W+stjGz-H< z1T`>)s^F6p%D*$+N;7cisvJ`y`*3?T(JlCf#wZ~oLR(QD?8C;^%aGQpOvBtgw66x>8@t*sQFdV1oK3~+cYh<7BkShB;Tym@f6I@+0R9i?h!p=GsTuq$!I?%TF>h7Kj3-hj zsSKR9*;?QJnsdml{D!*lBvz8&kU7NKcMvMJg6UsS8-kZ_BWV5cj|LN%6OK;s8{uT-A$WP~W zhm{^}dhgVo7FY}0Ge49tfz&h-l zsdI}XWH~z8x*i~S67lU_VLs5PJm=$v9L#*fD~WtaRVzm{1O;bxGQ$2j1z%xrR=!#G zS~P0oX!jChvFF=paQKjtf(sq$Lh{XRb;~pj++yl@aCml?+;AT=!D>YUia%h>7naO~3x&DP z5T#b|NB4d_Tww)s@^hEAr`eh`@LE@ObP{xT5kY_jleUN88p{dY5vl*cmo{KPdlP0@ zs7q6NyD%&LW#=YVk^S_B4ER52IuLO|2YGhOf5d zJm5f{2~v`xT6l9}S?1Fd-_9}i;DhvQ!3y*hBga~FY}G%=Q4*dk()#)i_unz2u3g^P zJ$u#U1-)Iqw(^)&&FimnOPC|aJLVnH5*bz_wo5J!mnf~1iSwb?-|KJ{POJsielh>; z*I9CktX2IX(4Q$^J^1B5GvqZI{c7m^m9&BwnRE54EyuvzZZH*$M4#_;B z7Vu$u7;v;V$uM#+Mo+E5o@e6g!2dw|(22mYDa~?}X0AakV6uxtnDp#y0SteYAhfm8 zU>W<=_4mq(;2EVlSSV-8`{Du3`S{dc{2xTGrGo7W)ZKel18asFTC$M$>G@Xl_IP&c z?_A2rwoqDLiu^XJ4v%QTub8a`--=iNZ)Nv?BT%1^Sd$_OH6dzq~-1@HNsWJ`k3vl_%Pz>Dpm6{`e=SMSA z3f_E&RuWYv%Odbifds)*cF3n6vWlzgTNtWyrHL+m|TO|)|6lwkrje|a*#(6jXh zyD)}-DLFow$5Z`O=jeb66Iyk&=2Ps<9ki*Cj)`MGwlLVSg_LCu_UGBzT)+9_7np^e=1k#@^(V_v!P|wS2IU zkHr2MDmElGh(XJG{F!lgE!YV|h4LsjCE|1f&3|WCMeggz9 zSulZeu-U9g^~Xh_x@aDlsnK>SHv2MUJ0OlcD^d z7s42&hW9g*s2s{>Q$apOB}mZ6gsTCfN&;0?c*Bqos^SOq2_l%_*SIEVT^m$noeiAa zqI7O#bEp^0&zv*KJpiHy5%5NmAnJ6Iz0N6W1O%r7qz(Idgac{9$VUNi3SuU?dy6Pi zvnQUavvXc5!=py`_-Ld5WdO=GFk#RVGfAE9rBzTruIp!vkia}35dwhR0^f{61@Uaw zu-x=iXSRZ0T{eL5C0Uv>;2cqgI|ul=^%%lR$KE95bsA`O zO}x9$z1u3NSpMs7&fd2Ugk!Cq^`99Nt>7^o`X4C@O(9!>+Y<=BkOkH28XCSb!Ff6q zlr%w)##H}>e7nbUiJnL6p%D9AEYkANp9;f^OmF-lqx`kwz`Ky~tNNlc4N00jdPS&s zZ#+xXfp@o#W7UV3Axy#OvURDNBOlqV`~ANI#$EMF6F7KJVyU}chu5N49ag)Wyrd2n zv?pa}I2#{kc-5iofc|$SVD5gvoK2okqM%;(Zx5@BeMAbWCFwZX*qiyu_!Rp#O<%Q= zt3T&tb7lMG_=cBD!2sThGKHNXtJ0>C|luCy2B}`HT%Ub6vL>3HQ<{W zm))>*atB->6#R2Sc&=N?U~wS&f`GC+99Z!DCl^bdq~6SBp6l}(EqfwgACDa(D>YxverutMv&0Zl-hfd01U7E zGCVz~5OhkjJn$%Ba6JYr1oBg@o&O+_jG;)N(Ge*gJ%=Mo9%Ngt0nagygF2i5V2;2~ z9x8x|poSF+yZxdkVDO+Ip%KILV78z}1O^@fNOoBT$S;w60Vq000*=U&kHX|@6h3gI zS_GtGa*H2fApE3a^tQ}{H2@X+!1Lm9&e69y#jP!bI{sdCH|&ww)?|&pzVW8s3RtT2 zISO~D+SlA>rsB0bjyKmKpf;FL2qQ|wqw^WOf0f7*52~F$YR@{QYN*`ut#Ywi{?_ij zc&_yOsN3HQi+m~`HK}7h+xk*c`lpBAWs-ANzm6Gt&oCT&FRUnSxn@tyT;8~@HleO` zjf|b>8XS7!s8#jOZJ^h!xvxQ5klWpp9p?vG%!xc`pi6HTShzQAR6}3?7B1(jCSchw zHIAj$#GTI-q&HyfDCf_IwVlOo?w|^^mj%L!GhK@Jyibh0k`P;xV%b}JqbW>3wCm_4~S11xop~7>4BxnOf8dzl>oU|c9 zq!kOmoeO;NVCiQdp6UdxKLr9-{2&in2(7a%cibPA_RsAiz>+0BGn3CX!WROm2s7;P zmhUC8klLC&Cmv;OJGI(-i%Xa5Pscr zpzNh4G9Ogz8JJ?x_zU?5?UTDX+kML`l*kWC_t;;T*gq3062KuJl^F0;lHqijq+Xb# z1V4BDiA%jP>fOguI;m-G-Age3bircdz2orB+|N6USt)taZxWVGof``p2OWwDo9WKO z8nk7BIdcwi4Xj&JDUr|I{DfnN^T0$((^Pd_(&H~8;Lk1hmWz!IlhJJ{RpKngOukl)78sYza&nW?<+d$O-V`dyh*6&=F1&E?Hayfv;5E^B`9wIaV zjZ)ducT6Cs(P30$ggp|V)ygrg5?BgG8mkZNk8@Z3ZCX7# zaSMWD75_FLW3Vf0I^1pQ2iQ`?S}`GS^D+|6a&}H`dpFSk6nEXhhoC_6@2xjFqu)`e z^}oRGjRQ%h3psoA3@e`4Q1wL&mzQyN`JO zGQ51{`?;y3{qIXX?AnRVf6Yyl`LM?hNy%tzZts?B*eoBewK1110lP~umw%R#1xqcW zW5hQUhQx|4y5=s>I@Db7&s`w2&R~i4;-W+HVzV*514m1e>Eit?Sfo^jZ{pC!+^%uw zYGDAik1xr(Ch7w8l#FCf;6dj`LWEegc|P!CNRNH^${t`3;K;#VK_0YL0vm?^az%jt z1>L*r_j(S}m3`^brMNN@U){+j%71S&tySU2)e5+ee^0ziZIO`9W?Asq#r6^&lu>!|TZesE`qa{MaHk&oR-!;g?V%o6OSwc*Oh8okd z!z*17l4GiD$hZDl;M}zAtfe>`tkhypUn??T1^dfLpm+fRCsy`ENRZXYuh19zh-U}F ztW1DclfrCLyX_quEWP^G>fr(>84NkdIPoAPAbW&CXUqj}Tw> z#!ndM)Quj{)|KXW7sxz-)%mn+JIt34jrCx51HM!+Af0DE;Xr^I!itf({S|=#reVQ1 zh~OId`I8U$s{nICCIn?YZXU3#gqb1Nvbd`z0p& z)@@Lm;DEp+Q1BBpP+(A;A4VOsvB0eFY5T;3Gs$%v{e%Jy8{ov1*37So%r*`%;ob#* z;=xzGpIpAPP`vLQ#vQ}cSiiZ7rc9f>JDzfH`)}YO9Lq7vYrBl(dhaXFNV8os7gP&I zJVPjR3++kA&ub^jPp@y=zAII&wKpxJtjn`sA*grJx*0CM_uRQAt*tCw@ma=oa^d8| zwUvg^joL7Q;#6HH>4QhXM#WSYy>4gDRExtDt@oPM=-AK4dqF)8-!{09qEioka~VB1 zk7w_{bWY;(u=UPIlYl8mF1>Y90p$J9wTgw3x-zE>c=L@sIA6-f0u)p(AcXJYE@4(l z#%m?9b-9#pzR@_08^ozk-^?|X&y%2s1!ov?_X4=(dveZ2qvG4@LEAX(T>YYAw8Ykd zr9(3OM(4s@S3Tm{?eSU2z2NM)0d}ocu*>Or2*4p&@w#P+BOEBJmyfbhxm;xrwaS}j0{5bR0SrOLt65t?;05_wOlVr+ELK0U5 zg1sy({@Y5-ipRD;(EV%BKL4pM^OQlJ%kx<4b zJZ!39V+Mr@l*@W>c(8(g5>i0iH?A2BK$))%dxajpvi1H^J2YK!6dCRZxXWTfzaT6sGc^Q!p+)k^zgos6lheJ-P` z)p8@1c$CpdC4U>4_(;$BWijMiZDn*S-$S9H`y-VGEziiNZ;S@fI)9iezW-fdRx&Ar zANRTDTbf_YPTZ-tbdwZh{YJKwpARk-ecn0c>+bAjF~;9|;oYG_ZSJx0t~L1t+qJhA z&v@o^*q^v<(O*Sy7MXOl?wm9K)_+XNuGm5x4?qS+jL#2 zz44}lahvV!4yD6y03u`qqG~_6l~uKcliN`R2q=(ts9r#H$dP8oCbzKgkPTCZ9c035 zIq@s9qB#Q1oZKZRx8@AWA6#YYC`V!S(-U>#n3sGVUtk5h`De6~l&OX~e^k9n-!xx> z&;#haf#Lv6lTQ#0OS+>sH%V=PQw7OYX~3=xln^90WiN=2l>=s!CWbekg7M2QGml<{ ztv-_GjZQ%Xm?yRR&+XbgQ!m~hXMTC_eyp2|&*XflU|1}VmFUDxTiX_*-#nhdp&fSD zK+afPSt-OBWY1}?eZ3ji4<1cVM_UzPL;7gsZJ7&`!ao|o$h9)KoIJomu?vFZDJgjK z`CK!L2NiCQvyMFioV`J?r%MRp#&N*eU9p5H&~POX7~kH9*!Lqg#I8w59uHb5|A!p; z(P4hvkFb$_hUP%_C!^;xZ+m~Y8p-#LYZszbc)b<;)Wx1F?F7OM!VsSOYe*?bK2UM< zeJn8N{`a%^#dp7b)s62&b?3N_`7T^5@APt$AtPE@vwRAel~d$?nXVDce(QVE6#wu) z+%u6={37WKs&&i7eIYNxzkL-}F8Of9?cE8#?|&2Q=mi& zV3!lr&Fs8&K26_GN0d+4xsReSl3)tD?z3kG6xrx`@D~JipKQL2$F~>p-|f-n;zj2- zh*ZS^Nc6GB6(UD?!Ry@^I4&=+uk^IKRFFlW3QJUqj|Y-wL? zn;@|chQMR`pnoHV9m2}`5@>iKJIc1a6Odtfur`8O^v+w$Spba@5|=N#$csQ>_8~p` zXU+g?0TjpGVEnCwxDLkioE>Y4*+86_KE}O`;OtOAQoQ+H(Jf2Ry&~_@`~Pu7v0Bnd zAZAks8-@9!C4NlRX~{bdb#O~u{`}@mHds*tMtEB0wle5aoEeD#R`xwktE+Lpa|byV z7ZUMfPZ7=v=t!J`$q_9Qd{(o7e?ylK*%gwN&>;|$i7pJ)Hwui0s*iyyobk&qtx}ch z&^GYFh2TF~8+bSuc$k|3MDCp&;3FSNGGeBGp)j|*L)s6rkG>V&tXVx%znTuhkq3wy zqv1)PvebyOY!^MstgZ|@7}y8>eU_bru$TEFE^M^Hx#aj}oLqFnl0 zx(57UDpQYf9aZUFUh}T3yO%~Lj{gn08T82Rx5z0=LpmcWvGpzOxlg(Su6lj5KPy%R z3z51?5tDVlO1G!(AF&=Zz?;3@ZqeOerJ;g*_;0>Hiu5GaJGi-hCh^cM^YI>umfZ^t^moQ;Z6WY5 zCLSd;{^E|5xUrC=4-pjYWC=e4 zaquZ4@miQr9w?2Cjg6~7S-Jdg7qVtALWse`n}7R`8lE+|2yWQfk1K zB`EUwViVyc)A3swubvyJMOm|)D2>8XQ1-n9qV<6XTKhTmvFSiG}Ziz%&qUt8GXtSuS6oLWe)Wf4ny#6nj%u*U=e^ zp3Au$F*my_O!o|ZvJ2t%2Z8}85rM-2;a%xNKP2eW(jew&iiaAyI01~bS+1cnj937T z(7rS-#RCk71LHN=8Hl53MMImRJ|Am_fEl>=d$f<4)w-P_L4ZI@cqwwC^_~^!jt{pt zd;Fp=fCbjjPqVZC6u^zIO`a9(M+G9OMWR2gTj}+`;@6 zr99G=KU}H`AYgWOwl5kO-w@a9?5y>23>XGL_ys*{iakeV4=jZeIbFbZ$qwyCjb<8? zkfK+mA&D&k-3o|LPP821w@NKiz*OC=VkJ4(dIN;jmXMIp5xB+{xaN;Z2uWR%9cpst z6uE7AIW)ZSNN>ATp_WH{pZf48h3Lge-URHhV!?}`A}XL=^Z4m}5?wDrt0h(MpKxIi ziMckkb9gJObm9=Td>A|av=N)NduZaE_36R2s=d4VNiNS=b_03^=tB`LJ2RHfx0?#R z-IT;S6sw0C`*kQ5YShbs%A2He=Px7DWG(+_pHuPgdxZ;MuBREQ#N#TDJp-57rtLPp zfWJwpiU$jNIT}}cmaA;SbT^P#>H|(1#`5^GzDAZj@4ZQRuS96-Ln8R3x`hZO67;2Z z@`6wBARW{8O8~7mtH9g*oTc+O99UsbN=fk;R8g}VcBd(r+@<;KJ9m$p;~lOdLN`l6 zewzHrK{JU3FuoUGgkd9K4nheqNQjAvAuF2b5kb+m_5fQ&;!N|;pFibWNWdL1U?9dG zqoXORW(?UAKud9-Z1fFaX?CiZj{g3DrvK%VNx$oalyU8adZj9}esGJQn(~p4ij31=gQKMld)>-rIjq#httou=UQJYPBa>qg=G(88X!T=f%}A zlOs{ZgVfq%tNNEVsBe#x(Tuh#H*%e$eX*m949?u(xut_P-xfPb%y@ezAn)G&Z>`_d%;ZS=&twH$IF4rk-#8gUcwKX7dQ7$&IGd$dDTHAkV6Q0P;fAKPVH>C;DUj)>X1AFdo zf29B@)p=HxX5$nSqhK+Q-2JaeCSbSzV<65G!fg3eAg7=GLW9J$KLVp<1 zMr!W$1+e0hb*T(uXB>O!YeYqK{jT9686zP4_nuWl>1)@^fc1eT5cJaEegJ!66{G~> zNtfMM2)UJy1Bv@yqkAXq$URcv2VCp$Ws0x`0{I57NCY+X*0+3&NoYT4ozfy8W0c`K zX*rmTMX5z4vS?vQm|td>-73iC5ZH*i1L4HU+9xVnwF=jyhyIxKxyD$xWrKjRSO9Cz= z*1IM^V|Y%AJ+7LafHT2{N4Hg2UDC!xYpj{%_+EtL5J(m}vns$9HZz-!!Yqzv8GVYv zZVn64-g3nncqtQ$x@V>$eKhcoxScLhGdfQ%xqf#ENk8PU&}@3PS~= z%V2*DVc@?q(X2T3bnEk5yvo>)Ro0Bp0v;~Bzmje7u`xon+k%a8S-rj|3E!omMQpX&e9P=IU!dVEIGs?R|N*9Kq=pz=NO zpFt{fx$qYF0t3~g0&BxeOj2fDf2k2L`DYF8^YNlQxXAjEUJ}*^=VDb(Odk-R|G3>6dspWdoEWiMn(5gZdfMNgr+C<#f%;~wM-=$( zsmo2jQY@@V`@TWtGvcR6 zi9llWj9m6(%Nopwu7>7V->84wzOZY6h)i z@37}i|HlZ?s22(0`2nCm!U#zLK`VWeldnMX$}0jm0Ix7C<4bk3BCO*ksR$5#?>RTz~E} zwVoZk7TExYfyqcOfX&WKI|5ZIO@kDS6a_RLgwqUOujgi6tO z^FNL2F{k!h7A(7^1H-qz*{Pkzy{Kz^XIvD`^33X#Wo(MQ#nO(OV*=d)`wt<0{fOB{ zxhc8N`v)}^yO4F3CS2o2c>|OiIvs{Kc$%4?ZJ4-P|HniYG{0{ z4{B-~mPf$Qs6QK6h&u4GrlwIcE)Y-BRVP}iY7q?;|H&^bpq)&WJB0IzjTjcSg#1Fm z8QJ$eAR9^gH??HXmN#G1$HYGhK3+E}14Xn+6D<-=nH@F;Zbjs0Lf#?lNHVS3&H~VY4?jLeDA? z+WdcvWbH(fa;nOI&l`jd*}xZ)m;jzAgw2hhB4i)@6Z++O$Z(~o&U$xc}HXY|8f5^GqXpsv#yYtWY4QaP^kUf&U zM>5OK%E+cfc4VZ4qRa?M_R7lM_v_R5cc1&5`>)PvoN#?U@9}&+pO2^X?u2WTcFN0z zTAm(^y5c7e(O0#tn^qeG!;LtnO}mGYtJk|cD$@3pDN(>(C-+2l)>t;l2WF{h7dl*~ z-b(DmFApLpx#@KZ}uy|RHvEt&Tmbs;VF?M z`0n?ClmjSRAr0CJfoQlfwa z+O|D#CV1-kn1>%UAB6q}RHTB=sQ7p)Lez?Zh=fGD646g+4@AI{O1jiH;^{`K%qzs> zcp%ntW}DWj@{mr3KwGkVYt^&m9XCV*1pJnbCUSw1@dS2)uU95ywDVCx|2YMb=)+l7 z8Q2Q|A~EnSQyS8j>fj84*v$DWPWh1QPft((0JJXf#HMIvN&yQj5-y{~cP{}~iE=S1 zR=ogf0m*|8th^L!^>jwQ1i5!rHF%uupoj~>2z z>hnPSY5BM@4Szmu7pETA>=&}2=FQBty8@x9^-C{b#Xv}K4(fr>+(}rjP>jswRO)il z{w*iwj#1}szgo$dfiuC)=YZsiLAQ1%ag9=m!I~S!tOo?}p{*eAHNGeeks`2yDRDpV z2zmr-xiEjM6lh|B3-}{;_7~Uq?aS-h*jd%le`R7r*cEsZ6=87iCr7~V@crRc_oz6>u956(N^0x{X~$xAT){k6k3iopy)_mcFoso z_ua(!5^>#F))Rm2UH*lWIcpj|h+Flxr$Ov9F&~M9;=G50=3IdkzqdM9Pm+aSru19!Vm7oP>?cU9t4g9@EvUA_6~@!)eMB-?KcbE9j5zl;6Q{6 z@o0<|6H^lnC@!+HBKN3KkS?2rt}!`~pf6tepzA>U}?a}#G&rH72x{?3oF z^zRf>=)4P9rMn;~B^c$7&01DDxSl}Wc5_NGr#Hb)X)T|8|eESYUF)g*KX$Ps^lkO7u?x5 z+Td6iOVYCm|A;3TVh!i;gCnNzKn{MJTx1X{7s~p`E|5f4%iWma^IxlmX~}jAK_Xm; zw>pd!HaE+`LI5XEgn{*14-I1;sEf5_hbfPn-7h$Fwsu?n`P%&!Qaax-cxh1nxMG@< z^a0*l%tVr<)m`6}ny_>*CW7q+F(B@=v7K`_Dw1|LR4*v4`*}eS3l!Kh-45m$h6`v& zZ^O_MA?!igmmAHEP(qxXV!(BT@0hXQZ4D!L-#;P(;82JMzHKt>fFMZp-_(!_6Hok{ zY8lH;6cGXYMIlYk>_Zqr0x=Z1#Jn6xi9AEVA#zPUl(WI$P?M5*Eu(oSrrHkUz1niE_f{MKJ-e7>pqKNYVj5B0+z#-t0wd9LtQJ9F?s@2`O8Lqj+zn#Z8@>s zKdjpB;Rt!1IGe3q3A`oUbt%vJu@k@#Iwl|uaHLC#{}+6`SBKs4Zo9S(mYi>Y4w1J| z%08vPA!*OFb}&*r+@TQ+7exC_Xhst`(5XeNycypK%fPxMVP}lK#8DMl<66e4}k+8_>iot48F~8`hjm8 zjN$5;GTzi+{yIE7gjyTMO2CHp#?c|>1Ny>X7*oS?@}tpPjD`wq%K`atKn>;KcOwl! zfoE|K+@2!N)+HYoTE-M*RT0Ql6s=}7nCGSeT`cis2`*k3UOyZ6+q(4cZ4)5OkkUBA z4FD3z96-i)v7&<&saA#=+u6}*rD$6CDqu<(Pmcz-GA-PO?Uc@2+gV$3Qmb&u^gOrD zh-|A6!B#83$hyQoHD z`ks4ktjC^EwFG=*4IP+Jz9aDQ^AIm~@YE2ClV?{GgB&OPnO-zPS63|$R$P!zoKs3B ze(BBFaeZ-&+KM>0@mw2`VM%rlaes(Zy^x#XjQudfm&o6XctkzSuGn|Av4(d_X-qEN z5U9$CWakec^BhZ@B~fZP=f!(gc@!7!!))vA!>1YN^bLpp8k%tqZJWi6+cmk_|+UW z@^~M%8?hYIlF8k0vg8VlBUa;Z9HYmogYFD}3pCo&TNkaQ2c`$%{-K^aKn&xAn;`E{ z;RiQ+LyfKS=dThA;*|a$wTpsbbj)=AJf6IV=f#cqBvb;E8vkDGK_J@qqIl4x~@jD5&n)*hE0OmIwvehbMp_hALyoJb_w;EfJ5+ z|94Z_^iEujXC(Q00gZ}i)4;%YlC$v^EGgRBJ&nahZABmQy=}Bfj`e#O@Pp&9>Kypo z0km*Yd!DwEy`PpnatdX-8%50^o(BqFz4=l+=0__{<^Fh?cWc33Z21vgzT59?Df~1S z9p^>W;{e*v?1r~d_LQ7e=P0#S_OELGNpE^!uW!lo`hn+2S)yQ_i=12sCkq#Ux;kD- z;>%)p8%Klra|3U6m+fhYTQx6v4sB;f7Z-bu%LE=WqHqPACR{Hq6(zc{tQJnkTD^#!w;0LWEZk0nYaeK|do&FJ! zs^hR13vP{G=T!Q7;{zof#wJ4iW=@fqYpJR7mpb?-5q!zmc3XLpd_EEmgd_v)x^rS! zr3dMQI_l_{X~}PvqV3b5X$^&{0-37h!u(b#-1y??AjzWf>efZD7|sKXGo|b2z`#cs zOtht6wx^|<1SuM{qIvjW;B+zd9jm*xdzm3`L?~BtIEPCpF{-c=YU(t)lbrgJ2odRi;>}EwVGxsL)8H zRqJprj$kK(P$Xp-$Ij}wJ#%bLy3g0k!|)irPPU5&w}AsFt$Q~e;JgY8(54Crs+SWo ze0(q~MWU2mUW}uXRfew~DZ)zOQG0qIk5J`JoE?Jfd|BD`v7#Kxo! zo9$k6xpQ1vi!EY0eaIXR^T}TE3Rb+`-QDLojhCJc1=d(Y<}t}2_UTikw*G+W9+0F` z)6#O_fxty&k~{>H!n9EZ9K|Z&|Clf>~!F|Zg6I5+v&#mva>ZVCcIyMuBE?o zKCg{dOnpdoWyE=Tr|kC*3(bwyGtojFE0QLRnOAqdHLQudB5(`ATcnIPnco}NkbfF+ zk?|eoclq7v_0T$_f>}kL%7t1j3VDoAk02ko*LQ}^@4*k3489z0MuoPT;5UUAstvx$ zOmQA#66vMrxHL^b$x}O1kkp^Wu-SMq30t8>9yu-P!F=5oiyJu%;RBxS3kDvnH-jPU z>Bp}jMI`nL=A0jdXT%|+E4RD7jh@&gzZuU1f~Ual))r$=6b-M|Zx}vK0hYlPNfUtP z-99)-OF>R9f+{tti&<+q4S*ZQ5LYnbee{E*Jr1(|%fyz(VW*VY4k!~MzKeB6IZ1;b4+ zU}Jq4k~%VoL&8DkpL2W>Dd%iynP{0wxWVcTzVVZA!~FN6@wB$_=4-NnPfY`l&r@p2 z26d7?r$v8r!OqtSgXgP|>EYD;ZC4asCH}fuc z<{49ist%e=3r5Aut{O3RAw1!q*W*WbWd}9&DU&lpZTM%EHMv5nFOXZN?T$J5Qk&eS z6p+Sq_LKKHbMWSLJ#%klJSA_=MMn%}8YXgy+Z_L7&iQ0+9?)q*4u=SP0X~}*TC_cf z`zDE6Wq4Lu39;racGcT3&rl(!6N%-E0!RM=Ps;wQ(_y6cTkW6UQHM?~t)kgQq9;!Y z%?+6!%`?lPl$m!^7(YCU2-U*tE9e=mf*ls3Pe0cOvgkl%Mo@2hHkDIgR^sueK!MhY z9${r=Ed*d7ZV>QI`Va;Wv#d{21d$RE90T6pWms4y=&F1JFFQmVAk>h^!C&3M^2QB5 z^G7~QwX3m*v`3ETHwtvrC+D6!hs}Gx1z0$GyaLKWBM?yPH25u$7CK`{#34M(R6yK~ z3B&jk)`V(M8EndtFkU~J?UQ-mZyV4;%`GkQb#-+)pMOo5_ol@UmLNd5KNl>m=oi8G zTBuy&4NlLap6-x{Z|ixO7W$5gYJnSk1;x;G0DGKn0#>Ve#nJf?I6?uzCl^zu8G$dg zthYNIE`NYa74O!0OfZRqIJP|Bowlx4XZwXC^Y*`UQ$d=jZZAJx@C zT*t=fpH!8(@mz6Q`9YmFW8JH7NOD>#pL z=bo7td7~~x$R9FHXG18S;nX>Lt@(=zxF7rpJ55p;t=esF_eM)|UOBF3~vlWW4Iz&7EmtN^MEAc-S|cDb*+smyLHK4p*Wd zSe@PY6VSM9yw=LFx_8>0+FofnU&l^`M*T+0p#uI+vz_j_A`;oNy&E=CAi$Fn5t9b( zyr3M-=9JY$-7A*IPkS2B+_SukD1ypv%JI$kndF!6=aq%w^T? z%dkEu#h%8p$!i^4E9Buvv}wf70GGu=VKNsu?7+bT1d~|$8@TlVRA724zg%0?PvBT5 zyRRArKJ#C|6fFiA<;2n46*cr@KqnDES<^ewzY)zG&W-O8uprZPHrV%M(ADy)=E)^JZjkbg1Z5in zp2z{gB@g3`&A*T*ey^f8k@FaI(-9c2!%a@}_OG4Vx?{Sa=;W2_8r;5(lkW1d+Q5cG z$;ABqtlK$rH)#1?XSr{j28j+UR1#ig7$WTWV){no0^V?eI*HUd19eSij(O!PUYBww znK!Sx zGt|}Z$bswmqdI!Xk^n15i%Pn0;KJN-QS~mPP?TFpL?NUKB%0|KhwXh-{9r?U?*Pi|~J3dvagr6vk!6#wl39lnS z*dy5yh2h|U%s^2Evp@s-^!dt=w13pM)04vrDA|jdW<*v64ty|YU2+(yeEbXx#o8&R z0ay78;<{$nfsqV_#gpJNdwyN-|Jt1oZp(ZEx3d=ssWyDjJhRG)vyfmJa- z2}&&Xu!w+VW~GcpfL}@2!p+{Y_ty6CIP_;BdIKm_A^-&fQ(S*{H(8M3Y85>iPKqlw zrN?|Ig(6?1SBo(Wh91?tkM&aAjZGQDl-^xDY!-sE0Rgab0l30VBY(0H`w<3;j@bkc zZc<XN| zTb}Q+`YT$>GMi-Mp4M+7~Xq!SsD1d{A32y!9UjgHJHE=IHa4#3^r`?hn=bJ`%M>Ec%ERU%wqRMHH#r~U%^z%bqc;W?^%Zf>+FVF`(_$ChA# zfZYR3&u;12P6#OlQ6SY37=JvL1g@8G2L=hUdH<_(0#98{+8lVFeF+UJQcVe5^`jR| zet3)}F74he{b>PS$jw~L01E(?S~ahXhXRzNm&NnvJ@Zgxy%F;1i-vTK`ov!Q6*B{R zgous&XJE6Ah=4SNB4V8aYX*>6dJ8q53&RqEbc0yuVxUJJ8Iz?Vp?+8$Zo)G6KQK1v zAD)F}%a_vs=Aa=K-?=H%H!zSV?N~C6iNx6CYn`VnkUpKUWPgTDVq^iN=C{?K^_y+b zMJ0H+Gv<71kFu|D2%x3D%)z?%CGdziz;0LQLe`$4)N$gVhBkQSHN??VGh;x7`wYZQP!3 z$&wPdevGYI^gr0Jn0accs>JM z^-2N$p&5Mo9R4^?zJI0(D>+SwA)0gG7d2k$|3!~UJoouPV+lSRXiL(RiU_djA>nd+ zyiOn{sxMLHLyrXFhZ=;EBa zq?^;@S7TRY)j+oNB8k!>RgJ1vw4zn@+I&9o1c7PpL6{i|2JaaRHTul}g@q|0B+UhK zxByEBLp@)qkIBE#^vxWd7vP_-<L95wpZKM+A!9qUR{!C(0 ztuJ}k!M#}`pSkzpmf4o&qSdk~!|NGqwJ;R(qmeWG<#V#FilX1>tk3aee7cgGsbo=A zUibL7-B8`s&*i-2UEZbNZiYFJTE?<2e*I$gJKK+z{R5u-k$&S$Ls!mJIz}N%bxzSclreJxlwN*4g{20nc!;kp_8(<4X*S`cpXsi@fC%g z&zYG}cQ(cp-?;521W`}5ztUO!lNR^L7N1`EMbxv2+&>;NpD9~ril0KRl*DW*p}J z;x@&Da23$iRuVs)w4->0N=v?%Io3C*IQiEXE<{bfZ)n|b=UgJhHTUo(j5Z&A%o-WOyt?Z08?;?p@$Be|EUGgSt|K;hziI%?V7@pYg zPE43Ocgr?)qE~X2d5?l>aGd?dpYF9~pWgUOEx4?@0G*4mO)v~Unuim1W>yx6jcGbX zzQ5gYBh*e65(sl4JCUL)g~N3@&;c5RrX}Uh8{{Nmm57v0xU$ZLmEKv<&lzs*R!4t| zJkx&e7u`YNuzL>%PjSjLN0vVVv)|kU$y1>-ntEK>bPZee*pdejo`6zL7-@DR*4f_> zrPnIM1DY&bJDm9$QDC|H-2DWccZr0Yq3{1yEdp03g#G<(edA9Mo%qOhA`ERo#UwAT z=>a%+nkIV>zh~lELjaxj&Jg#-tTxArZvhpdKt@<_umHZ+SF6c}va7ZNJlH=!>jxUI zr|0%^vl-?W&svKixD|-hAwE0EQDyg>-`1O#vKBoDgL;4~gWQhD4CGqTV6Be#kZR{# z?Py+$PA`h*;=qUWEU7BVV3IZ9t?yo%7iu~B+W~4*IoZGG;7}$1H~h1rL|NK^*^~h4 ziQ`sdcAPz$>rB+>B?g+@bT(Bh8a`LWm2V|cy+bOYwcc3qS0duRDG#r@8!2^p>XxLf z)sSZ=O6|SF9uD1b9BKC;G2wSHRq%Wonm!y#@rFY0S^7Nwa#Zb>U*DR)vL-+Ja`{i)T@murPW*QEib(0~Y$<#AX- z&;YX54tGLa3ToEN3wh!$a_FfWsBjIGQ^h~Y#qbr7c~hzO$;3u&onktPjmw~5Z176| zmi<9F4?l=690FUW08Et?01c)&_&R8iYG3nUKah-31`a_SU3!w06|9?_oJeFhiRdhx z!K?3mB!s#g!$0X3;Gwh{Ei-kg#zG{W|Hl_F^>_M|oF5koK<3HB&e+z{CZ9iJeZKg>lB%UcEPnF`v zE=(-2v>e-et+Abm{ALT$7kK|rv?MyBAn>3;jbsOhL-Ctl-1o%P>B~&Y!x2KNc?|Zi z@6yVQU`x~ACXTNg|Dm_vdj9fWxodNBKfji?{m)mqtv!8jT2$T@M^$~zvk0@FQF)pk zVNY1kV|Az6I?&!y&dEyFk>}A{-HtZw+Aw?u-mmWi_zy<^&r`;S+S0Vp7@UaKqG{6X zL;jXFHt&TJ2A|n+0%)GU#ZePTw%Fv=SShz`5lqe4_D$t|BXoOXQ zz8@N8HdMaJ*ycC@=~&o{`n}8 zIRqjt0v>wuF#}Ue6hgLV>1cJV8z%wQ0o`p84Ni1)!VHJ$d* zw^L@$$2$cWwj;y_b2Y|dP!oa4wi9^Wt3N|^55Ry3ddV!HiHRx)su$oG84Tx4m@_2O zqus8#g41?l7u@s^pMFct+nxrDC%*TJlyUUj{ecBZo2)l!Z!&kZi;EG3i1CqV>VxrC zk#eT2@$Z-GCzEU^letK0|1>p%_T>QQ<7a*?sP)L$6Nz7k;cM4#c@f>KxD}4+TTqq6 zxl3T+9r0&C(L;_KEB=sU;w7dJomLkAu34Mbu{KhAgxnXu_pgI_hbrgGH9EtRmF2;c z#`Rm5?2f}o-oH%Op$RaLB1S!o)D3vosIzozXe3KtqCDYzJ~rh(2mk0c>tI;{ zW9dI`JXR;%@8mfIB9e!M=)46#35MkFb0+z!ikL-&m(FoRb&O2_dX}U?miX&qF4U9U3I6#S5Z-#;2NCXfbkP}(?N-&rsDVySpxem>V@thI7?z-?S&+J ze!1Y*_6P77b)Q0Q4nCD4(Y-PuWag;coALDJoo+;$Dn2=mZaD6zX^w?nIPK;MCk~Pt zI3}of#4SAvgr3#HnMY~J^r1iV)BlPCBXWt5_AUobhbCxG+32JGvX6l~N^(2wo z9XX9QJ^4PYK-U~AX&zU-#Hy1umL#~57j))F9_0>?LR%1thx_ZUN+wbF?4Z>JM(Oql)l1n`tdkB_pB&9F&51200z~ z!Db=`2XJ4x@}x>$US2UUHL1|j#B=6CV}(|~BH2}r(1`pb^^$ZJRV4$)+>i*#sNB?u zBuY+drM8>2E`JS6{rSb+CndE?O8_`fM4vzllvng8kS1cL`K%;N5GGA`NB2d|yEgrB z2`gbIg8VZS3Eu23g~PYFF+?m$Ie^cX@zu(}R~PmR__Ik!R08_!t^obHAP#=;9qf0; zU%=4N!_|Qd1=hGpgcgnbDj8D&Vfke26o|_ofIBZ41(>S{_$;CdlKxeo!gLc{nM_l- zsVVp$$cbpiV-|@=5l1#Azc+IO>6Tn=VoB5-6cc-A`cfAO)i=VvaZP zh^Twwf(DIf>=o4eSpA)3Q6W}>0?6U>*2Q$ z4wWza?d%l2Y^Y@}vVW-*&DgwV4I#gImV+5y`F#y=U}ySV2Q*tkVbw9%DBla6F48FHiW_3ElT9O@^OZ4gwi@&>LSzHIad;N#2$PF!CN5*!`rFNO!#;G!uu02;XLrm?y z8fY`^N8YIQv|0ao6F-qVSGUgLL8(+q$pqQHz(9%du~XB)yA%5Hp}CElJa~ae*MGd( zz?BI&(sCHDhC6=ocv2S4HGvIMLBVfr4GRKr%lw zMDbd<-j&~vJdAe3eW$Ki6&Bc4^gG`Ba7IVDs9H!>YVrb$^2;RAxikRq%>m-WjuWZ7 z)M?o4<5Gn?<@WNh1q4yKd~D2>27oLLwPOF+JRF)((4<5|XZQx{RuE$h4IGRi%n*Tr zg%wDiZjY&W0T8ob3_^n(yo=IX@v(k0S3Q4u&u8=CK2aYUxO!Vhy;zbEC9}TLGilJ% z%rrT(tJsgzR^RsMnkorf5bCOtf}SZkjy&&nZyURNJtnH5!pkSb(|@IL`l}|_BXKna zaaFxi{M$FzGUo}0CX#!af3Vm$#l9pUW^q}nk?JHine#7;A0AtJ)!$axrK$hGe|f5K z=hL;FwP%vZ>|)72SYOrYs}$<$-R9-lx4S2JZ=lWRPW#_#C|F*E=ULWMC?6aCVruyoih>y)80L&)to%5L_lQzLH)4 zoZ)QA!=KAHRqafms3JI#QCO{QLMmb1yK`$u;Fdx=;!|5HC zh3P{nUv~vJiF=w%OnW!KK z+5&(w@D(3~Sp#^+>n}vFH&k?!nTqQS1tyi*em+wtxW{M?I}9}ORX3C@w{MB2S93Q&U3 z?sFY37JzF6%<*l=@PTzWDFMp00Xl+KRY!x^hC!370*AgD)7lM}=C?>k(b<6Ccx-PS zuBwut32rfejK_^-KA_Ip{`2a0<^gM`hb|`^BfsC+yV*&`=Sz&)!Tlqc*sSJg*rB_x zW&CKSEow<*FnD%Mb|tcs;_Iu2H!exa3hTGNbfYgPzBv&vSeul5mdjUs_EqK2zK_)! z9U9MV2<_a*Gk-P%oXGVG@AF52fAQZF_$@aFe!87v`h*YLl};#n<;s;U-_iTln(){s(sm0x!|Evs-TCYaZ?}e@pvKY}u`Xe<`{12avP%U=s9t3T54Q>c z31xc*R0wQCU~KQIe2EB`s$-)uNm|w;8JpfhDm%WlC(V%t?kA4t{u8_tyTD#TF7$BK zP{YNUn_&Jvd`#8%C4B?8^sMkOs*E5l>C;PMF-v{<+_jF z39(V{R)|l01-a0Gy7E!R=F`ailP0kwbw3}H!Y%VxldoDdl}adr`mPx^v8R?pq(&v8 zQj?~16hiMrf*I3lA~G@>5C%k=06&J2L%I58R$4=%0hLc+zz0nMngja1&WT0C9kKwc z2IdKB`BVc+xJ8kS)t1~5Q17b55an3p5E1VbehrU{iovSG_!fHM{_2}}&$em@9t=pg zY!wI{?>~&BRYIxboF5{e>}?fl{ah9n_)vc4>h$%JRqG;8LN-f^kc_W@a5SUhdP~zx zyYe>m?hr5Ig$5O5$T2KGl`RQI=UqA1vWzg^%*Izd4C zS%>oGSSTJA6|;c*#1T>?ftuqEZv0IkWTtr=^&aWf>!|`%#w7U50#jakCDg*p&qa$Q z4dWzwss*}^%9Eh?Y!0P;h`sAM?%p1(FTHD5^y~52W;nJc(PQ9F3A;=m$QJLrd(DyF zoY8QtgWmXjMM^L=QG<8yN3AA&{&1dw08*uZvX*d_nH5Yq2BsdraWs0zX%s2UStFT~ zhk1sDuVcFrX8$rrBT&C!E{GkJh*d2Llqd+YzWWe|Rr-KVawNd3Xh+#}SM)(? z(4X5cx>ak^-Mup3{dO8N9(9cbcX^FD`T6DJRc-H$<6p8)q>1U}Vg zVX^}3mwvZU>=&@O@|ajB2WTP=#B-d=yb(4Nq#U7`0Xhg>MRdZ?I01$c&=0nDh@D6p z7>H9Rgkm%>FcK)f_&TjQQa$etQ>ky8J~z~hkm^G5dSGyG#BKUd{Jh(3Rb}O;tGQ2hy2cGP;SN@j;ji8CD|R)ccsIYN1a9Sv%r1LP-)$ zIEb5$iHV6*P#rO~ji%(nbrSUgdj4R1I=kr&trbZ<^9Y!UjEw9(1SDXIpu!kh_Hwg8 zP){rydZ!bxlmn4G8|vWv>@PNAdgRJ{{kbzqhfDvQ5@Gf@=W&+KOwa3N(__lsGw`ee!FL*7Gi&2+1~(&-ZyE`*0O&fexHFnRc%jVSouvpZ zW%)%fWyDyzp?0%?^lpswj}>)%+k${5sF&H^7F@aAhkM&)$USmEDOYVFf_n4DWTX8(5_f`}ux+M7oViS7a3 z8IG$DlOaJNA_mo~Wvy_jWbWV)#6rn|RL=;&ML))YmUhz@0%>r3*d)7LvkTP56~EGF z)76#T-R2%15_M3J({TcB5&y4(Y|z9johW-kwXZ$*k@%9q6{mIr2#`Vu-YDdhD%){~+jz|oRGS9#I05=P|+qGWeF#wbc zmD`n&xbYH9$?0(zth@jMsEvfi+R(QEuwOjgmb~+i;Jk^I-_n%M^egh`+u98M&^r^> z%StCjprT7_+Y>b-r3^KA?dvL*)Q5<11WJ2nA427mEpT@Do~a|9+$e<{9pMvqhPw}N zU{79z&3n_v!Kxkn%dOpDPI@1Vm;Y7VeaTFUSS68e)YLi0^pjF$Nc}5Sx5qG7i>K-| zKQm!Imo{-QREJ6Ng*)ZDwdUvIVcT$T_^&z<430sO6d<89B#`=m7@a85laZdD3lL@i zyB7kp1Mbz}XC(?kY|%gx_%go_3|z(}t77mQ&yLo|8X4Clx#KQp;+JD!*rVeUG>0 z!&^=}dT{$7yI*8>HEnRM_SO?#LD3F#OBEs={4aOODzD*`Wmxps;{7s75hD2R9ba+F z!K}*a`8MOmckhksm?_q=jpE%`g@p3gX(p&{;xU9g)yN~KE5`jP0CGxOa8!%v$U}k-4@8s6?-5udJS5 z_|p;aaanqJ>#_f@5p&h^R~ZIf?t%rsg*84peQz9Y7Rl87s7gVV=J2=c7miL2Pbf~- z*qW(OFKC5~&S5z9j+8E?Y=Y$@1ONbCmH2k|Sw#h9fO}n##0~Zrbw!m*LTp5Jr&(k^ z&KtX`FXEaos<Z=->{%l&AE&mgVe^n*Cz1rFo(8~?>6GYZVK38kmWdm_I#DiT84*Ke_ z)wmt)xxj!`5(3)kZXbUCFUb3&$roYjXr!OOg7Xedru-ASE>ZMCI0oH!U5P7l$I$NZ zoGpi9D(;L`SyKqo{%aV=HB*;ct)FM5QC0^!IMhLdSRIEYL3+~)Xj9Jt1u74$dFED7 z9g$`z_ChbP7Q_jZLV6ZF^f1Q2NaNxu^j9d(i!CQnXx;>BDEp$Hnl3Huz0M?=2OI_Y z>_q*)XraN?QqXM7Qp3J(#;zuP3_5QjeOK#wPocBp=#)FtXk)N@keI9J%C{K>9(t}X%KJaBr>sdvQ(1a=cxAu=|!lPnG5kR%SUy+bS=vUv%j& zFrgGt(|1TXsRJ7lwvlqRc5}Y2q$6btA%k$>`%QEpQ_ccfM3ab_ z{tZ|`ky%!_&hk1|*2Di}ZuOrn<__R!pm;ptpU6&x0y{ODMcD_^dB|7;REY@4C&Pn6 z3|5CjENqrJI($UK?&uZO-~sW+gG!GJ1?c5ep00@%uqqKHV81|7I&%kv`Dg}UA+17M ziQ0BsPW_P}fIsW|2lKM%&ZA3#>t*NHrCUzV{QiJP#7TgD9Y&Zqzm>0ZTj2-gNHoqp z-duw3B3=%C<+-oXY&X)ZYh6($yjLsCjX8!5xJM$Hj;}2Z>kk>3pXfT>d(Pl>TlmVl zEDwZpQTJ9_11irx_KweS-(!Aoqs5bd^NNU2UF9XGiGXp5H3S5xCrX~LsmA{Ensb!v zD(}y*~RsN!eAd^IwMKNc1iN_Lxfn@qv({u#<+ z?v3p<;!~{fQ>otkBN+ovfEqfFYx@z7iWC8UNfJd<#>)~iIGT{CeYx(_H2O;EG}}vu z&k8~qRx8FivKK?xg`4S%_jM7`bE)aseFJ9In+^u_ykp-Ggank}X_8=g67NmyZdbB% z79=XbroMqtgm`fB;dmI!A{~Y}A()wG;1#yAf)rO2Tfp8uuvKlsIBL&#;*gcqdxom{ z?-%$2sgO3!=FM-?6`(olsY8(jEC&DoB!py0q!83yUVWH;%v`|?etuQ+x* z=;dNAhJc2AWr60v%=>Ic4XL@Uq6Jz#M*3<*qk$P&H7z!7@^+J6IrOm=*VH+d1n_Jd zoE_2@Ugnt^msvmvy7FnhLMhSYAjNu=sXzD0W;7e24nJPWZH!y9riMnT&jifK5@1S1 zE0#ufM$ya`HzXpThdn<@k1-6JNIe=0O$w0x#L6XMebNnLdH9Px9t(=!2a!wDIYW?G z<$PE8J)8EPgBrf5x%hJ^4H7^R!J?wJ!d-Mc4S@E4iU3Tr)$xL~wl-yA{}+h?hgEu6 z*{zF+#PF|T3I^p&tgJkm*oEa}sDbW>Mdb~Agu1!ky5H`M+Pf_Da`?=|U+)BncnL|S zS*nBn#{jw;#-8qDBy4Nr<-a30-w9Y{T@@D({iH4j%mG+nBJ66Sz#)U>NeqVc<_>=p zCsK-n`i*$OCm;QrmLQE+h_4DL*Wi=D3EIhr2`)S_90H;6x6VE4ejKaP7&poV?Ig`>M(|LHt5)=a|NQt59KT7Pso!56GIBl^2-57* zU&ZlTKV5CrbUtQLag|5$<7NhPN+@9kGL(WYKANHAdxx%9h+1O)BXL8%I^l00ky@V? z9_HnA=aQSH`T0=qRZ7K*!L8Z?GlA5h2P7ETWqXbsi^;&vW_w46w4at!=>~##CL%bi zRVU=nxU@Qs)x8zl%%lh-O*NS@EK?EI`&a_pp!o4?_;vL;Rh-kn!jG0uJ~ zm+tO=xWZ*IIeUR0FwHLOnQMOYnNX|F1dRX%Nnt*eN;XoQCVPQWvv|ZJ!J+MM1o(kK zEp^lKo@fLQ-_{XK%?09dbBjRd{2+V_6Hj{p@3s*HHz<{jpboFQG_IE}W?C3ka0;zN zS@UV)lveG~Zk7)6VS;c7D4g(fgBj@_z`(Bu2Fe4WViQCry!S{fgMvZ~g#^CY06zc! zGM}UzNSbR3$#F==fOf8iyWblwhyULgVkz&Mde!SAS44}1d?xoiR_%=#Cs1-cqlV?OlKdC@D+jLin3dJ zxk?s6G%6sr!Ue0V3-geYN`u@bGG%I|?#&|LAtYf#4UO4gzukhmUTL_{2<|t_yDq=3 z3$UtJjgmiJ7ks<;dQCxm_hX?7NrrBIaZtuh9S@_2eY82ptR!E*q_LC*It?FQ7Q|LR z^n5;g;+o+b#3#D+#dvP!t;h6i)GfqigAtKlg>zS0)drmhuBBR!seWsYu`;n; zsmqZ#o_S5JKKP+D^KadvWwz>#KZ#xbWc{Mern{^Lbv275?H<3g52&&ZL+l?wK16Ro zC^@$DcQ~uhLazKlp8UaQ#A%L-OZUMzRfF-C)GGNNqdI~gM1!i0j^f%@7OgT!fp7C( zu^KU=W$q^~iW1>k43;FWZ{0CS(dK2P2WbQPdWaNVnBlMi4%IEjpYFzQ%c9*l0YEc2 zFn}kUJRA$cA>5dF$njA~@)|b?oY~!EnfM9K61~lys5g#d60ohG(+w=3MdV4igUb1( z0#F=4YLfw#Qb|FC#je`CgeoNbo)udl!hv<(<7?{udqp&vtq`MKsb zngUE@auMnes@JuX$_92 z7Y9_*83j|x%*RnS(J5^sxwvC0_TsZ@eQlqvePpN^Og@`9CaK?#BVG~1v%31QYPop# ztbNt8eTqIoQG)~yAs#cA8jA_1y71h-rnr2V<2@0l2Txaaitk+dkUO5Q{CwE=+wStZ z%Lp_kUX!s)m;CkiS#$AN!|MwALpf246tlJA6Ve{vN#{YI{aFrvMwBefXx^=9LVr~q zo6kayA_AI(J}T}kii(}WUO5^S%T9=MLX9qj?*d{70vJe(;H94$eeq-O_KUg8Z~)0~ z;=hv!G}v~SWlR}S*{g>{z#-yd;%7ct!DARW19IvPx&T`3;CD4tzU=xd>*q&C&G?E0 zZtlw<2pS+jAkU5Is8RGn!B8zOpiy#Ts}IFN14sN(@_`T#EScVzHwQRa|eh3FS^^g)Phpz(NZt<}cQ2vi{40n-58~Jv|(anQ>jHB8q~&=yeL(xO90oJ0<*w zc!(Zx+eGig(GT`-yjf@{rfD&H1T51X2FG!hvDxP?s}`w-`;>!`7H>>8XJIh1b2-gr z5|)cHpVsIHyT)vt@#C3);UQ>(=!1Jpuv!2>Y9nwNd* zF-(388@)Lc-dY`H#t43|mK2t+tv(07fbj3oU-f{bAeRrIG-8>hJ)VFQ|EqE|DS+@fkT?$*dJtLspX$Yh z0+{L+L|9V)BSt`)6Ocm?@tMAn6B(uQrq|#bjMbpk@atv)tRL|7saF=lJsAc*i(HWy za3YHNK~MRE{G=nOu$x{7O48Bwta;=3hJ>}Zn2nU|Bjcm;;qizEOE^ULG7Ek_Vq&x` z%vM#P4XI=Z$+&!Zy7~Tjh2dq*zBX~Gl%QUonfgn>7AO5ILF*(?-+Y?gbcG^u`eJ!| zkFWirqm}q84}&4|8xn+L3DaK0#4+3>3Z1wd!KOj@XCjoS&v8A+C-VD)qqMGs3dgSs zeWT1yIZw(H6mLoVHyG!{T66yxDFA?<$?BPr}=j zl8UeK$lb>Y$WiozoyIhM+jfM5HYBAlh?1}1>4`VAFl~-;;>s}C+!nf{Xv4T}v)Jg~ zc3FDX0Zo!lrMx)vXs>43`Tgn9L@Wv=qpj3C_0xJ{|C?vo$>?yiN9!jBQyE8y1F59z z0ivVOHl!u|%*@-+6#a6xtPk6hZjM)49qwnnUF&}2_kA-GBP?xz=2p4-fkDQLk^YAO zEeUQA(n$cd8C%O$Bc<@d!-q-Cflq30n5_EQG9lqJ7hEOGmX?-sA-*%E*b5uQRBIoI zW24o!y239SAXWyhV8W^NeZ2S)>pp_1%5~ z<-5edo}>Dp54}}_>cQb24t|1@t=1>;XL)h=#~?XY+_k+pxTJ5@|5dQXEwX1~#GkIY z_~r1ZTn*}0^48V)<+g9YX{EJbli{LFmG#61cW8)_J`^Jm@KI5y1~1MA|NYC|G)dAL zwBZjSRi7u(C5nAG{8B(MIw$gjH!yOdak6eb^R$s1#r`bh53yRDCNS5>TsU~yvI!;+PB)$~#NHHE1r$X$V@+AEl~|!)e9JNbD8FKPowsCl!0(*uo54 zgBCfnhhncjY|0?g_y@C3>+28RQ?kM31%;Cbhn+v8HT-6JgL(S!4SbtK)$5L$CSk=* zvu^F-G(f}&H=JTXJZD)7iG38>f@asa@zgo=zQK={K>5Xnv&O@CIO#|cR5cjBgcG4l zq3k`FyVQt+VIl*FdRu zguAb-tH&F?C5xs)hvZ)i>>>_4pNy)%k?~LQz!!OJ-?Kq)$QV;M{j)Gzm9B>Lg<1 z1W{#-qgA2uI{#Y`*$pJ4t=`-9Ju01R8H^-9e?1XPC@Z~<7O0Z!X|)KVeR|t1%KIel zW2xR78iYZ?XmzrolCgJZn_pjyu3zt)JJE7P^=lLLZ)VDsw=+xr@T`wzi>FM}K3g*s z&A&#aBfbB{O0G^Juls>vy;ty?Z!<&;5?3LGcsNal>F~6tZ7I5~ZuM=b`Rjji@os{c z;L)&+y?!Ct+c$2Eq^NSb`t4{hC(82W_a_%T-f-V`%2>!$qN?m$e!(`s}XM{Z~5HzXSPSWpZr712Cw zTEK_OH8walp8nC(l2+2~LsC3RilhyIHUEuC9X_y$FNLhgIXYq6Lft6H2ipLEA+dyT zw57{;7#42UlUm&qsklp(EviAnK$j`fQz97l@AjjJG%70l8?TN?td2VGVER--dkA=@ z8Ew3X$q>Q&{o7sYR=X0$*TTq0-WKn)y^FM?-(ilOR8GE0uj)y@lsdLT#)#lqdlEr& z5W)2&(Wj9ZxBjqAZ7A9;&6>8hI{sY0x1*N0T3x9rk!;92FV(+{rJ{7IJ>!z;l(Ifu zZtLBg+s{afd_R`8x0g&&)o<}Td!8s8q77Y~x}-ge-}0@PJ>~d5@hXF@`&Hgw%YDsX zsdc&BT~X4Aj{w(dnV z+b#JNgAbA7R|B+~E1@5g^xqyLS*-|uv=2Cqit?q8LlDFfizQ$l&}IPi{!2j%Q2VHF z;&vuRFh4FFb%I{K!gX;+VD#n7dO*enVqIwXhA9VbfMO?nO=RY|j(SzZ!5;}SGlG(} z)D@T_0n{+FXTHb5Msz&*u1b_ zb7X0b0(V%``=!>tA6x`HukKNYai!c<pcl>SIK{RkNEHXbBM8F z2|X#gl_z@ay;h8$9E%M2c|1@!NyzX%v{{93F+gCXq;%ZxkzkFa^X^gUmbIHqGRO4% zjpp2!>*CY@=o*8x#$LBrhGmU-&j;On8$fScY7l!^q14)+6ZDPahcBzG#cGFYWd!SX zr0^vawpx*tnjv|m1!_--?XzhS&qZR*Y(e_*Vw~qQlwxI$E zpEjOy7!=G-(>{GG`38aWw7Pqm)DU+faO*)4mwodo= zM-)3Rgx*(uA0;LmtiN1A`Cn;A3veVW@w9xzKw??nCe|i-{f@!y4sf~!MwH@ z)85o97)6<}(cF4()c3tYBQ`3wXX&FU4Z>$sH1b2e4TBBYlTqDjDz$NCZj0Aqe3MgP z{3h!0j6I}J0%5PBL>Ap{K&G*=2&jy2yefo?$il(`xHkwzeGCIB4?In+ zdYN^yPOt*`KJ0^UY`MCFn`u-Mnb~=+Ldl1^ViZ*TfXx9oI#99~{bxV|Jqq=IL;%2D z7)#>p>}_TyTIo{VzDo+d)$dFB z>9q(KqTTMD*|SpJZIHgoG2zKfB)i-dW}-IXE1fzjioKzWsD+vwV}34Qi$n7X1GvVV zGgi8nJbxsL;k0(Sh_Fb@1BW!EZjk2(x-{XQ-7(IBiAdayFx?-D~oAr&1 zjFgCbpI=oUo1f3+;3ypZg~Y?idWj4xjPs<1x;{N+dO?XjcedqU1ICxDMNv!Q7@&og zY5~lGk1IEtRx(^7Xebf##Jv{&v*UNMej#YHbhiVm@VU!;c~Cc87BRk-yF8xzUv3dJ z)6^LABY0AEA>N6A90;ZVOmCy0Z}bEX5*q~)9BdSj3&b0`KK}lCkP!~ZQGc2cWK{n2 zdMEcd!a^op9&9jtkT6(TDcBJqA#NY3$gT)2lJ+%haJFI9MRbRCI##;PG;3**tk4rj zPeRc3HHYC9yTQri8ABYe+}oU6OD!`CgEm?+>T zcMX*fV@m!H>-S0m@qyv-gzFC{mkYwb-gLgE`ZaMyN31ow?9oX#vGDptk#=A7Fsa<1 zg*dy%yX&tl6HY=s*jgoaqO!NdzhyV#mqQ9_nSsmh_wvU1<**&8^jZ3ONYkR@ev)U* zD|dzHOKhZS6*fOzd05TlywX^%QWQ$j43R+C9{n;q$>Hy)@)zRzow|~Ypp{i@1-f#9 zUmtO^sKt!g*;Au#9=Qf@iR5(hUHr^KAM8&P8A5L1;OXq#+3W-wjlOgoY?;t)OYWk5 z)J&b7x+iKKA^*5`w6uqj9*sp`|59XrKF|`OM#%nsJ#gVbR6}pUe&M*ea)0;kMH6;4 z$1~Mlg*@aL(u(>SB!aJ^x&|4vKgn zdR4TvlA!X%0KnGxSU5M{AV5+h_r|zJ;S4M<-Eff7;7|Y&tfxq`W&p^cOVxWrr;MA| zjGuwwK93@##4`<88({n!GkBzMkKHft<7h-EXcGw4wjJ-6-`w~j}C%~dl#;n;&1f?h2rB{ zCm&fF=MT@VuT>xl9R=qrS-92P1;VN6QBSh*N2N`>yYt_2N!^*`5leZ-g7-V**|}9# zviiovJC=*^+|(%H=cu(V$+_dO>c6KXyYIJO$P;%B+hpMP1s0*Xx`eTxX5IVN8QCWF z-DhyAHdoA18}A_(2B3z74ZrVdH#*qkN(GPW>zyD5<+ zs9Py(b-GvO=7IuN8rDi_SCznt_Lk?}Zv|WaNhe%UqHk3A%Hs z9e=;mVc#sU;hxU0nRCjX;UKhmU%=8W&x7ZO4O!NUyW)VPbktU~t6Docau0VwISGVl zIUTHz%MWyxZfxG`jjT$u@VgAC;N4MC#|*%Gn%JANH)D^$Qkm>JLq4+96+|ni$AirB z;>w;IVPhfHvmGfdXt5DbyaJ~^#0x)DE7}BECu`U; zpVhIuZr=l{XMY58rV+Z@9@0OKU%uY?dl-uN@drm+4Ph#oPP2MKS4g+6`Nde++Pyg2 z;ed1f?y=)dTKmL6-)~dKm49Ek5^u2aRJugHy?QO#p>$rX;R?|RzQ=y0Y)=;3JH9oB zC>7C_R_f5lh2PT(5Seer<0hLzuQs@yXte&-vWgQhlA)KwZWsN&sh2zw?eJ0C52g3T zBBB>xNB{Lil^v78Mb=wK9`QsWnf(Lt(L;JZ1M!AQjVah8JP&p>_^uKX|7)+? zeKzCXRe9?N>z@<4D{}9T78BSoX_G;7SCXVggrc;YD`wp#Z!0cSCX zpw~Xn%wj#cQ@bru?F3_qC-L2i(d#M?OQ#niyRG4bnxd&thd>VnUA2I0`rJf>M>nkz zimE3;u(`zc+NR0C;wyN25NLl00)s17mk0KIC{#*SDtK8XB)QXtNfpaMkGpkO=$z6$ zZ2M&4%PI47!r=_2%dfpl`NJ1o6p-B}5n?wv^Y1o!UYDhOk&PAgZ9ukkLqv3a;JTbXWsxJ3x#!G=7_+U#sm$J2G#E(TSTq$VUxRlfN z&FVc?aSd+E+|IRtHTuW7{<2If&((9gZL5ECqU*#rIM8nG7oDn0 z;?i#Nvgmlz0ltaWw~`@yF(AuBmc{<1%5YL6zj{EnN{mf%wshj>7)5bZ8bc8V*JW-YtW8bL<7jUV^B~=Y>7fzgnaz{8+S|fVhSUG2%5Atd$x&)?>cT_|MX}lBH`Z=sCak~v8B7BnQCP{Rh)!u$A zF3D&tagBFKry;|i7jSZFkofmKO4ZV$;M12{-jyF!f6N_g9?EswFkn}rb2k|KaD=ID zl_(C2Mj*)=mh|~s{$>aS^v|_Y2?c!J#)-vQ_e^y_Tc^hb`ZzGYmwMypG5*TRYTVmM zsZgV4*lYaMTj%12*bwh3cO3`y`*_p+0_$AG(vVS}tdSs{Y}{A4?^mZLk9(@RWkdd6 zC`{l%uEXCnOv2z?;17s0{s|lO2^_d_NCPSw5fOjR{?>M}7(l=KSa6#ok~Ub+OH)G3BCV}3YGXbGJi>P*HV zNCnh&m>~vS#gr498ykACRTCqCD561BTXyd)_rFM`hBPPrjN%2*JauEHtjacjLmEy9jvxG@xj{e|uL+Do5;KhG;)O35%yc z|I7C*_He#3=>tKo{Kue11qOWA8RuY{H(VXz)lJhhR3iKn-mXm$voxJIb%WlaQo!YQcb=H%0@rF%y1qQP8XxgI~-4tR~L$d|)==Np|efX|KuJ<)D})NnHlB=V-gME=4=GJ&Q~Om;D==Uo*qCmUto~mow+XE!h>@%huKmGK+>> zR%tS)_L)N|SGLpeBF$WPn;&z@#<`oajZmka4Kbs{}xk3AMIboFa!j;7`GA_OSe+-#toI z3KxSp9o_=KEvs3aN*2gIJZ6#!GZPpibdFYF{{ZobJwJA0Zk-N7llSQsWzf{ilNWAf z*^j=|?RK5bVQ(&Re{smW{E3;R-Qf=vp&ZrlKe=6BRIR*Pe(23^C;-)PtwU;4y|}4_ z+cPGo()!`yvBKDqk~8&{T48;XH&yHYYb7q0Ebo@>`9|cWR-Zpu=&+J$ExBTlN6zk} z5xL~AhOq9|rugwU(SLr(D$M&>hMOhAE-m+$r{c>ib8pWa%4bT}zPU(t+15CFDdl1TrKDs3$0DqdQ`#cuh-cX08mx!64sZ=NrQcQq~W*q<*=ll zr9K#7o8M}4s|6 zZsCY)RM~=5Dtx8~@HRBYk&jjE1nK1fnUv8wD4}gkqeg7>GdpyjejE2XhFgWoLASd7 zJ2(W1*dfeHSyv4cyGpp%*yNFI1cwG_z7Pm76yqbH?gBJVar+;GJtEjFvHR3MJbAw2 zbsKEUP|r=3(2YRA8}4y1ua%vy)S)VHr6r>nj~uDSV`E}?3gI+?d$8(-{W@alLrZEhESJbARew@28|BDh zbe?I8`}h6Z`!X-~CxVFf$hKexg!a}pf9OmfG8!4-w9fFlcm5!(hUqLseP{dP{4%nE zNck|(V>6=4N?vS>!1?ra?0eyCA}!5q2rE%n{tG*|E0OtI8U-V%xi@9LeW|a~5aBD) z_)T8_8`oD2J#hFOB}^v%N@_mQ?jorzK0(NwZ0GVzsUQgy58X_Jz{B4OuP-z1_ix7_Q^b0{LPAX{8jEQ}N zhe79PYJcN$&|=)Rh$aVH+Xzre=F3I810al5(jG)B>9<*8Z6M501MvU|IpcC{@gk!d z@6|zWyjF=K9R19cuhUM*ZqUxfn$XDIUS0xi(_4sFoCd8nb5BRe;j9XO84&`LCI;t< zFu43&r@W7s)9hgA5Y_0y93sCi2ufg?qYD+T6h zo@c7n9>s(kx-ca1=Uz_ehWeamP8o`dVp&ov8TUp>8Smip0sV-f3LvqJ3zS!Bt*hCO z&d1$-?w@SwMf~CXmeYnUdo~q@NRRftK_=~R6H9kk3aLaioPvbAVqVO%U;C2AeG%9A zlIcam>0`t8ykiDl(XeZ+mHSg``V_`gO4>B_U#trzicZsmbO|U`{{389IG?{PpvyDa zKw?2p86hm4(v@I!>g?LG<$N!jS;_UY{qO*%)P(7L<}E_Y%m(MW#q_auF&CfNcXTO3 zf~LK;?@Z(h6PKe1-EM3+(i8fkZ`G33;E|2?}D!B6B#&+9cz+X5=B8x#k2UH+8Tsts7U{drUloX?+qoM-sf)l(#sk#`% z7J~F}cZc9Gz;tz!+Hxjl88<4Z5m`*=2vlB9>~`*U$r{1p&GtlggMp+p<8H@XQ7X){ z{{vN6K!62cAIwuY2_q1niOEw%KtpT1VC#+o#vd+`#T8l&^^)-Nf>9+rG&*Msi*D#= z+>0QS*BqN$5Qd^ClSAL&2CN8;jXy=(t{utfDC0dV6JwGKK^o$k<^D8!0Hao5S>HkT zF({q5s`|cnHJWVUgpmIaL~{8)dz?=KT(KH(#)))ymkzSy3H{>-eahQG&Jz zeTBz-(sQgW(D)YgXDwsKz3pt8M5xtc+Sfu}F@rK<_BOA%)I3^eUy8>b;VPVvKm9wh z@rCZX4FM(ZYA)_vh#$TPw7zgoOjA5(nyMF^?83J9T9_R%?$%Ksp9D^W;c7U6Wi3y7M;Kjhu zMIQKHeOU-7SPMZ;Gm}`Mx&4U9cQ>=d{FV4L@%6o2OhCYBoS$W74Sryv2;I z6o#=1dC<`!{F>v{JzXhQ$fmji`}yz@eBp2hT}`>W)~pFecwp##eSLL|jOY#6-vfcI ziNj0UMOo|=6HcN*7_Kh#{?9Jh8J9y4-x@9z4o9Ijf>hU{YOY<7bgn7bY!W%v7++R& z?iFk&*z3M5>5%T#|2!s^5`VLd*kgKBxb7|%sGW4P#F?AU!T2a zB14HGxN=>&{fYZnqW2sSO>660WCu7ymB>44cyb-WeODZ|1126zOZo~g1_sl>SazzbSKc)KU_@N9X=rxJXo4cnwc^(g^YzXc#{2r4^d#iE zO-wR0kFCdpAh~enCIVNG4fHUaMNzAP@`7|}!qKG=aPVLMY^o-j2x0ifG#U;v7?JJ> zrrABa2SgKwpN1Y&D35`oBsL^*>SU6BSdsSycJL>~$=S$y?!KojDlnr5x-CfE(il|* zEzi3HdNrPfK+98qVCmT2gY?4B!tf{XBgLtf)+tdCzkc`UyE z#_u^Uf{2?S_6=Xs&4RI&h9`sbZWc-Lp>?aNgTF_|dk1;qaa?YJRh|LiBWI$$Ma2Dp zdFRHmWR5MuwZh8(N2$Qzh*8s0z&Uq9I66^lG5?F1$DwQ(Aa!L@k{&K0+q?#F3@>g!)HvtPUT=8g%#^Okxbc@Z_9cd zeXvx<@^A8$(D$?l^pxz1^Z3+$SaCf|V9BG7!<{^i6x)VtJ-t2z(|LvHuZ=z61QP2!=0fQ50CN$D5v-K5jX;14MbQKK+%&|ZVq#Zei$!RH>m0aH%xqC-@^x-bEAzq2 zp;aY@+#McsY*a~iHsO`pC!eUFAvxHiauxED!LWLgH_^HxCKR+@iavj$Wnd;qOeIxC zsw;IgDrEaRMqP(7j5O#w0nZ9cbjHbzQKvahq(JgJe9o8pQ_0H7l^)6xKNCm;#;}4! zRjeu>-_>#7nTn9np%cmi z@hdX6=g<5*$ww!}#FZPkoAI(Cvu^^vl2qa(M@+R`&UQQgVk9yV@ZrQE&!Cf$N~iXk zX$4=Ctd{#hNo9y=e`~JZkf7M!T!F2jC=Rn|-*-nmYv&d5b;nyPtrR7BXJgV;U1e*j zBIa)uNxvNlc}~47-|1otECdp5m;VS2Gio{kLzK0u_DE$7h|*dZ*Wz|hLC zH@VHg;R{koqiRb$syG0n6gdH&#~jUY>j3SBxom(2!bWJi5TIZ?;XRUp^~0>ewd4PU zOyJs@{t)sg*Qmp=_wHMrC#ab7u@*`V@GlOm{0qG%!(Ty%C?0T_h)XK_Sb zh@}O9nw#gRtFjkzgoU{`TL~lZSF+uIB&rLB396+~$g6YGS?h{UbLm`87k-KL4~Zz3 z{ymYu{O4xD@Z4ZXBR8SSo6{i&U6GRG6Yh1U;!@uJ#dK{{?WlGUIyW-~RU6{bDJ6jN zR8vA+KmFQoWxjRfG;K0RC(;t3IzMx9fWvRqKz>bA3g7OtH*%JvPt#pzmY&QNx>B16 zNlBdR$((f#qlZ7;O{uh~j!X(t$*mnA` z?P6BO&$^cgw{g~QW?#MNIdtd4+RRq;Kz5{cDsYqE@ucJ^I|7(*bv#0%YI>&n+nwCiN2N-e1pOK z%d!_uqEnNVEMOGiCyCG{9zYVHV0K)DbvE3x8=hcUo{lyte&S*ujYiw zjQkRX0Tg(~h3^6$KQN~U03{xp47aE=MU)lM;g`OzMJb6;Q4dvI&5UDQ?nL>xO5$Sk0^Kl`ym#ET|5q9s(k|FHM2F*h8TiIpJ^KuVMOeOZZo^E+0Nb~CnYs5cH)&aXfD1)D8gTsc9N?U z%|}?qESr8iJo)8E^M38_62eI8eT^6!N|CDD7MTQcubeur3u6-#1d!#67zVXwe=RU=;RZoqn%x`f40NpApyoR>QQ+C>augeW$7vgm8Z0{fAxL%=)Gz(y+ zmwmt#dX`b!_|9f+b%144{NeE3cMoUOcXpFPDN`pgjO^{FQWI{~2Sv&oNouR*r|L^w3-#K}Z>I>|Y9^b`OJ7e>a_ z(#7l?7DS8jb%q3DI9t@1=u`0GE5ynr4Ng>$;EM-JhglH27{WcP$Z1TUG)3cTAR#P_ zf{PezP@s8#3+#FPkpu7%@Yrz#5`f0ywpNC8{Hw89>EWJTWVdhykuf&b7w2a`11*u2 zQ=S;nht{et#p{R__2bF92U^knkLLnx;PA(kDFHkMM)PvRH~FA3qE^7Hl@NJEiokR@ zfvOs4mb|O#FSY*@79Ato_+H(^zqA^8oS(r#mjFHSL|(m=eLU)1DYRr(9M32LP5YRi zKCa1n?w_S&Y)I;7VFdgthNQcKiSOBAo$wXHMxMop?CJjPGz|D5Hq^nwc0zc6K}Qao zvrKa8pq9pwJh>B}hlNJAjX$5re^BDrlkYKZgc%u?*{1&}#s>WK-RH-jaLM6L)9kNA z=v`WkStsRR85m(3-TOPMJfv%=E8cgHwGakX15_5Y)%Y z_!obDdH#5WD~@mDpu_<)7O;}nJrJJ( zK>Xr>L!XR!PC$YKr3w@#8dPE!K_d)ykWLOdGz_l=k9b6s3>uLDv<5gKuKpY(uW+r$ zk&zarmf-U`ze5dlRIG_=vg9s)$L1;P2QW+6s!v5Aje;(`)bAL{0oE`)eYB5+283fF zsMueB8NuM~g!J;fARfZ0UjJ@JULCS~Z}}yQOzsIXx*@&MV0G7YY$=y8@x`=XA|sC1pIU}uUiqmW ztdml&f7GwI>-bQ56zVuabkg|OZp8;U3xxXYNWxaPkBq|a8Xh8wFWhME@cgiS#@1o= z{#*>zKyJ!QG~s8eYMf}i5jFVny^4T7o0y{-RYcM6ZxtnWIb(w^6VAlFubitSw>va% z-*FG_LcREmB_1Amae`ODydM6%>`lAmhC%SzhE>~NOsL8*)T-`7Lq>pgvW0|pku-tfM@~|;Wh(a2{G)D_-f5)3SKxpiFu0X{C4WxUSp9{D^P~rNbcC&aJ^Yx zBZJq2H!yfpBL%ZN7=Q{ChD0RPvgdAMV zBhCJwbpeDxM<0O*55wE}R0@2d zPC+)cQn^w;KolT5h#34{U;l?!X6|)-=!7-pE#zcEO(UST8VjwJFqgix*Wq|Z*iNi` zy(kr{_VPEhHD{{M*Xnp7Uhl7{#XvYXkct_K1+CI8zg$w{WcX#*Cp3DW!VP7O@cc!RqxNyrDXvW*bG{D*>SR$sA zNL6x0K%NqSlBE0?n8{Jg_~q43O*Wa7{9{`)Dy8tgC0 zGRF3Ig1#*|t}<*IY56y^+#b`3b81*B6xFLT(Olh$N8r$ujd93b_aD|UC4KleZL->l zFOlUDwf~QE8FQ~)2?Xl5M70}1!&19vpPWDo{jOc#?ZV#!B$X5u+!vsN{n@sVbg_1b zCBbIOPi|sJ{&e2b3BNj537bD3M{1p|#(gi4Qf=SR-&+Eon3-5ZJ-PhvT5Ado zFKkA5vUJ&uZMf{XpUQ@Rd|n?g-;VBgS1YB%sSw7rPFS|Vm7Pzi01OrpBni57PSg!AV|cEtcbO(E%NkbQe8y42%aKOGgZav&<)Z%0omwXDUDH4D{B=kt`t8bqlwRLr~PfM1ns(3 zQX*bk=94jh20LYJE76g*Gm8E9`7I>u|rk0Yb`u{g-pT=~(VnV<4YvaWnLuC_>8 z!4@+js78rd;vDGW`s!z)kE`UfPVx=qT(!sZfy9dWpEnX?8}xh!4F$He>OGj9v+MOQ zos`?Xa`u(wjrhk@+VW%d!;in#AA;yDjl@pd^hs6~#{;tsqK1snK5BN|d@m@?&Rv6d z>vDSfFOJ;M@0q3zK%rgs_~D1+6*g%o+K6nfoB^@&VSzNq-q9_pKm|fAwO_klslM~A zJO55U&jr5UxuG#CHQ^f>*j(AKTly0QhDs}Fna~(bAzzE-=E@tST_71OD=$}{Zg_*}HRdly^y-!t!rTJ92r=p&Cv{(y z9>~uBr_3;|y&ngWbOs89040^c`%#qI328MjlNkLcWLHu&Zg73ICq)6i&b(#-(`r1I zl$QfprG_F?sUi4O4_JuDK)yrvxmq_44+2y51jEn-`=EvnfK~X? zX_9($_~|;bVH>`LYQM>yGnA54{d}8*`ShD_R`7)bwj5l-nzXx9G(Q8g=MUl_rh57+ zB-d=(3q6|pjd+=_vG{7iZ_!F7ln>ra`mT&4q9*~ZW5bDZA%aN z&6=6R_Fo<<(6EN3wg9N-=PlN zf%I`F{fC{;P`Tp|&ViY2@ABc6yKs{AIq`4=xF2tG;mKXsL&-`HMOJPQx)n4H-uOl- z+TOP>Rpi77)86SeZ{gi*2)R+w`!sFql z=@r%ZR*rJYU@o9UjKj7m>zAjHhk|FgjD8PIV@$z-HSwF&DpLK||N8m))jq9f1PIsJ zW?I?f&sw=oraPJ#7x{;i+3gWa2&QhC=gg?QyNH zSnF#`Kjiy;UvKQL3i^0AJX$^>NEy%IOK#YL8>bw8pRqNO2Ul)uX4u20pDb}`?xqBo zo~+##ER^b2pjLRyMW}EI*@gHcjbO*xv&38wJ>em-Y->r=k(`VZC`%pqHMZ`tTc;V9|yy+<0lgtRiUBZYb>RF=YhO{?S&O7k&%}B4G6O zk3UZ_xj8*OJxeh*;xaSxcX=!Tu>-gMURm|hZP&!-=v0>u{ zNiy+(*3<*Ue$b9XA;%L9L@Qqr4Y2>kv4p@B8#TBsO}kVXC`L(cw_a+lgigsS!^9=r z$SVzQSF$vhAavd|*<>M7DeF_|)MTYMafWNjsj^)jwcoL|a75T#(8il^6xXUe3nc4+ z=P(9QXl=i+^Cb*avvO)gJXfLK5P`s?XQV3phvn0+>3D?FYa0%eP3ZByz-SstyK-T4 zfcXrP^NA3)z%r@sBOo#yx}3QHh0VQ#HD`AFZ6YMf9?8W5-m}{;*y6g0!*(tv@L!IUiQ1!}1o(^-mj>9emdlJNQh(C7kBLQKneM z^``W`H zI6o4*wRCbAN*i=oH-FnO(oLREA@ksy^xVpuAFnmy-3H5PnTog_L{^jO-W?|>2-hij zekp#F%XGX%Wt{F8g)zGSk|)Bd`ia#|bviR~j+bT;EK{gI{Pu717_fe9$Gs{IznTSG znwwjbHSvzOn9;wqc3O9CO!)Ho2q>7+F3izC$6=G^a>6z8L+&EH6B+X9YiXzgdj8pDVf0k1S;SdML^mk zG^^$6bj<8NI)N-D9}tk-;i0YmUTz_WiC4&8wV9~2kaw1GF-D;O@UH*f_faD#F+PoP zCLePZOryZ(C1)0wgXw-;kd0KAk_uB{fzh;K`Us#h%>tTq;EqHhjN3v(=JzmBZ@>ea zHn?5}EdOfCXX4yWt>awq+;=q7fLzyxLB6ZKlx-m<5>NC}oMNsKRfAwe)q{?QY>FS- zp3?Fe{)B&jYu0;6+W+5bh4e9%VzS!8^Mr{7zKhUX)@}Par%4a$KyYLaDN;Ow&A1X8Wkq$ zmEOJXJK=2;rD*!iL53uRr%*n#(iZCJzh! z(oNM8Aj+b8%QkKr-*W)3{iL`({$*yoME<`lFLGS17%aZmIAb)d0c+*P?}8!REZ?HC z=zP8e^s5%I+ditYs&_W9B$QVxZU1~HwP0=3T&D99z0ciw$ z=CXoN6lFbp2zh?&epohC+ko*thuse19}&4PNmPxE>;B_{qxHt>bj4IVHVHM4CmY?_ zel@cW7^y+E>O(?SPUSNOhIecE2@wZn7BU!@1>_Ne_y|rjECgsBfw52lA{YoKEIB{~ z0e=Rg2&97Lvd?dC`VSzL7^2uxZ8_lo>zQw2mCNXh5!3>a|@Jr-6 zhd@j*mRcU4&0>euxg?5IO+;k)-j&5rGAs`S70x0bmQ&+G;;+%bBB_~6L z=!46)sFB>CH1~J8Q*V(u1|3_v^|9wo&A($Qdg4Z`p~C+IPa~o}EQI+4$#lOTJq*HMU+`502qN(8K2sLf>KG9laURNF0bxK|j&IeRlGM49 zt&$>supoYa0;Bc)`e|~E$~7)OmkD3(+9#}$-ISbDCPe!_%0rmR*Y1uYkeb=1q2R!^ zXz*P6^aOY@T{U4QZ1zKPppvpzAlgCC{0!or!E9sQKLU$ZL@cJz z8bXLUi)g@bgEK+F%8=cU_tAHDbaINL%e21SS&L%TG=U#)vYDU){KNIbxWu;bZH;P03@0C#KjA{8+bS$s`Yj z38N_H&b87r7`pq<=Nlsi6__Lw(AG3&`1Q>Ir=K^Hj|11Cue@ z_M3vQXp3w1GFDx_;cK&@x^MH>N6d%3%MXTLFw)@}>!5FHs`DVD{^`jL3L8@qc}(zR zQEPl%Br>*3vODg3I(hP5GU8C7rP@mqG6>I4gwCMxs?lNT)6>iSwfDxXm7-q3{O2ZP zh$~e7Z>%U)0x|1rk+t#D&3s}!FvMblZxI`^GHn>d4rwiu?4D50vv-oZv;72Mcc28o zIwITGpe;vy{P-~no;=Km@L1%7K@Si|;9vFOpED5loO4)FAlOiXtUS)Bc1$=d!1|#8 z7A!XWe-V*idjv(0&4+3S7HcK6=Q@J+0fX6_d&lW%8XZWylLJ;zmmPIj-^9bA0Vfp( zHlA(`^u}B7IT^TrV{;_Dhb=5KigMm32{t)l;>&(V^C8u-4h-+^Yh$Rx>>k3JtHzMz zAvGfUR3X0YXTk%n&}F00z5&@?mU$5%eS zAo_x;yf(i)TJ6B9aA6I5NRj(OUCuE&x31UCK~mjB%%Ur7u7zUzRJMiPb|cuZTLJx! zrIb|z+nQ{a{7rGhfY|G4uLlj=+3rOTojq^4P14ub22hPkNL2mMyxk&kF}!r$_!`@% zDvLwg*2Ao@^+TN*ddnKi?pgo2kh952V=oVnVJ~JCZIj=+DY}q1hHdkRr|45ZgR3>P zKU5UCceoNe0Dbc&dWum|kyJnG)i>r#U@+_S#4byxTaed2&r;=V|Fvp!6J%nxX_S~0 zUDl*aRN-Pr2qbKv6y~`0ApAu1mF|T)OCzjiSlQlSUCKWTnPmq2~G|8qF z@y^xxm;?PX#qE_lLuK+X%VJ{nYTcMX?t!m8=xZxE0!5gS764+vDV5(Z)W!_2iK61< zTc=B!*;1FqgJBI0HI9p|_F4u9FGhHj4@~UW`FU%EVblQ+obpo*8sJBGD^-n|NlMu= z_rh)OEJ*R>zD&FRYecQxwr zWBs!3L<_P9!qYAjW%Oa)S3Gc$GCSn6gDMZ-N1+)5@#UW^+s$NG z9$(NaPbeinEP0a~RHd$uQcAH+d*);$y6ei%T|3q5ZAeg;UwQDFX135_!!Z(H>CP&e zY@fUDUw$ivWRYGzUqVdmkb~19z@MA2;7W3hA9xvJm!qejzNT*cLKDY@IQpb!>L6>MF^T9X&TF^CKk!8tsvy@RYdTZ7&yUw{9)Z@5@;f@uY? zTIa?>1r}`Ea;H07)I^YI^q*>4$;N{tX9$jaBnT09el=HqBD|LHBUfgDnFWPWfh4sZ zzTZBhL>01GD1|0Ls16TpWvkDX^WB0*tZzbj`X*6T_2d=;c?wLN&yn6rOdmxgV?Rxq zJP-+gB$=dvMZ;&7*nBB@(1zQ+m_L*im<6(!55C zKYmt>A38$VWh=wQ9g!=q_2&++f2bU4I%MwF>*rqyt*MqnwY1J1FN>BiRXB=TTOtjv z=q7tVYj9UJ7EyaPuZ)TdGW^|&mb8EN2s^@hhIO8`YvN-6lJN&0A}KBW?dXz()aQ0l z9bx~_Vbjf_XaAn$WamMTPQ4339dG9#YvPjQ_#o@JCUW7JnJKDK{x+T>4EMEeX5xum zPvTKu!gzXm``*=6-iqzi7G+G z8l3D(srAYIJs=J>LE^(AsmgrI5|ig3uZVHAT!*&@P5?}>IEBm+5?ZSq_gB6!u(Eyv zvcTrf+UD0tS9qG6po+I12y)785ou>K!YXB`#g`hNWx za%hGYDZ!vYL1`FLMCnG65Rni8B?O6~OTr@pN=SorBi*8Og91uOC|v?l?=|Oq*KfW5 z=yKUS^W66pdw(_>ATbQp4wECJqa7Gx<2d?~PaaxTaFI%SgQj9&3-ZR=ooVZ^V4+9B zyb^SG%1VK7$PR#3&)-Fx=TaW@d7$_aNL8H8qo~I-B=y-yKJD^0L^kOT|sL157thSX40`N z^U>+&(v-kI`Cy!6Zy>V;BV?G3UJCQnH18}9o}llcvl!cggxYO!_j){T*yX6xieheb}DN@jYIan?GYc7GnAkF&jr(IT^27 ztbTr4?wjY=-w!S(PYXDX^!TgRUWuqU;gkqXdbI;{5r!jeZyUldE@?GUh-eJqm7nIz7!L0vG4SJ)vG|3b_UZV`30 z4~Nc}n7>G~V!(Kz$Ffi>x+CFNGGi|WLZm0-^1L%?=)5?LkbxfpwsG@!*3H2HE`yc` zuUBU512{6kB*2}7hZkGPCoXsk_HY($!Na?Vui3Fd*ChxuzY$tN^jA9%2j(`Y)`{}) z^^``ocIn+15j-|aeaWtMUby2Lr?tUFbm810aPa@1J#~;{Az-i(3ijIFq1z+~+)KO1 z4FE*2h)BAvGF_q}VP;}Nph-0LHwA75#a>G_43ZCr3DxiQ^~(Tk=eZQC1LlXp(NXqX)x4DKBA*(L}t{?nt#^Ah4mA&W)dT zvTkAHWX(ngB%WP@*}jSN-_QN#zaPqkZ8z(@AjKa9S86xnxo|wWf~1@Gl5?LfQ{@e1 z8UD~3mCf@`4Ihp^E?U0h|B2FZ{Nd;~Zx>;$EN~@;yW)b0EAqp33OxHFZ6v1fGfi zx$m3T`7&euXi=S4Ywl@mZUEcw)$f#l4LZ;mb7~+h44|$7ZhZ_$;oymIAYgJ#HYd!9 zQ(xFZsosL%382Thl-DKpc=L?uSxeIK^(rbyBK-S0vQbAH!Su`Cd&Zwb6>V+Gl#9U|yI#F7?!??r6pjW?kCc7;;UEl#yq z@YVbnLRN^I^W(=(+urW0#hgBtFrWwa_4P+z5Hqns*9vpGTKP=sKgpWhTCv%#5x)|& zf>OBM^5ujk@rGIW>?`!e2Sk~>skWYX{{VzZRNdV2T7aDQUN?gO=I}?=yU2*k(K%Tv zaVFn09VAIcqRucBkH>!crg0a!H{5yWX)IX5-S2iYKV7%4ubL9(J7PP+-}k=nn;#XM zk@o944CimQkixb{@MzrkWc*PfAVy%W>Ay>6eY06}!8{VO2{fObpmKb`!eAjl=KI33 zDws-?pq3%+gfJj!_0*3yne=|&7Ljjl(fQ2Oa%)2Sm8)FRP~1SP14&|T!aqf0;2i@9 z7*yXJgtEYYl6?953F|FB7Ma%2M}>gpxRfR8yEg8#_8B}zXG6|O0#oKH-e^&Ej9O5)pmB)i zlsB=K7o8TVD5H{kq|4vsUF<75)kmhJUp+`AXFBnY3t+K%36LAl5a12zqX5s$~li^Q%rJrM{(DT^ik4o>2^JIOGf zabvX{-@v8oE0gpx^Sw!;`YW5sN3ucmx8q~?c$HqP-;82k2Nq>v(?N$&T#<2k_Of`C zcE$#q@HwF8$>v|_X{pccXw6Mw%AGk0^b4~a$3#iBUcEU{rN?t=`_N1HW7juNY3hiw zIKsEt=a%(Ktl2f;%L*56FnDA@8P^KsQP%J;tVN3_7HYNj$D|ra33w2!k}jbjrs&%6 z5E^LA8_NTk^mx7VgB(BTu_H_tX$I=|#_rDI*kk4n;aoSP24L`y*DcM77eF_Ak0Ie^Fz!3L_)wxhnEN2K}es zqwkrDW8GSn0H`~C-FUmA*&q=9tmSOq10hmk{VX+na3J@oQMVwwumOTIs!ULM2`#Zw z>R-McJ=Xo1yPP|gA45;2C~*a80lmRHYb~XgBqM%|AC2_s-VcnWd}XsRo&L26qqEx6(<81*M5e= zaE6p*ga)cQyr z1x@rc3D3h#8R=U*0h&!k*oQ3!Sr)L}lq={r+=u27`kIvSGtDZ~7~9KN+u8ki((@ z9-oB)&ZqfX9r+93ujuJX5wDDCmtl1mSo$SptE2x+Hf%H=`R_)7T7E7z8e9>~?Cd%7 zozc+o|8Gcwb4%bPb`aVF?S-;P03gqtv|PNhtS;H2muDqm%mAt6DdwJ5R~bb()=pA8a~8aBvL!5e`FL7 zz6$w}HXA;4RKzQdr3p@JE0dY3U$I8qR&>i6`MH-&R$`;zo}T8);KXk`=9)41&_!(} z)u%T+w}RgU`PU|8Wo-2*KkmMA{s(!{rNg4i?_Snrl}o*5X5RasSe7dPdxfn!EV&~i z&8LHJZ>|+LT?ys-=BHnBKS+o7576Ovf9vNPEO^}>5`LcAHlBb2k|Xgd2;!8l*Wq2? z<^QNLVs7XpZNUVU7MHnE;NH5C%j>0Q{6jFS!~t3&lv`TQdU9v{jK;6+TLd|h@c#K?m0MSr2#O;;^wlyk)(Wt7I&TXuxc@Oq?#z`%sK*1xvs!H-7o zibwq^&HQNwq^ikKp{e9Ug*JxLJ6`|&TQU+xXC3R)b@+jiH&-XtgU9vNEWjnq#Lj+2 zeb{MGnUQccl;Zpif}@{Fd9d>%ZhGr&Va%}Q3~T@b5IBH95*n;le$ru4IG2GR15yfD z)A@B36|MaAV0)VlySpH5^$P^0LS@l$5a{u%-+TR8bi>J-qc0iO&kajAyW>4B*GO`= zxDnmg&Lyjw#_Tn&<{`QiJfm$kNy)_ruI=xRCl9O9+& z$JzAH4;@7g1`MVY<;7k*l~FwyR*s(q1YUHi!;?<#_!UnCR!VN$wkI>h!mTi9>8k)y zE17BE1V#!Gb1bev+2i4A*+^MLXKxN-3&b#QzZ#Y(cz z|4qn&)iVSl%c}rGWN~yhn*sO(E%O zK4qE*I)DYniG>&vZOqK2B%#;_y93n|Yo1HErOHh9`~QTrIHMF!6Afq>o=dn&|3xyK zGqC?vQUb;-uHFYR9_Opv=c-w;{w*X#myMD>5ufL!bCqCx+!*%kGu+fPxF^XDUk9@$ z;0XWO|2C@39q_Ta+iV-sInC;ke^vt)2CXYGISnn8a?YEoY}{2e9IOt5S2cx_Z@G}g5t zUo>L#ZQaHU<^7)-_tbcpRB9A=x(rtd1{Ux+%Ys%aVxB0;>}w}h@R?X@iI%9pIsdu! z$i}isAk1E{M9$9bi13eQAh(C;Q_y75yJY)p?!`12jErBM~Z`nnN&>{q``$#}147-=lS#f0`O<9Ez331p;V( zoED$82(eEQ%hX)>Z0oQlIsTev==aHpc@X`0!=Sg$e6?LKU108?NkM1z3WR}Hz@Caz zQnNqa=!nbtQ4QftT4E@%bXAv23TUve#Y^^S7oPYFwNJ#I9D35@qQV_7(vXZpfaQ1` zibYPrlm4Bfa-KkYo;e5z>-Wo4EGa|Dnb-{lDcbQ}_gJ~bT&{~K5*+Un5s*$iMmMqtGeLcfV`2fFb5Io*7QAT7Bjfoika-nyULwu;~+xfa}o?J)kK zk*l1inCv(IuIb6>*u0sI6uU=4gp&4aqcq_5AVO28ZgC$8BhF*+FfyD`kpmR(kXM*< zeKq1*zviizHn+T{G7cd{)W+&8{eZ0`c__0a-SxLL z&wd#-Gmg2K8oHYrhV~Mkftm{QK}RhRNeViLdt@G%xa)ifR8-JJnG2-Rw$E=3 z-@`oLbcdKs5T9oM=Mn%g5`b}F*cfU|Z+OpHIR>xwF)2dabJr$_>~rFeV{614w=8fX zeb65S?RolPl=Vlw06KEj64qZ}9t|~>1;1+OsAXH|6nt9nZzqD`1qBWU`fqeFokpT@ zYAX!#jSf`KAv&Z$kTbV?{m>X0zAR1&!;nn^1SqEgpd#+m=?vX)%fC!X3#Jx#xM81t zI&g~THUhALZ{Q4$kcqvym<$DW3YUcwdP1%<#@6V*3x0yAx`%+czH+pTh z5DR^Tx^)aaB0knb8AG5QKND+ZRY8;qAB8oP1|JgS=e0tWxaEMv>Bxd^% zl$%So-{^2gG@eV}4?c+jhF_HjUOJrQm|UYoXZ7Gf+yM+tPKPtNRAyZAV6q0WT}6^y z2S4D~&Mj*TV_KFi_!+o{Me+5}KHnL-EN@sD8w`{ju(jhZ5T*_nmL*Xu-Emh7<2Vmc zL*4NK#_WCE(!0LR7o)!`#wD*7_Ty;HtS$fk3z45a0R#3?(l_$e(PLMHa=c=$qCyF} z3^E_N68HvFX(lh!g_-17%DPikHvfDBOs&*<9@UkY4er+%`|#suNW#dX+k1ryOL)5J zd+D7IO3LS{-}!mV9X~OTElY9*HWh|AO)N!AnaqL@4*% zea-Q`nQ99raN?945u>5sLRcOkLR2r(a2Dh*)e6Gy=k-dh9~r9i2F$Wxk-^Cc^da6k zu;{45Y6^5n@GEp-@bEvI5p+FsEpzaW)6&x7^8WPduq6RpR2aT2tu;JL@T9L#zhKVi zd~8^Y{om2O7eJ>kM$_Ao?POYg`5&TGyiA}`xVVT;jDvthbA|d*xiKea!Mz%q|284b zHZx#Z4j?Yp<9+2Y*>Yvc?rRk*f}ysE7ELmii_z~QuJcG$%Q95^AQ8ny8swk0QVS{u zoa)nOoBdcZ)+RtOC{V#nliciVu@ku`&XV)yu1jN|p2R|c5@RY=N=s~XISIA)queO& zX)(Rmt~b3|UvA(2?8DL}d*50+RH+@ItTeGw|2WL;dU-_dZEek053f)cZ!#4fjIL}J zxi@|gID^26<>27KEgrAmui5clUf;Zz(^XWe|Kf{hv9}CXiO*F`_ff=(F4tY%z|M1n z&nBu)ZYJnlTgp!MaRrg%v|qfS`6E(9*}?2-9V8--H_}nF7YMJ{t`zZsh$~T7?H70e zZ$ld_uLKHY^M-J{YAP6MC2runL)49p%FVebd^(hbpDGW2$SWt7)_}|cO*EV6!yM}O zU>_&IQrF=j;46dbRCs$w1s*95GLYNU1On7DgqZng)i+{Jx$|D?vkVozD4!a0D#W2SnxO8dkb%EAOYp;8d zdpR?90vHuBcxCW`NRsyW2e)H_R*T*s^YQz(?@e&phN7Sjf1`$jw;A!P02{;d+A(aC zKN?*Z14qEP>jynvLS{Opi=nFGQMy zpCaXmp7;mJ-S05#DfSs_^O-eMUpQkduUD9lIYCqVs@P&~fQh%@T_pMMhxGixWS^(b zqTfjnzshQ^Xw~@@t6^N9-f3C#De8gER~4_dhz;(hpwMqmtIO_pv{A`JFoIG%z;ODmWHy8RLA{c?jd*lknVI{JZeVXV6qC|T_MVrybWb}9syJi z6kus47FgJk)LA;eL>XgXaCjlUdk_p7NCd?6v0=-|Q~?fzfR(>4^-g4DBpQv|As}W3 z(iFi0`1v!+8D|1}R>})IXN_n7O+$>|-p1^}atRWPsTG=q$x#xB!ES z7~1a_xu1^3Yjt6>6(t$4oRm{djF`8C=ml=Wx0g+P)*6>gH;78ei|&RKk=y)itsZ55 z8g)o_*tayXH+M~pv+l{-#jDAsYEm5X;P7M-!e7oNd9;nLKcF&;9Iu}{#KuxPXdn-( zeUGZ`pVcG{4iC?lRuOa+5X0&SjfU50gQ&HLqebsQs7r$YlLfCmN>9mDB!s;5p9AGmHwtlk7s<7*SK^t0X4Kcy=f*h;IFut&$4cJ>5 zS5ylF$34yD8*uOC1gr6&$2dk@WkShtdpQol0yiW{H*pV4TA2Icwl(?+;0FC1ufUs= zOcD>&2EgOB1@IU&0tf#9m-toHtDqzUnq?7Y9cGi4;RaCvjZv&xmeG5Kl6^-AJ^+OR zm^KgfF2kD37^4C?zc2!)66I!k3y98v9Kc57WWx1#3vc3o+I`XvV5M_1PRRtuj#48@*C_Q|2V-ILwKc`pw9F zbmP;sT)L%JkHw+9WNg`m+gw`rnW=BZDvRDFS?3xM$Q?^ewLVALPf!@X?Thv#&sx>K zsH1q$ld}%}?cKTMrn7F9lvg8mrA1M6|XgsC;IkID~Nd5fCC8{JBkZ|a05fS6|C$?v#?;2!@wa4mo1L| z0&Z&D0vNC^1PHLRi2e&w$K@Wudq{&N1FbKtkeJS$O9R;sdh(5ARKRqdJ8pEP*G-ri zun8WCwdv1bu`V~Hozg0+`-Z$r;S}_()cp7s=vFJOS0x<2> z7ly5xejmKlH%_ZG3^x-ki&A%NC&beNfge$NI$ zw5KgMA*_{@Lddbz94&{R>K&KWSVsh63PWGmfyp?w1yj`Me6Tt&$E0fe#c+MT*TGn8 zb$)Q>btoPMSxRRQskPll$H2_lRgtV}h=u}L?gApW!o2nHf zwVO5zGcz6n%mL&uiQJJB5uyEvErHb%1?dIc7S{qmbn=ho4BEU}-{D9-%sv65_BU&R zQ@r}UL2CK)w)zXmS5{Cv_mj^Q@;;DGSK+BciG{4>hMW&WOiL8C`W zIz0j}^nROv-+*j7kt%nqcM8c&HW+Ec*TenM(QV99;cr$1+nT2K7C9(wBMOSo*p2{2 zeKG~Q^l5kGTf=ARDPdn}N8Pe>FBFC4jZj--=k?y9oTX_}pey1fM;Jx)mle!N<+O-o zz;GU3L>$}?a0USFMc|@g`1e3zT|lO)1VdRI=N_66h=)Q|@lV4&nyQZr&4x+Tt880w z*aA6BR#8CPEXaXtXo!-Tp64-)t=j0ra8dR9y;(3%^G-yKR5^%8(M|;dcMGmv2>r1E z@m3%;4h@J~470Lc(m0&Ccct;LANIKLN6Vx9V2$t}@Ih2qnA&JUxXs`84mf^=b>UwO zVTX`3m3`+j?XvD>+KyuX7$AAxk5NxlIY7t+11=06H-}o^Jb&ZdUKmw#O4G68y%*CF z+V7bB*lzdG7T-vG(5t6+9>Zd_JFC~#$w@rK+j^24R3*`QjxO&zA+P^~T=#Q1o=m_} zF!mZ@?74Fg9sO8WOQK)$8R-KR!p-aW@X3blvf5(ItbwfNhGP+6-TP_ol^A0LuS5?obI(4Vb~u&J!zZ!J~bbKdj<2&gbQ zs8o&Kx0V%P?$I`;UiNC~wIfy{;=41P2@|2Xhl6k_g6@fvlOHS>N(5B`596dF?4JH5 zUNH^qdl+=T11cs^v;pIORc#-~+%lnu=`U+wCBB}h&laQFVQw~}yqoxkm)Q5`T+jfK zsSo4euQ2u?gq+{B=7k49QW^T?5_1&$#R{mAT42ioW)ln#;WdO6;Gi6+M~6jm8Zr15 zXe!!D2FKSWCs<5X^+BPdqzxCf{{y+tJOKL>N#bu3x)W_8X>2i@{JNJp#B= z7&9g7ak3vueV8}!s{I{F5Z^wl!ESoVT^?*JRTB_y6DCKGjSjfV49w40P+9+zn0?EF zF$Uy%!b1Yx>A;l+VzZO3w8wTPjP~Ja*+6}ZW1@hF1`iAR0MeXwO?7p2r#nua7ubxW zX~;)p+>F){s2egdp?59gO&KgSy0Z5m1xQ+Yldsk%tE0)=uth7l`&zgoBy_R<*K=dQ zb-*VWpL!{x`AE8iJW%g3`*YMV1 zR$t9>Y>w&KO%a#a%R>m7gLU^V%kCoR;P1h>a2uki_6z~}{uPM82XU!A^_08Z(*0zj zd|okJ=9+r;8jvfhIV%|&>UCS^AF!Vouyu+Q+(kzjKd+(2sg;|VAIZp`{+!6w;|1YF z0F^mGsXh?y5R@eh9E|T@v9(*l{+KDc8x)pT^Fg%--K=3j8~!8^4ZTA)o89mW!XLS$ z^_>-A&IN2h-Wzz{PZ7BTuB>vWThTz_G_7+Z)Jsv~{8uWEz$VL1JlcmS#7;O&)bHG( zCM$(5NeA-%c(MlI*8ZQj0?4tob#+kf!@>wic^IXO{N1ER^gY=y$jo_sgD(^kyXBu< zh(Ud&45GdhN$6x`Y=}w&lXgaae)rv4mtV{FW=G!~@r>4PT5x_FzAxKpc6j_^>qy9# zuwaWgt@FX2JHg7j(_dD{UlNv+1R52?p060{zQ_3{c!6Pc__XZ#ZD!DDoRmKu-bM*YsG??>PFPiJ6vB%^?0#OB0qd#O||b>dyy zoxH?Jh1FA&c$a;vf9KwPw$q;*_o&eDLl1C^9{(DjC%GWala*upju=CFLAtnLQ^-T+ zLg12k6cEfIO!-&sdQDM2LiJxusjDe{3Ka(I@{ok0bn%T&nI13X7H7|GeY~jzHcBwf zLnsO{oz;y*eJIs%E}~Z09%bo}LO!J(th&UXZ>EC6Ko8=z3;{N(Sqc(;u+c+Y7B24# za&}96PCOTC1!3M&<&gMyGenNubliF2jUmyF!zARVe1f>ItUUS58!k3|U((%~gT7tr z$;L>$qk6(SSyc)!S{elm4?QY3a81>iKF+arlOUGR09GaVqD3&|b!-TLPh?}H2KE&4 z>^NV40qsBBa|O=wh|oe6?~xdmPBdWa5Afd2){7XdP%Iw$d|Cu9`u-*^)pQzRa76VC zIzJuHgSPl%BA>GbU(!c&j|ON<|FX;Exg!btMPK1r@*!Na+eJo=UlI%cDZO4QM~Jm^ zFibJ5u`1frdeQifszeK=Ba`&uT7KxG9H1$-veZCpk zfVUpko7>04Gb?uvZk?lhf7)ZX`K3-1qsbqno8*7lCCL(RMDkAF{J~QB{U^qSi;hot}EuwU{bV4zU@Qyy(f43Jqt(lAAGkhN3ja0 z>86}hmbW3&k`8QYI$=HdHr^DSp{aoxCXf~~sS$sFg1wUR+_D4aKjm&P;L?O+2WO}6 z*r*;jDw;aaSAGHFFAp&xi=7ze;$mB7mQKHH+wgIGtp*=zsY7S&nWHC@Hv$N|cIs#9 zs1UI<}eAQCAhfsdEW>_C=vt#;-wzPzJRQo zg`A%Op(XHnSjbuBLqIv})LgL{bbS<`N*V(MSlyo7O=&6x6jQJt^bYM&U{MCBxeI*G zczGVG8z?U)xsXbJV5b)&f+08Tk+Bi-); z0igyX@VmQU%XMUKRmyHZny|0QZm(&C#X$ry#IbfIt$rTSq3yP3LzHQA?R`^r0P*h$ z%?uOzULpxi;)d{`vk==)GYrw@ZJz`Vk{KNWbV!5Qrt@FB3O)J0Cx~c>iCPou)mMnu z{(hJ2$z3k`z~6=Cue|kp$5CpYn=Fi5-+Qq&$g^h~)tgiHRhDgp{hx}&8o3B`Vx{~5 zHzewskc}J`HD@A1%vgCc2zh*YKPz;)x`6e$ASyzXWfhc-my9-#?i;B0WDt9sGIVXH zFhwzKvESjQUb${xR`oxZwUT=AOPn`+-{@i>g}dVF^AkWbIQ0VVxgaN}v(n)%RVU+Y zi$;psNtoJr6h~je?f2z5K5S@0*HN0|3jW&&Y8*%G6gr@ENy5Ns4CMDcmuCBj zJ)jJQs`Dom(@yhMgQ9yRI4e1nI?#ibdfQGExd2oQ@a7TCxFpP4WTju{XHPGjZM+E>@2zd3vGkW@P;zb)Dfvh{6j-oxAD)+U^J#I>V4^MNjEXykFwP4AD9xxs}qS6 zAQh`}nDt=0#RKAIQFTQ#vmZT%joWYbk$&AbU7oB5&Kw_iipio zuErriG8B&(lI={{@cdPZUca5ZcGfiNpwDVfSm)WEYA$cwhV8*qJ>1tU=TN5I7rp+h zUyLT9nt4QS+6=9KHuxIBGIjE$4uPneS8g2d_xbY#A!unTqeV|%VxWwiY}vJK4zE~$ zpyyP;Sy6QH<)!{l(Ue|PjE^U<4pOJoN0i4S8w2O46%I1gX`<$v-B0nMPUDHYld&d0CmAXA%ubu;+&@Bjm%#MT?c1?=&8|8^aBA|#sWhy zEO96H>Ok}2G*tz`lek>UtoJ`|0%g`uhZK+)P(ZZ@Srn2^R!O;K!BV%YD!>`?l~Z?iJ0Ld2v5)P2k!?=I@04$G@{;>LM6^fZ1EZk=h1MI3GeR z*|%5QE#^IZW>xs(4ll0O|FWYg5ZwTa`B%9k);RvFIy0WXDfl@nWKG#<)z1yMc(|+ zP8q{beF{cp#~m!b%{X(DEO>+p)DSe29(TNNqA@hxxyvNGtyDAoWSN6=!tE<%eToLl zup@G&js1{+{m1@wt$me=OJp2=V=hk?Ekc#7OC=ap>CwaK7ld7k+#U3qJ8Q~JVS3HU zFpUL+1$f)kKibUOsglHgp%`Sa){;9tnCDxsSxVXIhm4*is2w5?E+l;1bdSvxFq<26;BpZ<=OLRS0O}l_ z|4_sxm3H(vtsQvT#){3T*g{hh5>Qa$W{$hEhETC*pLeXkTEZvue3JvRv)%944LPk! zP#JB#w9kb*ML+All+HTJ;YXv4QM@r7OOhjmW8j1$|EUUcKTE(A4EfJZCD=xT{5ciY zk)S_lUJEd$v-k_XcY1Qt6i76L?Z1WSKS;7uwiHlS8WtG6Ivt8{tk?yic6IRig3sTK zO+o)$ln~YLGrNIY0yp3d3b%{Q+G+6&sZWUhyT?m+rEb~#jMm4$Q^E-b(CfCZI#x^GS(X+o1Le! zZzhP-|13V8D@5oFxYA;iI)DCr{A@orURx0@C$u)j-?bYZg|C_;t&T5xL5tT2@$_JQ zUk;fH^GM1QJZpU~$T6&GE#ohQob#aVp$x;S_UkM2)*TuM}3}RO^DSQx7uf3UrrKrF;ksf@s7?w|PPg96B9D{#z-rxO2TPC)$$doGxhfb2d2BCoAu z6c@xbFs2aZk}48}4BvG3S++0b{Wv&Fv~1k(IktR7b}OuDpI!Fc8a@VqAbYS#CgUqU)zJjGOZktLdjujIH=+bmVqdzW>T-kfT8^Q0ONWJtLC4Zo$| zD>%p3qy?|~Qz8sYVdNdLl7c5h${8!7-6=LMuXz_+@mvQu)%OAz^a~<9!k;jelxwEt zxTA_ewM!<+uT3{Dki+LS8}S1njGyu1oOJ((dAXjwkPqtnoA>lZI}5Z@$a;m5&uG7& zHCE4rn|Y%(H0~%4?}o>=aQCfg`ff3?v416Ncp>q)uDxN0=+rf!zta-Ss9tDTOyTgl zC(t7$>=2n|y?5!iM3KR8j%1c@-<`n+SB)NMS}y#Ka2j_I6WR^E{^JE-00BhV@2uBt z`1Ii}1L#w7hqBEL2z(9f^#g^LjI!uc#S%U6Kn<%L5l`w?3W6cfNCh z04Lpwn(whSG|4gO5Fsmharx{psDcNqsUIXkLi81!@wl~dIZtNnb7+8UfI{$Zs0ofb z0RvZrIqW3hq^|(C8hjj>nVE468{j?}#VNxG{JAPrDNxduFx@et3;s$6vu_S?u!A_j zUMq0$^Y4%bJ>E-TlK=exY?9p@&r{qb#PkN!TYS1Y&#GCQJmw>2)hXL@RS!eUmM~u0 z^51l@R(0#|P*vJHK2k5_W84e|Lj`Yg*|L(c29l&A7TAI~yU$p!)26X8DChg#5)t(y zs*<1}$!&13M<}>t)y(Hw-WxH}9wtYe^V)q-jpQb?QbrnZyN2s;1@-&VW8`9&#=kb=R-c+~e&3X4)XrMw#r?h};!}3){Zu@J zt#*ZneDYhAJSzNSW3Xeun63c#KRIAyCja#Q6%Ibd(kl?=q*FhN*Uj5y$OQ? zYMYf3|1zPyVIY$1y)(LG)L}9kw)8B%X!JynIjHL~Z}s8w$BC#B<^ZHXbeYf}uP^EO zT5Aal%PVb43pt4miV6%!|NQtA+-)O+d0~*G|&qv}Kjnv!! zo1>$1ynvxaFqVli4h6&vMCws!)q*7g=ZB7p)s|5?D*IYsej#D=krC2x+?6w(G(P(G zy`s&FfgGLAyCARb2PL-H;m-TBq3tkpJ!sD zt?$V)e2~|ARC{gI%2oT9PKCJU=swlbcmegp!8`6WWxF4XAJQo9&iNIVa5E34+FW)i zezYg7oBnii5sPa5+MJ)@yEZVz`-$+EN#(zp5zAnv!hfhaocC7 z^x-tkM$`p1KMxC+sMAMY*mcT&BUDhTY@!T@DYylKi(vI13Uiu$uOo;?E?OZB@IzO< z2J_(izau$CFygA(P`i{Fi-d46^_Cr@{8qD~jPNk+X#CLoK50agOu^dd{*j^L&1xuV!T|YSxHTc%;kYOn z+^Y@@1j2k=8lI5`_CYr;%YGvRSOjB7D{sFU$vikm4|JiPY{14M=-n~_B6<-tWk-X; zmImImTibAZ11sJq=*l`oP4kYy-U0hpX`ksea_eeQ{zt@} zm@%?cm#TEq2&(X;Eng{`Hq`w|Pb4OvFI}(u;%7RHCt#v%p+!~<;>qU|O$^^x|4Fgb1lM|db zH{f3IBgdy+*;k8xm=@jMQjM{*1u*Q9mGRIB@4)UIS*`sWls`QaXn zv6T$FcsMlE>KwUbcfM2~ma5#vm~wJn7ZDjgfz;Ap>8>kd554Miz=8&N4^w=5pE4h1 z)C@|LKTj8A8-8~~b;2PQm7(kBmmO)?1tnZya})V#6f%GQK0{RWOpd?a-8ekRw!=d} zca1g0h+lqCNIFLMQ(Uko-RhIq$CCRNl?H_8h4rWc$7#k^GqKX;*l@x%)i%5Qq-}H+ z7ZhVc=YsukEC|?lOyk~Hh_Hy+Zh0II@$YaFa{@W2!~!2qY8-wZH^z+b*5~d5c`p!v zk*`~QRh2-T_n+6jYQ(SD`mRGu0P_u51b#YPVQ^_^SW1pkXrWjVz9r53%VC_%qxFhOag}zenncOpbO( zX`x4^mwgN3uca{*%3WCF$s`0Gw~q}NvP z=JR7SsVD5oPoo&JQs0t@4@b}Gi=FUP$?XqqAE`RtX1a;k{Bd^jqhHo}PN}T8xZj!O z=FT1r6g}uo=tpTa#)}5761PdM5~QzqDmNV81u-L3KN>XF`g&4+6IB8bS52)D3c_aa zP_!4A2iMMvLylmOj#^0_CkW*7O86rnPzZ_Wbi#G_jsSD1fSDnLPz{5T6k<8hP2FH_ zcq+X&qDz2)jEHpbz8FrtVH0=4B4&CWeMGQo7QGM((r=}wFWvBd0MAoiR(@z$NEYS+HB+G$Xy%BnUV)mO(vcZuT9_l|;M20?= zO_a^)mHpu$x!3`W>8FA`c{`&mm!T{7)+ND6uwk{2$IrZ2-cdW5evP7|MqQvoY(Wn& z7Y;5b`qp*!T$*016G;B>|B?1^mGbF373In?P+eI}leRP&=llDH=xAv~xF?tbo)?}r z%3gnyLkR4`ki0}HauL3YVh|ye4Cd2JsF1;K95tID(F88@nfg)#+}H%Cp^YIok5{eY zyH1V|9^*^a`oh?&@ut5-jPvJgDfC9To-&MO&zui;ctqX?ObOypTSUay10WP$L=sGhero88@EXy5ay5mZ#pmYUk_;AQDc!MAyS|@{kYVt#r}b>RMR}NuAg6e)T#*YKFKBMcOa)AG*Bi*9cpV!RR1Y zo^O|^Js2iD@=z@=mDR_!3X_jL-qNQzD6tIPQk2NRawO68KCYObnh6!H)Oo}uZ`t5y z<=`Im>40zzkNDfh{^0SJzF^qf%QKO4!RLL?%gFE`cxm!=vbQz*tv0*OR*Bo0pKI8r z7`ozna=AK=-^rux#W#q3q}mx=YIW%`Uw~Q7;vu4|`H$sp(?_9_z3|&z*s!Hh*_;d3 z%FhHjw8`xIbk8ZfzQ0L$S=4~B(kp3A+L!fWhHl?bYOkn8WD3@rzk^Y3ziOtE&GnTI z4T44Dsnr5b)%FJbqr7oymt=ZkQRNq?hl)_;4f(D-znux4P4_Em+x7xGuD7KUcFF(& z73MEeK7poaiC{|uNnhTqK-+iW(+sp>1hA4Ot-Drc`U{LsEd`{h(%dp4B8o}`V|mY) z(?T#xU@GSV-`TvNXc4D>i_e&Kx;VZkQDN*FcgB&teP48LC;G#{Kk^N( z_{IT+bh_Ssqr+KRo5qXHqTy~<<0&wyBt;y7=4OrlKni97jp7rF%Wgn@;>7l$_Dv=i7e4Hqnp1vCw5ANE$IC1Ls8q=eu#9 z>aXmF6FErK$06m5oMCjM4d2C^(`MwO6A?tE4<;Sctvsj|$gpc}jGa6p`c;o>2ry$C zfBElRemRuSsiT6inrZdo82)O&aQ7v!@)jPi`taCXrClF+aBvcTMpATCxzxNvS8)UM zJSB@)Kxmww8H-D-wpMR`Bm>#lU;t?MN%-5|kU*|-W}-nzmW z^;+C9vDciAF>kdsEVR|Zk+7P#+^OVG9Qj5ErY8`l5(07%FhTWXqmr*sYg6x++AN0A zUIADv@EJ*|l0w$hHtIHH^KLlI&{*q9XSCGhZ29JYP)9e`ES7Oi1IFEL<2&obE7A*2 zFj(W{WC6BUAT^4wE|}gd4E3_WnNru#&@fdK^qQb9&@MH?iMt`s3lgc`*boyD(IMbx zlz}5b-LVvc?QVKN^Zg;w_hce+oc!eqfB{jR;=|kzcS2*4iC*)dcjV!nfI$@gv2pI#I)p_otPl7OSRN=%CAitqkT6|&Uo<|tr@#G9?R5nlkv+r&?{I;^6#wPl%zC& z(%vb%eSfO@EQjL)$HE+ho5U!kD4M=Vw zkNOg-T0(}Z6Dg}Q2fQN~iT^(iANZI66$^u(ixlMK)Hzrj+873{NHh#lFAn6PKngl# zOaX~uVUWKV^rZGz_M-|o;p4P%(X_*>s%>fo&>XLl7}zaLaa!v-b=~|3`)C@ct|(F9 z89=i&!2sl$&2JA&8P0;qV;TVbB+M&btu|bNAhfy>wB*6e6pU;-_F+Rr}VXl`yg(PH?a$(VwJ>}j#Fb`N~*CtFJ)LZeO ze3`PK_5Ie=@uw!!UFw)*rPIY;G5mp9qmHL#`~Epxc8|!zg$JHw*b^&LRKd&#z2H5G zge!YW(6cA-x(|!DBIArA`*DQU*_FBb`NezgGtGXz(bC(W{{d}t_l`6Lf+q`)f>cgF z(_gzq5PUR|a?V}Wv3Y)^?}OyYHK@@f7gWbx-I&om3{+Aqe<$^N6hr;s^i1$T0t4!m zD)#NK)jU)zak0as^#gpwL*kfCM_(Cu-Vp5b^uRwEED@fbl17fO1lCfUg?SnQ0*wBC zC5sedQ&^~v2;8#3rOGbxe_BsJd{l(ppZ$HgjE%hTAIN)3{2NOPBOF|)AS`rn$)u`0rSO+?XZa^eK)g>a9k?@ZNB|T)fc_;p z18ESph;A%(=0{J`Ovo!`k+=G@A_BXhT9QiEkOIxybF%$u&W5l+1l{Hpp*r;4;#zdp z7e&x)-*CC8(49#^)4*Xdr`L5;&jh_jSNS;mU2b!rTTN0$U7tz|DXWtJ_X-n65aaA? z8onu;=`lBDEg#L`%FR0^#qcdpJ2h>ZJWQnU*5K6HMc-uih6v^B$#FL;yVltk&}T0; zP8hHR(&L4mrq!PV6LhN~p=a^EkSZQitNqz3g_8_symH3$+j_b!v-Egd(D|{M(c)?R zi4co~QU*-t4J>1!+p}ELqfp_s$0>w#d#8PPUJ%!jwWiEtqe5OL{8Fa+lwR;&6AkG@ zw`c7boDxOoY+K0i&)(jfWAqtmjNg1*jCH%e30>u7^m`>R7}VfGp;Wov0?xPboEYq!;C|OpgZCd`A$pcjR=@}Of;#Y@{!I|E z{EY^_jWm{`EmesVKB_RrHwd-8hG{V;JPUrG-|@RTYW||{j@bXB=_;e5>e}`hhVB?b zq>%>cl$Mqb=?3W%5Re)=B}7628M>5~kZuvBOF(H6k?v5w&GWABkH1*T^6azEeP0=R zG`H~Mw9yb|MB)nszu>!eJ-qn?{;80`QMzv7zRrE3G5i#rWaJZH^}rG*y^8jeGWOHz z-;y30xGo|&Xu5kH=(4QK_NYJO0)^qn60-4Sf2gyk3mt1CEUbe~i15ep#m3#CRkQL= zPU0B?*(B@f07~19_`0#jh-1?b%ix`*o7P30xVvR9c$?VcRdv3feb{_diq7+a&{pdo z4Okv1KfiBkRROwly0)g!<}(@SOV9l;gC$v^>v?aUhd6(6`CQfTy-T_E10R!Q)u$0l ztm0pX$cp?V?2Wm1UEIOTcdC-tMtAf|(mx1jl(4&Rti5 zj#kjT8f30SBdWwgsIVLpA741auqqKhoEU*k*qlfhj*CnEGNopiP*vh?QES?dt6hi6 zCHhVMjm3qg*1e}6CvlqIZb~;@E!O8r7@P!b|84Vda42oyGVcg#QC~Cq;GAw}xULm) zwWGE%$21BnDk=FXjMq*VCySwhsT&((p_07{g2|)pjq6^5!kI^QuAtainUj?gg~s$qA;3K6Ah zZD6q|%wr8)k){=}gWd5%Qc_ZC>+Z+O_tn*Vlm9T;%9tz~9_%&4;wK{2Z=kFS%{{9q z(<&tEnQVd+3@sk#M=5Sez-#3!%&&2>ja<(xC-V*YzljG7t73>^b$|Wq{yPTom78s} zGC{besLR zKZpetUG6yMr0ATPLQG<)-`al8dEedV;WrUYBE#l`QDUe^fs5R@YP{GvsRtm zYF=I2JD%^}!rKWs%3f-7_wmuMe*az=PuzdKHSFA6UK_JgUI$T9QGw2O=*u7ZEGjni z@Pwmaoc+S+r}#&5rYaz2jg7^51`=e8oT$M^92lIz|D_Y)RxXUmfpY_h1;OqQG!*)# zrjNih&<_qCk4XbI(xr}%kB>p`Av#%}H{oy{XhPZ?n$tBfaGh_6t7`d44JdjL*q~5? zjBTDCt?=hbXT~jK7s1X`$?ox@ahIX+aRR;lVAtWS2d*Gum*OOk@4^aSS5{tOjhA{%neNx$e_x>sgYkd!bw5HGDh5g`Fq3pB1Pe( zc`YgM1mtX*?h&m1VFfhN zYw6JA6f{}b7wInQ!?-6If>7~9#aaU9TMdNt0YmLt^rpxzRyb|VYpr03rhzS zM0R}e@*5lEVG|Y|G^VfcQ31pCtrNth&J1Vyh;B;PaW`4=5|=%6?{`!X zuvScJ8AtWaiEx{HQGBVT?3&UJ_)2b2x2isuuBoT4A?Fca2phO5n*t$gz^L%F47( za0XTsz&;p1r%|#n_e(?=~Rz%F(XnFBC2xP9DA5Us6 z`2knMTS*Ctk295X+@At@bfrUXt~}7Fm-?4tSkW9FW9B zw)Y+}o1(jj_JqrpiM^{}YI|+0f!ONIdi>?I(MLOJWP~PJI->i_`HWx4IvP__#OFnu zC-P0@0)8~BGI!T&HaheO= zhENe#rFKWHHZl2W6CQR}7CL^RZnE*?%RwJB?rB|~7`_xegCb=m=-2slbqAp+u^(D> ztBt_B-YH?8=NNgf3D+@r`H*j#Of`Ah?Xs*^arh)f^+g(G;;151G><=qf zKUFR%OU`7KYA`AY;W_EuzU<&=P@4Os+UY^=Nje}r(PtmH`!gJ=Aa0`?*^eQ8YhKQ7 zZv9FLl3|*Whk-7@7}@26PT*N#ze=s-ZLB>E4Bj=yW_|$?6tz zQAXeZ7_+{YYbhhM-n^EBp+B7TV%Pw=u>3k0nTCO)G~QIxIFltg5&C2m;Ec3c6~z85 zTx3>Ls%ym%JBlwwc88lxpj-%Ae%aJ6ShK8jESM~P$p>A{A}~+{LqfQb1Ca&n6Xbn$?{GeF&(z|zb26y36K>0{L+Wuj^l?d#u7XkFkXdpcw6umh;t$|W4DI6q!A z#MnKfj2Djjy`mj|F&L%^3=BbC%{&w(>kNl%siEjC!t>HOt#7;Z{dJuF$XUa3JdnSM z;U|Z~hVwQUgJA)Kr{v4z+c=-(rzh<3T1Ql!r8dUY8_hxJ_zKvDFSq(Q96u@w4^pP{ zLn6}GslyQZ+CS?Bidd@4Q=*lXui3C-+7f%jMIz_L`@;?QCDUZB;LC(v29rrNw{k_o z(+&DSUb=u|jJCD!d&=)RV9Oj?wxP<;f7y#!y;Z{GT`R8Y!&uiAi}=#;STO|_qW!p7 znTkS>XIj^$Rt)Q$>wL$y|iGT-0J8_6f6j z!wzm9JGR>>NUYfUoR9VkX$(n=;z!_wX)u;>=x+Bb&-#*nd6sVge3`Ff7ZkWN)r!kn zTJEH(L;}>`YlLwQ0dfM@#Rw%HJSe^z1Rs8|F@m=|9o+~90naTHP;DqV8-Nud3Rs&| znC^dX_F`_IF(&^bd`!4m6ojaYJXlD@Mc{kxs2EmT@TBrsD|0q*^gRu$0Oyqby3Ewp zwovl1n;Vb%|@oIUT7S8q&zg#Li#Je#Hq$D8w>(7KwG~A%u}wn znU@Qxq|0Kv!7Y1dOK2#@+}MaL(k_N4FMVn5774-IvL3yb3mm_LA@*d|zb*W`=2`IR zX}>&Da5e4;r(!q)mS|DhK%X0Jyvt#X5FBM-ce;9*&LObk6@kX{G@&3G<|329^MJ(n z!-wvvXCZu1>nj?ePcy$o*+rM+6Y8Ukt-nzm&x;hL!Oy?B`8`KH^3G{G(|XofjcK1Ap*3tU!?@K9UUrrnB}U)DN#WyJr{L%3G5hk*Y8^!^E#Hs?S+vn5c8pQBcxT#lKSrb0ewada_#1fKfFFoLD0Tzq@2|F_k>2bd$E-N|=i|I# ziC!bMj^j-D1O(&YxlK<`gCtzDBGhu){tKJSD2@F*9RsHF47`)VftVJjdBJQd8y+rkX zIqvoQk?#DAxciG849dIuBhmC;pUdxtcpk5_^(q8HmT+KelG(?9G_HFR^`OX;n@koj z3(WoXzw-Icmxs>>lSA+;HN`NKdf^TRo+EMm18GBc z$G6SkHltPgWDF5Yad5pFc7$Ro{rZ+JN+pK)=4Qn+OW(l$W0j!BFpX{iOR>_@c6(DHadHMAP zbQ(bu_$H6e&zu&B^Jf^#q^?tF;tlbif9cy<7W9#(L85tLzTJZVAwkNs2=x~y{7j!& z%k0xa}RtVm^Rm0?*9nulEZfnzC_| z{W_edLSKhro>(g>!)PrR*)ou4N*E>0D*EE-qzBwFT6_Xt5-sJ~Q_lCR2$}g6{Zhmn zCQ3U$S(V{jo^cqDX2%2X;@iFYt6^~$#Hmr{TX_bJN}c6^M(qkPo)0&=P4E2wYKmA7cidDDgq9o2lmFe4|E&eQnTbOP<@x=_r=D47ydSX6eeK zmCRjwi#C-NPot8MSSpKom0UZ9 z=h#tvY>Vy^lUiz4Jo`_R4Dr*7a=hhzs!8$i;r8|GZKWs~Gnq$vNEe){#!;~p}|#M;yt zCmtOxtKs!9UK6gf=#4iz*wLmjI9l?&qo}|(z<$i%-?)&d> zDS4Ma18-X81|9{s3S}irSi~0`&S&4{sj1i*ia1v9)pl&kGfm1I=E#B;LymVGS>zxr z>4Gi6*PIR5JF~yO^mImenFISnMh3;bG*xF8mxq#crC?m92K|DUm(Qu`=rTxQU=2fu zz`J|T>>fsCxOWmrnf>fT(p|w`WWcB(Y{_Lp9wVi#gU#|K&}zMOh;QI&o3o-t3h}5} z>oXppvAoYUQejYOmoyIEZBKv*1N}z9$cQE+Yi^#47)M9W%sf^o)BzKG6vQ^MC3GiR z4p`F!UaQN2*Ip-6A2ABUC}2jk%T$8s5;VVi_aA!pq~Bkg^n0U@K?7g> zjnTaITkjPQji^B|p1}7)fto5Iihdt7M6s(x_RgbWbiT5z=M0xjawI?L`Qb7yw$|exzpq?F)2$UmIIGnxsqv~j-nFg=?bgG^9S0?JghFOA|=@( z4O*+rS7^E>#HMe}om##QSbs*9VfS&^{NdyBkp?^a6GI&YX4Zp)_C50mPn8(^Z=POZ z%fld@rLCd0wY8+Un1y+cB!n#`C>WP!sz952SeF$>hZt#LVzo^j9M~_7^)KI3Z)Ok} zQ2Ax$KgeW0``W5FyJSdgQyobLUZprAa4$2Ys|~q;fOzmRmyCV@$s!TR;s30q>a20G zDJu8M3Jc-DN~)kBPPQOlDW4^XZDj*+wm$Kg8g6p@P?@8f4;2Pp&2aLx4&R$&ts8~B zi!TmO=MYSTC!j(Q0|FN`B#!nb$2-SoLe(F9{)ejPf6tbHF~1mm1VEDmDB`;HxHF}u zkc-j~>anIVS}Ri%#uT$~1ktsJP(*oNsFY5sgL5g{OO@8ZB7z{ z3M|loe&u+PIvz~j%zwP!otdVKJEluw_wU+wi_-V2sK;7W8LAs6CD&)s-dJzwFre$7 zqMa2r@99D<-4-x7rT>i@LL>JbpW9J~A24+*_n@D(FCv4e`yg^-o{x1CX0xGARchvVBd2LOF=5G~WaI3(uw*L)7aOY|!xD7e@cj5Ok7#MIM za8);zWNbT%i!qo^;bybSw-E#APy!|I0Jz6Nh3zDGF&XY*JO)#Cl(65QIXTda%Lpj< z;>VyOw8rg9_`QKwpOgMMy}pJ9!Sy_%qQVBO3-{&_Ag=PB#w4nO6Z|kswmf?+#Tx=L ztC$;)P)$->{GMopr<>~b@84bG%B*Rr_vxXhhk4iUa3OFQWt)Ss6-@`IE)<2NqA|4Y zk*-W?K5*N6A^PK71Uh0!$BN*nII{^lulpbtGM#OO|0kM)Q0s`H2Tg}SR_7HjDj;ii z<7HUNmQ2EDJ=u63>g7b}v5YJyWKX@Ypt~rAHdUCVpHMI%l&ss&A3=B?j!EnoooxDt z=aac5W7E#_ZPOoUP|f?#zP<{1r(Xnlnu>;+_*#eg^Nuv9i4K^#iYYooaWt>&_U$d;G&?ypVA4N$AZ zFjApADmvI!b02-VU|qmDxk(UW2K&0ZyGw(s37oDALM1z597&1WHsZaQU?=%Np z@}n4{10Ej^;DuJ0SJ2c07)yZWK8+N*F5B3HROaFePSF1S+M$>o*Xd10p%$ZpEnq0X z2@n7aUqKxRs^E$sWV~ZrLvvSHhxX=Tk{5RB?m5D$a>4$PyluH_)@!iOWbGb906F3|;r7TE>$PJrc}+~$jy26xA&Mz1a_F~t?MZE$ z5DpV26Q)YO`QDn*at4OG>2k(ah%3C&zPk~B?g_=>mmZP&8Xowfz@je=*I93F#3pN! zux2F+e>Ps#3(3$O&d|s2pk`Me`*;2N&%gXK>Sg@Ga$gwrwu}8;6IGI#x7BUWp;kW` zq8g>S3}NXVq}m5^o|X1bSX{V99Zx+W#_I#3v%m;;o|HCYrf{c^$WbibKwc!j=lP
      AGv5@7{6G zA08cgjym?s^R8#EIe)VxMcIp?>MbNYh>$^%hG3PB1wM^hD11}n2HWOn^}JKmf5}1k z=1rsH!Nv?6!5C$J3Lr*QIu@~MYB(G?kT?c?W%gj+Cw3d0h#0#dOa)>?MuqjL4d^s{ zeWuP+6@Qem&$FlNHf|hx0Qes#o8!*pq9BZO5X5A_i^9V5G1Q}CBOs(W8H|lTVe0g% zu+L$ly&dQ3a>~sIAks@IDD*?oLAY&YHyGSZ0R@a}x;gv@IzwAIcdU@z4BjNLi@ zC0jq!P8UM~cPaB~M-9s?cC!K74E{_NRlgsIr7a+6oV z`_;;dkb@$H^~$w8mci!pPA%;ocqR9OLA+}}CML!tZV@N5sHcL#IEj#mha#ddpgs7R z$jr4KVQz#Kj~n}o&iRvoTowJ@IT8A1Asz z)|8%ldyppJoL%=%0$O{=UkNx1TJo7o>}BgoI|T;l9rB?B0#oWNPg9@|GSnqKg(wzq zaEAZFD+kiyA0Dlt<#)QdAiSytk-;tq6?r{=oRmTd;5!MZAbY!MR%wen104(Gs@7oe zTRI77w{2RCy9)X{9G5q;S6FD(eL=qEMX?1geM`C_A}r}D@3?MX2N#D%_$(zVxv9@S zSeCaPoNe{pSk#TRy+xiFJ!6B3fXJ+13ZN^mqeQTe{8(c!dK0RN2%#+Z3J)<+6MOd~ zQE!!qtZa`eHWU05_`0|Ymk`k6kzhl=B_H3qL^e@Fih%E7=O%36BFI&h30j`9TW5Jv zswyk!Gv_-elVfo>Q-r#3sQT;g)w2`iBcazZDu_Ps_Pv~4eQaiLuVV2A`2Ip?}OjzJ07OWiRms=L356B;HPQ|m_+0Wnbov5-C&YqAKEpJFp!Rch! zI9YS|Xp9E>rO5MG)53A&H)uWZccH)j@6cd@BGl4@8b`&N{(5eDpUtrqj&8|dDK`h44~ooS zy`oG6!J$VH;z{s!EOLQ$Bm~?*z0G$6niRA;L8?0Ln*wte$8-&0&`x3QkZU}`8WxuH zcIg=z9RHCzZ|&GD&C@yMblp^>eyOT;6$aWO$tmlOyZXw}PRsv<-#Gc6)abn}Z#=$R z)QmkK3wV2MGWlk|*)HJET;goS;AJ9jRl?gIa}3(SyA8l~|qh*I>)Q z#R+m`kqHe(oB#~X=Gq!$ZyiAni;a)ph5R>sN#Ou{N9<;B<%-`(M$U!XR3zAN zn2$RkYBx^+G?VATXcyzbxez02Sw0RV8s-QSGF?&rQTVIpZ>N4vKwlq^itI9_0u~`} zL5eED@CTs)tJ6J_wz=hplV~4H>x~0P{3%Y>0Jkd{z(OTq-bM+prLBz-+kLDpn9=0wb=Cwze2C>q!y8GDaEtx9~ zlw|j&@Hk{btk3%`Hcz(k>bH_^=PDk{NQ~$PWNEQHc@}F`-uBxv`nZq!g>WG5b>6RY zS%aT^#E{l}uO6ZQhBMut0Mcd|gdd$VX@f~TeyLr4&50wj@ab$z@|pL-b@PxG`l~T2 z!^iZvswF4aa%u>&BCR@eE*Hiiq7Kit4+w*a7_b<@j`7XQV(&Ofl-Djt3$je$1=Edc zu5nuqQ$awa4)YAcEK7eK7L4qLDMc;OXziI-g+%ZOV!>@5baSqeti$p-k9<4xz1a7{ORZwr3Q!yf&BR_bGE z8JX@#0(bxQJJ4UYFaBUaR8H>efa1wLXgwG2q=#$&Won|BNH{$iECwB`!OB*7_v2T% zuqETP*SHla!^vv$#%KY=aCm=rznxRV=}fO1AZ@coYj60lx*|E!H%~%52dE7=7$t~U z)BN~dGzgSMx;!L$t3Wx|CE)Oz9am)!5$(+6hJzb+?DTdw*dvl6OUAt{#%0zDk{$Oq zXLF9hKi<$N`b!?$T75#(>qD`~hs~!V;>3nblejb5yos;?8Ld`BwctK;Rw8Bdo=rVe zy4bQ1=_GTNNzNQ(4OS7s<7K?&xcFxzamDE`1Ga*K#j4d*5pcQpVMmx3?5b zB!@^F+>k+n2<$7Yp7Rc;a<-oo5JGdZxo@$%yvPT_kUcF3k)Pg|@bSI7x5)EFhnG%W z7(BHYh^|E{Bg2|xqc^VpV{%|8Z)Pai%KQxwZFOZNXZ)P9 z&&$@0-WxltdhpRWL+DYov!D*_j5v0>Q#Jo>$Q<4+*@2p7Qe_{71MSwDdE=~MG12@K zhG8V|&k%S#h!L1e0`!LhlsUd21>8M{;EIcf8zu|y5eN+tM`&(kcs{eXtULZczRRAq z>3pvo>^+#qc+3vzE%|(b>vWCVpClcj76=TalVib_wnjAV(U`56L57A35SF3F2o<7-_a9U!ZeX*OB%^w7LcndZ@V8`XUc>(5Yd zHUWV-o#So%=Brx^#IvEXN>Ay{yam(at=`+Z39hX*XV2$=^Qrcx_?&P42DBg|Q1bY{ zLRPG&?Ou9(^|U05?tlNwZS#@>>V=>wx&eBWv+3E`oFMNQkxe~{CDzWvN^K{eP)A~? z^4-qgftw8rH$oJ(pc^^1_kMkWBzkhJAMaktAVp`vR|7>#BsD<>4Nxh72=-2;i|~5_%?k`_U|Yiw0f}<| zFI9&~|0^W|6MDk9USWd>MgzkF4=bWB4@}Pi6xPF%oeoyMa3tniKU3QQ5+t8}m@a}D z*QBKkUg7OL>~I>MpKLmT`0@2}IUGcX0AOliytF8XA)p9-UZRwT=3!leV6bL)(m%tx zjIlQ&a=~ngR94J!f^`Epv@@?**3-ky7Dfyyad9fq%hbJ4@JFjHlkQ-O`Dt((J+g2r zTaVtl>Va$Po!xbB`o7pWIH(}M*FwLT}WwJg5_XZ?SPyc39~mJ#6RI_cuUxxjivSL!=(^q`9sm+HE$-wPwOK014`b%V88 zIPmypX~4Myp{A&lwHh{JjzcFTukwb%tkQyK-IppEhh_Ame_l`sCdZU!ekw0$R!1L1 z$Q~R1Cy&S)k3V(ZTkjekC62W`;u*m*HI{CP{iQK6(nNj5t9f=#*e7w=@2XkI8@#{k z%!X`U9NxChdiE=-s4PxAtB6CR7L0ZJ*F+<`uBXP+w()h6^4FElxB=L2y!=2xc2uP{2x5 z66q$6z^K+xJ}*f79Im|yu-u227LHy_TwMOAPq#7gC!pm6AI|0B!=(SLi66YyjWKHj z1pE>-G#gP+0BRIW@~Rk95{$F}EcMQg!1Sb$V`1cwC1UUMqm^Vf)`RS#B`%}@#?3Z6 zpwEMhI=MBvzQ>Qd1j}6-FlhtJK#%~depOvqm0s(s#Emwfz)r}nWWf^ye%cARDZR|f zvWJfv&PL4p)m*3x_RX-Y`n{{pj=_)x5lz=%?#8fCxg4&}n>-KCpCPBF)Jq3gd166w z5I{N`KG}0wo*Xz-ssvpg`J-gGM*Iexx`ZycBAj#cZ{9Jb4q@8u}!uK#ETR0TB;^oJ9$jX_->8t-MKc+V#HIV z+|A*eVl#7++GCoiA!=ZlIb*m-GV9!%Kba;Y|pU$ zBx{ik@xi)mB(bPbc24ZK|6;K9)gg<_B0|5&SBvG2IvQ)~+NM0!!P)AG_i(S`qY3l7 zjXxO?cVNKX!%TVppgFuZ7pfL97MGzk2zJ!cNXA#^e?^co>~PteV$24`;-MT2wR(=% zf4o!;W+AF~-ph(q5*ny67$4?Dd05<@s$t<*Rz=bil{{e9FatJM<{PvkKns|nw1LJ2 zHr(Alkm6Ep9Kpgu-luYy(IT4`Vf{ATrw9uLGDzM8HN@J$0f)c$?;mvMfGj&I;C zf*J_4iA&cC{Y+kj5ewA@nUBXV6jSwdRez!^Ib&e-^q@wuL-w1lgNJ=v-nvc1dRmIP z3pq4IaBy&NGo7q&bbwaBD*+Ae1SkTr{r>h=JAK>S9DDD|F37$>_dp_2wQ&L6fvLNN z9Xs4S0HM)IFWL$JBa$}jylv9RNC+!{%J82U~auM^j^eNK&zY_3h>HM3>^@ zl^dYU`4HUiyKFLlqEf&U(9>JqtmNlGzv**(J@V^;hlA^P!VhGrRjOdfzkuzLHr%7K@TVJ62}!#`xmtM(=j{pW_m z0kXz8rNI6>+ibHZNAlSe_q*-yH|{afn>5k~dQIZb$GTxHMvaQRv2z~Z_9wUzv@+QG zsqtLcd+|;g_E5rW1uFKABp#i&s za-g&{80%7guBEm2{xDL!yKnmf&Hlxm7MByzq*|#+0nXKD5-NGKAjFkgU+fEM+Gzh_Iu; zASoUsh8F`KK-}n>{i&admCwzNk!U>taJdK^Pt;A1LMTkPRUv2JxGgF#&wO+XZU+zo z03JdZTw|m_Q2D=t9*|oxJ9h*?!6x9Tg9HF-M7N^^AWm?%*)yX@;QSV zKWSvz!>t=PHC))?gvM842T(`yn&aU_TRQD;v^It{A~s_mqaH&vARAu|`N2_g9paX} zrNmX)J>MBQxDph>TKTM) zpK!}UhXuWi8zQ4d-I?C(?Pm{$2igRVU$^Ahg4LceaL9Zxs7f3iQTl_QO)UNr?+;Jy zgTJm@)hBGPK8-RC(A(F(J{^pA?;;lRAWf`_tKr z$<7~9o`<{X8+r05D9$dJf<4P8SW&B%8^3c-ecFD?vJewp+x{B0d<{uV#O#cu&ip1v zF2+F}Df&`c-8l&r-~J-9yiG7EA>lJcgMRlv0^8XxvXGz!MH+b7J+dGJCa$f9!XPo6 zS$*REvwX7$DElYfMgly*rU#Sw%l@zAxd~t6IdM>&yM0?e;OT}94UETz;Mst7QT};s z1dv_cz`@lcFTSCJVgIN#f~&Lnz~9_^J`B?^)ha?_4tx3ny+7yKuoN`dCb|8P@xat% z`5^*K$OKsb0N*`fU!7FB zzNHAZ4a^7^sKxap8oogk5@cH^NrZCLeNUEXPK#bPNq^SoH+#F3kk&4)B0(Xq@#UZi zmpykuk|e2ojHtgcdt9CkHf?#DaN)a(a7IfZTZmb4tU&j!$(WYf2% zT^wy%PrNSC*HsnovnSF09V(PWX)J`>+}t7jnHiD0&K#S*zepHl(3yb1b`Pn%#w&=W zmG{mc9vl@8yZJ4*;SBw}PhY4Mp3~a4w5r#xhTQZR-qml}xmAo+G31SX#qT~%g7_9+ zPSE19wF*LnEr##`2fGAz`2BGA)Pi@X!A+}p)%ixjHmuG1f!prh8!o~f?red!mgzKN zoq~SzI%Vy4FNtOLN_P#J0!Vzn>Vb2_x8_nLsa4wkWAGxdHT-U?^=XrSUHL6%1xD^3 z+AC&8UobNnT%;Pz-UCCTRdD+?pn^se^1V5Eo+t|Q$%HauMI)yWzisHR?jyI6)PRN2JAYA7AbVNVL>==KG&74x68ug*CRr* z19B@r8eO`&_2qhBly+eVV0qyKR*P|M6M?fQ3R5NrpE10_Ko$F+C-3|2%eZ8aL+I_k z#)lwsi;E*D z9B777d&<=W&!flDa@w=Vd~Wh(jOQOS>ED}edO z0BAEO|G81Xs@jus(h7+n-NVMhPINgUj(C0HiM85+xH;>y$rTKYrB?Z56>Jwzf8d69dsB|kwmUW?}OC*yd z?mv!tA#tf4tvGr-iIyMDuSc1g(nSK7s!^XDM};7pxpOWOn^_>hNK1*jdBKOZ1Ih~R zQu*=1Y}4BtQ1o^Q=&yh^0RCBfkpUr_z~pNvZ2}o7{(l}M0K9`_k1>8vd@}f7g(-u+ z{5B4_Lm5@bt-%Ti?Jw6cZ_E((pcNk(nE$m#K6Izq?*0CL!?2)Q6gBEDghWy1a!&rz zKpMks5|Q7H9*_ms4Dep!F;rjOwX*#`lWma%bXI<%;CF3h^jCnoiMDWvuFx;H84+n# znq+-9AE|MpWo7nWHEe+o`}6;zPrX&?E}59jFX+Gsz#VYf-9VTlDPhu&7WpXnJi?Mj zo&YPanPA}a1B*1K@D_zZSM4(bHcu1ANG#R`ysT<1Wr-Vh0!LigBq8a9P7RjQpd&hh z!xb79*Ok}{`xI~XU}es2VMpCG7VPATKgSQX$ycmm%1j-4lq`o-AsURBycJ}%n_DdG zTg3Y|P=vjO{@EN>jP&s-J3-uU@h87LO@>mhX(-~4j8>GCQ|X-0*{yxMFL=k7Qt!7# zke>$8=PXjkLd1tKz(VK7U0*83uJvl(o~ym&*M-dw>Gu#<>rCfv>Cu;pR6Vb>SdOGO zMr|Gow~UUG9Qz7i|M*Kv3u~o{n!pyYfu3xAkC^VhzBY7&>qvupuM}0j(Y#?A-u&dj z7(-y3M$I2LZJn1*m0vvW$--Fh-)Ke!#se1A3?wZ1Q5`mp88S;s9K&111`iX)KE$`7 z6&5}@>1-QVKdWPr9*pTxq2^!cLWFCM!J5pEg(9(BS8=$nmH;NDI*rxmDto>bW-oaB zXUS4Bio^#0UBl+a)%DKSKtRKtni|Mw-SXn6_o3MacI>F$izPuZf_ zSJtA2(rWI#M>QwIML~f5ZL$HWBKmS!(0U#8e_Ltvv}Wd$sYL5%{uyChesAc?pzk! z1xOL~=0ctb`B!>vyYdwHf<}yyW$PfGdEy!oaDYb_|26T_N0tYDI%pD$Xu;sfZO z)4mEl?jGyRD93PkgNQ(Zs(!HMdQLfe^i!YxQQVv<|Iu8Q3c+wL_X%a}=jFupzLkHA zS=GjK_0_knCwp`fU0knS?1Y&N%^-7GV!icg2OMS|l&wk9?gTaCGLr?&KxQ&1g>}$zbh40BR85u&ruD+Ufr#|*r5_5a(6iFh zm2clplYcOWfM<$_0%}(=krgOkMSxJR1-?Ad0<}1 zm5P*j=t)U{d&o=h*n=~#AYkzCxe+D#jghThtMep}f%!V2vbx^_r<)h&!i)7P%ikqP zLHM-)?=ZVR^EH&5o`uCBMwH*PANCkEcfSk7#K&uF7h>2|04P^~PHO}57pz#IA;A;~ z!O>b^s?T3X)VgH$c`$dRKEEw&H#(@{Y?^L9@3UPf}0yMag!q>H@D^WEd$T?HlbUJWpI>CHJC;Y zn>Ao5$K$t)>wKI7QJL!?j&YI^I&f(qr{#T}=AK}uUDH#NLD}6a!v*t`%|+HRkRQj9 zUC-D|d1G@cPKE?#35|8@GHY(EG)^J|Fgyqek#!sgV_UkpD8mqb~ZANE&@~&@|^GA zLw-^ZE4Cm3&NT24L9`oWO*weLAf~qrDPHi9z%}zfp1I%yEOI0b93|l4g~v}zOL3#| z#d7OKld zE)U1OK9Z-*5v33yiSTj>vy=tXLyfb?*)K0PB zu)gZB-#UpA_Ia94~NySvJciT!?!y_}CzBFS#I z<=cxH^kwMY&0Ui-Iq}>QwmN%yx_nj1e}dV$aUEkwvVdg$Q-~|ZLa?PxM4r<&FY(0Y zTYQCKYK*8=Mkkm3ElrdbLEhL&Ua|TTlHzHDW@a8DI{nSE4J!zXN|!9#TjFGPRV~IP z`Vah@Q0Jo_S&-y|CyiQ_--qzc;Be*^1x~PVsPacMK(!WXA3#YOt~qR4Ys+-%%5E}e z0bBZm7^YG|v~vlR0$L$+{=yV^Uygz;G#;qjFj(WjF#>`D=H5wIf*JGyVvq;cVpz6= zr<8(Xqv62v-@ySD0@T?5^>$z?z@WDSvjNTC+J2-$#H}0c)bc~*jnll$&-ykDlo*;j z=j-k-nXK0d1>v=|O7!zjsyg6_cRs*G+~;nfUhjc9&N}6^5}Zu1pQW%Pfk-h#)R94A zRSYcf@>YPhYnb+budXVu-ci{e1pl2+Hk||SyB6pg0m~^gmoeZVO<(YMS-?$)OWFnn zDTnKKn@PqmbFrb*I7n|;u>N{fig)Hc_Cbyyw8WGATJOsrN#A`(Bp{hFFM;^`>!tg7 zmoBgPKV77+3OmyWH-xb7q}5`XupjI7705mdg%Jf3yBuJU10@&J;{d znrtH*@9yuMWA^2-+ctc$Pe@Bh*n^c70%cK=VT#n+M=GKZR7JUrlG!rs#5$?Df>VMW ziSOh~T7Hn60{Z|5r&L>IVuzq^Q`aCrvlGViBq^RFs#rEkTXCFg7$dTCDrtv0xqr zKjhX$X7t0gSijZ$UG)GSFcyzkMvReX;D|(zN7hA7!$DlyI{#o-PKK=46ZgqGk6zx> zsY|*?Qj1k1IE_<5nups+s31WV;v!|8tQw?TLReEts${FpPJWjtA(V2O6X!vjiBRnu z%N~JGtNT@7iu?LbPV5GmUs+g8i2_CJsY+iBrdUuk+qf3Cr6ZDYNEV>J1i^EiJjUq3T>(`y8C(|?Ev5I-NbltVT@{%iV-}SXVvw0j@z}yX!z;juX&%RfFZ)bBg zpUU4&6)5;Nr`oKImS|44iQ&*6>|UQ!2{mc8d@Og~G-w(1q+v7jn#`v^#oyPr97Q6y zrlgVgr;pMS#yK`0-J);)yM{Xyr{v#XcsTaNU2d*cesu50isF+6Qg`pRRgk1+xE*&9 zY|%v>0Rn5zJGsty+yzlbx_wvrUD3HMBHRhvZxyPv=bD2o9CCkryBt;lx(u=h_oVE3N0!I%VflaB(zb7acDBeiw?PqwcEj zWN;kmCj5c%y&A&>!o*`FBtjvp`1|*7?S656*=1^7J-u&$NPY%vjwG~gf2QOIXo3d1 zBg|aU`2-ji|9i=M)18vz=GeVem$nK`1edv-(9CD4;sS9YtjpFp-tg*5v_aE5cEHBz z8lJ)jH>UOR@?x1dj>2|8?tL@2c|D8Pwpr|qg`<`W0g-6#wo;5w6fOq{WmnhBA8TqT z?F3U_>gwv|nh2r+Ua6XA&FqIn^dKC{K7#33kai?^pn|_ID2;`nf6g6mNRYIjB)@U< za+gN|c`M1(+AedKVT`E5^y9Ck-6X3-K@yrD$yFWso;xmb+Q|dpMqW{I17Bs%eEs_ftZ|-Bc-=&R)#hgl)>5Bz@;Q$5Wvilkm+vIQC4%mN42g^j; zoCrl1a+;3^SCn#l(tBa|G8c5OZ>LU|3MMAC}9M3LAQ{a)$zBqxc};ke^%N>yi55O zg@3I&BGfU)rMJrdh1<)2{@3p&?j?y><2g9cM|l)VC`YVay^)jgSN-J)nj>^6OS-;k z`+4`qHSITU)5bBPsp&xio#{LB`aI2H-^`LlPpDN57Q7P0c&peuxGel;^@WR`fT%9w z9{^vT?brx#z|9`K0S{573A9yeBCN+qU^qhL78Zt?-MJGLSpfxTKt&mX7bOA#o^Tul zFy%2?2d4HGfnjo&hDOQA$iNz&UZl0ER9%Irtsp%!^J`#a7jI|A`0%-feFn{Qo?v>% zuoTKopTVcfYA%!nb|lb8tE(OLT&RxU!5Cbr1rTKtfl~%hd+4TUsEuf)zgP3|V`W$v zE(mERRSCb~4w{~orJF$mP^sC2jP*KQ*Z$ZZUIeSU;oT1|rnJN%xh>{5wKIyIrJr!)PS?wq@77UB-?r-(%6Lr#JxI=k5@? zMCVd6S-+JT=zaC)gKf6gKRy#RlPvwS4829zTge`pI+*UmQuPhpD&%8*zHM^RN4Ge3 z^;1z4i;m)_ExGLdSLJ6{EYFIh+3C-&2o4TT`ube)NgOlqASpjU(KG#wOV&HK>+2i8 zMEsm{`Whg#%NYZpzgI+3LSl(g_BxiLga)ANSo>LNOpn5mz_8)Fhrf6`QRtk?F>E{D zKpXXHuS`T)jq?sX8Sg(Dzi@c-3tDqOrl2MH!X=6$oZt7)=IMToKu4#bzaE_ZyP)mb z&R6cRjRA*NcY7kI>^AtcJ}kbP)uA*T@)IRsZnOkWXZ|LqqKpR;{BwKl5VBL=W`;EKg0L*Ok`=e5osx2WNOmUw2; zAK`Z1tKchO^_%(1vm+HLf^n-r|KGP0gYXj27~dH*4}b^b_c508SG*>oXUdEU z%YM26)2{OGlIfY5SLYP4I@O=8{`fH!3}}#5(q4#w%4EtgRStE12D|iEuR8wx5sZn7 zQ!!0mo5A)H6j+%=R)kdvI!sUS%zM9|H80Q zb+eg0Pt0e?XW8qIWJOQ~ZqVb?rZkI7hzhs$iqcfUffjllrVJ(j8DixfWApvE_2TrmQaYJ>>V_+pjg$jeiASM@5Q3Xi#u3qg!z{h??Po(8Y8NnN98Z1<9_< zmWg0+DW4*NBGYcI*|+zm$4srHJ*U0zfj7X{g;F*BFF^=ml6B_aT8wDAqT;%SlOM{_ z$!R3}yZ24-vo2)4HWDb*!cZb22>@Dm{c(ee+A73B+U7PkH~9u+L3E6a%>CF214obM zM67Ta5=D~SD$@1RAN4SS6JKEG_$<-Nw}7qtb%rZrMQadc++wo_Gltl1-;6mjzQIZx zVjefBpg8u$~L+I9HUu_*WT(+)&_g5`ohOP4d^2->pQ0_S8Yx47EU*V?H9VQTan>dh^ z6Z7<=AHJb14l-8EW6J&adMo7ggV*VD7iFX;`_|L%*?Lj8ZkRk{^E;TXJuAC{u#2?w zDd{pL;9&oVM=_sKT;5U?(fB;@=vNvd&w%OZO2{^9qKve6FPY6+Xt8@;MAE+O+0-h1 zv)_*=vw;Xr-4|&xdvAo0Z#H+sgaedc}*HxuPB!S3G}t{DNyh=A<8i z=%s{y7;%)QYd>P{)u!Ld0DRRB{+*}C;I&Om-zKx zLR8cjV{OTQ`9-r53gEu%+0UPx&f5JTt)48=c4(w#n8NrZQ*p{XiM8&ik)+K)!?57v zm>fx)#CN-Z0L4^S9aL20qe_#}NyTi@7e!BDgHoIW@Ln!>HNiPkh|UWO3zLWgAAahu zU%xZhrgy?)REnqdq70 zQ0J|8B6KYEYAU1P2KxYPLa@wWSII6ju@a+Wb+1t>_*5APd5N)R#%5$ zkYDkE>~fe0Nsl>+vJGCBZDk25=lV&&Gg%5dU8d{mWA7&p&hWUWWtg1O=}4U)?oWyE z>vC%H=F}lyNkRNfO60lobj|xn&GY?FO@E;TYWCzgUBjxn(!|Ag=3_qx6pc(d8#Z0j z^3B?%E1Njle9dbcYRscMY?_u`MuyC7e}%BqJ1(B~N317PT&1>itQuL0j?7JI-N}CJ zcVVRzb#>!dR8M|QE%fyhF4mmjzfUXfQB9@`PwmM4P$CKW>l@iwvl#kazb){5x@+Xf ze{F@Dl!N~M@$8qa_vMyk@BBE8vZ^s(l$XnH%?qyMp9a*QLnqpu*>kcz(d_DLoDO$Q zMn@+pNf19VIdd5Z^$37BvzlrQTeLIM^Jj-lY{&Xt=PT}J!1%0!ns7M7XLv{;myHM zrA~mBg13}gS>kpf+?p~)i-^NQYTRCewq8T$2NNc;t8KYJXZTQ2 zp^T__vT6CDrlu&{n^*1;c&9OhpT2|ifMVD2vO>TH6`)yBJPWnioep{fj0T*p*+-i9 zqU#^#a+c3l-;$l+V~xRSmzk%;bgj9-ux+pFT#y3c)k1g@FVA4SJeVdwNVI^Q;Nt8| z01h%ZR#Y+nnwrukCML%G2u3crQ-LHUjxf~Fh`1Eeocm5W-$^`0^jZ6HWBF@-&evhd z=%ml|{W%P}{p~i0=nf&%e=?$Scdd=BDN^L0-+djW6|A0414vE|H9vU8?ltUxEI<4E z4(N=V+|P5`u#BA>lxjAfTb)siDJ+H|Jm(L}LP#Da_t(e0`Zg5wk<$I?$Sf8jbWTSP zx9HxO)5GsGw>tO6E#qchD|Pi+ZC~UT)#SYjhgIV1$W&dx7t)af2 zUJ)N#Z2Q$H;X-x-41^A@BcOW27zPLL?j;fwTcK z5ds047X+i&Io+yKNvm6H+=$u|fWI){lZh9?i;A?lLtlY)GI9;w+^Tu4%96&>idUh% zU6SFpy~Jl;zD^AnRe}|BrbkylOPPMBj7qLvlo>udm~HwKChRvq^yTMXnJ_YvG$gRw zu+*NzVG`?;`;U-whrza=3Rma$6iCIQ6LN3|*7@1m*`JZ$KOp*X_A+Nt$Ld0hsP&3N zH4)+kVx#HgOYQQCRdc`61r}{lK(znjlLfc5MjC=5aMk13lIXScH>K6b4VX=Ym-{W6 zWywsCz1d4Txkdh0AL%ns{1chWw3o6`zvJsy_yLD6WcDee)cNu4)!)9Cq}*nRZ9K?X z>dB@z@#|dxrpL-Pq2W3N#U({~imA?1E}8wtoL|TbP`0c=A$0rJzYJ2IqapP?Bqbxp7%}Q(b#nbbXmO|p zzaJt-6oVonfpTMKEnRho?mv1qE2H00!MELhZp^EfZ&&XMpKrfW`&Ntr%jC zZ__cNtl@c+LZRfkfZag1%8wTWv1{Roj;j(R{%N~c9ZC*(MAj~kV|qJX=l8OR=i?ng z@{^9=m5c|F1#27#Z~E{JLcT1KFTlrXO}%Y-R3t)jCpl`l0ul6LF5#`B$OS|XI(MxO ziB{K6@@xrzO&m?m*T>ayzPI^8YaoZjZdezQm-1KM=|q1YZ#+%&9?5B7YkrKN&85wC zbfUPx;xN4UbEHR%Z9l*L`afn|M2Pj_trE@_a zh5gDl`UR2D+xM}vZq@F89h_6xyfAOjs64cZ&AjjG`dsO-h3t|~b}=Bf1-m>_#-=nC z&{{ZlF_agTg6!64WfEtON+k;J)Bt;X_LLwpnD46jzEmB&yeV77n;w3pMRq(xjY55I z;!U{8xLn7I{yRx3$tWt_F8gW8bUM zoY9Nv(H;4ZEz&UVDOjw$v?oK<8SoE57#7wgA8jn+V`KA71dAG}V??2T#t>#$C^Diz z!1pN-Pwx{{-WW4I~! zUm$nJg_J~J4^uI_0o;tT^>3%A@(J|!@i6M#6c!Wz)iaf_aaj_k6gGOzFqi_&6N~D0gA| z#wb%eD85Z>t0$&sirDg>qTg>jHhf_vn#ZmbhFAJ-NbSn~)>aoaFnb<&*zP1MFZD`O z@kLqU$7Jz=;w(R`pZ}cPac`V4eourtjg9LvviP=_n8*87qU+Mx>+CX%hSwW z49tFCu@gKS5=!#qboW2uL&|I^unqaVHL{GiFuW2pK0+ol45fAV2(=>~!Pf;-b}#6GEsFB|SMD#4@WS{5H*zrT?B)vEwq{n5q8hH07N)Phn5@ z+(I|dr7YGeY*HW3S}UWa$N$x#wY_Qko7-WDffBPX&`EC7qzW}QH|%5<6+4)bGo+#Qq^9?wXNel*|iYb|f9|1kdBCW%t@7^>m{C(i4S&(sT-1I~_ zd@V8glb=Ef^WQxpgt_aLs(3r4t6cu(qo1qIQ4X?kZ3QVPJ5^V=N?(&2gtg0i+?6bc z44Pk`wNcMKg`feJ z{hB`Ttd}W&oxdOwK0Ez93_x@L8oAvh(tiIDaUzkM9LGKgVB*W!F*4G4+=}u(%9yWb zb*N14D_&DN(UJZ!w1zho_}axv-t#y@__5dA$?kCg>zb1?A{|{(rw26ebF{&}U5@MTTB;8AUW zh!-5~1LhBVc%Jg{@x4Df@&TMK74{KzjHVv@8%KjyO~nMQDRR|kuQqc=t5Bly$7QVxYe47vYbalY9TkwS@~u37jjr*6rU zAs#?^%aAR*y7A67zb+A#Si+NT4WH$hXgeE4nQmVR&wkZB#B@z%z}c}x%_9Jc)7wG$ zA&lWX(EfOGvR3wGLwnB_IzB$Y&S2Dhr2PfswJcDeu!3Nog9|$hcG`ui&|3rFiLt_s zxmvN}14H%{xhJd&%Sb|8btSj?2|&+6yS}Ppsh|JUAW>NFtcXI)Hw+k@M8oSBga_p%wT|)dF+V7j?+uSEs6ddN%;P zg{#}ao{_`QyWX9)Nrag3p6@*uz@2zemEoXuuiL>rkU>w;L7}yh<$<3xJ}Udql}jrK zyFJk)1h?nQBuYbiu99#90gn8;2paXFN}Lp|5k@J51|qI){!l3E1y)uK){lpme+)>~ z_D;vzL&k5TT!==|shW=u%AWYsD$@jfUQW=g+L8N}r%)mj&O@K& zP&|JjbxLC4KiF0DmuoJjn7H{GvCxLnzHr@Y{`QlmlbNURnk>~W#G0;QOZ=E18QUj# zesc|F2bjs$g%D z>6qHLgSTp56Thldt+8gW6rMe(o@JuUfzp-_nXg->Rm(#h)u4ZD56N))9B6I6(jmWj2|W|jC0*A#YIKUoPZ;rf5CW$r8L+l zaprzH9U+%0e<6S<{9`u5uCsXl;215Y;b&zVfQ2GS)6GHPZO7BqpgK$~V^zH$F8+ji0V*G|S$3 zh<)R||j^n(i)1N-G_o}b=z+bPd{$9TorC0 zneSF0Z%nJ+*%2efGctKL{gbe^mr5x*P}lc{NB3)umrt`GEA{;;Cby@DLF4mqYTGyR z_U8v1+Ds6cI;vF}+z2LG+)apLF2wmEQk02m4(4qlv`?q%3{8$qu`#hH6(%hi%34j7 z3>*{@zhsSO=d#cWiXV+=J-p?eU0mhj{oEqvp4_DSwYmt|L`}6R`UTGcFLIovIw4#Y zWssF|1z?T;TOAmN*I~w0hmj1%@To@ss~9H&ge^doB3aZQ9v|1hL~}sg>=r?RHx~~w zJfKS@5@KOetArd6pihMvfkr%kik84OdwwNnhwafNqa`ouAe!q~4}n%Go~sw@3q6O) zArOn411h8=0)xC;z}z-wouFBZf&z-L)5jP=Wcc647RcGI?(R-%p*1x%qvq9M;5?mTI4BLsqR0Yl;^n21cxG3ZJ!l6)E zojx3D{#ey1fO|+~NMt6`Nt+r#Ki5j{!gy1+w+g*@1LbhH-i1W!N-w3EYu?9SYTVum zC0G3wR?NvM_&6!l6aV_K>d9}nZ^L-e>*PLBF^}7$s?F#4DxyA={7v>I_U2PbMUU?q zNL?;^hTv3#UprsdD}t#jL&t~lc&;24dQ$NH6wvXik(#c(KYgk|Ql>!IGNETeX!3HL z>K?5w+6gr*b@{zYW;1=Tc!--RxjNgH4uXU{7>8bjCa*>$-2e3={iI~bc8{rU%;3T~ z{uA4SY>ybdK5K7pBD=+#CMG3UaIu1FjM=X6u!Y$o&w9Ule~s#zFQAHV^Ek6`zH+qs z*DAa$_|hYx?>L#B2Swsug!co|d z5guVgs7&PC!FvSz)(%}0snY58d#@M~t}j>38~QOf@rXhB-M%AOm`Wq*_=)AY514Fa zsEk`|@iO{Ro}^+ibyL!*p%UqKj7o&nGeM-2D;eVsIcZ2$qZjXk)#XL1Hk}Ye*e3QZ zM4jnzizZH{JlBcP@4hppQ*~=9EyxtX*>K~JGqt*XGZFSNx#8XHwG&{U{sVY6EZ9D* zd4MiuC`gOBw*FdKAuQ3sG@VjVV0y0L+So3uuM!QH2{97)0iWMGHpMHJ6fx;U~nMz%Z08wqC*2QFGE zu^tlc?ZteLQq4L2qSR#-xQb2CwGsT_q1&10)9weBo19dLkPldfua-5;p5=1f!?zs9 z_G7aSz|xfIS+GP-JWq@`usPUZ`17NIjBIl%?A4to^LhAeo$dcfeyw1~#OZTI#wnVb zKYbowwoiGQ6kir6RcbjBk(})-rgwFjJL{n>U!9%|ZZo0GGKz1Z@dlaj5$CWV-o?U9 zdF!mz0mJBZsn!AH2HzgNo(GA@r7!FDe6{Jx`Tm=9=4kuiqBKeUF{-*fWEpf2~Ls z2iY?)5F+yErrGwz*)AajDSgBx#rf&&GCj)x0*P&8U!ELqOh<%k0UJfP={J3CLA2L* z5^o$})`{=FgS&Y6^wdw_z&fU-LI7la7jPd#bej(WN%CUgPl4Y6vh+6$EF^oR}I&7?|p)+%~03S!Lp<{fANauUk zX%`IU>9yE)+Lotj)1+2kI8NZNHnZ=4CBzDx>)cAjw{=80L%PL;C>$}Sj1y+$ohWI9 zYN!t;O>30*(UhM+$)v9f037^Kg)E&cb_B8t4< zQ!|b{_{w_Fob6Aw{IB);(NsWYj5566Kh4Nl4$I+6!}ruwWKPh%+o15+i84(~Dn}B9=&izBqe@*yl#}NmatI%W zsv)dcuRYeanfOh*K3&ViviUW7)@3G?xK1wm%a@)mNe!~rweJjw@CVk;iRRcZNY^X! z!;5`vKA)vNiWB3@R2(4UL`_Ex{@bW^GS zfVJ|YHKujVnn)^X<52Q6<>N4(E3rJn`@U0WARYZNtOg*Ec51&l{A-9`ARg}JHqH4W zBK|Q>V+qerj)R2MIgcr|B|zhueY8=^%1~dpRrHFcwZ5&K;M;Mt%l6@E-Uh#9pp2cf zHE8~SIS>9pWAm;Cjjm64-$!_Ug3%|wZ_zYcEV_jyU!AQaC(nw$YHi!v#`>-L!Ti5{uC>fW|$t9U( z5Mn|2d-&x$bt0W8lnn|h%ZVy+7bLV%aDg6cggzct@J>`az%I_Nu6BR^{3$gNs)mFW z;JvRG+2D>Q&RIl)hr2SzGXO<4F24DGL8edSk}h+&ovBc)4IDt5=xu0#lOJ3_>p1fp#_v}AQ@wZ=cRAl}WPB;*))pDSs^g zH@d&2`XEt#+|E=r|3g4@)`G9$g=zAxhdVY$MI{Yq!70o-pEwdZC`B-;lX$TULC^iL z3`lz9Bq_?M`Q|GJ&)$vwh1>5GurZI_TW1y}>fEP-zZBPNx_h8X#Jg#0FiGXPZ}p#& z$m+D1rEoAtk3FT}^;Ru;RS@*5y+-7%5DU8Vpk%*^IlJMAjzr^k@Xwz@g?zUviY0H- zx394f&@4y>?gaSlD+Z(lJ<%y{KiY?=aQjo-)hI75-34@#Hi9h=GVS*4z99fu8D^aS-U%{lR$jJsCjOg_1dF# zj!slEx_Gg@y0kFaZ_!*CH)Bfpxlg@Xn~xIKH)SyO>W5xJc_{b$x6``~DuGPT0nQMt zo#`Zuv;YT%(CJ&*qnSa)Kj_^lj$_S;Kyc#)a6y?_Eg8;XiC|C*fpuI;QE{-EHv=Zh z!=^#MSqBX2)lz!wLM4AB8fy)ABn#pqU|jC6`@pO_Vn!}ds5MEiJF4ly8DgcD>}w2R zJ{Iq;FQat?d*el_<4c>>8RJF768iiTBE%)XGcukN<)VemJ``Q8S^vuK-{rLs&7inf zZ1B+*Oy#e+@mGIDiS!QzXYUigp663Mkz=i(+itpyt^6ZC&v>R_wV{;{idIn-I>@fT&O+I$OsWMoy`C=O7MNM<6$dUlgOnnb@VM4 zt#S#+ldPt0&(dN%ZD1;z%e-Err=!i=-`){#KgG%`$$j{w0CQd9iN3A8K%Y&Wt8-zp zkL%|KrB0fWhvvn}c^o9La;JyCO->Z*MfW^Bx{C4%bDg$DF#v@C%<6sf7bqK9k|2ps zgQ*V2CAYxBLd@+4hZJ&^U%?;?r2PoAyoJLddI^JM`2VK^!kt5%G+t^5){QZ#v8S|y z7T%UWa=8Alxy*(2n!y0w9?gLQ90MP#T#4uXpg9tbN^>L>0bkxLL101IAyy^{EPE#` z48`{1HP#T|gH(btL|huAmzNi={5Lft!v;rnKo*8?2=77!o!2E~@z}lM)+OKq_vM5M z1*-#a9%mNes1Wm3ihOANa+$U#%G7G)O+~W0OfQkHJ+)H~mx;YRUFTCXK|uTHS%Q}> z4@W;jy=J!^<*Fla;}wyOE`hSu`6zX>+IwS*%Zg`*f8h46QoFcota z{&3lnK>nBpsD|zv$~$IxiAEF^4v6*-p`spb*M}F}i>ZWFuLb<}c|GsY{13T1W6!T{ zb(mcDU_pJJA;BKwNSVm2c1gZOoteWTFvWG+Ba*O1T#V9&(w0-Qx-&X+{+HK0 zXH};~-#!#%YX~In?0hZykw#&uO`U|uo{Q#rs7{{7AG0H|=Bh!zrEl-&Blq)U{oG%2 zKA)g#xCw$*Q=-ZMzuz?z^TYe*Nvzaiaq0^pl?zYR4Ks-2rW zT<5yRA8DKTnX^WKZD~_?l1?C>D}tM+GgX2&wPzNjiuz9@OFQzf{=6u-FQOaCJ-`s^ ziAkmJ%+ABvF4w1m$H$HDxx2pxtOpN~w1q2niLO%b7e~&$%5cNwmXRn0`z+nMZB7XJ z@9+Uh)Q?VL*V{=5rZ<@RT$UO4P1f+4^W4JW@f}@ ze?K@wqSWa->O)Vrb7^`OjT{tciWG$7LwS`1V;YQti53txjI3Qx`F*g?_%j{uvPCSW zW{69M+cJ-+DQ%X^{YjRVJ-TBYYr7G_ZB4EQ17UfakwRC#G+G{dyC@TzFNl@Ig8yO#a2DVS(7vK`;XL= zB5{q#9|mRDO4A@ZzFvjI)znx8tt1u071OC*z)sp4#h)~OFitOPT*4W_t`0v3F`-;RqJuM# zV-D{z_)mi2o(jERAB~I5h31fpo$Uvc&G)cV9v9(=jn&US|i$0uDRO9ZzQ< zcMkRvoCz2nL`dNSp_B;_!q;gG0eVCqhHaO_I`V&X%yQ%!T3~XvCj7} z6;iZ^zDIKc-vf|35(#p_aqQPx;?0Gvk$M|6^uOs&gQ^9I`nqBKd7n4|W87ZrbT?%P@ z4I1oK1OtKBpGj${D7`!EohSRQpT4n3+YEju?du!BEVmzvc+q%fWqO&Y6uf$)Q=I=< zm`nJNJgH;ZR&e04gvDRJz>v?~ya&(P64l90^soos6jF49(>_!YRq_3D~*;^ReCQ|WP+5OE9SI7)=r9$uFqN# zL;j05f*1*@xjIV3X+D{6$BQFg(Wo$YKEqtMwdF)R1M{aPz+-nqDLqMbsAF8IQ$oBw z#gNn^*MIi5j)2&->$DrfkoHFZDECN#-(;Ph5q-jf%%w;!P?6-+*I(W6$(quSt|HP< z2k{)NEu<#OaCt$fE)Lgml@mzZRlM|~H`xviTw{BI2%osL%Ootq|6_}pQ|S@+|MY>z zX+Glgf|S9P{wxNf()SR&n+g(c(4n0pKnCoUSc*>9afW~c`A(e+rt|JdwGfE##5z$F zCZZ7YLR-U1ga8MNi-!jd?mIYbU<;^T-29;y0(s5=o!+ZU6FLPv=^__f=no`sh9|4| zbe%e$VI>ENj7@Y#0oA&6uPq=u3#yn!u39s_gQh{+B)zC`D_xlyC3RywuEMwJPf5J) zkhIp0=k;WBNsdZX$FHx^ri3K~$#k&?{+s#tukoZR&VT(O+|}lq*17Gb=4&(K=oaCC zL&8kouU=0N`-_YPJ$Ayo8rg)s-$3nZO#OP_MnRYu4u)#T*p6h{qnfcSQ^!FKCi@Bl7Lpm`H9CJOvL9|qdiGlTdv~M zm1b39u3;T=2Le2j)~t8FUcxfxnPI>&dY?+uC)l}RcpsFkEo zk51TIUswFoIQd{XKRK&ha8j%<*;dI?C#vtEvKp(Ov3f8mSYK!8Al3@n~iu4c~09^3{!t zg<{kahlZ)mib&e(vuu1Uq+{&CfMqwL0GuHhcA;}IeI71VK**utrT*?XeCe&CoffnK zZFB;uC!s*J4{jm@q#O?mYpjm`U9@;oUURcz46C_N=uPJs9E<}+ZAYsm7*k_r)$|O9 zCD@w{#47P*hHBbG1PhYA0Sgb7iEX{=zEvt>MTmQ%MWON<7Lxy@G5>{eQ~_{P=k`su z4!}lT@E1b^7odzUU)tevrg1U4Yir_S@yVtj!Y2hUCbVZWFU=t3IMtJ#7`Z8SIM9}_84Vird&!>>!@+!Fx^7x^^xH#IhH*` zN>=x<@5Md$D%(SrQV8(8bG;+dX@UxM1H`oqc%#2Rr~?n;z)m?~OEh^gk!tPYI<*HU&RhEmOLyE+X%> zdtCuVEI`VnKE#2gZ6?y+Bf6l~C@CZ3Fqh*?#6wp}fd7t=qwg8tmn^E)9+dHYOd6(r zw`9t~mCEawSG3Wc=vt_T$C>Jrt(M>?@Ocf2_~DOY$!7PfhR$PsfcaJ*g+4K)7mW+9Y-Km%${N= zz$JzV!Q8Z^Q!PmFw6%0bF~)t$>voeaW?KqKxr$-aY^x(_H~dikf#2}yt4SluKLxO@?SxUO2eT?`WGc!;KOGyq$=#q7!0IKHSuFeNy&>G;w@YUfq z2<01wghT|Q#JEhyMr%;<%&!6Z$k`LL6X3{^&opM)T7BYqaW_#+kP%-H2Nh}w;96%O zhZgc?aNEe0hF@I#g=nvS2z=B~gVtJ1=AY4k+ z#JCx|RCr5fF%fpe!1NjW$;7Q+ia#WZR)}fTnd_XF+XF1(sL&m>->dceqHh~nJZeRD zjiJW|1AG~>j)Tr~vigv;U2BlPm7F|;ZgUqzK666^EEy#rQT+Ap`n2h6l6d?o^v}ZE zNsL%8lBxC?2wU0TXFl#+=2#%{@#X>PP5V%QInb zcQFfcn&S3O-_J)z|5mb3SF%7AXLTPi;-=)pzPv`#Xqgs~8iA})Ed7)gT0Hd?ehEfS zh)5U38-hfEL@SMs$gx{YxY|A=^d;u^os{P~vemj|Ud`ofUx>LAtpbmT?JP@@b@aq) z1|csch+`-;#@d8FcA5>!u;#mHsb@R{ z1!(V{KiLsyN7;dza-Qs|G@8;{=hQtu$RfT_ThX2!Crxin>s^DV(i}DYftvhQ#AiRk zv3ubhv7FC?#>sSO-zJ9JM2IAkz&GgdHdOA->pSM2orcsr)&d7PBkz0fW+mLVxq+by zgGTJQ-wa*3QnF~`ia)ZinzYc&Iy&C+f=I-s|MKj7y70dog--j_=V5eEHEC(#yHZF^ zO+_^hb!i*Suhhg*7!z8ixJZ`Vp?EZ_ulQC=UFfc1(1n2g*kDMqHai z@NMzUVHoX@0c*N^7ALqTy@XMN&6=o98U>QK!7R`62XCj#sw0=n=2tN z4|<1i65xF)v*;mWkq$UmH7+i2VL|Ro#@lf?VGy@ZDby?L$ot6#OMkcyudL67sM%#3 zZKYMZTi+^zykbG`BPJMdvStZ`*$sP~KR8}Y5XwIQ19ZsrBnk}+W3r*3qoZ?j5wM{E zU5?AWdzb8t`vwN80a^w<$NirsEq2s}q5KS^=-Q2%RZLa%0_BeV@$!3QRb&{c|M091`dMtN&nb)*sROE4Xro z^}RxhY8)Pu?gqj%)^ztG zxh{${Oj$_RmzXh*;}#Qp)NT{TEcH|4R2Y(0tdE#hrCW$DkEzko-q2Q=+T_!0huV|;wEkq7!h+Uq#$@j>#Y?;8YhryELqb0;~(wAi)@bMM+b62PW zNlGaJlIDPbtp5UvqdW3TN=lw;<3e9>S_N?KX*tLIFDLm) zL?#x(I<#=d5qJ(JeW-)NwR`+m){DZC&-d;{_O(bt91W4bWPPvc+wq)tou*)*f(}rb z<*)nxI@Z@C!sFFrqdw)u=7kp|19QlnmlLk#z$<+rG?(e^NLRINlS@Ednpz$|d~WQF zRwW*PT|du6nVVJ_t^eibJV{wHdSx-CXDLNv*3s1XtvbbO$ct#Y&T5)5bMXipW!G9Q z1OC5}>)%jG6XNS5QD|l(dcGI3`1$3BdSc6T72zic4GW)>^5)hf(dnBL*#!|^^oh3yDe49fb! zgV9H^O2jr_ zhx32T{#LQVceyul>KJNaD@HX|txt_dO7gyJ)#QR%(~p)q;=vQ~5-xHyz`kqXpzF+N z6A^&KFi7w*gVKRpml!@XJK(hdHGvDVQVaS0+wE(^LqTBjilMC!9!4h@muNU=MGDKF zE|Zl=C|=f@AUB&>#(68?gZyfZ!sdrYrddnvG?Y7p@dr}Dtf$+qku?#V{Pp^aejY>bUwJlP&N=2V#~Y^J->NiYlg_v z7%=dGxEeB*mDGS=fwTq4AOdNBXD9P7r)W{vX(=YU9O$b|Crrz9oZYAN7nWoK^|seQ z?OMaiBh@N#j%W4mH13_L`a5rKnCB}Gix<7Wse^ND2fgnNS>mH4%eHkF?5(Cpr0HH- zl3k-HGoPS@Ld)B!si}^K-I@wJ*@HdGnsB`Hz0; z84UD{=-dUhqw5x$j0NFsBz4ZYLyu*_>+w#;bF2Pf)S>A)-fK@k??N{F8Q*Vf z7Vq{iYr4%Xgsxo<=2oUnO5LHJQu5HoLbmsS zs&Mtl%I?T$c7J3#(+ko7zP6|D@5l`v+yqrLyvH!e{p|ve&xi8sAe08qHa3rc<2C#P z9YZ$xHy=`8PAWpzWX-5{~Rhb8I0%;!|o7S z#}bQ2>^`WQQ#@Pql3B|n$FB0Kk>B#*dl4j;cKsKs^v}(Itv5{-As&{keE*Y`3me%u zMCq^CQi%6o8mr`qMt=xOPh}CrZLVBO97rw?I?t`SX zzy8fn8C>*-F^cUkT&8)shDrGozJmcHTDLenOfj9(cVkw_xLizvqLQts|w2sezoiLij`};9k};72I^dsXaLqu z*5&>Ra)jstL(QV+@bixZ3Lk-!H)1O1ul>A}l*MN`;XPTZ*^2ThU~ni3SiO<`wGmR#z77pRpW&nQy9ofHe&ppxlHA0z;Kyf1@v4Td zE9*XXk~A8PQ?ns54a0M&}7gD@YZ+l-aR5gcr$;27F`8uQsH<2FP0(Y z+6KmVP)R#NhZHUs>wkjOXFU$!5YbbP1l%^ZPl=fT37{LO`9W2;l9H10KuKyR4rGGJ zUm*3b$zq5r@RTrX?we~W!mqJ2U9ka02=-YnKk%Lvq@Ahv&2RHIbgmPm;n6@%Y_~Gp z-|0Prx;bWR>uN#}cDcVkHS(smuKeTQukM)vM=QQrEj@N3 z&Rabg6#3UQvS#n>NwPTF$Tx;)e@2)?=>FtbF^7uF?D{Z)cqd1a`q0GLp*v!o@Y+36 zEUOq9hwSlIi+e!Cht26M3CBaOD;0c0n=eTo?r?6kZ=Mm*oWvU?UxCYKctMo2oREL_ z0`=Rnw%3ZMq@{QF_$C`|gk=^4PENNlyvHZ}P*b$N66d#gak_RKq&0Qs6a6}F8FX?~ zzs7Wh?aFKTyrWsqGr5Ns%-;Le8Xfm+WkPJwsEF^WmISZA)}JgLfejh`OPl?_rJvmY zycFE^`Wpq~H zfCro^3Cmz=PiPp&W>#abhhGEx9dH47t9_9`vO;=L9)x%R7m7PT!^4TPq=WG1sWRb) zb39RQ4kHq1Fn8pH$3|dydd2(!mQir02622;l$Qtc!D#1f1WL^Z|1c9h?ybH#Z=@Xh z%E6RTv@`Llwh^sEVF=A8cJ z=n_M}Mwfkf8-ZQB7WQyEW8z|8uMxrY{MNDlr{5dY3uz9GG=V3%!mn*se%Kn>KD~_a zZfE&kc?@MlQ&4|B-`C&YDk4A;HRf%^&4FiES9reNx8GOAc9J?Ym*eU(B}8h?ilh~I zcH1+SAR!|Ko#~ZU$&MBlUC_iRQ7t%OvR=sD=2ftz3{4}A&!t_^d%maKD+W{`@IEgQ zB$qJOMM7Fn0g=KBH>`Un$?wH_^-{V3)kByS;W|$4gI5joc9B*vyV(9)tJaOgLGj>vfVhuoq8xybfKVSzEc4v)weJ7uBOlSc z92{}k^=~Q8CUIjB`bKUHMgloon8kn)k&@~RC&6I^e}8|=(0HNnQ^24VhfRTC1Fo{v ztSo!*Yn3)Pv*W%47!CFX<1*u^?Jo8~@RogoH37#V(Oo6kmy7$)q-qNSA}~aKhmh?y z5!h}Bv`lRK zbEv;a(MV?&CbN~h96}TK>kejK=jt-ovELsyTnFf~C+i(G+X~Qj+=qK~16M}Ke!FCh zYE-YtjO3GliBy#E~Ti4};CVB&X4CXl12_@hAzh0Q1_(*Aa z{Fn0jQkRt}1)7$?A%0a_NhZv(9M8>EQ-D>MqYU%7tnJ2x1(x_770d)$X}t=uNBQrs z6kM-ZJ3tvAN$K`=wA`F66n~bCDgW&*W#jCXSk>Xp3i&H0Voz(j>RG*4pBl@Ab>58K z%n$r@Kjc`0)8(3CD%Im{-@Gsi>jVE@m z{)MhDq#soH z=&*1ns`t=IJ2=HZO2V_A$&Z=2Sn^C_C%(hgjEDJp@X~9lG5esmLV|U!*Cy*+?`T5G z%mxl^Se=`jQ$(Hl!_-d4qiF~)7@9n`enH5$^Ydw**ZQFPAQ29PR zmL^lwB(uHxuO=uV3Ee!gRRsK6=v!~g`O3Sw(|E+3gqX#~4biGjq-A#P$@fHC9?N{@ zq5ig^PH&D(xGI~RXo$WT`;d2=hehCy`=nm7&;muuCl+hx%Ter-yAEB&_@NVb_stRJ z;kO2gWM~;~sZRC<%|0gM-PfDz8?i_Z0v?0rM`aNG)Ji4Hx?W1(^EfEsOCmm_ia;3x{m$R>9D%N5Q zsTAt<)`tViq@nq0`G%SEb3%bcHUpj$n{=g#Q5*Dp1hkqb9X9qAP9=fvRm{H}T0Mmr zC9$J}mm|60D}Arl?CUk?k%B&oui%Bz-LZftj!WhG_3K}=2mAUAVdxg^9QyW657d@% z-32(g8ZJ?Y)a|T0iyjAo5nMdu#cq|rVa*5<>2fDIyus=!|Ps(t^ce8ObcLmMSyjzug*1;BEQWAT8)X7TZ|0Wt<*X$_gaHn zp8yH&TDo(eJYDE;ZXI$?6B>fHN`ZJ0LGN!Xan5Dxi8O7xt6lkpSPslh$Fj?|lMJN_ zHm0Uhgz3Yo6d&*qfJN&+dGg_Ili%UGbn{`qIJlKU$;BPGsjeXeLI?|29pVj4zQ?fp zo#|wr_Br5xp$Zuhr_moM_vX4~LTJfn_#KK4gPmI74PW$KfXl$ z+R(7Hyhe0%O~l)eJ>|kXiZ)LUwR1t&=2D2e>VC-L#oi&Nzx$%yi!hakX3YAg;JG(X zRmv`%`@~t085X^CuK$*Z{GHbIyM)KQ4kB;;DW)G$*&Gjv)KPCJ@1i^tjAsA5x+nXLwU~BdG36V?3XGiSRC{^ms z?AkMV;iiN6Z_s{O5x)R;gGj!w1y3OI5e$zoRf7Ex3_Zp0 zqT)n!aK1q0@fITd0Hw>A9F|DjwfbKc8^wbAxDewXPzUOs9@m#7ew&wa5lrDZ(G(#7;7!4~g;}tg`$-zp$7uli zj7v?P0=iPEb}^3^Az0@$|Rjjpe%tQcl2VR7kk13W*wX33Rc_ zALv#{FwM5yJ{h~>DQQJFhs~l0`uXsoDl$xzpG%bw5-z~h2`N7u;KiHSYnb@>yIg!w z&T9f{bM|*2Qz~}xSgus`6%=GM=?-jfWqD?9mrBpOo*e!Z`nFEz=AE@ZlHjr56;Hp5#olS6*eJx)5BN%!>Dzf@>unP8m+6s+I^*-7>bN+_ z5Ppb4+k=>->&bUndSsCW2)#XWC#A7fYQnv)3%qmmSHDgZw4B(^zSREk2|3wQ`+SBG zaS5?xn349W=?j?@o!oI z>WJApR+A>UEGBWnd;Gug48$DgZeKj;Z9uFM{1^N(R&nC&G9`64P=oej0JpU!-BqQ7 zfyYf=4!3XLZUj}uZIWDFt~(z!4S79dDiy!ABM2KvCA8k<|5nEQRqZ)(iPTJA#pG$w zt%OJkutYSgkx8KJRq@y)_75#R||1*!4e8Jh~jfA{E^)U28bM)SOE%E1V@)=_ij(9c7iv$ z1xpXYco4)5f$0)q#mxq?ccuEf17bO(lY@~K&@h^|{Ycb+On?V+*xVBjhZlxL1h5T! z5LH{xr*1(kJ+R2GeELy38jrZO6s+fuXFQ4Vu^c2GQ+6+uont_d95Yo%IdBy!IZ)?* zKC+32Oy{QiB13o{4Fy8zbM5{bd-q<97Jv?6schga*NvwpT#A?>pL^JR` z$SZj*j3kr6R-VHep3C8WfKm-ZS~CS}1xs9yU29M)82D9e=`}9%{FTD_9)C)_>mPZG zn!Xk-j1~z`(PA(9NYSy@ZM5v%ZP`csMtacEwBNlg+UP*XHuF#9cm0ONzux^*>gJDu z$H?qpS5mB~Rx#B|&{&;}b@BEW>Lyb5)5+N!seg#|JnF^H^e}?58yEzqi;1~2e9X(- zPeqz`1{L+<{IOKW-ZqRm{{h|PrF-|dxXo-8H-nuzGFM_V`uK&gVx`M=yO z8axocaCx=uKtV3oz*Ss-0|cad4a&cuh~nBW=oW;`McMAo^vQfml77koP{XvrZ#KtW zehhNJlfTnx$+Ryl1Fq)rw^an}33gr$qrrp9El0<2WJ@H2;IK3cc$aWXAP5hhY_$^K zz;!=t)0YCoK!GqbGXvkTEd;{Zz<4g;SOvg%5C?R;)o_r2Ty@!})VPEx2T4?lXt~gZ z0TP+TR12?qvIm=m$EY!ER5GTPYiI>4A4L(z+ws0`$njqSjUY6pMkl-y{UM>GiYHfD zN>N}s52}T<{qs0)vVxLqqKItzPacF-m!}Kx0kt^Y3@&HNx%p(n{p?(Pf)4xB&!3SN zduLfO6#*v;{K>w#yze-SSBosMOSRr3rR@m)!8DnZx641Wp1hNgC~cmY=M!Dc14&OIaqrmmMRaw zf7qTq`-2GBuCbgu3#dIu{?xBS)Z6KN@k5UC!oraH`dJlyd4$L{%j-gWlU$O?(LeU~ zkS3vlXMd%)mK2W(81H>STDAT-m1kjGy)%0>ZVnNOzegeanjC{#Ra;HC()b)Ll(YpW zaAam6T|E&an$uIkKsUUBWKPm5fR){a)q+C|1X0@HO5=WAX8R^&f8FQXCqBNr%NvUWoj1Ia%ipfc0Z zM(g0^z>j5RWxc}XD#|2aFNFTgi3!Vy;F4Tn>)b2@st@jF!~f6a+=FtsR|Z|@|7XpQ zhRu_U3s*ng8N-5W1lAGYFZ6)nJYl;4oW#&f`SLN_)!1Ml7|AldaCwk#QAzW-JiUbk zzeW7(V4r#(cos)xd>2F^aBoXu8J6z<>6fnIkMw}PF!q+x$toL7{F=7)$Aek&>r8{* zI4qk5c-fha;3cQ7(CLXM8pRw?k3eShSnIq?_8VRB|_XNidlyvZS68-^_32&WaL28PGwuVsZkZaNX(dbZX~-Bm@S zZorn4cU4|>>&UwC_iICGn}E{Q-}l-9XrX;A|Byy7cC(cf|C`B^o$X(2CK2VaR4w-_ zEidIFg%CxEF|wPNLx%TKP4JY`Tf8q|D`kim_E6NFiLo!@TL?54s%p* zz>~4^BzpY||I=TB0#3DB?U|h@%O9GGr;<%u&)K<1=JA{I3kmM_HHAu@5F2NCv$jX~jEgntTT?71m9%`B< zfi>_Ph;dLeZfF%dr6zh1A1#`QhRigL5c>snuos93R7XdKTz-?0uTi5wH#JIwFPGDk zNf#x;T|J!+a(r(z3i~uXIigy+=R%z;IBRGP$ec{*dTe-QZ*pObQrDIyjcjP*D3Sox zjm(2SWHhtpYJ=PA4Y1FEzX>RK2#uqL12dvVu%IofsA#Zs?InCj0O#Z4!X6FE``jIZnehDv^P31PKqc!Lq|I3$uZdoMRL8)&%X$dUiL9G#035Y z`+;u&9y9AXfpDkNzO;|aC#_Bgoy~r^Pmva4UmJ|PPGRLL{t>XH3f=3K2DSsap)ey`qG9&IG z-e61dp3`7h$GT`3f<5tqAuTGErieOhou816s{gHCI>!RdUTyL-l{@5yzlaPGB2n_w zbqj9>&uAv@9$z+zC9LmgNyAW{^jn(am=*jYidpgr;l=jFO>)ByS_O_r(arx7st85@JvHNDPS(IN?F3<$lA&2JQ+1qcH4%_MvL4iWplKCZ*gdwLger z;?*qbWYIb~M1dCVRsP;^k!s3ON=X((XsI?Yqv%J8{eA^Te39y7m)NT@3nqL`tScKr zGEj#`cFz`gxz~dU36E$JjCG9KVu#Q=IE;~6Pt!;Z?l|8^j~H=EN`WVBT8b3GZ6cRo z48S3A&f}%HjNfE!9N`K2wc2;Rd}E46IS zx;yb{?6xILbgOOD8`*krt#UgMp+9 zoISvn{Ptn|e0(W7?Xp!RvQEZD3xdJl;_aQ`3nm@|pFoc! z;RBN6-IEc;lMzU26uR)m?#eO;4L`=f@5k5u9~&=DnGi9Ke#9t*{j@>m*f+YW2r3)z zj|QLA2LqVgj(+-ku(BA@3p2&<^;h`QS3DUhF=F!BLg81S_^B|$*BF4Rcizs={!Yeu zpnNFEdO=C;)tZPEWzF zNMoX*paxAf%7=742of$s)WukvZhj)@4=2~kUx}hQ6o#IwH)7l6sZWLTdM-zl@}B7gEN@Ga z%}lBme11ywGWaHZlQWRd7DkDFH!jYnq~yN@+%tD}HXvKAZOVhDL#p zrTJj|03OwFK@f_GL`;Ex$w#9NW12z{gr!}0^fHF)Q$YT}?%6#=|#2tsjH|!_RkI?dt9( z@f^6p3nAyxGZzo_ISM-tm$MCSTlnxa+72i{d3Cp1Jaar4rjfYd&@21@P2*-q3v*Vj zk=K5|57ri7e~vrG|JT}5&8>$IgLG+4O%iUqLttUPkrEY6@HLjB#i7~?b`UaKOEgI4 z1q`O|H40VeRI|E0S=aw&?B1$*0^y|)8m^u)sT~RpwM@}Y5J+r+K*AMc!qoG`!|06q z{zar{i^e!Tou23`L@B}5c|>Ul(i4&2=51{Il&o+RX~Bp=eZ{$M{OHvWaCdMkkk|%N zdM$u(Bd~Lgh`Y5n)ZBIi6C(uxlkycRgW`leh7 z9r^X`LKG(VNO01OD=XuA>{FZ9$;locdP!7T_6GCJNCF*%0U7dS0G}swIzVGK4t_=qf!6ovc(y3 ze1DH76QW!j%VYtgaQNCHsyBYsIyPj9l(?GxxiZ}eqIzC*?8EC zTM&Kyx>Rqd_Fnn8i~e_|561vj;jGax8vu<)QN-dxdu~8xfdW@K385K82*5s~!Tpdio-eTBD>nalN`!wx2R?z?(${^s{r7*-O zQFM8}A5XU%Q8biZUj&@gi4$NC+f*9Tp_ce=W!jvlxTdF{+SNGbx)gbs_ zg-@)Q3y$bB6=g~)D*dyy=F_zsfm^}sjYUpkGV2RU{z2ASiM?B4gO*`|$G>NDClyFS zt{G-z1#c|fkI#2NcAPVQ!~a*2;q338``mN)qk}}Iy|m=iW%*4e2(?nAiJc+;aUmn> z0)sk0#&b;{q~?>wg^3W8cd;@&={v!Pu0jgjEaUB`^rI&Z6(bXd!#|v@0;vPGYD-J- z!7)kdebgfe``>MhsU~?t!}OQOe(b)-Pv#gK5HgeQ_yTl>d3Yg`MLL9+VmTz08mMAD zETq2>I28N*q$T{cxTn>Hf$5}a<<)U;8%j70&kd z8mM+%x_1I0ITS-yZqD4LVJ;M}(UBm>(*AcXjel@ydg>;XgtkcKY>~L$rlbC$iOUD% zMcNisUTiS1`+wdsdvKC_*rsxdO(`-Ns*J5v33w>0fhg%uQ-~TPZI@_$c}ZdNXYZR5 z_zaHL1`@$^pr)Z$rzb#ylXVTwW-{nj2#~PpeD+1Bk_<CWNOSHRs9 z9u5E#AaD_0Sj+E^gzI_hp$a!44KYTpvhQUTf>1RzZ?JPf1jO=J3Ktp)WsLoCI2tY zG+Gp=&+B}hhc1TBUGyMXm#0as*-vGfE!g8|O~bo8({uz_Y&l4+S`tyiyG=!5fv<(g zFYaqCa^#sRSX;Q8&}(od67t7uQ&kB?$uk0}6SrU@(pd^}Fn#y$jrAK|pclIis9_2Z zUFSKQ+Y((e0jv4$pDg_kULx+QElhLP-rG{^S?hjog>Yu?_&PS&I==Db#f<0anbh4V z2gOZlSi4B4^);mk&b_NGwd9{GAiXOYaISB zq4PsVZkmrD3z}W~?C5S8T3g~a>+{~B`bPFWHPW`zN)DS<6kZYB|MfIV zI;4dRIV905Aw`&{6TuCrZHUeM%_D7|+dE-^Eof?lP^#qEDSwNF zkSukk<$;>$toncM@QF!FXP(>w4+ho0Mu=LcQEpF&r$?iiWpoeG8$)VUiS6b+m}8sy zZq{iN{L4&}yp=ey?QbS9u5$SHs2ztz@m0}e8-0DU^|dwY!`T3N0Qc;c zq5X?cWauD6e+{HUttAKWdN^u)FA3j%bA}5PXsnPT05(QovU=DwI@z+pc=>DmzmsJ^ zO@bOWAy&1V6kt}){n1FJOJNMtDuWG6wQs?(!KByE3QR%CfiKWZqKXCS>PD8PGn zV)o$r!=AquXZM?z>;kYYY3mYyRx)C6m-!J&E79Pv5x#iq(f7Gwu59m>>wL28Lv_!q zFF;Y%3`*1jEsw1siOzJOs&5Dv5L84;GlH$@e4VkG=GbR0-;C} z!KID~+lQ^4XfaJZCmcU?-ffZ$NB059+%06m6gQ`khaUUn8Vu^w09TJUq^)YjNC% zSiR%csVNgsu^>ap?b%2XBC94bc-X_mUU^&B0ta7EaYWe~UdDCa62P>+?4Br-l^GIk9U;SlFi8B{(l5f7 z)Mrflq~Z}H-nOOW_czl*Md&$; zz#&0dvCkq`5i=ZpxVZ>!~LllQu2MhGBWB5%x8sl&@)M|Ls}XQGOg5o2P$G8D&3 zRKn=zEy}py=L})lX3~=^qeugJlQ)!eiW3!giB*JIx$=3{7_}3$&e#myBBTal2}lc& z^XVq6cT<++8*EA>)N6&}JKIfs2JQ=X0SxtAS%9r{-N%1F_Yy_dvX4_5OWNW6^UT*6 zd*iPxS(zUu3jcEFX>Omz#b#CdN|aE3)+CDop8?OpQhnLn~#dwQ4Wag`nZAHeI{iV&6m6d{ zO|&YLDg~FNdect?C2kfh2%bAT6Q-Bm(^Y{9!2ftxrl$Cam`MBgW_q&dmT9%&wmy0| zV5kMFIkbXW^RPdi`q?i?;^-4I_JGE)67msLZL~ix-7hzSqkC^Iwe5_nMt~oOA9O(o zI?yr4#DHfKg!^&x^Hv9rPONC~B*277EJ3woi-3SL!24N3b=q7|fTc)Y2_I;vK_5Cn z`u7h;hnQWcPoXVhrk&y)4Ke9>X*ei!ts139d7H2(#ZeDWQEeQGRV=j-D_#-d!Wdz0 zIG|9jn$r?oRpJ~ZOMK~RJE|C=LH`loMgZrU$Via@k)vZdJQQ0HXxO~`Y-FPKpw8jv z^Y!v|(c}e+#qIITwezgq!v_a^W?r99F>00c+`?m&jNheJY{Iv~E6jyB&n`U5=3Wc)<<2zqPp(X=-W{may!Ub0K~c*~gZ?_6c=vWZlkDZ$9*_Cu$pjfJd4)wpte>Gj^GN0V8P|lN zLTh@CL9q^wL|5A@wACN)h~nT^ZxCX6)9Xk6#y1e_iO86sr~14hSECahqaNlO$Mm_H zxjKogyslb6`^nH<`mnI6yjVI&K&+-DAE<`ey3_2T7dw-%LGcodtxVB$XkKsu?D+$N z8u-*(R`r0Y%t%XX2PMuv_=M07-tSd5cyLhJ*}>pwhz?+YVd}x=G^`XfA7(Q+czb&T z3<$koL*rA?<~bW;a5c4qT9;zvwY}jI=-knF={yEMBnEk8-T4phJ5WuoN-+bnJa&9w zd=FfMv-irxik=RBp^e&6J!Oyt`vUw?2o?c)QmdShnqK0>3dUUw1vsLx?S_6U7PRF> zKp{{AY{4MC3&U`f5HTj@L+OT}K5+-7H5%-lf!lIH*NTE-@h@fA-@sx|^4_$5?r>WY+2qR- zNI+v|WXzgs^jNHh&EMMq32Eu+mpTIKgC8&zl$&j|J9_Bk4*kzod)zRE;vHuN$t6Ov zZ^w{5ax&IIZ1&mYImm_`>Rz8pm#@jq@2k3XN>V8lEm1ngC8sY`iD#Wrip&jU zk-!#x#rbrnX(?#?>6p$LtH>d5-%ie;stPNv#IMDwwMGXB-22F7qj1eAtX#P9@s)a# zpV)(Otgo7K=KgRBa@jHEt!&}?$Zs8gzMN;;J`!{N@Z>gAUZsErSNx>g4gNiN1pf?Q zo((_Ee!li*51lj<%$lbo#*LtVhMSQrDH8E;?P{RfbwVv;IzrTLPCq8*cOQLQdWsa? z9}3)mZfm{geUksNOX*sDeAyDm;tjT%_9#0OO3i=5Ft`Vw#5QxT-v-V;Fu+%D?lBZm zUxB5t1cY6`G6cXR|J}FWaBFmI@=YMxm$5J9jO0yVapE(doYdmyX({n=>1oRAprI}Q z+It5F2NT8_;QNkFKHK~K*|^^23I;0CkN$nQl_AnTKlkrl@bnET+H z`*(`(8APK{KpgUf6iWtu#NH6AAiWUAiFQU}zD7d5LLwraF%F>^0>m}e@J=%Yob943 zO*B^$^7@hzfFM`}@l5{_Caw7h0IL@BWQgiG+=OR`HwqFWm6C|joD68*0X6ydn-4iQ zh!&Xpglhz%?PxCrFjNf5hydC&o&oc&Spv>gR?k>)5dooU+?# z*?Ia-xeiM7J^t?goApIx^gYf49?aAF8G2UFdskr zw(sVU^X&J251mExJ)|mBUG)H#s-!j~&)1w$jP8lEZnOHGuK?0ndVG}5LGmXF=1426 zG^)=?W|hL2)E;XEm7DWjKlEcnVm(#u6-ePWv%f+^@C1`UB9Yri#h~zC8c)AX}iK*TWq_t6O42?;<~(+#)M;Pw~G-1`5lP1InG zgD??z-b4)7($mw$e!}lG7+9l_|LS-AxCvsW*+LZb^@lNZ&=*@t4mCJ?4{St`D5*?n znF-OMS4^B5iQ+ELnD#3(?wQAO8Y@1N);i?Ub~xh;{~Is`+jS(u^zwhwHT2F3%!XBx9rR*Q~uIyWIQ`LMtcoivl+s-k5^#xmq zj%OZxihV>Vv`1NuUvbF}N5kcR&*x}991PwE4YMa`2AhRe(btsph@{^OJ1l-GU$nR= z!ik^Gd|)b(U%b({q`TcdsDe`3cB-7dPhs>hPua6~=i`UDksWDMj5|9y0ORvx(GGvq z=W#CXzdCI}YI%WA6i0e*RekbRF!i%*BNS@bM>sCCH-eiwvsny@Q%gyuFx!X4&xjSI zdB^*gR^*)c{=r2d&SsJ^N^k;B#aUE+mvN99Rwgo=9&ywPR=@AEVYmD(cYAU4bKC#0 z3#y&}*@N%DDiUcA-p$i!VW^%VnRI*X^gOwYm_2q~#ilb%bN!a4ieuBy${Um%gZmzA zA!3I$1_e{R21q;a01+%xjZu!(lc}reILM5P`dW4E=QrUCE!L9xp4I9p+-9y%9^B(E zg66vM-CKw#F4j*m%rG_*d0|7X3ZdqP?}0H1>!AJOVhb*IpB#0SkpJhPy1h8)65ygh zXp=Vuemkhcx+gCpR(jYqNHi2xoVIf~TV%L3Ksd7FqY%~nN9xFf{}TVt$&2`xeMy01 zJS$Da-C3IWL30MO`~Y^Yf21wTpJLd!k{>+@rt@(7VYKn(ri4TUjF{~6wV>BuUtPtp zAqHjwIyeh`|3PpT@ML<^h6V?Bpm%9}HvrR^#^q-q!u{PO2w_{xF~TYaoIsKcy9+E| zQR1k7cRyFXan^DuU@5uPBp9Dx+VQrtUp{HYz+Okfz(KYW7?Z#oj?_pJv-TKD->q=e z`fG_OD;wdaH0t3H=1XcDsg(LEF=l&p!c-b2`Y#RNQ2VcHTS%=ROuJb;tz``PY`Wgo zv~c5StYnrXLN4!S$oCCKup!{p7a{n9$X#bgcj70^!k;!DHgU=FPp8qk)7{EcF^gUM z6V?oH{ipAQ@C`Pub_cvzmfuycIA>+-Q={$)-<=1!8Va`tlEx*~wNwd$-Gt?1sV=^_2b8zxfi!OUcVKz@6Df(ndS`_)J>G zT(O7{a~6A;;Y3fZdqD~Q7VsdM?3YyNGK*IgikwO%dnXq9^VX1YR0s_cbOiy+#@2+& zM0Bvs!{L>|$cDu{c&tt<1+)QV&`Uh3AuF-m`$dGvvOUeoT0Xjf?eVv>autx5|E_Yb z1JSGHg7#>#mD(RGV=A;*)YPGf*@U|X+$J#|#oMQ7Hyk=__J8pV@1O9*1pbD9i2=eu z?jcE#h(tWe5dm|;ZcXkvaf~ovvyxIM4Ykng#Sn5l97C~F5XfpIit_zCK8#~D#*nEd zUYcmTxRGoq_m2a5pNP-i33oyI)C{m#(C{BDG8qJ7WoyeGz-gLIcxde(B*k@uM8NQg zF61IXP!eEX6fu)@F$ua7*b-4`VhLp(_KbaS`N#}oA%H91xP8i~kU?rKb1mt7r|f+( z24C$sdnUs|lVGwT1C}mZh^2{*E|w7IsoPF#|0jhc{INUiNiUd0suNtsoNiv@6yAo> z_*C5D7npGtZ?&Fo*gjcNfx;XN)M3n===p&AYKIJy`d>zbzxR z75HCt$B5`|+tI#?TkIEa-Hr8~sIZWim6BQ;93B=OsIF!W8OpF{z{L^qNV_70AedI< ziuOvLQ`8-PsCR%6iNOVmRI@|PJ_io{+M6vYoNF-_s-o_%>&ELJy;ZSJJkhqjEuDdg z9g`U?^yCyE02o0=AsH5IRqrzPNj+nxNEAZ_Cl(mLdWlIBW?+RNMl>0|fiU6Ge#Z%~ zkMxcV+XTtK4a$u^7WyGjyQSdvWP|iUUXU}mS{l0i7w9=QJ)K$X3pwaXDIz#X*QQl& zh(o`rdk9Y*XoqIDi4A3NZzYP`K9g+~7J!S%loETYiUvKO?UuR-7^wcAbg2I{k^uiy=U z(x}w5+z@h);JPx0Gu^*}z;Lv&$5zk>58!V#wc8PD*bnTG@rvYtl&($RsUD8a=e-ds zk_^y6ySl{m^EH9bBRa)~pT^!x@o#Dj(f0oqC5ZR@*z4(3{?btEVfkHaXBz&Z{a`Y= zMwefoUJ{{M^bN4#J6tc6v{HZGX%NZSUA@LSZWnMIzp^HUH*pzYfn$nyYekwOh)BgC z;Zh#7_02%}GhP@D$RzE^xw?3o5?_ZQ5 zfn|ix_BGHAuxBx??;09XL5#Us5>EvoHBPXgL!e-mYy%u|0NX;WyQ8Nk^~X691oTC= ze*Av3C1v5N)-Kq69&o%my?%o)5$snV7C^ zOx2Y9MKhzy(HY0BQ{TT!+5P4mI;NnSc&M9T7$^+n6d}n6J=3#)orw3#`@(WB@SB?{ zLvvoTa#7$|U98I*C$PWT@%F0ZO znLUS&Ok7Nu^J#S;Jk9T`ds(P zunn^~Zd&m@5jp^gJWkTEcax6esNs3}pLe$VE&Fs0vdA)x4u<+=1OwH?nd~iY?|>H% zChk}=RrVWf6JEO1$mh?We>ETT(My|#;Q*A!Xe31-1`_NbSiSVx^*<)EB;Ua6t;o35wmKD^G>PdqsTHVs5`vt{P-B{n}?F?L4(n0*oX8m-U2k|V7 zK{(i(=WwpKL)sQS1xy}brMq!)x()JQK+tX!ChPsnAp?`={}hgkSp}fR1cS3EVs%sL zb^CuC3v_k0hLQY|)DnFT>J!M^!FhAq;JzQ}dhcQyF4q z!4QoCZ7Pc>vCcclmuguVwd5Q)n)%u_PRx);Dp<6{&7^|t5tXA3dXl4-X`ieha!Oui z4zzFMb20jgOt&XihFX=gZov=BCDEGu?3tMvEl~O#p`*^nuDUhvl8GeGQ=|ruA>XAe zIF-nG;k;|vy1u)yY>sV7I=|wI!dm#aqIN0a|J}h^BEcpH|*$#QOcHFn`0?Z&(} zw?`~|=0$fGueODMU%{&UDPw;V&RiP?d4w|?VGGZ^cJ3+RjQ8qG@_HN^7H0e4;|G@= zl01vc4QKT8t*2}*yCIIEcg-wHk6Q*1`&Ps6W*5%4F9ljpE9BjdE(eU6M{f6i{sY+O z?PsUv$Di)SsTp*Gw&WTcw#2f5$nw=G6~1o@3-2xccru##be2l2a0{!6_84pp#fTp! zKgr?twWSm{gyeBwOkHLgh_k(dt9~;`Y|sCVM~T(j{KP9tVY^n-^?LMWBCA(Z#xn-% ztZt~^d)vkV(%}^xF%h{@O{n-?( zcX-4kgM6&O@vnMoMbeuVi|_x2wq!ia2rYUvjXs31YDIFnzW+sQk0SohjDaXKu42dG zL*#*g0i%6#l77?_P5!}X2eIP-gUb+j?Etj`{_7&)B9#yz`vlQ|2uFi<326ziQf(+8 zH{tg#w={?iaq+t5b>O4JJF(gRhqi0b!B=G69J-wN}AL||8#Lnh^i)aw?^8=zj%lWC}Cru>~R+VG8iIT&@vWa zuuPcyKHBVaLh{DsLwGKbc^a_O;z!ruz`g_QkwFm#l( za1>3e>~1}E0H3`i6kdc2vSg&Z%^RZzhYsG5*vo>?z zYx&7``hodF**5v1=SJmE){J_!3{?;Io@X~XOgiMgKA7??AHI;;)_?dWly$I)yynx| z)Sa(}ym4{!{WkGdoA2chvLa&i?}qs8WCp~gw)_zp;~`@kS{|x4h()YYJLTVEWXA6N zrm!ybu5Dg_hbQ3Vx@(mLVPb1LG2!;*WHu+P%Vr+i0y}gsIy(9>Fns`$aFj6kGK>0w zN1^R85t9-Q1%))(k>rB~EHB|}O&mHu|FqJNY@#gHarSB^t46X0}Tj?loQRyvSiP!A9xA~|E)$py7I6WRQ zJ2u35a{9Vczj+}mmZ{6Y$S4M?*CADi(JeI-90gavr(e~J6(&}}q|7oAu;sFL{0$5% zNc!vRTZL{eIE50P+L9R77tC4I>9-QU)yTiIwNNw~&d(VqU4bld?%aEU2L=SG54^8< zSeVJ>s>|i}fqB6hbIykr?QFnkfA`=6V~w?+-;ZBP@MMKnCKiE+K^uX#&Z&gJZHbBE zP>;)lWCX3EBpV}G9m59^8*%m&1c}7cgUfr}2?b_?>VW=uZ+7$7<0-(J$B&uk&ahe z9?K-TJO(6`Gk2bBN1+zOJ!%?Dx>aL-=UsuvNSn45g8o&}&iMgKf0< z=H;78yh^%#L=U^FTYirNp>`|tz7n~^BNh|8zb^db*p}pNdlzlav!qLV za*@A7-brttFr(-L$sNA&-sTT2oKm^NS0GVOQpd1!zwN|7;_P9z28AiDdeT31W`&3! z1Z-8{dG7%cmAs!LoVA*8G8R$@Z{ds=|E}}N+m9z6>&wTy6-)hg?X|hSbT+F#hA6gF zCH!w(TAYK?mb9UlS*}K*!wEZmtb^I)N)TWr?Yei`kRQ3IkIzP2(|knPS4G-YiS^v+ zn2ON+DxPTPna4f)FjIUh_;xXw*1awWRq9yUdnP_(Ll^o$d`gT={ANskL=q>P-e1eD zE77ztJbnB=E1KyV)ct%fBO-(VM+Sr`xX0p{WeM4^(VU^Vj$pX`d43xJc9w#O3Wg$( zC!MC*q41npUfx0{N_74(@!OO|dI9^}Wk2cXA`YtJHJFHu&%cwU_|r_RRPjA_d+0#O zZK#11mX_uR+IbL++}J|efBeWohhKtKxd&J?#vi<|{qyY~V^dSgUyn`bZ7iRW@X|)- zk2vCc8^9l7#O0={U@8^teFX#swcfH1m>rWIh@u?#w8dY&RL}2XS z^M;Ye-1E&t$$9N0PAkFG0tofGCI=$gV056@pmTvZZ=3bsXGj5P5V+udE zXOfar?AL$fSdFnPDK7UWAh_skWH!%EFG8p{P1O3&uWjwUW5F?w;|2ps>RRIP^5;K)s--pUEDE}i9XmR+Rxm(;_)`b?HVX?0S;D!}dV8;;Sgk-2 zZ0ex02l#ra;hV;KGQ^xWSsV)&I~=nS(Dm&~`1<)}0b}=H1Zjh&X!ydH*UH^I$6v*~ zc<@DeRE^L#UbO#x)7AD?!>jnB{H-w5CMcptr>nwk`U8e1L3o5#^f}#Si0_YB=`8$& zV}yadNRAK^73Bafd=#uY6jkUM8L45)tArouTnAaMQ3%xI_X4j{Q<*+kKYL~ZH=aSo z1mKz66+WvKu>Co1hP82ZLjxVaB9iXQA8~Yh2(0~Wf?F={b5p{xAG1V<54mH*V^5uf zU{>&2^I4x%HPx0k~3Dw`)&iY~t=<93z&@+DK|EfSKGLKP%i zgs016D`Q7&2&LRL8ZQ27PZU}ey;FaAR&&&+|MU5G)m{gYK<*}%(qW|=rYITFM>Kr8 zifRQyV#FbD6<5VBmI?yGEt=--8+52~Z=DQM@P1eR=b&o;&%pIu-_z+?|2tZm>ha96 z&mOz*3@tT0(?G_Ke|KBo!3o{EN#4>a0u z0-Goc79vApg@{ecgiIfPHC^AjN%q^YaxtV}sVD`K(gGyqJ3eD75{$=o#1V!${5c$U zC1eYMESCP|J&?ASHZ)9#F_6F;D+W<$XhR7UXP`R%P#+IuEBL0xX;w8hu9#5)a)>ho zy_T2#)6W5CfD;j?2|><^O8C4*l^%;~luDM+#_Lsr>Oqqdy+$3TNoJ=)R(}eKDjOQw zTzwVr{Ki@T%}-0#UUu$nAZ6jAf4If)fmZHm?AyTYMxJ zjGj~i0@@I$o*q@SXz(L4pL0&#^#Ov@dKpI^+LnVgNgT{5gu%_^Glas)ftzx*azVN?+L^@#hdZ_8~iNZY@6&3^$W z-MHZa<7PnH^Xbd*3G*j7Yq#UshO$law+S@trF)dcS-MUG4l8y>4cSdg`g@{Q?9#=}t^E}l+N}JI`@LCQ#%FF&h&YQesHjvbk*Ddx&`ud1eq4%qG&ci}#qWzG5?G;5&_bXO zo((Y|XQi^J5m_2l0L9@kbSwu$$IE->nu_Eyi{9}%h5c*CWdhA|Z!4wq1if`t|kARUgEr{-(JYu}}z>6kE*k_}vFDn@AQsi*6Ewl$>H7+G-3yF*K zz{~|kL+F$Y_)THOalSa)?dt(KT=er6K^PjBPOQ^ky&5cx3rj%(DS+Ry#@Ps5zg}>M z@3nbFFvs0%tW*c>yzn1V8P$%%L5;}AhvyfcEkd4*!l1}d(fJBKTsIY~x`QvOR z1F<6_rY%cljR`fhBE@u}%Z|`6W~c)nDmq3f1dQU&BsRn@ob(hFfHr5vS5WDsoQ#aH zoCpTELw#%Gp&b*`k|f)YlMPhpS@6rxkLV1judwGY_Qj{dyYnws&B4#_YzHLY>KUKy zt6s!VUH6fSkVlYod6%tnoW{@nmOm%nYT46s`QC`T?9#$$fFzqTg@A>)p+}iIt!;5# ze0O1{uqF`vKJc7(y|+AemxHdfxm4i52&u2ZO=#TEQh_bHm~ z_D*XOKgMUT`J$BQZ9x09w}U0`PLkBa5wSpLTABcS0aF4@#fb1e@|WUsJ2vt2=WV;; zNAu$6WRMGp<;cxoML)TSm8~gANS+8^#S=71cOLQ#a^*k@Ikp%tZ+=V508sGE$vW*Vq2xVX~}~ zIs!CFu`@H~-y1zR%06_y=Yz|S$o_U^a_80C)}zI`wGSr*8Kpe&uZp|ENl!7<7^Mb@ z^RP-(S*twvOQ?U$9^KRLF_~9S#Z+i9w-_<;*qKvQR6!^BR>3i~dOC@Ive7YZ2uo{g zC2U0$T<9Jb$IFXHyNj3zK+yDbb_Q8Gp#Ms))aXg>eP?XlOIS=S1YUPZAt4mlr6J9j zER&Eu^K5xM7kzO?&r`Z?g)cB!H4L^089RPNa5+%JDc-1Vi-Kg4R~yV6-(|{6?NLPUXbN9!yn6Sy>#40!LuWwNPbw8^_bjBI>$${76O7?!7z3Xare!G^Y=Qu6 zVEX2c*2UKL#a1UoAf9W{Y77^8C%mMmt!Q#2a=l1Cod3#ift5#a!xvlgt4h{zL-}B@ zpT*f7ubRLgll(hx#V-gic8c}ch_QIRp8up)Bv*PE+R*GIE%$foGT8RSs$b~8OO*~u z9K*VVd%g31z()B|$)zt|h{QSO;%K=&(}G)kEqTcowck|8 z)gr=sG4`Q@CR;eUys$c3r)&NFil6|YHhN_-Z^gCc1ANuv+je8!WFRp+JuNMwZrqmb zheFAdj_i?bZ{y134*ipzY~qV^K&Xy>>3^!{$%8s7r_*1mU-8yDLNc#d>tid<&BTv? zR}_|%8WY^MR&Ft((i%-+%jAx;N#=~CP-KC{V^z%qtTer?-j8{XPGI z_vqO06KUFW#=arR4znodx-~``=ue<-?D)tGeM}_H%q82&$w@@VHdvQD=h`t+H!u*O z#`o*&mqfxHnw4w~nkdip@`fhc_|cbJiILPMc1o&7*G*qzq8cww);<2YnII9D$Vq@M z5o=Aa{dl&V9WqNM3&XyTV4C1tD8y zbF%;}*4#HHh2J}W;~R6nG2$o&3<`ITBI2nHSG>r44ftnH+4M>Gl{$r}86T_#-|z^! z#s*jBqJjH5o`wGCScjO^v>X(YUm*3=u00DMSp>}pqk)!+BDJa#lB-L|bCcb49fd=v zZ;78K-4PUgU7>yP!HyTdkEgqc@!Z^BWKlkE)S%>YRt?&4aJs}J{|vosb`N~IBW;5n zec;XWdMpy_@NNC09+p`@S-}r~7!U-5Kdi(uNJ0!^<^*zG9u_5BUBih%;a5~&vJC&U zU7p924=lg_0rB@^pT!;GgtBU>a&{bK0`9{6qsCRNw)m@;ed=r>D!%^D?eS^cUhL5T z3IDXAR97a%PuPD3hq{_HN{KCOLmp3odG>th=TWT1EO6BUdtK1W7Inw1+-9s8M2+m#YMUY(>GH*uQuKvC%sURE6BELPk;9S{x= z;@KU{u?%c~xae+;8%=)J{BGGBpQUxOW1y_NYDbmO`{^9EbP&^3Kd`tW?e&Dhp~9Z4 zr>EtI2gSa|3BJxwH#6tN$cj?#hp9%p(uQ6)gztRnpLuEIpJSPC>t0YQLhI}J>{&WI zj#C~b4-YL9(VYeY1zUkQd_#nB%kvvQpUy%s(p8SIX4jeKbaYxXq8)OBvhb~9Iv{^i z6^@WH%gL7~Y=*XQ;Lwf9VVmXdol%9RY#JSrnYMs7OZ(9Mxd$*mghm6VhHORM`}?(% z0K*3~P&Y)Bp?x6;M7-=l8nsfMnV@vPJ$!B8aV>*b-M)C1RDiO=>nuou{Rl4v-1>@d zzfo2ye1^;IscaN`N5W@LO_eHR8G>r3Y#MAAHs2>Ji<6KQBEJ);E;(NQqLH3~0h7YY!^6N>92)`i7U||(57j36p{KitE0FC)%4aShv%3tXuFPFwkvTYQX%hl-J zob^VUGgAS%$zj_R!^hUv`7&~H=DvW~-T4U_>o%u{+ZNv-kn`YKa~z$S%CBIb`%l<( znD4jCpX~{r_2gd4KIf;TGd~hpIuU0Va7rt(t2GRr6Id{Iv`b*&#bECtYq^jW!j4!* zboR|I%KI;fSGk@u)Y3Xobng;v8w{@z%RTO|H}#1kiXP>WJ$NB){|bR$u10kn=->Z| z_H1PP{N}sMU-5D;BfIxxr^1ABC(J)ERrvn&F4RumoIQPV_Op~TRLgK_fGgzuYM|Mb z+|&KG1@+l|qN6XLFJt=R7#ljB5H>?uv}Clr5gO!)35H)YXZDLf=AORK_4RXi7n1Zl za(_4F()ouvhK5o?WNfD@gJ(l7H3$c9_S@V~ZvtjH{?2#dur7AEf3(TKFO1x1%HHd= z(NDm!aCV*+s&k@?X8j%@M?`s+)?lU{;!GbFci#$!f+uQceaFII-;d=3s{m>Y;hv|% zh7By4k&?oc$4< zrBenhIgvaJ4NHRY$U4=2Ebh#ARhF}}vIDpNN5JJd`bNECgYL31QGin;QNo8}QW^Ox zFI@>Aj*Q>>{aGdYutvzy)N4p)e_LkW7-?%{BFi#8dE3q?#44g9;Cx;GqlpKaT}U5% zetJkml+oSY9rACNBP`4oLJrbp8n`iodJql}C6cC$vHngYsoR4;pO?~#K1xh?3S<5W z3wfB;Ttjes@2hZ39k;f2EC5{U$F@-Lt$J z+3vchj^%dLszbl5R1=f)b&3xWk zP5RBvx-7C?3;zT8d91cW(f)fkF^tuue6gLrDpB{52g*EI)-}w(Tk%@Vo9$wwARy}U zAX;3OCo$}G%B^0@b4d<~ofRgby;Cafsa8zpfPfBu1P>(WpT7&_o=X)JA^pVqK*R9dEbA3c{lz3R`qO0dcpDW zyGHdxf5K%K)9~@#Mf{wurNY{8n5?(xnJ|S2^P=J}k4tvd+b-`-9!^%poi`Y+#e7x& zFfD@)X!+a%A?E3DHYU{L7$Zl;K%RnZ>*>llo1?;xGnlVKHL4K)Hn7A|!;yMGjID6G z$|@HPrijpYo@80<%+wDO3yk*N7eZc~Coia;FMAU4OJJ;s-OL%&K-R_Le$zsxet|2= zvtWcZ6Vp1yP%6$w4JO&Xi=Z zaBe&ICpDw&r-1dpQqaIdI4J~Z#U>_FD60UcF9^p;iboZ6$?&2`^Yn1U%LIX6=&PxX zr)Nq8J`DGt+^-z}E{p_?-&jW>8i%c^6-oADMH!~p2$BEBl`w2`l)k@8y!B!B+?B`Z zsGN1M{Fc^y?^QRL^Te5S#EaG}WITL_L1A@yaSr1!fRYffg*?QW@Ba$B7&ymptkG_g zvok-uJ2ggc-%lF4dB$2-@j@>H^Dn{9+7ZXb=}ODbAPr*+Nid*}rb(F2EfX@o~Cf|X3e!E&d5cHVt~XoG&MHT`z=uA`g{X@w#7UX?=Y{w zs;{(+39}rNb|RYe0|HvdBv#sM7L=tw>>7 z*!P4l0i$;0XpAQS&+S>Ce%{Spp~s>yG^Ol<6pnccXj zjB?;(T8Fxg3_=#zi9T&O4p(C0q>))oST*IVP9ZV$1?E_ygZipgC}}kCUzbxQKcE^T zY4&69=ybRR@$wSK1s__l_=R}NGCLsa@z$A?0kvczd=5Z)=I!O#@XY-_UPBX{dEE!n zZ)ggQ1=ft-{$kfUmJa@<3oowWr?>;s-v&a#K{!!RaP(M@2=l_-4Vs#NCf2bL0>;p! zKq&$3Ib>&ntT7Tg_qrE|b^zW`PypBRzud1;aChp03QhXn=I_s$PRm2t2qSyLZjX&L z>YsX1oSIo0yO66ZU}I?el7I#}c^&NNL*PRNaVVLT%?-fbohwEdJsO2+7APT+`Mi$} zN+3X;242H;1r-VRIn+ZWG@0Ze%I+E|P|vok`Y)%Ihz%Q>KAdPeMEh3MuU~e;5LjGP z#I;;H*LHTm5F54ve*CxJ779tBkcZ?2_{vOjf8d9K5Rh2D^3CX#B2Z$wFhRoZx_*z6 zZ}L$`79p}oBT1##Lm*aI2}$!kvign|jt67SG^QeX2=RuQW{f39Cq0#EIQGU1rZ?<6 ztQi}P#vctvUdXoden<=Wgeoj1_@s?tXwh5iO-6t2A~r(U3*B zMe9Y$?$FaqdK4kb#*r~Ikdw7v)j`Kp!afCb{mg;S&v2RUI{WqgqP$HV}utG>AQW#a51s%$7s>Cd3DA&5g*f2A#pfwHfr$} z5Z?>k{1&hBKy2yS6ePIn>Fb9plG9J$bTW=m`0z3~#W1Xg(5;hX`m3eD^-rpP&gJug zJRhfzB(1aV^Y>Tt_qQHsnnm$6wSL_cG-%gAN}8r1c&~ePOY$}Sq#i6;F;x#=l-=i+kJG+bSxcJ1GGT z<21U)LH=)(FjqhAs!WazRmTgwe}%}$QA-y-+veEUQ#K?pQV>2_)iDzXPwM?{G_#*HJfN>bzeaI{AURcQAXUp`zieI6Q_Ng(-SzbM+)`*RXR2pfq2--tbk#-)vQjfW;?B!;tn$qihHco@YP(rIFmmc{=6IZz3%NAt z9%XKCpC5eK8G71+!(o#-O;t5z<5+JRu}IGD6KF=Oq;SKuKfb)<$F2!+oS6gO@PefD zy3aJ7e8@xpqwtX|KWwX4`@83?+6W;%u`gP|F^c3GOTJnPRegk%k_a3GNvSR2=>b!3 zVnL0uj5qP@X}tRGPuXyQI;-#QaH#K?HQ2dK)sjw|w_;Q@y33j$d?o2W{A=^~2r>Td ziqh+5LWK&Z;D!w@3|@?{QaZA#-(3{fsk=Y8j<{Y=^nN_!D(Q4zCFE&Z0Zs40<~S{u zGHL{yo&-bbow3T738Dx}ls`iBsO@qe=jY#Ewzo*QCIq-2KN2VS~zmUS%&wu3S}^K7Ulmi^h;WQP6J?7EuF?JrE=!1VnN`)&!%S-NcDixwl}eCj=?|XbJ@V zesUH~tXh{OUxWsxf?O^g6#YjO#owI0R7ZjqwY4AdH9f?sg0zTsln^l%tuR~zgTEdd zB7adT&Z%bq@$z56h`!{X(PpDJU3rOQQ;n4??o3Xo<(?Yb*0L zEVCKnJUXnk$g!)xIfp9YgWt~lIyK=(;10F5E)iKAb=vi&HOnR>owp7vbg+lq#9bo! z6L6+`Zz14v>$>G0PHJsmQXNO>H9-#I;N{w;-eH z{{)uLPT-5Qbo1^DWh&#c8@UHdafjb7D3pCN`63T?m8R>HN~B*6sbdV8G!SwqpRbgs zxX;&r_L&;Exlpw1*1lE;%8=_=1{E|SO8nM^j?$toZzJ^r?_g*tB1v8rvyMJXNv34Q z4^fN|A`FypwMaO`&gL4kkDr^}J`t2VPoJ(_pWW(N()m`-5v5dmN7k(-wB%E(r4Kja zto@;R;PmA=OW+CTS2YqPxhIORViYsP5{K#7PWv!Y(DI$ObKl(d*|TpB!fj(4XRbq) z*zqr0SrF*WL43=_-wJu7H+KfRyHy7BboAYYJQso`!a`5^zY7v#eqp-Fv0X!l)560U`oIG$||6(~dJcnTl z=omd=Y@9OiD=sA-5NV9)))_t%<5Sv7_&lbb(bQTi!u8PH5bS6eV>*^v7P1|s<44npc+kx;w8PO%(%uTlQ1}Q) zw*Q7tK;zLu^nhnz_(?eU zS?-!bZc5%Cu6-4IsW`2TJTsygXu~(Iv@{6f(6O49a(8Yo7U~T#DqZo>^>&?{NZ`k3 zB_5_WT_@-H!2~s$HWK|6xHj%w2iWoR4IF^5_o+H%{2ub`$ZvV^G0r>c5uIzd+u3k# zN9N_I7m5+romxyj{JE&=3cKEv%>5 zsB))2WswX5@U*=9`aSQ(s;=AFK^FA2_my%M2^z0!`5iwA2tkW4HhunkgD5Kfj45{hg)(IQ*C64Xs{}EiGBI;aOSxDN93(FStz{to~@K$Fh#;Sg^8w^q+X<#ev^PRgDrh9|BLBWcJ|En`Fxdo z&NL&YnG$hz6Q35cD2WGQ%O@C?_M&{v?y(H2)Xzu#YU%XM8Y-sAOrJnxUkLqU}D1rZ;KY77zim+QV`UNF zc`(%vFf0s$W;-W>Ox5g5Q6zTxo%m8qV!ZeU&TG!+>^oFkSuAS0NG@zt*p(8h$xpc~ z)j##BtHE|g@FYY^>J_5PoWP`YBRey*Kj2qw?z=@-+oS1A^G80-E$UrgUIvmLEz?(Vl?Ia0s*wrFx> zvF?>zz1w?R>C8tfP66>d>pktQhb@GpBSiczozB6$xoYy#LEaZt9}6c4vcBgz{jKl+ zd;H#FA~9QM;D$oW^2<(9FAQFyirj~gffo|!SjW2+XGbck{4XT+IX+2lY+zXJ}2;gJzET*4n{nX-&A zO)d)sOshIc>L`xbr|g&5DqLt)bPI7^Saa;;NE&uC(f0W&gmU-SF!D#SZ^j<}UFCOda=}l|0R|S)_gUSQcDG?!lM5j~%b*Se^?84m z)Y}xdx|f$H_r`H|OLF|MKVgTq`VA{M^+s6<^WfH~H#{u0n8F=E#R6e%rw3V_qBUv) z@7J;v*i;NeG0f6*F6!mp%&(`26@#1ie0aWzP9L|n6TqW7eDEj9_b5)%`thWNQa7@t z)lhHFX}pmQ2C+$%VBvWr+4(tLa<-2y8f1<7{j;bMNm$3|y!JczF%5|WKl^}`T85{H z?FURx`bM>#iV!OFsdRnFacWk`*@@+L_xghGmCoY}h?u=I5T>0Qz;G#37ac;Qcp1%s)>G96cCCuSvTA7)lic*|pNay%iSSs1( z3c{?%vp?NV4Hfb5?H7e)8g_53YS+RUqmIS^m5?4neLQ<2^+vVM7JA951s}6T5({<>Cl24s=*Jcds=IpO%@kXQh>1*DE?qk{AEIi}zE zRJk62SB``4Qqx>WPdJo^k3w@Y(Yo-ZVmhpt`ym#3yD_5V2GMLcd3xYxJN;92ChL0m zzdPYKjX=t@)W+)< zCj1Vbp2K2-AQfhHIo!JSz9$X5N`0XC;%*07S^hW{xyx`XfDSxP>3w7805Y=k{vuiZ zI>nrVhEd5XP8lVtD2^!9EWQKJDNk|mi3%2H}xvU(=?vxO#Dxhk#Sc>e}@L*S&p?YLiH ztL^MG^%1eHtZ@%%pydJHjj#TpS6l7n+?#ewJ$7&2n5=TU@X4{3T^v=2;v~;a?C&h% zTmFYjD;X+~y{Vu)CwG@{z3;NE#l_=4j{|Aij)IkxAN+U{+AJ9NQHH$9cS*M z^tkC&NowVvm_dC1n!R#4rRWJ8pDP*0N9_1f%BWDa5X5^#QBZn>7`}K4!f!)L0xu(1 zrLc^8wUB3Kw_fS-bdEEv4J)npL)yEa*L_-bj6Ff+>7Hz-UH zxJbqomO@E=XJM3uE4XV}9nL|(m~4?UT$1)qF{fupaXDTamed2UY2ryh8W=DTL(Y<@ zAU--$V3oi*vb)l21eF)?S&d_FyM8pV>t4zd5TNM-wJZp`h1LKT`M<{@fB&~E`wrw% z?z3754+w8;UU$h@e%&w3b?Vmb8B6KENFWeR*Dm3Wc3M`)VGaM7ma0{l@lh9LntQH1 zy((L?97Ur7=9D#?OiN||+dU9o9S?9nAhx`bDDo-7Y5f>L#r`9xspc1ZNa&B58Y2ME z9lleqE}Z%xF8Uc-Wh0bDox4kP!^67$I&ts>X{U$YLYVzvTBx9@M`+o&g&B`VyDC!R zQYVgv#gh}*SPw%`h39{9HfEs3uuI?c)4G~hD@QTL#0CEnEl$`FqctkLsbSv+AU^;B zvQknF$7_Z0ra({+-aXp#X?xu2!#@7&T~^JdVs-XQXoET?)~()qt=lZv;ap#W@vK_< zc22`w)qolzK0=K2HOs?CdmVCoVJ{Mh|6SjWCadZqSWxglxBYfG5|oPbn#)j;_r@*+ zf0MMhevZ)o+K_*~fF4@iDAL1@sa-VaLLQ@-Onqn}ZT|}q{iWnwto-S&gsocT@S3kX zGqGs+z*_B;xk4AgE9Cdnt)qn~+q23;E`?JT)Zj^xF*3V^$|%TRk&P?*W;?Yu$!t$s5TJBgX6)VW7{3M_-som4skS$&z7jUfe% zjW^zX*SjbC8b-q3*9xg2qBKG}QE+%E!K`eoOO}M`&l(|l#bSeW&&ihJ!j&a8iFBbQ zGWv09yjw;UgdczQgo=`1k>JbW%}LRqbQjp&hKO3%$|;fp!FJ<|j!mCJ%_{8jF)Nxt z*inv#(wj?awsc-Uup@#UTN8aK3;luL3AZP_j5D&ci(zTDJUQ&x8#lbR#(U+$QwnDw zUAQJRJu{IOkZ z-YfH?8$}cap z0s*B>uuS1GV^(@HOG39%0jF&`hz6j?ttWs@V&{avu(~gx_09&s1?|b;$h%URm_pr6 zCuT69Fge2G7L?JY#z>(5D^MJ;QI0Lpf)y~IwfE6D6c-?2d~0d;xVZge!o92N>_=e7n4C>W14|%L-$!zjX?3a{?j@5I zQi73C=QRKrw~vv>Ul;sYRoI8Tdlh{SvhVpbiv*4pJL|Hln?%;y50bsT`p+lA-^0|1 z5Z|APb68t8?BiLV!4PSGC!*T1>1czPLX`T?0v}y}CGZr%n(}3T!*bl?Rz!UrTgsa8 z`zV?RWX0W4)`zrYIWFZS;>w;c*djF%TA#oDTDkFL|K4uc;Cy&*+(7fq5cZ&y8ifau|<-lC1fsE)Ah>W!Fu@k zpQ1@4Z|G}9W^3#GtBC=MpLARyCR%k$Mm%D#BRT!QVj|t zWw`9m8bK!pU=l_FDy4-d84Pyhy4GS-j<7KU*8rRd0REDaPV9_ld-wZW zX13Pu%Ny^0@X7JLHjS?k&&MGP2zWGR(LdMTZZJ1|0t% zW7tOT^3z#txXC8Bk(37^nq+|txVHdS)&8im7DKs-YCasp^ZJIN|=P;g@I z#qH>s!W`<2}Y23$TU?pxCMdyVy}M64$&qy)Wqe*JhxS zQL+SPln2hvFLrT7kUOKfr#~-6P_W20Uayv3IehFk%&DG~gV=f&BXj)kIi=vn)=kZt zCI9#LbyWvHwGt-& zv?sUV3JfJ_#r|)H9vjW+Bwm!E91G(+{t|e4&i~QGRa0zRGTa7)=PKLUm}t!_t!4}A z{p#2>FW)2fI@h-`D{=kD+R!x;9RVgcL%|;9LFpiy&kXU)*U$dk^v61$ML%xcHS9g2 z!r%0rlJKuxXL#HH_5Pm_C2UA9ZUdDrO8)7~7pK`f_3-m0&DJLl*5~PtjwO|QG`8lY zU!9kyFs$ZN$@WB$_l?BeKScRt73T?qM=ZJ=jf;MnZ7bP6DnN!(Wn|MyC+d&j&2^I+ z6y!K;l94t*jy{2jW8|^zH8J03~2~%h9GU6!^D~3DPCj9z1GC7%sSZt!7 zOTb}>HBV0bJVN<+FyI%60cJu_NGJ+S1*Vl2VHTC|kCE`s=P?7a=CtDV)ZOTu99F8t z2in!im^u0Gnx1EX0R0r?7 zx3<}?YPfxqgB(hJqPxuE+J-pTg-C4|4Rti$r`dt4{!@N_{vSXQB5+X64OUq%=eaVX ztlK;7*rIMKgl`XWb+LDTkE`jl?H!(iS|*|h@oh+6k*x3vMiddN;_jsIYilY*Xtk}U za=TgDn6EfUEEKKSeSc*p?;Ep8J&|XIa-O+@aUv&tDc3K>pVnDtBe`CM`=aD{nRkc3 zaZ`zpcE^-<8Y=U3PI^$rG0!2-Bb`|?l@t0E0_aCQ!QF9_>Kj)#ff|Ac!8`kS)f!uv zdCF>gx;!zY+xM7q(``rhmVuYSj_-nbnMu;sw@c@Y!P7Bj#S{)}zSt!0VC2mUgPRDE zPn~*6&7TTfWdcYW!tj&_sAMsG1tm_>w%$a)ngtZf}k zbyEq2+U*8AYT8>WNVeT8HX)9{XGKUva~9WoC+N1a1?|1cWJjf-b*>o|otRQ`gw_m@ zR{JjPE189^#j!%kkBE>^a7Q|9PELSl1nn&ZUgiXKw2E&J?2Ap~x18eP=`kS*7b zCt;ok&L@Bd;EkR9z{=zJMG6fdvJnY`jgJfjEZO+TR}Z4t-!tJ*7zECU&)kTUuJ2C0MuLTF%R4ZzEkg?Q+Z4VhPPZ}+CNjxc1AtBZ|KHr;#= zuH10&-~5fB8Ig$j~ewljZvw@`w&zygM@rp;S19 z_pdLxM@51d7VrP_BqIPzEdnTm5GdN&YZy3GQd8T5oRxwe(Aa%e<&RWFK`LrTGq>~< zS8D%KNv1n+g#rzJ@??peIO!@h8t`MOn}Y?prZqUratW>Ar1{bV2nd8FJ25y}1Tc9l zZ9YHOjCNo7yd%p!J6;V-p@DA-6DcY!y(UesoM{dHC166o3z*)wtPbiZ2xH@z-h8phl-fw3AEH% zHtirODi%AHGiRttIG|8V+PwbGKbvw3zXyh(rO|e;oq+Of_l#6zq=!_qVB}EZ1$=~( zN6+=$xU+nl91OzL1j0n)s3|EBW=Qs)y`L(_fq}ne{C`O_uFM}D=5WW=4W8z(?B~0$PC;T_ z29ERO5otT#1Ch^;2&wt>6}x1$Z~I5&vMJFz%EOI)Zb#RBedqbQhkdo#A{mupKYn)K zc{^~-zunOwM?@QIwD>X&d|%w>-67N`XV7g~Al~PjG=hp;2F8_uKo$xzZ~f|~j`-g- zg{JDB+N|XNI_-8{>saU3=8bdYG3oZy)lM=jMvINzp%*j+sv-m4bC8yl26P=@QO1SC z06cr5f4-n9Ajs&O`E-0N4{ze6hx1Uee(5nTz6;p-?JTGufr~IWl&a}q+!B=tmo?NTjBw{-vlM{Ewn~c-g(w;6_CgoE)=jfl1BX-Q~!fC3+3@-C#_;x1h-L z93F*H5cs?V*C?0?aN{;`Q)XI8ILZ}A2ZFCYM$Ed=odu>T;8m!{fAFL`cIcBLU?&d% zV9c%B?_0K3Rw?klg-Z>_GTeSIiMznGT-)1*Tbl;{PorUK=P{Wi$b`8k$yfy(^k78* z=1lX6g&2GFa##${fu)l4*5{ItNZx4KS$gL;GHJItB6(3=LnP-~ecM$DWG&^))=({B zB;JnIFNWv-*ehME8>eym7Iw1j9wP>+^W0I~1l1d{<;sh7ZMku+Q?h% zu$}kBv@Wb};ogx#zp`p^wrY37jl10e3sYxVt%`@uxwU@utP1z#5SQcREFnl|6c*X503i-@{GKCtoyq-H!(mcnE~H zx{65&E_KNi9Ai7|=}-CzJj4w;eU#IljVQidHNLSp^` z!;e_sgE!JrwL(C3g>YlU=ce>-hmWK0Ap{}Ra0W4`CJ+xeacJ;pcYbG~>#ZT}8Y*(5 zNM6xze_-KUSq8}=nuKZ+mX!>VA0Y2n29pxWoU6(=)=>n3ZQ(L7z}nToZ}yEBW!qSx zncxU;e9-gZdA#=FLnK}hJZxxGVG}jd*@+Lj9s}%af5Iy|22`I&5E*$)cCaa6qye`u zvt;s&f?1KB^JN4bX&8?eTD}WA{Qq=*T`Ix(lPw>)nu1JA@UP$izZA4V25Ju~)hX0N zaf@em6eLK%41y!EJ-&RPhA)G-9 z|6~cHCqMj1|7UJ_&(t?DWwg{7iY;RU2g0XY$+Swcz6_>Cb}IPNi5HeFWEY!xC#^X` z0YRGll@O#selZ`IM0~#D2R0r*U1kFKePwbhsljI77$)kR9Es0hSgks(b#(@ltd^F) zL?-$+3(e2YIW;<32-dMXpwIpW!(Koa%ytc*n7RtR8(ea(9BF!6)H!k=?C<#{hRB~ht}Q>p}Xeqn%1wR+6D!l{aL_gmn@B| z*eFV%5hcvNY-qt1$@wKB9PcLqJNNbYrN$?Rqu3Ef@1>3iRypk~#8Soe=o&X7ciTXa z00hr=D9?62LtwO(o8*N(a5^T6L4&}HFe-9Ir(XmfoHh8ZK^<-sZ>?@*MEq)|SF}oI zp&(EEsZO-VLO*vHVgKTt6SZx^n)68z@%T?mCA%59iX*js*P3Jko@ouMi(q+v53CPY z(Z%Vq%ukmguVzH@in`OX^sV;dnk`a@6Pns4ZOvOE;c$xeR7LK?c^n+6%~s=r%A!@6 zGo==5I;r^-B#mU|CyM+6Ltew$DQ*rzkU?Ttt!->BbE<*?fJMQN4xTXG?H>Wb#}C4( z>$SHjLG)%8HAdm#uC{6z8SsNZXyzbS^U2hRzAp0avkYHF@-J>kKP3LN0jgsq>wm(| zJHwEj+e1Y76&tVYZil7pk$!ym2oani^^}I(ePYP9|Yo*9@||53RfCp|T=-+3%_T^c z)twSFLE~Vb%@IQh22v22^ubica5YV%BTv8hbMz+9j&feZCygD)_i3WqNf52WV-1g( z0N7{!*-LGEy9@cgZPmlhDQ`m*v-L1YN|U0L!F0P}@B4K;ZMnzTsudQceSOKxZ0b&% zW$+>{es;~hnm7Sp)#~B0l3?M@R^FIqZn;;@glFC}SMlT{rSzj~9yErB1& z`P7P;liBKKPZT18QX!~n&X4lRQT!>%5he3?vp{CeaT)u8mwF$s#pZAu;wsK_{HOYD z8m!94FpvnY>?%~iyEjD%+niQ4eCZ{R#hGbZQGfj~^A7tZGL~=_%5m)_GOD$3+dm}C zf?C*}>$c?fC82FrhkuS&J3?H*c-Hvbkc#kCedxVf<*v@K@r+JUNwiKQvu46H>c#}C zW9%?O7yKjTV?VqrnUow%P)k;HKreG^FViRitq&|SgbazM7L45iyGa2A&!zS!QguQi z3|xfLi3MhYG$GFJ)HC1A$yoJRIQ zU}856?r^)nX%QbWY1C0uLOxYTECfIRi*s@q2?LImu4IS3*9~Ov-(3*wc}67Z<)>~3 zgF_Thi7yj_U+=#jb|w^5#LklH6WTMCideO~64-kq$*2VV&BO?F$`Ul_-4E6ngzuuG z-Yhf(hFYr~d*u7th3Kv@64xf21x`25uYdz|v&+quy@8S!K@9 zi_`r~+mOINZGnXB>JOGZ35`(2=g6sbp3xYx5*p%B+5K7b*=-DbETDMuU1TY9L1waM z;FqUy&cjNUQW{?2w>zD`p{?!KA6$3R9xPqKe9JanCkWMVr3MMBrfbgM?TCXP>NTwy za$>};S*{e&;`x^lE`&d{!NwnvM?ITXSnP?jNGREzkJ(Mqs1tF*Vj|j}2=Fs;geIah zaFrN*W(mc=U{lu&$9xFlN z8e9cL_$4S8l6oxiwV4{j3kwGDl=wKX=ta>*frIS-XI0jZ1{>egYawAo5|E_?33VVV z7ymCqiz($1$bdLq5mLOSX#e@x(g`VrxGg*cm6(h9rC2INe%R$jK++y6Ekd1c`w7jA7?3l;wl-(c_zTOgtd2h-DlHBMLDSR{lcKW>e9DFR}w z;o0^(&V=fEoVNqi+0eab0wHF#4(E3ocCJoV$A?i3cIn#R_8;jpcqV+3)RVJNdCNdX zHLUH%?vfD=SvZkem$f}>LKN0v2g8s zMPftQc&pkNwDqZM{LYGK;ik(iVWbAfRISc6Nh_F0r@~jEu}O8N;tP{zhAJzsWZz4Jj{|Y!fA!*D<8dB)%|z*PbjIb*nOZ=_yH>AxSVoFih+gb$@RGICDh+X=NnB*0 zl2=)e2;A++dLn>|VS)Fo-YAT07cO2bPu02faQofitCo{rGq$g959U00=k~2an^ea7 zYi_oZ|Jnny2U~YO$FqFL3f(+VC8bxcomY1`rpFFXw6Qe$e_xL*+$qwUsj$f+)}hv7 za!ZKEm){$@UG2U?blhL67-MieCp>%jbbI;3ZjZ2M!MPrVi`lfNPo{kgz{>CfI#b;N zoT;*c9D^cw3=C+d6!cQq)T+-(b zEc(^9U-X>9R@v?sA&)n9JsHiPdvlmY`$zLt$=WNXG*ZWtM&Y)5K5LB+oh$q95!4hU z-U`Mb0Tqpkgjc3Sy~U>}a)vBzmke}`nIuRQ`Y+7*K0$IzI=6OYPZXFplenQ=8~O9# zARRz$col(mA~{YH43b@!3oH27x?tocN5C}(IpUn|rC&@aS#1Xf2Ec|5i#oh^Tw6j- zjo5e%E(vqG-jy+wN??!IKM^+AxOk+``h8+7-&xI%olU3IManA%Ui*pP>M84ve#V~p zu>$781N>HqrBur(!8OYgB2xdZL?Dr5w|JIF{I8Y4$w}SpM=c@(2r6ugxahf4`=f5vLc888+@~aQjBfQ7Fww5QaHf=;5#j)B z$e|_@bZD|L3@r}`Jg}!TJH#03Ajhw8VAxTSsGM3A>?S%wI;iRn2x17mltzz(7z`Q9QS<&w!O)FR=7PDW~98M7M%A``n--tt)e2zO$QM!TTo zDMkTR@i$>)fih?H^1io-y9)Y|!yOgX4q>V{vR-`Eb0+&-^y&+RPEt44L7h(H-#tEF z6h6cl(S_&Va&~442X8yz2#&Fy`Xrp;ZX~(Sx8-YVN;ci^PC5R>77N1V-J^Iud~hr;137o4$(BXC2jYt_33F6z)` zdYlmrY{UqJBl&-D4oG*M{QJvq_Xoh{lZDgyTqj=P<_W|iT4mBmMID}Z1vXVNzx-L? zFosL$oNS;18OQANV`e8U@1({~XdEenSj%=GCtfEbzkg%McFJ0~i#HilD|@Fy$ihemCxPtwi_;jz zs2Rn(e&8;F1`M!bz$)%HBEP~;RfWpqDt3?O~5&)@)lDcuDcWhSus0$lOn=g%Sd0BxxDckhw|my3h$|7M#)`y&LS z!=_B(@h>}H-?UgUxS}8mm4r@k&kYyz0doQ54M9wroHueGhE0gOVmn?Wp6h!JEPn35 zUuopW(Q4YW0Hk@q8RcS6v;&R_LrC97vawIzXY3V&h!Mfy3-6h5H$@g`b9pfBMgg6V zvtHH(o;|?}Qqfsnju9z=j%5a3kZjFx>4zYhR1>Q}TB0&qhgs3z4C1|>!$VKndn2uu zTI#|%_?qBINQmu+2ix7iOK{|f?%{-o+xPW#+Dg-yY(ku-$4#;DZH8!Q@xNJxsrDGwYu|)a^I6cIJ-r!FnxRiF@;lW zhK?F|WhqIB$S@8fOK|U3jAP(3-kdP?@>N9lZ+(>Ik5ys1w^2AYznetp?mo38gRc@`jG{_weY%R2)4 zATdJ60h`{ZxgOn|o;7B=IH~wI+n;_hh6+p(q)yyeTsvGGFs=Jg180lSkB*L;~Ys#r{^-X6tn zvSfW*s`vGf3y*PphUS+On=qoQVOr`Y708h0BKYJpulO zF#s-A=%zu4W{rCCLe4-`K_tli2t$a_0;wPTt2#-caE%DT01Fwr@QZ{JKPb1t&DyGAAp;EZ_=u|>x z46~fKu5%?zBZ$hNaO0F}I4m@qCOo}(6#`2JiZO7+L2=^q1R*?zK5a3Lf{r|`CQV;7 zb_b3Z%MQBDmqNL8uNTu`ThKaij3A!8D|taYcTkOwp10Tv6FF`HP%m&_Esjb^giC$^ zL?DC6f)hssq`#{1UD|NukUvDeC8RL>ror3`b8c};u!86tZ%TLK@80U7hP5+^HR$zT zojB4nsaip&$As$=(nW5MNkZ6_agdk1{A^ZQ8tC^2`tyGGcjC}gFM)r>3 zH2FuXDP$r~=xlVtWB9)w$&`hJJv1=!P{k)h9k-Zj1#LU;SgH*5RH3@6FQR{^SSSr4 zm+JcYWyPq_bAzjclp-44OpYLmShy~yP%`jMKI+(_@sbggU+Ohe408m3j}}D4fB>+& zl!7RPl9Sui6zb}cJqN1XU>d}3D+DT|o#vsf978W3f{AWa}vF{=hf3NKNR8r6L z>$4kZc#q~GJkaIDF?6NNMoyeyL+Ta=-i2`H0A>mCH(->20tITwj#HLvP3eL68hfZm zB`k1LNyTA01^SA}G1k!x2(*|=%SMc`igb$?#A5=BtD?T6k_nY_|4RS{j)06)6-HLv z=AoZ>DBKgCd_1N=TmjOfHTqfQ3S4StLm=n9Iv}vQh=Rh8T4j4nTj~0)o)nl^Aq^M6 z@IQyU2cqP1myaPP;%EMId#WZ1O2(^qG?VjB)(Jy|DKs?KBhD}eeas89tVX*g*N zF54{<&KlDsezu6v;hTbbpH~+3{6;$VP>)jh271SFC}Etp{vWx%{o8)pWD7G-rmlOe zD&!LXh%fl3oC_tvHJ@(bL|%ZV_;9Ee88gRyT=CEprL1gLqoS;%tnBv~+b|RHLD|)T zseND8o+2~|g@09v{Z6SP6<&(Dh5ovanh-OBxgmNW10W>k3NLdP@g zi6JKKWv>ez-|K9>|A14GYc&`VpSg#rK%j+RboUTq-*}aPUWN@YCbFHn#Q$OttsvG9 zVoos-Uj(oB0#N%DO8@Rsizzgb2w&|@n}=Z^Yp5hEQ}+{P?#N>qx$x^Te! z5GzJ;w=dy3k`#7T4qeq4|;l-{)aeH0ng_6P2C8z25jG;ZChtAuyJmb9Tr+7LuI3J{RR6fW>j?Y^;SiM>PE{36Cu6pG3p%$uRBqTeSiNJ9> z`E2#uQ!TpdG7xm2ZWLrHpiw@hDq*B$@xAsmcC$e$Pl2(jPlQ~`wDtKG0 zC`<2~R10)4QhIdS4=oj}*)UjZGnd{s^tc#t()v>;inZ0yK9(ahV@aB>VXSkKvRtS( zgoWaAH0O$hK;1Z)A;H_i9)62RC2vZvBR3+Q9v*M-YpIDPT}^>=+<*$03U%S^@bnr% z)?SAyveeIGnwX4!j+``(&00GT(JoYNmxu{Y$0Y);4RIjgRlp_|?*N!{-8fkBeact? z=X9Er5%%)}cocvXm>7hofHPPv!tO*U#fp;Sbhc%wgi?OAlQ7@_eO9LCHyw~c&uCSG zXv^TO2-@?sGR|F@iUO4lkT-6otUB0SbP#i9mJ11k%FC?aXHtiE3l}(v+r;wVHeFG` z2ikdin|ko0V(427F-Vffh-3t_N3x~rqzvf1V1pL9dneLq@iH0p?4G>_sZB1eFm~jw z)T8rYWKp3)EnMj+2p!MpA>46f(D}~H^!9DaNKaaWMJ0%X-ggLF5zAy`ra=h;JqfSX zR z82EKGGn3A1L6{$EN|cBwx#bR62*ScRg8GZNaL<$>zh0v4mC!%;35x%{!g5wR*uy=- z$m-u4A|hSqQ|~t1!Iq_z&Hoku=dYCEQDa~isZZ1tKG6Sx?tqwwD{5wMZXs6SL!&oU zz{#aA55)L;m`Qu&6XNl{;C+$*l(6yeM@#&I%tIC(iy({k z?PTq?D8sE1kGuDYj7Rs=(#=EtFu6KR;R*PnDN&3D|71Zh)^*!IBRy=VOKdrF)%I$i zn7Clf#K6OeFI1T+eA-8?{rc9eZUW-zaY6u(3Fxig9vkHwg4U-F zArW9&GJ*BPqeoLRJTJ%iVLFj!=z$+QHMR5@0RpDoY(vkplfx=r^aikcmJN43@xvNA zcc592FPam0d^QheNpCb3U*q`((D*nczad*msAIXzL!gNT{fCx-#8gS$S-MBW<0Y%$rBcAsAh5K{QQaH)rX)w{7fEE_nA z3SP7@r|Z|PZEoU*Uhu%j$=N%$X4&D)zcprFsz5PZ)*BsS2;z;#x1EGgOZT&# z5hW{~$n7S(j*vOJ*1V2b++x=3d6)==8RNBxAUh;c1-D821HJYK4m3KbH8UD<#BeB-cSoCIj@N!;%ax#?>DOG~=lS=cL64Hox_-5mXA^lktUf9j zQ_V8GB-mr4RPMR=;iY119J!sBZ{CSd5nCY_f%NS;(eYO-DzkDJ)mMz~-pTy@`6WT* z8iG?mS{-4g>yD@OHU>X$#+2yhbl_8>Npsa-Y@7)X<(Tk`#sb2AQn1|Jr^2I(Q2w~h zQCDS4Xjr|SkCzwx<1TG-@2cmQMK$dBRo2eKU-EIpY_dVyr@e)xRKoZu)VhB@Ja|v!x}%}H8vK56UEv09 zSju`HM}htbT=lPCvWz_-HZoDffuM*V1ne0_u&PcJ)Jx+MgR=-nsTKZ}j~;5!5tkhG zK|9IAWBET+>zZnhjsud60pd0@7miC72|kIOE{n+egdw#+hGdrZ$Sb6G0#B~0&UZ6< zTxKvN!9h66^UFe$H|-s32={?rg^T$iIhi|IBD%nYKMGvAIM+K9lQKZozx_|Shv0z2 zs2&Q%=l?B6@Dck0EsnZmVXDMl669+3D>`9MS--w8G_xUSbdfei8f;F@4Z#Y_Z|h2cjF~O>vFG>W5B_z5g!{{cc8Z_(QWxK~9hYN=G!>DE$U+1mUS-`r z#Rp|&6iM+<3B}sncs25$rb9}GDuMS%jChT{^ErIVppLDw4jZnqudtTDJTQ&7x2ukw z*J1TE=*axSh#<`Q&>mxd1=>Yb2$KLpk$F1g^Zb&)(? z`o0r#&vy&2)x4I&w5XG|Wp~yH`*-Bc=yfP;)?SLvwaQcUf% zrPySEDA-P&O^%&eY6M-3@{{!lJsJsw-HP_Zj1tUwdT(8rOQFUm3H`6e({Ot&X3Za6 z66P<0R$pi(g+lnDJsu`7Y@@_Z7}@AoEjs+EVDUN3X+T<${7nRcW2qe@?s<+>3Bvu- zyq3Zk0SJV?>`_=i_AZq|M z!+XyJGAalS{2-b>#rdzw$GWjtX|N4|xttMK$5$Ay$UpwdS^##?RH}J~ypgK;?3XWJ z*4H6|=zGyxOmOBbg9Fco-6}!I74sK678*|ZhCvGq4iA15i@k5=sjyVRx)VOWR#A8f zrvHc1fmZG?lBGs9~nIH0NWRfyW1t)A51*IghPzw4I&bhFDEU4aoDnrlGU-{*Q z^jHt0BDMj|uRAIUo5;@~)_~sn85Sn~e^)nE^wpyr*(d!uKglx@UH zXE_%Wn9nGj=x#+s)z)d9SO3lQ;%oLiQTuQoyK-4qxyK@>^f$8yNOUNxG1bkyjvpBummMN=#yAhN~|8~!-rxz&4p zb4^+bcay(r{+5w`qjm4u^?-l?KR7fB!#eU;MQdb%mN^qwjReM;#`fwRAY3NznV6<5j%kY8UACrCs`g~CBl1upH=H-5mI&7q$ZUciet0t-v&bFm3*g_Hkts@fU*gyPYGRic2p|8s z7V#Iu&W14XftGOKmkm>bsGMB?7868+fGrw~Fw4uFQ)a%f(597x70mw+#{HXv#lt}e zzR@SRx}c_PoOK451)ut(!>v_OQX;zG_9ZlKul@IGpZaxL2dknc`X`)`VnmR81(P1) zZ|f=DEdTNY0o*nJAO1K&bRSYwRMdTY1Z;vqHBBYG4`J|f?me)KL=niFgfvpb!K^fRCny6!^{Ah~?cS9TWozb0 zq`Qvy4bbyk&U1`h%k6w%OlUgfu|-i?A0u()edzH7DGT&ob?g?}IK8A(Z8}`6oRN{+ zP#a-dDNR7F1JguQnnw6O&Cpc{%=#aPh74&4@mK?ocSklG7h1nToYqBi8yjJHrR4Bm z1|g9<{cYHlrtjY}^Hy7l)q)bHIF>6I1Y(1Ol%<=_w>+XdTe)#Yo_n^j>AUg4lNYFV zkAZ1>tJV|rap~1ohI@Yf^@u+T!ND!U@0080cU9_xOrz_bfuXIpC}?bQdfMjk0)OQj zmB~7CdnC$bV!q^B+ArBww(u{mrYR$krQ~9R-75L}cj=zdjwc=I>3r(JmwPSbsAWhA@YQnyU z!BX_r_j+>`>v^$C2Qh;4E2(CbK*l_9BA2vPXN4UtdFsY9QqU%X49{-zFtufeBr8-X z|i8qulfxInfEKyMHc4mCt*o!6c(1)U5Fhu5@z!4^YB%sjy^0%B|nf$D&DDjbfX zUIy+K$g_fG+!QF9AdUgl2wiFVV3QT*)uI$wED4W=M0&v1FK*4q8;vWRF#*palF=#% zroxu9(<9iV!y5I!)LT*vqH*3&0CGei^g9b-AN$?;aM9Dj=XG!LE^kh>p?zc3#^UpT zq&)li%Nf_b17C);LnE$D&X62PAqWph{vvVIC3Xhm2BFHuuhp?tl0x53R@;Zrio*WD43J>l2S6@?fx>;Lx6lJkmd6D8XF4|7{d2cpK@;%T zo9BCLfGgEX;)cBdG$GxDyMww{Y918+bMlkQoxuJ^xD#Wf9v`*(m#Q0(y$B3qU|^uEv@~w`-3caUU7LCL z_;3y0rZ=Vze`b-;tGCBZydynpSZA|)PN90$lFFR?`(ca~UUE?+F;S2+oiZk@`B8!t zszBcF&wYd+-shnAgd<;N$vx2;k7d=F-;qpK4@nK>S9)q|k!W#j2H?9_2)gQG>{~3N*IIp zo^`Ok@$F!xM}dluU#|`Yi7oSvHRDbitw51?7JqTqnf!D}Kt|~ZeB)C2gIM+}W z6pn@TM7e8S?vhC6{vLEwT&c*AcW8FjDnc5H2iE{L#m%T?Cd`7#T$=q~U%PHX+zmSv zZDcFsP!qVe<;*TqH=9sC#wWnFdLZI7J7#Lfr)Bue@~U|}OuraSdNSZbLT=&c&Hti7 zHyVzfbw~TO?q@?6(qfT1mE2AzE?pF!-X{kWYOYV^w%-~!!lG%3noahr(&VHI08SZa3_@F5_mhdDbZ06LCcVZvF^VfBv{VrEed zqbJK6g+%pfRkNUK_j7!|5W$5vmM%&*E#$v@v%lkNuzP z8#`yKhKucmCL6@4x*h4hRK@61mle#piJrmDfNq_T;NbgDPf5m6s{^2S^w$`CkrWllxbY z^p+vKmMzT8JcQW7RPzaP`r1E2s1u^Pu1*~=kUD6~f_0P(BNCDN0|Gg<1Z73zap=)N zja_WV|IFcVB`$}cNpILZx`YS0em;vI-5JA9?rJ3w0uX~;htR#-BU_1^p0)p8z6+P8 z+nIr|DZ*f$w3E05P=Nqp>QE$E_}#tpC4i_<0DTa-*um0>xjWNv4mZDU-vgU2M6}U^ zjPr`c36w;f;{v`nht27F9AONb3Pk&d4=CJ08x9%(9Meh}Sb^dUBBnYBlTDYpS509v zhHEhNHh@p6BNI!?9L=CJg+^Kbl8ML9GPh4ukiEuRoK=X)rfrSEusL#s+5O z4_BOCg}rI5t4o<_@?05NINe-uZvk`3#H8Z#Xv5%hbe@6@^7*QF{%57gKi$;bJ<=Cx z0@xUhW`ymP?Pf_EZQGsPBP0sBl`rVHteJ46##2$e!WRt>A@*KrJN$$q`>w5lpa(vF`^M1dk{`7-I z$5`q%omfFTAG{`>25Jss#m$A*)+^NEcyUk>0wqZBet^#m%@VjPPk@5f!j&mZH#P7c z*6=OB4LwBTz{Ll-eACM56B~cxH(+4~xG_r{&C#1t9gKmQsg$9<=_#N#_|xyVP@&O< zu78lAHW4I#>5e4_qR-0vc>p(`{w5BT?~Kx!$_gXAj%a0`{Y9*?i zjMVqJ!&?H5FCsw;1S8bnB8$I8lXVxdU0$AtzZY6|QJa4M5?)>Zb2I!zAx+_hp1wnh z{RmB>_lrU(#|`Mm*CR&tBR0ZS+nvgmZe=BS!e7y%*NJ z$xdH-i?cQ2(vk=ig|(;4BfZ6$Dm{PUA4|rP4Q5rYQ1OMc`P`nO)9KB#^iZsQS_U_p zHGb38vq=z0!A)gNs*J?N5E#I<0@ypT)WrG4?K(1hr?Y{UBO!&5mGT?i1pf$qK3Lx1X1x+s&0z|y9MKLlK zz&1>#6h1PdrLArS{YJ2MVRprMT_}h!KX@^TMEqY;OY{m|58Zma%!NVO`*El&Ngf4;D3CBIuObAZZ9LC3p$y>CtvTFap6YOIWy+FF$ zDdr3c^;Gpx2&1A>s+p#O#cB5sh>hHZ2`=uA=?d0k({#}HdPLo8?+E`0lLrLvb6lq5 zRZ!9j=TIv|b`*sWplp*kw(EqhEk5Kag4iS}CE^9gr4J(5EuXhoc-@ZAh@e!;B>z-Q z>ix^8=x6xuOor!zay88cIEmRROtn{6@A z&9w6|!$a9F3=B84s{UUQ0Tf}fV?%)t>dV5yjv+{9h9I*IBVBTLPdu9%VIyGT^@4y~ zTQfAK5vI~{tXQWwV9tB&uG?TeMFP9?A4r-0FKSvuxeU4UTV)N10ouFL<8NJATbmYaj3By1^(C4 z%f2EG!nGuL@f9<6>1nO#)Y&O~{BwSXt!OkwVCO=}N_ge{_RtWaTTp8`CQ6czUJfVs z;3n^&yrqzviN&@%D_xdYm6Snl7=_m)F?WjbGOPrh4`2A7Kr`gUPnT1IqHy6$8~O>$ zRabm*#&J}WsDu-z&DlVr8pt$MlHGR9rNTqp4!dH?p6Z-!HMk{ifI`zUye@H8@0Xws;B+R#ydz9agR!jQP$=~$YuW#O6^fa}vg z7ja2^)CK91< zca<%(#S7doU%-88SP6hm7az-EZHXc8e}le_hsSexw4kEI%`M)r5EGsQiXRs2;P!TT z>|nT4lC&l7UyCKi%<(AP{|Vj}v#FlEi9&WfrPBVi&M|%kW0d}1(4Wyi{v0>%=mnzu zln#&&f%G3nFAUu@BQH)Et|Jes61Fp(S&&eMxz4Cb#Iwq7V~R#GndD^_tt@cE@zdMF ztmJpR6otuwzKv5lxxs1X&}W}_4=MKA^nX#a*);$~z+41Z43rf3NU23 za1%_CTgk?nwm-(A;Sz5VCBSaqCfX1rFf6gO3YE|L5hD}v(9n;(h_q*#PcmCQe3ywP zq&EkNP@uU96}u(7bBu$Hi%N;FHvV91ijte3s`QN%8*hO8Pu&0ah{^!#NuNqZK!w=; z>GnTy{>I4ozX0zhUMtObD>M&NWa88xmHWB zqYbOVZEi`K%MvR_)H!1{OE>X+ahrsRcXF_>av}3@R_M41YCWhQwYgn>wN(O&8cei| z*FC}Cqs6gc*2A4qV=9L5RVbsUiH)SE)_dRbaBd78&gJ?%mgEqdUNrprho^+9MZ;omc~icWau@8oi9gI~Yxp)# zeLP;bh;+0L6R}~{@J;nwE#TKDMMKV(>wM$GJxnp&RWh05#SgD*w!%1tAN;F&3-*;0 zj<18h^70wX1Q4OgTlPNnm0%-{3K>hs3liB0tiGFO>SyFd3gReYWF6TQhacgX zcpnKp>fk5SIM~ID=Ttucr>#!~d>`Qxntajunb1cY!O4~>BVGeUc;3Aq2nTFeRr^w1 z&+VtcIn?Ko5fcNdz@)}ymXH6%?UaojCaS^~zg`dApm@9oz+N7V;W(~;t?`bqb{1MKOdoC4^7o{$ z9?Z(eGfA+Q&5wkLo!n^$`Q+_OR=#*Dnfwq%0|}^1)N`aA3K&ubzyL}DbQFi+ z`mpgeVP*MYt0*6>%#mV~6+h+22Pfl#h!i9lC6#}eS8b+h>3(`W06MAvvb>*c$duGB7T#tm+W#L^YDRK z%uRk-cQab2J2pqXVRxFk7lm~1dSI06Hws$uj8^n7tCwWe^gafMVi(HhR6G$*9Tto%D5s|1jgr!C33N< zdEQkNP)S)Q74Tb^UHRHQ+thJKx+Z&&sT$o}k`K>uxi@JBw}r^i(2x~0<)yi7dDfpa zrcj&&vS6-hh(p@@WzhN}P6#?>)wwu>-K8gbo-sZxsJf-1!aV+BD-QNgOxP`G4aWc= zXunqq1e$kqJv58TXclQhev%TX)-V2)YmQ4Y0_-1ZH%DCpAWG zECoP$V#<%Ppx<4|fXpT?WhRxLuq@9HWnLec!s7ERZPAr zzWk!Oih5~b3O50E_mN3cwMnbl=XnSGC}Z{MJq8~HIx;FM-FJJ=KYqSNV^*$s2!U5| z@jy0mv`rtp=BUB$>37mF*X%3mj;fctKVkUl{|JI|>~1^5u>TBJO0XY>SbBO21C
      %2;_Yf)d=HFzUTXK(nDixks z?~KhKot(N}2w1rAMD0)Hy`Si@=#jk!ow*C|J|4X}d$=zYVgav`9Wy2K&QI_@C`3nWR}M%f61Cg20BKSz=|j$ z6q+R%Cho#}bO&yg=LKLcfvd+Rf>4K-1|vLp5~Bh`MF0AMnu6Ohq&ipsp*F(uMg&q}-}1II zUpP{m3y;wed>HJr=IooVget?_pZegk1kn<4j!L(c)3fYqPl-I*ZnQH(1Xm6aKG_Lu zP0{Z4$PPT6U685g<5yj&ZIXW5kAGBg(Y|wmoyZbFpkQl+xe@Eq<+2mzuzq>}%TIvR z+t;sO7e#PGo{F+|hx67h6QZ&?EIByce6D0CUz{-VsfOQoE;9;0iuHD)fhszMb0`6_ zQ;xpc?5FE3DMb*x^J&rUJzm1!EnX(8#-vwcOZVB>wbg|NIs|jC#ISd65}N1kBrg7$ zrX=W*WKwl@EpfeE$f0Js40RoY$DkpD%1)?`1GQowkElbH1I+P#nFDgX#rSE&|h6T$$38w__xiE+7b0yad4gL=@L07zb7 zyceGTfNFvU8>z6*&?j1;(jk7cO}$;pr2E}){NNM5ccbTYonHv7pv?fq1WVqG8s5f^_p#D5$c{ERy=bRd$DRpE#;=g#&lVMAwKF;kvIW>DVSJO0ie5gS@Qn=c0GPIs%_<3dd6~ z8_xk1&BS8Auvw&C$N_5as#djap=&|dP`H249oq$bd7cPtL&T8HNDUL5e<7^ zz!PHTGi?WtBId?m?UjP~O$&TE>Ty3GeLG;eU+w`>2SoaZns_s-Kg4s*JRrXFDL!i; z5(I^xKgaNy)WPr_>1GZVi3Sighf@nF0W*WR_jVlUb)U)qDnq*Awt{d0JE&2Fn`gxU zf#|&c&l`CmGf*s7uAl6|1PL-s^_WtK_lbhU0I)#F0imQ_EN;XHpVR{hp#kb>0|B z-ESY38sD<7p?@&*-tnhb?&(~y38VzZj8Uuo8aw4A4I;O3zQmjLUo_Y+mx{s>1&=ek zhI85=lA!$&&6jCk6M$&0?J-&S3%Y#RZf-+evth=-cgbv|_)^Ia)jw^Y5^txEwwKZw zJFiHPZ<=lCCg_M?)wdPj4QR|HGg}Ue-RL6nD4gfI((=Q4=KH94w)zT04f3nREvseF z_RvA_igUSR#Cs$yy^}KGnnIiA#%_zr(!%hvB1EP+zUXL)tm<{7>1Jjci@Dsh4vx!T zmYMS&1!qA$q!2>USBDEyA9fUOqYT} z1|8c96{~YKgPqr_lntsRCYkOh<6V~RNx_3(-~Z?9fDQ+t238xE*gH66RlYmsn0~=B zV54z>d;LclBsqwypi{#eYAv6F8tFe}QbS52$n+7fpw&_r{>@jLo1ixp zJ8|M0R{@#=3jFS|184WYl!6p(1!pLmA%Rs7SZ84C!FhE132zL0KOd8fsg63A_%BL1 z6^3Y+PKLnfqTlR_%u}N+4jLPYW})G+jDL2>Lgg52uvx30^8Y9nx|KigGg*}b)fupN z@tq$&xHu#OK~foMXt2xeftojh#1K+wm!6&QsO8Ut|9L90L~B0%auER1S%tqt`CS9U zg1;qeK3eI;o3ZL`-;Wz+BDCgyRyNkw?4Q1SK6#7l?zw^Izn7<^^du|#CxvJrIo3Cu z^VNlq-%4L)9(uT%2x&MGhNQb&&GIA2ocfV>e5CvcnLh7Tb^L|s>$N{d=@C_g?6#;B zW8g3&L73ijY(}o zr}K6^oLVGKI|lMY0b`_8CI|Mz{So11;6U%aDAvfZJOU5!XQ7eV*;uDqr{K?`WUrW| zoO%iPM^^qv5r0<3LI5uF8;lhN_4V~ve00^Hg8s&uhW0X@T-MmtaExUf9|4r?RU2Zl z2jA`}5S-1n{$ngm!JGk)EPMn8AV9GMJ;tb-ITOUkI}@1go_9R>IfRSJ<$J;{RRlE2 za5I5sm`QtgoxG3!vHzTbsR!O;uy@h2p6^D1$s*%BEVcPva=y_r4XrrjHQv|Z0aZu1yBkL6nF>(COpQt97EyRM&K;}(B?7! z0-NF{Jvoqe02){hXM;EnkyWmNP)xSVu-hDJjLJd&>BTF4yF`XJOIN|0yW7 z0s22(`>y{th>aas8fI*0uZpC+0diZy&P0Hg;JmHb%5mAjB{93E!<`C#Y6K8;QxD;2 zg1`3{6A%uR|H0syvXIn-5zilA)Ew<-d72&hqmTa``hRVDlPl*N_A1&9!Esebn9Bs4 zP=-o{Dz*P*rk`;9yBhs#zSGH7Nov3IZM$1qjBc!KL=8q!-L=2WlA1JwTx-+DL-W%cL0`{ZH@QWR6%OpS9+VsFJ^b~x^w+O9 zUWezOj}UDT7XJNqI)6y!hjFL94_@ntUJl_}`x zT>0A{<81vJXL_>b@cI*gPN#<|1e48I{o}zl6kGHOU`tlu`4S1sZB6>Hj3nEN=)3L| z3*ETUt7Hp{1_69-VoeHe31VS@uL9JPj-q}IYQ7@oLjAW!j_bdEaf2v`SbZwo!m~)* zioN6TP^{}M_X*6A)mc>AIjPS@#6djB5ue5HTWZN;I_v^DV6ck)^>{n}W~c;alfx>{ z4=xAnt9ydPm&>oi^@eh2?4lhSjM$rBlSeiJvx2(aR z?Xp@hx8+l6T>i`aoyx6G1IEr^TF%I1e0HhGQ5`JKfB(sJdz2NRL$wqPYw<*M-c90& zz;-1}p-a?xuNoccYi@;EhWvAG|Dgj_wCG*(-YPMl*pZ9N^lH_jAydQ5II)-3Pvk-@ zKgaYRHlSnVSiDlH_FJz9o!;BP7fGIY5lvvNCgeb@=xmB=MzCVme?Iub2I z)1qjkG9LWvG=D{f3g4|638FY#w}wOH(Sy{_X&Y?#)LuYhGPlUAV1K_$U7Oujugb@GP4<;Q$jOW6k)crtCk_P_{+TUQ#KCKvSkC z64!6Dsu!tD&MN8M_lBW{w}v}LJRTFL2kn7iw#k|oN;lB*^Yeovw-OZ?_(8wuUAShW6KrcJeGb}G5IlOoHv0tB@6pj^N=ec8p>rhg z{LDW|1QQ$a8piGj1AYDbfq~hYFC~>BjYgjvI#r(Pzl{Jw;oHnie!$20fRCTIe6kwn zF$uX(3u|V#wBb}@Wg+|m1DQ59Hn`O&GHL`r6^10!e*s1^`HZN)3%)bpt^!~j*R2CB zpj!9_C{``1PiPK;urhq+NE9V`<~?z-G$g&L`YpVEInB>>Tt(gxs!h0@qOL7GYS!PF zh{ZMdYCcdmto48T2zn#b_iby6G^YN!RF~#GtYKRUf3go zTmRHwm>|;e)2KDI{rsAp^Tvoh$}hc&IDN9*iiN-p=}4uE+~~b~WB#iMJ&_etuUl3W zOY=9q)a;~bK`Q>I&o}W=NL%5XjU>Hwmc!?_&%+HR7Hu`@LLpi7>gvOARY9L<>(`q^ zrjGQ_SHf!j8oI(ypu^i;!38oQlR1{0@d6rY=#yEO>@|qX-`3g_ei5Zn#+83{S8V)V zNwI&B;4j%OkFqgQJFiWEfdH#6Krc%V*H(!us3Ntv^|`4(A7rO$L+X8lF83Z>|L{bM z{Zcz=on{(=-^NGyz3lCITnYxf6U*}PV`i|DzsT%n;hvNh5$T+FqlKm1v|Jy?rDIq^ zVe(dpTpY|40praofLV7mH1-dMWd)pw5S8Wj`4rbVv0V(;fN>TR?V(`oh2C$Y9s`hC z^?jkctsza|6H>Sf|51vF>Xo8-S5oFq=EHBaSNrbqvyhi2^6+SSt`gwO2h08~kOe)^ zUc&i^tU~>4H#BDS8Ko`tbLMg&>S)iNa^_S{QxC?$$PKco2KOawi)O#)8JR)n>p?94 z)&9ZH&Gfug^(C=0QX=9{gD0G`Ov&uItXA15k~B3H@XiN!w z&L?vvvs>IYDDbqck_uMyUKwLkKp^RP!j1TGmD&dTs^h|^+;hlk?&wk+{$uzPp2$(1 z&GDdPI!(`9Pz1tB8!_O}AtHK+zGs7l9IjC5VE}`ey3X=gl^f3MgI^8r=ND9D@rHXs>z=M#~_e51Hie%5b20gfH(L~R(y{=6a z;W|qY+Gc;d!72mT{^wSNM9H12_Wo^O!>hH`8H>Vb@RZ?pQ%iEEiyR#EEFY@c=iXNZ z+>|3uM2(`qFEQ@2n^;yh2O&u6I!Z)b9!dySKChc~r5PwmgtnNM>1k=;E;HI>HZd`Q zb6NJs+uAym^V&5zB}F4B3C*j#b0ZdF;J?-RL*!ZwR~G|22Y>~BFba|P?%kt_nEkQm z#L?}{fo@KMtLtts6!Y%-9T3DCFd^fYA>xo*_H4J)y@qEsILnS+=64=h)dYhT9hf$O z-jL^t$UVu-l~3Y;lz~rdsoHfSrn>a%Tv-NtCar%=4(k@Xo`OBqfsCi9Ow-%LgIo!h zu!(|Nu4%q5EXk?%(?|1!jX#nGZ}rU0%1GUGY&+rZL z<=c$X9Dly`ef+h;!my5q#a;x>8(s3nxG9qgX21vusp9$YfP;FinrRo=qdBiApNHBu zm#oR2ti8kOd%jNp>WqJ(b7ekS`Yuuh)v?Fg{_bDr1y<|f?gKJXu_p1GNspnnEpRwn zOQ1qtESki&FAYU`!hCH*%8ZCOg)-?RdBF7`Lr+(gC49p8Hfe+{S$lt6;^V4h-#ir; z#(>v>D9%{b!<~~K8w1Xt4)f8YNt_`eqw*6x9fI$71c*CLg*nxWl0Gu`dhi=j3TCRV z{aO9DwtecepYAEq6Jcej`*vJGI1^%l`C~$_K2nH}QYtJ!GyJ{teTq9%t9V*@KuA2^ zMk6U4dWL!yadD1LAE)uYfsb|EX?)G#Pryw#Q3lg@lOOcoPH$j_t&#igZ^xJ6m0yO7 zNpQ9KD%a|1eRH$RhDwpAw`i&WxCgr26%P~@- zq=evvC%+5C{r5TWv}}hC`vh$Uli9dbHv-g z5&7XQ`3a?`mu81?Cp>y&;whj@7n%Qt4e<$0r;Eg`d!suevoB4yEUs^qrsk!(SaBnO zHS7{O9$U)Ri`h@M8n|vGr6$V1_$Q6=)l1t9WjFVwhi~JPGBuq2)C~Gdx#jc7=>`?G zlEF1W|D9Qae5Pq*e5wGA zfyKXZi^o;-Zai87ajVyNc@k+WVuDpt$P4m1@FHjBBl~bsl7$+&)x2{PWc8z8kzG>b z8Kg$M?#~!>d{4IeM)sl-G(5#LXrSG zK3~eOHekm1otDxPQ zc6w?G$wLU7;R##BNo&bQs_OAsy$_1xbQ8?g};<3veznXZ?B_Bw_r;5hXn>>?^q zV124+w6?MeQO3g}-bAS-u?+~ragJJFTQii-{jasn%E>7vfmPP+YRdi$96+S(&xr|| z2d=Jao%kX(6_Xpp2+y>L=r0?88sM8DBIx<^=u}!vtXPQP`B#uErw`c8l0sNcZJ(wx zI}eWFN>eS4jQxavj@P?MFZ{elUG8c5eC;=o9s@Uw@#ye(;xyAHwcn%8vZHnn@Tcux z=C$u=u-N&!KL~75M7jFs!2a$8NlXJan8Q=w;w>*YRlD%Vrk)MGBj3`pr3Ra=?^uYU zbKyLHC|d5}w%Bh;uI-D;QTL0{K5Zj@;%ZnizC!93d*^XCBlXNzuEh7a-{&QB!dqu=YsTN_@z z@jf2?eem!-;Sq1fhcCvn51;nc`Opd5l+-G6>7}R_N#E5mFmkZ4pn9C&cu$>LSqr*G z;ZJwCO+_uKl~EjcDq6O)ud8`^s(Ducm0b7#tVJax;_SE!tFL}PdQvTk*h~p;dgrLT z8{jxp(@h;FTi-A^ewe}GRWc!DA5r@+6f;6k;?!#Jcmif*Sz zXF~Ra@8a3Xfo%s{Rduxj#)zb^uTOx`H!yGnObiBV+veh~LGi$2!I!c@EK1=}o(W?( z;+6het=D6DZuPej_eyp9vTF;Tv}(dz2RgZtEuVhe`+)a+brH*}g^R}MVT7%oSUQ>3eOziv`NF50-`V;WN1GEog=2$%sJrcW69eq(@a&(LVL z2@MJQk)PglbZBmb>LG5flrL%9tL-_oulX3L))N1 zDVl>i$gd&-m%9kr*#pm3Sn7+ST>00tZBYVRU8i97?_<1zj2T zCH+JwuXsP}3g|2V4n=UD{yoVB^h8Jm{zz57`s?TvfW@mkkX(w6DH;0-JnAJBCjAeX zvKaQ5m5j#u3gIm_Tse?h+Zxf(Ipfn?w_!pawObbjb?v*0ACJ=Gymq(?&xCk`ugfg^v4qZ9G)y92VqgRMf zz5={x>ZoO~vMTpSnZM;_?OGH~m+uD~6`+ZzKHQ>1LLBxN7px4t%7}Lty_~y8GJhDw z|1H}c%<2m|o!$sjg@FFQm~@k;kOwEnfHuwV$fTonE5NHjv)_6eqctAEVx+H1vaS)1 zmHp+;rsb^rB%@vcT~k;hsX>G-Lx&tR031ly&k7Pri}@==Xtk(qaYb37KM`gAnC%T8 z6q=ooP|if}6+(h6C=Qcyw+0jxd*LZ}2g zqaI*TKblW&`7mDFG`g&|#LXRE2#-SAtHc*0APP1&H4QIe8>-5N;a5OFpflTV5nfEF z_W`<`x2tPnB8_Bdbn+WfNo61*J$9aF#N_=S0m@NNy;h}-Zt-Q9W+l(jG2OWU%G=gdfd zl{fqqoLkn@soq^sB28_^T&Crp+9c|)PCOEUbY%NVd3CO`ckjl)8+lcvuCDGrBt}eq z`&JiZ1I)co)7_pX^_Ln^0Uueg+Rp!-{+#>Z1&HIN8%+xPJb-o88keIUDwpfy#5pN^ zrSX)FVYjx|E7h(1_>nn7Qiq*=eCLRoyc8XiXlI1xhydhI>mHSIOmvD`vq8IDe7;~` zD*+5+#ZU#L4ED)=X#;hxCf?x#HsVfZYU(5-pbTDQWtm*et;-yhmY0{`Y|1MkP>hhC zoVpTZ#9d+soP|5!lt#Em}*2 zcH(#X#lA($S+eX&GOdN*QiK!W!z3sx&edzTvFSeh(7B#WJ$D!6kV8@aZ8vj$N@O7K z!KVx_?aY)Gk=Ct@#xHpR+NM=H4drZ#JH!1iDwU$Y#zk78cZQAeBkq4O_IgpQ-+qrj z{jw3+6$vW0p71OwtIbHyS=XB((wcQkC7cKqiRX6oQC9c$X!aYe_rSIab6(dn3KzmJ zQafwCe+S&WtqOnerw@oRHEEZ+m+P;9&lR+curcV%%PS?GW@Tk5;&#u>FxTO{ z-rQF|?~|pc5xDbcp+<}hg_@IdXRkJ*Qji1S9g40UN=9%H+l?FiK71^pK26WyYCR4h zAj0537`UwS;?VrEQB^Ya>L-rtT{@aK?es{k@ws9;lBh>2%N{`mBXXx?*x4`De@q}?1M!|mc z<)`=Rj=_EatdtXzljDH;iHV6}7O2*R`a)O`#N2hFK{igA_%iU=h%wE&j=jeq(6-DE6MEgy%i~tLs-Zy?!VZ^x-?`7NC`Cjg(7Gm5Yq! zP2V6&5YdB&q0jvzXWwLYQ1K%qv68SQhx5j$Ojj-WFAZB_AFySo`Aj{mF)PMTKq8T3 zDJ=5gg8W#i6i6jRDnj>Vt3>bUG^O8R>H2O{LJ;jmLeSsbNGIt~Hbl*nF#@8@!hVl6 z=vEDo84!kJ0Rzb|IaKoFX7y*Bks_RtPV)2LujIYZcSLoC_CK;5%lAml$Ce6r+xBL? zg35GT8T}D(>nGdRT}4!Se#1TWDkP8f%fvsX$}k_N5s<%y@DYArUeSp|kWs?AOLH29 zMu%toI68&fQp#95Za;KPl$o9TPIui<94La4XRP~7NeV`Zp?CidC13l{U z;DO12O3m~tY_QOHp%#gkEBWx#8uW>{Wc6ZD-iv=by}QaAu>b8wI??ct)eadjmD70VZ68yg!O#PQ7?e=<0# zeP~`kd;3T@&`&d`R}Jo0MS3@xNkxwu7cA@ysNEIj2oZgW_L>;f_;vR?LH}KmlCVsY zsmK(_JI{oqmi-S&2Pd(Til4nvcXfzDgIA49Ln=(U>~PwNV(9BS1)ZYJX(ywt!oFsA1(9z@S5!oRL#zw!QZP+-SRzA(aho1*hT2~q zaoVT*C~ zwX*AqGWEOz@27-11Z~HNJF4eIAO3(DR*eEi1*YDr?LPr+okGs+E*|7!2$83Uu~a7g539gvY)NC^QC6hW!SXnXg}|Xq7`C z3IHa}bdRMDJaiG9r%Tocn9YTfyyg7QyA=pD3j`WMqJ@1xcn$)D#B6n{(Etb^e3mj& zjT^a@u%WBv7YbkoGvXZvA*4McwcwinXY7MCFarn5P(@8YT>sf$OxEx z)7|=S*l7$t564dfqR1n5a;f#OB4elBsmE^dn#fLA) z?R!M`VqSF+ywo5QXbmKE5GY%oJE1On;9}$D#n}B8&Au!iJYmb}`T#%o_iiUyknFJ6 zFQ2AWQ7Y54>j?T{f(Au3ZbGAWpqOoZ5#J=8wON% zRJ3$$jd~`l-$aKhIH`Q!5uT=U36+cG9Y88Szv`yMY(+qi;*8v6kw;c05-BWa3@Z=V zP-JsWB%os&CO70a88xoq4KBE_CNn`29YBcjD;Yz33ls5a19s*X7Ez)B4fRd)6?*F4 zlFYMo6K?hNh{7Rf8=Ek|8Lvuc#lg5jQPd8L;l0IT zBn?1@X_ZjkC+2?8!}y>OmU5s4VbJ~xM6Gsd-(gC)n>v9*5(lmvXnTI2K6c(iN<|~7 z*8G7qyIO~&eBww*%+639(&t*Fdyfk5sh*NBPqrA@cM59HtZ3{>B5XFMkL9)TAk<1f zUt2iKBEvyj(YmlEX?k3!JfTW>d?3sA;Wuw+15w*sF6nQ^KX?_J9ms--WcIvTp$Kbc z$Nah#v@}l$V2O$0XUx7!FKnv5tVhJgXv!sJP%WQ57|bs!x=|lU%NiL%aPy?Ohy)u_PS|rdoZm>+S0imO+7E6yNZ2_ApFcYlib}{?p7{mCN*8f zWjn;leW~8JGpXG07hX*fmkrSlDy2B$3 zfUdy#PXyiJ|W=%5|F?%0Q@Nd43L5Qt7@kiab#eUqQeYy_*k6ACb7Mg zn$lS89Z!d?Pk)I!(|KqxyR`k${B)7^<`K6^j(lFVfwWYn!?QdDw-aV}R_sO88 z1I9mKc+0Glkt&{ zqX)Dll;k;2{yJiWCeUVQzt9O6rXWzoAOs0K-nEK*_H3_I=e0|vK7iwJMSYu_TZR1% zjN^|kL2m9Y*fYA|G=aXsqki@~5E@D1{9!y2S2!jSK$T8pWfgP1cKieybifw%-_G<| zJ*0~?E!B#!mDzRLu_5=I4E#a*2D)eE63%92Z z#_2)=c5Mbna#yev_M+w$FjgpwahwyIqIR-aGS6^+#0+k6pgQp7$KZ70DoV zOD#r=Zd5Lm_cHq@q5B8uTMGQ3YgE#Dp7n5ko%$Mwh=DqFq-kFmTi;N?3Hrm5n<7_g z)9mx_5Up_|lOp0Y@WxSxtu>WWN|aSbR^@HJNe`x32E7jtDh_xDL=k3ysw%qmoeso? z@V-mj%7}Z)P7taPuk1Nn%ElM|)m>5WK-!_I5q1-jf;#t|UJu^Fa2mS^TTS>H1MM#@ zB$RhmyvDeE#-_XkUHB1)4vmHf6P`|tvR zI^BI(A_k_~^<-5Ii{k_`re~y~tq~Y}i5T{j0lUDH0Sn0Jh}3pcNm3w)sjaPLR*RWu z3iAhoar}2nR8()%e!YJ=*0#np^>$lU^zO@@z$gUUuos32NgMS0Rr(qvT)6U+Mis<9G;1JpZ_l6%VG*{lkN?!=R6{n-J_J1H+FWuNPIN}z8p(e*Jn_>3k)oz zF15X)?^3-3tBc{~=qY(6H7o>dIUFut&d#?#TrYN?k)7G9V_;?Fw2{ynEaRxphlg+? zIYtWs3l3-(>vD9hp>+$2V&hjD`mQ!OST6MeY&toU zU%LjjqSgh6WG=1yLksa|f7&rs+a@H8^`b+^8*4jAi)McPa7yG6xDiTbOm7NgOi04rz3 z3x+Q{gg6c7$|l&?I8svqNgnw3we;A^$d!;FCt*= z4ijEqU*B3$)|%plXo>P}#jn{wJ`OX!VgBW+W|a>Af4+P^n>*~7T_Xw_WR{RGBO&2aC?zp zTh7Xd7s3zNHHhJ1`OO*&qx+Jm-RvQbqrnxo{nb#|;JW1j1}W5dT>xq151Y&YqS5_e zdaHFI{ntJ9BqdmY@obKe9WWSPwGGdbMTJKsGAh`ji{LuNDdkL!BP!CpUq>$K^ZeE1 zh92zs73o2T4ncULKB2GqhmIRZsopYMayiPymYnSixOoqGY?0J!5?MH@ z;<`<9))e&b!LClwKUQO@q+Tg9*?(iQ|CUu`|Bj@ln+KHI3X{*J#lJL`n)_~GcdMZb zm%NH)5M6uw9>G&fVXlhmCjg*VZn64BxDX{j%e$Jb^Gkh2yl!~lfN6Up3wgVgA@%*} z+iLXU`;dmE%!W~<@Ym%f+$eRCzC^q(!V#u7l+3Ps0Jt{JZgmW0BZ1*k(dv4sf&c85 zqKJrTQJ#eT%$pJ5P65KlY8%RP&yrS>M;TES++~3^jTiwuQbtCGC5kVD9^mEra7?iY zP8){kLWrefBf!aGTh5jsdoB(=ocCv?mG=CP=6z>*W1#+=3gTJ8<+OXf23=uyu*(q< z6~)Od4J#*eINoD`mb+^Ac|zGLe-RPR4OSDkv9&6ErM@z5e zQP2lEl`FjrI2z~~Qgtq`=B0cXl}Jj}D61l1buFw!Z2+ z?Sx;v`!C-}?r?EXRTg?vA~+2{OXSk(>gq2HENr2cWa|lRs1+Uiu-DlX^G>&K?i1pV zMLX==r-4KX^>qG`?tecvoP4op>(_B0j|}IT4q|z5+TNAjeqP0TS~U=Kv~xaBtC=ff zMi}}^kVw+td0RnDjC^1h+nrI=)ySC}f=Sm=u1q~d!e3iL4Eo*#+YAd1r@A~{POav0 z@BX~REx-BLky1#n056i7JYwp!utK+*E$&ljc$~W$k(QY1gi_8rSWati%bCWO2rj); zJfT#$)wiYb8s|nBq}^hu1yI?O40EtY7j;gtkHC230n#a>6v}a@RQPaR%9*rp%sAB^ z!&|7RSCIcI(WCSCZ_!+F4{T#+SiPzz7)G)8VemDKEh*ucYt)+Vfw9K9ygXFFr4*Bw zWQLE}2F8=wmBn0nX=#a54!-?6)e9Spj+gweK8%+gWQ%)*viL1xF*bAIEP!DE ze%ahH*w9*ppFy9_Z^n*DD>F1RtKDLQ8Awz@f=ivi#np8LR5y<0LQ+z(FtRw+&q72` z>AYKVsYnrrT3NmV75v8Ogt3e5bu%wZzKmyQx8t6KUvY>d$@7OU$Hlk~MC4jjcxutb zx9>F^;Y-VxWEUp}XNI9;DzuGP{aHZVZwn{>cf!S#L8)TqSqsb1{mqG{wuSY_F;l!qTfMyCH6r_8svgWy|(cl*~O*hOby&JJB1rn(SaN--4<+x?_LL8f4BCSZDxrFx*BqcdU zo;rIoCcjdQtbS+(NQxxpTt8~~j{o;1KhHk5Ux=o*<$Ty(J0ov<3LmPHlHXzo{_feq za57`FKm4+-?Hf+0)wxV;xJghjHRB@S+l*m~05}*mR^(*^P3g>*7~I*I!eEZp{Mjv1 zBYF5S1Nqh8+=&PT6((YQ%ZCp|9=U|nTB-}CD+(Vf3D(k$s|$+GSKyaN66>Wjz9B;7 zX>$YU_Wh{k=wmvjxa#roQP9QF#jrhgrE_}^cB1vLN zhM$imi4moK2_#+N2Y(~9+@>UTwConIe@!N$N5Qu+_VvG zV8@{5aQo==juM7|NkmvuQ$a2Q{IGRSkV=05JTJJeGBV+7`9c~5=~KF?HlVbuozR!Z zLckWlt5?tlJSR+om-BXERi(%PY{a*EBA^5!Ws<-w`@i331Z#JIUvty$8;5V-gKtX8 zC*qu;txyhpFfc+s+HvXY9CnFLz&N3geR%1|NWmGVRNPeiKhy=r21%byI!ykny?wT{ zf0FH@^^E+FFxE3Rj1(`L0Pwh_fph^%au6?k@+r#&bOpmC-xu`*v>PT@KUlxv6ijYB zM6^MD7xalh*o=v0nU-pst!5%2#fo+*qzs9Y;}ze|$$oJIv4{~T=iI)veFsXFb-CO7 z!uzxDu87AQIhV)gCkB$H5nV?tYeG18ZH~!7P-3OXrF*tU#mnMuz*P8}O6JU=QW}ss$xNhVjwBgNDpR5&l_EnK z5>3hwa#DV;r*rT9{@4Gkv({Os&OP_o`*}W}_xm;ezM#3cFt)?~?r}*{`mO5fT|7=v zG}Tf|SD)?~Rd4HpojmuO`cKByQN}C#_SOygaqFfSe;p|M;#Tuu-Q%OQJ7T?6$J}gq zESr;`Xh~S|EJPeoXNsVhY2_*zYUrz$m6rzOZq|1fG7gQ2JBaGo(q`P8CRzjs}^KFjE5K9;Hw_LPbZS1w(0 z@u=6#zG>I$N4qWFWpBjz%vc+1^L6pzM{HFmv%-A{oNO`cAJHiH!KJTQPQOL0zCL+k zW!LI&$1e$!`+}3N3~J7)-2Ti$QP7(fOg%U|n-s<;5`4!Zy*^3mziQOm z_OCqL&o1xk?j8+>f)E$rK&K<&l_#pte0_b1+HevIU4ra4Yj%B+P^xi(fJv9Cqf_)! zq3#JLNyNjH!EqXr%Xr_hM^ajEJK(M4wbs#|hHLd@^+SiKRLT-fl!t9CChreTzi+QD zR?=n-b)SyEx-#6nvVs(xMm*mUay%tp5C-I2N{Q&NleHxMS#O zcmPuu_77imY%pRc@8{YbJZK%rXEa)TrI~FKj<$c!#y$KasJJ#{*uz4+_=l%wiO+{- z?s8qZyQgbab#{oeYPLL^_tT@l%oo&tjWfA_3WsGZePSF zh_OiIRJy*)t2*ycNTO;%3MIdVIE)5~ya zDaxj06Gjk2366pl2hRoJ!1Q}9HO%M$^AQ}@G|SsWbEI{2-R+Qj>r-3H zK@g}=ae>eJ3vW}KJ-0tueA~^}>*qkU4h?EPn2Fy0)sr!Wrmc=?trt_n`@}tYb@dP1 z;Utlhho5r8jT<+fW7P1fphUIfuY{*S(G$MDf!)2JSFu&t*xFJtaRfiP(VSF6In0S#mA`tX1vdDJvGA5q1;~dcJ zMa9i5t^OHV?Rci~`R-zSARomGIQemxp)~#d8P4B z*Z$C{2T%3T=!D-6y{Ec*p@lAoge!_)d8z-;;K4m%pI#Ot(Kp4+FiCuC(aEDnUv7_Q z_WDQM?f#4F)C3#Ns9_%FJ4b7_-!N&b-geJJ!&G5r-lv6%9S-~z zo48w1qdN;0Fpde>lSrf%6AOt*@44@I$ZG-b^9{clOy#5I*Y-K1sL)O?DvOwu#AHl{_rQ z;CiQDChT6{gHhOG`5tRsgRgWcePY41mU+O<J?@EbeZzG;H=-Lp7Y;M;Eip-%cdPmE!jJ8Y%DBZ?yvP z%|ftIeco9k7IjNd$mct>U%0OQzu^@g!v_Os1y~sr=iWy||J4=Rp8~<>=QogS+|biS zw35E?za0WGakB=L*wzx_6UQ6>Bj=H_rPL?kgo2d%#P~Te_83amCQM9=ffaS#1xTtO zT2isU*J+1-)E2la89QE=O3uxjnfW;up(J+-CpS;lgTBbQZG00UAmT)whh@@f_GY>h zcess2bWlSAk=2Pg;^+CW+3j=iYG z!*fiSI_}-M69<=ohX+`XL7G?X=QjpI%nI$ZF4SV6LvXL1ngnMZRAw{%E|F z1o9fN>=xe`XV1f2FP^(jvTlkHbdnE%N@{?vrfTcj`l}Vg8z(~63%Lj(*qb=t7qNSu zX$;vH_;wW`%=Ct5TUD3%XT@T>Ht_e;$UDa* zlLdY@Gg^TN%|8^n(h+w0H#AF@%7%2-fuzFprv{RBisn_O;C{pduqDQsBZgvhiqWwpNJ|G5Hr^y)tX`zMj+I6> zVt`bkn+wvCF-VU`__JIM2v{cZWV=GF8ipV9vY41y2~)NFgQ}{ z0DDkP0@p*Kllc1}vaVH`M1{qk6tb2ncIN|WMafNLJ2}aJK2D9zPPsdbsnfD02|OEF z@UM;ZtcaB~$uJ|}KHpG!`S-8N%-z!2i1j@tO>BQEYmAKJJhTkSuJVFR`;>Yd z_qFF3nCf>{W?KY@P96%K{J@6BC40!);$Uz#*eo4TT-Ro4Nq+Q%5>Kzs%Xst6w%Qz{ zsx;2l?&~}vTzVJ37u^V`mWW~E`waLw{)Pr$mfSI;*%v#z)Tl&edvcs9D z+UHku##h#?KCZ`g;Z>eCym966?8VVGDigE8jjHLYlz0{)LdijstyKaA7KAHZUF@k5 z*<+I8!z;{3R3^@E+&&oI1%;K4+qpB8-#wRixf+ByInDkJa1S_e#1V z-{PLvkfJC|$W=w@@989rgjR%7^=I@(N5Pc1C)u3E=@sfZmo5=iyEH^01g3ZzR^b~6 z9@mM&e`Mr0v1fet7jGm`tbFxYgD`=M6dDQRiKek zgYHT(lcC7!Hs~4HJLI0LB{j{3t(4yh9I>96TXxrRj_Zo`{>I{Vuxugx2z%-{+9f^` z3dW`xSM^0#Uaw0pQ7hv^CA-7RQYK5jB$0N+flBwLV=sB5oka28R{0Py?z2X_v(ETb z^#(b3v2POEDcq*jx3=vTDkgWxDfb*{yjixbuHTvGvr13#g7%!mQL?V$X>%slYYUMC zPavn^Q?ZLxTXF2FqIE>v8wH&K*)ETovQzi@Au|Im2VOXpLr-smiU~s~F8zlbi{*t4SBOF&-gN+4`75bNclZkadN%&-X z=H+?_J^G*H54fBuZw#Er>hY@kjh6InCRCu#qI3PejLUe-8H8F11}QkYZ!{#hQmQ!gOIJ2moW@pjJY_`#L) z+rMWXS7+s(b9g`UyZm6s!QWrP=-(C#2;S^F%duLC^(|VZ+w|R@q-zfr{Dwomi+wF> zJ7npgq$yXFOA3d|)Aa)pHTRiOZRYGWGLxfDs=@>&yn}{D?C=%ZqzpLeFQ(V_LO+mdT;V2Q?n#T2CEWT-}U)PGXr$75i zGeW0T7G9YPTP62|F4imtQsf?fqalgy&lRpZ8+YZQAAJKrdFk!j)7ZInqVOaVvVxbrnKgSe(2Zhj@5^Dx^DI3 z-yL7jTIK9nY~dUf`C}Ugx9AbteZM`SOB`436YcGcalh*poy;Rzu62C(mMp2QTRP;9 zH@@9+E*^6tG_^tY>ExH=V}mLr4R1XdA7CSZ(5BwDu=mp&R+j$B7ru(iKxON}t#CDS z`@{~bg|7U3J_pn67G@R-*TxMSAW3-RnnYo3qeQgUodCTIfm`+a2qZ|(U!rT58BkFH z*E}XBgNH!QWSmOR*q|n96w}d<7fGS7CT*B(^Xncls{hm^ z$R3nb;ea>Uzki747m!%6Am)v4Oa8S6VE9zInUJAlur|)Y)pVC3k%uL0AZS_KbtB7` zTUQfn-F?UXKycjcG-*Q|^y3{XH=@$dAihAHR>-WNNcMt2e&6o6_sX5sQcfPY;-`Oq z4_h5LxYB-bh4;|2%ggFnHL)!VD_b*!JiB>(Ufp`IzmKxnN0?a;n$$7yY`*(*zNPsB1LqU9B|EoS z!jIbk;kuIg%vm;HVoNr5;A9^r$>C zENdH+^VzGrlOoCdxPbi>qipHMWAfs7+qpR4c*av= zWQN3s2S-1>WZxAC?=+^T4efLs=Tw6_-vvU2&%;|RqI0u2FS$O^{_y<_>_#5;Di1Ry zB+sk#5DpTC0B+4$!()Y&I;OY~+;@%qe zC>C8S4ZkZbm1k!A1Ab11tlV$>+ZWVMsYD$MD4$Y_IA?-U3@xyCGMOc(~00!A2f zEa;5!+Mr9bd@8;GIA1}p!fOwK3L2ZId$B%ZC9=32l z5Fu@*u<`D;w)gAowH&3JBI10tkw9@`riBrw#q9?R((whI!8fs4aQ$_MXg`UEw#3DQ zkTF5n-_nKX+7hr6gCP1r6uC5|4mj~&TfiaTwaYgte_R3ADvBf);+SWn5Sie;`aOL&$`u5 zSI4gYo?lITe;Xc*Ubxr}rvUr#&5(UHc(TUo%z7#=ml z8A%&qMzSd+TS9#tecT}};7pCdyMEeYGW?lpyLOcUjjKU=&r!@{zcH7)1F2h{m~dm! zfcyD6SOttgE|bGi2fT$|?)da5BiVSGom1)!rPGXe?v>=0;3q}NQ~GN=Kc2Mvf*sW5 zT0Ps5#|LO#6%@?-pRQF&^=Qt*3{BLwI6t zq)Q^>fKt4c63ePt5q)FBxE+~{JICb%Bm_a*^U`0sd%d+rCCv|xHG3eHtHSC$jF5-mx1OXSVX^D#QU)cYsHC(EnTPg7l$$Agilr$;ChH}{ zqw;<}QhGpBOa?#PNs5u;xATEjJ4Z!W;}@ucVEam?SQoLNp8uOk-W;nQw~LBqeI(MP z#UP8kWWfi^-G@_+JPC2YkLERO4jHzAzou`$hl`eugtO=9e7BM-+QtDNGLsxneiEts zAF5o04;2rOf~x8T=;n&k%}V5SU=K!aiSa&NL7iyreMl>`dZbuDDn)e7xwSlB7%#`a z#I+RVtgK__Sy7y-fQeLC2wKGt0|Nu!mLRpBR9_Zbomg$KPvaM&_qeb+681;(k5bsO z%+ZS*IIICaP0c21Xa1mO^D!3i($rR+9AkAU3dv{$Y?sXU5#h~VgN z^=%fl;IPf4X1XK3^_;%7BsX?qbaMIB*>UKmD26aaQ%|5iyL(cqQ|)^H7wV-F-&cpC z&7O2Sj#AIZii`hvATR0A7+ZUciAt&9 zr^0vDp`D)%J7k&YaI!H;dlPxj>x8~9$1*o05eoJJU%O&FA`o!c8a;x1eN8iTX}(UP z@(1N3$LrY1F0*%_3wom(^ZnICRa%6Wj9M&w6m5THlZT(GjoB5o?>n30|1r}>U2UOk zKQ54R>Y3rbrdAtQ?-FGI}fgiM623xJJSOWbWWbPRneis*%TK3<7sVnJxa(tG9g zS+;)u{)$M-?>hp|%b%wLtCJ|QdfLcQB(Y2;-Marr`SSv2YMlvP%JCl|_vE2to0Hnx zV5JGW7x{hs8p$Z#_@%VK z9!%xZcfoiqw}Ee#g?}C$UeP;_YG4SYgp1Q_eL5#z*h#Yn3a;DW_LZYv8Xrcd+rZ`N zjYbU7&RJX>M%<;@_r6#oH>mDIo26XByW`snvpIPlUwUrGW_f;tZoaOq-1T&x3b71h z7IPZAgnRuje(h$8Kp;GC@F!00cBgB5ek|Q}zNAa-JY>y81MB9(;^LxdPOO`SY|XRz zVXK6@bp?TZxY;4%hM;HxFh8sgkdbhcQ3$%1KAN5EU)TXKu)+n_g#l=@GUJltsb%x; zBqGN%>{J{gfRCMi&pQ&nE7UGXn<*Y+Y8nl?%~k&SSg1Wx(l?_w&z_XK82*KV&HqV`U^?k|Nf+=5TFe2SSuk#K{Z7+#d ztVT#F>4IW}r#0d;HPxyQ@cYfN^Tyil@7rir%oGu>TZM2YQ6bzQj|8^^xnMuW$f)V` zdW)GZa!cW}=iL^QIeZSMD|}Oc++uerdXk3WD@QmKtn*M8i7K0enocZ;D|S&p2Gm59 z-zu4$kZz5KOJv8}?&wSQMhPu?J7Vk3jec2Wk#g;p%~B zR0XpYrrSC<-P=PVT)r5MjpS>9cnZnS2yY$vARaHsIa(l&0LKOKr=yM%x|6<~Pj!%p zF7@=Qtr%r{mTjwo!Rcqn)46?jzWQzRNFvY#(GfQAxGa|(xA?DDgY)tKfdZ=26F8|g1~sd0BH$L&;k9!YZQrfevNKWuP<>RD6Suj6K~!WR*< zC1UTOl5Z{}={^yzb9vORqNKmC4^dNG9AXBos3Zj5J-O#eR~N>J`WLYL96^c?E(Lf& zut5M0FxJ7__~Fz;gu!4NewM3x9z-Vs0r7`1;VYg3wZNxxf}PMPLUv7+yG4$TU)MKMk>0wpq5}6-{IH?IrWry;i=*wa$o=NEhlfhz-thHmsJo6A`t!Oqgum&lgYsO`e!MG21q^ayd14vW}%hoE-Z}7J*);l zcGaKU*>hx%;La$6(An{J4T+t&@1t3H!#-CIughEaePaH^#_A2$9OVAGnwKPcy1b<2 zHl_8U7o+Q6#=I4jgw~Bt+ar~E1D}vU0&R=o=We?Fl41jo(*mT00{qWQ`gH1zv$NK} zZSz`WU;7Z}b~2+sLv)(-nBrMh35DRhcO>IqbW9v$mB^1S4d68xUWjjbcBG?U{%qFE z&kzJ@`E-}4>a^+*aT>KU15;BWi3q4E9>Dk1Mt4kWPTbg3wChwI5bnp?P-u9~X+WbY zG_GKh9e2k;hHYm^XTQ;PJ!I#L|HH$hVD42xh|DCSv6&D?bVA*M2rqn-H|ib%MOeqaz*!)I$>U8JA0UpYMJNIuO2W(oxNGp;yONy453&i@51>vbkJq1$`l>-# zTZr*tA$RE>lnL7*yn(Lp*zPU3ETA7f7iUpyMt%7c{AIHHCUB)jz$fJ^t((-yVMIdK?y+vwn+C(5y;?+1I9G ze)U)4)qKV0HpnK^O{U`OI*ETyH( z?z--K1(4o`bcS|7zem>q*LhuFh>H!wL6JB1-Fi-G4$sw$@kybe>e|4GFO@ljz632wB z=D%{JOs8(*|AdemJ}f+ii`Cwqi34x!9D)g;HSoVZ#6s%#-U+o)+9r*cxOcFmrS@IY zec{YtQ?HHi6%P*)8Xrw|NN{qeQV*OJWa@Nydg_j-fjK!EMBnfB_V%Uho~gT$3g>R# z>ofUPLi$EyxO}*@gH1JEDDSF^cM#tN@3?7y|IqD?HNT-xHohR@bb4XOa!?!-bN{QG zJKds+*i#Dw7ApsR_kP##yral|TylRk~fD)KkzBn?)Pj*6~Rr zz|yWF=u*ib-RYph7o(v~mF-U$(>Mz1aB1~IN>pK0vrZsY7xFHpzZeu}Pgj?$d}05W zS)9^fq^t}Bi_J8fMnG;#vale;!OAed_meC~VBrf5%v9=s-m8O@7`G~?7itAyh_jOg zZ~0=*E`Zp0y`TVbt~!1v>LH;hE>5>J?UWk@5@DqYij+9F?Y>YV#-Sv2-KEyZ086@r7ja%r2y0{zp-s_LyalT8Q+Tjhl?mER-K~e|#fZlT140G1bB-Frof4QeAKt z*HK&!oO3R4ni6c}ctgg?dfeV>$3Byx`DDFcze!kfN%fLEaL1N$1W+K(uFh^<7eqFo zB-e7y>3IaKrHFt(y*-2?2_(4neGZh)l26nuHv8mRam`KcX74{7bSxn^XCK)6(_K$% zo^&sL{{5M%N*?*8l&-^e=hHXNO@G^*&XTwAO(6_)!ISC)VU4BD@hnwm4ip#hP>mBN zMLn}j9dCbF)8;3zr~Xv)o2{4aO!tf_b@Q>Nt;uI}W>h?)mCoTZ5Kt|{QnB-k=2Z28 zp6<#w61`edf+f0b^>Gs+p|6jixsC|*h{`@DM{2Xttd{Bx$$dIi0wjsEUSgRWnQ6u> zX-Y*VoyA7$2NDRS;S0}?!Uk__$e8REF|)xzfV2mE%MiQ=!l}usr39wA_yxV_=`^_M z5!b%X9Eddf!K>?YLHL*F$x1Rceg$|VD3qf~!+Im}UzO3~ojpoQj2?QK?%FKzC;|eS zHV?uO$!&DewI|p)_|N>H0tv9Z&@Ut&Rdk|QG^yXn^e3{l{;LxAemQ1uqff=q8%3l5&uXPW3bprPYH)(!nO+;FCGp@mJE z=K|YE;M#EJqj$IGTgWUQE{bI&UGX7tJhC^rciMSfV+iN%k?-2CEN@153x9p-vHwm+ zadqz3a=m$psF7qrlNyI4J3YRFwz{Y{!R*Y>qs-?w>84by&0uaa=kn%W&r`PD($H2U z+FnfZI^#N`2CN*&to1`y3b>XNQyDF-VJgX92=`lMkw>^*Qn?+-_ zXp>Pc6VR6Yc4$)hA%b}+5^ynQv9iD-uDv;5IJVVB%_&h#sv`^7m>)kvH!xTy|1z_G z+Qox8m5>WT7r-WKw5RlW3zFjsB)n zB$IYyAATDoqO4^QE?5{B*;D*}lQc@c|GB=jPp5PK@-WTdwsn1Ov}sej3dBJwhn_$@ z^U|f*%8^26$A5m`eoL39&crdS8`22d5_hD0@0z;4pC`^N1s|R4$Z+43UGr0R7qd!1 z342gW{b~Z@Ol-vCwYC)l-w&7(rJDqPIJ?VhV#o|ee7B_Q9 zK>P+TX2l)7);osHL9t>BY}7bLQ-x)BmO!5i>k#6uyU{ampq#CK5h6 z8mIzsu!ft(Z+Ey8j?W3~7^*>Qr1=rogm1V5+2(KdXy{;`!i9BSqzx!sSC>PE`d@M8 z>azOkA-p)9&<-%LRqSk)<$IDx3Mb%xk@H#+I}W6dzkbC=`xb#`$`f!7H#^ z^BIapxif1NZ_?`s23ZJc5f=B(K~*BELYYV26@pGuz&}4eZvx~9QuZxBRO-un1cB$&OwTduW3p0hDVvs@}jqn48=%ozuatM zEl1T?E*{PdW@CP;P$Ae*7|{7%`Pm1#VvC#UPd-!$G6fw6_!(U$zvV8e^Fp=I#<|uB zJs3JBc_z#z5c{mjj=x!dpp6>XIpQRPlfXGhmW8XpmaHpR#DskxgkFJJnWxapl4#vM z52LLNKPe}!W%U&Xbg7N`&roF&TDTkLZt$Y4t{B9+VFq`?noS$_t1NA z|IVFG>~sZB-V-p`3(q%sUBISbc{y z@x;)P`GkX1Qy|oyb1u=hV_^J9xUs0RK zp~)LGRkGZs(WgBcsi3NIQ^gx zZ2K=UjgFb_zGP0bi{2GtUY9;2%dhULf}Y2y3Vj|JmOF3#k6i1;?XKDQ*27~`ukb9c zx=>Vr=B00bk{|xKI9aL~Pp-B^JH9SKA$V-7O6j6!IO*HZu3=OLmp=QD>ja$3evz?0 zetg||Oc5lY6UZD`6e?;e&kaawQH%T^s>#1Kpawah^@oxks&9LEHm&sV?*{a0{3q7q z_Isx%XA+%YLvGHy%1?sL7`ho_k+K7ob`{VQO@!>Dk_`-1fNR6y)UPX=MYDtOpe*&^ zeQyeJlRSo0I{8A|b8^Su^Tb!|Jf-)HSaF|p?LX^XQTL@+oXbMo_=b`3oe&lONxCGP z-6w=^w{}O}^5ZW^NM^nb;#;K5(lWs!YjVeI2RC<2@E83pJ_a}IJgDYz?b>ACRD&@) zYC?63oer#1CQL<%1>#D5Tz*VvReI)MOf|;G(S{R>wK5CnxOYOX-l1h2z}Mm1$;Oap z@*ugp5XZspr#nQ2{Jzzg#S?)jVx<4XOCdG3%!1GpB_$>Kkm_A5$Xt&YI)Q9o7ez4U z!MjJ90Se#?Br*medn3k7-oy7e!sf)ngf_7GtaJ8ISzVb|OrqtXb2p5P<@+-63p(ee zQPAhX2P@NCiEpas2w8Xb`X;iB=B%E)_}~5UKWI_Yk?3uzpK5!BfB78zwRuf=Z8!

      +PD54O!3Q5Kjk6Vj7T=#ugN|N)PZnQ#4+KpZI0#U`-lFg|rVQ#97*xF>1jp4Z7PvA!%9 zZ}8M*@I>SX)XR~Jn6D+idfdQcm$)sS<&of*7Rz9=mZ$PGr9nj|lhanI=SZfh$$TzM z&2MUtz0qS!lgodvEMt7D%EMz{uLbWh`%GbGgV&|Wn|Vs5qHc9U--?lHUAReT6oM0K zq$1}B=AJx>uRYF6E6ZR)@vT1xbO#_!TpWn5*g=)7O}L)$F2Shh%+0O$n31HSrk04P zHwL0WQ2UZ5P8-=hd!FhDa~Ix&$o1543Tr%}S4I`gLy+8Swps}0ZlX;>WbB!GC zJYj}@_{`8(=T6#Rxx=i?LN5`yn#Q=NfsC6Z|CY(JeWc)Xl&{yV(XoJjvE5Kh2iN}e z8Isj+(X%z^X=&s} z%9=Mf`*(I>5J>v~87NG8@Jx2WfKew+bnQwlm{4RIE47Pq z(fV{s%CR_ve#9<)9nk(q`f_tpZG-5JWb!J^I2YOC|m1AIAMzy?uLLwK(wXN z4vbzi0N5A54z$ILPNG$N1_0mLv+i_wl<|ci6&z`Kp*Yx`)y$1eOsdRSQnlsePM-ubJdumFb#esa%b2-)HFl z_x%3h+rhnc!`h7pQ8YMf)bzthJDzz{!iSLcTf^$&nQZqnxK|%I;&C1)AKRnJ+O212 z^{8bQkj}LSqFVlI{c%B#&fkq4j~>ktV>KpF|H1n$xwNLEV&Cr5H#6w#{xO;yt9suR zfBa0md(awX6LZfB1W{5g0;pujKQ87apSRcCeTgb(sHc2ADk2-d=ktQyomTJ07TIj> z)SY9gYYJJI9lTgK-HqW&^xCW(^Vu-N3>6p$py^ZTnLfqbW;zve)8v^BWy$@NXmgD$ z6mk?kUFuk>%v`p3G4fXi7S|_;8{^5vjr(>wSa)YWO+YGP%wJ1G6OM}Wf6;`$2%=+U zY*0fNuGW*d_6UpEzH4o-y@^C{te`*|p@%^^z_>>ZvxgqWXsnlTrP`&A!|OtF@)H1p zd*eRyw1|ngMtYc7nfE;8#x~L_ct5AjgPGU9uX@}uM0!U%god5O~yjS_mKcp z0iz2{4kRZC_YoJzi&(37Gjv5m(?an=v-IXXF<3ecp4q`{PS({7-?z?Y2kh8Z+gDH|e%X&4^F!SDX>9ooafjAcil&q^r6{sCJVEi? z*H^4AuQqB|@XNeNooWd7qsaR4Yk3rTJ?Xl!EyED#&eQp~Jrb;K1^r)~qne$S(rd8& zLwZ{N`iH)g=poxjxQr3x{yS6v-~g(GiitC+{QAe>M!Y_@K@$I(8EW1LBS+Eq?Ty+H zS$W*r_7M?rHi?>O>09~HyPsg}aVmX)5X7^h3hN#6vU5++LQ&KLRDA?7VT!_biQC~H z7l?I^+shw9m#Rc_uYTp6wa?6nD|FFf5^y8^Ye&*Ha?~#s4gGX6)XPms?ZzcpuG6Qc zuL}o%KHkJnk7^b-DPGQp!6s0bm7A^0*3x8u)88|HdGiImlX$Z?%{wkEaB|Nzy!LS~ zeaUkxl!1KmJ75Rx{o$Gv3&F2f4P#96!U$ao;-`n9i6g%|Km{oeB%1yapazu(T zGu6^_>e#RYlh+gv%M;eNTLD9w6LM5d{hBy)S4pcB+Q{Z7t=(6Xr{rqZBXxS-p(F6d zyvoMcQD^+PB<-A@e{-JZF9^jli>ZjE=Bj(|L(1#?f|z6}7DeYvtj&{D{quVfJq`ae zEWh{a>R`_3DzT)44}d11&h7(Z5QueQZmwEI;NM(Llr0b%A0iVWg-FyojR&1TRH0^u zlh>V1QOgX8NpZfr`0*ELC;LqeZRw-Uy!BP{>q1SIxf)CJ{@U~Z_2-A)p+w%^e|nq? z7NZj#_bQbWy{;|U$y}s-UQZ3f0~~WXPmqa;lq#%=AO)Tn@H1^@W$6G)M}+xUZ^~1V zW73j+yD^L|T+xy4jL+GDh*OUN`;VN8;{4&pij3c}UZXLdl|$@F3=3j`92O@o(Y*h;0C%L}m^y zH=5p$_*~oft1gfc0d9N!CR&|-W*^FJ!DZp+37vBNztBIUG{mGQAdy(pl zR+aYcp)XRouy79SdFT1(;TK_X6*+8cf2U5iBn}s+&c#4g_G9h5%BS3}j!XxGGD(@* zwaFzMoKn`N$%Nc3QVf~_+_Pqq8R919UeZ)e_8$mtjw-$5|0$AO_3qfzFB+ZB9eR(y zx2vkea72+#|k`D8@l0j={e#f64)=1Vd%n}5}ep-c~rdECT^V< zg=4%;%2joy;=-VVG83(d&Tdw1l&oN%QY|Qb4slBP>(9yEZN8D`I8eF#L#@nxpV`{UJ zitkF$j$JRuL2Sk~9a|~lV0F;?*4CVtYM*!(P#=AJ-PbLDkqn|jgovwQb!j?*U>q2W zZ&t_L+ptF;B^>+o^%zefr#w}d+);JL_^UwSChnLwu*lr^zx^xsz%T9Yr(N%q83h^h zG=F&1%fbZxbdi3upcyGhO8Rit@3wD#O%5^}VdChsL->g_U*QvG`5M>2im6PBf2JX8~ez))CqyjrRcq`jsVd0lUl zt$m0mTo% z7RRNC8_}hheA`YMPN4O6K5zj{0bj^!d(yl}$V78=XTcN+U^Q6*)kIv2nMKd-2$wd1 zr3Xka3y%Z1q7q72z^m4d{Y~6mA2W)ZQpt6u=Z>K!MYz5E|94S#2Uv2+&;%04&5avx zCX?+d^q|PXN{0Ya4IQMgwvlN(`|&8kg2Pu0C&FN7^k|OpK#)3Ts?Tosuo8PKUVm-xlbQLs)%9 z-TGTKb*>7==Ay%IB+6Zc&%5Y5JIjQiEc5}7H;tTT)=kM)wVqNwDFYg@oYn!o+^L3& zE$)+WSU31>iGH(lTvw8j~)hu6NlKcxg9Fb}fAOvaIJ*zQzp?Z+G(ED{{nT zqHgW&;8*whEH7*+xFjpdA`{=*m#}$TZ1+^}^W-RI81Fg2j(I?5l`v$^J{M19HU);dJAHca6ulBW8eu zbOMsgdkqbb0l(e(RFabwhtJ4++g=)=D((9|i<}=vcqDT81$-(9)1uET0o?>5BaLF{ zyS{z&7mr|~>k6b-4C!X|?QMMfZ$8O;D-lSiD8=2 z@|}^&CR=cLC~i3wr|2D#U&7WeGhTbx=6qa^ zoby)!EV|J?Jpmcq{-vTf#l>T;>s9Jr?)(CNg_|SjTtTUk?n#4DzzKyYT zE}Mhe?9>xdwO(;*PxFW5)+j_h4D2d-l8*fy%`0*ziR zRjAT~)OS#5@IO7PWj$fADd;}8l^4SVVTa) z<29$Bs`HgkDwzFoHP5nrZ1wJ_=P5nUY)`YcRlI4v(RV1 z{HDs4cx2_&)q7wGM(VjPmDMi$TVqn2?8B`|DiN}*R2jBA-esH5+?VFBjJ+JdB#&+9 z-w^c^_o$tM-6Dd(CZ#g=nDQQ&WbjD5Xs$=I9M=#7oYuKCqQlU7g!Ps9dn)McryBZ?kDnqdQ%T3V?_4#@>DUvt?^Vx|e zZGL{4xd^J6rGwhiAyT-YsdY4$BOA2}GJjzc^OBZ*k(I|dxTB36<6gR?JIP+)b?Lul zvUwl-q^EZ58HY@X;^8iqp%v%8ZAFU~j`FN+#5nSs2P<3ypa73aIC1eSm^+O6qS<*0 z!`O`bqRb4%3<`{jQ_&;TCM$&mTd%p~9zF6#k6rRLmgY>hNLjuEgrzZ7ad{mQ^_Q8%1CM7K(8co~H)n&gBD6>vbS ztT5F=KP^_{^8{-OO+}r!jK!rA1v$AC8T`?C_1N#LnY4L<6K&tuB)0%woZ-oSB|+au zAHE}TbyUR2f^~ALF%tHnS6}5>zCNEDv)Sb#OLW%G5H4s(=jtkb+ zg`#~!%#Feq*p*$*b40YVYuQQd#J!j%?A-gg<>hCfCoP1^{Ixe+(2x$y;9`WY`AFki zJ?IA@$OJe~WF0`O85#Gc?xX`^V@BXxa0Zosj;TlOm(=3-kse)Yo;V9Z3d5@sBg;xm zBtt)7AM=|REXdC@ride?YGjm{v;T#6kJE%A#%%)_M{5bm2`wE!jz!QF9XtYSS9$WA zrZ9B`QdeFV$>{hHdZ`5CVTJHpR9AAzL-T0?+{HcnfRYKq$il_r(Wiq<`usXk%J!~J zty(^++Yis5e9S_vT>UxyowqCHXka@Vj&?cyMmmy3z+!8>@vqW8q<7Tpw7KN*U?(o#&IbNT#2!-S-$|5Ah@fzw6b z3;tt6CZ&EC3#v1DGd-K)4!3LUuj%9u7ANpndh)pIrc5=wQ9qGhBV+gl^5Mp z{8Xy|WUc`VbF5@^U>=%4ME27i2g)oINMJwg)b_i+eNG}sB}DVIWT)yn|Jm>#uBprd z573G4@9tm9COTXUC6ERYh$r8phG<(vn+8$jxqsij9rCWnj%C2k4}T3DqRXGIU44Wo z{$^lZHFWUa;|d^L7;xOM?K~-74Er;G$OMOY@k~n6=_vPu)0~?sOA1bGp`&l&F#A85 zBmZHN%l#9D0U4Yq*Xe*<^xsaF#%BOQq0hr4zi#>Uo-5B1hZMY7c+_{!sUR9Q%KtWI zI$fI9J?nVj)T*kgS|O@r>W8NLK9c4y>`R|GGx8%>LgRRz#pr8j2Dbi+Fe_$t;%fT! zMnF^aLL+iKqCWmci^)!#gHhzPZ9Irx4~@Ol~w} zaVV3Jo_Jt(9b`XT)K@xc-AoX!nKjd;Mdo=nFWjrucQM|SaAXRI;Ow#CN~sHNp4f+{ zUt2+U7hqBaj!(#lM%}E5Bn}zSfT_AI0JH!#R@Bv<0wGV7IyS>`yXVS!;959hsF_2) zP}#u59)eFDms(4ga^N^!Z69u7x`5)>uILK+di}d_5)qr^yEu(27wPzQwqzpxu8xKU zbNi5^f$ppx6Y&iG_o7`xiEOzdDj?%LW)&OUcp$aLqu?1lwEC%TrL${zqCDHM05#p?+zT_YWLOo*Yg1*7bv@b&~Z~2!|x=%0@7W zZy6`(Wvv+RoPT;zDfmLEtQ+0^Db?===-$(%CbM&&E;f5OsFZHzyID?H_(-YdnyqIu zPDJ;yUAz^r9dVt$@h@h&TZ}eZl~EeVK?nPuR(EyZg+%#i?v&!GR(AHn%I=q6X|8?P zYGUr;fr-4%-2S?IHdmgPw2Wy-R$}NjfD|Bf5^WklcnZF~9=n(XEn8yCD zV>n}G^rQ@7YTmNSRK<|4A$zkOT$vT)K{bW$6Mn*~MT zuKiBMDJtFuQm$pp zoM43j=S|xRtEz?u1Dz;<`-a7>A-Qc6W_j?3^0APL>Pl34@B!eW+GHOG)qxk4?DFeP zwD(KR_Z`Ds!lVoL#M$@$X?#C6<{}%*-`2FcKa9!g`A@k38HepOt#l+Df=_o}+2bs%A4e}ZBJl3nswSVE+G-?enzh!nh~xV|B#@LA{l zu$?B~HfE!t*vGk};_(ixQNULOnT|r=Ue||OJg^e5F`T-e%RmJD;DE<@zT2cX|1)(- zK7BKlvTb5^eyRuOx`)s>u29VI$OwT;I|S2NvD#6fSu{?dmxy2vZtj;~3Ea?3^&dk2 zq{%)5l@1aV&t~senT_f$!6Ab3+T2s$#$;I!%AI%F=*ypb8ETxrJ-Dbeqrdv|p%{X_ zg{NAQCux950`t~^Y$SZfvf|=GfN*~Gz z=AFDN`!E{K33mGrHCmU6b)9_46vRE?+}BHj5TJcWtDTRPp_lowC!EP%OdOd$u|+RL zwY4_tI&*WCWN0%n+y`lF5HB7t9FTP`4&R7bncJ7WG&a@XV#avG7~l_ zN>b)2woo<^N#+JKWr)lQnWvDDOl3|&<{^}XWXe3HLX=Dq|GMk>zyJF?o}+q?=Xo96 z`?}Y)*168XrN%T$6-_YVZ$|CYuY0@_y{{5Q%LECq2N^nl$-4eeovs~o76z~GOSDUn z`9OSo{dvrd4@L)PLF;~YoBBTj_z)lqXovWM?R3eQy>wAxizW;NS>Z8S9{`(+vDL#3 z&{?L+W01&M%hF*+&@IT;jARUVo$My-Xi`w^gGp39{mF+L$ZwmS;S6q`!^c}cJ7U?2 z48=+Y7rp`%Cb)&e>lw&UhR9LhYwRiRpQ$iYvk8d(96jhJ$(C(2r&F~N`L@{s53*nf zOm6w^1qK1ULBgxnh#1@}_zDvAr*!mz$^xm4KS1H6p(hy5qT81MP4~Rlz<0P3tDw_{ zl@)*_)QGYQ z^fucwz?=sXCM+xvUe;E3HUJkxysx-IvBW$4;q@wt-B4E76G1|=L}Wd_k9xZ=ti}$e z)_oO1I5Y{0ZEGveVc{wii7s+mG=AZ0OA1J{BORJjP@{)?BRJ;pds0t53G3_A@$J%7wAPbhCfyV9l8%1htyncHCT;7Tj5$w&qpvRN`jG|{T5mp zU?T>MyCOqC&^lqJ;pG>P)J2m5P;!c66&V0fu&1};5BwOd3q2jP1qg}~NmVz$vVgxR z+<_A172YsapsDQX^GVsL67nz+(wV-;^|vh7f~w*F`td;^2rAZBG%yk+egoVP^@8h# z^}}^Qx>^JjjvsVk9Sp<3ngi}NP&-CON4L!C##md1+O!5&KQ<{c3ADU9^5Hjlr}li& zw}VC+%V0|Y7co8DV-Y&A@TzaOpE+GX3>Z!0;69i^5u-xo?*Z}Bc#*B5ft4l2O$tPb z^PXnk;;WP5iW4w7Rq8NOSO}`Q1v`VJ0sp4JIW!cmlioS4r)eqsRC%u<)uv4D_d}8< zyO>|AAK4!x*Io1*RLpW1@<%o)@1HL|J8fWk{SQz*q~n3q|CF-2 zIvtp))=#~QfEy7YE2zk(HfJhFF1T>AN_6Dlxo&>;(j~?rNR|jo!|w}Edb30X3t;(9 zQ|jljUQT(Lp1NauBa*_4e9mKxoBREH|MPT6W}x4e)875z3|vk5^>QZEt^hEiVB0t+ z?gQ`cX%xbDBX7MIv)1KWwQ%-$C@DOMH|F>Gf*y%rN*d+Nv9)0Hn7d5zCt+Yx#(t5Y zUsAX0f`;SiHe>-pZVI2Qz1uzSqJ+34Mo3`M^U#ck48pYeQxJCwVW_Zj7>%B}cuWLA zfJ%{M!xBOJCTD19ND0Q8Ss34@;9>`PEkGn)aP*FXItlfNK?h2(qy2{&q6OS0158U? zwgb9>Hb$TEH9tHfV8zGPi$;h~>aweNU54PY<-{McgIve>34>7yOUd zc=DhT0Y~XL)2@pR`wrp}0)`wFcme|>3s$7B02f1Dl7M#}l!7)M0M>(3jXK~86(%`Q zd%z7F0nRMV@%z>fkeDGgVEF3chM#@V%25IL$+E)WsjO0eNbAmJ#IaspjVtN3;)tceJX3ESomrCxs;wQ%y$4F>tVqeQ~AHZQ_d5_JKOPhB^uQHSh7& z^l^yNz-j2snw+|Oj6h$;Yu$R`8I>M?D1WoW0a>%onXELC@MZ-^19sIL43%IcQiyuY z75o%U+aE0l)VM5qciybz^&R$k_gx2m}V-0A1xH80>*2 z0lw~_tOL5r%RtD8wzUO&U|2IJhr%aNK5ziq6R?Ou2T>qwj`AgCzJqcPo1%8O3wRWL zIkgDzRy3m<&(i)UPadbB3{lkMeN_ZSvIb0m{c=hEx0c{*-HIn>D9d!JYt+e9o8b2l$59&hgP-X_aySd<##oPo{}kYKyFRwi~})BhYuV$oI)Le1Z>bMcg@zSfx~GMx|Dv-I*z z<^ih-C5gz1-N6Y;iTp!jI(8rLDeg?&(pNtmP8j@T5p+VGXyGbwSM==EEQwM%Gv~rg zg=ve3@aVQ97qpfidLU_+PCr95_^!34=9);mi@h7+or6eDxK_@zVKgInYUo=g{F-#F z2699=@D%&*K??}n#8-fk6XS-yp?>*r4S*>J`~}8FXbf4Ip&fvF1Kh=V_nIz}D%htd zhdTf5ycscs%G)0=jLQQ*2u=IF;Kr%olgtA>iQMky3^d_*x~`8VfRq2f*o{g}x^=<7 zo6CdujKHkLv-T;zh@MRo?8(O3;5vKK2@G)aHy~^SE2xKR)?Bn75_)v?b7&Blu(BlR zLp}mY9I_+4N?^KMil~1e69p|(KVWOJ=M?|^TKs+|FevzHsId(BGS<87h1u z%&hK>?kfvUre^Z45uxL1FT3oRz?_g30#!V<9nOMGZ!Q+M~krqFsIQs)u zmLlPgSGx3`hlFA&$({zV2a!<%a{m=5csezH>yAF|ecrZYtxD-vVvQj{H|9ylzJy%i zQr|7X`n8X|8N8kMFOL|(fQjM-V@pd*N`%)fa(BmQi1mSo2xl-1XU#i)K1x+_e}%t~ z!gp9bzU;v5Dl9IJNAeZW2KGH!2g=}Q7f#4n1J##miCA{9sc9TQfcvRJ@(*XflInJo z4n7LdHJ=}cznQTy2R{K`Em)JX!c~X@ch9dpkjnxUl<)4= zy!dsO5r@iv(84j*T_U=bRD`36_-}1_CG}_*oj}dvxVxToJh#suR{bgBP9oJF=$`X? z1W%KDkOmD+Tk-5H)hBDaR+s0$w^z4K_6x~42Ux3`fq(9g?dUsqB=Tv4E<*&c zmWv+lW(&i~n}F!_B_<|9I1828LzciXJHDgA$yl4f7$iXY(4(Bhb;HLYg-Dd!TDF!8|w|Hw3{oMHuD_EXN zyp;lQ(WH=DEjwON`KbZ;Y#XLPpJ+P(qOwQ2?Iu^j&m3qBFKE?21A$GCq*>k${9z^p zT|f}S(9;W@h}`kxL0KY&{WCca%$lLwE_$VMjF3P=Nv|*{-{JmS8)R|2FVcYBFjB)x zqC2OsB}l9M15M%q(d53PwMy?Inho5dY%icb%;=X0RH4p7B#s|<>;L^O0=SK(9KkHk zhn}c#^K@lv#!;Hs9eApJ2*pC0C2%YhwwXmHMTRfy>yHdX`&26AZA`ec`YT}25Erb0 zC^Is-xBhy98oBo6@^JCuS#-PC1%?12%1ikL5&n7?=_~xe?OImSBa!XHG@ll&k#QO8 zyWb&FzNYs(V%(#9SG2v}y}18HuG_+uaPgA@Xn8B|XHD{Apb1974){Gh5UQ^T0em>_ zr}9Txfv=QF0PZIad@_%Gpd^8`}?l-!#VYEN|?_LKTzU5NAd(NhQo zxF2fze@1Cg;8R7C*HS|xhL>Crz}l#lC2ra~CxU($!rxD-k!tDw@m|aB|LZO)sVtvL zC_Ab?;KdZaQo(`iT~1EU;~TxGWCL0lYl+kF3F+nqL4->fa=yZZ3IQi`{}jm5$nU+z ztD}FGlw5wFCG$EPM;oIhF-(vMY3TsUYA?`ebHN9xrWPIwSh2>Kqescs@sfuZN)@&? z>S&aXVLp8Pps1YYWhpy351HmpJvwI7_4%AaMaizee2v<2!qY2Kn{4WBH}L976t;ywPl@ znSD15d{eG=+D^cJKVS*O<=JD7Vzh5t6R};rkU1>i7Wl|E#*T#n9-L(i^849T>J#f= zZ}H&Ziwf`7Jq%2$*vmW{Y3HRz#7DP*Kn8bKRyr>~WO&W30doxS`j4=!*6ECMKTdcj zy$Q1)iZg?r7Ib*4BGwb~u;hXV4*d7`utceS{=7M>7^OmjvK%E7d%+YK$-smfIHIrr z$qAq1_s7839}QuR=9Y)B!GqJa_q(_u5)Cc1@&Dw`PT%bLzhVW%!10lnT_9=MBTBJT{jkU<&-t{ zZB3e)J8Sd$)f;&i!<`sSttdzC7k3s%hdKv!eRN&p+~Px-M#^xP4Aqoe?NbmUy~y;5 zAdYwDw!e)pc<+7Zsq;Hn<9!>6p**CpUTOHGrl8Pv_IQ6Ix_WQ<`$~PbFt<+3f zHH(vzVXtggTp6jD6=Y`4PB>!Kysz!oae~iWAWz|&Aiq?pF=29NRyulq*Cn39q{+FW z(^fv09P{(>^wa{~z(;0Nw*q3O) zzyn*8rIAV|=&t)&Tf4Z?Y@((MC7`QxTYI8SlG|P^M^|KHFeHkElS7XpL^zZV{@GVI zX7+e?e)pne%g`(gYIe0%LKVl)%gZ|%8Rpz}5Q|;8+lcPkHtQ|-1Y<*2z?WpCKj^lR z+*nwy12q`}NtJLNJe^psIsWc;9U}tYJB-gwlrWHSdo_SSU$JW-E?g$cgBer!47oeZ zriV*`QB+;65<;Idc<+ml|K#Vapdil<=Ef=A#O{4I+LK3kb*C?#F<7}h4#|8@BR+IZ zH)y$&bQx<-j^m4!o(ej0kD83l5R#kq3S4~s2 zh~Tq|@CMWAsYTlN8NfFR&vLFbE17o{k%@Dhh!~+) z0WU#n1pYKAGQ7;KUS}rE-wb-K69*#U{G_CCko!Xi^8w9x=ag~we=z`{DTK>VBBP5a zVaMobstrdJkD@NfMKb=B`?V$ZVFcBcl$07DQYh;&|9zhA3hR=!u(xM(4Yc%6WJN!$ zsc&lSc3QHJq5!g~0t+dKoWlqSeUPF;VA*K_>=Pitc%`qh$?@|;D8W1_bIkF+luigq zYttHVSQfCgge4N0k|qI`gQd6lK-`BzWk@9Hw$|D^C5idG{G%=-oc=5^PRe&By8J6; z!^!)<9`GmIt@Qg@LN>G>eF-`EH)4hw=;ILjUhT#_!sD6ARPu)6$ql-^q|#Gt-_zN! zRRbT&#Nq>sct*)x1;j#0;7fHYeLg`j3F1JQHNi)AAtBXeSR{!A$*B=l4a z@LQqJ7gmTlierZHQSYplcvgtPhda|u;C%x($tMP)d_)$IDi>8uW_z}ICg)x@99URe zghi2A>Bwqo0WpX3v+ekuU($%=Pi00Cw)(?lPIlJDcdywpH>^Hvh^#0W@yAt?boh|T zgOGMH7=ndX!)Enh+N&lblJk-X>;84H{*iCW2FD_NnVn~A5VJ}Q=`A+4vl#qZx*N~t z;9k4Pv7}#rL#GwjDw4zLVv%9@zS#VE;6c@CncOUq(YgvBaFuiCzyVc;vz-$x#d6{V z2nQnX4i60>%MalJ1Kkzo9w6^oz!q_q=@($wPkXPK-@g5+KlmYuB zwXE>V+laG8D#&zPPO+)$O@hclFu1W@ao0tVIGrkAwKj7i4hIjBjO@zOGUXvE^e+xL z^#CTn%@zO_sIJlRfpy+djQN+dpKHSx9x1&XaR8d2T3#PBym5ffAa|e9@lh@kE6&Ma z%&zF+zDqI(h!K~z>53{!*BSY8a8|-E1cRZ+DQbWVtJ^Al(8nLP*jKz~vHp}^hLrN^ zjUxxF=|$HLAVGdBeS35Ww)4_zfjJc`avS>9li*U5AVHMWRU2yeHdYk+tm3&I8#@|K zbl^$<(8PRTrj?pGcA~k7lCpr{9JF{JqIm}`2e+ZM_PBzhf<$CBYZzt3M6^?LM^`Ms z0}}ihiVQp9jRR+4INwk!^eRUH($RwY>+bG;4I&AE63Kb03{p}Gj7mNLoB@VRy{Ikq z`}ZFLC}_R_`BgBd70jfGc99?+i6c#W_-%N&fI1K>23iXAn98p-Qe-DI3oC9B!M6lZ zMjCEUb3v)&F@GO*Kt2Y3RY^BiMKJ`nNTuYPt4sss!8)P|B+#v!Z2ArF6V4spSe}Rm zRvc)yVv7zyg9w=}P)mZEln|xVT)|-fj0;WDEJB9?{HwRL8Su81z^p=@F z?Q#P9TDW z0jpv@`n}14yIXNj4uZKW7WN|HhmDn_1|J#?oVvi{6#F&v{!5_YJi0r56toyL${&rtr=Q^KbV z4sz8tz;Tu2WW_*oIfQ?5(o;iFiZUVO@A?qz4*@AE~itWF5`yLX!@RL0YG%u`{ZQyZ0+^4vDm$*zN%T<0_y+JzaFM$xgzh z(=|Kot|YRU>4pf1L`dq!TD%FmJPhfaGw0Y<@PwQJlbRjcm%$N(3C*IS_My3C=0hyx zjo@KM(n=8|YA4yWCShMXBNG2Wcrx?n&9Hh_o5e8$%@KS!v4NKqO!q_QQ{fHrVe|xp zx=bI!G60)|KI!KYw^4~%4isltyTn!8{^z0aYpdIjTZ`}s2uh(Cw8lQUrv-(PM{!hWip8AG~4T{xM@IEpDZw62*^ZFt!GdKYx5EK%jOLhHq_8v znEKl9;1HhFuNmi$h>I^h4=OE5DXIDqNpZ@{Ol%*lW`S1}7&>`b`PTAM5SoFW*IJtR zEIR?3JK%pM9K29>2Fnl@t9oyptb;e0e!i2;sV^u*Y2YBzcXo5>%AQVIjZ7`cui!bM zFqO<>?3U3syef}i_XCEf>qI(5x%f+`+ZHsZ2;%nA!TP!@UBUtqFT7$dsNhRVWTp%0nkFTF~jXgIN5S^FYM<86LFdK}+ zK&B4%jpT^q7OZ4|vULrHM1bnxei?PS2{A(_yg{)Ny|@Q4vp$6iF4MtIElohHMlm{Q z#h}>oT_OGeyU~~g2rB+}!kW zXlwhnBkaag1J_o{lfDS7VQ7m*FK9_NHE*%0sa3hoY0V7Kry={Dr8X*&SuDw){2cR& zbnqKjgWQM6r_ElT?X4+VZ9zR;rL@{AYMXsKuPxX*Ybf8EU@9Re0Z-xp@GjDf`QSFxX6$U z0X}{!cBNd@^Up5rjnv%5*ZXrwwCZ{o-|tQ(0|#6K7w(a?Ap8B1jj_+#xBmT3 z({|aSqi@#Vy#rUOs&DKo>%oX7yVBf|op`^^z2<&*9+&Kxi7YKr{p~BFi9ek-?>Y^c zT)wRHL252BdRE7ij&}1#xTH!;#EGCD&rX_?E)j~Avu(vaIt|}GW^lKcl?SNl%_fzd zc-ET4RPa&)$*jng(iz)cTwH{PK^icPSRq4)GcZmR$_E!{k|Bn~snAI9*#cDBRRlVQ zqvcnHP;Kql#3XcGsH4#XS&Int)RujUA_8m31y)zj+b{1-AKlFoNLsF0t`F~rI_b$a|tX-%Sipkx#pY;`Z9;8<5`#7FM*yYFZ;aNq5MO}?y)=|wQ4fQdJjZj zx|?FSuZN;T$$+w!;c+?n*B#&4N5?lOeAfrbCX=YH{WMPqZEayv^f?q|^;}Ez>X`o^ zu&!&y?F1-;&uMKAvvHT1hi46`n>UvGU(5*-5DUgSa%}%DwkZk^%n~^k)C7IMP&hwh zkCX}~FCSl74C3{{6*7Og{86|V(%VY%dHE<|?@7y--}f~J8?W3|I&3 zWj@}h0E&P{-nk4^xyxbY3`hDjFucHYN>g1Agq*S9y&{~^I_5E<1M`JM8_0QKArUW0 zO^lml&Dad?e6r%etzf1q^jgglZm<98Wc8dSa+uynRJlA=wD zggz~;r*~qRp+7;Cvag@!oEdHtD#;2rmYj8O?$ROhj@_V{&2jq|R5A zcAC8B#j^KVUDtx^QiaA#%g8b4nw=Cy$dJmZn!UkgE(N0-Mx{%3yo9u4-=^;I)IWzy zEIZ*7Q|BxvruYb#(OJ*+h|Bw9C8^pvj>(O2Q-l=>&J^)kG4NSOxQKI&&Q6{5MtF-( z%wLR2_y7t&EyCbBF!sSx;vyS|@d;`oflCjPdQ{=s27^0bdqW!tAN_MLT&xQ3N|4gP|}Ge1Q(@$Y9TCpP!)8Yz<~ z|NhE?F<{a`5vzwHN4Si=oq1(7l*|qymk%A_`=?=jt;l8Yvd7fhL@^kwstT@+IU3=u zAW@4MzMm|Z35M;P@j;IsaakJ+A((}lGf;2kx@~aka3#WR41J=nV&03%S07whg5S{b z1s@Jq*|=R797b1rW`Ty4;KD+o7oJtl_92>L+zhKUzVyUrlH2F^*FFEeUwhjE7?%Zd zsiozJP|ezf%gdi&Thn3Y^W(K(l+{u^rIjJQV!S20F<L4Gs)(o zVRAsD8&h%wtY2+ScbgE(kpvQ&_0KpjE__%P( z<5pxj+PlKX0d>t_zppfvKXXp|+RLY4UL@DuU-ao5iM$Qb5=H3F*kL&G!~H9nZaSWK zJb}=!7}d`#*Gz0XkKVCsyb-?qXMDM?>gCH^xepfXy%M&=zjw~=i>yw zdjSg`#ILZH10>a${{e`y8&71f4{4|cpM7uyC=k<75RSw*EBdA@+&KWpyYNU8JWEp{ z=6Hr~xm9{J4r%%;va-^`)Ca@XkJ!WDmL`#|(WC|hL;`vzk&p9YuGYc0RYD__&am4N zy%URB7_pSZ?TOOiTx0%49IV0Fvjl#2L&;P?Hq z?RQ|zj7RUL9g)uQ;byMW@7zuhe+&b8Xp!l+r0rZ|a#nNYUC)irwvIC=vc2CO|G?i& z+2$!BT$>B-Ps80dg+Bv_)&a37;O|-;9ZRn2c>Zn-X4ockC2;10`yOs3?rH~nd+1Y0 zkn#cdI}BJ+-11srMulemA*C>2fkq+q;ln2&>PAHh5D5s1SGW{&AgQhgWZh(qXa#N9 zu4&lE*gb2Dnr&vF)^CDDa>5}9?9P@8KiD5#Paemg|M!`~BMlEnhXT4Gzr(`$l$*h> zC0=dfc(`m}3^OEQ%yI$jGNls|Yb%%78T_{P3R-?Zz0CQ^osBMs80mvOS zk35p~I1-k1&4`<_Ry&+lhg)Fv_I_s11sA$~LUjTX4V)! zXQ+xG<^u!_CNANFzKfdS5b+o-G^Yp3YSe+KMEd`mS3PBCV7=4`f}m+#ImPYa?r@@7 zNCL~z+Lb`a{zTDQ5~IH0(wpVta@~WIa8^} z1yC@2&rV9@vDYBGn-mMs-sh{sRS6_r9i2Id%b1SvXx=_Rg=O(?+6~!{kXcCa8f>yq z)y^ra2fVGPMk1YdlN#)zX)6tNnjn}@p%ivaYj59bk)Q?6z%(Y01%*)yVUTNl!7mN> zIUE;pKXJR!&{vD#(SQHbX_Djj$pNOH-_*vA88Vj@Ftpa&W+&7;1eXhq-W+EXI=quc z=lyOvf{s0WczFZBQT>AcV^Ft%VwFF#L<0H;@IwH9Mq{aXrw{^-)I)@~+ieuCa_fiy5?x^~yelBJ*9xyQktZhtu875kqQ}<% zAs8M;MNE!l$Did3KI{8{G;Z*Auj)f{hOXL4x$AR-eNr$?!MoL1B4jfSdL@w@n2EDQ zfO?W^SilAsnto+eKHhSo`MjR8P?`o!ErTZAF4wb`&GhA6-k0vT8^whP_I)%UzJWNT ziF#Ks4JL86e`5Te5^SCr%;EHB<(QD^5z4FQBvP7&afQ!IJGDtRG6!kI_7~ zzEHZ{vKo8nWLjLaBhx$ydzXXl`|8CIY7l!3(bSQp6ys=oD&T#|00z*5qCr86X!dKp$^L6e1t!GFY zB`?qb_*F@XR}`(7j#K`&*ZMPIxikz2RFUC`+jx^XZ>VPWb!cC~xFO4=sM&DmO_oU7 zx4>0`(4#NUBT^iou~fqFMMyq3Df$cqx)T}rYPM_r50h3U23e#j$j8I6YT=!)M zQC1vMHAMmIDG+7BUhf(JbE7X%N~$d+8i9Z!cehW zIwrFD_F-Ne?^(ktu~4WW0;2T%fr&=ZA`&~PAL?RqpNkHF)lPcDQ2fOqWd#Z}_zTP+Y-HS8Tc;&aZy9-@78pa;dYIMG_GZHVrft*us3JyG{ zUFy&x%FHjS9*#WkQM z8G|49ZCei?yUG!8yUJ=ZM-W>#H&(dbD(*N-Q!$^i!yqsl^7E&ia%&^Z!XrfX@86H2 zak@koV1xk`fVF^-9E`ebi9}gl-H>RDuqKUWfkH?3e|kk;a~$gF8fsW@%fXz41BA2U z`lz|TqzVaX1PfC_j&;r0{BlM1PE|U13Q}E? zm8yLi`MC7P$shiYn=J;VWRL3H9>dRQQb(NdcNU_u-vy;&OTnSF2W2;CAJ{3Y0gw+@ z2PCK+?u1t{1-6Lh1w@)4GUixN1W@|JVAJ*PT{7%sQRE0zQw7#fARikjGVNR*qson? z>gt#PF{5HIIHG4}MjtVVbfI&F7C$K|DKrs>uAmfl6~O@N7Z^i522eemA4QKY+B7{2 zUx>y12NW&vS$EJ-Qu@4Jv1?ej69@;8X=MsvxCtmz@YZ>igqln>HM$Bh1dL;@2rNe_3SBl2R?NQHkt(_n;Oxf>EL<%jWkniWzDo)8)NzX1aIOng2C= ze^DK5DSMn?wd0wPx?{q{c|M*Hv)~MyJfsnj^fRFtKd|JIa)Ds6esNW`sD!Hb#P2$h zLH0!!Hw&VR*0ji#?v*e4S8@j{^)5e=Y6w1>zUj32m}k3nrCq@351Z?*_+Ed*Z=<6q zGxQHYj&m38{H6@~@sW+%tdl05&8p;JMhwhuggFfJRCkLpbNpd`L&>Rhx67hpVhN)+ zr85NEJ8sF``j+6m)EGb^80>r_9A=MR{d4kjQM~|!!7GQ}0BCSUxwrF)uaTPJ5C4?A zxe?JDv+*Gl-xG8=zQuuypwSy2tx~V$zu(qns&`PBuww&`LSE?&(|USIHpMSLzKtK= z=i8}qagFfOm(uLiWRV&Pv6WD|KE41jg-Z!yCh)Q>};EJiwP;7=KjL$C-X^71PMK&F3_tNxAg zusWf#qK}Y7sYx19)hZadt=V|qtk{)VK=2{VlcJGfiJR}8hjIpgV12yMB$8WItNYr{=bQVK)siksW8UXX4 z69E>-l{wpQfZb{5GVH|K<%wJ9-ZBX6UUP|YIJ5J)`bRG&z7`bg2xSRmV;p!kb<#EBW8#gX zu^p|av4c4YpI*A-ts)*qx5!6I0%`~T_)uo#x)}(+{LTUy*hdoykR0Sgu7{i2g?ZGG>Z?u+PFWf4 z;#c;ooi~71qxKZ_$@Ooeo*mp7*nND!EqlGDdqddx>`q$vkNvSSQ5%9Lp59p^fuy&P z#iwa^x&Dw^w8!VmB@7Ehn@IxsI9-F46>k`CZvFnfZYDpBfZDyP`JFe2}x zPF?s&Ae>)F!reySGdo=05N`z@P*xAPs>zf}236r7@T}!*Zw-faE}(SKWg{*2;V_|t zz7@tbU{>6PSu@_=2RzqYx{H=zM(4}~EAUrd=v0q_9?%|i;AfhT=OlRU{AlOPxheR% z>xK6}=y-A|SLS)EI0F(+0mQDOB9o-ib4)& z;{8J&r1HLts*TrQmMwsp&h*O(i?`_fGnL zFPpg8=d|Y8XSbEvu8%P-*-e z&n3f>MX2*RUg<{O*eljAT6EVaLY=D^J&y;Sx0cV|9uLafUG}@r^ZQ5i@Wgyk`MpRc zYqCjnjxkGr_^`9sw3-DN>%rJFgdE8v<$zvJIz#bVQCCaT%aY@}O>gO<4@(wifkSsJ z02CigqDR|Z7M~G~Z5}7Mdf|M}!1xI~TKJjaLYFi%i-uCh3@fw@C|dAx(KDS&q=O`1 zetxLj&kPGVUxbY~HH>!8(QtdN4A44HbAYd}O8UHJA8s+FK7~v#HP==G zuZfgB@>#e@m4dwD@(lMsdE#c$lNWpPn`6Rz@(L?U(L(_XMNXT}g&5xb?Ci3BTi`1% zcC_vnDOHfjcrI2V*RUu4<37%t*JghOf3Ue_YN$z#$72jN(NcupPeny@HCCa^qTC;NdSiR^nw=Q?ellSqK>)sTP;!wv(RbIE&1q(UgHw49xgJp z3a%_Tt1?lv$k6vGENpLzMi~!L`r~;2?Tk`*mD-eIl%=*EcWNef1~;$l{#I;sHW$BAsVsbn)_1Yp zcTt^4?&&PGLQ7RkI#BI(>WfdeKktZP4M498XlGuZi#1gNAs8#;_8I+Y z(H&-@n2~AZ*Ya+K`ynAzA574|R5i8tKY*Vao2@E^DYj$(z+rS_iCszL z7X=@N*aa50Hhk^&*m7IW*$1ugrCN19ejIb%qT*J60AT`IolFUF_8lST{GF zp43q%0c%Mn65CZz)3DxoZqi$EGx}Z$CLqgm>>G^H^?;~ukIGJLy)xi&nkU@Q(yV+XEU%)?jBl4|e5Mn%?Z6Bcj{v{+}Lg z-rJkxnRMD)>1OmZ`njf08VV>x=eFuChlzCuJD5o3WTLvv5}%AudYt38EYYURaBgHU zU_Y7KRw)u5fo*1H87g`|>CQAmW4~WrdEmFjjzrhtP5>M7fJvAJ&4!c?JfZWcxd76J zy@BwTg^uulV-Luc9Gsj0O5`sVcm(JUa1ntw1kd1C$WfoBr(;0Q|MoO5jiD7!!AGgE z`y)Ci`q5yykG8c);Mm^<;a{d3nbTFUgr44R;Q$&CI8>~^E%6l3H@Ms6hWj}~K0e87 zCGmwZ6G>pNCwsUc>$x(t7nt$qOUcLt`}yQS4WdPh&8Pc>(B7Z2K8*c^u9PsPgGh7ZrWCfEmr zdXm;DSKzPeL)(B3fRH8%L-L3bAZ(g_AGyv0E%WjbG{6q2g6MYywN2NZ3Y8*)`LX62W8@o%x@xy}E=7k&9J4q;DQ8-KoXi1UY$ zSk6T%70yxN9I2ot-p{Od{I3puV0tR35^CFckOlTdO7o}a9L_&_#+QDIUTNye&Z=J+ z&t8v}dp51V|KLJ%6&G$Fvbh3sFU!2XSn#8D;hb;7Ki9$Qo+^8wWm)pow<15`gT!VT zDLjMS%soUvac4_1RZQ~OqaqRQgq6Asjj8^)SN5PRr)N%q-FlV?I20V@hdVm0zeU;y zkJtixEEroH_rmmuKJ49qkc=3V42FfGtg;BnkM`1E!Ok7H+c|)~m|VI9!d}!!KG^_$ z4`}&Tes&&3D?_VRH8^F5`cAR?k`dz;Z){a@#F0OqLeIhE(w%3_?#eLV72Q2L_~*u~ zmZ{VEGLZcJ8h5 zxO9Iwc{)you=Z+CbhC1cLUD!S==YJzlFFAa_YXJ8&Yv%3v9uHyIn%#iz?fAJcO78# zPP=ps!ki;_ud>49Cd%N14?|YLKZ=C(a7(0{o`Te@ECMIbs#V$3A-Nz1ppcr8$pxbZ z-v%beuG!B_etr;lN{&D&gbRV08SJN+(H-_Rx%+v;_ACV=P#WrHxRx8CJT43f2RFim z8v?{SSW0@O&jiqLXUaq|tM|4h{Uv<)`yb>JLE&ICc9lt6qJN1XOewH))XD2NVv8W^ z8;5olHT?EB{OsK0W;ZPUG|^JAlQfukn!~J@ok?z`@f&I%?*wMc&*B8%XlBl3`_KtV zIZ0wHe$e|}7HGoY=jVyOb~}g?ASEz?l|mxqr{Uoy&{x80 zi4lz(dvwZ;8pNp3Qbb7JT&~+dlP(iT0)kXxJ^!eOWQ`h%zhOf*UC6(V_h~Vuqx^94 ze=!WKH|xI`1sQ3@t?YP^RxIJL~21ZEx3R=ic5<`{onH-Q$%>Q5ZK0@$8|IYVk)s*%-Y@On z(7b=l%YVRW8}GGP;foa$O4h`xTuZ;l#xgp|7u=&oaERz7X-UcQY@On^=dSOJL5f!GK9 zHwZ8}07TEr5bOYs6)2bq5AD*3Gc2=x*2^)aj=%6~M}9`po|Db5=_IVnTte{Kkta?{j7yq-<& ztn+VHIpMM^G0~F6&|y5wcd8K89*CbiAtm@W2lu1i80kYSkyHNU^Jbomd!H+PxiYp# z*?)vw-NUgTaf&X~B2Xy@Pv0^;AMxkCI#}HT?Uu*a7ls{3NZ#SZD7pnMDBpQ*c{pAr zdTg0wu(`!-VyCL+c-p`Dh`u?~t+wQf7D1vV%q-GOF9R=5Th-bGBhZup^43~%iHZsy z(ewb8j}i`-sv0!P@UJG{(IUVdFqK9F2w^R&f`No_N`JVa7(9+zz;S~2wAidpOIrj* z-KXBmE@y*B$qf7{sGy*s2ktz8s{SyGC0B z=kHWU7ed@mpP*5^x=kCOQ5wk){1r?y2kdCbS}W**(OSsUh8L0s11P(l$v-nEeW01m z%S9tYfGGlZ08p}FA_OSm$d&pCDENk|wGb%+USqJwc~M$uRsUTzc+{<5*DbGJy*k)m1FF)I zr6@}KV*!$QdWaS6I5xW56dc0k+{kFZavRI0LT!ArQGAnujXLDL1!9o*O(}=goX%gx zV^wOmGjA8OH^28IIJ7&mCfj{=p7~wDg_OH%-`FWN zmMQ)UD?*66{4AkE0js@5SZ(nmLYI#Q-iAQSg_fyDF0C_x{oU>Arjbq*CLFe7fI}9^@C5&*$S;T9@y9+gLf+utp=}wmw>%6R#Oy zPu;Zg?Ub3M@#g6mT=Dt_8svL!;@05hKS%wxI?LG8iB=mkN&6fk0)RLv&2%)rxia(` zk~)8{!bbaUYI2{b$od0z#IF9tppJrSW3A_&EC7QQ;Km2$W<;*dzhAuiylQzHdO zLF{+E2&gbn?||3?oWw`ZDG*47wYYsd6=p5?2Xe-N!ERknaE5?sIFlFqLq_I73w`q+ zd_|6c*-RK%fy50QK&ifayIzoP zB0mok4e&A%C3sgQ9p?a*Mj0o4KjqlL!k8{dOyiC4QMhz|x~D7Z=zqI;y5l+h`r9w! zWNzX{mEOqd7?)uF<1xw>%+6yxv`U|NJAaEj5X(O@N}Wk(PSLRCv@5>bRkFvP=Cgjb z>iHN?&WQxIY@GJv$6+ySzZo`qle0Iccy_1ymc6>Y-NF3kp&&6!{t$U&EX@n{GKqkW zp4x~1!O_p+V(;tjqOl-&P|VD8Ub-*4 zIx2jSOeq~e-TNSPKraB^TiCirNCMv8fmelPC}pFOevH#s8Rtpla;<0Yu!2ndG{iQz ziW8yK{ZpV+E!S_4{yN-wCNw-V7bQRaM}K;_zy4TYB5vkcC{ehsHm%{Ej4{M)b=3My zEN?KYx3o-~OCS>TbnjLk;YMiyb@f8( zWS6fQ9Dv?L1F_zGcf8>q1mc~Wda$dwXJc)4h%MXlHKq9r<=ly6dw> zOf+~wkXrcF4d?w#+WCTO&orx3tc>mux>eOo2sROt*5cg3V{{CLCNhCd-T5m-+Lw+! z5?=9}r)p!g)4yNfKA4m6c`l_8F{cg+c(Xcs;tn$DLzh=vx?k$;s*h1|)FD@3asamr z6(tNVES(;geyBtKmtq2N#;^At^{ht4rW|_uKHu~+ntPvUJQbmX9~SLoWgZ4nNd2)7 zf0!=_;5_`o%hOTx&&)WPVz`<UM zpXv(M`%L05Xu@;_#|;Ii%1@@r^c0KGVfX-U=m6?HnZJ0=jnxB+a`t+(?nj)+uhTub zC1Xjm_?ss!LRs>QfP?gT<0|(2cav9qe)_dfJ4^)M8{cD%%8mikQ2`+PN1jP%zY=?( zcaU5$e%k3zQN!Bbr@9OJmxMkkaT$R?r=g;2J%(N98|_wCRE}2HsUEaSyQON^rNh~V zZ`sc{*xDo-`eUPoG6(#^XZo`QB7s0#?JXoB6W@$iZNmd?L<&zI!O)WpK!11^5DnoO z2_2?KtPY04&v3rZ>?F`rse{Pi+6JnR0f_Se+lFfz2z;;v1fd}CEYLJz+j1gIs}LRb z?j5?OrR6IHkCKL+&W1&MNU3CaXjUly1#aio2}weZzA2)5;x$N7-o)tq<(m8>n^ZFD zO)(l6a!4vfP8mJ;E!^B?>t=n&=l)Ex_(7QOlC(fARlU_N-#;TtUoZp!jCRT3eI~Bc zA1`PXjSQN_{|b<>kEZm$|KKE9_LQlDIs5bX2*{y7PlO#d+6>9?!>QDQ4Zw!N-SYWC zEFnxL-1Kf^Oq!?Li!ZMJ0?5vzhE)$;bcc+N-8K*RCdozrWNMk}AG@}k-p?qo#Y)l= z&zaqdNFcfG3ne|9ECgc63#YC1i`e?{qWts|5LKHT3v1 z3qgYelGID2IaNO;!ncG3m^o%4%7_O*YYST-3~N(fGLsgC2+=CU27riD5XVmWca0IymE&v8(FS)$7#6wA<7DxNk5t>oI3W zM3b}q&S#1OMQBuZ&+WcZ+?qx|kIQCeM+iAD&KY>3%+}3YCnu6WD4!(=KLfApyNRrY zfs@|+{JxRPVI5s3bxljB1K-d(f$){B@VR*>Ttw9VWmCy_muyH{a4z6QW+)H==LQ!; zD%KJRjR1&nTT(|KC}WeUw&3a>YXt^}0{qSW1x8`fc`)1|jna2e+l9-Az;_2|Q);Nm zupo*KL$M;V2;Xol-lQxLDWrH%>){V&$nUt(4K!}b}T$6G-al2D$e8Lw`Csnr9o)bqn{rz*OCPhB)+~e?HC391I3QN%m zaYFb|8ymi`-aL>zJ+*lv2_%u?oyP=%ok3xCQ6wic?Ec|S`gv06H=u62QBx0lUF4YR zV0@nq0~$O=l%NN1wr-v(sH8xw({oJ<{1ncE(i)5xBCPdGLuP=>g5L17e3=Q&=qCL+ z0eGY!-O}XQ9%^^Y&;2L(Rr<#`8-KBKfhpeXAkW7YDU@^B(C^VOI9l5BQNvCM0?>qMev5--)A+ue+Az-0QLXExW~jH|s& z4EOQBxho=VSUkC~{0C9^{bPc2SNO+y;nhmo5aPlKbr2(NoF4ryc70E9dBM2RUnloZE$E4 z=MM>b(1oV!c3%f>#J`$yJFPTLzhS=i2!tuo^Wz3L)OD|yRkRX2y)`AjZp~PHH(2kg z8+UYR)*2JzQzfgkv+?7Wmg-5ZllBt0X~z@%f8q zjlW@TCq@t~j(>;0g}S-mbb_52%(@`)5Y}MeMUUBp;`8He+GDDz{i*FCc+GzRD;8dA z6O$MA*#W1(+>}?%)>~kCfe3YQFnD|gH3PZjFO~vME6E}T^#6Mv87&>kgFG(3{^#-e z!JXbxT6~xj?TFLmfTJ9=wq4j*9;`qtS4LJAAD7~rNmiq2OR-?88UiuOk*ZcNpp`n0 z!GB0iUIu(UC*ai+RzWePw{P08btvgyn)XMe#fiI67q6uK^y11NZoKH5Q`4;>gG;R!o!{oTY%7M%!j!i00$$ ziXqQu6c2&L2$1VZIT8DLaUKlUVY>vlEL)Q04Y=!*7#%W(zyt^1VmyEq6#UgdLnnC` zdLiUUgLE}Y)Z?tI0uUO3LKz=v!S6S1K0{vpzbbQyF7$fhl(5`*xD1Y@n0HD-kb z|I_3CeU_z}wA_ymw^!ei^XK1{M&wusa|k~eq(G-_9pV&#FHqwRlrntO&K=Go44kY$ zXpK0pVKzw;l6 z;}D_@TS~>@txSCZH zF}l{xUrbqKni{hhnV#uU;eI};a6`q;Ld?$YzyS6775FOY&TPrta_Zb5#kSTV%Uz^s z^1X_Tt3mt>2j2_x(iB>J=$OC;b=$}1OpDlYR6;)rNm5r8gH3_|GLzyAvcIfm`}i6+ z#Jr$Gc+c>E9%8Yz(yEpGbl|*$M+!#CK3Uz1vv+-)?6tux@mn(-=ox2hKnD4=uT9SC zR&pDz1nfjiDhglrTF)>YoY}Z?A1~9ZVrpvY+_cxEvw=GW!Q9;Kou;7QPek$m2~kw; zoFu>(+eP&*kIhaW^fh-(ALJxZ9k-|B?`honQ^pzh`fA(6mERV}OF@Sb2?5JC{8Q`k z_nn$|<{nhvc*zYRrdK+{`$N`5&|6VgU%Q}tUzcgH1?kz+@@fvwk~6Y<1SDuob(F0wRi6|e+4rSK3a;+y`Rox zwyQS;d>nYS`l@dswv=Ac^46^`%&<%p{`fNut2lRso_VVt0Qsh5AMkwb*ya*L2nYWs z>b02x2|n6qfdB1L@9R{sWFx%aob_OJb||8`FEYuByD#)Hy)1^?5cbYQh>qhP|1R)v z;0G{t)U{#uqG}9wbb;7w8L~1jLP=onQqg-jfljG0E|ChBYu4kRt2-koaMUl!kNSPH zkZ1P#Z>iuPG>HR2RI=Mqnscr`Je`@mV#5@*ye7^V)N}Jvnxj68T_MrKFN23)Vi4Bb zBa6V@g(0}?890>(E@YWUwtJHnZ0XW++lH9kQf5_9o@kD$4%`u8f2tBven5^Q65{u_ z>#EJL9`dykQp1C<=)EAh%dzEL?(}Mkcw~hzvz9R>F#&iVzIYB43dDxOQ48jBICp*#0{SQxyD=vd4>Rn!q9p&$9?aCYvA4}?G;bCvvxBI`On6e1?ZevsZM$v8m`5S$AvuxwQMrruHtGHo zrz{0DTf?l@w~NWUm)&ObC1ti|5)6|So2; zd`dJ-4g5g+K6+LW_@rY=_&_Ouhj1Z7_Aw7E$GJZ22_E3WS@{A?*`?KhRlibj(BFew zB_NgwkwPLHFFs0~fv&D%V4it0T91Zg7kF;8!F!*F8*xuPmr(>SE?#{x@ccUaZ zG)5P;POy@LAsIIL=F4F`I)FAX;(-GeW@jf3*qiyZs!`YmAK%Yor;vD0=M$x3~#+==Y*^7DDeey@K}qWOrB1$eLsAh$wFMpYLs z3QlFo|Jh7slpCho)eo2-Hjra@K}z;7_75y2WaCzvqS2OL-*x!=TtdsLrPX?LhE&z_1 z5vJ4rXHoxI3R5lId`C}F=jw55w#7mGYSx&+nAfX{r{tJ?T5|fEp@iSo+G-MU;^#UCkI&m|-(8vVmJYmeW#z1q#6e|}YV3G5I`AjijejTT z<1ep|hSN9 zYESU9IuS(n-!Ge#N9#aQ*;|Wi3o?@=o26rKGH#=pwcS7E^MsMeM5ES7nbgYvIw{@7 zxpp>YFO0O9uF2yogBl1C0nDcE!+=80cL0N$+vAsbmhh&WXu3fks+G)hvZP$_iT7=E ziSB^|8D46_mWYF?!2Okuya>G~7ZnN66W?VL=AiY57kp<}?obEdf$|t4uFzC^0Ebp_ z2UH_;l=0}|D9P~0d5{ty{pSMBG1ZB%>F*R;1Fz%)QjYC?S(N2R&2*l&U_{t?yn92B zn$An8SpyjWs@p9RJ$y9r9ei5oYYlw|kY!AvZfM#~0wi?m^z+Y4e?XJr_V^huM^EH1 zU`txo$VIUjACy&OtZUBTv&#lPumBu59(6q&^|5)!$w{bDJ8{rQT)HKBTp6?*b-XJX zq%3Myd*D%&r!9|jAmmMAR3sDNOw#RhH@(5dq$-Hj&aq|b&R4$X4tJ53R&jXj3xQ;E zt&4ivIHp21a&At$yzpRJcVXR(e`K(E>T_zHkTF2l}GHqO`nSA^3noU_%)h9Ec$&L$Zg6|pN)6a@a zN;(xup}$m1&MWJq(7ypz_=Xm&OZQBlg|y{%wq%_pG>^Rx=|Y=(@fZ%%pZ;~v@$kcee<`#5O;B<4qzc6TwiFX{$bhk?q&rI{3_`oo;Lg`6 z(bvdYyrBn1pfi-jFeL>q{)$>G%+9>(HQ-}Lwrfy(zXjNNJj=yUP!w7LsUIdKwH`iz zFE;#xoH-ye>jc{|4E$D6Dcb6!s{ zK0j_=EloQ|J3lWrLXa2Nf$M{zgtlNrGM8Xl+RdcI1p#`&WcOk&I#pUNp76NTSU_5m ziRT${U z$RXYa2*{Y6|IXR~>hs;c{5xxKesj0d7jg=YWaVZMwaN7r@LQFl)8)DLWA=VuHPgcG5{DsI}d_i z;C?`_3FZvgiX-~*=zok$l27_>U|9mg4;eYZB3Qp@p@JWDERgen#7{w*KumO5S(&`C zH0 zxPu?s4JHk*7eI&~A>*8ajRjdL$YyH~VRa8wvpU?6K#AXT&Gkkg9j^q5E7uI%8_qtW=89cEyUd=&_2TyXmHLU#6Hi93eIvd`&i%NGQzWj6 z5+8%fSLb|4r%ldT1(eaG)a39{9y~SPuMt6o;q)0*Yu7e7LKzjQBgoI|=A#L6K7BZn z(3PW16T@NA@`;?c@fk_Gg5x-IHbW-}O5WVRnfNh}OiYDS4X0tOm?Cb>j3-ebMr%Cz zLDMFV51&kthbKHd5hs6^(-uGHIR_Eh87v(c9%qzk3_ZSk9$`2gmM4N%TMa|o4O#I_ z`Q@=g6^gmx>O;zfYCY%m1s|qqCndTIr^a%_IDji%B0iN7C%_vXZOwbVoL+*DNhK+o zw^t_Cj_@A=KDu5tEN`$HzP5Z}Po!UuxI{+)Q@Cbuo*JI+x=HiqzLJDebJOYUm2G1; zZW0u1K&R&BtoNa}s@uC~v3>9I`&*JlBX_!9@#K2dmk@`6Un4@Sivw1h%})h5+#6vbHc-?huZ_?a`_4G1J9)q7w4Idy@-T)h z)1mbhS+j=nqR)+nbD5Y~d*mj5sNJWoZD4D33pVja=}%zfaq(0`HYF;hps?JF3f4sM zyd_r`(mAz*{|G&yM2dpeJOc!Uupxpc1V+qcoTi%}VZekX4S}I2s&;fn9O^T5!SMnb z`~CmpJH*-R0JxTJk~M|#|J5G&#z_Yu1^7;H_5t>GiJ2P*;$%8^bI8DGJcP-|AXE#U zwXZG-PkA9^@@*VB^S5sPqZTpJl+xSeDCo^Lu8>$P#N|du_wY_SmVm^`6ZJBPNLRmT zWEl#$eYxK`G=~YAL3_iG@Rt1^*2kivK?=O>iGT~Y2b+H9>(h5j!{wK)8KXw_2_ zAfGIrah@ZBwm_hYi_0pG4u=8GJ11d}JkE&JriWXQFptIjTg|?{@ou9qxkme9`{3nw zWWlH;S`?RKSTvVaTmlsoBn5MP{yK zF%>myTaN#wAi z6rh*Kqvue3#l<-y_JccFTdgoJmXM2=Fg3M2l`ED59&Rk2b|Owt87JSRC_tLVmn6`s zSjZFG=gyO?+Em{VQA=(Zl_4yOxy7a7+vA2S5TvUR=vdDR*&M}RrZlt5Va0ps}S(N5FyQ; zf^xBxd;Qchw|y{Xt%PIBqg}K-m1xi=hT^PAb`2F9m}IOoNl5H`OA|ijPaG~yP4i2F zq?edpC8@XK-S~V0+`|Q+QM;agwkB)ccV32%3omxHiF( z8~O9kC1~$%1EUVPmCxzpVvtK3z!fKxA(kuNi6Bt>&rK5@X#t*3Qz;^Y zhSCambSu`-SknI~RNUyz^{Ye|s1Ikr{?Z?ld(&QdZ`71xFpu#I7Anxpl_+ytMLdU@t zyc>%|rlD;>-C(@5A?@ETeNc%QIprQ06#i3Ykim=c-v+=RI|RGAD35$a z+_~Y4qHVg=Nli?IvRX{JvUVE(!vv)WgO?nYT$Y;@s&qD_lA>p{_beZ-Az+y;PRRDk z^$_A<%HZEi_Fv`33e<1Y(m8#+In<>jKt?&ju84;plO3DGLd2CnN%=;9;n*nkm@|(z zFz%+;1!HFB-xt4JAU>PNNvcd7`uu`}vw$SWZD-Q9V3dsqO7Zq>`F6$(p6KX2&Js=@ zc^|99yqF~Vyk3?n)Au4oMV>p-9x%tWIG_lc6)g@r91A-1(qgQIUc&#!P(Jv$!b`}t zaS+Y+#2?MiGGm8Z+YV!AKECHF`)H_7FUw2Hg0*#;u;SFiBw_LzZ?}GuBL3RQR1;ay zfb24<3zx05Q*_?t2^~8-_nnny`S+-Og|H;B!5n{x!TS5Tdebi0;+-H+px&9VWgMjr zorA2yPhFm^$0{eHAdpdMI%HJL;luJ9I#D>$;AepTTRV}8ijk<{k zmZ>*_{G2Q96l8k_QtRaSaT;?|vt?_(mp94ms9UVcos zdoYwS4A%$L#=RI_q|f+en-MUGo3@g^uqypUUAlqqSK#BlRNy#_nje+con=IYXB`}k zNpO}rE6omSulY|f8%+B!{q=6ZRy03S)!x}8J!(g;Ad-~Rilo{&2R=L_h1rNZLxw3NbV>c` zGxywOBc1<@(N!a1VH^#c0J!W%Yi6VMTvou0kEmmjM`n8;0Vp6CU|m7=0VIt93Uf$L zYKQ+1(I+4$Aw+@W{i271l~u_2hE+53Z&0A0=&i%UdA(26c(Ggvr9+odWoJ<6e?}9| zxpSbVK=6s?9qw^5@xTO%?lG&D>_SYb2uiKItV}F7k%J4`(+b;Q5iG(c**KQv0X^U&X1^0# zJ$m+dGw5h=^5~=7o~qnFgmK!Q>#r!?CM7K=u~Nu-rGVce9WX3?*!3o0^3CBcjAN)( zv{J3S^UZEwWf7*}9Pbvb8twD_*Q)fAs@EF7Povk2RkWHKCPH(^o19wmn*>h^O`GqQ z(J#>*Pg4dXw7&TcVI-Paz#^fTUV7efv8YM^WBJR|QE=UMf&MeBL%f6EeYXkj7-H(AKxA9AhOpQ-)1dj;|nB;X+1kVb|)+uB;3yb$2hK+6ABy!_W(W_31R=)k6L& z69y^aU0ep-Y`XjU$U)jsu2>AlEx29)atxPqID2#J`|ElH zf3M>n&>O&=a;bUtKb4qwXQI_<5Zd`)h#{Brn*-nIOZUmpm(*@=)qeuP6B4hWr^-B2tt6 zEoA+EmfWABYFHj|NY*~(f8j}V73()9bH~u~Rc91qld>79RvgW8!#&5#DB&Gkb!x@T z#I@sl$KNd)yT+NE^L4G>tVBxZ>$a}WHjeeYXMVhKv@p5T5a^|llPZ`iAh^7^J$7~D zBEaOn(=d8jZ1~;b8qy|bRnf8{8K2rpB#u756_NVur(aHLANT=2Ne9li+uvv4DWyWj zboCqMu$`#{@xuxf5_<3xp!`VfbT=(a4p!nQ;d;Jy^!?Z6xs~>|$@`salGlTpD+1c4 zyC?Sj)*QJLV$}Ah#gEL_JVBzdQghm?$!u_UKgKbZY@4kMU%u6c$=K26*d>Bi(X*aJ zZt)$N{>`0fcIxflpBUnu*0FG%zz!PJ=gyh{vW1cUBP>9VL6n*A@YBUN^$cJ;7V|w&2A-#QR6V_vk}f`Zb>p z^iNLa`S8&*%o9d6XO)jpMN-kZh^;V4vn5$AUzrcPzx~;H$9i_f^{P~lbPZo6=%u2O zucaC~u0<{}-L8hnX;!?Jxw*ML;MXUmK+N+G06GlG#6z%K-J$=%Rgdgeet{iHa!&GQ zOqh6_+8O5$YieAohTw$WKlizNf?v#EBAki(;P6imhblCY6vuum$HY5z$7b6>m(?fM zx4+`}s@~VS^}DUUUHOGfg5})uOS!Co-Z1$usG1|1(K)>9Xqlp@5)5nkMS=Vlg$xwS#a4r> zjk_>FV?RWk8S#O~+d;>l+4sxY_xC}z98?7%Cw2L-i>|xzQl}6?z`&ND2|9!#q^8zS z)Bdxtuu#`(c@sB$SBymm+qsKcmI!{|`N7z;iBPP{jP$a+_UNMMc&61MOIzjhwLqpC zy^s>NU_I|Ls^CevhHZ~c@35qgM;f9!ZNIK?sxnCQnsjGPM`WH!OweSjpLU!|3J{ac zu4xk>g{NQ^}{ zB~Q~x`+>;G{P0Ki(T~A^-F}PLa7ZTcV85>#?6Yq5DsMDd{Hp){eo2CV`AFhuwdI%e z80nmyZW&Qm9G%#?7j48|cc@Diw&KKvq9{InVN zWpmZO?lB&$>Az*!8m)Iuh+zLYU>jDVW5E%%VRD5U9w{);(Xs>gZ0()oAn0)sdLA%| z{5un(K_UklU3nZ5-vrYtQa%od);Z_7wQO_|#;FoWVit@Dc(GhEt?*m{7?hv( zS5Sir^ zh@n#fKA#CybzAPJ@kB%XJ2ZC*YsXqkxd1r;NIyJ#Uj#+%1^auzSY%)b_2jAb`1E>k zZOPd2wdlf4a?^fuj%_0!OWCZ|8GF^Wn)oEn8+QVQTBnoB@oFcfkE9;DZkx{x{+Nue z8cj)Ob-23zCSsd+)jr54Yj9F(D(EeUUU;zIz3?m#*X8r)VE7M|N5pmorayg zdjC(py7jmv>D+|YYdqFcvIWyL_X~83Z96M$Fu73`cLW&2j_h7Dy3 z{SEAVkx+v_#Y&X#cb{KBRY<}@IJsb1O-bio-yKa9zNA(u`~pZ!#wBMdH$6Z{e~}lc zQ4(;d1N;CqE-&-`BBp!vlZHTv=XlGZ+Bn{DZ(i=mCga&N-jWOO1OdxG0zP<@zK;4U z?lkQ=8}@xPY-{f2bv=$rPxyajy)1^>%hSs?}`8ohyq?sThZcODh^l| zUjDGSccbDW-3@ope{O;(3MLW&!}bHkn>(Y5;GpN3?sDi3G=^pAFeUeFNlM$yuYNE3 z1VC)%aDmt_BZkbuw;Qg}GIfhb(U6NWD@`2saZ$9cwi6Nw@%bmW?G1lz$s}pmYUCrf z@@V|=-k-!}l*6euZ36|@+&AZC=36l7sw4(b&o9{Xh_gayeP=v_!r@Yd4N!CgOc=fc$Xul*4x zshB0TMNrcMZ-!P80hOrB*Ui7MP&H;Gip>p1aKg3It=_CZG>rdKDE}RtM7C>4pIT#T zm_9z7K5gs>{zZb{b%Oynpm}+jg zdm#v&=g(_Yx{r_*VXkl`_*Xx$m-L`w*SAwt|Kvl6zaP@W&AMzbAcpxKHBjLjl9w8( z$7KFcz+hFPd?porC1B{iD_(20Fx}YC5XU>@_WQv4t*3IS%N1ZL578nD=j56zpc%-w z)DG8URlmEVOfI)gmLAwVsKIqEGjvkc5DPkwif)lR)y7{o6aa441?dxrg0L0@>+UcS zf#wB4Q-cZ!VQT%=Lv(>L0IvlJZ4YmOpNQq>?HJDfwjeySZ zUjGCO83F?_gl7WKA9vnN@`Te$B~3G`W;shyX^4%9XW+3tD@B$YM<#9Ml9sETY@t+zW;;v$A1Xs2?7F- z%a`MleEfN1Qis-_PZ^}|1WDEpJ|ibK_v#xzvbJuIYX-NNFFezW*+GH6?(XG>S=$YZ zlBY$@uj~R{$7c`5)+GQ*P~U9XWrdCW1Qey;&F+7#c8*Iz2qGG|80bpGW9I0h(WOp* zqFKGC$+Bc~|0&y#iFs&NM{$r@vHuB!xspa##8>P4iE7UMy@d6FUCeER!+&MyTAB$G zgsq4ox3DDH;k1g61!Bop1FFZeBr9C5|8v`h($44>7=pnHY9d?3Yh9%sTdWa&B{_6S z4X;J-fdtk{gdHSC;1u~)+m;}LwF0_JC?wEAPT;~1_#8laPDm-~ci`u;iwXwrgt3uP z>&bdlygWXYEG8l7U>;_x(#713WEGeGcW%apU^ssFa3_#b-bqdBeU_2Y*Yson3l)Ie}xWTB> zQ=tyL>Udgse3P>(;{ZV&SkjS4*wCQneC*>;zrqo}x7aZU%{JovleRyakodUA)Yk(4#V znQP{8#)=if+}WvX;B+V+09F-TEh$Lm52)9HFG8;f(MlZDgSHjcC(NM;PmJY=4MI&u zQaxZAy0Bme9|JxhspIny)(}t{q3ZyhM6$LbE(ZQ-?br=)PIYYZb6vreSKM~F)(!D@ zX>!H?pAC3>8`X3E2!W}8`<}8l^>Dg^^>Yr;bKcwa(;BDGnYt})X{P%e!LSV+9H*7T zfeDF10U)f$D=ym>!b0H*d(8*XtvWFc(dS8q_^u+Hd8xU={n3;15V8RoE@zn3jiVi3 zC~pw^9b`ZVZu?~>8uG)UU*-ZiRkGe8RwL(Wc6hG;s!IwRVXA4wufc|IX9ly^R(N4F zD;#eFb7Qc}zH~}MqxVfX)5j3~*9hc_RLushwIY8PI7bpa36MQdxY%0Nd4 z_k9fHg(xe7?JznTD)ExnuR*f()@FR=&2&6)wn#a};N*rng$0^OIJ6;^dbTi_1@GN# z!_(_@Ds+Fz*K-BC-An5Q38gKXf8W`^WDtvmFfB&T*xV$+A!rnQL6F@6Oo?Zg?%|Nl z%Q@3p4)8+|icyX}&CCp=#fQZ(6Vhb@EgHrGC=}cr0IE=_GriS&9_msQJb%DLt$~gP zzEBYToY%PcNKwpc1|t|pHIWKV67ZrK@e*V5O(~)unJIu^C@dVsQQX&N$Fx(O0vMQ4 zVFwOU26!quq+V}HR>DN4MRxi#gPMDG@D1XUn^TBVUxcJR3fGDCWOsFYp`>h-m zTj-@Pkbs>_Y-;diGv9_-z8yTBHED?RQnhSqT0LN<2S_pfn;uEuk1Ek%5PJe+z) z1sG7nPEvnq(Er8ufmhKK3Dxcd3K$*;0926BwoqvOVEyG3NV78CoSl~n3GuCMZK0L^ z$Ps!IX9dv^6~dk(>_6R#? z6IVait(T%44(Iq=@AX_H8v+E6zi^yL${ZbC44nIrEs1&#TP~P6!xMDd#zqMa2~>M= z?6nu12+5u&hP?o5l+GD%15ubb3|!M76uyChM+>Bo%E~@jHdic%U!AQbl1JNsys1lv zBeBt=H!VT^tebvB)wk&Bj_2NMmP`z>!>12F;Mm5+jqv;;rsz46M;N9m&fOfoMI5|z zBY=oVvvM`)t2+7Asmr1P`NizgHY!hk@6}e{atd@Qck53m^uA`^ec?fL8Ns~S@ODN} z>ETlI_n?9GhL}cKb_NEU&Gkd?a}g9@So$$J<-4k%;5TQ9@0D&}s@T870^`qYo^FSx`M~13H~zr;>F)r_6I<)wFa+jP^IJ4>FGJfU zcMGb$nDV#6jgiQ1B->_oEMWut=0rU2BKB^D9rPyf7!jrb=pU-slfrQesl9#{lb54y@6UfTDaYig!D<4KSlxy5n+U<{A2YrPO_w-^(_2^H%Y@)DR~1%EL7)p#-nKI3k2cwjPry^= zu>Yb8_n=XjyQ7Xt*|wqkTuLaG9Mv_^{|@vu0F`@EQX=w(-8qsPrf;BBe{>yYuK#Ek zwnW|ni46xeHMoIn<8t731M0`z?qYUSiK|z70t_Y+3}vBLiN;#W4qVeB#N<GOt ztoHZ*%=^DJuG0Klf=^!c4|%X($TsX{H_vc}x4>Xr;b6=4c&)0YA2be40~8y zGvkJnem-P;z2pMeo!ZIiYVMY`!S#g2i-Q=m+a-YAkc0zNkDDb_MgsNQQB+)4E%Cmd z`NV`;yDedngiLlQmL8fVzdb94A%m-K-UZ^3m7;_e&jKzG1ZqBMeL{RRt<^vs#;jVq zT<+o?wmqeSHq~@5HyHm{=LA_d|o`dGbHi1U|MTkcK1&Q={cZQ9Lm~yk2Ai3jM_jgh&JODfldb zsM*exw{}(mZbUqeN#$@rutz_K`o=nW4ve$VNR$~}>EP)E1k&w$_wMB_%!9dXYGh+w z`lxHV1?0NOPVRE@&NaM@G0qnRe<5IQ{T%H`{+PGflh~zj16in4Ek)1Myp`K3PXH7- z#V_(wh_k->hcQ*#(AYQ^Ns@pb2+?Ah+VyEKf^!BsvtrCLPbjAWE?3>f0g-ispo`Z+jhbPO&tlu zP=L92avI5jGM(h+1hdn{!K>{}`rd;S=JBvjF}hfr zu6HXZbx{Bb-+fpx{c7^z=pk;}?_jfe;&AC|;jl{r;@W#nt=mOP`Lm$MxM|I0>$OMiqdb-j@!f8l7uxF3lC# zxnKAo_k+G(PDyMV$ckVwzvYA1LP;E!H0_#h_f$1U-= z`}A=)P=->}<3F!Ca-Pw`jTdzS-rY{e+m?FrVv8V+%UT%$i^C*GZCH{sM?+4miCkW) zsf{4CUAP}Ym<~gNuGfp|r&d1xav%1h4nm!mJ-pOMa^&|=2yNbLpl<4#87JOW8nV#b zy5qN3A~3&HEtP4u>hsL*wPVSdAlaOJ+cA6V$$|GRM@?I=c>b`j+WlE$msB8eEOjg4 z$chcE)VP+)sE_we_iXx2jv6EHy3_NgXzUlu2F*6RcvK>?OeZ*lLZk!nwJ z*q2}JO!?f(go|31kCj4z_#GxGGTW=y4IrYY$&e|>si8x!_}uhdy;Ce?e4UkDUWJId z_lI@x2^nQFpMBUxS}w1Q7~Y;;@fjLYXpTQb5Xr)>6NydJL{d6B3i^@R^TY%_ zbi(wAuLhXV04@hs`3Kl``y`4wg*HJ7q&6-FPJ<04B8apH-aHqA?@SJNV$FTG`7}0H zo>9e?jLOnGp9yu7F`{hNo49@NW_!-lBh)Z;l`UL!=b{8+4^Wq_x?jSMd{Kk6o;ruP zi?2!7OAU^zJ;{o5*9c>do1~ny_om%fT{-!Z*aFl3v9E*yU1+Jd=7j$KnY=+h_nMYJ zJ!#C#t5>rV?6sEZvdB#8uX_bwPF9^Y60{^E5G$V{aq#U&ix!V8$c^t-TbR5`6Vc!EOx=>-rBtUO~1m^%T3Ho*gs53#w0K$?aT6|>8bN=jInBc)hh-{{BgUSj_ zG;V!lHU7dPA|F#UWn(}AO`k#s=$xD=w%l$uzc`abx9NcGk401;C{IF-kt`EF=Y-`ywKA4CpR2zw`H^aU`QNoE9ca%E~YuyqlAOLKy4# zEwZjpFWjbFY%<)p4e<= zW-fCOYq(PkfM<5}`gyJ)FZlwi{B^YX`Uub{QRF6Rw-0>6X^k;@JN@z3|DeS%+=(zwDZvZa&;4SGDNFCcFK`8 zCH=GGRTTK*I}RJh_R_Rno-~g7G*0eJJC&|v|NfGl{U(HcbIE_zt4dOHqcN$LKz^0@HP5S~_cxsr!X<$XR1Z#_ zlfNu9{!5d5SPbjr!>16C-J$oKdt*T};HS<`)9SwL!S?adv}$@bzz4w=_W)Q+&>Vo5 z;(LmVg7VBwjipUQ@D52lq*OxPh?fe=P>8>SSugzkCS(ya3aq4Qujze|iPr$Lg)@P8 z7aGiMXH@7u`;(9VSydU`DPevcn#N9`gbmVSq*aVQneZ%pmIfIo2(^pTT48W^pVwmJ zZP(QOFR^Zw>4e)CJDBqxtno1s&7}#;$vU@P@iV%xm9ctlf4jg~PNw)zntu~nt=(t> z*&sjI{Q7o&yW8QHYqx(ll*icB7Aj#b47IcZ$6Wx7_vQMS_rr~1Hz1p~{Nbr{`w?jz zY#|C#qLJWB1GYv7xpk0dSE)|K>Av2) zJm64w=b>!L@i_lKG9r_mtpwx^^9F>~Qr2cn1ued@Bk0&@>0&?ydphW7F{tUm8Y&q4 zp|e|)t}mgF15qX1e|;cM17ajlp42c_r7qy|{%3lXTSEtztX!s>>3DtrP!?1HGV!fb zcR9l?Re;hwqo4*^oYSlQJXk~g8z|WF^=*EMaKT}!M~$KRbLuQJNC&Hhc$Yw?)oc$D zB*Y}OmBoZ!*thlM8K2|)k#V|hL2k{{^ubm1p!^!i!mskL=5^hu?1n#Yo5y(ER&wkk z>hjkzuk$6Haw1rFKJ7<)``jbj2J%!aDc{I=&Fre=_16!V`^6n2(AmEZpLrR%@*Qey zaoM><%2b?+U2mT4S-KK%up8cOyG{1_&)WI>u0rm+0jx%?X}MGW5Ot7KJsJyt4)p%M z7|aIo+v(}fIpU9V}ce6LYUYNhNq_$hnrWSXC-WXeGIJX=M|60li zoqb3~)1eYB2Fe}=i**w~cAyN+%oalEAudE2o-EtAGY$tc40|vofB~C)iT(?q(2N~e zF)_idZYppK1Y^+0gHj0@E@;d7z4zg0BVc~bTUEzI*kTs2;DxfdlV$g$T!h5stTYiR zrzt_mGxIWy_D3z7dxqa%N43(wPHUNu{Y+So>*Sk$m(~Oy zwi?p7()nv!$&C}rYvj zT##0%{?Kw#_^WVS}B)3c#zOn@3i zG=9jM3<3#nl4Tke=MOc(k_ANx`uJHFi;jkC07`Z|ECBjsfI-11)5)XXU}j8X_Qeoh}O-LlJG^(Pz*rF`uWs)0Nx zcP`!k#R4DxWABB7XHYjH$$;*bd?-~2c{uTPA=nmUIVc>p7?Dt&+Q83A^eM)&<_f{L z{#RW!u_lD;CcYV8wdN^Ui@cPORbU+$XpTanR)EQE6%b$sx^;x63j5BxAkMXd1mN-W z0q&4-0)!qqW!sGR1sq&P=N^HV0^-anoX0zY46R#vuv`_wkeBcRzE&HO$Dulh4|0J* z0qk~%l8-B1&koFR4#F{(!dQqxm65WF<0#u#_Rte#p!X`Xx^kT~oYq=qG@1CtF2fa$ zbenHs_3TB}4OT~O?`a8a2)>)h&dlB-sF!oSlVq^5$3}3N*_TkOlEDAnTKzUr9j0QA z@3rr0n!)-j3Bd;Ak4c#p26v8K;?-LW^&{*TQ1&|GpiDXDc#XE(XF@%*J5!5eL`BVJ zc+?exv(v=%KwjgKj`--$))E$O!YIue!%+MKSt*&*>cKo%iDZ?JfCVMO*lUCHZx+yZ zxiI^hJ39p1uNDJsWZw{s#6m&638r75#Y#rdLM&7;@CD;p+)GY+KUps}=>1T^BJ4D> zJJ0>z%Mmv#CUXh=XXHMKVJ_(YBZ!+#!UJ3ZtPWBfT#k`#B9Rzn=2O6HJUA^Hi?r;Z z_BsKb@9kXzNf;Y`@U6-in7FLNO70B2TQHAlYiq+tT0=N6v>+o11q8GhC^=zD56$aY zO5)eQB(d}mGzu%p-n2Z3F@X&>1o~ky5zwu}lozyAWrU%49H679qr_o4+$l?{%a+`~ zDP%1U5!>FOZW2zz`R5x6=08t`?fnop23ABv++uNh`ekj30{Jr6Ti4P8&9g_10cOg? z#qvR5InBX=Byi?WC2p?ZXxyd_EqzvCa(A2MrsgY_g?pR#IW>l3mc9@AG;V+YpdTbF zSC%}&F+bT~CivKFvJd8<)7ih8yTi#xVwM(L#@CAxS_y(Lity2KU~!Llao0!V zc4E^@DiLGxt^IDK1=+_alhb`8O_7U2vG_GwVNRCCvkP%ZN{Wr15{qsx52|!fAipQF zJDI)WN1>1!4(pSZ34eIu7&VY1{GHFhHwtvJ6|X2%mEn6e_Wk4PHeQRN;xH-a(@?Je zV|POJ)3L%PRo{jYv<#E1ht!nGHwmx+0K5(C02%DHp$(vhZGy70jNexAekPLFeGupzh@PC!Ymtf{eiMOEb|hZ9 zY3?9Nm5mN)zS=ktE(`{4RRR%W{$=3Lmuo*Xg8*ZJpU((rB9W#)Ce6t44U9{AMN$?S zH+fV`UtjG1pPoEA+5!6Y&e`^;^73*{xapCJy=z$2s_2S*lB(~}gaWMkLZiPyNVQKE z1?318sN3=6z3R;zl%zqbliX;ox#5^jNvlYD5lzX1a=?qqh2kocA@(r_$GTrM4myW(SN;gT|RzqObn;kRg^TCz*+6-0n^oL^uMwQt%@zR%N zmYU=tQG0tH|(08zg4iR@TK8r^PqVRP{s|{l~64Tm41YG z+9=vt>fTIaQh3Nndgw`v&e}wW3GRxU0JB^?(kYUH7i$gUpAM3SQJNY%Wvx7)!vo)B zp2%M6fpqNfr=3mrtng}s6=S($Mkm7piUC+je%g~TeB@pU zAhO{ia?Q$#(z>NjfSH!cO394huEfC@Z> zF)K8k%eT@P6;w{BgKJDmf5UM&XGrdNT!5`RfPBn|es5w7rw)d$iz3JK+}G7W={WJ_ zh3`VYe{BJ+>GGg7_#CxCVqm`j8Jy5t!NM8_QHnrW@~Df0Y?NdkWo2;vyLl0PE?Qqc zEC_5C1>1T|t{PkxJXmiI<(gYb%czj$nfFv~D`{4R)leqqH*N@}@QAlR7}G8TgN8bh z5U(K>ok~*ArYRuLyc^wFD2~Mwgm!mjVtDfJl7}rNsk{Dj+!HyultNG%{ZH8w`Y~R? zTCS~2-zHyoccIlQ{><<>aWvg)PuB1|y82jcqR81!bbKZA_I}y4NsXBpURD3E*3VRr zEjKMyh=e4>C|g+^NURjWK*+^4WXwRP1-lk>d$VLs;9AY?dg|s^snbzRv>jVC<6p>Z zD1Dl-?M94Shau%}b@q2*Gf_A5<-7*S{9xx)$H$JcWe&0|QiT}O7#JM}b`}aueISc^%`9n4^u1+4Z_#HT{eB5(F&Nk(*8J6=W1YaD3Gn4oizpq2IfHD zQ~^QU#_}CMf4-^+BYCn|2PkLSq_}y*yO&r2;~br}N0F9Z9K=fQ zY*`+mLKF%GtOL zx4B;qpna7_^FfiKRK&NEukDaGS~a~2n_>6E!u2uWoi};38Qg>nw0Y2XLI2{(20?IL zrJM`C`uf^#6d%oTu|Iw|ycW4PoS#|?_IF4t{5lU70>qwhb@LrUk|7n}U2B})Z}bL1 zmjIUjU{3Ui3-Sj62`g7VJAca)v%E-t5{wL83Oe)z_bU`(kg8)<$@HZqWm3*bk~quf z`$L(TG^g0+du5Mcy)>hMcpfZo-6mNTCxKlNQj zoX$=!J?+GRQq9A#s!=#~=M>zMdAg`^pQYyT#ldixpUN#7-6QtdQt}*Oq(Sw4s()7Y z>xx6M`qAz?1{;T#vKU?ywI;5x%uG(q7FWN^+QhvQ_Jg;h8I`hL7(TuWh2w{w-1(h5 zn^(hbq-mFqW+{zvp8Nl*dJ}Lc`}Tc&l(Lq=5D{jKH9LuH8Dkkck*sA&DZ8@MVrlFQ zWh+Y3BD?Hcb|FQD5Qb9OLiX^#rrz)G|Gv+0JO{_~U}o<7{#?s>p4WM4rLcXGE1j2k zdH>hQY3|0?`$wev9k8JAbEx6dd;4Z07MySxCd_obtmC_rjCB>8Z6~LnGF-)`0 zOKO_n+c_L>@H%}&x~}sffbytz1B?@vknNLCzRjfqKYCUg3}upglODaka2mu~c|h5M z^DC%e{&_ZoJqZLf`dEmrP{(*<+pq!$nC*RiKYhJLG0a5n3l)T;1Ojt#^&d=Z_}#CU zn^JQTc4?7F|IKD~zb+DaAcZ{UvPa=LU_OpW*)$A8%Zjg^V6Neu3x&g?EE<8us4-B< zQ8>uIi#Qx$83oY6Fuacc>z(%VZ3h4dce^h_sRX8_U=#(9D|`=@lwb^!Gv>~UIM3woL$9JaelTK@?xMgCBZt&{rf}k)z<;jb1XqML4}9)C;vG;%;mFU8%t;m1R11pZyLW*H=HQjQO-N-UP=HK7l)Ybp1@;IFS;~Go?JLU8SMwZ;Ar?V}8WkH+!?_b@#DO zVU?))*8a`?0Ys5Ep*mgVV#B$jgeUmh*zfcN1a_f`@!O}d?VyQap-V?q!l-mia$i}n z(cf=a|B)rQ_Vd-CcPeXDN7kRD5NRJ&( z#2*B0@+>UK6}a~!WAW|C)tXv0KP5pb$HCGB*8L;QY#$IXta>#(7tn#=^#xl*)A#Sf-DPyeS*Ux#N-zg~NrqF; zH0>;xlT5m;ZZu$iUV_Q5Veps%{u~t4g)zB_mt2n$mV~Fm*x8ks%N$4<3)AN5K(fR%$_5Ur0XASKbO4trCtxPT!oM=IU{}j zUr-jC%ecC^ErHzzW%d<&0072Vv&{5i**Elp8249JJk03K-gcl!mp6l5$(o%06UWe4 zJ-8g1y@LAQG$)Q8qE>7!2-}t(tUrp5RHCAP0q4$#h&Vpx2yIVFCTuqQnD0A3>lw+sXpQ8R$hL25pIVxIz&tjs z)3|TnDG$_H?tqvc!@K+I4(T1DZ)Gm?4OGd?y_qLnyuC?BjvQ%ALrzUi1+V@z2SGVC zqSAe=d1!uh&= zQx1Vk^?bArOHUGikdZ0Z)F^KmO1)~(Ld`5D|5J~RC^lEkZ2-UyV7>G*?>-3Ftfs~ zwfsc2^y9gJtkn$K+kC!vS*1jHx?B)1Jt7@bhBZy6y%i5ORold;r!z$C+dqMO)C7-m zM|*p5O$~h%@7+l_tL}P?Fg%w=8Ks%OW@6Im5l~Uxo?b|5UJtpi;B~u2N?$^wD1B4 zwB0G*Jsm)uf;X2ho`R7eNinf^8ygC6L@!*weiumZ@tW%~cxRZ%r$WGB1MEX@t`Az@ zfC3S56Z8|Y@$sJ>fdcHDS@DucO`e*8RgNbTQ zeU3=1$B^cAbVpj=Wt}rlRfAFnR7+JCOwX*@2=+1vR0F4!gL-5);^%0Pyb>sI{da~$ z-m{&&Zb24DBO3HIne-lsQcTi9;+FNd%<#js0f@(S$P*FBqbi;IOoXoonBh&r^#xlV z7z!P}%?H9BmhNuy8T$swQTIwk+S@}XzN2{Q9}|BrXL+(QM-qu`FVB37A>ryM4(=y2 z4Iofm_*OOS3S{#+%>xKnTR#beSDOPfw5vA4DF4fsiEuioZXUl&KVI!aTbVQ(E4BG-2iilP8Xj1IZb%suh0qHWD3xbEqTF^#O5* z;_C8;%izZCsG6Ms$`rlqV2Hm4DVJ@;*xM@krH&l>;aMj=%B%d#^ZQnpbJ?0ub+E%& z)-I}0Tf5)r(Rj_mTCd_~Ucbf#89Ztqt?f81Ci*t~neLWyvDQ*C9{;%TWydv-O8$Xk z2{g5Kg2`Sp^BL}iH+1liTx@Bn!rNyw@~jsb)0y~wD@&$$>2i-3@}>)I_kQ)R{l;wa zJs?X(4dWeRQuB61<%nO+Xlf}_^&OSI7`Up_{)KZ};)4YPKU#-f<$s5$iL%F-l$?tt z3cvm8{b+P5Yo;xJ29JWo+t|k1E}TxDoU{*OI-rhxjlIEm=#XX6kxjc8`#iJ=$7#4g zoTrsfojQ7i{s0dbS4>PB=17dDe3pWjYW9)+2Jq8Mur^A+ltyiPt}G{)l96k5=}n@J zL6x>{3fkUSV6PWL*K2=;?48E8wJ1OSmwCC3*RgQ>Bh-ROH#oA@Ze+m;y-6eUosaex z%yXKQ4Yz{vX$br}$U4*XA0@!}XY>>YxO`U3PrZGhL}7FtLHT)`kAh3NQCWiPGo>ys zEQEWVgvyqFwZVMMG+@~}F9s)2ot^95HkP2IHhI$nN(5m+*opCmSG|FM|6W}-uU8eXoDUS%u4er$T2pczqqr*o_D6wXvB z_im1{@Q{m^2|Akh-Y1sFb;Tll4$jB7SsOW`j@{*&;azva1sQ8+&o zrRLfECBUV^t44>1?J>B=?F{+p9W26j^vH6_>WmvRTLFA3Cr#DOm{zmw$Q0m1X1Pb`OwZ=KUYvv)|hx3~Ml=pL5Y z>DslFDB6~m7SK=Rf`E}YIR*p6D)1BrZ?Cx><>G1qpnG{!S^p?4Ootv~VuE-DN!+{o ze%x`l$`L#HOiftMET7p19?fj@2b`S`w;&^MRPEQ0_8iU9U-_jqp*n(}{!@WHaI+H~ zs4T0BqNV~)n2#1Vh(qdc$2lmpYFUhgm5X8-Y%BQ;-v)7DW1eZ>!VbSn=+qJUUK<^X zxjo?SNZ|3S51kUqzR1;Iir)5nD%8d5)91^q<^7<|2um>S+)4g*?h#hx{ngRf_5IUB zJ@wd7u?m6K4UHz$_627+vG?XY3G~XpB8$T#{?NWhi(}xSH8>ugNK3Z36|Cw(h=%)P z&taAP7Gj~RzlGq$oy#{#tx%%x%1Ru5^%v8bkM^)puC^bwk452zq-o7#kC)i=KD$l zd~$_yuu5KJyhZIDVG-|Y?rDNCT9m|XbSdPa#zSM_tdvU$C~J>~O+nb` zVSV#(&Wj7qu(&xkjq{|(mt3gXKwO{yBGD}&At5=Djh~+%KoCQOl(MouJZ|M>Wg4J> zixfT%K^`jQ?VxMdpq11xRR((pX6AsNSQ`m#b!6gFDp;8;Tr9H;&@=Sn4uY!@fk#rW zjW1h&x_*Oej}Dn66dwLefRSo~z|7qtP4|96R5DyxijMytpEn`OxAu^T=@=%k@qGlL zpYX}(%o%Po=Pa{pooU#aOfQE)H4K5fYDRn{DM%N^R%&aJgc-R`%dn=LF#1)XtreZo z>fawotkUJE4#o9!$#e66lp9Bmv=2*8Vk4+i=Bu4+k38~6oUWc+57`b6;dXT``=JS?XkVmL}`k>hepZg@%x+Qmhj2INmojo z2Np+FKzrmA4r>eq1bS3h_ZL&={PCrwKS-%!;C9+PH{1A9AH;F=XsI|~Pb@I`Ku8W} zT(qn8?cKH3iKeWyX$7JO*3N-@vlR0rKw6c|xjnH^@KEA3@J|;i$ELW(HzEa2k`+{+ z2_1O&FJ=F&$9@kFG&ZRK!++?|p<%W5kns+o>|n4bp4uMYQw2jm3M)VC`l)96d}HVX zyBj;#0kbrLE)1AvY1zZPs;&&~jxSu+&lj8(w={Wf2E&krvrT8(^rZ>S*#LJyQj;z8% zXjO2}a!!3oG~#*UG1C-5*5f2`T2ta$OeybOskbmEEM!-N-lNnmrnu-x2yNXNs@iBa~ zHJ_D8o^%I%ismrFr0gdL@a<xN49E3ye1vSP)BTAcQT~0 z$2;lW`6J)a3k==+9KM`$v@wD8hY2fEJSeDF?stC`lTPaXI<%rZ^0}m}tOWsRMb+8- z;j>K1%eNpqH-v1)WKs+P7kI*TpmB{BzMlO^Vo9$C%raK!0=lt2r<}*T!~2WRA#C=?{vxP(Rltj!{hO5E1zy4=QL0ME_lm* zG1~PwVXlh)AUZC0NS~`Cm!-|zv#KK*t44Z3k7luHi{Q36icb3W=>1{_=lO&Aj7e9s zIVu&r#N-19&CQ78csO^#s(q0*Kdx*74FZz_bBT5(==(!U*-!=I?1;J;MhzG9lG&&? z&129Ah~-rtPQPXN)bS}H^Uh0cJah|n4Gr<{-@hNqU4|{{rJ~W$G&J1UQ-w#B32Gz2 z>XGVTp z^A8Tb|Kv2OvUZs@5>2E2Zgm6|$sLKFS=l^?T@bt?Egu0K8#9f1(`K;hy;a>OrYX?X zj<548>pUYuH9Q0ePcn+7!b&{zp1tWQva9^@C>r$5;xYF{-A{>lrjt<`c><|WxY|pk zGCcSYsJM`!o5`ozfhTrnn-H(szD>}j-*V9Dfe!CSY)Zu zdQA(#$V;tqWL^Q1HG&MDQ9_I8sdScoMC*dHuKijL@Bw_Xwc#VZb&^S1+%|zOHh7%U zmALk6%&G7n%-9UJTcDEPE*3vlZDUB**L-f@s0PGcsD)28H!CxqAPse~UcWX#84!Ef zNifA!mWYDHxn}7DHHe-msLSNtF81_5+MLR_C~|Oh?WyoY!Y`u5xg;C^$SC)T2k$lNrH;JB8 z?S}&AUkyruVy>Uv8{jZX*PF(-?zgGDj5 z`_Zs#U``6s?}mjU%(&I@(Wa#XXfd=ix2*~-q<_|ofHEzX?Y2+#{V_X9CK}ne0s5?5 z4D3=Ffpri0x9kQt?5)+D#7Nsxp=hMQ%|u(nq?s;n6)WSq=_LTZn1;TVy?-xQwp2m z)re8nJX-paND6&i0|7XD9p4+dfxOmYI2zeKnUs3oEw(7xNXl7nI$Y5 zj*#uCxR`k0%ED&?vk_C6VpkEflx(xJu$V9 zI>vUJ{H-^WgOhU-kSRb7VUo11wUt`0_1T6A1*ML_v$3^pFE%DXqAm8h@f#~b%0l6O zz93P+4V11Kyp=Xbj3}u+gKRz-zytO8+ibN2;b>O|;^H>kX+RmLw;N7;a&o3H!p!zi z_k#IENllGz-q1t1$NO$l?x~q5H8_@zkx&lB)le^|V&T@6Kzb(ogcuR=3qD&TwH|0LQWkpNmkX*&cgX<5 zdMg#19Ku9kIJCVwMXtQ!QVlvP$SN!-2S6t+Y z?rWcwd|tMMuuo`#ARz#8a2YKc+7s^e@Y=#`C4z{}y_P4DU+ z7A4VXib17-2dv8ppf*j2gkS*5jWw zO|dE>)4Q-Ks0DC`r{B^kan?A8a#wiRd-Qj{R592%8bo1trjw1r6^8EagVxS{v`W3G zVM~;(u%Js7HN^n{LgX0x85_3d3|7&z^TRDH*^{X&mQ^Xpi<7s=hlil7e^1@V*~LJLig zmlo<_i0_|pSi=6vAYNLp2@;cpBHHn|xG~PGY8O?iVxq-y;}FlWV_(naw*eqTd;8(l zh7ro>_eDB-={}TEH0VHvl=W&*Y;6uu$H+*Ei-UO2tJ-D(BaHpx@8%XqMe*9OwL?Lv zNa+f_mdKhAcGK?PpTmd{X&ZM}i{J>v^Qyfi4K0D0=HLe4d7Z*H0-Xmv!K_pV$cyxR)Brz(e^qI7_y$YiAEj%eM7_aePTGl zbz^iQt0lCr?bu@wT2bHvcAfa_Y8t{f0(wzGXr2W`a*$P0PTJ1uElIA7wK7HJUhmUD zu`EAe9{7mu;v1oBN!0)FG!A`zJ;^o7t1DNoU&KJfp3!#rzP77Q%8>0zf)T3=4Kd z1v@+iT|>v*+{@L+;6($Ugp$qR|3Po@NAEm|eDep7t|luxkduPsLQ+?RjmLqM=jx5NfOYHetYX!d2 z%hYX0p6;y%}*l3UnCPw{a2Im~pSo zb} za!J~Tp^=fEX^go^@UPc26(2PghNT!`FO6mV6o)!;Zg}B+ce2CH#f<;dk)ji`NGL0w zQek|2gAe>7$4D+yS~t=@iVqlo9ymt11UPm=jj8z3~g;BwWrllVMYza1p4onx!ZpgA^km8|e0oLI+H8*J)ybL&?x}Rlyp$yA!PA_te|gQtv}}%4gn9E>T6{oeX5CJXNzR z-HzeT=}1dpHC3}Ot!JHVrDjb+vYgdKJEuq9pB}07ur`WLN@8yCnmPzgP{EM{2z`D1 zVx?V@3}x6zZmegQCo>!Zv+lUc$M}5-(Ec1ixkGssLEKVf8vkOS@`=A} zrN2YA<_^p0o4X=>4T~e}iGYmKw;;!N*DAeswyu+Y0JHx4$c?2V9K5_w_qK}ma1awg z*8&c`M`6l|(zW%(QlQd;0%m5*iwBq=oy~s_CwqG3-8&@gvY{$#Xa!PmX{ZS#~PhI7^LC5NDbqC1;2t;9W_tz>YJbwW33Y-OCfF2$m8syN3L?jcv zba&5J?~1k-WK3OMT`cZV@$p`b98CdlGb`1!VHOlCE2}N>Qr-jw z`aE_0CrZgQ@F?V7XxzXda~d8e;G5sW?SfDA*!1~@e;5iw5{6|D`aTGikk%C69F&jD z;8YPfh#UpSJ5MY(U^0cBrY+BI6njRszT*BqQ-U^gI! zS4BUjPKwB#e~f5lmm^TAqoY#xI;;qf-OkpevNb zgI(_(jgP;B6Sqis7{+d*-S zk2Y86b%ke|kE4&;=ZZKfM*9>NAb>giFMPAg|CpOrF%W(kEFqmSr0GLx@<^bl;Go}o z2uGdLbpz^QXKh`^gM!Bz(FB)^5$fOvF>N^lf)IgHyDyrFvOy?>nIyo(URnyqZsByI zuMQU4gIRGlXnLe%0WcXtvMB^_NC9#W>>1Q@vzn6`rS$5QFskR>>C?NSTnAh1*g(t*(lZLM!E4f__&A3Ei`;9tATMoymGGN7fJ^uJuJWJ@|V z+E*HTHC!ZH^H|b-Ug}#re)5^GejMvzbXh?%h1s2{xF;l6I%HujrcK2 zrh$QBV$me=H;tsNL?e5&ELx@SrZey+2v&x5&b5@9G*`WLv8RB}`puDGsiq zGT7SRSi5wiodR1u%?^!*@H_yrjcOP(0eli_R@l>(QunG2jur@pfa<*iReTrM7}x`8 zJ*JYTag)znGf@52)KoO=8eJ_2F$FL=P-AvMh9?psi2+Qj3>ti$k6m=gQB6@RrEVgb<6SLkqMb z&wN(aKW>rA6yd_QA2IStT2=LJcE}p%^mccTKa3d^LwJP=hnqy#%sYus@!>Fx0QvV^ znSOv_2()4(9gC3#bf2`ztT5p(=pm_OMq&N4HZGZ3z0de&0ns&ddt{u1+ViMiWhX1N z!xFv^XDk6s1ThXJL4in*FWwO*m8`C7zOs7N#fOkObxM~qx&VMBw8w$p(l7Bn=PUG! zm-xl|Q%B@Ik#mxLk>yXi80(}vLM4jTH#%^eu|8K)>N zP7Otm$JEhdvu>T-dgnT4078VK-s)>OlJ%RCy*19MA@ei3Tc*rh9|oVCo%5e@@bFZ8 zVa=Mc2RcBdFDy4eN)`~|G@>V@4X83aQJT>mjqB#4|-pfx^)`Wk{kY2U@`82KpJQLpL^dKvgWxp4Ev) z{|M`wS-Hn89exnXdRG%nH+V$=l2IGYf|i)>g}yPeJn}bxi2hQP;ZxanBmN@a47R)Y zMPkD}Ia2(GW`j+my$~1BZcesnrTgJ@daAkQ@2X~WRZ@6yJn$%MeX}Bs`0`_Ky7sN_ z=(q~D-ngC4pQ@1fb=vBH`UPuMk}Bu+u13?+D=Fuk5=FxRSmz<1s6dz?-pb=t;#8Ym z;&Zgg|Ck5`1b70#u>b*KTKb*H$T`q6wE;*SfqNZjz_Ew4JAb}%#=2-QAUK%YlSO%9 zyfFcmZ_!1AIu!|fl3mSND?P?5ro&s~j_&Ih6;9)XOrkupGE*ci6KoIUk_(Na;Mzs!fG5=aBvL4;P(t=zqM|^>c zE;Lfz3|H>cs2ytu1RuuJEm(*F@UzAZyIZriE_^XDF{ln{%FUuQS~CF)`Fp@-42=+zh&m$7l1IWk>p;-JeFqI+0BZN`aVVk>yvk z)uGsPbi5G|wvmi1$2|phhCOYEM7^wKQ!#5Nlz!u3W|NEMk5}XB6_dNZtR_xeU%eHt zTN7?~)YDwFlM$4QqxOnA=(jmty09DmGU*4rvh6l$DsjH%N_trAN#^S!mfG zf%RWbG@i}3WCN7M`J|Utg~%*Dvwe@$dUgNo7iCV^ zoIn2*kO@b?NGM$vkUb90K+ej13j*5f(>b5u;8Av73cz=)&Efq~w>Q<%bV9NtpO7NP z;FBE}8#{;Lg#}ww2tfZ|TK|SjJpgN*!-t@53Vp^PudGaof^>jpSmfpjteu3&bsTBHnPTf9X7On`2IdrG@2^vKe6o*o>Idp(>Wb@H&TQF&3nl=$R|#$YOw)45%$DE zyP!iol$Cg(0|FY9&$)f2PmKuyT5wF?3M@3i^|+3x1A@}EQYX>eY<`Z`gpXPa>;+ry zFpc!(ltPPsGfEGu$b^D`)Ezza_?Ia7*z3!QqP+l5Y7RY=^ z2z$FBBU@+}9&j^ZVTLOX8rI{jB!eZLKw|_G3e``Z6!piS@B--^1f`M7umFv+dK&P# zjfpU((|Az5m*5R#eC25O<>&kzrk@{)aX5YZe~yIFQ4{HBrDTBPcz{d90uAOqcD`)K3dbwMd!a4@qfA7fM$e@BixAVkkJ8>SG z6LM@MjADg*ruOGoEO(>zRHHK5&CQAZ&8w-%99*8_6%3GPC2wfaA`s*~tQEr_!UNI- z7QY}fY+9+arQ?ZABWIrUxJ{G-{;emLG8hZ$I4~NXIC?31y%qGPG}|6%KE%0}9;ktu z*LSkqc%1c@Rw_S0s}LE{9{Cm<@*0pW};lkt=}#n%JF+etz$*pFz>8`?RKES zlv7lUg0uu>kM(^X)nE?D#0z7!mttl#?i`*3FWU+MJRd%iyBj2v@Pq?aLeN(LZQmI> zdW&0L#>A&h5AkhwgNuClh}wmrA&yUO=p>{jem6S@kuI|2^?%1pNS_$UiwUp2o6tWb$(@^{&3sJTpu>}r6 z0(L1K=CRhs7b;+0*~q|P395_g)^IVQH*^~9mN=ZUpwlVY$Hu~*fW%rAXf4RiWGn&2 zm5Kpx7a7?p;A7UtSrmJEU=x#Qdq>CoseUr$vEEKkcbonW_luP|6ubw>(_P8FDi)fP zEGV_@;l7su%gkz)@Upe>jf?o${Wo;!PwI+3IUYP9dVCFY9P6e2`Ls=PuR{D1IDhQz zm$kkgQMDW6cL1Sx4#^B|kl(>`X>Hte8cbwJ1lkfF_NK7Q17I7o@21;oBKetJ5ycDY z!Ayhw5pPIG%~_9yWo&dzuvj9)$*u`|zK-(J($XTg>b9#zWLGu%Ll!%Uz72%5Tv|jE z3~?Pxh6s?tT2IS7oS@HYszXl>rA}1xfOaeYN$#LOAdB81CrJK76-??fo2`jg_%Qh? zo^(giQu6ZhzP4x30;HAjQEzkBLgu_&-!z|#&h2n*VQg2R4f`=KRXqzZk*<74} z;4uMe0XpdgW#VnLWqFKWlR6=OT291)MnE+8n6p}I%vGDuv;O^`ujHQgi;53_&Mz=n zbT*$7;5XN|wgOX)v_J}I=XPA;IeNCLBmMV>p+$wN5$~dc{KQ1mVKgUcoAr7NJYz=! zsFW{HNku8zQk(bt;DUvrWOF-4`b>oY#N5@Y_@#PYJ_!c#j`Xnw1^+{DUfB+)^vy0m z^rT~O*5Zf+U)fxPl|&AQ^u>w*z>DHRJ_DOh!W>F2H_nW2w4XGki&od67x;^u|6`<- zzxF-1i||z|CHpmQKM*+nC2&?e+@8p!_UB!oDKT)L|2ujXP3ABDQ-?rkGdxA9F<^8_ zIQka|Bu8}4q&EUv*v}w29l?QxkuoHrr>EzFqvPY_Iba-iDJ$S0;$>w7Og+Lp$Gu_@ zyQIz^5UF`$?w|%$;=Jf(TaR1XREm|LvUN6&P86%2ac)-e) zc3&MhE_XVY*(N=9u|qAdAfNMmUZC`y^x_B#Xy+1ec3#^Ocql*}DMF^aXJz4SkjXmN zLuzADhgVisKGlNZ;AoXsm{UVi9xL-Ccg6I1Mh)%uRd^JSbW+B ze;3^iV~DH>fXY8)52StPoF$_(h$)HJ{ZNk<`J&2C1g8$M3X(o!NtXeFNbW; z7s^-o<5~G|Rd;S&!U&Hk3@-Jbb9z8&U7;>~E-n@xW|N=G`J$FdDC6GO@dYmssj`rp z%x#qEn|0!~&6sC;jF@k`vuF?FOA5;loiz1PQda^GTmqb+@$sc zvqK^$H5Da9ID{uSx$)BRa;b{n-@=*V*OKhl&?|(1vzf_iOzHNGz)*fBJ2PLt# z+7|QCxJYp+QaH5c@X}8qy2Z*F- z;bb!4OCgF$y1mYGa$oN1aq%t<6s+8KmA}dly@kHHF|B%uMNWrm;e)>k{?R+NUC>06 zT|(>*y?E)_6-|NiE7+#NK+^-n!3F7A9B%Y3UMt@WNaQ(Kf^2A!@*H)Htc_?2JO?-D z8e0>HvA`$b`p=Z|3-3lpZ7k-#0%9+YyX5TL)C0-%8k`(!zM6=|vOd+Az0K^sM^3l; zdTe!L`{v0UOt-?e%$0kVRxw8XYXcr)Hv2I1Sq>E8=Ookzh?@Yi&Yma7*Xp?wOu^S!xULeYfWS22hm&UszbD8Edc7;P(!rqvBWAtA5DFDkW%EO$YR zXuF*(&ElwEoqGJP?vWCR@eUzEHvO>piyhR)FhrF5N~4nwAzwcQGt2PgI71C;eNjs? zS>MFG^90L*Hdx%ti2$WH4DMXb-jASc*~!vM*Zo@~{mVP=E}b2Ba6^{jf{#Od2-nR2 z*bE<5k3xS$^U=Qa2HFe`ZHvTSJD0}<=vd{yYM60Q8e>gn3fLaQn%WB06I@5z86T*h zKt@i=4<}Alb^8wpNJ0|wdvzn1naxyR<;B`fIfsYYpB*G`H{bok`#TMC>t#tcEmJ}g zRwuVjOPSRv!`0&6kx~uXLraEyza3Tks!^Hf#7LzyX%QwkGOjOXGYNB zj0}=9kLZXV%TbpR@2;4(wzfi-g=Hwwfmj2h)?ZKtgG^E(-f{K-?DMwl_kE zJ?(epj=yo$IR72&Tr@WuM!n$(^h4YoUPsi?j+3Orka5Ai!C~T-gRYgzbkK0$og7~E z5~G~|)a>7RcPKFH)8C_?i%Q}0z=WLMIY=x}E!M4mvWE4Z!0{h%H>1zyI_Z8cxrfpl znbwWgT<;D%N2?B-&GC|Tzi@*~QT@&0HcV?Ws|6|RpklJH?MkdX4O29Z9K z?tPf#(XO{!l(D{k_vpf@1z%q0KiD2y) zWM9wJ;XEWe#IaX{cKd%#h|k4woqYKQcMtZx7aw?$$euNG-QWlrrwsWDHi5WWsMl9i zXw^II;k>Ifi@ERARflpAOYBRF)rdJc4FD=Rv`omYK=#!Ubcd_Y@MZArb!2^wp%WSA^EEh|fD6byD|G^-)8^s<*{K__ zddrWk9JE2$pVXCyreSjM)Be_DQ{L735-tD)iNrliT#J4F{JCxGC#Z4(Wc2s(Nk&|_ zdNn2+#`0&;UckQAdYBL(_nB7PRN$K}8kX4rNdQU!6jWiLc7Woc;7apq24&Ebf^JGn zzXpL=9i_rMZpnKouS&AF6i-D z3%h^_sPw>YMfT6MklJgb8(U|#_5C-$rk-H~Xz#b)vhi&Sw}he>0L~*qwPnq~3{n4) zjnE7ea4>A6X--%0>BXmlCme zb936DGeL;7o9eY!5LtNw=U`p%Zb%#Shj8K~It`leg)g~1J zI`JX%olX^TdOE@!AEiVG9C{XWl-POHabFV{4vC4Ne;kt-=A+}m*}+?frIjP0N8s85 zzBW3DJrlb1TsQ?r1StK(KcPr*>AsC#YLpgSb;X0)=NgxZHF zYTT_^ErIPsl<5H{uBfZQ)ewx_v;V-V&YI7N(XaiqG3vCDw~oJ1iT+j2@j;H**fe!h zNn)p6$Srns$>57N=y+1PoP3!PgeQ?o5~SZGEHBAX3?Jb-{y<2T-(?27?X@Gf=Hu2T zgozs>Y>`^MMm4pt9epQisd5T>tHrN{lgv`Xq_^$6@g$Kyax*7t|5>SysKGt?e3(WX@>q-Cc?2QxEtE#FYbL{$6 zi|?8WX(`cnbZ7ioP;5-HS`e0Ce{KuK{SZUI!u!8VCX>wjBa@ZcEt1d$bdV?jR;v;J zHdd1SJJrr{q}#~R7)lzySGJwLwztu}O0ZI7_9Ru4sGyTl;gJZv&ZzNld^Ej%s{UN! z58%Ehq!>XpWJIn0?u4zC(&*v@%t<>OlBb#&^BdQc&x{a$(*H*&{JxH`a3Blgf5#8w zV7u_Pte^BEnb`W3l&LoAG4CQbQt?T|N8JnZhyQ9O7oLmZtCk?)F5Q@dqX5IJr<#bOPFSGF#qxU z#{h-H|Mjsb^wn|Z+#^58qO2rwaT?Arz&z$n&sGg)5nm2J!AA(*6)F`s(X1N4KGGo4 zpM3G5zQ`y`xeFi8N9zgrqLL(|hLTa|ec|YLKdyNKF`U2rE2Qywy+&Rm7)gvSD#<+~ z*2St*uTuF-k&BUist-n2A_ix$~#)&vN(N zmyw1=rj#!w=l>sWm+}nGUi8z*V$T>Oge?KR{7J#3;Rg$yyJQ1Cvj(}MHgRjY`EFHr z=$K34o#xTe(Oba`5aJ3-o5w1Gl*97ul%MM~m@J;OBYf3Vi(p`$Up`D=-*m{xsNg+W zDo>CQSWL~$nS9isaQOM%*sAO6;*qHm;faZ>*asR5$+^sV{<@u;)uF&(UGH7|s)QaF z9}H?fR;2z%$P9Gql&J6z0mG||tcm_w(>qrcaTQn&YmfQ}DMq&<6~v#88-Hk?)PKA? zUsZr{e>5#BNy2NA>Yxd(g3=qB;YL}5~VLrC3>cuD88 z|LT=mWQ1Pn6CulYPi?g;H|)-x(>d|S$r<+VG1Ssu?OS=-^%E2XE`6Tsk_7GrKOvXk z9~E^~ktJ{jibuAg+4Q6Q)si<+Sn0|3sG4oR5TP95+cN?Fu%Hkozr{`7>#0v}8FtQS zKY8eBb^Y%J|G!}8FV|P4{ixXUE(>qy#v^m9D(ZI1(k$SB`J*u-qL>kw#V{Q|n^c}7 zVu^*Rz)c$UMmL?M&8Mf$umB1*gY#Z!YBTPwZRbcT z5P$E4JfJ0+g9)fBG;K}`EUmqtXtm%UlywILK)!V7K@a}t8NWh!f$A7`WryX7dzVKP zo2AO3!!iARv{AiZX-z}FD&cU*2TET055yCUrjQ#rGg_CD^G_l&kCIu~3XP~_r(n$u zDEq&gPlPf@?DFMh8DS1`wuHW+l|FSnW>q~!VnKBvg|oC??zV7%au<7wo#%-0S~QWZ z`L($ww!`49X1sa|%R)V0G?(I~rF73;#bh^5^5*iJ<3+{7Nokx=o4~4oiY(TkO+)Nm zR+)L`ZKHpj@qeBYFHb4idF|#0DHZFuqTEEgw&L8#&XEfy)}4Q(7?(z%+CkE$4Aty`l3CW!ub3#g^fzS3$GNvbLhqxX8g!gk|#XTGkt_UP{(y? z3mS)^3S#bO{y09Ch;}}wZoVJlE-#4F)q0sdl!vP}9?6xHq9f`a_{xV?S{)Bh@5Y@Q z8#Mnf;p^!T9iYwzTQ6Uu@hJ5aR$artdG9~C+1r8zDs%UfT9R}6lylyQ_-8S+c#>I9kAp#$0CL3EZ~|H+Tx{hgX;QA@fkY|FCW zH`e);!l#iDr@d!b0IPc@wTj2B}qD;W8QOOuGoxDW>~a zf;uq@t1hkc^4b3c&l{w^rXAFW!hT$FD%qh3Q*&N=SCg5INkdLqLbFZ1GfurT9`G%Y z2M@gv>o2q@9TLL)S*vUm=vxV75f01pC`w7YBOuyuCAX!nBht6>tJfnmdFfh4Q*g9%;5gR*x|p* zIg3SjU%@@r1NM@nrOR{oL^*UUBEIdmw$>?*NG3!4MWnn zeBoa>)n7Bo6IA-~67mVYar>gNHyKU%AAnFerCdQcYDt)3sY4x;hFggeKDe%wmvH+# zhgnI|H*J#E1;*R(2kmlO_;grUcRt@ZxSFPeWZge5`6BCI<+X>jfGi-%w#MpGbHqjZ z^5~B#vDWqNimmQ=^^SGETrIV*-km_w+~B%{@zj~r;Gu-ci;|{f`^DEgp(nrkN9imE z{7rrTf?J61Vbjwg&uM-$GvkctNxAJa1)cu)hY}>a)RhH!ChH%a7yJ9uzZ2Zx>${nm z$4vveHp*|NqdFow6hG0psRZ;Z>#YsQ{63J#y4L@bU-xe+*wL_tuMHm(<(XYp{QIMq zo+jb_n~VG`Om;M1tp;adwIp$5lS)RFoS-vNbbnuAH~is^>c0iGBU|=Z$TdwtyY zJRQe{2@C{yKCm*7ZcNeH*QD6lJe^3PnYN#X#_>O z@Y~n(BwTu#9j%5{ZS*qzSG7k=iu_+(-@CDcd591HzhC~(TUT3Wi1@!p{C9%jzmLE7 zt%F{G|8H0|4t~DJ@mDTQHsa~gZ*o^7c5td>j;8uw4(3$W`}Z^dg2lf(2KEVrr9G<5 Xx=dpQA%|xO_=lirh%dxlxc&bDM<*Jd literal 0 HcmV?d00001 diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app new file mode 100644 index 0000000000..9b71b6cfb6 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.app @@ -0,0 +1,6 @@ +display: Volume Reset +description: robot speaks reset volume +platform: all +run: jsk_robot_startup/auto_speak_volume_reset.l +interface: jsk_robot_startup/volume_reset.interface +icon: jsk_robot_startup/volume_reset.png \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface new file mode 100644 index 0000000000..5cb4ae9816 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.interface @@ -0,0 +1,2 @@ +published_topics: {} +subscribed_topics: {} \ No newline at end of file diff --git a/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png b/jsk_robot_common/jsk_robot_startup/apps/volume_reset/volume_reset.png new file mode 100644 index 0000000000000000000000000000000000000000..d9dbfbc14f4915ec02ff822b6250421f3d5cf43d GIT binary patch literal 81525 zcmYg%by$?!7w%vjPy_@~R0I?TVE`Eg0cn(+p=4mBLn)EYp}~U+(hS`a12Qxyohl;T z&5+XF4R;Ucckgrk=ksB{Z^zmz-u14vKfhFxrMP)dt>;xEvhh=-+ouCgK1C4e6)|x zer@i=l|lw15w)98+@ZIWQyqN?0`ZQ8V$S5Z(!&{f9Z*{h*ud9dDRoK6Ys5!j80$^M zUCZyM7WW0jlI+DaQGU?-V9C2LeI9_vv-zA;4#|~W1MX8Rs*^&aX2B9(5%BjxdNs%e z2;|=Jj)vT3S4w}HCB8z##7hU=mrhHaGXUNwi2e!zlRtAVO1JxgWhKAWerJDVYJ-kP z71p4N)U-GP@~IP(xNsc;nW*D+8NLgX5a`@`n5|SV>ahVfHot zcu9MdXX!`AyVNvjFYtBD^Z({A=2HV_T3>H}HznZaMyHv!XV&3G@KxaRb3v~*VVjH6 zq8W--I_bw>>cAt@!5c&o-T8RwK6ov!+@)o$6Cs&t-4(PZUvwnn?DwdaIDGx!g=-Lq z%|L~&XSHarYX<9C1}kA8Kz$K%X zRk87Naxl%vBLCr68SUKhpcUb<8zwCTLSNRQVGA6*Vbb>F7I>6Ku$HIawxp~rlREa5 zZy{9oF0q~O-=O~saR!6TRTocO-@8Xv8m_(~Nu3K@59t1rz(+ZvRy#OkA2x#%dXL*D zjj%}H>?Ulsv|j-Ow<5WWz(TE7H;;Zix$!1lQx4_RO^ms{y1gP{OT6ZV2+luncc4(50&0GYJPyN6wb$)=N{}M$w zFRO`i`NhK2^)~U@{y)-=NzDJqXSP`1Iv=D{@?4CEO>IG9pOoH)5D`o@CYKxFs4l*@lma@!$P+NjpOjrDtJDZO?rg4BI1&RBc$=LYQn7TDS`=JgZ0>hk{P;`h z9UjERv7t@*DdHl_E)vCDr(n9Ht|?Tu9YLR0d0K7abVe2})aMO7BMu^5f6D*@dE7I= z@t{eTbVQl{<>4zVVO&_-Q}XE{cmc9XbJH8_;~|eD)@x?_hO)@J7Kv#^>eG84)&4!V zxVqK*M13=fi!VJ+8nsF;G{(EvMXc&oeHbK)60*!+0=WpnL;A?ffb7Uhv;umDo`*n? z&-zx(0n7waXLW8at+bk`J4{UCChwMZF&x`a1Te_B%i#Axd#((yiTZxvSb;&3Dp?VB z8F}gR@%Y~H{|vGqn%oL(#fMei4$);rQ7iI7KjNt#=AbS0T-F5x=Yk^r33U0llE{IS z_3}PxfV093wl(h`+#wl*UmdBS+w23r`}|^}N~-FA*2v``;L- z%&tb*v^|^k;9(qMKtCRV8?8F`nss6_M5Dh)CSZMF3BSV_TV=N77P(SS{Q&WwpilfB z@dG(}wctySgG)w2)bqHN1jU~*Qa#Wk|@R9Os*_0hIW7u6V`HAI2$Y5| z_!&a_54kmXOWc9pBO(kZudG@`g^Bo-dXN4bgW^xOz%&!E+k0q%k%|3AX5P%m4uS|S7Kgr#XR%rb@ z+CmOzD^5LbTtitn=dZ;#V|2kXxA*S8t}xK>z8KK(3?HK_UuKA4^2bhIyn9%IGXzlfwg zKcXmk6Dfyx~rY&&^z5K5VcmRd2-!FAli+j zhlf9XIFo|Jl?!<~{Ht$Dem6y$M_yIHlHl1E#aUVsUBb^f^c!mVt-ul17{{Xg%yZ`; zIzikq`@76rt$(lAC9x3C$w_^YdskNbr`OHZ{IG-LiWc~1AVF6*3Y&oR@!($P7qFQJ z+RVfLZ!;5St{O+{lovmq&!e>4tNnmoAi>f;T#3Q+pV{^FEe*G&w6r#}g^b&Dm)7RW zS2We-BsR%F-26m$fwo}!DIPYB{QN1eiXO9siKgN?`pE6u4@XLoNLZ%DnvQVcsqxO> zjbi`|K3Pq{p=LRv+jZ=_zouqvc^HzgO`^2alhmxSjsw@aEw?BMrkZ86J5woP_L&8p z)mUHdHrQFVX{Eu*uS3P1vm~ke1$5^+QdzN%K|C3ImnbTTu2wZ+L!)O>yMTzRbKI7F zmG0beS^ulHYlaxbEtH< zZI&rJ{E`vdg#vm3fYIu5=}wI|rW(j)wI$bJ=mWoWLt^le@X8_iG%P9KQnI2iXQIrx zDt3|MOcAx&uJ!j4BALOgR3G1d@Qbi^vFygVci(n=kKkZQ^V!pSYPu@$!Zi$Y>olSC zB1FP^>E6*3{{E6?xEw4QJ(}(6@mST4wA}tWqV@YaCiv-ySAKi&WhXXBWkDx6-LmqQ zHMzJ-y@=j$5#N~!=eqH#QWsiar2{Q(iu5o5tF zWO~YPvYsr6KsFE}HF0MBH%cJl#|Tft=w<8HB2wqr!V%B4<&N>Mqqa4v#@=Q` zbkpfYe!`U{RNbc~GHT&5j2+AAl&B{75+TmEve=hv-$z2821L8U@`fUhD;o|o@c8af zJ)rTmD#9HXp;yQhDkp(Zy#6ezokSMyPB2+)>_@dSs-n?ZrN`Lgi;yo~b|i)FHtTZe znMB4XBR7m6!qoN3S*!7cch%B~(EF8lz0Cwffiyfc6YXs+(uX`1(Ljzd^s53k}jk=l&JuZM+R^EcfDG2Bz&h5f9FkvDAjo*)cHghzEa;G&9$&Y{e;cQ z=>P=QlStC_jsAV-4|-F$ZPawW6{~^s{P#4;+*(v7O=xuD#BWpJ=;jyZ+~qdI<9~)& zmT@aJoqol0i2y0WoxY3@Xwzuo^FI6`N)k-6=tw~kt6Vvy(-!@5a*yKwS5@u&E62e z<|SJxc+3@cNs5UDto;kdq4M}pBYQ_d5k1~)vbXcUZ0?KKO+--Y;^#@m#S;b+1d6-i zk@QZ7p=7S9KlJ_~EeK(d;$*}-IgUm~x8>BySN4&VTBm z?rEuCC)=Z0vlfUCQAs45!AguPf{zXQ#apr`Cnt~YRlMygRa{_gAS_vmR!xF5v1i~~ z2>wj-aAA!R8|f!_)x)T4=-3c(a|yaVO~e@{bM~XG4ZsY$WAHT(Ln@=pV ziY`*?VgR3V2PkddW%oIRs9@Fx+$HcBIj&ZdCV0K=t0Ur z&sea5x}46HO>-d1+Q68@)TUuZ0EcGEDS_uS{P@a&29nYc6oG9CI6V3qIy%Jny0ILc zZ1!EtFje@m>%I2?rtprp>3YgW2PQrpwn(B!TBF`7Nfl@SZN)6=Brak9YUZ{(k)TKx zElBgQZyrl02=`jSZz3eNH!pVp^z}H+G5ZuBmeT(dY1mjgx~u}c!lC`GEMlrP*ZOY%KNMnQ#y>_EM$vpZnrCik+FyNv(-3JVJ}S!%g; zxa4>HE7eK{FRR3SeW5^) zly~1RzKLbzv21~p1G1pNRHyfhQ241*J*sD@c7LI7ZJ=ENW)9z02nD#+YSHSlXu-h9Vu~Zo*et$M~K; zb0%u%a&ujdG(gwhK6}TxpL~5g5?FMh^2%_%tGa*^sH<_xYo|cqAF_F=_*cS=RW3WL zS7>{ZD(or)O6f$J=DO&0Z-6N-vSjz5xqoZrMoXh>?iLy2XzzM}KcBEdvkDFBAF3Yr zwkkj&7-@Wmp;#||Q5Af=um~k-!Wr!9wh~z^(hphT6P(l2)AFC)-Kf;!wr2Ty$TGM zN&;9#Gl>3l&IM2wyP1iyfiWj_gvzBG%W*o){xc$r7sHdyC@2{6lvwW@`f2)j11mhK zGKioxUCep!RJ;?1JY@~nS{);Z{rEvmOg^{~K?!2{3s;^mZ^pIDXJMDcviy~~^s1a+ zR|m7?|Eu|){N_2k^r+S+w|q%E?`PP_#<*{>0z?~3cOab&$vEH3K?-COU+)6OllD@jgkck#~IdYl#pxdd3P0zeq>#ZL?9VO9pPL!2xk z(wF8yocE6XBG+urZy6W59UBpto9$M!DvygWQW+B%wh~7{NuK=t?{g7lNmO9Th;sIe zaUQ;QJiUhl-Dlu+d7sOne$M9Fh0rfKUe$h&(Z`J5#oX6&7#kseF=QIhLI?|{Q zdcc^GMH+EP_hmgFAK6~RCavqdOD~Lptqod&yi07@qQ(f%G5)wmv?}6%EG2KGd{N(k zo|~lPE)OP|rt;SAJ4=mGd7jEOYZj07*5dZN26B&YT)Yi7W3GUbMBTY_M{xD4B;^rX zY&CPbAhpWk8p#ndMzhFhymGgqO`rAgMac5fTwuEUinV~g?cYh+jD((xEU7ebo;@{x zzh-Qr({zvkSB2HqZ2sFhdBceb{V&8_Rvx!rL!g&_^7}%Ay1xnZSdLG|A;uUuY`ZAT#0~e1>N+o14EPvxQsscSYbKx{TjbI7f-PDpTL0Y2 zhMHLq4nKch3G3-m%Q$Umy*njRCu)pE*F0f3H}l^3Yt0?(g2_*u~hKlCG&@V#2@ID2{x|I^b zoh0VDIMH311wj4)8Ra`0fEKJ^@|znQ8|5r*v-Bbk?_c<=sw|qa1%OPX)7(G(IDCh` zKmE3|8haj3F_eR3&sp>ib%R3M2u^v-@L*GVxV-Yxvx%~GaOO?Dh||bjEGtX6cB$_5 zB6ZpS=#@i>uwD(!OvM@fW4Esg@n0{Eat@`@7Q4?X#tYQ?+WxASB05gj_ZjW|V?6!$ zJQMC-97n=Le+dVPIhzpaI~4>l94nnfT;m4^McpfMmg`zbkuY;tDX_i0Eg}^_6o|^pHq8GDmZdA z+_NFp+pYBllJQ;4w(|7K?wwTL$CNK7zzS-`F6v@S<9~J(Ez_|scslkaOA*-*2~*+q zLyB=;dX2F3wuCEXja%@Bv zV}O1h-64)p`}S+kjCz{nPdG;L)YmApBHCXXFzc~qb1FW8!N$1FJRM4o`EN4=Kd6gBAb}q| zq+)t2B1kK&5T#aY)L@mXtU9xbQ?tIS>)OrqxxH?%gP7d7o(R%mn{A2@j%pJV4&$1b z)Y0hI=f0TH77_HBGq3DR%I_XkrIDqbTan(Cjf-cu$y&|^^>{>>IY3z6Ed=Um7(|+&Ob!WeW~lc#XZV4)znIo}9|%0P?7L37v6V5^x`U;T1(6wCVz2 zDn@yCidD11bm+-Jy=!jsLGR!m-CclN=N}Lr)jk2vo&&#WChwGtLhdPYz-u1Ie~4w3 z->o*!A2~)}09fH#WPY{h7AEA`@_Mh_!F$HloN}jlX{n}u4X14t-?cKQty%frrh!m} zhMGzh0P7^EM0?y9CMJ%jDTSxjXg9248Gc9Ux4t1}CdE@OtW9~9o?Ftgj821q0Ld5X zdk>bFh$teXD&9VlWpWy%%C9~>GzL{GHn2(AN{0Gv`m!4gW!nMXKdbHCH9C5i!+?>KbXySldQ z_60~CS0rnsVTiC*mreGLmHMGyQ*c(tk@;g05DH1vOJ zvH0U0e(%y-IjduI0HShpdrj0t&HZH_#LVB66t{c)UXucfyHisQEX==%^tHE71M7m9 z*FnppnTqXS%pL;qd{Q(vr300#dZ^}(+YA=fIu@6Ii(O3xK3TEjQ8X>f%I+3Ni1nwb zv7U7BhLCg~;P$^-jMx@(i5J?1yeuFC)*Tb8gVJ-GiThkW z#2Ak~NmaTaBw5^oa%jJ3@rr-_xot1S?(Ca4AUN}Cl(ystJsrvCV${c)L(jtO5`K^u>SVjWud2Rr-IN^z&dVJlJ%1tt@>(7p< z+J)7-0e&>yUFGx1(M+Z8UEg+i3*_Ge#6;@xTva^Wy+92?Ovo}M znT_8(v`<0j)5Nr{s3e&iC8Nk4ODg6LFs>ekuwI>TL-_e_@MIi|*b%T6OEIN$V z4CdcgA7H%)BLhAGiQc;e91PB*`*S8dPT(vX=^E?y>^yF`CdoI8pAH!hP;$j!l-Rii zcuOv>{nipHccUJ5BPE!(b6tW^65AuXYrxq(lTb)(u37w( z7A)kD-go+?>M%4tZSgPDd3EswC)d1`SGCw^-}_9qTX82Yw7stK;mth`n5f~mA$KRy zq`xjUM|9-GalAX??KV3Rwf4O!z8PK*8I+zYLT?`SnH6n*+>KN#|7~iCnpNIYVU|yol3* zAenZ6)O3xhRa%!r5qngD!9fiCmK2nu%{ z(s)C>JxV6N(%tUc#}=}#FrCg9n=DXJhq3(I09XTvleAp3c-10)sVXdqtEXcTdf)WI z*mqiLEN;5>B)PG%ajt*5iQM^o7dOiFbRsrPwkE@a80fUqHooG+_m@10yBNGFjT$TS zJejdi7k|>j?}*iK_@~A^%NaJ*?SZiv*>!cK$^7eCCk@^-Cs^KbarnA(*wlG|)zV8i zuj(vkF~jo5$~KmwmS=(@6cder|ErAhcQfv8`5oWp8<1Of9e|R$q~b$C)G!-mNbpl_ z{jhFx=2U9xdS>E5xHYk!hhd3Z)^DHQwYWT%=;->^z<0?f^BQH+7eJrn)_DYiw9r5~ znF$mTKWQne#ep^rsysa2&t3)$P+M>A)`R{1{gkw}S+~Etwy_NA$c;lcE`S9f1^H5Y*+|*if{6Y62wp^; zZg^D$R@JjtuCls_k#|$##P!Kz5Rr5ph-GmT`-8vzx%yiLbT{GD)c3eSc1_Ilhdxo9 zRlDfNAR9M!T>}%i71CB#_F~%DT<4`rR$$JhS|P7^9w< z=^J99a!_9fb=ve>k)F?VA_02R-&)c4zRd6;0*1RBxkNlps$6l?lQGl%_ZK0n@9H~4 z)uJf5MeRWK`a!IhM0biFGOL!T7Wc@cQAuS}{%8C>@~tQuAPs2_Ttvb$BS7{wC5*hm zD+{Fo-oWRKHt{k;(SWBp;*a1~DKe$SWS%P~B^I10p=^T%Tg%5f4Qxwigl-SZRb3@2 za!giuvkdMd3=)sEg9+@@?t6y;G{UDp(^Zj~iy^D8!Sv5!bWmbM$2q-9_gBhvLe~J> z%0jE!C*0Vmtd-i{;<@?4gLZ-h^4R0`OU!|&Srf>2HRX5v{WLTL4!CwRm^==Fv zuaj7sBf<;Dc&z#%{dg<+_^-g`?_~BN6W(bBpq2sAZ=x8*`z^$>8R2@HdnyH_kom2T z-cT>ls1W8G*ESFn4gd3W-gYZWKM5cwNQ{|(x_bj!{WyfKI`r}qcQF|TbK>DNo+7BtapR-%ll@^zKmG zGyey&AgxLu7ab{EjkdqL>l~|VZSoMT;i2>g1+8ajOSdzYVacsuuO`M$UW2pfRJZq( z1A5(`3=OgVIC2q>=h&G$FMk{Gb7D6aKkta6Sj5>JX}rq7Rr$47>U3rn-B7+jys3A_0D_B@sEP_hNT* zvVM|xX@gn6*Ie8PB!8~MZQ7o`(Ujwvle>JXu1dC;b1d*hwme;=aPr##UBgGgnbm`V zvb2~7Kd@#gS*~;4_4NmDd|!4v02FC;wu*R}2MA%d8as~iTELnX50XuR4nSO0zjs^mZMhDS=xAGd zkQMkezP7gD$@(KrSGz3aIl_Y+DgbPztmBA~+#M+Il1sh1-tG`W6{qS_HOJTz4W|Jk zaJ;+(+5Qw?$`{BtlE2;=tt0dw2MPINeG}o*mO-(`p&}N?1D1a|zz^H{+qz=)P{1#@ zPSl5q8M0j`sg-z1|Bmp%-y5>=lF1?IrBc6ih|CBCl4x0L@1#&8BI21KJV%1PRAmVJ zA@TY5S%ar#(&Z8=c4G9V9V0c%ezs5+{{B(Zx zTnQjn#2^vRe_~y7Y%0i_EzWYq`RF_WFJG)AcsQIfR*&99=y@yz{ z$2NtZ4vJ-3Bv%dEo%&4aDgM_FGjg@h^o+so*K2qP`&qcqxgb2UPUD36(78f}00O3R zuIHS-2B6ZHD+`qFwmy-PjwiK=!xpS|qQ?LENsM))xX=hsn+2SJW^)I5&v%o40%hPx zkso{1*1|x0;*t6rFhm0t1;nIYvh$Jl8m=5SvmKxF-OW2E3R6o%aRr(uY(nA&c z0QA$D&P9!zYD+A-THU=4v zJfnO@(bw}&iOYE4cgZ^z2ReI3a{F6w+m7LhvpBWkp^xO?`?{J*>}ExF|4Fj8r*wL+ zCD{v_^%9g6JFB+Fw`t46QZME3ev$a@T zJiRMWo6~5SPBV$z{on-BH`fHe*Cv}(f#6Jhc=kR)nHb)Q4&xU`u#BLLwO8`?76aE;wzyogRc}Y-Qf2Gzeti2)Y%J4<3lPeLPf&fKXV1Kh3JzvbQzA`K zv>~XDrvI#zGHKPRpNDN|i+M`jq<`gFpf-|v5{BynJy*5(Mn7khjMD-@5InoDkci!X z=l<2vj%8UMxe(d)yqri5Jhm@O-v*Q=zma(rl$9mRvC+;pB-MGNNm8;lt)2g!og(jb zaazbT2$i(s7&Iy@C5%lea{pEH0*PZ9l_B>(U2__I>%x1P|gQobpm7~tmTVe&HcDr8WW zN)+@PyMHB!d8Q8?e~qoy_y38M!nDAtB#2`;*&>GMcUO_8ioAxL>kPjnL9j6ip||2= z;>JTvX+5t)3PKp2cEnpiZz2glnj4E_Q`ZxD@!vU`x2k_s)2hH%kAP zZG?O=EldCX%PjLGjk6|HwSCdTz9E+s|ABMcG_z#HaOZX*%i?`vyOf)l*QazI{%6Ob z3`N#jMY4csTAVVaUD{}UFW$43JDod(Or`1i*{KiUZU4rQD4}IjD&Dr=*DqF;(c!3mczKEzr zHVF`OcKqR}gUrl?!32rHz+6k{U&FS^MkTW&)}(D>uX3z1SiJY?^_^(xcCS^Oj+u$3 zg?+W+wVTvQ^g-clrB?bd4pu5x335o8y(X5)ZFCc~K;&Y|noSk7mK%o7^>~{tI-*}$ z;h0%_8V4IvJGq0X)8+~BBRdP|!m&{Vf&ITw^xvtC-^5x6pm(z_h9xPoY{3OVqh>j@{CodCKX{2#-E~@3w>mSg5kGL@AFVEeO{9P+I zWALhb-9oR4ZF*Jp;k!ln(ckvxHHZ~NeqmfVfNzx1I)q()VR)E(f6iIsZ*G2FOexw^%( z_)tCSC}_on@rSPhY%n3w+?L<9vV{y~+)I)HJJPviuOqiv_-Y9uCg}J%om3s5*l!8M zRJuSMk62+6QKuVC^qgv?8WyhXcYIkd}UiNHE# zhz;iaA7-_={{dPnflm$7n_V3+GYz{Sg!)YL&}&vB+flhMGW=SL=k2$jAQB-9RtJv& zK_FT>YV&hI$FC`OHEYx=AnKLO!)wd*yGHoBXMqEw6O z2HN}R^2MuP*cfjws_mk4UoH6oEaIEGPiibwwR|21JF}O*=pJ0KS^wphu2Jf`6Kvrs zEw%i0O`d}U({6}z4o2x=W;IPIzJg-p>aZ^`#`%vfT+qnL$$DPZjR4x+z^T>q@}1~i z_PLv!ubyV)`Z&#GZ=EeI$K0p9L|LVzJ`qF@Z!5wWw;-NgDwo!wqvn?1J8Xzl7fVYj zjmh5K0EpRSMKblM^Pc&4y;sszDk+z#pZ76&>%BxF1&!V2hClDXZ$w^@sBN?)z-xDO z3W(jF)RSAKaE+Mh-}G~el-Hixr4>4M1v99s`Z5YR{tc70I@@K9Rv;|ywf10XS|8QD z576&@_nlIH^^A2$PWPKcYIagcYb))Ou-SG&dqRa{Z4$roYd9Z>RK*U|3DC$&Dk?Z( zYGx&6JBA&-Hz`59@UZpAU}%;kR>yS!U9HqY0y@5{x~JZy(v+!ct9;I|ko za54J2qi!c$D)pe8&yw5U4{OiZ-`iWvdXgv?yxMdBF2tlyGDQ#4xc+h}MWx}0YiQz| z3{$H)#P#w`Z-{x4)tmbv-?cE97Uh?)J-EM#lG8UMtUR}Rrr*5N1+gWrAQX}Zfrjxc zaLjz;m#r|!Yo6mCDchLqIZdSL-d0cbcH>w9)vBHo7?AQtQPJrW_t;p z*e?s>jUcTLDG)Q%sI;f?`Pd~N9tJ_sSOgee(eDuc{|Bv`?~!h!18-s93>6vs-Yc}3 zGz@umyk6=u|A^XCU*7587v!U9y^)eVK5r_kCA3gdAJkVHTCuSVNn8{z`;wXIruQ6w zb+O&^Snkr!tKJ>v{Ju5%NKXiI6oT-d4t_S(O|zlK8=s$O>d3>7olBr=zH3h`!qI&% zCcETzU_;_Pw0`{$7P<6c5?3oYTM(iFQm?)A_E$G&c_7t(m+p6FE-@fn%J??-vsScE z`F`l#H~X5mzU5a|&e3Uv5Ds^ABCR#uoLjk3LM&G2iXBBp9J^?Kmxn7`0SoBpw?zLs*2e3y%n_tm-&1ZiV z)F-q%KErSauT{N7EvpKmeXc@y(I>Z#bKV1orHK1wYFzRy;svqHJ&%iNWyOJ>*lgrH z{p$s)0JqX%_{v;aTWih(7&0QYQ^M(}r^s@1geA9MQrP@SyXHT;KA}e9W!v3NGAy+} z2$>lkl(0w?b9y5`xJcnJhxlZ?_OCf0(JHJns{8KV6JK1X7mvgyO)>IYrd)%FGTkn? ze0$ynXi!9b{S8X-<3Gw8$PP?MIko5Gc7fHrT3YJJScV%ZjZ7ZfUEu?I7y>3Ew_Z*O za`dVKR8oUvnLK}CBetqDSWmkI$sflzB7AcD+49S0?{Yx*W?vYRL0aovV99XZTGXOIy&j|9FHCiUw_jZWdHWaahqDJf2y4euD1ZQ|44DsghKIQmtGs_t$eB ze{&kVJvgj_ZA+-C`U&~`yfiDqGp>6Bn%bUjD@>m`>Z&Qfkr@0|SjSfNy<>R7Gk9#E zafpcx=Ega6B)_h|0?4E1k|@40t7MhPviq@0yD0pflCdVNnhP3>n{#(5*cl3AX{184 zJ*ijXF&MW6$rrr;1eGy>G^yA0?ukv8fi0ki5122wfvyqnSe`64gt4>pzS!)BBTTe3 zVk)8zv}`ekv!YjUKlhSAC-ePpWhFJg?vOvM({ z)>=9NqLvm8fG?@!uH|)0(g1)Q`?4{ zXADtd5%xR)q;4HAOg3N>OLj8ilYWgB(@{MDkM^$xOlm7l#Pv1Kh-oAWOhTU+yQ zS)aYqi;}y#ryfWwykWiFXg^%6d!K~S!G72NnO{Vs|LSckq0+SJ@n>){dOBwjVJRs$ zORl_iazGYzOE-#aLtSf&RsvHElQR4=Q1@GidUCyVRkT7+m- z^DX5&j20e$llH3S?yXoX{$sFK1`S9MpJ?!UYeKki)!`pz{1n_OB#5yRuN1?>QF;3K zg7?Lu^++|DPg+z2Ei_$aHz4lpY`vcX@pu$^v{$KXwacgVY?RXVi{C1JghB0K5<9uOB^1LZ{0}^GdZ#xE@ut#zBg!3Xy(`Md|UN!)Ed7A;}`>1 znPiX)gH5^G`W&!V?^w%obtNE_23~ECxM9FR8gI!b7e%bDuA)ywZ+(CikOz42%114` z4d|5~WVa^P<>*jFc7-e5b&|IZ@H-$(d>{DN7SZ%mG+Qg$#E{KAdH2M=_D3@HrrC$*KU|;Lt177TI4PpM5+A- z^}G`8T#QG#<`VKk+A)d@6UmET+Wu(KS9eV-4(R7TPn%V>}>fVx#L8~ z5ezOBhy(sW-UW+kKV914&W2 zuR!c`wF0WFGW!=PQNW*pMggwcsR6wt{yNXP5AFT*(n8YZw+nvn+zfH)oyhhJRV}19 zAj=KRaM1U5<97(q6%Tf!Gxmi)G2;yF$0b&BJw#$`jI5 zn(Kpf_Q*d|d@x+@BCUSG3L5L{`$F0Bk?wFe9{n`FDw{a)d#gA3f!}0S1%?I>cgRH3 z%7lrTghX>RMM~D}5`I1Zo`IKR+X1 z4<_}004azkALh!st6Q}{*!5~lb!bx<`pA#09Rq~@^YeU15ny=GOQs( z;6z8=ZDNJb%<~+S(2?hvrg!j7#|xcp!R8uqX)kf7c`{9`sWF@DM)To6Sy&qJ;ot7x zy6mJcS9JN-8f;Zu{^_M5!N-h~-Kv1h?LOp^n2i~^GEXwWO=q>^(;ySKqHd1V$G(Y; zenHHnz0KNlOaI0`osarEYta>6BnvZfS{r<_lL82Xj)lBOckUXLmZduk{SFe3URcQz zGonROQ^PW+Reu#X^v{nlK|ew266Zl?)iS(N-(_;-F7GNSb**zA&@vNFAEA+`;FU`{ zpJTFFD&35m7(IW^ww<9GQ=xEg!W=foe_sOTSq{Rx)$-!1$_qI09F!6+JJX8RY8&mH6fd*)ccj@%yKVM3GLM1p@7L}{XgwwCeosg; z?2e4*w~SZYsW@DHU6j>vp*1Rav#BXs&OZ`Zj5g^$#3sHWR*0}POGQ;OM!UJC=#&cX z$%28MK5A>pNqJV;!N}wz-FX%t}dU_Zc%$c+q9pp9h2!s*tah}9ei!@<7Sa* zU}DAJ4`?vz!fi50kESSGEjOiKgJn4&Y8fu?+^g$(&JY!FzJKMM0$HaVh<{b(jB{=Q zJkIAuD7S{`g-Y%ueCF`Y?EJy5KfC|zU`jW%m8z*hXI#AX9cTR4z^a)EP!4}ro^;;> zq$ufXQ`(?mEDBsES<;9A3tna}b+{2W$53==UMKHv0QgCduuGSm)WahBtp;tvIK>j} zOJ2Ub%#I@q;n>Eym1@cQ6+3zEOA7_nwag0<(@ z-tmDvCXGqw>Azdi_`NpaNO9&{5xA4^!I>P?5enEy%4rW4jSx!q?ZV+Ksp&b>svF7x z08aNI^sZ-KsLYT4eYp1=X z9Q(EHql9pgQPt*^^5zg@rJ-0*FZ2rN=4z6akqM?ZD-nAa1+M-56#XGhBzU~5sj;-H zwK@Lda;@Lx?KV&-BvmuoCDX}j$WZa>@^FHox~^kipXP2}!i^Dc*4Wk`x~#{>I{_bS zm~Jr2NO+BH8514XT1h^aYd%;%K<22ulsrdUn?irN$1%wo_yOZ#ufNDEr)PpP#G^XX?Hs8Xe(Tw7@3b zV#4$_{=I~qJS+ph`7duYm*y9-@v91TRNIYj@Srdn9F){+Rnno_P2`EIXQI#B){YFR zO%5to^Q36ZG5xudjIY#AjjIS^l4=(&RO01|M7&Oqei*7IURvIZrW%sB<*gim&$YP~ z99G>SyCU(Wk*&(LJ6}f0LiF446BiY%I9?4+y#o3)AiL3_(D;G<7wjc|#mi2dGPxlc znol(&m9Hh+{6OG^6M3H2>5hwMtAh%b+o4yK9HgHM7lC#+K3S?E+)Z4(M56EB_8Wc+ zg?ZBDNGH$IwreiZIQOWRWA)<(@Ir(6I@o?4&jV$}-8PF`I~CU|Z)eI#ArNhETaW&1 zP6um4E1WM>3him!vQ3T~vNJe4H|NYx%6|4_a(d^f(O{|>|eY1D9 zfb$J5qCZ#9Ly`qo+GqQ~KIAWqRq<7yJQNqQV0aP>y{%QTZA~BR4l(JHjz@icYsJzi zaAy7HWMJt^kkQ1q2iWx8^>svCLd78Vkz>ee$(4s*kQmYb@A|OFn)guoLwXA;#wgAc z)2KupA#Lp|HBQQXazQd*tDFeGgREc99WVO7CRueq)vR$psI&I6Updo2wk%rioFquB z-D|l&LQRf8%B?-ljPAF$)kn+nw|0-ynm+oh`76M#eOSdJ7)s+^T07_vpCH1`1>Z?L zcbYbki|vtGvFeIB6`(+JN~c++i(BV$+MAh*%#1iQ0R_!Q^MQPEeGpzNvE0=lhfTrB zk8>=rq}0HlmxLnQ&62F+w=58FHKwG?|A(k6kB9R8+GB5%ud-w>SsH7RWF3_-$TD`> zipaiY$u^`S62`t)$WHcsOOkc64PuP!`#y#lX5MGi@AE$Y_{*95KF>MlKKFI5bDr^h z$@VrU*pxz=6XH`{9NR#jLV)@ZD4QJhXG(^Il5F_b9;EKFrkE5dBHk#^Y|?D*ZZkb3 z-34&h*;YPMbRiG-xby+>@?#}l{ z9{vGp>P?5uK>)P%x$WWSS;04J2PNYn3H4E|`_@f;uYubr&>(YbCO)1etL{%_>7nUB z{WYPn17)#XCP_K3pq5XQOw?@|NQD~jj<-nv@3npJ3r)aN3i|6iK(o>g`l#NLxJzax z1Na1lHXSiLne<#Jsa{-ca}4Evd zUzwZAch!v$k@I5etYCm1OVWILWj>|mrdW!F+bRASElUvxBC}?F2 zDFq;tbLMwdnDK2thhm3UL7C$$byS#^c?6jLLenU^vzfOj?UpD3YXE`2I5DwoQno_; z6;sxT6)TxM#J6rsV7udCiTby0`!lt%LRG^a1^NPcTI~1QHZBk7om;nds+sU#QoMv? z2!5Kdfz*m!`Hl4((|eCYQm&G=1mpA;(&8gxp!IgmQfo(XKW&^Fga|rL%t(J=1m;>b;T+Y3b%zIcw1~h9J|6 z6$V!>q;C{l58X&o-%UuTJ2S;JAZ1WOTb!+u>R0^<| ztJHHG(oS_j_X;wX8Cl1|0RE9L!_(ihe_$^kc=~Sl8Qi9!aM4!Fs04WqkUlOmQ6C&7 z&tDQt%95Ps&Z{SW^ViwEiZw3%S2xLJe)H6I7pXr3#5632SXN$$sybcVw`lo3~qZ-4pT1@Z(RQoqT=U@%Uqe;`KsfqwGt!W zHL&tQ7x^f{3`gGI%{hIhC95Md{r+S>K<1aG^n-qhXK`>?rRt@li!SaOxWcYv zI;wDfJK0*%^!}QhD#gK;p;cTiEaLvo`@!CcTjo2Y2kV(! zbBpJj5&O}os}8Nd<(<7dY2c#-wDryaG*AMDL}WSNES)>D)vqLyb92SznaAo`^v+5F z&z&)V=Lo3YH~}D#xz8=hA9o6@{UB585$m~3mAN-hr*+ zN;4XPE>}KWhqKiH9rvIMaxG}!7bqj5RYr*C#^&SE?#tM%h>K^?-8U8)`f^j8ma%*D zIjfdp2^NuacPU;^Tjmq7SkQvy=4rLIP2}7NzsZI9B^Gf@;J)gk+M(ed*G%Rg89UL? zHUKg1`Ej|;%e{usm&Su$W(I;$={^CUv?Hu#yIhkg>3sWzg8Zhw&O5a6(Ic#SxlbL3q zzKR)r82*oek$DnO@-NnK1hDG?>Z#l-cX`zj)isM87$Noo5L%{_k9-QKGQ!|Xksjbq zQTvIShte4a(b}2VIG!B0*qlrpuF$1<4pvR^!|(5;^#4=xI{o+b(?D!5idxpi*ujJWQ}Nd+)T#gFq{ z+~AhyyWOdJo`dbIqBzj{Skl>v4zy<8xcAl_s+8)px&o(#-Q<(|*n?)#(GRRiH&{m> z-BY8SeyGXG_yo*V`K-dP3>XoU({S$Q8zTRb(_q(Lc=vsTkb!mqB(>W5-rsfjJy5I2 zG7rR}LL^8l*PL%x<`5M-9F1(mJ2|3`KOR^)<^p?4=359kb{Ai$Mb-1*rOqZ_zkg0) zcjS|yC;qVS&fjzFqYuzlySOR^slE}d9a~x^OaYL6#Pkgo7>TtT<>kZQ4XyTTD_}iI z+M2~uy_P*PMaZT9lI*7so@ysB3EQnqwY?@&jzG;U#p(cGr--N;<(rtpg|!2E8F=s9 zseBOF^`W*k=A6=gy+OtiFD-2k9r|R^KS%qaI+W4X2Ko_LXXnCi!2Et1nU*X8Jk4cSF(_~&fAOxb#nENfq^X&5Xoe^SnTE(QDY ztUF)j+X%=fBDOe9BjqP~Hy>+FZVyFH&B+ybCbL4@&N=y<#S0AaR%35p`VnWT#-H`>ILShc^H+>HEAUtq5c{+VsCoJU;EXHqBx`(DV}W zy$|SAAKbYx%8>|A-wGRrC54uymqwZ4df<~vf2WeI(4Y*tDHtr?_*#aP4l=h=;93v$ z-?sy>Sk{1~prYdBVKzXV1^>+W(ZkJ{IE1b-98HrtUrV4MsHs)ZbKG%?mr|URdHB(F z>BGFmlnC0hI1t->yEiq2+(7~4Dny`P@Ew+e*d7TF-ve!>0|4oc&C$+=?VkJRYiICA zh#a${RsaOS-GdlXn7*D8>Gz3N9m_f@#$O|610ei;HTB4OV2VJCWfq;L|r%5l!l-Z{L>T<%aj>>tUTHn4YfbT&wY_CEExn*x|Z{sUX%ITA- zuacLs&zcku55O|7u}AHjnWPp%uGf3fxmPC53cv@SSH83y{EzyiKy7GI^f6>(6H)?M z!`NO;lww%9DE#G!h;9f(s00I8u%+Z;=eM$I}s`-W=pl8E5i%Nk*-&%p_Nc0=9oTLMdp_auflYMi85s#`=f?J@)7O2h2!e6T4v zx`orZeIU&_#1L6QLX4J3@Y0NY+hiOXZNB2((ZATS)|Mrtv>(X}P1rxuamt6R_1a#& z_NMPcRCjk6Dy#pe8OJ{@zd&DY*_ELZ-`#fX6M1*8c9N?oChVJqPxL~U=+K2yBE>;y z6_A%Sep5tv)+}RW0B8HAVA!|J!!kw&`9L#<0lD$g#gA)CpF}0uN+L{a#Z_Nxcq2<% zP4-0w8Lyn=R?_=!w$*p`MxnZIVXc|1JbWU5r2wGxy-_>9fjS7^KRGDF(Itw~3ExgT z`Tdr7Pk_(w3OS6vWU$++xGaMad8_4)9TvN@iIJ_ zc%Me~*8oAAYHI3XKP~4h#5BNmvD8gcaq|=F$s3b3&8B>yLHHQl{=#iV)B0ZgKBs1- zjle@Df3uUp_mdYN{XIO~RLu}UU+sszsALq7Op|NDkSnQ=f1o~ z(%QBpdAdM%1XkXd@IeP5L$zfsevSi2b29u7l~;yk+8)(>1SY1IW9=kY`N<4Z;As=< zj1J>|dH5JzMCwT?X{(i1Wc;J<2i)q#Gp`qd1|h{Q6fHWB9&OyL40;r-st(=tO_n{X zVH;%v$Q@(>Go^Jo07pSXFm6$ytPYb;+&Fxh7m;@();a!;%} zo+!8Ew2EYuQ{n&?CBODw8Dzn=_K(iV}kR^$AA=KhWLkdfD3l^^%Hg z{qKsoiT4cn=PqghAUGY12%JXe68ofcFIm6_!n)TfBsUqlyvXwcLE{g_z~b`9+qkf< zq_vVDzWOh>!1ay1ox&;r*gJe-lJ?BH;6nuaUT@z0254ZatGYy-fBY}&yy)J(LtxYr z@O*W=k2RdRq9z_!W%7ciMJh6UNbSftD;2*tpep>Xd62;~6rk0wt~#w0O;nHrjNZGi z;fLt*IJ!x+%oCO4_BxeQIgRc73)r=>GO1xpAt`{_C|6z+*7zpVOWl9l#-5q}-Y*8( zG2fxCXV;>a$9jyAww?j1sk-Q3=;`GasmMaWNqMNN7+wsu3`r3eQ-e?Q72>Ga_~YvB_BZBCF>$isnzVN0slnr)JcQv zuV=#BRlbvQ(6&4P=|yY5pjO%PgucWggNTl~$2=LwmX;De4B$eg!*g)SvZ#@=lG)d^&pcsPCYLU%$~2k@@V>xnV3gDN zwnChkRAtK)(FKO^_l;-9s?r5o*vy`)bKU(bi5o1|2tbJ;@>|*u+(W$$8}3QO&HpJZ zT&=dt^g;#aBb1|&XR(|!G7JH?1uMe=46PQGP{-;x*~WPVj?_T>p2iX zlxJ`2NA&IgH){84^{OF-#2@lfKnJqF5^`KEJ-SDxR4mvwA1hZzu6QW>_Pk7S&5~8+ zQynB|BBT)+TbmUv&a|^a`~!EZ(cC3lgwVvW(^;0lTV^$bwFGp$<$1fZAp=ard^IJ( zHp9)hfJ7QM`F>hH^L{#uVZ^v@`#fXAv~1UtgULHH`s!eM4OPQUoWe5vN-31QjyA;$ z_(~5Vo%l{i{AKeHUyz)_u?3%uat8FTdujnx*u^XIyz-A7{0$V$PbS!y181iO z%>JX#I{v_lvH22IeC7`HiES9Z#u+}IL3godzJvd-&57^WUT>a8!(B2?;I~`yyK;Tc z8W49w%^9iJ?OHq*dXC{n7B8cq7$_LGbXAQ%mx+7lYpC2cpmYF40Hn3W1Td}U5sRNE zmp^O+^#sAY@WQOxc`~xoBzXBrkzomfZ$Slb_D%<4u?Cf>f2`Yp)FIT(jTXGpr2B(B zwbwR9Bfg38is9+4KbSj}A^=B!kx}Shc z61Up{TYUH*u0VW!^c*2r$R9JZ}<-|CU1N7b@|9rWy%YTB;wJWL)?- z`=}y@mtQpVdUMPbE`>gR`>-C|=jV^^XsoufQm`4>O(cG5i?;2VYd?)368UN1C zUyf%%(4*uHIYmZpl8Gyg*o8=-M@_vTK|>y@uku;7WT-I4MrLI=m#JWyWlH=0IsO9Q z^q2VE1)%cSHc9*!S1&593kQ-?9cz+19hn)wXUolb_#`E*=91^a=Wq)TP%4+XL(8|f zJ6atX*JS&H37ed4X6m}i=?z%vR<=P30JZ!E)P4Ro0yhBtK(2n@0e}Yp4{`@4tUkqS z{q~rPLK>oP#y`2opnl5I$_;SQf^zHPH!YG1)Atzf{Hm+vYu;D7s5r($7Br(o+g@ZCKN)oKYLboT;())MyQN*AG0lsxcN9JemxPmm!PKfw(JBnn1Yx7n zzO*|o4HgaowU(}g@EG0?H5-%2)oB8q&8t7;(eHplejXZ~qPFyg`?Uz(aaxg4JBrkm zcn+5)VmiLE@9W2;V$*7Mgyxs?&2gl)t|t9kk_kV7o!I>am_hqDlHyrvweZD_@Vr=0 z7G_t(d^ZASkSVC}SvMNU1_m8*K_X2n_{e!;FP`&Pi!jZ4yaFL`)9c6VnxwOPgMY*DKOikp?I( zyitAc+UzoT7}9`DQ9G4E7pkF7#)cjxWu=LxhOCOd+6nLjIxGx7S593IZc)mR>$4By)^mbQ@zU7#Oa!GeJz%ubcj>1gW!E z7qS2?NTy83>cMW{o6r5?{T4UGxOudKy+V_8&M#bJNXfwbN<_&ja)ZRbz*kU7f4E+W zoGz1*{d?^T4i)8_m^#`c6(~EYC61pH$%Uyi3Byl`i9YY^^nX3TH3e1J4wW<-j7$+n$wqbBc}Lskpd;NAgWeNJF*}E&QyXf`sc0pdYm%#sK+h*H zUoK4;=dMh2-R%_qjjmwdn)x#@b?B!hRI9hx<^7%$;<744mbBzU^c2eb0rx7yDRP9) zd%XOKfvD1cAQFYaxTFE(dQPrk6zC=}V8Pf5d zIRb`CT3c(vlx}QJglQ};(EDJraME$7xQ&$n7_r{YKNglVISAxxwHzCFxJ))S`_4{-r7 zR|7$)x_q<+pej2f%VsGPq6#FF>PEMoI&6GPy}}cz;M01W@Z{Uymr@sO42!6bBAw~1 z6~sGqJb4q(4~AMYK&RogejYvv+j_t(Z9#j87eU}}0+wul zA3;XL6mQ<#t{DLn*9es$wE3T%S7Z{CZnHtE22CZp-pd10L6n{<>rbr23;)UD{hU03 z(4QzkR6T|C`TRTFBz0qL982qFzl9%a4HRGihF16)4fe@~qqnO64QGcPcI8w781K1m zv9;UHn`QnAOtG+vw+41TcM0FXt#cM)*u&$E)c-C z=LfK63&o@tJ|<{;WTm{EtV$}iWzJFUaM^d zZ?~33&~LlzJq&#wtywh5>hAT0c^TzE8>b@A`F)nhRcs=|E0uv6M3wRIE*M=Ly=9F{@AkX zmh{P2CQ@$BTm0H@Ep9Oe$kFejQub2PCPBni^)%%fm%6hdj2;-<-=Z3?y`QlWB5llm z_)(VbHP%x;O&xr$b1QH!a$`7i8X5zm37;6?&#iVu0kwa~fQ&F+c+j=BB2>h|3b(qZT!IbsgEw!O~!Zzo3+A%V)_Ej=J^T2>F0q_kY z#EZn+ZlgMmgRcrj#&6yH6?0o$TkB%ZoAb4A2sZ9n@~dCcTuwV*WAz8nNB&=?g2 z46jmHXjD{*Zp~u3){TBduKPN>Mm0$vACu>JUo8r-Pj3!EE=)D8=Gnv*nnRxCzOL9K0KhS-eb$YVlO>ms$9+?A0TAcFk#8(n-Z|xLLYFj4) z-aeLbzsew@j)0920@nWfE(dL0X+<&$a9!)%y{Weo^DXGskW)$0%D3A-n|5OWJ4l%; zJ#QuCVz9aPMWAlp45yzA5Rc=@B|VUo?H&T;g^utZ^aj zJg+<{o9mAad%jd3@=i+TtG}VWfm#Jcr+)+i71R>eFiE4gj8mag)sCGPf2P$gf*X>Z zkd9dl&;x_Wm-H8ST$C-R3#^q15^dSNHymAA zro4+V8o;nL#zCF$9X^@{7!GcSX41Z)W4X5gMHCO?*Irx&y=E@_Js4A{IDL?sGtd7y zV%Ns&5m>(i z3j6$?qzsrk(4Dijg)L8!8krC>nN;D_C@W6nZB$36?S5jwuT-ArEtJ`WD!o4&fMw?a_Rx;jQcmb``I2oo^M$AWijn~ZF1VfiL zL#c0&*_fdHhPOEm&+Q4t`GsXEFMvTEgMDgMQlCAit&Dr%3L_3d^X&{Tw*$Ob@YLIF z=AAzgD4^S)AxUgw{n9#8NGWc9bNAPSx4$>$yn0>c+KQW7^F+*<7!6t#F2{*5`#e0{ z(&CA3CMW)-UW8R3>b4_fO14%$P5MnB`${qdvOjAzLwjEtH74#)=>A!U|u zzN0t67FGM`rsg>x25E&BZr0QgD->oDVV2k$i!b{&_IWQ$)e?S!%^S_y81)P8B-f_= zbP@V0zmC{ELx8Hx8k0O=c*@ex{gXMW%&-hQ+2QlvjWvFAcmd+EOoPgaP)YS^l(?za$q5Bx%~1%j{h=g*(+ z2Fn!X>~R00rRKG7>`Jo_+#wVZqV8^+0t8_7c2 z`SAW*l*w3}w+E>_$-{Y|zDy{f*=19Y3742tiEE!FgMrIZf8yebDsuH~4{I=T2n}!o zz{~E}E+g*mbaA%EVCCGpaE(Al86k|a)nN7Zpbl(2kpf5nObk2@wM*}k=#tT9h<=&l zU)aR;UA*m9n!nsA&V`9X;iPVkB|~t-K$3}tT*qE6$5sRYtmRiuN9nWA?g)??*u@g~ z{130~Ex~n=Yscs_iy?9!oHcUb#kB;SP4rB0lS zM-;bah7`o}GPrISS3UQ|o7Hy3@c}>a>-yQ?yVau(e(%N-wk^~W7cN;K76hX$?jCCU z5hEMWkx)v?+IfW2+I-^H>tnd+lFPRy3{aR+xsFVmQaqZ$SI+FVIeBFcoQFCX<6Q!2 ztu`wO^{K-@!`@DOFc(Mk&O|v>8vf=ZvrQo*%Y$luo?&G@Z|LlLj5rPcwjwW zMkDLLgLePb016Y^PEaG>jvf;3h7`nof3A-Zma>o?a%wS!F*?4SK}GQ89(gKq4=pOT zs21-LAM~~yC6rASWj;t2zxntL--*r1+eZ^l87b&vlh$Ha0JQPS!dsl?#=$MNh(5uM z1#s?LzrAAlq9*-{{kK4`W9KTL-17F>sZ~XjM%#_DiUs6Izmj^^hfs#ww8cNU1;K{T zY04qC1j%X92_GP9&oZc1dCfb^oo$^Rro|DB{y|oM@PwF#P~HUw@wj~*pRL^0*2i>8 zK>IxZeknl6Kj($upckWFXC1dq4tu@f^q7bDU@lD@bfr-WnIxv1A zijY#??nUmPpFRsg_M1TYv;dgB;r=@|ExJMbgl&)7HrI1)DM0_F7x-CPcLiR!e9P80 zcX=93@Q)Ut5#tAT(0A}=$HQJL*W*LdrPULmB&KsoRX|Sp+`k*a2(-QZVivBJF!x@G z77#_A#N%8g|2q$cX-!zKK0((bdZ{Y0Er~e=A;xyLYock`VeC3kU)-I=A#zk9cqj7L zvOpiV_@E6>Z03pQsz)JV=sch+WW}Z6*7m#dIBi80xkf6gK<5NQuZFh+k9d-*CS-9B zG0s$X!1ZCgv$p_dmppcHB7d2I_!R7#np|h`r5XyIR>i$QXmX!B+CB+#-FdZ#gp{p! zH}?TUaRCYnDuNl?exQi`>c>B&O-Ee1l>2&O*I^O`2foOaRYa6uyHHoHgTA2r1sE>N zd}4BfTA_7fPuE)!8Kl2bIj+6-+6YE;t&hjAnchj#mp5%Cu1wkbe3(RIUZ;@(s!H#B z0h{$pEKu77bo1tgao37Qqc6wd1tpUh6FM3b{UZ<*fmpem%d|Bnqy**9%K;xvAf7Jt zB$%-!Cn#D9?mQaxi7;yZy}ovFsWSXVR7il0mM1O0eJA(v$!X?qRU-i%bf`|{Ry2#i zt>N$Z`$BDzzyO_QGk|=lhV>rfsC6ae;k=9}BC7-~B=fm>6A^=f>VC-)3Y;9<e`H$^Y3&;N3 ztp{FR(XCJ~&`P6t0P#FB7(UqdW3DMGWPOtjO3xEL$J)H`jo{Zi z(LK*6qrccS>LX_Q1*Rq-))i&l>-|aLzHH`FNKk zoju_uIuOL+MI}&sOq6PcZ)kuy!$oN40=J%a&M4W)tEEYmyklQ@B>s%E2y}zI?7##x zsrVN_^o3o2ySUIAG?VF161;t0=S7y4#O`p)%cQhgSt_w}of|eT92h|+_Mxu3wCh6( zNt{2{-N0{t{O}Yt{E2u>F^%KR+VErikG#$x$pO@>8c4RXvhfed_}9f$A4wrfp+8B6 z=V?PH8MqpdeUOFhz>d^3n&kgBwQK@hr6rAh9<4mP;cET($eQRo{e<*9SXC|~_?mlu zho5L$;l`xpNd5oTi*#DT8WQY`lSGUck6Zma3LWo!ObH$;1@+x%y~BC&Q~T4pdj-|^ z7dd$D9=8dM@TvJZ2+Cb<16zJL!|5vUflGwp5-_isFud>+K=PFTV#w? zOy%D4Oxp9Y<16)a(tr$zFPoAxKvG z;n!#rqMd-@78SiT`qc4;^HIaniIaz`>FrxSU8e6zrt0ls9X=FO`ToKCzkDYgzll-t zru{zi{Zc-g>-@ukMI#CwvTVE%NGmap?!v{?i3020^qv5eg9~JTelQz;*^4Ie$CSLM zC(V_aRuf0A8g>%ny{O|4QEAdy{*o7T8Fl;?M_7Y(?ZT?LJu4|T0w|uRoJ|3gY3{#r zIG%DG={FNeewUUD-Ze>$7pJgSY%P6!V3HuqFQB`!6X~fhT7&+SOZw80 zeTQ)+k8Ax(^9VbfDJA*R1gj>egk+zw;dQwC8cG8hbgMh`=OvwB&130^M*a=#e`VRv z+Vql}nJvsNQ^Y>x4e?mw^5N{1S>7y>qC78Ic|q^5Vt&6oOB-GvR~y6m;7zflE^lS( zL|UfremZ>I{J{dvP&^o?&7h6SyWr@ur4y!G&3DwknQ6kzI3zu+Ie8*WpTe;7KYyCM=OsLr!SMr^OL7 zRy@9>0k-kST_`f??%VoZVcWkjXMK)-C63LOvaMWv%oJ!x2YujB>Nh?=enAqe`Qt11 z?rA*rp|Oe~lGt4eln)**FtT-UJq8+^bdEx*p0cM$!_FVyQ?}aZY^H!NM%1^@Ann&R zvgnJ0WF!_%<+j4F{)v#v<_-Ex`H{TRs%`EI<1){PwL<0oH-FQcRe~&&?QF5LW$>Y6 zo{txMhQd>JPTIe?boU*p?9Dn@T)7ywMLAyjH6}=rP;a%+;~#kx`-45ickJw8&q8Q> z&t~$uVDb_x<`?KDHZ4;Xj_cS++@23ALCCxB!cD0T+wh|tEv*{)BWe#5j{%F=GWWOb zKhcQtrs5ve;H@>Qe7RRIr}9u2EuHJ5=)YF7_ZCy*=2Uw#=(^|K?TP@GyG`e;Olg$J z24UYWUU417q50^S&2C4h~v!Uxu~5w5&ZUm;{An7rGz%^pqckI zo4+2IlRZ2!Vn@-!t0#$MGvXWLl9DCXpJER25jN2#_V!|S6DzOuQ;ujVnN;iq0iS6} zd_c#Lal_5gr?}d;_UCJMS4@M~+QhlDE1y7j9d)*D;r!Vhsqc@SvB8!|Z^@H1H=q37 z#ZQDE4{gub#h{HDE05XGXH|ka4|_w9$|+^Hs$kO|s0R!uS5j$iXiW7>W8@peji)6z zFFu|k3|&&2s}RhTZ!nOeTyf;Y1TFufddubRS_pa$+H463I;tNNkv|ByUH1^!h)u!S zkLweyB3Ue{^xa;NM?A=F@8U&)e0{G<=`Namyb<#@I>Ik*rqv z8hfuqBptyEPdQMQO1;6kA@fIHf#Z3=bDwlVBrE^L@T0)v|Y*-B0j5AJcRT zdU-XZrYZWqC~`5{)EFE~Z0Fxov1oKT!58VWx~(kjaTia=X5VS+|L)qBzvVtJ1p>ab zh-7V=ct`eBk-?lcZ-u(GmAq&kLZr!>;8fE`-Wj$L>aSM?-|k^qfg#teP647`_BQs5 zzuIOB%4`=EHW#a;&i{%l?p*JIotOsOkDkqeBmJBlR<$JM%D2Z6JWWm5dS zqu0lG9@TFAYGXOI|I8^uD1-c=ri^1}v@Hs=1JkFLkNd1-8$av1|0KXIfXmCo20VRT z@t{2VXnmaumpowc#LQ z+M72*wN;fpUshOiGb+#1pWjU34b=c*`m{Lt^I*?!O0vS?Ztx#)u1 zYVTL;FSZXM7L0$I=5J+f@<482y53L-B)9hEm1dP@X^64PL$$k;;?B7y`CwpFFH18MC|z zzxbHK*4Fj~Bwi63e0FiOYh7_ofclQdrV4eecmH{XH0;c&t*{taecjsr0}%?{#mHV@ z6=2*oJNuTo1MaehDv8TC7SibRotPRqdMW2tM}U1yA%uiJq>e3rg2rRZ)_&C4;?*tr ztSsdM4(~~C;%YLN(08NgjY`ex*J*y#lMP=j?rodZ*7|x`*d!95Rz13xDed~R4>Z01 zJv;h%L9AS;L8Rg}wT?^c$*+?uJ`IEd6LT`rZe52ooB1CPyw9N(#$Jx4Iwi)CWa# zkCW|?cP5R&0yk_DCfV5xxT`04kL^#Vbi$Kq<=T1mq=$(*Cs#qdJ@A6+J4Q3!l`d>< zfx>NJUOe&K6Ws&U`7%>Rj&Evg3&K)Nz?V51kbk3axcpe8WK7n~#iex=C**# zcnUBqGTy5`eEe8!+T-Hy^E!#s&B5K3f-aJGhqxT=Ep>V|CFY#dq+K&%ch!)5!FHSW z8%G(yCF6&iLYo}sNDIDcS4UQNINuBbw+{cTsdX$h^TdlbXqxigm13EofyCPehc=AJ5>^sU(rdhYH{4!*`sSZ}gr%`;#%QKLSAu4qB zAG`>e?73hOc}Ak1y3Q$J9Vy?$%yB9lsTCaJ(K%{Fx_@!aH4!$#cE}+~zioQG62;&$ zL6+Se1?LXLrzj+ER1cvfW|jpMRDP_5NJvU%mx~6@f^46;HhAq!{jipiq_8l08`Qm` ziuE+(BwHP$41Y)y7WH^3t6&eJ>lo1NcQP+b$O%bC3 z$X*|Nuzi%{N*V%p!BH8vV9p^f%J@VH)v)@Ku9o)!ISkIr7<^oxZY4!pK_E9u*<3I& zPy5F%h(EKo)ygI-d|?P=csSR`S;I2MXcC#!J~BVQ_GiB(oHr6Z;Icjt$MB!~h)RZ1 z>f!7FTH)4|C;FS?PBA9?G|^`~`tl}N!vAolwXl5v7Ljcdd_L}M$8 zo=X*Q5|OG?%j>f9motkl+-LU~T}|D1m{y`H4b#1N3^(^s>J}95%3ij(7yUh&f9~~e zhP~OV<(-{Qv}H<%mRMDp{i>0#Tb#yub=}s3C4Q@uwt8-;DD6NyjY>vdka($QB>C%t z(n=)g_+Zi%-jhzZ!)Llmt*P{56p7>fmru;UxqJ?QE@tjY2K{baQS!j!lM~+OL#hGY zK6?)SDnc=wcX=6kZ;ZW`EBnLelrl_1&`Iu`b;P-qP@k5)44RL|^{mCYZBoHM%{+l_ zkT@ikLm$LMHjS50C=Q7a!h){%!3&sts;02|T8z~K+joi%(D`iPA{2QC&3jFrcR2?p z@~@7oGrCnR%6J~>u{~zxzHG9th%M0OSAsD-q(%+w{gj9czl)oKiTRhh7t#H7#gx77 zxH!mVDclP*O*NBmyj4z;#MLkeifh;_w&i?qo_6MxWgkQ0U>_#YmO=$g6FGJ6Yn1)y z#T@Yl6gu?5+>*B*gH2_-q-VWf``*$1`S(x%8b#lE%Em49$ye5(9)o$){1MacJ{&;y zeRAEDR^%i}sUG(;HamH%y*an}yHcJ(l{9a@z)Q<7L zD`5fp2M)a6T<_1kuX97=y?Pt$zKR|$ol4$C(677F9mPZyQk96)9Q56;Xjw>=a-9B> z{s36*wdQzn8E0k?I{l1VXXa+b*~6DnI6G6bWWGy9Q4>U z)3iv;hj3JSEnLaVr|`&v{dRP=zrZBC6wOpYe)OCo39UH28b9m|wW@UwjtCce^zhQ*07E zW1Gk(^Zt+J$~jsGTHaQY6wRDZD;< zAj-Tcd5KD7S3Q_b%ZKuRA?C66?cK8bn#=@$imvB&HSK$-3l3lIwLF_kjdER$pzTq} zNeT+J=ix^#IGSHV!x%*(n5Rx;gPqyChO(9<(hZ{7kKFV!g3-?V^lwT6P}RR47@r34 z1t@|7BP~bp(jZ194F#yqa7t0_{H*6$*oWE2P9ISN=hynqLU^#db<725z&96zLr zQksrk;FExF(-%#<>H3Jq!_~AS&)y6!Q&!gNo#1+Zvtlv9)pw3V5E8W4|3JSliQ5;m z&&bjFRUtWeuH<{kL+XU4U5>6o?td;34Sc65i~-}Az#u*1wf)kOj*-!&X6O6JuqyyF zrAOvG(YO_&PK^zrqJW&PBr z(D9pNZOj@znZBanms$XSCSYt8pS2Mtn0W&6Ei$f6G@6| zrZ+gruT9y)km8Ck_Yt!RLy$95ilOX;fzc^ zD}B9Si|TN^OYw_I@Q~av8rgX=^A+V_+s{;?8m06qIBM=z2@tpCBPl$d&W1nKqfr9& z^;yr3RGjP>ldlAfu}Q-p2H!)9!ge7j(^k}>MKB9vOp_N-##wV|SP}4|N}Ogx`pN08 zDKN_aGEUmkWuWPeVs9L3U9J{<*KA?xC!Et+Mi zNe$OgY-t2ZZUPflq9> z8sE)(&(D56wa%iepvUgVgQWQC=}jPE@u%?CI0M|@K-+(6aLVzS|3}nS21MC4?WL7` z0O=GIRGK9vRge}jkZzW4VQCgoIwhBs2I=l@SU^I$Q))@+_-+v1kN=!K_c;^S%v>{v zX?VMCx4p?i`(iyFPJ_gB1Y?MEclqwqsh6AoZvOJ6Q}1XX#J%)O5DrWsaQv$^bn11G z%MAZT{cg#PZb@kQL3g&yk0$9{mrP2UI1DFcN=D^V+m9^jZTBBPqnGCJI$nvB^4z$z z=d3Mqo#@5fZ<%Kb(q1D(i+MtPR3*go9z^XXLI@{A(crcFZ7fr`@Z#Sw6nW90{O5HZ z(s;oai!rwTZmv~;BP!welKts>c80p*5~`Z0&Fr%BC`BLm3%JUt8(>6Ebsl7r9x-hp zChVuk%jkr#cC?qsSah8KT&JacYi)^k&`Pjqp)3vNNQ0Ul?Hu)o-=W}Gn(RNJqQOR( z;q^X;?KaQfKs3=fMMUyYf3P}FRx{MK)CIqg5Yldx4E^0V?by_A*Y0x%Tns514dzF= z7nJz1w>}eSb~1WV?$VeQs6xl_9X>2G4uVq+KZl4qch0SS>xim`wLbik0|KJV2Y7>2 zuN*m37p9-jk}; zXa^bZTXzhk_NzQCfo#ct*`Pf6uj#Q>gXeu6-zbzGh6+24Qhr*x*9f%qu+{A>1*ava zj>R#jKb|btYQOiB6ra_0$BHqVEUPfhhrW zHD*DSC(=oYbqM_s3gHQotx03_?|y=->`5GVDBu}3z0vl>6^4&uH=}LT#3MC;(7q{(B->Ppx)rVcpUTc)u~>!x};Iq8E(s<8fA?Ma`i+@ig!fW*%ii94(~reoH1}gxTMLHOyfBR#R7Vv` z@fWLmKUvm)9blDaLyOW9+-PkhaGdbcWDMoQ#?I_mi$xldfD8v*I)r8g{U?`-R%k0Q z4YX=?aBoubojH$SQ&7j*XvA>}+|Wy=baa5$cVoSnc=Q=ZSfWfL6iBU^uu#+RqMATR zb0pDC$|*^<(wY0NhBIF;4msX)QGQtS4Mk3Gkph;CmG{qzhi+V8@DQGX7&+l|TFPrnEx3y9xV}2AW`=aA zsEA$5;-6!};ju35V_I_9zq~s`LHStU;oe^_C{6PTqZO2tp7*4$7pUdrgoa)&59@qu znO;@iTesvW)8K>ZA?>lz)`lEuhWB=ikNg}UAk+_g3vQ!Y>T1aHAgWJK)#RpGNEH191L+_++u3>==+_`g*58pYzH&UYPAAywU!b&F|-Od2sguF_fX z#A5mz`cL*OKF~+w^A`n%W{j;VkkvALa z_3KKd5Hv?FftgmL*lIv`wxxHcyQ(y4 zFkWc-`)2?-iTFqPP*G`^2j>~VO7rHgW_`B!nnjh?NYG@t#ZXM7R-tFoy?~CIFK+L* zDT(FdXGNelk@ixVbQ(%9ndm1l63X(e{E&Gs7EV!w-0bSY18O=rYXJ@2+CeDpV^X@4 z5-6NsTIuJpC1D3^sxG}qyx%)Mq_k!$sEDLt+?&cq*eG}OOy8lc@l{g|;#mL4!T%nO zTrobTS9X>IUSlZ)Bpb3orqkRV7FBGzKLE$lKrggg?fdyQRP-19np=XVP9)-W?p)s2_)+G?5`WQ8K!~;xr})n;!pyOi$S^ffkSJ> z+kw52FGzJwYU;~wYu3Gy_9OEbFwe{cw{^pt_*X&;O!7lMYLW;)QVFFHt_nl>J>9fU z3Ny(7WNIeH*?f-+>{5F+CNVF{Fci=dIzTkHW`Y4&?bJFJtQKZzA7lO8=b8128ltDH zH;A+#9lg8W?TnVS{Sy~6RV>OMO+8W*Gn6>pj1&sV!4Mm>8oKd|2P+{}{1Iv{-|uUk z6TuR|VAC1KfC-*d2K%nP58vl{h4op9O_yvN|0fIK;Wj?ad*iX5FHF|X8NVPjsvy0w zJ!{x3{@AKZ-`6ZKq@lqMXXd=`?rltDK{RaF)qGj?zzC2IZb-Q2(3`dyM5En!_qIlr z{H>=N6&9pmJE3XJ1Tz}vfL2o9G!_AD+njd6fRvY{HEZzq4X*#a>4#|Up_QKr_Hs~O zy&Iqpn94Fcvffjn;hivr6ioZl`xKo|F|yv)s|^TiQ_otEp_=r|mruV}N5 zC||JjN;f_QvQWShTE32sy2aBV9MosgKlJJjmblOgn^!{~Q=0+1I&LpDhbR0Z(z!vh zk|`j0HTRh*zX9%aCIJCL3ElTlX$yRKV zscNd~kPa^6Q3ex(qZH-kbAPpbyoP=TgfVN__n7+=V=-tsbKwfzC{zi?mX1Bk(Hx(6 zqzfd3<+;t*BEaF+V$9sUTIpmDad!SN_5{bZ?SAW^bZUHqx3YStFJbo@@waE(#)8na zTwQbh&cDi=4)2Em9nanGfgMz!ljCC&pxMtCJr>jQM6j|1?vr2+l1YWkxFh5QS7ub6 zBFt_75Z`%!R(wH`39Q1{@lo!{$$S01vNGEIZ&V);4Px!@?<rw%a z4DZ<#4*Im#rSf-xV*wp=pwE2T8p?TF!8Ztd{PfXgAHtk98z0K7i`Q7bWT)TW61OOuj@Dedam+E&0597l@M z6Vn3whc-NF639QcPCW5}hn)JQ*HnXU zFa~Qz8l}#5qDV-!4YVSy&<}MkYgr}~9*ttSnw9;AU+Ln{m zB(a}oN{aE$E2VqyPz+X7Z$TBSC=)F}WPR{UqtAwpvx-NK$! z0j8IM3arq_Zr$6iARg;j?+8s?x%=pj^fBux+r+4gRV+^fpqAM z!3ZdV`3Jl&B~?8_$UuaEzTD#dqt29-=?CIoi(yqdn|$;jy{cOf63}^#Co7Fqd|rV$ zN|iov(wooqV3Lx7T;I;qi-b`qmX4?n6F+gMZ43_)%cp=9XKih|=PQR)Ko32W+5d(4 z0ow{Rx<5 z?0EZ+U_OR#ie`hJxHpE~#Ggp*W+pPyd`GYQHdS-5pd+djTZzR%B_9qTQ-L-pk%+buqD zj03y?ag^)D-*a(c3G$mxOiPa<2YeG)6}1Gbtk3;fAuY)?nR#1}aT~*B?zB2d2_<=i zv9z*6xfO$ePDG8AiGv})xv_n(N;=N!Peh*3ZkPW1ejpe>cw)V(&H{4aAmO_O{svt2 zIcO~lQeeBWVLziU%@0|{SV0`{2B?`@YpsD{DmDbEJ9 zmIHsPxo_lYJp6~KqWHrLW2#nF-Di$d8D5aqoXlJIeK{#_H${~{)!|GodgjKpYKO;u zr7(Es9op6x0@(9c4pl}~eo$a8ORSs#zbI*mr(xUm*bbt=hEgt15C6>H3yPQ_NA!NA zoKhbx#rh{0DG{I=hpnHG!_H>?yd~h-XS)Z0p>3Hzch#|bqyDsDsoswr-ubA3p)mM93y(qWM3|#mldru{WGQ zUsh!F;hv*&K*3frAgugs`K$-Hz*k%ftk8Ow@uU4`hxg&eJ+>j%{YW>km4N$m2Fn5| zXt-wnbhlreYDPI}_@zp@`FLShTtxD%GU&N!V|D7xOsHW9u_pt!=7uwEY+YAP!1S)? zAe}!-WM955Ha^en&W<5J9afPlP7X1*e-eK|A262v@?{zZ=D=9hs9FFZ6ANR-hGhdn zk&qjTjW4TddLNs7xw@_;hE5!VxbuJcpqby7u|HMfJhP=aE_OSIKd1y~!es8CA41RA z&ftBC|LZPU1JA=gb!Y05s2BP*15S)QC-Wz> zy)jocK10B)wLq!4b;vjZ_fEU*zR=izFU_dNL4UzlDHVR;np-}K0sUOhC;tt0@XUHh zZAxGH&UAw5mL84F>^-;3`2n0)YK#Jlih5b$qo>m<>2>U#gRhv`YYTsA714^{{X>}= zQ;jxnWTAlp1{+I+`&X7Xc%&e_q1!O2EkUQlARv>5)NYaG z2Ysky!YAldai~JC8ZYdff7FJYRjzh)&sa z@BIvhx`TGVlD=mK;c~D$y|HO1j?QMPVEGyUOS}HSFap)!U9MTc0K(5GW8C!#dK$-@ zcmXcs1E%!5yE}5D`R-gV>2gvw-|+x-u%^&Lk(dA4-Y82re&5xg62Pz*^LOgCt(LTiet@kSco3&XBuqrr!Q114Zb4KT=(^#k#Gd}Wc?9s-D6=J}u zp`baQ?=mwnSQMx0nqrdg6AET>hSrn6c|#gIRq*}}Kjg9WiEdCMGOI(jHa|vu@K}L& zT-PKK?3B1nLw3c+#R*8w*wRFC4<9QWJ@;+se~O!6cjzq0Kk#Nqk4;P=EY`XLlOfsQj8Ayi7o|)*A4*J_PV52a+dTz^vpd}O90E#*g}E^ z22aQq=STWfooP#2nk3X*$)&9VdNtvp}m4z&@^H(&FQp zA>I8I77oN*itmrerRTo+MdG5loS~v)?FWCz;62j`^s!I8F&^Ew6xF)iFeVURlR99x zI%vI9E3V@39(Mo0fQjxN=?>0HIvqf8yHohVlm$p5D$D_8!rW%SM*%)3q(lD2KPe`3 z+OpX2*J94m)`O5OW#t)DX-ZDZrN1Nv9Fo@9c&{@{lT&7_N(DVC+SC>W3|hNL^9jl{wPV7Ha+;y-&28jE@f{VGZbw1B!A zolyI32jKoQEAt}u)pC?WEI<5}`DL!TrqGIN@8qJc%mhCPyi=2Y`s~s2sAPe+fl|ol zuE+OZQ^fjX7axPo8WZ+eQ_}bOV9%)mWTSdeZtodabv|qf!}Hx;NrT+&zdX%(tGX=O z!1{OAl@!%`k~iB)5CV`rkl(@ptQCi8JQ+^AHPv^|)$r4vXi-4vJ8FtlqnI;S(fD@X zp*(W93;QJx^F@89sF#NMYa2LB7VCx>s^oyAHdTeL#;*xMBUCTfl(SsDI#$!=Aw%k) zJ=8zKC~7EB$VmY}ag*H$c$$s8T>U#@-)j74N`!&@0Y2L1RMmS7jJ0o6mX*4pN*t;{ z@D{c&=m_9jw;i8zUC`I%R>x^~Vglu(0g>zKZB4%Wux79T9Q#vt3c)oaK|b~rO2ho{`i`Ue3jula_Ggis0yBM^djhEL{;EzU5V z&&w5vapuK#w*2D~NY^-qUqELHKNpt`?bsfsV%_Od8ek8sXt{P0Uo`u-$AYNfxbtau zm*a(YlATka78kaW+J3A;nkmIstOEV=E1%b2W zlPqrhN46bbi<$76wFYoV_W-U8yKoi5kTR?Ah%fPyxXUdx!UQj>^1`iHEhQlD-#?)4 zByuq^n|-xbp@h=3`OYl&1Peyu@u%_cD8Y@f&RBonQRcLO)#T5dxMOP%O#TNYyhYzVLB4Zo^QrbvI z;w>d4-Qp5$S*m;svgbZEg=&%WO#VIZfA5wQ6!6s!9w6xzzfPU?Gqh zow(`&BtsEnW1~7Lj=UnZ2`&LlSbhkU7K*^Ia3@H`EWL9%hVg;?8pCt)q=X+ zzzW@!qe`KHEvzwYXbWOn&~a`KEh~opLI<k!322;(QN3G-IUy}oeH-Yhk-Ctk~y z#1dd_?jTa3$=w=cwVdX^AY4lybC}I+L?f(=lmU1iF+P!ZSqtJBpO|QAfthvyomyE5 z;7fYdjzNg0poT{k)NhG7$CvRD6d`Hh4Oc=qi;ND^PmC7~!SozZtJ5)WbYyQL2Kjs@ zG0?WIX+4&Ltu9k2!nc(h$eqLCO1p~Ai>)Wj>;TuSz`n4y4=#{e5pLHywJAZ>p!**J6Pa z;&;$QzkrJ9w|rtb1VSWs`zt?wu#|OqO?6`FeVWS7j)H)a5c%KYc zsA^Ot6zWprC@kI2fNDK6DU&Hf!1!l=hlHkYXi#ojX%3R8rvb|7uOY99?R zisdRH6@@`w2>+4o!|RhO?i3KGz;BpEWKhbdwM=oAa6nh{A*h2mi+$6Pl?>8@C6Qwa zSk^8F%{U8TyIhiASr02|E)+$Qq9_jold{u=-Pga}CWGDR&c-@kOMWed)(8b2p_wx= z_Mo@yaI~y>KVcC04`k_{juOm2_yN|M@Y!V(N4xTh;x+HJ1twq>VMo#y_p+j37CsE| zytOO^Bn@jBaSK0l3bYcI)b)5+lG7=yO~!uU`!LrnxeJKo$fk)YQL{`wn+(D2lmeAo zOlHJ>IcRoqw94k?K#KD1=WdmgI#J(cf%61(Sf(0kDz#}T%8HKmpFm>9H~j+LZfX^B zT6o8yDl|MpDCAhoje%z*sDs3q)~lyNm~f4Wg;DvIc$fdJ(>v4UN!`rHFi1IhX;~Xl z7_%(`2)=$`)Rifa;qpYu1&Wq~U&?So%D5cR1_9~@VBvv8esb|t(SC7Vhy35J?Ek;Z zFDT|yrE7z}=a;c2JmpsjUQ$c~+Fyn=KT4kJ?Jc#oh1uv_GNZJB@U%{yw`jaZ>gi2HPl^G2HwwVR^35o%NwGWg6sEsXt?Jq!V^wQ5lTCb^gpNac7cndayD z|L#t`>?D{*Xq}geKflBmnBOosvp32E#ucqF8_mxoAsVcxrTl@fUwfr(*0!-oKy8=p`!IRe{Oj}cedY6FMBvCw4;bt(^!kKjn)j(c zF2I9YGXeP*O-y%rW5f8?r!E>-u(UmFh2u#Gi^p0>8}qcL^bn+rPu|{X(x=}(QXC73 zEypZ^>$JZXHXFEe?F9svwUPOL(%NGPggod&56h2i)0e1~XPOnZ8*h{8-3o&&G!IT6 zPe%dMkwMfX=jUO&cR_@f2>w`mnb|Dm&I+~tmBm(qus;c-`BgacszXS~Q=T+tTwgXa zD?w%!GUBA&cz2cj3* zicoFNWsD$&N=2f0fZBO2Az`23+hawk`M}cw#n`io7Ma$Cp)azPC@S4B=S)ei(u@|# ze@qN7M`=t9a=QmK0`H!o$%FHpzZ}eky~1Dx_qR_x{UX`=M?<6oLwxAA&Q5}ZMY`+O z=GrT)YO;^x#0cN-oW(kpWV?!_h0_v13RtiV-*T4>zDD8ft;1y;48#IKVw85ZoaZOY zwVajn;^lb$wyEo39=`(3wj2S@;@T?hJ)=MsI2^4}y*Dz)D-BMKnJz#3mF$)I{XtkF zP#73lb5Qu6W+X^1g7skPkSKoW^@g4zD=t|K4I#FTV&V12yhmoAeu z^5u^oPluhXn&#!z2aGBaqnst=JN|H$IAsFW7TXMiTH~HAQ3@-f`6eZ- zl&ED5Rzo*k0i9*c^eOF3;fqCyaZ0YzklNdDE5BX|s z$9Wcxc6KOI=~l`LbeOG$E6vZH?~i7TkM}<>Zxyt})UhG3uBP&r=6H>4O@IB6LCt9; z5OPN1vX|@=B4*=E{f}qBqRQEsQ(;;6E9EjM%QFaDn@!92MNoGuY!=nrNAK0CU?Ro$ zxK48mY8Q#nc^{BN-{$b9nCgK;aNOb2dH176s)>>z>Hych0V!IFe$eo373x#BL%C4n zTv5j*B{G_cqO|I~LQZ-!Ec~}g7)62oibk=CobwpHkp~xG?0_A5die?XEhl&+SJo|I z>fl#nfeVMm2|tfmsYd{kxXaAh%!}s8MVqPaGpV$&-$<-V!02wrg)wOkFMZRr*E!TXMV6w<+Yr?5I5f6e3#veJ|roEjoh=VJE;k6_!b5;%| zS88vf%!41{*=_ zKWki=Tvkjk7++%$li;U?;Lhci^r^*B0DOZH*k@{R&DBBxhr5oe{KJO<)6+xHN#h?Y zBy8Tf6i2h&c`a71GB*Mm7A=LV7=LU6Z77br7~MQ`Kt%?}T_Bshu;@1Ozgc1P&7&b+cbB^E=hZ;HS{x3)2MprMd%fJ#^YAHo-5$4BTY993}@R#7}l$d#l z_H~cUZ-Cv7TC*msZP*J&t` zwLVq?R=2@WeH*$H)-W(%yrHM4;cdyt$ZQECxR)mNTpNh*IK%3Lt&V$&412qK81)qb zAw;~q^EfrnRdaSdPR2BRpCVyNyvsBl5afZu@>Ls@R3m>tS17-Ep7 z#JfP|!4Y?0CI4#hMWR3EpdG&T7ZNk+eAC>Lqb$3uvlixF0uxp_ZTXN6U567f{+5axnu;urm{Hln}BNS{gd_ZQamLj3{O9Ifzb##{Hc~s`Upd*=S7=}jh&)e30{P9K4XY! zesM}v1Nv6X#MY#43epSR?UWHxybV^Pw?z{0cPljyoSxaosOlY_OqY~stHk*F z9XQ6T2c2$lVJ}149Swpr1YD*DXa={63=Dai|-tQTz>#mT&vD)znAYZ;j%d~n`m3}M2nlV>o-?}6>k_AQsl~(X0&Ouk+>DG? z9cX8$r0}bm#o?8Xa-CmIXpqkL&b^k+CG2oMW5Q- zx#ssyxmdYwU+Xg+u1?m0pwmHi#3>26hL5G1}`J6jDm9oR@GGZ z-|_v3+KQW&I3gAb`jr+5>J&qWa6_I`w*!ydb%PE3tYIZg%zT(t`N1QE<)x#UMocT0 znINI@Y>K);GR)9O-kau|CB(dweOod{|EkgK@QqXadl3^4%gNNvs|Ok8_5byZCSW)k5%w{~oE1GK0COTqD%25*lQBJPhw2 zTYusyY=#o)SOlGL{)pK7JAE{B)cJ39plKSEwX__BVTp>1AfSs$NbsnSrucWfmWyc( zxbuui4Z_rPm~#jc8>0<@TVK1HkJd0vlLNGNqPM%D5|^z&JF-Z}24fV#jNu$y&%UnX z5Uk-~=>c=LSKn4e{7A188nWSR*f>c99+vyJu&06E#d_IfT?F*ET1)A{Q3R}&I?!Y2 zF?BUxvB7mz>ITsg`FT?D9z6i@8Qk62kX!9}FfgPj=4J?~W1yT2VxS2WICfoBMpL~$ z;H4^(AC?*=Yc=ubRnK!{#}Cczn|saLk?ZbYwNn;3A2dFttr~>+FEx!CRf>`4)P4Qi zXfY!|1DT(NW{_EP<v1SjrB!#j&SIK)9tqng zf86Bkp=BM!(93z*3#2hRl=cZ!8Op6@@k7IQr;(TzY-R*hRYvRP_^1eD4Y}D5+8_0{UC8~W+J zUt4DtPFoXe^jE9C_dcATf$vAfxeN<9;{?g%evEbU95I*@n&o3^vLla;jejX z$+tsOgHPukp=2W=iK?pdsW&P@IT-#!5|wst^QMAuu`hb=qUSJzVg98dA)CZ;2y$A&FI_ z>bgOY;w1R_I^CQ?kQFYtVWaky&tXu356};EKy75Jr{`wCuI*@^y+0&2d(FJJnB6?O zIg-+D6qhqRet86q&@LTfvsZJ7fbHS}^S()F(_GR_PTiG(-^zejpcPuac{YrbcEPf} zv1e5jXTOyHOzE^2^-EsJHd!Lb%=&QAeQ!L=57p#+8c71<6J(YknFAnVe-PP zU5?kn<1dqa&!KGvsmLG2t$|cp!%O{ip?$<{z^%qCM zV81C3X92Met9LQir!3uq{U6n6-i12y{HwpmY($uj;SLATr+t|D7LaK@2zhU8(Ndn~ z-yi9yFDWCkxZ(}0eNtYWGL_ql^>^?tt-0;SQZ&MU>zQsJFWOzu{=+K3I45!~z|e&l z^lFm_`+GQxxhGEjj94(3dG2C-b=8}7{0SIMaNp*KR*m!DNJ1wzLP!0xD-tkRKtQa^ zku(f)EUP`%0Yy^RZ&}F0G+$uO^bsAl;zB(>3vdbBu8-|cE&V%>_poZ4-xE-YUTu8x z&)e-2`|DNTap)O*1fPh_l3+wgb$;ibZab(Qr<$&;4n9P&VCq97f=;<@UlTT$oT`2O zS>Ivq>uSu#Z3#lHr)IAhgv3$Yz@!WO?#Gp^s$TL(;C!0jxD8cHI zV5kw6IzK6o@@x9OD;)=?*{6Tl!$bzfdo;hwvR9*5kz6AY?s<4|mLd4cK*VWec(@;} z=vB!V0~7zFM*1Q5Ck)nzII7h$ZrwvE5Ex;6QgG1z`O{`xPI<9>#8Vwq62PXbvf8{ya# zwBCsZO(wU~6-#Ur@=t$$pQ~Ac{E3*NOilMv;BDkYFmh8ICpGeGzkE{s|F z!2^)>ZYl#AG6E(!qFKSIq9FXNOkR-#lrTu6HBNM#7xG}Nk z9DpKZ&2hK^+~*ICW+V1D^JF@7n(N)$`Gv1#G%Wo)F3A4E+n#FG)IDwTR|8MXaKnSL z2OKC#KhfOFYAl~&c7C@9=IuO(jh~+ZshOE~M?8%PWZin}&w{{!`#_d<94yAKU3cRD z^S=XY+`RZKX+IxfTwu}F5WpCRu-nd9Lxaud74hYLc0Bh z9J^9{>FsKxh*vuI?TD2wM=p+LuMl4r8RS$kSh;7&2u-%8IZ`6@bk3s0c3Y7^#Qg1m zEf@vIdlY(hRR#_QOO?>!xPX9K+I16t80Hv|tzW2S$*;_UTu>1v*KKG?>@B4`Hi;FV z<&Ucm3~HM!C887p&O8XdyF&eVP+_HA>%2$X{ZF!yXr)`tb9Xt8x(jbAOeKq+=AvmB zPYLi{uW6>xIPEYOZ*BCN8$QmG^?EK{$`~(K>_ui>u9ixSsvo7cSiotBeQz4ckY;Xl zRTVH_2i=0SPEKNBN2bx;rUM_t`(Ssxf1qYt3!|48bRXO@Cr#5Dwp#?Q*118IBFZS< zs#XlrL#$C``uCQZ9cV<)pQLVNjC&LhkK=w2-SI>{WQS%pRVu;|j<$uH$C*5b>HT_~ zj&`3qt^8}ePU-+pMYn{Dll1Qrr3=EHU}mFvnsKd14ss_v;alH69xa4k9W)xRSt+52 zt98YB)*c?YZ&%0eMk$r-tRN|ra^L2j4YFQ3n6`0vTG*6E*{c7&5SX`E+geLj4|C+p&pL_c>eS6XzTL4WLw|~u4ltmF6HOU%?h;m*DH-6T~c&kc; zoApVf=7fm*lN9=lvKvrhVeCoZSl50xbpvp;iLbK)!@&FMr(fjxq|h@Y4!?bctKwZE zH>b}UzD8Zjx=5n&+O`Vz&9hC z67XjgAsv4yw0UldC(ZDg(onIF!>+ov2CgD?Q! zT^Ye`%zN2FBX_l6QA6u|+CJbW4u++FYA;b{#;n)neA1JWmws*n5kMfPOIELC#NCAG z`WM#BQ2&c})#OrdGA0dxfJ7Dhtbp$1nX=}6w2JKs-Xnk&|H`kSwAr%$WTo0>C?i|; z!jmkVhlA^}SsU}_5sKwVG-&V@SaXVLHv>d%wl<#RJuiB^9^kgE^bZT4#)2M+7d8D} zdGjR9ZN>maI`BD+V8-b<|Lj*Toe9FH8rgv8wJ6)+A682pcOBatIPq1lQLMI-r3*UT zLpa(6$LjKcqZk>cAI<}V&M1;@U46tmFtKsh*D=1Q;#XkF!%9*P)(fZ3H|9N>!2lO8-R(`+!kLwiRX z1=oY`kFNE`?YG6(Eu%QnOVOlt$YTcgBcGWIWYXHq)yMO2(zffFq6~wxbi9R14{NK; z=8zG7O;#wbS-ocTa;*={QToxj)8ph}4?40|( z)Pu6I9D0VhAEZ7zm&w7_0SFzVLiAcmJioa%Arqdy@u$ z;i_t~6b3<8g{yN-9>I`HKP0gP+}Wq9AP_NOOuH#F;^#R#=r$tq!kMB2v>Mfw!>Fn$ zg(t2?*{=n@zs?R**IE*|O*J~RfrD3`#3^Xvr9`~r-j@pzy;#Dkc_j9$EX?5}tn)P5 zx0BT9YQX-=exJj`!ogwtcqIE*XgvkAHlasj!!r68gnzq=B;EBSJy8EP)F|+Sp*=YN zvC-xbzvLn@CB!r1aqwp#v$`imLR)PaM8$70^|lKN$tZKo=|nt1Iu?g3HAz&+t)<&^ zOfFom=;2%R8qkpJP2Z&DP3d4G#|f4<1NK5EFa$Q1Mfza12nsgNn3vf zT#O|Hb(a){OUc(g9;-ecT{_?SqU$o?ktezdNip61thMY6A`d_Sj$3vK?p{6{nb$3lSlBt%>2j%4}7nY-<9^!_NY zUE*mQXM_IuNrxpB-FruAZHt-OlPUR`h}4U#SSO?u#Nnt&b2^!9y7RUlc`XP1ym50= zv(3%wY5MQha(rQ$evhJ~U&-3&n6f*-hG+X@V;s$5tn$kE>JG{rF9(v`=bMZym)cP# zNX1WuG6ZcFT9vthAs=N!C}Rk2RAJ=Tp|gkee{gOpoP)1`v3(*Fi}_0ygbE|I-bm5T zr4=_U_nqy}+efb+A2XyfIL?W^o03h`Vw#Nw<_dCM*HGYbf0tnggO0Pa_Z`)XR_b?f zz$`7kKCAPb@iPRwZMRJY&Snq@6Nq~gTJ8VIX?Wf$ddeVdkW}&djk~se}BT}MRJN#ALAbY&e0ZRarA3k0+Es|U{?jbX> zfUkTxWMoxmuXWOJ5QAp_n`+ik=>s2;C;x+f6hA?e@}pmy$;AA&i*lyU8B{lf`~y+0 zF$}x5?gE#mY!8~6ITiQ1x?Y@w)j?-P0%F~L1A*@PR^B-NH-FynVH2!vRAQ>^wh~i;HzuC1g9iI9J>D{)aV+BofCf4g7d zY|9Kfv2fk^_?VdEf$Lng&M;uCa3x?$T*8aTQ&p#zv zXmoX{$ocFNj|7#WznV^GO>6;4TsnE~g}d`k)afcuDtLN~Vd?bEYqaWg zE)mKK%a8>7%M++8i$~}!ST@iK?HOKb2o8KGXD3!meXIl8J%SL>o*xAgIg?yTyb+o{ z_d3=7t(KhEE{+rVNN?_N12&zj+B~>#gNMt#0hK~8{n*p3hY8W1E;AbigtK9unt5nU78f_ z=mq3_A@Nm-*koM`OETGscM(DBNDsS^5ckYB4{$K@dc)_f9;r20&$gpQsoJdatn5l& zm@PgBH{sG9v;S{e;k`ynvCn_%J)@IYWiLRR+* z1ho*bCk87Vy)%EkEud2_R|D*x1*a?zPBNZxdhY7y^%i4n zTvsUQNASXB^cRHyKB@Nc60?}o`SLN^Z9qnfjqW9aMc|$e3@1F{afbrrFUKt$b2uj} zBzU|FaSV6EBDf;h*?l;%uecPrKMstkc8iX)TEj-4IcRGXtAh3?`jGe1j*OrTs&4~h zLR8=`M*J=f*+zN>uWdS*F+B!po^kYx+>}}kOsG)nfzf+zXZW5T!UY=0Ams-21 zFPndH+8yaZI=YU5)cu*A3jy`{t2Z7s1#k}rj$BZc$=1f~_m%CeGQOH4y8pZ%L$t^3 zb~Zc)r(Xf{Mnp?O#NDR)UR6hD7=EA(p5}5682_I*;d< zM#c?dVPry4;Dy!@_}QN2xnn9B1G9h4@AEQb;^MXAToD)9@Y9bg($Fp`FK;laba`mE zU4L=5y<#}=e@uOQAk*Lf|InRC7b>A#bIENkxvmRoh|K-2FqK=mUpMbmLM3w@9yoaZ^u>*G8QpYFdme)3c%#cTGTrl{8} zlQYA{_uFaDJKdUH_nsM`gJj>`XfEFkswcw6S3jhm9SK%b_`*Uyq{QX{r5- znnT>@XC;w2Cky7^vk$qlDO`w6*PC$<64u%XP)@f_iR1}V%rM2PDcO|Y(w8xSKSl%i z#I&>!n|iUo?F3s@#{!Qln1z+`$p)*)GJpzxb6FTU5#v+RKW6>W8)}_hJ}_?Jj7cZf zu&3r0|C&4;&86wup7jsW%lnfD_1*P@e0$8a;aUj%6W z>+^NH6~-M`M6)Jazar&CeI{n$Q0#u4er*_GY%>F1_+|7k-1lbV$!_ZRFWBJ%PgNFYmxA$oey zqN1n()MFufF+a5lS;N}B9Sd$T3g>}txv$<=9$m4c-vZl>J|y)3#9@TG54*zi0HE&A zUtI0Qa<|Tw**v1j(=7%N&znv{-HFDLJVmr<+00MfHYZMy&!nN1u2SQpnKd1W|o{p)hryf`11g5@%XBi(5XE*FrW{%UvaU9}v$`x;TwKed?z2u1U(1 z^mp}l76zaX>QDLQd}4QgZ93Zi8M4TYTin$6t6N=HMd>RP%+i*C;#kHP_@uh$n>4*0 zFSPxmmSuo(6c9qNh6HZ>RxvMq`C;zm%Yar{k*}8+C;vxo4=^@I(xs<@03u|OE*)1m zG|Z44Zwk1=BjU!?4YR>eYPkohFdCOu(ASUhZWY3j4uDD z(3WpZrDhJZ6U!>pgqxh;3}Bck79N&?x;C z3A?P*OIr9(gt)x(!jx_^`5k;cjL9}PGvlqf4BS2%lSA`7jRBzQQ>;q~oHU$@jIw2k z(#msCXAheZm>&CoN0G>~pk{R{oo)#Wo&JU{r+3CU2{p0kCTFUG=-%rG=reA#~CM(+SW`%-P}a4m(`2mFXf+nUZxeW zIOJaIkq1;(%`d+WnP}c@2>3FP_enAP^<^>I{m4116;7W2cEyjA99ba%w{LywM>q4| z4{)?-y?yE{%wQ&+3IW&OIC9Dc#zCepNMQ$GEZwo@}0Q^roHdpv3Pzk?pq zM- zw57-CKYd)f{2J(VhoRGPW$;@!z)`j-Y1R$)vNFt9rtfq^u(B$r+HUTy>n5IJUd&Ir z^RrOGgWhMg{_KADqmC}rwd-g zfqNg~R`!n!gN!nfZct)v|9D)BxH3^&zK~@qyDM`rPSBr z-=Ik%p(Nay65MmE*=z+)EjW{a+&_$Ez|8;|<_n-K#CYujvG=&u^mE(gv)FeLzpaiF zk_?ldG^>=-KR4OV&G_qn|Fz8nKF~D2a<2gmf;+ZIK>nMDOc!XR!mU$X{ROh^J@IL* zy@P23=`9zd-#z}E`ZEn?NAFbRQKd09j7BAnfQtX4JJqkZ3F>1Pa?%nie!i$> zdXI%Gu8_`jJ*yeCb-7LRip(sVScLp7rvXYfRpV=z>0;C;`yS5CvjUUOAC(=ie~7?f zB`g3^`!{os64Ose){m4QO|Su8`iWEqE9~xQGQRSJyM-_I@A3S9K~np@g}kkCJ7JAX z-=DV0(OJhGk2vl*32OzfD1N49%bJ37zXslD4(lS>W-!sWNtx{UO@MoILj}V#|LyPT zDN738J!<5-1BrVv{Q_Orac>#_92?Cm+^3QtPKXTOEx0vnv4}I}@G0kW`^BqrKxftI z*Ut}aR>^;(T9Gw_i&u0WQiqpj7zG5b>9?GyN39>Gn2&ycf45t^kON?9pwBcKIQ;yO zW8*n_fS#^gf@d`{8flVvu0pt8{SK1%Z`dI3S9-=y)pO|d6cbWeToYh>*81qHCr1Mn zq@VrXX+wREIJc43N8$FO_@&iMIx?oZ%f{B*wkVwmgA)b+Qhtf7RY>AmpEV(W&!Ao5 z(o8M!(YTNuJPYA_c^I$+a%8rEF5tSG``Wt{(=kzZmlSkhPcU>wEu~qqAFE5ITVD;XkM{ z(q`}CO&b)VxI|4bXao*-5BM}TEY@(*Tihd}?F<4DzWAl?>L1MM^XK86nCY3W^upeu zac{GGfg{(xq@FqBRKHT;0tUovCWtSHHpE{&V>#CMfJz3~TnS5YSRO%*ZQJ;;|HfkH zc7-dxhu(EJs`_VfJ{~!qeOZlv-DO(|_VU=`7~{d7jQnF=_5YCVjHz$l~)n*&gvugA~N%p&jg z(lf;D>LkUS@1I+D>(m(&47=q{|J$w?5s^=hIOe$tyn@gh%{+eDBitShH{W+tVMXIU z&E)hcMpASqjDI<#C+uL;lz#4wvjcYt?w?R_29bmf5nh6( z?27!2e=Yu0i_+Uta`~NHNv2_S589W|cYNh}hQJ5wEx(K`dM~}rJKX{ z6rmP_n6vSAFMH&GdM7F4-%w&IUyR0ma%KT9N10W6LoCS0_sFrI{#Ld~+Zn{a0MIzS zvsXyK`&g%R8CP7bbE!axs!(4;T^TRCl=7+U-v%3C+VXUf^x-cM$~T??TbcPC>}_ZG z)pOz<5Et`(rjN{1G&n9(wz$FAT8~3N?~>X@*{NnEWTu|N`rlqW;4(gixRT0O=NDr3 zo}PUN=-HAlsAnp-GN_9}?he!kT;N;@=nM@Js*TU`dX%*x{&|ByK(~A@l@s&`Y(tkVVw$<0NC#X_V%h1th0|5^swX%Bi?g_HY z6CqE}G_-FBH(KAw-F3Keqt+#9EqyXgY*%m#l z%GN;2HJr9M*^2y#)p-Lrk4(1Jh!QLLGR5#RY~Q_6{Z-h5W|tEy#Fj1L{~Sk#DW!&m zTO3*u^_JCt`f>KID=cR(w@hpM7jStG2s`;GJR$sbhlgxO=)UJiwU6%ZWmZ;(*|=un z|6V%dP2j(KC5g5JFkl7!JUhR$d#)WR)grn+8MdrZUfEgQzkS{IHE3=+;zYiYD?Gm| z;;Nx;svSeMkb1*G*$MPtdPi0++CQ)2F|dbGU|4=s0YGyC`<;0o5hNuUjzLB*P4m*W z$)Uu7O7MjIz#+nimfh>@DQPD1;B=dZPS(o*Wi&o1;2Geqg%f`QlkXHG%Sx){#a__v z))H0_n9Q?l!oNNhNs`^a6%#za$OI?B6sTnE(yzu{8`nzaH#NV%2WZyBGkR4Xm*i2K zAJHL-AKyt$>wg|*{By^I&t*b>?MMetc;w@j_*!*k+il|;eRP8zX*O4OIJ zM0INGq)Xfq1omI}S8D&s+ZMYu@?r-cxXZY2f}J(mi<4Z{N0-`emXHF>R!wXbV*@JZ zVh%%O^edTf>=_H*_r0@;L4zdys-UMoT7u2~27zb5=gEksqcYFFFnk*J=X&9iAc&|R z1x(${jMQyxHbARK+uy2ZdkpOuNF*j~0?*X-4QF1k&-un29E)fr23Q0!nWbNPUQ8WO zB{{n!n_k_A+73bRn4nr!zg_vw7Hu5)>zGEtlYOY$QUBb&#*4GM{=Bi^>67EJf`=>) zxWv0tMhouRiwAwdgq4wnsrJxF*MR$Q$}BzfaEn!yixF#C+QR;ilE-<`XQ!@1aj>4D;P+GwTgp&{9_m!G zM|I8ETg1xM80BXzzcLKTwiE4e)f$Os#y49MWuDdt|9Hyp{gX?FBS}D=CB?a1hhT`7 z!?{bjxh33~?>STzD3XR5Ww-@kNjg}F@gk#1fh5zBqZh|$aEqD|Zc3GZ3Qh5&OebvQ zH-5Y$!F=~;FwfGV6)i3<>+1s_g^gz<2lDYxkoc0+H2yjF-1S+!8S3Mr8U*xAk9qrh z4n&Qb8;zmquT6RHv=m&jL)gbRzQFMx1F^FPWDl!yT()TMi}J&7s42?gU2YGnIatiO zO-@eQ>E4VTzl-XKSoSBoh)mqiKY8@gI*-{+OX6UeeYN-Guf3mX;fV)XQn<>*q~ta4 z|Hu^&)9c1OU-7XrQ1VlY@XR6Z)nBBytUQ9&(gM>N1bazcyx#V0Rp#p{^)-LXoeVLo z^RwlB5+K$i=#k@&gxMCu6xlAmWnL`N+t3uhK|PYLw%q@wF`CYC&{WIBpknW&8v0rF zo;JY<8hEFKnDKsjKX?am1;l!R9Mse<)*{;aZN_6^Lw|HpNIa+9c$9Y63580-^g@h{ zjqF9)uW)6H6@`2J$RS(3y1E{Jhji&2MUFb}w~2H97SEv;$P#n6+(NRNjX~iQ ztip5$DE=sPD+C-smz6NsM*YD|Snb6?B@m*E|!H~X$+SM;^y$iPOR`+ZRVzzJ6 zRl52~egTvZmpPLJv{*v8_|ZvddHWiXP#Q@*rx-H1htHJphNEzmKknJ*)N-NjG`@zS z%&R;jU`mj83{UIjGg7l34Eo*0h-Mo}Hj3Q)B3WV-wCrJfspu+ES(MgG_N#HW@{Upe73J%lJERYlRooc+R}K;JIF`^v2M| z>zV&Vi^aiI2|!*=K0uANp(?P}21HPgdM&RCSoG+wJ>)E73o`Hz){Vgi?T8ixo4WRMzyB_lN*l~>`pnu9cw(tek8tuLO$ zspe<1`KGg$Br~r92A0^876R*dH=6|e`b_N@56il=@A;wpXJqTp$Nw0GhEX%<{3W}Z zl_Jx{0GwldCK79)dR^m~rNPYtdB;!Qq#K(~+=SZQ|7{#WxguF10lSoHPrBz}!FLSfQ(y5Td=?fV z6~SHNW@d@3U3>}J(U~HT57O1TID76aWv@-Nqbs-9eF2}9tQmFqUwwHiK;6c3^jaTi zAiD|1FP@8Z(?>Gz!lh>SlG}}ENjVGh$57^~J_wjE-hnGJ>gLCpE2oV?h}?#(9SOt?bvVRvWALW+JRd1w=3qYp)`FMy4_ixZnE z^iL7Tr_XcOT-V@hA!%Pj6Et^z3;&$F4PO_QWvSbFt5|H>jgwyog2Cq{p%!``3gkEq z&+^gyPGokw>(0qLqgdYLmCT)kThWD-V_XJ%I+}sQ}#y4#$MZ-PYlysLJ{&j6{oxVD}}tvjjic-!E| zYqFt%0knN_k2tpH5(zrS5(3W#oQPfhuQBcQo|_s4V;`??S4(n+8A|2U;rl%iHW|AI zxhPUQ14zcKs2H&A4zb+PpY6LL1=aB5UVI|egOy0&~!#&0K=g=7F@ zw;?BQvB|TUx*zcRYD1(HkqKHdR(bSYFjNZT3K==R3PCOIsXx@Y$n(dUq&j%i)U+O! zJcrTSx*z0Z8jbYdBl+Q`7>_M0LzvvNMwf(I=CsM|4)&8M z5?u-W`}ak%W~E@rmmd`{njpHaBThY-lyR83W&i3>4{i?mz+Z#Rn~!g}l92a&%x^S8 zYzL`LXgwVKM0NXHLeJ7=ol1sU3-ugJ2wcld(E5_Y=iiy7+v^#ACQp!I(vs^ZP3!5y zYIWmBH*Hf_c;0s+`Qu++ihmCF>#i8@j`dy3OIln{v@&+gRrfanv7HCxfC#VjLVW=1 zFetUS9|s$vRnLAUz)bBuLN-E7kUM<`8-?AOYyomfIdyG`Jyy&Q*gGUTzmm;GRSc~# z=v=n?`oW_tF{uegF!7=nm#jCA%Wuuw`xXuQ0*jNlA7^f#0_c2*5#V8v#9-%u!Z6gF zFnMW=RzcG7>j)<)N_+lxqi!W_GE{cWp4P?tue~8SR&J)qI{K$zapGvLp-e#Wg`7J{ zur?iKq9?+U-XIE=jm$$_5$bd6Gb7MTc@={(3ZJPXZF*7@iSu}|R5ORKe@{2u0JS!; zpHoO!T_?k@w7DCPGli|4RF~74ND**yj2F;kM(QM*8{5?HZQ<;*1jO^kyPtn07@1m< zX<1Y)#g37D=ou|k1$V9k*YbACCczAVPTHJg7DTInzD8<_Nd8+Z0 zL%Iiua!@NT;u^s`e{z9@ydH);EQQ6o?zHLgJJvjs8uiQR8#{HSF%Hz`+C z#2UYpJOQV)JN7yB?X41l_0p_JwzZ)IWKS-ipFHS5m`pnanA|EUS(5BFzGu^4?YhsCr!y5W=0BP@`ijn_gb;} z;+ve$?ogy1VFoF#AW4Prsbwk44>gE*xx^lFSIrGYBz_dAGbL11-``ptb3X&q;-LWbEDg>o~ZqBMmyJ zwspT9?Lw>f3ZZeLIjwKJ$~Jgb(W;oa539hM)bEJcrd~){6nVo3YK-k>!UdibOhOhI(D#G@2u0_~2OPb^-Iq4e6hlV2AoRp_D(<3t-WMnKqq!z*) zixIOU?;xUm(-j>$gBhtctBdN4iN6+)8^=gPN@n`U-|Drp*f^+;&N{^0vP@08HmvYw z>5RvlE`j*~xpCnYEH&ddsg`yaMXE+_kiWZM%Mv9k4=+R*1%zy5FuHvIoXLg@PSMkl z%X4{}8&k7si&LSq!tRVE+(R%m2Y<$CknwchIr$D7A_^)U2ZYE}^X}59w|C?ddZfg~ z4QB_AM&9@wvsN7Ra3xJllQxy8Z}y6(wh*vFJzB{+dgAFcm=@KEYK&V5^cDn}%(#2akC&^6J%kXo3m*BL5Y1G%z(Oy%f)I(xOc& zjg#w-fDL`|#j$G}9;Nj=DUCT<@7NI0hOwWX8Zro76n=UW^BH3i??{o-3vr4dD;#a) z+{b=}CF-)WM_FC?I12Ae z1LQxX(lqgD0aef7a05j4+;L)b_^s2hBA9`CN1?#WZ~bS#Iy778hBzd*9Z(2M4ZG+u zR(Fz2L|mFwTlT6rEr_$VD=gH?7te$I&!4mn-YZI75u^|E^*|oc<8A01e)cCk@6hVKS2F`N8m~E zm(WcQjH<$jJp9?Opl?lY%*;xban6l%c7}Byi;E?!0gwSIb;zmsUb!+vq-MB;R?==CD=<6K z)`uWIaL7kQHlAk3;+LD3vx6rD;}-Kx4W9G!(9;dNang(0K*r$3eFJoeD_T~{VbtNv zo#GLl&P2!v!TX^}MlRs%9+vZEiZhx?r|SGkW*4B|^U%=weA2fb-Tt%X`rV}^c-2=g z>e@*0@rT&2NEIf@x-zvLTJ+9-?Z#`0fc8E6J!1s{g;x;wUdsrbHbtODOLipM01{Xb zXtzgfS}%@Yu<-jDEcS)ocGe*%#-P1x0|l?%wfM2YF=SQ`lXj8Jc-V9Ck>!Q}@(S>8 z`L4@8D(UGeQ~HMiThOHTNgCDbTDZOrWD!wu8(BZ)4^x7QfhBK1lzqBkAS;_M``hR1 z9nzPB1{M|;Nx@X$e}y)iAlJB@eFj4N>)gd@+VepCL8c87WDRK3rmaG|`GD1OTwXiR z{>&_8D)Gb#HC4?e{#px@1piwO$1_^a$gqY!MF_2Ssv-50;s>^*xkkT@{=6iv$1unp zL42wb?(NAqIi!s~>0+3YAr?0~+x7&BGSE%6dGW%0xhA;3_+!qQBTh%0Q5_|F;-V9gqRC-T5GuZtFK7Ks=0t&2AE`q9GEDy%Q)ImRj(7STIK99S$d?;* zddkFPs28Pu)v-)(mjrJ(H2=dTi_krJfONTR3Cjd6W*NrjbEYtap(Y*bJnS2H+)W9D zO@@<05UFd_stRcXIzLE_(jt1}J4nKp%p^^Z0|uhJ`Wnh$`^Tn6M$2~hDX^iEQ+CNl zO<;-2J4CC~OlE_ly*?_Zd8351^n7RH%vP8&P<2b5xsMcm>9y3Aq3v%335j#Vnr66^vy01P-f zR$P)XG93;kpse8Xsq=yOV#MplPPlVVniy%iG)P;c)6pj9=Av(6-UQsy;Isa^V)iL_ zCj9{W6_941z^L%q%$ao3#_gvPFoWdZZ7h+yPc4(|is&R7JI;WDVm1Lg?ZRd!;;>vK z&IPr$6t6M=3A%+86^WCp-fT$4Eaaj~>C-!vyB@X_`Ka0B*Fnx!iIqFEKY#nzpAenf zI6hrhTs(RiXjFiHRq@S8OIP1G#>Pl-w9t!HqEp~O^S6c_w>mrBoR=wzpMpIXhhP)Q z;tlhE#PCvRY66C!uQCxfVW(l#bm^i03W+b0N?1Inam;;;5 z**(tBqP;97FXt=!XL)Q`vY&d{kBFwY7EU*3Bt>x?xAt|a{_@TsFY%T6=xFhjj687D zTEmpFtGSH=4dtfakHDA5z}Fq5`#G9EcaRb<9tKupXojEx;#x1gw)Swq9=4SPYu_1D z4650box2}}5%s(2yj+uKT@_B$HcaAAfz>>l-z-iGc~$2fN0e-N)#iW*0XfHe7jO0y zVc_$U>#r_P_@j}RG1#;p;()on(o2iFT{7k2H|LeSsTsh%`r6e*N>2*?N_V-4zijwn z+)x_FV*K}%IlQ41NnPaHlm=?Yotd_GodjQ(?q-ar*Ixu}QGoY{4hsnj4`v>4KhK$(HH6!;G-rcMi|_z=qQK_c1{;g%MTvK_DFksP0ws=3$kEpAc&N zQ}uGHJ?xBK#S}FxUkf~Iv~5N9>muYdTdc>c&(i_&$B{jDwuUhPs5GOhV!IR{mb9zi z%rk$iT%ib9`s*KVt_7AvBOe-mDKY|IYOKEbGocPs=h&;Y8722s4mtoyVC0@a8{0ps>Yn*`_`j~) z^1X#J@z-#=i3@)d9g$lsT?Uzz04&NgFYmmVt!YS5pENk`LK=^rHg)8Ifr+ov0f05K#P6+X)usk{g3?7NDlRJ8C1A$*PEht z4yiap6c|%pB%kSD;!UdJY-Cs-cYHmQ`g3Ab{ z3gu6Nl>(5i(BhRRL?3tKH&av7(5S)Yx)9-0 z)8E6M$a6@D8lA6dD6Ng1o8|+9yKoPl-=qK)q>n%5GI9~y zt=G;CLAIozJRwQNjznK$C4v4ezrkokCJ}PC!?KVjDvWZK!OSl50=Dtsh_l*THI1%n z-HK@4srDq81*EwKaA}d4;+tzXa(~<`sK)Nv7e6@!#R1mM-sk@35oF0yvd}pi`=T)N zjkz4XWhgs+?t;2ViEt?o?sY7-Gp`yb?~Ppq&h5JVsq3I$$8H_F4tr2NOui)APe1j@ z+rq+IsmcTRggTzmA%zp21;~am71vA6Ei9za$%!Ag$jjwbt{1o$g@GDI{er`*EO*?X z4HI>D7RYlRfqTTOD;D}TYaaFx`wsH5b88hNZzQB+2MZu=V^d+!M{P%ZDAv3-W3^4RjA8%{jPwh*bdc4FgpBM3I zbVDqu-Z4WSZ?%1#?ee)qXSC~yk403>0#`f2Ufjg!97_jT%sk6#np<+P2i~rxV;NGNHE8%rn;b?UoO(3(n^!;F=m~OnW12m( zN%1f@^nL}2MpI0G74bHYDiKu1(^}vGRK!x_)`fd4LcNmKmXdngWHZ*MTvJ5QJvjL0 zJbnO;A1#^nm;L$=$3;~We0L&Q=cGSF@I}l?cx?H6c57>EwSrt&JR8SDYsmyuZ;Mq~ zty={Nan*G1X`aV?^@Kmm=KFclrGdriQm2{ub>ofb>mYZ-Lqp)oB#Z9O_U_P7Cbg*> z@~hzy)Xj7J>%or27M8>!!m5lvhaO9bec_m+8Op|d9aXVkqu%(di-{$lYRK==ONm`b6jqH&jhku zC`_k)FCl^F_`#JEJB}^^3o`RQLU$r+c($*xr9uHK8XK^ns#^OIPjz*Fb~iKZY*MSj z51@DFcQqyHEPxDpQ?l{!DZ)J8ysMmMtO^z=Dt7I~D{C$l+SlLND`W5{2))=&wF3wFBcaZCro%)Scw0a z11drUK^xcumGqK`v9?@4xol%fJ3*Fv*}LIT(JX!au+OWUN=c0_bpN_SAcO7T!1>>C zKNoO~r1&_7$_}Wzug}@M+cEnEg%K=SGO+B`7~jRW%jdm zr@vg^Aj8B$l2Q82J^K2^l1883@GmMXi|lc5e-JB@b*h+35a0L)G+ydv+&MUlX3s_p zx1c}RTE%lx-$gXDpKUNwJ+zYp#G>sM+P(QjwT23Rtfk!P#jQ{6MMd%3ZEbVjJ2hB4 z1D*Ggms4jQ^fom2-V`Re+WHh&8OaD~>8Na;@FG8Is^h#|ZUnRWbhl+G6gOtKlg6y- z!6f1qNdut1NDTCC4o3nZ=IN&-&rWb-)}mq zmJw7q`3k2_FfK8C9Hu49Mrhd;5^rd@-5q3)8UV-xF^p$NvuiptU(r8ZYfbu|x~aB5 zGy?J*Wvn{Y#&4`G~HjDuZO9TRJo*72)#OZ|(osxeu9|-Z^e0Fpp$Xc>uf#>pN zd!QH{2n`8kkLi+_4nYr>~=MuFmg;htE78dZx+my~y$gf{Vp!NA3KA*lT<|Dg4y&|fr z!t;}4W^eh>`2m;$TN6K5gC{NsleZTJ$JA{-Go|S0SC_skr`fJP?-_K=@gl z*J;>X=DA+ybjwlwQ5QF}N9Od* zNCO6+c9$b{ZiAewhPM=~RaLhJF=#Tpcd27*9bD7OmfC;98E~2SFW!D$kS3q>Q! zbjs$8@Rtz3;qafPMN^)lxw+E=c0OJDf__FmKg7|VI}h-vyZX?P9-*l*_H(tHaeOac zlJe(Uc=CN=I6pL~yeu{C>BL%=f5*Hx^;zRAR~I99-|2=Ah%5JQA0PEZ1QWkbmxxq- zFv?Ee5aReB_ z+?=MFnc3_B_0oXv!DDRaBQegmk0jc54b0pqp&vJ#gDT;b@|*2MS@D+NI}#nJRHurO z0CKbV4&vB(neG6ZCRHKvbAMuXuAoNFWW${+Yy|Nrip_nX2vJ9^%Ca<|S^5fRJZc*8 z1_6K3ZwxyGUZpZ~k`|dWMsv$PF-a)w;vSIGU~@L8ZzB$~IU8$h%}49?TVn$sY_y3A z*=q>=x9(m9UPFZeqB=Xca+jg?fL`OmUW& zu&^+>cd?53qf*;GR;6952!G;r^btTpWK_Etja5RmRW&Iyg6qfJc#8j6gT>6@x{8XR zn|?s@$IZ@u1?0DL2L`b>bMe}R^zP9LPtF+vtz5b~4 zRI+thTG}kCZ0PQmG4BhZ4S7)z!7U2qoSl(s-M3gJd_qs&WUcE@feLi_rajEjcLMh< zFZh=3?H%m;RV7a3!hGOvMu$S{M4#@Om&0Qzme&V@;Z(7( zvGt_Ts%b$v(gl$N{m}P=?(i9P|JC27>yYz64yr!+7N`U%nDeCVytBJiWkC*_Gj}~a}iOm zmDL|jtGoSluOzs4)%_5N>(hJTw);8#j30{P*}SGY_Lwlz`6tJYu||=l z1Pz(P%ZJvXv?XRoPhdKII6k_SCeZ4n8 ziuTq}!6z5^J!q51w4WE4kJ&+0K3&vR z%iR;u+(LBDvW11pA9teV503yUgOoU-@&FEMlbQa|_IN3zOUw;Dh zjRS*)`gz_e6Eo{R6TO&4u0D$EzyN@+M>;%Yb$rC*H>TXDGveCp5O#`Sd38i^SvL;y zzSjQD9re#nFi?X}$Gp!VS%df{6eFo^*?ZPRYV|dc7lO*85QF6DPKwgUF-?OQL5RLn z+ez>G5Z7iWnngr%B`*)hfpefh?{YT?kPCCpU@}WlOqXbs^W!VPkDY5au?&M0wdrc{ z%9emRd7Dlj>2|GC$$kP|-9i0i&&JUCW0Qu5L0G=csG`~rByW=dYMo`Ai>gsC1=IKue4I?LOPy^-Y7%aaX zzAn(un_Jkv_qbLpm14pA`pVG2rW$~Oh)$>60QPU$yHQ!aZU~O%9mGi885dqCXkxAX z*63TYAxTMzLFM5tu-j@i98r>v{ZldlJ^RP7qmxfAyg(~6ZFk)1t~DYWD&2o`vqJ{C zH)$7SZ8okDai0woR>(!k2E5qF4gKEhw^mDjE+4lKe$P4seksrnLu0K+P`TBr48P}| z(?L&?%nT%2B;|a*)Z4`K3P^B^*5`rBeGKR;CX;4n{9XiHpGAjcqNEyla-4OR3F;E< z%oU*jBx)hNlH`qVss(9&NFF5^$XV%G0C9>5m>qctRK8plaM-aL0MXp2UPo610}sp? zr2J+T0)Yr!PKsPH{;aZVkxktl2=6hlBUTk^Kw98UKkUxzijfG{O~ykW)cz*PY5K0HUthQL5UEs< zNuPb0XJzj{{Dqoaf9Gq0xCO@+on2W$Gyvur_X{+>3h9?$ z53rUZ_0~>4o|B*P$u2~%9rGN(eMt~xlQYV?`yZ8&?l?R-v!QnYbneMPXL`fBVR{#< zQrn2iOeBQ;Nv1&X{pgdD^41Td9e-b!6L7m3C}qg!ySr=Y*KaW&o#z>zddCS4YG?!p zUr&{^Gb@wki#Kh4U@}s>Z~ZoF25^bQlWJ+WKGJfg=tVjSlL0HvX;$+N8WrsRI0#u} zq~F<|U~jk(e10G?8Yl^df0V{C(SG4Aq=We!T0lMuicD(}pU#itqvv;K8O$wv#al?Z zxlB*Hl~{fpE@ns^RMj9f$SVV_6Hcf$w7+>cV1e?e_i(&QpNE_D-x-`ln^SPXKh|Iq zOX83Dx3DRRShtpR2`pd=u}t^|`Yh<-?+q~`(DJ`bx>xOFrMLMI>QxOmmJn-}E~De2 zy%V24(d?>H;%{omiHNNwW=a8=l;+|D(Rh0rdpAA($2L1h!#n=XW|3Q^-Uyeh33D6T zHIn#{-XRto!HveF1p!<`=xs?X{~wA4mL26&uYdddXYi!NQpvmGqdn>0eOB02}23y*zllN6V6#{;Ic^e1{0>5gTT(nu1`Q)YcR#6#`eFn54bNcly zwjO-D7kD1DFY?R^=p)j2>C2Mv)53$P9r~ldMs8-+y+Oa6m7sG8@i3L8xd@7e)JdCt zcGxLzI4_dfX}Q}GnlVII>thm5vx8C&!j4ANV~tS7KfwpKMLjz}&`FsQypCM}R?4zdKF|rR!FYoXp2p9$`BV zBG}uYnDe!U-dXciP7m6%-+#Ag?`1i}5kN#_#4M^qt5Pl00PkebeV0luO-dpdHdE0- zlywB)<}DFKHV}CGY6&A8e#PY$NaWd49 z5pRI7d*v)S;w9sqqSY}Xute!OIN4fGklPmt;J~JK>Pa5T>16@|VK0nGKpM*941C*} zY6R1vHSZ5P1fULhTlJpk>Qu5itys`$Z3 zqWgF8nm0gT2PQ6Q-7sbRAQW`TKK<$P9FP%79!G^5G9!L)lJ=nDeH$)8KpH6I<7Iq{ z{#i(-Bj0@$Eeul7JjzXe*&ew2a{Y$BQ1SD2>HK1Z!oSw=w;wdbv+=Rn)K)>(W^9|T zx1pk+eEy!YBr+G+Ly`cRtzl8+5UtnkQfE{-pDH{hki}_r7Gy5;?_4 z_u!7qvpgPv7_Ki_G=m@~0tSh-K-o$2E_?e6FfSP(XZO{wfE1#Ier`sPBs9&IyGp@? zMR%$EJOt<_%Lqi?Nfb-|)Dq`-rzn(bma$}+YSW>P07&>IyG@a3v2pS_77p64^VcH& z=lviAV)C1vNqi1fl6n=Y;P4nYMGCS2qRD?XCtA8y9VY}xXt({^q#AFzHR@677!WrP zZawpc7%#5_BHXfp1$6aWk(K(rw0n}X&c-g(;RRm*iOc*l0g$D!b>Q9Z)vGO4dr^Qh zxCAqhi?6mHd%(Pz#ORjV2kfJuqqX}AW4eF3-{>+n>n4{OKIY`{1LjUJm1wv6V69k& zt_l~!WS*WF#gi^dg-EM2#R@khfK$*t-pK><8+m*6W^G;H8FFeEPh1XC5lnt}m1PDM z&^39ZBQ9BlY+ zUIMmYj^dxX^e7SIeA{hcE#<(i47hi!iUk3gaB)}g$i7Gr=>D$v6_q!c)qI9L-1oIG zR`Y01{%0)BfsIf}{PCIo4=&YWkODcp$Eltm0FpEGwh%%UJofw z4+0D2if7`p2jX~5e<0Du_ti)Wi6px554><)4=9@a zzn;E3AnES=AIq|ye6+G`Xs$$a|P0dVj;Y`y^%#r5a zm6?W`dmxTniF=^A@OR(z`TqXm58m&~z2}~L#_PP!<>%mM7;NeUYj+?3*`3;cdvh@L zN$~thb0lvnS9t^wlo5!P)nzmxG*?4NX;ZSeE?7kiNZ@qLSvMb> zXvB%X8c8==yV^0kUr`3iY&BmxVERjMwb?gryd--Gn;;3YpogSLrs&YdLUffw)t7Q{ z1J4#rr z>1Cfu)#Do?QoMn%KxRF;_26Wu>s@ah<>fh9bm=Jo;04+hu-*vqC7xFTkjfQr5;pcScFYv}-LSr7W?Z1YrvM*=n&Xnacj#BMkB%HiY3SE47e z5K8dvG2{*XlEpbE9sX2#z7j;y4wH4Gn7TJ=yN*sT+n@jQ>?riE-jN7i>(GnCEPxcH z?(+MX8j6oyAGd+<={UUsTZ*D+GPG9f3%_MZ&D5!Jdg_VKIFj(LC+ zFYw7p_uk^gB6ha(qFCxrWenOvJaOoo7N_4;=z=lU+Nq)%oVHXKhwZms{%kn78(V2?R1OzoLy*AktVIt+sg|*kHp_cU6~<5!UT!4(6dI@q{G zrw{RMlWfgJ_vQ=!{mZ8tj*}`%8O*PuB067o?0{)X3kk7vH zDPLf6C)7Mbw7J6Z7{O$m-SaxRCts`3NZ0ImbAlbB1N5MD@7M-ZCt3Z(XgByD?=8nG z#PU>ZnY#jn5LM3^k{6)vtQ_=1yZc9S0bkPsm58}gp4oCc9vdd^b$jXnH2=##*r`gV zb(UNX)UU-r>?peH|9pslsZSzG_WajDxGEvXW=k{yYpuFP zh1#|VG1s@3mH!3?%YjHP@3`ygMzG(yEGGu9jV+ZfR(SzDL5!C%CjMbpnV9aiwFoLR zU0@3^_O0K#TrpOTbx>zfrd$8djH;xGZwAI zD&K5(MnlSzY;-pAOX6-dBXV}kvS%k`I7J^e{lu9;^T)@YLwR)E z&aRw$->1`Y15}JMNS&%&XNaewG489s;5X%>5i4kSh7oouT*Ws0Qvt2jHo-Lgc+=(= zr(ch@!|2~puh#z6Z-rPz$R4+|CduQdQaNCemk&z;b+Sz+x7(L`OnmVxS*dhr7`&l; zj074K6EWyzGoi*YL~RMFn~ygTWG0GT6a#l}#;o-SA1xwD)+n+tNd)rfR5=tY>#+Sp zWbIO&bYmt`c7qYJnwuWsIg(>s*z0bAtdrdM;skh5FuFGc69`eh-p2^xN z`8W`0g<6bgAEY=kRk=p|73OBJ9n7=LCQzBVr5t z(E5KNf-sdh{-&4n+|aJiOaWdw?UZ&*1`USLeCU8Vdkb)*{gg=^jo|JNv(3wU{bZys zcoxa`^gxV?3vGg;fqR5N6r&*txNf7E}%_jG=dN68ySpDf#aK80=E zJX;d+A>jDlsghqaPWrPkE(J&{aKs#@4s8Pm^ll_PEkvn($)ap^1#`x<^HV3}#<>Y6oC-bq0^U>N2{jpHA9f!MN*gwhf3-KL>dlgKeS)5zLGG}^+N zSN|JeuthaxCM4lYA?G2cN;L;fCWah(rEBTt-dMu#lnZSC=)==g z--zE9tKZYHeeP>l>E`!Tpp!ecluF~2#7=n!*kI1+?Grbdal^|Hwu7YrvRp=y_k63Y z{Ycn&yu!ytckE+nh1M)LBI|4KkFJhk!wF@9f3|_mRWZ&cl4%6s&fm5L;IC{H(A_;s zAr9+QC>kRM`r8170CaX#gU*iG@$~S%59sC37to!4K90i=; zZ&IIb2Sr830R~dp&Vkh;mlo-tw26!N1O-A?q!DUrTo*Xy0GCr15m`6C@DSZv{`_!!(aQ>ou5W`DY50$j*~T*> zKQ-vro8fC>+)Q8##G;48Turt)&0XIp7U_{ceE_DAvVIh3dHVpk zwMNO|PoU_$7V6RklE8(i+?CI3<7U|L#RZD8qyIz>uwa^xi(PnN2Dj0 zt=Hg*6e^nwlsgyVH z#(25Ravwm5D*^+=KsuGnEL5tQ&dBIc(4MY4-;zncTY5JCNj;E5%n$OK&K76Isu@f6 zz6q8P9q{MoTC?HAjbC)6=tYOGKxdruWa=yBN3GI*U&V>Z-;z&LkNKo}4{U>%3GnDj zpi4KRQlgCsda6i^C^aLv`o5WF7eMcw)RMmRV=xy$WH8+LPD(x?MRGEW6J$b2S>>LS zNaSu1s8u^O>|7uVMJcj>cIl5wLld}$uTN8O7`-=bHAy2X?%wjSQT7Cf&iVKHfkG|eLhhg^Q9eX?VAYNGu37Dtq|Vl|ALj&BqvY3-P*ATqm{t|T1N9+w zSDbo)H~n;U)+bU;db6F$N73pZgX*TSySt$V;H#_e&0^Em^A_E!9;X^6_L-MEr!Y37 zSg#uR|HXf<1(uQEKG&&nx-^rdK^)m9s9wuQDT_M-!3))QoyiUFm)1rmYDz{DfgG@l zwSX9<=rrI$K)w(7({A*@nO)$Y?53dyOoObx2yjG%;H#hqoHVe7odlpG1TZk(AO;vB@>Y z`XEQD=F~&HLTlzJPr@WN z0ssDaC_2Zs%+!0MmcJ693e_ArR@DUiVkSE$b|%5nr7&N%^9qT9L+tvZS2x05E-e;r&Iez?3CpqoTR<@{k6P^O#OFn_%0Q&G-iDNw4c z`M?;XD5k?n6}7WNOA2;-^#HsyjiNw$n9eM5il2CC`+ScWEYRT2PuJ#eWsQQphW9TP zLwCWku(G_M?!k9s8XI|B*bqcxKVi;-~;?k9QvxRlE_Q)g3 zu{KQ3hqWPWSaQu>(4+zI_81pDD&r$@p*1uPft1#tHN?9yL>|L{wG|I}Yw?{!P?J@N z^gGpsG$q8&T2)O&&k5#>L1I_C6g6V)r5J74m*-+~sZY zpvL&MG0TQ`MW);+dgFSviY#P(RPqn7e|SDjXlMry;iqG?5a0L1O4iM{vk9KR&~5A zO+I>K^ST@Jft7BZ=a_BGo#G|%)({25#&%enCuF!^iZnebpJZkk`C&_odn#vQq@Q?O z-d#sZf(8}LmDTzyGiIfKSefqoE@k6hK?fQ)wufET4Ct}GfFA3ca>+M?t`U1AVFFl3 zS8el~rP7wdjhq_7h&?$NL<^(jYs96T-f4w`%|0Zq2}<2@%ZI0SetJPzKPI=j{ouTU zSq4ou)7S>gdsY)WZnXL0vt|#U7P7s{Q*itraoGgm?CVVA@yc1&j1ywl)n6cz4X_VS-It+Io6|^FFXzFj=8v@6g<6pc3DdoDs7Ot# z9bTf){^pytQ!KVddkZGhwG(d2n33SOD!{+>(0f2yh^s3Ja_n{Up-*}GL_b|jyPA!S zar}zjthqGokhBXh;eR%^xy5p1<5XCruhjm@JW7B|e70qZM?gEA_kfn8wW)O&t z!lag}e&745=3-HJ9mtEsLlQ`brMPdp-B3wRu+zOiF<&7hW|vo?!!~*}0i~{lc(w29 zvqrs=dqtxL%IYKN8W$rI`+lo)j5g=MMG1$Ga$o<~7E|iNd?FH;X@Bzv`v4{To=<}v z3>Ij?7f4BXAztcDr9OH3mS0o4#JDGG?FYaLZ?NuDXbrOi7%fC&CNi*W_HZF4r=*-QXqnRXL*t z(7pZ+aJ*Mg6V0hM!--@l#H&_m7Q|ei?!8D>dhf&2RLk_ZfI&s&(U#&Nh$dx-?wL4k4IDiU-VF)EMMdkiP7jNsgCzkjX9G>{xuqkUkti7 zF0NwXNCLH$u@?cQ_%BZ&6NWo1MxE6iU@#!^Xc__49&w``H@t*2|r zCxLmo<}}#lMA|&4R0=(ORnJg9gGNp%e@J8c#;uj`>1?Si#ms>KShR45 zf2ir=$@;0GQ=#br(KyIa96nokVKu8{B#H`e3~vY=Nwip^LH>j|V^F(YVw)b|?$^JO z)-)+(3>Yn5G>cxMHt2%;rHh6^*xC_~yI)jR<2q6syE*z%Qcl)vtRBnwt=`$@0u{KK+u--o&+S4t=W&M zo`6a`Rw*SHX^~*=xhlA#&d?t1)Y+0(3+qB?Cv*Xgt~TYK$nu@%uz)*@G)06aO4dFj zmr;OauiotwJf0*&8q>zIgC|BUFQSuzI(Zy!Wj^77IFkCQyYQ*EDI(`@xB6Y_FjUdfx~g zf;=Jkrk?5^ItVJPl5d)N$GQuH-hW*vZi5jDVTN32n&E#7v}zib=Jo$;2xX{V*5MH{ z+2sqp?^}mczOFMt343^MW~U2<@?gy3)AtpDGcS@I__GU0M?%VA|qq*%!;W3 zoYc0?=PDR*46LR_OAnCl0q}`bmgDHRc34&!%nf!4TK=|@KB%@xqhZ36#(_e)60`@b zs)m4;2I`*YP7KaM1>FANsB@Y)5*~JHRSPc@r+aK05L;y0Y`nw2+)(1-sl-PtZA*d&o^^8O}2&{MwD(bLYz7SZ|a_=3#N%!tKCcq{H zkh|N&%hGiKa%e1ZJw{-oIF1^}2$u zHZ_!M4B6GTtoFD--0RV?tz&q66lP(U2qIE2LVojpe%l(gkdN{Nc@#IR5)PsVKQ(u7 z&q}TCtgpUuXnC76sb4|2L+GCT9)S;2Gxd}Tue=^2N_ROz3!v1`YSbzXTS26{75452 zHu8HI#XG(%Ga}{r^Znr!1845mm3(pEgSwJB#~HY6d&)MPDBqKYHCztAH8Ei2QzpV9 zJtbptNZAFTM}B3yek;R-6^Zw*fNq@@kWAjM`419p%nL8rzhgWh!Y8%e)PG&A_&Ka! zS|s(27O_@k)8KyQlaxNg>s-CR-^K1pcD7H()x16TM}DWzYTPS&5#l}My@{|$*?lB; zfV=ILN-%wlqGR!#8Tz;XOu#_AS4;N5^7UCLy1>&0dP02$p6r>eM3qJx{Yd+y8C@r{+3v@Q;p(mKeB!!3xkzC%(nGo63&ewQdqQ z=~FqJut2lSB=(|mS6njIT9-+J&1VK-*bhKF>(}jNE5U6socl_|5IC}Mq|Y2F@wF22 z`E(ify#Vs^-SI?Jo*EoUS|4ck63~2p2*gFzobPPuen2!7lmz9eIMu1K^Pe zqUmd&2g?kl02h@@npoBgHBMmAE8t0BqPqZ8X+qG>3}yr!7!3m8&6pI3X>m5=d^+nq zgL|RK6UK*$8UYd08Zfz{(a6TsJLTfr76{^Co|^nzLH}2nB{T=1Ao$v&7dL-SogSgA#w|!FXfj0kX-e_>-mz6&v@XX=`3ws0qfmk4FLwbwHo( zR_&I~&>R}734GKk^@h991I0Qtufx$d9?pspK2qq(=z>4Nwe^9nrqV7JTjvB~@ih4raZ7n+o z89{t$O%Lgo=QU5zw1hnGmV?N@#YOF4WtX^LhbYRS8Yt%GIfS`#s_hq zfZgT=58?`sPVH0_%KC;3dr!=jlA)xfPLJ<|G|C_h5;GkS7!R#qSz{~y{l9P3{^|ov zCa!M7z~q3T{&0vjyL0K{+k3z!a`u?7-9eNk3-EC1#nqR&>gILf2;CL%JH&fvng*?A zOx=#Ezx%`w-=+ta5Y3Mc$aG83=hCxXf(7BTUA!UO86MW>4Foe(0xJN89>i%78Y?XE zqeL(Z7F!_mfvKo-r{Hk<_x`C+w{@Y0j){Hq28hh_Ts7d|w@nWk{@+KH?G8Hk>s9NH zt)%Z8ovsh%;^u!tSKMJ|R3!kn?E$W_WscfP^i6lb2G z{4&-we?K;d)-c)pmz|*X0um8F#T8yNoM4&>{GU{?lPlhSlFS8HfScxS!j}_9Xma~+ zb*wT-irVKQFq?O{M+Mgep=7Wxw{scFr@tkQvw$0!<%R1|aYp76D;gVAp)P+pBM5CqmqNH=a8_{@^w} zaO4IoEuwi5rCEZp7sXH1nvv80KS#$lh&#qO2)9o6Q2(rkf=*$6NhwE z)P#8?fIcT4QQw7%_R${J4S80-B>caYFBqO{O9Cq>@Kw-|13_%QwAQzdc9cFocn$X~ zSHI*2LAfgcs`3YI1fEASOe2>%Kvc4+#jS3~s6yKeTW%bjLb{upWVw0wl7!!N#XeN~ z`!(wC*Jj}n(igygbUMN*g<|I??}$uyVhxGm#znFJ+eDA=+)Wg<0SB}Hx4N~JobKghBPOPG*=svw z@C=?pG9IiBS-TYLQV^hyG)u}(H7hRb_*Wmw?_eI^|New%GRIA?%9~j_`OYrurgW_u z+|`g#_CGQ59pj3z#*(EKZQ`vhUeKze+ZXV9&G8XjUk?T*=*$}kKKQU#9QU6oz)!

      GZ$q5){mx#?SxbYkaa({uq%YG0`xR*gh)(l0}%P2X~BTosfgMOV~02 zZJtJ7i_Fn~i%c+4mA~KjgHrEpQ;ZbBDU>O9Y#8D6hg&`m>F1q4LlCs-%xQBB1g!`EU3YWi2Jk^3A2EaEAn1(wALqlkKl;Mc+&yrbQvO_8 z&(m$Ek2`&K5OU~wHX3q&MISKVv!@K&TlQ@5udJ74u{{SeH}uxUAg%^{3{bVSe7ZyP z*~_w5$C}2gw9(%-`=C~&f$MdSG=U}_78)gKjk(;MIm&@#iWs# z7|rBccX-Mu_A@3%onCTITRsQbza3#sOFT?I*Qf_Ub=m8;L#{#AbMc2C zpWUCO#D0X0`c^Phnk!lh4d~`V>!7aQW^WX7qT$`Ulo4*fnm*BuC!9pF^Q2&G>)(Lk zj^^kh8}?<~s9)LK&$rjpqZ1v?&2ufWBspl{Is#e)`RIZ_a#VD2f!0xjAx0q?ZQca8 zuksKi{7cytivE&C4R7QN28Ux3#HBCN&^gK6Ivu6?9~+<=(-&*DK(2EpDGQaMe3oqD z?Jcy5KI;%Nlj&gcMh^1FtN$(s8HRA=iSunVTHS*DX4X;K{38q@)~O>S84p3zb89sr zC}-NK;FP)Z4qLnuVI||#hb!K6cj*%?HU#y0z%#I6Ev!fy1Omay3G7O@@DO094R?p9v)88Kw5bjHSOm^u|2V*C} zt}~QFrM!+5PK$-|n^(?jPt~?y6S>|mVe>1&#_J8W%#qmak9RTk9|%D#&(b-{Z}QMM z6)?raYNzC&=~NASQqIHrP9eQ|A8mS;-eDHE;T8n>H@pPSQ|8xp3?8Q$i_<6+}H zfzz_$Q7Jup!@3FnIJA6>Q?&H-RT$hXB?nMg_;M`l`fD0tejZ`mj3bYvI7bV3YF*?mXK9J zl_YY!6;`jhVWZ`sYt7~$>@=qo7o86n%VsZ|X`<^L+$LoN{*WBo|Fz;S@)+f|c zG+f$Bt1Y!KPt1d7@3sY)t*0X)nU_?*)cSs8fDoA7TzCPF_V<|}+PmU7ITB9N?EEh4 zy9PN*893{yE6P7doC08S@H~9$>~c=V+5My6ccNA7*k%}W0zK>~xcE}B1|Z&B(X)8c zcqXlmIVK}EE!z>bV57mozWv87;E!KJ5Ox}wC|ecwkr6>%`3uV=OoJpGcs&GdumY%3SSrBxx1%AMfo$>7Ac*$tr%g9p%I&bC}Fp4n<$>_af$V`***Nr!# z##Z>U78aAd6%lSW(mA&oO#X@dWyn?AdJf;{p{rXMHAdu*xZnO7|-ofb{;TC{>v$;5RCitd^D=NHIl8vvWh!rFSO^F;px4K;hK zaoBi;a!~XYIM?_jc_fpB(|sANh?%e2*jSZp$^rUgfdcUNA-A27>l>{4e2cA$a(X)m zx{Acs_u}qn@v3mlMOQBTxd|$A%CHA9H&R=#Xr67*LAleMBe~($0DPwx1uxH+Ys9aX zI47s_q5^vLVGC9!)9kYH#ykKQ(UHeN)cNe6yg&?bKSs21!ii&4Uwuts-Tnj2&7ZLm zzB`jj5sX>u^@Y#XnMpNhdU~;jhsXY%yfp}kf%DFcAKI15x>!lO<@Jb=iPj?oUsSPV z4OByX5xW60OsaTvZW-06qT|wSNs7ELI5K+6jDrWMWO^+e6S=J*CaNQaUL!R(Gd%6s z+Q>kZ1?>2$mhk9ToihZ^$$C{YM;sMZBhFbZzs3@%PWsPgKv2bLplYC+deWjN!Y)N+ zKi)A&$Wfho4UoPbq}k{p*mwO81HhU6q@Wx26=i%1y&J{ai#7N90>`A`&2`}UcS~G4 z937NZGW@OaE-6U#>-N|Ef_x1?Zfy1__JZrb-*fuZ3DPiMhbDE(p8tfkQn$=s1B|y- z^5I!q1HZpX_Ohju5xFzQw{9X| zgZlqJeY}cxj>1Wsh|Iohw({=bs|9th8!_08#X@QEQiruDk*~ z&k2jI_>Yy0uOaYA!EhxZVvwV2_LCmTLuL7+F*^~y?p5=f=zQK2@2JJ93BAjlMd0~9 z7?FtILiAcCm$e z%e&QEGfh6Ng%Fm2pEM3Bq+ z29g-S>)g3|^D}@n(NiF|2e!O>wp$+E1U_F-ioZRtFtg*~y z9RwqeW5y@}K(?SM0l_TS+P@a+d4J&AUcA#|8+JvuBw05!!x5_$@cZ_4;Qos3fELrK z6zN+<(x>jxUjB~^FB-}E9%Yj~NCnYyTfxiu(-lPrtQ%EKk2+L3T2kwhu!PTf(!a@I z+0H2gc6X3JtB>Rgt_o1T`Z6c#Vp(_xKF$fe8051SSj_ce+%KZA;j4n8wOXY89btbI zQ3>TeZ}L0w*9c4R<1eW3v90Az{h>uaG!G|g=ce`w==_> zvnBh8yc7;r;hQ=HZCP_1>dLDCI4ii2XjDfElCDBy|Qko zwqwlYVW3IY0t&h62m?1@YjG<4N+~ZZKMv{Pd}relxkp4S#$0nHV=W*PS+KEhgUmon zF(cSfva#eXcDa zkUA5z*p>SqGU7X=Q#h*(d*|^X&x2q+{d3^Qe{Z)icS^Hq9=BQ^ZyiiUS|nnrVgqp1 z_Tq7<=KE{2u`C@u9kRoeBY9t7XnhoetpxiLB)ps;2l=Fn17j&AgaE-8{RQ&Q1YIp! z;xYloMrc|KV6XqgZa~K18mRGGhhy%PHCDv(ZP6x!WLVD0mx@N}hv6^yHENmW@WqE^RWPa>76MQ47Xa8oBK2%@&~}8# zljiqFQEc2JI47n-fN2eU0M*ays;Vkg!b-k9HK&w=gsDHI`3S(0;jECWj0ourll)b| zVVfe;SDjr3f|2Mb{bE!(u0LxiXD58d< z$D}K7xygA-&}`w`>_@ktVpg+p z(HW4g2hy!ynT=g>`!=4R;Ia#KPRwPLO7e<8wmrH@K?xA}3W}%gy{<#MZOJd==U*rv zqOa!KA|rTZDo0N@@;z+yoWjVm+|K)fQEpSt=H@@awNK4{8gTY$tjb(64-kzY#YF?z zvW{d@ya|p3AFDOTp|T)A^HkV|74_|n1Zwrfcit2C=&J{I#E_Ojh zI2aVQhh|6HIV7!-Fmo;DN1g5MurvO0Z5BZ8tQ1HM=TuTyImJsu%Hs%khlP~YU~oMS zOjh(%)oZzr_$_8s*f*wvDIQ&*TYO&g#|1JNegK%POBaMf!}RPD)xlnJInV2oh*Uk| zcmYTi2Ty}#Ex82%CQGk6cr@pF#W*b=MLK{T=34!&qqqPBf{zYeY zT6#a$7qJ&41i-$hY@lB*sLTO``8YJn>|mCDPfK?ppmw={HQjCk9R4K0m%ELZ>jV~U z8Iu|-LW&^+=pw8911dqFYM@`vJRv9Eu~pVHld$HWBo1l8#iaM~)u)#L0F2(-*M>E3 zPl_4uEZ~SrloqszQ=I_Q;b`o60HX2sGb-h6vNxy45781yByvzZm>XQq z`Iv%eC9Z^zX2`rerVOW4GD{eFh!(8&v@ZnU`C7ud8ixlOnWxOzugjJa9VYUTwI0cs zMu|S`(NNvR({eQqUu$(F)REbFG1ixSQN!#_B7oFY+pTi*nropT+^!zpF`9@^Ko*XP zcOFt$w>r1ppWqi*6rZP3B4*#UzQN@3Khbe5LQtvq6Mq3Xs0*^W>k(d-$QrhtCVH_& zUCYkp3FaQ4r{L+mUuw4j=Dj+BhK7dut?J8T`9YngS?%1_)C6>tke{Q!WK*38evji) zSlOyB#K_K&=9kRmN9%9BLj$LeJPmSRs)Y)|J)j~i0-#x7B0m?A`}rOEtvc|n>iqtyJTUTGILkm8GqGj+N_NIUph&uvSFzpwuYv1tb$7j`& zoux4pk$Vf$n^3y~9zXEm)xeqo^G3Kd#jC|HxPq1#c7W!N23rpKr^LNgQpkBvcw7R7FI{`inX3d;=*@8%m7g;R8`(VQlE;(vrY z!2tGfbs_}T8>yOWM$dhIYAp5jTIfL{Ct6_SfzmFoISx(7uBuo?Gcz24o@KUXJC-Y% zTQ&Z6%2o*kJog%9kgK8rY64&& ze}CK;mtuL22dI-N7l!N_<^9mQE>>Kzq)v}>L7%zfJ$<7 zzoXdN3T=#WjsEnCX;5>jzxnekjA^cWfLr*WL8`OXT`m^ymJD~J`!JCK-df-7Nqt~y z(1wpE6kWv^L7sQ`IArZtZnP3;Gv11^{y%*)`ljv%xh}O%F(`dH2L+|=%6@0)I4nUc zAXx7>d_M^5nj$)X)Dbw|ofj<0iTs5|XY*pts=~Jl+co~X9}A3e7b7qQ3o^6NGrcH+5rBnf3 z)#={+N2NokH#3ZX1Fi%G0?xSyNKF-!gE3ylzej|an`AM~{w328ylS(AFe;@Y@^Cnb ze4sk(ROBh1&|Mnd2_*N`%XaXhstf*k<7YPXSshQ9eG0(9xD_@UgxCv=<_(I4#;|}{ zI|JbqGofv(w-%T+Oc|q{Thulbh1|c~FQ_C`%`+-6ytIn>zrA6$3WdIUv<|4{hZKaO zq@ZTvaU)@GMm|02r1^*2tFhpJcFpnVFTMcgx=pKRW{Eqhk6Km~w_~m-|MIg8++Wrh zvkyuY?!;+iPCe0Kg)#Zk;*uL)MqELvDiU0uzV|b@-=lh@RL3SqaSBVc$e+^AWP1L$ zN{2#Ip)IaKPK*id#-UmJNvw=JR*@w2Y-BXRS!x=ga3=c86=H*5x~`22#<@xhgB`aX zKM9v7kkIYbPc^wAR~z_+3c6*_Lb4n!hdqS!c*=o#CX6BCn#^AZ+9!~i=H`G{%@mlm zYTGvrafJZ&Rxz@M2*ksIb|*#IDQ&7XnqwJ3G`~Lyf?5UUw2Ic zJ@0Tx741vkPa|mUJO91@$GT`pvtN|RgEv}eBVWIDj+~CqXL6P&^IpNvchfm0XH%dH zP{aM0nk+wXY{nU56|YTSoFf!X9t2O&OayPR)#GF%f1=rZSf%5o9RXFiijF$U&!9Sd z9AziMJ>pyIP{X$le1n#01uz?DvkzRTLpBr0ZP7!KI64ARsjSIUEtkFVoESBaQG&kK9N!_y9faBRI>W|@ zwa2@d^8_ZPfQ%<;LBdNa2ozG3R3GE0nm6T(3dMgF5(9i;^nUZ|^m>@9AAq?!4lC-$ zRPxRsRN9>y{}mbl0DH=9D2oKTt{nfzf1GU;%FT9FYrYFq(T&bAaHU9GvT_8O$bkK)VL?xc%lR$E1URw=W=ZLoo z1K90$8c2uz);yddV7i&^++dNV*)iDRRc(Szrfky2K`c(L#Gs%ePg6xK<{6O zT-8~6mPMVQTu495DuSs~aT!QIpu(Kg0QcW|wq{FL+`n@-^PL)an^M@ZcoLCdbz}@I zP4qXgiPBRK#P|_~y(1tVAT}8NHSQ<;SVHd=SLW7Oa)f}#0 z*lzf$CA85;9{2e-$&JGMn&_ui%XH7F=d|`;e|ru*e!HOp-t`k~wVmd1$&`M< zS*0X9fXvXe0A%uL-!tp?6mDrw$&V+`L(?D29R8N45qZ4nOnT)VY?+j!!SFjKJGF5QIDd#$PB<6upcG zdf?aqHu6Gt*bThs|M(bm6bKH^^${I-=k&Abk#k(GcF?ebHy*Af^np=od^bWj>A}?# zde!r-PctM-b&Ndbit9ZkX2-9qYd2t{(hj9|N4Vq3-(pm3(95sltM}6+%S@&+0tE|L zKv5}fluLC|dGilLC$%`hG|68OvbKO?={uWh?~27IGX>L z+7NGC!KN@&CJzEK^=(TsZ|(*;f-HJY?(wcVm}%j)x~B`+_?qJb=U2n6d%-Awq-GM+ zn9`1&l!U-C)+$-QY44>3%J1=a??RIzmTZwUYwz3@iD-Byh$yJeZFZCYYkH|DfIhEPLfg#9&-ZIiU>ESMz5d;6fHYnAZuWl- zlK*Pd>765nUoppOF@eecwP4&4-y1dc{va9cYa4&}mL-k)|HfSO)>F{NG*2T~d~|wb zCQfFNLz?>5110Vt98-Xg%kA;cWE@%nyC@M8lkvqb_0A+@Cbw3?iKM39Ic=?~pO>^n z&n8DZSC8=prqZoohh~fm->i9;V>}QxdHLu_DPVl8!wVx*Mzow{rw;tju$l}uPH8{O z8>WMRjwegrH;KCBZDsW@XLlnIG|pfIJVMUx^+vFi&T#L%I@_YY;=fF59|7tnpws_) zk5bE;UsU5KPlG-E!%tZ+{iaY_twY`@cWFc*1>8T-4$6gIXSi5#>ShWCZiG#Njj;So z=1Y19yb%V3yuY9=Wd?v&PP05Cx+k7@bka^&TJt)WM=z+r{=45TVRNrN@SYy9?d<1Z zzuczusQGZs08>F`zq)gxRv0t%_zN7q>Rd}NC($zzGq|P%Zyi5 zv)LuVTCj7AiEtT*A&u}8xbA~do~r39w@IXYY8)C@v>4{apVnq3{`$uC>ndb+eJK7R z7y6$s=!w;Q6bp8?S^f_5tFkrV#Lw4kDa#_91oVtxLh66cl~!4Z-;s`vIR2Xp_WlOl zyn<5^%{8HApO08(sZTja+1{gYx&P*hqFQAUgm`m7fKGw?eW0_R?{&5j#ft$TrsFVMw{=#Sf~Cg7DV4%2OV5jzqhQ8zXES4m`FLF zR#JmLTp`eFXJO!Uvy=Pu=kIq0u3IDQRC1__Q=&yaQZSdbV251QBx|5t=JgZhgg%s58BzzM?dzoNwaIcDwixf)yKVzMZI0^SW zEA_ZU>BPiMgB!Sr<61Puq#F1(&#c}N#>+Fp|2SWyenQn^rx;XMQqx7aV3g;gIcZYhS z_wE57&_UNV$H51*9jp)h`O709ID>y1KyeCxt_7tI_*j+p!Dmf0+!+DVZ_T=B@bSOf z!5aK;>Hg<7a4h^UWc~*izzzNfmH$f<|4WhUqCqJ9|ECABsz4fs%IaFHqo$_4g#!KP z9=IJ5s2DeXBX1@^NBL!p9i@=NyQCHOi*_2@8q?!BNX)(9Mid=A zbf0-dQFTo5X^4aDu5DB%`RgsUcKlpn=mNs-JGoSF+j!Zy?>k#qC{69zEje;<&zj?4 zezylskMwUtj1Q&Y)B6{{8qRA zPTJS7g0c1(P2_iCO)J}PaF}GCO*8#zz?@~XiH0Tlrkb#@X725&bRj-Y5F@ugw{l| zOL5d6*};EM1v?PS&vQHOaN4KIMI}eP@lB@@9@!U-uP|-3Fn7}egT0PgzOlG_8i7m6 z>`*fDE@KC8fu1@|wHW`s9+<>1O3 zCc|4oMoU>{IysVoog;r?+rsZCCd%g=P^2@{^~GD=-#cnqvb^sp^+iMj-407t_Vx9p zUtbcw_+%v5U8=&%*}G?sEd0pEQ4fnR#Zq1_e3~>GReBSxYhj*(eEKx-nE14Mkanqv zOUqc1fkNr+NrPCdbmp7$=BTh^=~ZY<6&h*QJ0iJxU}VMpcTr9MB!leN8?enaLhvx7 zYA7wJ$qSwpCx89=zlwfZW%7m{)1Hiqou%FU>!8;{zJOksUYW&gri`hn<(gG7=P9id zORjjeE%c{PoqzlYjH4)P1!kYuut>k~mFd9$&hy9uqvi}e>TN36IrE5|l=YbByXJ%O zvS{?X?$cC_8x~dxn0pS+iA*!>hnvL}H|B!fB(uFCk(nQ5)Jw8gXjQ&hwYDsQ4_*7UmU#2JN{HM||Jlm_OCIo7gfvCyw&pS8@G` z_wG{VHtE2(S|#7y>|jpIZ>*!@zr0Gmxe(}ui^RJej`r|T(y*L*o3U6{2efIrc`??C zitUkv#UckkpC12A2|JB)--k@!whzgt7@lusr*j*xqRJkcna2>bU9G2Syf?BinRh}3$QRXvP6{pN~Y*cL3V{b%7 z7@t>vfQdX$z2Ws`!7hL0Z2)Sa*N)nj2^tYBtbh*~=M5Xbwsf`evdkVH<9*?O@%>Gq zQ~M`BJkwy8gJfKbX=|I1@lVh_jMY5757Q(XwoINzvskqGQe3?Z-}9Ka4Iz8&(VR{u zz3*@oh6dWa-17I<)#9yYHW`V;hmRzUPdLp4<@_oM&;n3u6MwyX*1u?j zB`!47EHK=Dt6RMBxq7`bfyoy?!8B+M%C&IUS|#>r4aN}YyYF*kyjtoW0av|0!($7S+SJ6oPwc7(<#OciWuA9D9{|24I zRH!Hf4JhV>(!Te8)fU^Q1!>k=BNU2q%Vk!|fQheJ7Ii+nWu$qsQ`8YSFd)tun#G6G zBUj=Ir95(#8&6zlcFZm8%BO$eno0%&~M9{}mCoKtQ=nC8MJJY3e_t_>Mfi3Fsf;e==HGV()er(dsX5#eN0)t#_y0+V4)#2XXsI+2t zT7I~)|6!2gu!O?IxcD#Cylu>4#uQEl(igU0AaUY+xIvZFN4~1tebofaWQsEB>17NVXwQxIHaHiTL&WZ-D4Oa#2 zTyC3R-jq{$av#DnXK|4@ZjTwMCEMi;IxL9wQ+iPW)u!Tp>YaV`i6Ps zyl5Z6d_z_$8*y}c*P{w0+qks!s4#lfRnTX`CQOq?ikVDyRA;OK$@P5(PO)Z6<&$e! z8Bj@mh~xJt)0=iJE;t*7cCO{Fb<9Y$iu{fxI0m<5l%y}x7l;`c%y?Z%nBRxn4K=OU zT%s4wO7SI)_(!5tVRPxyOzXSh1>?Cm9=Ve>*{@`&eXWzHk+-H>u)5~XZQ!l@x3rM2 zUn&{8Vy)hV>*S^g$7fP#JE=ya6ilWnebHL$ac^Tu$4Ky`=~{a$#d;&++_wr*CT(_D z*4VP*&10g=-1z;w3?$_XMZGRJea`5@-Gk0SsL-o^Y-_Wr2jV_Kw5=Kc{X#YVf_Sl5 z)d)lN1Sf2)&b|5Lr@WPcml|>r1Ui_=WBH+YuX3~fB7uFQ!chKPTuVo%3wdSNkmpS2 z7xIN|pOP!Rz{o|*ba`ccj&N}oUNWP62OsvVUs83x?Su`2ZcYdYZa%U#>RTbtd2WWm z>S=wRPGday{S*APps8E~)uW2@I9U z#?>?LcwOO(-Li!zgu>;NP5f^Q_i$ZG>!KmB7tkN^>FZ^)ORk+)1HE`$(16iQ)y+ut zjx7mzz*taCn-_ZZ7dg6`o2Rs1$=qf7edgvZUNyl@pf1|o$KY2>MZ(WyHgQe&?~-h| zPf00ay6Vfp@8Y{tPjp>gy*4Bg@jdX_sh5b+!Y_-+d^bOI*DrBDwq3;L(>M>1x-X4Z zE`qiVo*+!p(APGeH8f^+6NIGvd#!Jpr@-rJ@)GW{81Z9uZR6v{;;ay1>w?O}w8;AchXa67IG!M6KR?S_C?1K3+d$)06l%qB8DTWxF5}1hn!Ixhf#_&s1 zQ$-kINhCVK(MIK?-$bhyI>AZnm%4P@17@Y7tfrDHUVKj{ zxetHx<%~O@7?bZ6RU}+Ks$Z5(d81LGvitf%!${05<9?G4gZ2H1kVTe8S|VDEulA}m zd;x$zy|PC7$&6eHj>X(xATT?Y^6|jWzB!{7~eix{;GOmD+xM-Ez!p*U0;ISi~ ziP_o@Yx$QzcllkXrO>M{H}>wbQ3Ixqoc?reCFPR9OPH#wLy~z-|+89={8B&dtDLsMJ_QN?nB898&-rO3ab0_lc8Gz*e&C27r&)A5$)~mA( zYt_+WGEE7+8=?5vcG0)~hILJK)yHg#9f6+IYLy*!-g==Fpa9RgTVGmm@W9`Za62zJ zD+n5Tro}TfT4VD5hrCAmO7o}j2Uu&<*U#A&M*ch+WeiJTwqrF~--u35>E$R;8N{Wl zhwnOV@r;z4J}S2dtS^p{iZP$3w$Pf-k*ei$qRyTJ+EwrH>6Z zsw-91ozlC3(k0cwU1Qfi=O>(Gz3($j0KQUIy>NpEpZ7>7UHNTFW^OI3;6$9F*S_0j z=oI*QL(F`_;B#iJcJubBrJ*G1i{?l8EKbi~-!|KV7l7ihic+k3;z-O$ovz+}*?~aG z9Z%oqpZ`MBLu+!&j(!o!>*$Y4K0IjH1;2kc+$LOCu=8uNYh3*qU{!yyKBjyiAwKFW zaKa-ry3}G=vJ5s=!z&qIgg5QAEX;Lji5zZR+E8siPDoD4Y4f}1Y^!kN>EI0m17OQ3 z)-xABp|AB2P0wg$tGW!07#AZi*F{zMd2CwmgT#I2{$*VpcF}v*T3cZV&DDQ=Y3J>~ z{dZk=0r!TqRP_muXg-_;RbP)*gUmA_#fm;j^(1Jz9>HcP_kxoU`lBB6^p#q{Rmtm~ zUw*RNGLKAJf5b`OjD$setGAhFGz9;b@1;DoBhhfjOgloTl; zaK7{sPKD=qWuUJgPd|S{G5zh)kzJts!6#<{>}I|`tfuF3M2*d|2oK3N^l(6B9p13L zSD%rD5h=}5SczyCwRrM(w|H`wlN)BH#AF9}=I!ZEfAhd;*Igox)Yf~p*0-cHqxx0! zb1TH5JbH(NbL=Nx=ps5px=0&ueRx8Dpky!=Gzb4eoK4lpEck&f_YZdyq#8Bo<($sw z#~#_ewM#e9d>CVW24(tUaV4YhtfnJwXUg>bZbeHUV$miW@Wklng`uF~8XTP{9~qeF z(WrIoz4lJ8=09W6E5hOB?~g95$=jehV*r|2Tu&3yln^Vm52=7|-(#m|EB1>Y;paIye|C zi*s%^p2BI$qjM(}2MQU_%YpGP=f+DFK~IpQsi;+B?TJe#<>3R2kk3L40d^a3+IynW z7?}f5n{jU8=Ni)%CdZrLYw0`Uo+0^U$qSneGr0?n9BlEY1|0#*QX+_WQEix+3Oetw zR^lvhGRW~&0e}6*8q=ym4%WIMs~L15#*I+-H^(|{^wf?)Nn^owbeDGp<)sSBMs3kj zK|!X0TnQsg6@xC4q~9Q+%RNdVv(@rLcmkJSpkw25l>9~i26dG(JNs^WsFA6I(lPb2 z(^IUd2 z)|k*QFb)hee9OHZUvb8a>uWY(eg@Iffw79cm=``}3p!Q(`ux=zl1m^1D`0r-0%s9z zE+x5#%hj`-*41Vf$g3%*tLj<4E8f|X$x%im1T`J<3q7l4;qx-gY8Q#FIi|;)UB~WY zXE7Is866H{&laR*LqeN`k#v2|F-DvTtbQQi)bMnNwF0$LasCdQzm`vy-CUR~K3QDu zmkq3++9LW;PYO4Y_HsqC2SMqHmE}06@$n&rv_wn;cxYU22tvz38)c=9KyB{u zly|;&%ZT>Ayw=-h{7>_!OpB;0>SAtk<=Wi#wO)ySx%)P^J1E|-nEo@rRB-?k=RnwH z@nJ`ccOD`q6qoH8aEcI~7&v7WD{ub6NNX@nIl#s{080fijKco7uLO$z&>v$r z?qjlF+G$wa!+Hd`5m1A1b7$oC3eU$;IGvcv!pK?BVm#a0+N!`{OGS!xItTPNw|pOd z0qp0)vA7lsaOElK94`fb79rH5{VXdp2I0%~rc#pa)oM)!dcp#~WP9eG%AalFa_?x+ z6fMTliGnyqCKmkwBlYYYi62fxV>>x!$GoRrwB$4`4;!NeO{uoErqbvdIC)UeKx{>7q!ol|@5+D=yL@;&Rqf-F=wZ6wg$ zU8c&^s^0GgZjgkrN|{q>XOSnT$LC`@fAonR_pa+L?llDGp1xc&%>W%Gv+>Md(T|Yt zNMzObuNK+PjN!?O>z3K4?Y!?g^yFZ@)%i#u%~osXRB4Vz5b0B*vBpSCBXz^}kkVdR zTF_=mA8(~^;;D?ltDL=L`gp>ax7?JfF$z&v~z`2g%;r zZHaAxD0eQ>jLsBAdj`nTDxVsM-VY?`dlNz(^vhn+w*vq=r-iHHrWoky*|-#s-X^lk zzY*9V7klPp?m`A~ zl#tay#94_kDc5_QDu^TVEz-%t>ctHHN4BPgISI(GY0XBXX^XcFs@zt1)vuDuYIA=w zyxvoiT1e4ut<#l-MGU0!IQ<9nS-+8m-`L{wQHEyvGE=d}Aj5!^0JmCqy}D8tlbfx8 z{a}IW3`p$iKDV-xR+j{c zyJm|hqDN_y9v!V}7n~zcQ^RInPF}0`$Zg5&i1hc_u~cD##B`3ddrKx()WVt!nt9~( zKaRquXP}yEPO0;iDamS`j0HA0!fi!xXN6rAd!jPU=?Q^qeI*r)4$S%ZIA+2Qmzf9oAa9r_DGUu+TAk zn?mAk5?{YZNkv}9n@eg%e*Mg%gLGWz8Lz1ag-pv*rHmvE;wfsDyUQHs8|zf8YIwEP zKT~@x%@Z-!P0KL`lG=Tf4ssW!D|9hd0IlyT$r6#guOYK+?Cxs%q@qjc zvq>{i`Yu0{u!5OyNAU)im;T`04MSg-ENo`m0?sOLnRcV)rJAT0(=*CcuGHYZuP8Lu zMrLw$`X+BI*@U+b8Cd+YqBlgpmN)u(u_Lm7uAe-w6F9M2o7f~R9DH_GMU&T;BF(Y4 zGJev)ex5otq|y@j!IOBH-)l*r`_(5%3nvA}mN^;H&dy6gU)ZWcgy0lBDV#Ky%DZ&M zA?jMjt07@^_tNAkBcve7(Pf7to)|)Y-@nUD388+E!oEjwTy2&N9Q#V6)9Ok%YP(y^ z3~0s0--v2-CKsEpMbrKJ=1EQxR+QM9revk9pgr+9IZalJRd=#_5Q6X2dtJi%T$YBUOZ_`KiKVrwEIw7-lSu9yy zXkXZnd|W_bZ+GWVdjaaGbZ0>7mc;~>OEb@$1>+B^vP@~o0t)ocs1nr8bMwI>(ugjJQcISzY3WbYD*{44DERQBVUO`v! ziR!VG_>VrKnPwe)QI)E(xcM$NV@pf=V@$=&*xlAlCMPGWEoR5<>n^k9Z;F>}wTEb8 ze5p*->0^lhJ6bd0=i|4JuOH}(V&4J1>Qk?OvzPny!ez@T^YB4|V69mdSC(>m_6L@L zmR0@yOwJ@#ow#(?D0I%7K@sLq*toPEytyOiMKR=v!Ur9ayj?||Ru5M$}&i1#33Ohi3ot->mS zQC2=f+ILj;=0vockwc6t>%TifI7a0nmmEhy-=(0-J>9l))hOk>I7F7&D#(UoL zH&iE@^J!+*M?5Qie%OCRt`Ftzh@QZ2p_x{nDj04#V5PN-oRL>UC-%KGimli=%iCP2 zCK8cFIYRY~dk4;Z(*)-^YU(eB&OfZJ&$9Po?@G`;@SCjU#~K#X0b{l6g|Ng78`*Xs z$Dm+DawpPntLRHU>-=&+{@j7U6`+|VtYDmQ#3LljwsL8Z${y_FlZ5QQ)g96kcO3#Ra`#fu zy!Fs*n>U_(1PIo1;~5;JGpyR4%4&JZ;UWj0W~GtnQzlbF*aW)!>75v@&iENvd`U`7+mya<)rf!0!zVn9~hJNwxJyti9L?n20|K=X&^@S7x=L4pSiY zV9~$QrOj!f5@|XyQhER>THr;EBps>{O&n03=}igJy^h<_Wnmr;E5&<|Buyk~^czsj zHq(=|F&|QL5^vDs9{?$}{@`4V&UukIo9jN>YVU-78M123vNSfFPd+s|O ziSr|p6Mlk!>cg$?9mn3Wzc8B6tuJ@QA}{M#%#$-m{0y~gHH1HSvM(TYF0U*jiPf8q z;D{mfZg_ND#!++~R@HZF6Q5ft6@ySs}P=G?O zCYAt>8Sm2{F~C)oh0RJLr_BQXy50atZk@dfVkNk0zRE$2x7M0UyF>nY%hA%Eh(o)I zQnC^Qt=pIQS-P^1AqGDp8*lSct|)&hkVpAv_T_C_DMu_X82qTzf`1Im?-I*@`2m+s zvM63^C~Q>WaKCT;JL^Agt=CcrT0|SK3Wo_k-z6<-Rv!!$`f{C#RGzyRJU%YV4rmdz z^^T_|$(82DxTVru<|FxV95@<^EcG-nPgF;vaxACIXKypu*Lkec4=q0zEDSLI{#n~5 zRwQydSWL3H5!qik`ZUt7Y<6GY#CZHUBeHMyJX_c59`}9JN#_4O#Mh|J(~VO zji6ne_Pegvl%jHuipk{dYQFf+pFf33HW!@)(^i##)4-~;`i4s zo3>@y8CYp;E=}w=x!3Z>&&hOteo{CkYo43&Bl@vpw_@GiU>R1XuN?={iDIcwvvdXD zN(=LeTVkFbKUvqM`Og=cHoZeB;ExGQa#2;0!0Gv~Gi3o=0Bsg~gTfiqZOjBN*#}Xc zE9vpUrd~kP3ayQ3V_6-%?Xjou{_mwk+el$-Cwq3SZ2s-q+1}B(cT$qix4EeIOU2vmFEKEKHy&210oIy)WK7YKT_sgy0H-+C}ogr@Nev4-vA3i{7 za(+#}$7UcK`uoLRE*a&em`{@Qkq;W!U$U5w93>$}7RSyzuZ-B)*!Betu^467W#HGD z-uP!zv%cLKh<{tXY0xv$Um8cb-YgGv`bi;Q{A%rpG@}D6N%agE^8Ia1wc^n`m$2HX zQ3Y!&zg~Sc{^q1;;Z*c7Q0LZEAG}8)fgdhv!cNKv^r_$^a_YN?ftG8L5}K_!LB^aK zOD_tQNmX!_emveso%uIx^`3LYj+VTd>9u?rS-qSjV`ZGnH&*8%WnqL_mPzW)s{S>4 z8%-7}uvX_1>S)aW$JABFMfE-HOP2^M0!oLX(nvQbD58K!2}mm;5)v-Gi$x2lh=PC; zf;7^(Al)KLcP-MrEG)b4S-$)}pLhS?bM8Ge^UTaMbLI}NbFC-8)UNmMRtKc!+IQ3W z$=|>GZ(9ZNYpxh#%dfl-4Sj!4_e#c}CBmXdRX{I3P>fg}LPe+L)$J+UDVj6X^?UN) z7({GTA?kuAC%9EGC7jWD8FfncaJL7&<@xS8ckc`vhz*(@gqGBpG1NFYJ;MGRDs1J) zOsO5eqw+6J4HOs?*c6mUSRI&o(jTN($p({#S9Z#0iq1seOk2A`3}YUZf8Q_eJX}(i{EeIf?JI#EQfyH&HLZr^$qH#BX6^D~<&Dm$?NFdS zce_TbI1{RS!2}9uEgxK+efV^1k?mhO|4c9}&&=fWRS~|9ni;W77PoE@i>KpJhbg{9 zy@^O8V>HAySky!>tjDh846S={M5ZKli}}qj&?>Jd459pxwpD ze$-SIyW9S_+{h9;Zz0lur!L%=(Pys`(2x(@c18tUdJNpJA3n;>xIIMD*Z5 z{)q3ur|9bG77VUM8pOnM_J@)QOLUkCKgN&zd{*GHoH=k2aNqPklN;f1xWyn~CK5{- zJh!|{Z_mfQ-Sv@mcE`OESg-LP&KJ7zn-5*OVF)jfnDq! z3A~-YznXRAuwJ{_!d<(N;H)A~P|0A_uHXE@m5vT=Bf6oygx~0ak)R8FDhf+g`W#7B z-R;tX89P_DwhR2xJFGK{jDoyV7Gqt2D}Dp+FVqraD8mj!=M~lOAAW~ytfxPQ1!`aM z2G9AKpf@-#HsRSwZ&ic|T(5S;*J^#8VbFcQ%TqX7?l!4Iw0Jv3&#K(Ndx;~@^}g#n z2i~#>SO(WsW}lV>np68wkt2c873DI-EIzw&kO77ZSv~&8|E9$J>CE3y$F$EkVVk{u zzi$H^#g#0(R!m3FEUF-$Q_0D{IZZoUzMilQHZYPOi7yRx_RzKnFX3wP+?uOfzn#AK z`=92lTM{=y^-ERSi+SQ5hVrKm{Z=|==9nv&>%P6ecWobjb@xif81PdwsArk$0W--* z{)nw(4hc&NuN9<`^L4FNox&dxW^+N_T5O&kuNkffhAUo|Ub}@diM#h$cQe}};$1=H zunhH@Q7dt79pst=SVN`cAVkh4XW%4e;PfS(sL%m#-#=zGit|2eAWyM$A1@uW;J!H; z7|}?ci3>F2PxVJDPWo<7uw!Zg+4M4NH!7_!S8V8TC;b)}M^ZY5SvC2<@*$b4nDOq# zDVK^c02}Pyus%Rh)bW{Ni|#G^-Hr>4)6E4M(EU1~a~AKA8R~Wm2DlH`+Ixfkdrh4psW-y=op(@W;#})*(&7?wxi1g_|6`&F zUPM*;F-|*b2qt5sdj7FSdVZ%x#DR%?^P|DZ!gc=%P%zqG4Cwwg&MH&DQXF2)0sA+? zzIXJy=W{Y+9$q)zh%8y7veek1sj-TMa0H{HO94emxmh)^I&rWIkqvYL3DMEK2I&Kx#f}R&_jPhZ@!4wr?>4Tiv?j>Plo*-`hl{EGS#ZR@%0IR0CWXyX>08KGyK5uc3rzhLI{%-%zOWNOIDXvK$Y?4 z^zI(Ke=5y(pn3z-jQm=B)n!jiMvw%6c)*= zaF5<+e0Px0Isn(pmByzpSM|MiCcU&cVXXZfw%YnZEI~>26a}$$wq8bt{h&zv=$k(K z(Xv9~z7S4PqN8R>to#H1cFIiq`UK)=J){%dh(V(u3Vnp}`R63vA@;${Fgd9n;z5sThDYBFFF*wm zCJF+3i4ph8F4gF*u+V_UiQ1688V7=rg>G*aY|u+S`X>XV`+f|JqT8(ha4^Xc-O3Q* z@_^(^8>-dBA#h}v7ax|AH$JyAbqGZmM7PSl+F$@zq}eMB zzrAZ`covJOD=l*|H_%&nDpp$Nh&2K?b1D!M(Nsl8fy#0Boz z-ixo!FFRP4SQ16K0^_r=nhWXRn#ux!C&0~&%8ZoDrRONUJm!X<<~!_N37UWV>J?Q_ zL9bIat`&e%BVtXAZuV8kUoArAfShyPR1ue)incbOIZmU;>ipM1Z0HFD&z-_OIWbML zFd#%&0wqZPyl>oMpc-&Dh{yBoT1Z~$TmJPb`3%Cw%rHai)-yT0>pp1I#!)!<{RTN~ z+eOPnPs`5?M};hMDhHw&q8@&T!7B6v|He8*xs8O|FDm!Z<)YK#jAcTDMW;@f*2A~SYr`j`w5E*^GDZ!R^{;Z_3mg-ZsLosx0Osjn7xGV2V?zQ*49lln$BO$J8C5k*E(0s=ze!n zjD!aiK$o#~`70y4$a}N#{7b{z6p?7Wznjdz@=}y=+FHaOzyyp0gDEH5l#I+87Q??? zX4M~5-gZ=6YFyP;{j6-K1B=OF|BdN>0bcf$!}KS<)VRhFM1JQ#+e7@g!$tJiZU$a| zWig)^jALGIFjQ7F=%_yRHl>v-R%D ztDX578DibBbvBmXGroigCs<$fjWkg{{IV|{tBU_Run9}mmeUOG?CcoaVM8b`?c0&- zxWCi)3=mS<&!<}S%PA~6F*1PqPyK*Zz=w$iwZ#GzVUJgFMMsDp?&+)QY` zs{3MT`Bk#!>^@q4EGsWw6?NJs$RoOIGfCK2`})03m=+JyNdafh@%`k%fGX~ zAh`Ru@(;9?2EOR(VSB`eoB!g$y~EF2vno#yh9_lFXd;{;nd%t9LB&8Lk{e)9mG{5NJD^#psEEQm z_}IggCQmNs&qritGxeV8a>c+CbN!uLlC8EA4zucm04_E!T4xO?Q9U5xroOk7SG?+LQZ%0>3 zN=JlyXW<*m{M@^3RHgZNuapP}Y;}RA#`&ll7Pqm|L?C>NEi%ATjSWkecVTe;rr&?6 zx_Y~og!-tNt|AnIR@*FN67gdjzkrS=TCu{Oc3x7!{`fN=k?PV-^D&+-Rl>;Spo7?GzquE- zbSqSg4J2TOO!+~2#gm(lk5GAeNz8)!Yx#fydt8dwWcNPy+#xfL5OrZ+tTN#n-8=5c z_lP^AVsP)Ck^ya9Cy&lnRs0JWY_h0b^0-mziKT@`2}2a%KKte`bx|RFUZb2#Z+{m8 zm9mPzVw3PjdJqW60-GrU!>K`SveQFX)n8F!cGcqSqpoM+drmAOVf3{&Nq6C|=^f7jxW(4(kvf#nvLO zlW{a2BqLNg`YbKOl?fHCpv6R^BLyYJh2r5Gfj{{zsKx+%b)kGp|8g^{j#y4?ol_mF z5xQ{fJ4nJZKlA;Lz)biYrL=%~mPC*9#u%@YX`(sDU5e($Xu6dCWie5ntLfd}G3j2r znJDT;>_D$yF#q`NQW66H$@x1@qeDKVff??6B;7H7d44a=-*pU=VyB`!Y(ug(r7)_; zDj*hd&q@F{tFib?fFP%Ck-FH z>^cNDI=4^4F&f)}ihI?5+e6nR&g>O}BiZ6di#mu2Cd2MQSyEHjvN*bNF@-d^h9s zh!pw*F`|))HmwF-<@uj&d1Y)U8Uzdsv@N0z^a8c5u*vL%HM`{$xFeGOjUiqKOl6E{ zQx(L`YK%4Bc9!N-b;J1JcDkQ2V8nrTCZdOH*39mI{3cqLS0>O@1~qp>Lk~Xu%Xdg;>AjqBw)Y=A3#2Zg z`}bAy0>Q}o32?FopZ+sUMDjnHg-*<+^nt{GtIeJTT+&twDczKeRcl89_rbe>Jb%s`5XY2 zmgRqa9Vix6%g55I7>x%J{P(n-yl;+dUi_ZnwpzuJ-wMB69{RyE$hrhqn|Z(`Mih$y zMtH(iVU@pky=o_GAfX-AYHXl=<>nD#xEcdhcWhbWCeglwcSIT6m>X!jR)#-?!NjbK zMg+gyXD(pOyFmV@4E=}8#SYPG`G&eOIN4Hn)NbUSe{o)TvfxXevcG<Ia|&#fIetm`dK#`tm<@el%q%1)zG zBu%w7=t+4j223sEP4LpX7LT^vW-3C-jpVJL=lGSItYwW^5y(#w#9r2iukd&6O5BL% zLX>8v&0^)kjF5MrGcfQ=;@G1@xer{i-((mYJDj*OnC8+1!8>QSk;!k~Q7l%;h z%wR}}bUCDG{X@fiu{yc&%+Kn_y9ap%U48@KB>D)wT}xOJ9gai>$;l8#drcYyq~@k# z>Ujl4#Rq<=?WL5?q|oHiuUxA*#t#dB5vPn9U|!kT35Tr*kI4w+#BE+YQYKVsb9=?I z+ewj?AL*8??0Cn*sEskkf&@|?ESoqjkD*Xp$h8;@&!M!rDMv!fIeOQ4c$_x6peMgC z-2^8|qNM?TQtc$m0#AN;R`*y;#b6Zt37l`jwA?ZN4!w%=3|m952E#&;!VRpy7O@T$ z5@x^!8b>xFA(d0N^7H>Jm-FRR+}WOthOW7l?oq&Su|H@xv@kh2OII3>;J@Vl2ECOy z*#+zD?xxo`D!q7h53iVhBUOxE(0Q#Eo!rXSa9NBV#(O)f$>XMzvOm7mm4gLl6i3G9 zWt1^N7!JtSPT9g}LRZ}yp0jtY>bg>>28PP4J>oxlT>H7;->K8ANSNfa&+|{~9-~ zn_$kxIn%SoezD2jT9@=$=s;ah=>LF|LEhXJ3$fd8xE9&h9QYTA0d0H6pX7gsBY&zQ zON0;qCQ&hMAk!*^=S_;%dYE7LsOw3E$A94jaLGYt=>(i+L57P?mKv${eAESg?>h3qov&&TVl#Rs$!$G z50(jzUIDx>>$TUej}5Yb~u;N=MBI5 zKWa0+BBW>|2$+UElm>@v@rC!^@tw;L3PsH#t+(8MwocTbCqqfr7jul+GmpM8Z8{{* z9NCv;ZaQ18NjyeU^l6@>U2nQjyJAZkL);*1*V%RQ+2lCu^^M;(aOT13ZjvmmP*>F` zUflVQIMA1RCGLZwHn&>IE~t(^Z%2jA@uf1Jr=cF4i$k>j-Cn;ttAMBSN)2&5rlS1?$`EZb39e6W7Rl1WkRfqdd@hyMce4@q<-q zH$H1|R$UE{D#jGt3uTiZ&MB_S#y<33SDTlVt4l`Q#KECoE@Y)T5-o0_p}HF>s!VI% zCJmof1yRAb5}G}63DaZ9lN!y2RY$suVD zKqk%)c=|=_f!iORd~;Gs>_;G3Vvr6c_y|kPp3jLX<|1 z_|DYFD|a_R8hQvx)TH@dYRt*8u!t;?)W4luJ@fNCW%L6?G}TMKREd#6f1x;3ZvkBn ze^|J@E+u5SCg@^4Z$;PoKn>#V5hA#1ItvjJh_F~5UCl{0?( zNt<@gSvj{nfYD@MP3M&oB%CR!+bZ}(5`W2)RrEl(3&ki^c(KJ`fG#^+Dr%i_%Gqp3 zY?|*S@sJ#6C?H4KBWC6+(iBzX_wUj#;oB$7R?V@cwme#f!q0_i9?j?fri6nTekwG; z+;TTTN}5pjcvt35&=v#4F=VS+wcN^oRS_TD5K;Wczp7KH2jPE2h(3-egog>1D@s!Y^PRDcj4o@CT}as+VPuYmw5k<52fy36lnluo zy>Ca+aJlhbJr(=+(s$y^{KD5AuIn#ay<}{{Ze^->!;Bu1T*!SAfMCLlO?wL*yNJ8f zZ1r4YPYJijR^x4-?NbeoL#JG`Y5Uw~^{6Ph)FuuiOkQV+x9A>qD;xkM-+($Qzyjpv^G00 zFK>K$1n2h*z*{J7pIq6em;BIRZdwXh@A|=1Vf7_U{PGoe8kZ#dWt! znZgft;FPG_8v9o-qty&yO_v9!y0y0CJ$@!Lh~6N|K2)HMEmt23z20a-cE4>2CBbs- zE*#f7@YvfkNN4CUEK81DZKU65QqvmLra$M?MsjF zo6ru*7G8~JHr7}Z{I1t~l|`8kIJ;g{*duH+2g^2m*Eq*q-1{9uEqQ2ZyzXe*{qWuy z(j2HYh4m(%XUIFBN820gJ=Tf(V z_I#!sLTI?nN{N-pSlgV{?TXOL8aH_Ek1L9AoWHX=$1R@x=cq5Z|K=%fH$(MyxY&&xsdH*0G~9ZnWOB{J zm(yCdsjWZATw?v9GC^E{Lhmq8fKu)7;2;QUP<_Sd!?&?tJj*E0pMFq=D;DQ{Cs81B zy!OitAZW3$HIt^?^1#bDis05S>Qh@qdFJJ=6nglJf^Ub$O)VoFmwiXvoL>(CeUgJ3 zj10h@X>k`{_RkSM4vWHU&WPJ(BO8L|z2kYY`wUi z%G8BD$B#*PtHQ02ENV7oLQQ5`35hLx>L=+VE}cjKhJ}@u7T*Wm8qO-NVjK~tA+zDW zNxJ4t!?;nTBwJc_HDRVKMG39BUSVHqLux5_5*c_sS0UN&6uoA?vtK40WCK23VQ2(l zeb&nk54VS2)DlAN%NCLm&fAt*ckp_`tg%q64JaIChGr(Fr&knNhkeUbvYcY7-3 zmVW9dXK*<3IYc!YIG2Naalr(mR{*?Rg4oW4S)S-~l#N(DF8B<&NvR)AxVzAOm(XG58%4se}ZkzB?B|*kR)IB0M(=@H=J_ zB{F_^rx>HSf5Y4BTA1jMhdTCqS)qki!aQqhNVtlW^MLbqukPYJ9~1J}qA#`dtS)|J zGO#+|&BLczfS08BGsfkdvP^)CAz1fAV(^;rn`-=_OG#TYLgbtYdmO@cE5GjXs>~fw zz6fC|vX2@lb1S%lduMt`T_;7#$VC6kQHaF4n+9+5KS>YynT=$u-V23SD88_S*q+Pn zyfZH!$gy5mP5mUC^B-PB`EEtuB81KJrABq2CW1Rq)(38ffmJ%-lGK@ERmtLUq6mJS zM_a|oRNB&5)v;L9$4#u|S5{l)MA#JQA9 z$5F`BK;E>mVq$*8=sX z*E|*3@Go2EyFP;h;)gW)hY8m9(M7D*vtO^?|6}E(1aGZ%oR-uip1;?M@!TjPas*aP*mUaLP3yv<=9g`PoWdxw%T~IgjPmat>uCbE79?Ws;Nwl4#F|rD@Qk_ zn4*&QmWQ2Cz1!*yM$;WHXg-JPpOnqI!j6OnWLSZRfYTM50a$LJ$r01e3wPF@h) zj&ac!^k97A+qfs@l4Dp$#)VgxVrpLN*)lWA?JPeM1Y*@Powu6U7Mt8t?DxlWI=x}; z`VmcfP6CtaMsZr=2Gz<>^tgeF7>dPDi8YRBv!QR2G;U93rMeqms;D$aPLgvF_Ac-x z_|0;(_~Tt(4pF)ux`cg8Mi{393EDyFaP!q=Mr?1{g)0X(JTn{TuE|MLJ_x8mP+zh? z))70a>#f_`8K*UBF0@cz*{f2Zq;KFPjt^h=nscPFLO3}a%|CbH~ z((Z$EfxZ_jDUTe>Mr($!Lcxw++kaNKT0DJ~B3Oy*@+p)_mz<)r6aZ>zd1Nx@UHXyz z!qhBW8MpBcTk1X`pwWL=+0vj)$am;PeX#CDHSTLAPnqqnIJil)j`Q8yaj9QgoB4h; zv(?jcuiw+}&i|Hujig83Zek~I(YmiOzB+AiV@OV&E!`r;(aOuGct{Mmg=0So%n{IlS@-Q8fyqkX++xQ8aQ2OBcH z2?KTyNbCIpS3v&cdgOrITqwvS>`2v&7($!jMd-<|N18$P#v}PDvfES|>Az|rWmWp2 zG!%>4ew##3`3Z7xjvko4^;&nPxIZ;KQk|t<6cL($eMeGEctt~+dR`q$A5TgetZt9$ z>q=0`q~TEHy=v=ff;oLEfO2flU#^Vummh-gEHr?`^!yjr{pnK@H`3QwlTAd$G(Vi8 zZ~cMfJr-VCp?xR&(~$Y{v(g)e%=&Gz<$u=>VHHR5jtYudXl@NzPAumc z3d>yx=I(uBU`a8=HMefFAou#^;GF>7aoBZgx)1~0wfT|fKCtbUBskD~j&lVo+Xte*S5w(RdpJci%KCES>`5k? z$y2FOz2Vp|+OxsCgLB-RyAfLdvpyBI7U93!nh#A4kPrT-8FOT%u-`0$>Tli$QnY9- z1?ENx%Z-j54KlaR-C|fWDMn99&_NHz2_#U>R3=H{`P9}yVXL}DsX6AiH+LDfRQ}U9 zLEn0qCF~lbXS61L%(yb85qZOLfLpU21$wYk*9u2w_&_<*Hat35T zK-nryXc^vmb*?s_kEA*9--Wf)p~AW$x(H2tE|-yO^#63`9aYO-iz8*XF2C>-am9ph zF9d#MTnSUt=xMzf+FW`U8!HtjFSw_$)yB~Cc`OGm603Y7!en`C*CuY(dGqLSj;63i?xb?ZJ`rre z`Cn&r3O0rJyy9dazw0G!WU2zm5uxF)d5v$t2UnO z0LyjE{dDtYFVmN~HRC_tCDjp)7KY_h=XAL)q<)VPYZD}l&EEj&tE5JFX!cS}cJWq$ z^h~$xWbW?4^*|&Zj08JdPJ1^^aqMUYgqbM=JD<7n+*3!_kDa1V;`S2h_FM+9EErlr3* z6wn`BF-1XJZ?YApx$(uJmESLikcN|okDZUZx_M9X#aUnaJX)HAxRjNlB07o*KTWCb zx8y~cIVF9X`MpAfv*0Y!k9{NG{l6wTE|l*Od1py@dNCTH|V7{^@Twv5pRCxObPYm(u?nYLnW#>(Q$F-wwB_uM%^_oWZ z)fQq(Th5V`&jSsyz>ekKtN~?6@Z0ecD!c~qXw_&L1h)L9X6G&Ay)hfiEpm>j)gO=j8|Qaq{4fp?8*hJ44!X6FbYSKF&wyEEv6L0kzb<$E zbb4p8H{FS~zVWrGJ)g*ryikRrHZ9(~#^pDSY;jEEjT4i6!;^486I_&x0J3|i)g?&q zx=d-&o{YHk%7WyjKLYp8g14XQck#y< z)v?4ToaYIWNdBrSb`mw+yf4(5Yud@<@%oeb*TG&vxa)Y;ZkSS=2XV=8NDCx9w*f>w zmVhRLMm`tNZ4{ox7@NRvMs8}3J0$zw==X77)TAc@35@e<1+vxWYxcGD!VpVxcnIIv zM1V!8qc%tbme*ElLm*pm#t4=29DKj~T}sv#v!jVuAkoQnr(Go=B&OVS>b-+yyO)fog~)H;mjcq3dH|on7tOiu(5i13AJI+llHx5OKb7Nt9$W-!_=7A)?>)(FbXtsJxqG+c@}EhcsChl zuV{2ljl}BS`6>4h{{ueghwrw%;vc#HVd~cx&MQp5Fr-1Es?dXn8A!)x2kYT8GNzXj z!tD%4#)o~AavpFKS4Yxa08FFFyfT3lgm(A({}55*NY&rn0U2Ngdi3_PjMTb07Z&~0 z(R4i>nQs4ciB~ILSJY@|yz$ANxN|!9xmKYgLnW30vX(3-oY8qz^u2Ox{q;Fh>>#P> ze996D{f}(Gz=MxeDUk$*o7Vc3LX5E+Mv_$FpU`LE@QM`4#p@Q`%OCCk7l|mey>93= zF}hE}WOe#uHfeau&fxNHV)0NgjauqERT;ns$^-v0-DqVnKe-ezDkenuCQ3HNe+%cK zafj|eIFw9+oL+sU^8YW%S6??}+NWJd1FFa+cryo&B{HwFy0I6|%_8YUpNw_t9r??J9kW`T zwo$mIf0=PpMQ3XZ&BOn6Kj_aTaFbc5zT=#f)jiy$?@N6FTzEo+)?NDR-w(3!z>*8M z+(wkRWv9Po)yErBSaxBxyE)uzE?5=s^RmhwL&SU2SgJn>Ego8L`?seG9M#Jrs5QJp zl4TBW)(C~_CV*7SQ?Z~|@9+_zuOj#uAtJUJ=edx8!|1Q!gm}~sW$CXP)0;@Gy>To; z`*LzRa6XRwALDv!_6wbNU{G+HGm{ZDnDC)GuJD-()>Hk$@psfN?)tANY?&3P$LHp5 z>HTDEDL?wL<;K=Cx*9erMBreAk*^Fw2=>uCJ?@S<~}iIDoN-}FzY8%-oY;4 zb=Av1P0q_QCY4yLtYZg#0}Xmr1%UHYk3+;gITjf=)fc!)HW_WDxzTj9Qb~sfx%&L8 zkOLjvx#Rbzq8f){s8?PEZ8*H5;kia_bD`yu=4$e{sqjz%6Ju;hkqa@M%B|VbGsVi1 z)!m-MiolM_KBKcH;d6e&mgVo0|JQ}-)~mkBy$p? zx_-McpMvp1J`Vw zeZMqsf?)cvT@{?J8ztl*Z0ZpWMTb(;%E6s>sL%E2$9g6VN>d$iAIFFt&!2?(sB=l5 zmDpq+I~CReho)r4TIRU><|08$FKWw7O_oTw7wKcE)VGQ0WjEvG;RI&ycFcNOg=a-r zN3oJlukVuE3Ft`mkko7T7#Q7`NDPheEqN$~?Y$x1F#0@ex0e%Hl9{%n9x8zyOx?8L zA>rfy_0ZcY?-@IQ1*fx+;Yb~mq0Pq6B=RRn3i`L9!Y*v)En=sSaaSE`@>En<(1<|u zDAJU>9}zUjV+w0sHow}#yZPHB|8dUHGU6k;@gzibwB^P2HHvn@aG3@S z!fViizvg17*&D#axB<%NRMih64X{x%dEUv>vMBi@Mstc6MswMcx%#90*iofV2e0J` zyh!Vpq+E=VR8}OdxT{`4vPP;lM}@r^3@6uje!hdl+5+ZCAq#C)dasgGX%#Nu3H>Ow zETB?HWy`1tjSP|2$9u;8YyyWm`3c4l>5^u@SSJe!sFN9`M z%<8PHtvsNU1BDB=evJ!&lONhHI5&w6S1LM915afB@hY!EvCHM@+Y7x;$(<*qyN+{^ zk4CgZtR3vdBk5u)mk$Gp1vD_72kvi*`hye;9OkV$HDJ`p=}bes1Xi}urAG+gHD8Ur z`KrsGCcXP~6Iv!p@#ID4e~^E%{`80ndDbQGi6ANScM;PXAI0R~ih%XKEZVDkcm!$4 zUIqFCn28u0Ee{<_Y-=(?GqLl<(XX^jilojv8rCz)*aGhrv15xQuc6VJs;eo4F+nuH zF?nu*&O2M3VhjLN98)tS^jWrp*r@$Y{H4_e}W8 zI|P$b5Dg>GRZ<<}?Gh`qVCDqn0KbB3)*Gqa4sTV@IaI8wrWN(r{D&cq0nHCO4k?&L z?z^|MIqV*__oz;c??=MP`)DYpNRZy}4+Ze%C8Y9e<>6^8WX*hCV{ZxoxB#gKzEE+voRs^3U03DmGK#t@rC5m0n#Em`2!?*+kLQe?za3IG54BIfCT zz+k-;kkI{I^I5b`x{Em;HcOs5d#XlaV%tr`n!R$h{9=M1K3JKs_?-j!WV~*d1U8m} z8WQ?bv-b9=f~AiHnyi=o%%n)P9SLiyC)lm|V(Yr5t}hgHf0`}Gk(C&-dRh===sr{; z)==sJS1*OZRVRQ2?_%0$bE%;R!H;K)`7EGrJym_pD}*+=qGKma_6#a>n><6tB8xEo zXl-^O^4mWxe`-Y%Yso_bjI&qnEmWAC|GQN5XEGwshBP#r>puVjN%kFlpE_G06kI6M z*~q%q{NdyIE_YYEe24$UbFP9+%c0lu@>+zFqHv)jjavO?vHo8w_LR*s9)*Rc7gj+Q z;N2LKs!7bhjK61}ZuuhQPbHW_;*alxt;MgjmuRaLu!@2?e6AjQi4&3Op{z(EE4CPO zEs~DcLxI+Z6l4OiRK53qfLd#+9m5Z@9~~$L(y_f!z7H6j;uQ6Iwy|LO3vd9A7j8Av zeZC;mga+T?;&g#d#OyA##iQ(Z|NTqy1+Iv*73@=YAwGtnW%Eh4!0mZAT@VxY^__W` zd6e(nNbDtO@|jOr?!fyI92#6uUS}~ndoMel>GdB`DASxHRXs9HDW*P&5@_@L)Cf>rcLZMHaaT7tA36mwg*6CzXr8@i7jyb21w;kMr1fc*e^=_ha+DyZA} zeRRgl--b#sc51b;w;k<&4CU8~pTw>7O0*5N`%~+-LB9L)z$+g+Rw|yp72(csGFsNAYX7BM zSuz$3d|hn|Esf{lr<`JL%ya7=diOFG?iO)&04;OWadQYF_v4lnEUc84M87!afv&2!pq#n21}+d$%uX zuLjA!$Yv3tT5yNf9H0}le&M$=R4Mrpdw%VeP>?5#F34D(M1dO)d-E(Z6cF;>$UMDIIOle`KVBp2+TazL zeBDUYwwjpyQxB6Ddc*nHe*{=oK1go;Pja!ZC1Z@RXGP^asCY&e39adr`YM9ffM^Hn z0RMJdgM>W$y3%UAS;q3uZA^BXrO1T9Q0|;WOMk#Gy%Vzx7p9vt>R}B2f{Y`fCGi5& zU^YqmDvo0qYT$2YNXbJZ9e4ib;?j)A?CSj+Ia3bH4SD^)A{%NPO(1o&&1v0Pay_D3 zdv$3cBI4X&1nmRpqbeyRRQOz$j5&!E zttx98p)Mw5 z*j6&amDpvqRlsZ)O$-U8YCYJ2ma!aknAA-}Q~9crlGL=73_fqFl27~?^M|NchnrsA zJ*`4!q<5fG4Wr!XaWx9rf$f4ZeY0K{l*sm1iRJZr~b6X=Q9D37gSB0?h{Gwra*9lXZH2A$k0nqS$AK&fb*zJ2&6S@vh zLwp;>D}QoqmHR;s_H$hC(SKS`yBt>Q&mLSK0Er7tX);d2M{-Sbq4d-&P%nOPt-f7>`EmhGPHIbbXt^qh%{uh%vqr$(kn_BLry;VWy^d zgrM(P?LQ zU~ouZ1HI(X0i<*8-$PCe-u{MuP~ASehbHAvG! z;n8;5V_zUx5p#iN>Xrn;k1F-_rs$VX=axYjD8jAwqeGR`FwO}4$;rL*4U3P~=jQ+L zi`lH?9CY@nh432k0&tb~e*)=2HrMe>-WYqSE+Gyf#rd&KOCRwpgzA5aHg<*?CbHJ+ zmSzV~s;eF}+%mB9o#DCasBXMF@YuY*Lp5RKM>6V7Un+iu@9jxwOu_Jo_p&{OHOu*| zAGRU(+A-{qPi0z(RphB zXYnoDMiQSl6odq)rY+)v@ruMflV>RmrAV6t<}by>Y^d-6Kc4#B1G-ypYk<64@r6fR z;ER)x2>ks(b$b<2&21yk!d|s~@wq>oa*;sPmS=S#iPysAH7ficQXH2am=i*M^hW_1 zaMlTJq1OK|Rx@bC4eo&U&IW%EmDW9EehJ?#-io&WIrWwL@>*o?iTIUy?sldHUlU*$ z5h()-^N*#?o+@aO9z<+sKncIl{Sktg`OI^7M`BgvkbD9^HBP$d1Z8xZ?@pbmKUW$H zJtTeg%?lS^1KPb;>KTAJNL+|a+Dm+y1F*{ej4YjI(i-O&>78Q_75%KA+6Tr!;RREB z$&8c=we@dv60vAq<4}sdf_~_i`53#t9#k@a30~sTD2=jIb>qj~UlCR$b z-@O41LsprzV7JB}C84KD@w&kCM}A%#AIZp~ASjU^w}XX?a$ebEvA*>lZ1oq^etVW7 z6z>hYtpbYgB<&-qQCSB>E}Eqf9L$jNY3SS4R=R^?umQ2cmzsKe#FjP|=rPW=g`7vH z-JD5BnZV-*e3MI94chA5sj&Q&oB>xN?!3Ndts8vv583~a+_wZqa^pvt+N*5xEP}uF!dT0`NV|EDNO9o z1?Dlm`8+j)E5^+RLZBDH`PF44wGbie{yY2wc5a7o=|bAQlWx;jG6~<(PDh@VV7X_c z_O_p7%Hu)L9IXzqF?O>!x&}a$RdXxJY!s=NcmrWpL%V(uMY-46)h4=_p|E( zR59ZP`Pi;A-TCpW{Q_hQ?0bUQ8N^cE?w9yT_+E(DzKuf|UU2j4Pn1$vkd2bnY&=0N zSMgKO^9fdptr>_-x5IzgBp`x<_MA_zN*K&s)-xsq$Sxq z!9dNwax_eg+~hw3?#GHE8=%-q|Gl-OL_|{)oeqn7&`3dct`0b@`E#vx~74G^wq1|3P%^-kM* z+fO8H{3%F{MDCOR;O1e4{K9u#V$mpYxNMRf^r$EC@@=e~jrkcV zpDifK zRr+GRn>LmhjgM$)B9%$OLxvQMJlCv{OVvN^s zi0XF!c6&?bg{C&7fMgsWAESJ?bVO#d`GH5Ut5M9n+%53`X!`DWD*yle`y88WBC?KE zws%%G9U+A5EhM9i$lg@PUWrslh3t{N$tEOwhEVq2$M1Ff{J!r$dp{oTbHDD_xSrSZ zx~^A7cG>Rm;Jn2v3V~kVLMR`f1C@!SUYW_yQz=QHw7oicr#50zaR%>KX$LPbFaG5* zBN=)woCS8{IoGQgB>l^|50n2c=P+8xl+2QZwF0d~Y0YOfI1m@H_P9w?myZmp-#-a_ z`_J+BL8XG861tf=0u10>HDxnPp9dZ-AKOPB{8zPdj7AunI?fzCP*!;tFv`AW0Ix&e zfkw0aM<0@(4@?hWnV`o-#APStNXY1WNyNmUjZ@15T|n7bEINP6?QGWdU3P}ioD+AN9X zsJT@(e8<&}qyi1iH(3#8C`}!4c_G)=!KvMARJluaJ+XaW4d{q9a~7zo0?kB;j+g7w zz`Nv&hP5eA)ngE4O;^aIYwe@uMYJ!q@VUjy7Lo0OltdKQbjc0CI_(bzFG0}n8q_$4 zCnzzTDadD8WMKfIcEZ-icO}3P+(zbgCFtO3(ZybGnPU-U^M(H44HU9L6nqubwX|J~ z{Lif0rCKB*m_5E?79kDOCK>%>f~4o({q}&!*9WpL!}6z=`O7S$TWHPg#Y9bkkd7A` z*1E1aNWxPd5ZSZ9p^3(4_1nE4bui2`%H#e5c}Sq=Lf?)f6T&h^HE5Nd& z%py1vxrv*a;mdR2{#q=@>S_0)1#grAmaXmscnRgSg^4M;n(mg&{gbDAQo7szoq33G zjFl_}S3M5svzk1MN2F^ea70Bjff;;DBo065M@)>aF3ZhDJQrnmx!sSC`a^0{{Wn%+=)ECL0v?`Zy?jI zpW_MfC7AXN1%OgHruA(&vELbMrs9C~@-h{3U!VrseXE6^h0)5Q{@Evo(?=WTgA`OY z&gzDwz_)YjR`Hv~$CAu8bn6}D?6!|)@ZH}d4h;L{#E&V!Y1+qN22l>OIg=P1jGj7! zt`8w#9eXSa3pkgb$ zO+v|u<*egxv*loPI6>3xd1qqrKiPvbc1eAPX{iG52EnUt!yhhxIStNTS$!3YFQr6j zb;dNFFDMkTzS5iktY($dddss8q~F9P=AW2af+)<=a3B*gX93+<4oNnEz`)-Y?O!^w zZ)}IhJsN7-S>|_kJ1hiDgh*wrZ^T2Gd5tktqFpd=Xo znAQgF1Af=TwvD!Y6QbNxG7bV}8~{x+t*H@VoBFxFrvwg-SAREtMEU9^IitWQm{3!8 zkA1sN9h_lFBp-^i^f)H!$L(7eQLad)g8&8dV}cUKpFosi+@u6{rW_}Ooo^PI3(R>g z|JJrlDeaxH`SJ^d=wi3irluR*9w

      VHSyUWWmX&%~SwBtu~3a$dx9dv$P5HygeNMxEx2(gYbWUbCPNP+D?xt~!^Prbw$zk9K1$ z?ZOxw+L_eGxX1y(?aOLcH#Xp>=HqW+90-p$w}U9a_qiHr1APP#BdC+z`?XfiZFQwN zGWmTxjnObdJD@wrvkrwA0V|pMyc|LfDrnB<&KN%>0R@2jl-OeeW45f4Jj`wlVq-(7 z^5B?6 z%vqWCf&xNgEVB&?^W`0WdcHsL$fZ^Reb?)r5O@@UMYBO^Sh5|b6k(N17byaY#byGv zPX9cUg4ex2EE(eH1^Y&R3OtH;yjzMYuH zS5k5$??pM73${~TKG-hHcVkJQ;Dc-XK_Zj*SRGZ#)9czY)7SNjZ}%zT3Q0SJ%S{|b zB}!6id~2T<+8fTjc+-1dP^{xk7JswfJ5@B$vX~GKqx$ub9REELT>PMA2Ue$y851Mx zL%2AM-#^n~au3rx+y?WSsO)y&SMKIC-dw28g&@dAPL7$3O?v7GcG@@$2T>z9CO0Na zKK-Xv-$EJ~=S;L@q5t1K1+Oo85l z1|)R-yMY0L*M#68ZX_h+u!9s2rCB>8Auv_?h>G2Jnmmx$NyEJV6`qsy)2}$b!RJqG zX!q*%oE(Rc{0DI+Az-QU;4OOfIhyZ&ekl}JUd(^Bha8L9SVlCBzt4`$(msAH!^E`8 zwst&vi6L7Bx{~Vk01x_$coPv~;-~$QV4ngIL_oT9qp8vdEpl@k7h>HTajM?orXsYh!&j31 zY1MeNSO8{G0O>ABY1*0=h%R{BgP5D`{=+#~pNH}H$0J+l#GCa3&!iz{m{2_R7kDt1F4xkN4SiYaw`&jFj7|$=G}~eW zPiaB3QrW1mQy)#D!$kZPHn- zN?up*rQ++nlZsKeNW>URCg0g_p-^PU=l|uEcs@MzUAaOmu$|}whHG-{&0P2S`E0uA z;~%_;^T~|d1X0s@6D{zxn_}#fC~MVcfeu$`6EZ9Xv(asc7b)f`X4Dn`Qo1a}Q+X~} zAMyjxXLK4NFS0_BnZGgp0}LU5S`Xv-lm7nD{+2##6cV#RoSjzl>DUe4`)uf?IK5U! z3N-hIc{g9qk3wr?C@C=@*ZF!|3eT=Q$##)WpKWy$-MrS>|I<6-+Nz3 zZGZcK@*-7OiIsSPJ?Ljz>yo+Sm@v|Ea$Yq0bs%9mcbPlb44ClpoOc z4V_m&B_fwQ$+>|okS4Ob0!)i5Hhii5lDt@TH1p4_eq!_#(?&qRU(PSbaId{Lf0G`# zEo@s2nn>Fjmjs}@&fZlJOHXv>u%?hF5@NLCgYv5Kd@aQZpxf` z7bx=P5N@Jm^(xW?$?j~mY90(bG$vx|Nh1hEw=Oq%X{igVL?{SB zf@lF@oB6fIvYRfW2K+41&t(GoyMkP*na9iONGeKgwdu6VbPU@RQ++YNo4Vfbm%Hiz z$qnr#!@AIvo_%|OMM*&Oo(y+LZ|zuF~B`ObmNe&*9V#eZpxqUJ5`yZUwU6|@IR%)Y}^++Y{iU!v3B=b+RDiEy!il(ijNhw zu0vi1pus~A6j=gW_!*L)n?wPyg$wOW)loeG!RU<-MyHMQ`xiP;?z4-5@jFsLBm$!( zkr#B@$5z89|B@K*#PuM4-KpS|2pI-$lV6!_x1e6LDm!JZb0Y;!B-w@&bT1*RAB;v6 zV^%FVlp6$sr<;Jygi)NPDJR#W4@`gV7sxnVuWAg3QWPDjOHPXtzDK~*Y(keyK(rVobB?hg3CU1*{ ztXXbU>b$VZ!GXw=N!Qt!d-V-1zY3qn$FnLli|2v&OAr--=A86`>4Y#8n3`*u3&Y3C z>bB~dB~p_IzB1%zcH@$wfN8D)RuKc z+d8n|N+$sEF4kzqqTt+_d`I$dj8Rb~j`Yc8g-SFywlPuIrMVLuL664Nw)UEz>;kpH~uR9OI*u@f8Y?)xq!-?L$JZFJU3G2r_MzLM8kLZGb5?gb8hfu z6(NIoUGS(?bWDH>6*iRw<-?VXo?OXoH|pwnH6eD zEE05r(S14ve z>*)C;rPXAbTwQx3qi~iW=#Xii0p^T`eBSrqln$7zo)>wCk_d>lYQQu=lXwZR|GXD_ z+I|0rTdZ97yYN>?^OtiQ8%{mUZ}*Sf7~KRmV{TqMi_yb|PxveYmvp`qFfq*;>`w#Z z6z1CZ6MzA4;A%K(S#I zM|a-<>xFm58WW{Bn8k zc_~GRuW;hdI0>NUQTKN`FI8gIde1u*!ei2|hXx*JELagaHRVLc|wMGZiEra#h1)uE?h=p;~83jeyX5+eDKGz-_w?WrXOh#01 zL~F{%+bQZ3#jw}wK`!V>R%f@f*_HOd{!_JSdKRqO!u`3B6lmEmmw9vT8Bp28p-kCO zM8q|%J-a;qN=LTVKV;WzeoVf^5L-P_b8-H%(>5Lw`P;)WfkUCR|5!g6gGpnyGzAii z(ZKUjnhm)hbp0>XE9_<-%lP=+8LGRNxL}_YXbX-2tAZOSdBQtXB@uww(eX8%3h6sg zlYht7P&4Q6(`HH0aR^!Bfmwov+ADFn4}Sq}p=fj#e{2)Af}s38X@)}iqylXiJ@oCx zqKWWbR<-Xm@$K}SHRn5OJ%5fZ_s?u#i{R=U@Y}DBV2CZzZ3fF-a)qSfSzGUMo0z2^ z|9$3Zsx@~!uFK)2?)gP^f&_XO8%GFtwC>ujX3x`FheBc^3v&rkhx)ulo6fz%uTI~=g)WM~os3l%q|&@+QnvVO%R-*ZGcJ73 zbdQo!+q$92EUEhr@{Co^z9?rh3IG#(KgWg9IvHbugV*;Mr@iKs^U^kfl0OUX8QGmg zMME6rRXnNQ3Yr&vTvoR*-G{;NtYib=d=~eV3<2bTujhte{(oA5*|`4VXpdJ<)P%?h z*-)7!qHcs;$;7jdJ9`ml^WOb81$&C_%&iM=k6v4lxp3;dfBL6lR{wh+fR>zAdLTH$ z173GEQSpZQJ{x%R0l~E-5$`66H^>Gn1jXCSADi}4P}2G%Fzs*V?)`D*Bq|D_GyG;Y+VZY_1pZ-pr7GMUTZl-YeqEpurC); zEyRK1v1^%IdgnaiQ-9#1HC2$gHLri&u41~|qO{Ibmc<)S#yOsdI{EpV(XW>Lp!HEU zLM>101APKN0zIS&1y#AMJj$$*t})SGX7#Mhh+utcfdEIEk{a3l5j6Uhq2F@k`hdyT zGqrbfdc|Ik8#u?BvX%i?U*@y#&~>%{M8hqV#+Qi+v7(Y%h(Bi_lqI1J1V}ZKJ)_kV zKFmjhR9s-qg=Tp?|NpSTPV$GG%BOk_rO7y27n+?t3rf|WB23!lEXXG1n0c0Y8^BDa zD2S$8CY=7;F9@~wd3y&Ni^;JuX{<5?FKf61L3c&5QhpqnRsPVsPDkH2f^zE>(rle3 zi{C>gfL-)C(b`M+^j2Dx#1qP#AJzT0ZvvxP`(wVwt+g_`>V*Q~yEI-KB^1aEpG|9U zwbW4E{o7Rcf1%OJZ;%579vj!!iu3|BL-V06c^y$!c%JgyM`IDq9vl~S}7V0#QW z$zB8;4k|N`H`?~4x`?>m>xOY^)UkJ)h6@uZQ) zC$YtM9ukD&G~S6Z>1h+g+nRD?kO*X)H|$W4Q!ajYtUS{v2qqXJ9x63>+?PJ~i4rD` z@MmywR~8A>@&5ahnWmm6W zPIHL19H{^q68@+5YRCd7h&N^)SCOIC77M5@Eh{~OmRtQ@Hx+WShbEKlx3nKO%Q!C|LzeW%^8AB z5gdmbVq)wJyjfM+S3bur~UMomV*aeF`J@oUzA@^ivSI< zy{?pt2|)BIFaHj^zdNE^Ij;)m0OIc>x#rRyl(x8+KZ#;5Km677rJ`_=O+ z=hBfs;RBj@ePuUM0~BPKh1`a9c;};T@7D;bp9>+GVA^)jQ)ph`HPDma3I!K@`FGUd z!yL995`W$gMO;7p&+~rx-@Li1+qil+Jpyl_GT%xr^&A8TPlvx0v?ny*ay6f38az+x z=S{ZwPQOrWRqgn<{NMjxbER5W;%?tM13))@?{DJ=k#A04s0sPHM%m(}TYtBtAhP(; zQ4d#tnEOBGnS-!49WiD}>%)0^Ek&)5oQG~UOS6Vy?3QpjD85h9#?`TCeq3(MV7P02 zrU9oqsXzG>Y|JhJ`>)LT128b80x~gtrIMNlMVE-GFJ+k#nz|dv&e6rU_1$}ah23q^ zT}|iA`w8ryP90Fa2X$6BTy#uO*FDf{OtkSwAmHwWEs`LJGJf;B9XTE;qOA}~6AA9# zcsl)I+5KrtR;Pru`WgUK$QoGQEFB3NJl%TdAixA5j$5Hfd4uXYzM2AzFtTl<)=>c$ zwKJW*x4+M%`J^lSEha}a_#+OXNnSb2Cd;*e^4cfe9=LFYoB6hwkRYSnxBx$X)4_wm zO`5|(?I2o|;*y!g6GjdPy zVHfk-Q%0c%jWWV!9)K{?!ZEB-`)8-uLD?=seG_`0`mIPmNnp9Faa`2(O53;dvg4u! zR|`Wh4eQz**|k;*bY3! zyAChu6%IbDcovGEwFQUR8J|DT#4m6tr;9S-ibceqKFGxr#0J^zkm^0mK<3oe=9rHS z4Q{vl{do74;4`48@~8ApSkZ;z;A<`3rVh3vB)Ael3gC_HH>inDy5ewH%ilE(;&Y$r zp33-_AmL=+Th<|?u!{u*guRvZ^^H7(iz=qy{{>%&*hGK6a`{ju35X-EKh>L^P1oJl zHVxV6d%s%xH1U@2ss7sE6~iJf@lsHc^(RBQactt%0nvNPDkCKzC16AaMD7XMg*cv60Ha0bH34Yr&+?lYs}KvD zeG4(N+}z0dAI9rxJ^|4&zS)dEtA55 zY(FqZr_*DnMZ(dkZ*k)_HNUd}1r+7rulS|JbO0;@nL--crvo$DIF4~URl(-{4`0B} zkt99x(_cg|ZZWae^z_GPzXRRf!S!dK=vXyRKV0WR!2q!>^%gXipOH+or3OcfRADeU z!$Q6XjpFSc)b*W!$9aK&;%7;Ic?y(!-Mqpw^#6fnTzA`2f

      `+$sb0+z4k5aI^OUEoD7e_6U1 zdS8FBgBVoQ%IWm{A${1JzUUZ1-5_9^LP4oKnb<0_V?b82~#_LQk&QNiiU{j0%0agMB{1))S~}{sZiIUF|TP7 zai(5&SI3lSXvN+Fw=6%0dTL^WT3aF<3Qid%i zT8-%!%_cMnD5eHz>oI0)l>U~c9PD}oE$+3QHsZ|{vP!aNun21ucJW?-9BLf5xaOZMD-|(EoQ{8I*laMe8BG!jt?s zn|()_G6k>U$u$#kLNtGShrh>>&Cqqxk5v?4FZ5P;Ow9Vkf9`SY!RWtH+%{jt8i^4R z@$5G+pTVR$wXSRHbr|=h*S8k8qVNq_A$--w3yz zbnOs9uP}!W1H027h65M)!dMyhW_c%h4hx%8+XV{4Klpin0J!+c+)c>cq}+pAx`Cm% zHYBW_(X-(>H_AZsvA|;k&n5FC>dh&0lsEAg==s>n{)73@RY8Q^KXN ze}8a#8<;M%A1>d40?fbuvd3&z=1-(9tXEmuI6XcO{ho3yQ{-&(N;j+fmC;*x2YRXV7MAH``-{%Jjc>oAYp1Aq| zq_kZvPyh$da0RU1L_=%xd*qlEqm6)4V>$J%RVwrxYPN9iaCZDCpY{S}?gE}Dh#W93 zugG?`oC{PL@I-p)-m!a6)yr=W3Qyx-7KpG@hjL@BsjS?&6kiuUE8$f6*^{ZlpR{)8 z!K?%ZSOxJcqdzRZSdA@zK@>&&`A2>rrC5a>2<$w2hU85(k~QX^6auELzWMQGJ<*;c z^U^xgYq(2TaE1apStxQ_x@vId-k*hao@C6a0br9C+{l4=r9Y9Hwicl! zTB>-8-kUXHN`^T*-F&5L1fhvzd4d1_#H#7mE7Uy9k>@;*^o2?b^lM2%`j=k?yVO06 zP@a;BxYs}Te)@u>;4j`7D4~JX@nu#wY`8x%2N_>sI6u1OP~9C~kgLsB(`iWeF|!Pw zMVO3#!n5-u`7foO8nOoEJ3ZioTG{JnL>=hyu($xF`4a zXSYkEELg;2DND0}n6vHJRAkWg-lZh8)fk{oG)Mq>DY6ZskU^X+D7Tcjp!uI}HR zo62QxoSZ+rS;)dPZ4aysf%pWd^lO`c2wW`iWZiAu)ndw-k`*6RgHA_*encIYic;e` z4y)Ra^XekRPPzh;+{))(+{*ZS5kZZoLwIzi12N&MaX`@y7njTmqix%X+;7j`HJzHE zajEb%Tr@1oM{>>hqqJ_|>gD-#Is!MTr`Z zzHijCG<_FUj0KJ%Mrb@G3z&cTt18R7<*x0Z;XLBY^XIkmxxdwD;VcbNQOuyR_PERk zP-iOp>IMg<=2wSXK$MiC6`zb?5nyf|k-V86BM_77u%jehDWMOOk0;NHPYNtB6bJS1-(2Zq zIw)%ACk1UP6n9uhfcW$`J=eOS)x^8z)IGXZq+KG4V;mQ%)Oe78>7xGL5rAH9@BA8LK!jV}D<_F)?WH$SY`Ul(j0D>D; z0OEG=*1=$5(KT{uVnMBlQj|6C5cF@@H4CZ}u3>TJJd9$#bB7SclMd?8!-rIn{4hV1 znXPdz`uJm|@#(Fkicv&>C*em|J{ewp(5(yfOJX6tvPQ-u&NfNV`~4SNl@U!xc~9*< z!IqK_#MfapJfa%(g$j-xQh6^<#&=^e?LrmRCq>`(Q>c z@$p&3g#Sg7MY<~E9e71$wq66(y?);MU&fqshcGODP=}}#XNvP_I3~vVNz$gw(Hxfb zcWfycNq)Yp?)&)-?a3BF)hO}BQ5AA(bz<;(!2VWH<-FV7*bJfuK=De+#*+T&^WV)E z8AVaHQzyPDt2EZv6?}JIaj&WY=Z9oM`^{$K0t2kT4T0x}n_nG5*7}%v4dD2{UV}!? zyS1_PP%QloCA^tgGoE^8%~|3puus8}serL}hgCLqn}A6`Ap3GDxCSZrvr~*&F$HA^P~jzA=A3@C&HY)2XyWkpTSdJS6)4VvxNO%WNy%=X)_dXtH_E##Mc2v6~FTk6s1dpyC4k z)0A>fI-H|>2^`V4Ux1!^=Hn%35g3K1iWKBNFVsV~U&@+cgxe|h3Z`+SW<&EumDU83 zM-ipM8sLp1PRpv7E#R0c;6uQq=6AJ+jhP8FQpe3=09D4`d+4xqM>w8Qa|xs^s)BF& zG2_bkWZu9~x%-EXJ!71ZS~rBe`!j=7`%Jdrqh)Z?ii^tRiIm@f-f!nW?)xCV`q~+D za=hVmU5=blUI9&(!Cy`2x|gJoAZH8A#_DKYCITyys?x8^ES2X}g9^g(%GFatY3)*^ zhHD$vy9`VmTnr&!XMb4~)QdOX<^Gb8Y5^ifJ`9A77(#pcr=t-)lh?;6740|}4ZFaX z_QIEE_CET}eP?nYJ%?H1rc7{FIA7OtiZwg?h0~`1>(nd|K*crT)!)bp02KNaV{8F1 zd@|h~Y7AbvrjBKLs7@Qda**RV=3ctY7XWafdnNYbyPN5zvLhq-D9D)VvbGJ|z4- zZ@2xG`Klg2)B>+{Gl~w7J|I{kTfBoy}FRE`-8Vy%jgo{e$ zGA=sJgsq23C9-+>8M5kIe_fa*heNzUpK*vyQ}NT~9d#2cQRJDC3swkD9wFF|+5o58-H&a( zZb8QO{u@?)=mrE*gm7m9k(8J<<*mHkMGIs@9eZYWY`yE>pI-!3l!r7nm?fB5;`4HE zoUxZ1uPdkrC;P%@=3tnn$MMC>r#R;psk~Jx)3Wc4SR(_&cU-7 zuFPyI$gU&pT}U^cuo`yz`w2T~u~EfS>jM4B(3{2Qbe91K#w-Io(B8=D1=X86hL8*5 z+-Uyhd?z-Pq}Nk{|0>sGNxekmD8d#v%3FZwUZJ$q_*#_=`I7g9Af=2RWC=H!MZ$Qk zMYt}~*sw&X2)kLI^`=$1@S6!|j(qr;{1B!`QfiiXJK8=qrhY1${r)n0 z#P4#D7j^Tw3UQ+Z;5)v(rI25l9y#^;Vtzq-BY?E2km7ayOAO}OyW*QtcoJb3j>1lK z@ps!q2GMqVXN;r@MTKNnw!kSVc^!`;+4H%K=dUes;r6?Y#s}w8ignbAS~^qOTDE%G(ds=I0%w4WJ){7ckeie z6K&g^3;ZRk?-Uf(K zcX3aYk8Xf*5QC=AY zUZ-z1`*N_QG!^EJAk;#4!`o8ht?|P`ca?bzo2-5c43+cEAE2zeiK&BOk8$J|#^BDc+h_O2`x?moWaU)jW= z{~>3sCjum~+JrAfJ4M07g++20GC>HV*1uscDI#5ZtqIkC0)pK(Z?v0G5-~5Fx4tQC zrCC26jRM>zDmC|~A8H>EA}qOc|9OsI72!Bu?4C=;M4*s_VB1^GJUXRNgz})je?i9Z zf$zNYCTwPf$EcMAn)hbv53G1K*oVA5IZZ0Pw~*6e>RFN!HalHn-63FeTz-=&{Srgy z7+F)10{56fOMbIj#TRELZyyFJWTze^DSaodafeb1M-B97AjZ4{d=QCril^N8WSY zXQ#`|_rS@#)TQ~;(n%yLB{IJ>IFdFq^lbzWu7B;p+ObGhvx&WAP5CLcrgTZ*U}hV6 z&2QqS4+|_0!L0%rt@`@-4)E!zoC&SHh_vwfCzN(ZM_WJEYbEP6Fh~jcKK^>vUD;6i zSiJbD@wcV9kYMm^jiAJS6SzjbnNx4fDrYxA+_8vHN&E2nm7X+%>ft`Q^w>c49U2p` zCR7NYJ%405M+W!?N~ScZSiJ6UbQiYT7ptJ?6IqUOFfDJ_E7CsJe=4`9vF{qoRQ2lhDqk&WF^k*Mm- z-!suSSfqcdOtQlhdGH})!Y-;G=&kMU z60rG;|H6*&1qiEX#dyE43d!H;r!dgRKiPyX=a~-l>{?uY<3UZMY6v#>?RHb_0==&& zE@j)rM#1O>Z)1Siv=c6HV*kC4s|*3L>G@GO4v9I=wg%fIW&RZ)iNlZeZ<2Z#K6g%8 zA;_|8h-VnJ2|6s-L&OfxfWrjsej|iW^^w0?GS=vH&FDe{ZFuatrjAw=IW6LT_3DB= z>u-hq#y&9dU8AO0pS_sdDwOeU1Q%qqoK9^&qrKfXU0{zu>!!Tm(L@M*ucBl2wc2b| zyUIs@b$GN!N>eHQ7?Bgv8K7BQ+GyMe^Q7ok*^tXM^K`F{m06C=i`Jjt26tmu=dC$H z2GKT;&atPC^qTqi8yQ0Yq~XH7du)?mpY-oBxOze0K_`&&4W7Ai$$|e9T;#kIz6XAiO^m)5$t+e|N zbsbW)s6RC6TKjFlutpt@pHyc-EC{$iHxIlx;N?koozr2%b;3(ab4#kRG&C);&poql zlcZ$2hh%*NI@m3ga$Ap}fb1AOYen*NoXJ25&zU+kwxd;G%~1lO z!K|5od60xAK<+5g7R`o>XYoY+?{SXy@vERbm`jPt5Ki;;tUfyx*iPp^G4=FxncNI_ z2~NqmQqF$7Il0L&Htk;U_{t0`_#8(>Eb?AQzh9BB&6F)$&3DI8x1-6te2AgZAMoy=*G?p|Pyw%;eD`%jZ;$Ld70pQNbUd8l04rx98}}7hA=Ll2 z^)?RrC`7vG^rj@0(L-W6;cRCW)$25r;0qaFrp$MPgb$D_N;x=$2OVU(nSa~r>hN$z zEKb{}inS9jJ-;tRrbXls5eQHXmhjdQ=M`rfuz5?X{NO$vs65B|rc1lDKf)YvE9j<@ z0TEp4{VPHGyh*`vVY3e?9T_%P7W;4i3;F$hp9y4g?0OH}?pC{l){MU_ACfnRIvT^! zg15?2Vz0IIxLNJm96amY0AtJCTbvfC*~Z@l-sKfxcbeZ$aJ*UU=K0SSCAE#djU6(iw$QF{}l<1)|ov>J+l&<8j zrf*_WO%R#+_KbvyQlnCs|670B`K!ToH-*=M#?Kz>GKV|}B3Ee=cz zWs^W_c!Gw~o8PJ*`>UH`vyGnYeOa1tYZ*~x3m)V5FF!erD7`=52jbM-ZLGr^z|~oI zhy&SK>lHe9>{4{uGXFLq!T@=t{Jo{<&Y~(MqN7-~9t-q>KwJwNXlT-eSQ1yGud8S0 zzMAJ$b9p*yjQ)R*T5Lnwttp9KR*BvgI!imNk%YNR6e`M~D-71wO{AGV8R+K-$B)k! zCxLe%99L3`lg%POcI`8TfF?>42KD>JH&Oqgw*D`kiIRzrb@q+%hG~st^nsrC@r$$K z*t>%AsX?Ok7>OVSdq>~Vk@WL5Z5q2|+)4;!Dl*-nAYfgaD0iIQsIPT4s&i>hw5>8k zPh3}dAvj`3%m9Q?nvAkaj3^`dS8K$ zCQ%M(o)=sVRQm=?=oEOR`MRg(?(8R`>xtAFx-^>`Mfw-zb_>GXK49`&4@nRi`sS6( z;k7uL`8iT4hU6!_RK1Ey-9b=5Z!2AzH&YjWu(pKhlBnuCm2!t~mz=TVkO*ULSZE?u z)Xda;nJ2VQ-pdD$PPa`nfsEiI26H8mnsaZ9f`ix_b3OF1^a>Lr2(o}b*3|DrFE(xQ zk{)cM^*9}K+xVY@LgpG&y;@kC=01J#gK#a5kEpXG4-e5$TN~l7uxJ7#%8t9oq1@h7 zv?iban|<@#qi`f8KqqMQ?U(2>zLnCB&6x!3XMYrI3S$k3pCOdFaVnvq!6=J|VD9_=F#NWnj0}`w4PMY!BZNGa z-#Jvd5B}Y?05@cwZLUw(deRxjDd>LRW`&A(rGA)6I1kRtxpllkytmqj{%0A}OkKxC z6+h=xe|0Yc%)5?vOU;VE!{F%|5*gtqJ6y2eJ!_m>6cMrcl0s3Njt(vI6b%7F{Je(s zIMi>-iq>*9BtUaWMDfpl_`(lx!8I+tGgEU_l--h}^m0kI+jwMpPykWPtjMiHzT*zp z47}AnKhGZx6nh4azALfWQyW>*i zN_if{G|doJ$|Xeom&28LQ_|^0x~$8lwVmc{Aq9AvDiP8%c7xgUk8wD*{LhCE&X6w- zmBwQNgY)OF#qR7a1f^fIexiFW+&n9(EsBdiopAXED9W0_!t8+*S8$o0!&CW!*v)CF z8pq8UK|%B4xmU=*Y6rtOabJA8pkJspgi42$?ThK!bgw6aA;+HYPLm+27`?;i{P!t!-xaKkL|Gw!3rUfk@{J!GYP;SoP4lFgU-RQ_A_NUwZ@0X`apj2r$_T$VE4^N83$}Xvbw1~51ZooHtcyUMjkKp-|y~!^6T&BKC)=G zGRA{K=UJ!&-dybZ_-;B09p7$sq9czKE;}}mBk*BG1{ZA3wTFx(SNT$B zukO)3t&4bJthTdy9f7OoeY1BK=x17R-~yk`%L^LRjbH5l>IvHJsWDmUT7#Z%Pp|i< zTNJKxJ@w~T2vywv(crW1A$07i@?HWA{QVXbo_wkA=0^8fTcmUFdm2fyEO>)pn68A%Ac%z0iiEV%E!`pA-AhZud)ME4|GuAd&pqeNoSA24p1C0K zHygfYy#XbAy4y2m^XpsfCBuAeE?$G`18<=_Za~Irh2K?7O>G|R-J~PZesxv&tEtn| z{1cJW3fRkUcvT268$``rx$n>U^u`Ahq?f)^Ip6_)lxLAPHYEdJ!-cQ@Xf81f9Z<2`+*CZ)O`91txaFntn;AP>;=32Z+0K#V~G;=V`mmm zp+!oTx@=^IH}o#a5K&kE+Fot5qqY$C$iV(^7QM@Gt?QBh^S`@>j`vzT2aGoT#}i6C z?Q3)@{KnG;w_He7AU&aDl9Kr1TJ=a=JP5|q5qmbqJ@F_y*q6#Vh$aQS=Jt+zV3XyB z+dVCw#{2ennFUjf9!t-S8C=G$ zsU$VBWvJ-ChYOc=kRraV_4d-G-AM+Va36ST+T_>N;gKTPEyl7Y<#d7DLT5r z$mS-9vsxova?8H5&!43yfz*8%j<(dTp@oS(v7a0Hb$`R?>ed52HMkN7o@p#!@{V+x{Np-^1Xn{D#D(zs1?`XLb^3kFETazi@E`KG|a*yjy<_i-Cj zf?%luQec`Wxhq7;8yCl)`t@IYAa*SgN&8ui2$DH$?&{(;Z1O>Perj&&q7$9?7LPEI z6inWn6z=#5m949*MTiLAiT9OY`Wi=#dlo0Fh>4BxTv#pqVk|sbW!T8FsICER0Bih# z;X3+-(}RHaNa?-d4V(`qK?fgA#ce<)JVVe(S90I;+kKB6Nr6!BL$J!!hgpnv3%MH# zFjhP`|2F(#*n`KQx|t&5;zv;({ftQ4Wb9^G>Xj8WU{LA0HM5c7e%X(4M~F$TP{Fa1 z_R`0A-S>8}ny_J7EHLQuR@bo$wX%?|-j{l`_HHGR(KsmK1@F#`d4U(>{U z6MUvGC={6Uk&Z`-{4;XJO_SkH%wtf0{@wmo7qGjK>S#V+)dWz;@Gi;sjUDEf)9nNl zm*^y>c|`_4*Pom?tDdsLw~|qIiTj*q_5Qc@qj!e0h=uo7DRr2RW)A%cyah_k2lIa! z9Z)j{3lI>i>hr_|EkD(p8be4Ms$$TXTK>EcxL8Z(S89PX(qZ@jBP`0m*R_Fxs)8N% zKD)}_VtlG8W@fufoxAVo|3bfJmlRQ-HGPywx-DnE;gy|-z6X0a zwcYQmNZ?=JW7`g2jGh6ji&PgF=rI4$>Z!)c@=cw#k;bN-?ph%_M*cu*^x@U4$wZ+b z6Cvjr6)@M}u|LjAK<*$k`JgL4;0KoE1s2l#kz!chm;3^U_uV_6c#=zwDfk<$K>d*e zlwv5MR?cPHoivtxrbfOw7N@j z*gTgFsX;RHH>-^^^gibw*fWm&1WR*Ms{P~Fy-L5oY`m9$la6Q1$s8u=Y}NiJ0SxNX zAHj_EinRS(Py51UprGOrmJ(LOBSKgGODXe_Pwt^zq8CEe53>`Puwj=4ztjzs=6RW; zO+V|r(Fz5iD0&Omz%DO=yYm3C@4j|#ttR%t(DhX0kyu+Ct1A`zNL2NHN%e9BOH;`T zH?k5n@NIt+#pB1Cd${m&EzvTB(&AxO+m-)zR|4V^${KfqM<{pT|#S+ zar%tVNs87bwX#U#J?Jf|tylk<)4Wubz5UOd3};NsD;XJl*VN!c9DBvJk9F&}aGby@ z5wkbxq@?skDW`0eLoZ$yLwFz<#>mq4DCm(!>o+ovx~Y*~`#OSeb9?33yKDJjY+F^H#e%ZFiKkRTDY-TXOH$(_WiJ$GJJL{>5o;u z+O?A6GH{i4_Jvf=QHZisbID}r(0ucRCXrBDAT_!y>^OoV-A zdTcUvsJD~-agcwm;2_Zt6Z6cGPRNU&2z06n)K`oGTxxoAuIwVyI|zBW{SO-03^fz$AW6q2dG^kLO$_=Sw@oe@@2bOcril{(g>%MDuNKBU)(c zYHP`3QFNCo*z@#rE%wbRkq|~Y3yADHhu$W6)2iPM`7c~6MsssR3E?El+7ARfJ}{nF zdW|N<8o6FKNnalPet6Xig@CVy96fdhGb1!F zzM8lllSg^XY3%g`G{E3JxP$oqkVRb0Rfov-<=g`C_$Q2XJ8s0~HG8w9gHrzc*Bc8w zB%<)DLV2k2nst-@sqeSx#0Vvf_Jr^i-koRPP(7C-Yw|)~lxQwZk@0#y;D=O3lm4jZ z=RD&s7kf*39HjQc`@q}AqCLaMC@g`{v~IU{KvpEL4ifX^!K<9@suFH;M9tvrZ-Ka6 zi)bOUNPgf;;$ViDFg1ei;4G}?{sRS_gHF4~Q>H{lyzH}r{@O|pc?X6GUai1jFxg6T zrHi~ht4X7JFy1k-#!oQs*_y5z-`6l}!$@%;OM}Z#J!dwvIp%0et-h>2#zsLfa<~_7 z5rbnsEp;x+E!gsNLOk{n#X48T~$mw8`>;e1i#diXa z%da**r%(O-zP(dHU|Mbh53LCK;I~l}6Em*oSs+?{VMO;>Dv$Xo=HknlKi~7fUL|*8 ze|P;=%#PRl$9D8meSP19M?vJTBtO8j(D+kG|5`FL>H8<~2?(LdH}pwJ0F+#6W_#PN zKVz&?VT|v?R%FQ-LHbKFkw%f$Tf)T#m)Dj-HX8 zPsCCcru$oA6MDI1oti(G93E81=CPL_ZL*cAZ!$K%{@(XBUlAH~D*8`~|36R~ZQiY6 zk2wpwN&h;rVB2D-mDl$bb#xm5;%v0YG5EBO9WXbSAOC^=R=sehAmqYm&W*m0+vG=oNYy5&_`0IEX+PlpbnG9Zq6waF`E0PW>zfMJLX#@MkzOt zQc{rj?l78CrYC4c4l@c5fC=Y?A+o>gU#}EwKuvZ=&jUd8DVs{)*Tc+DcmAYvk)Q&#gy-i!EUMV(q5t z-=0Cz`KM;vG)mn;l1#nRM~*-?K7nZ7IgN}Q9fSCT)!7ZEuKAmC99vpk zXu9oOoFNJm}ELKm%9d&&Lb@a&)l8?k<|oCT=lg z13(y=nJy|Og0H)&beguZf)d8JP6!+o)hu9M4?<|ctQxmh2H>Q;3zd5|5-K<5-wZpf zQ3{iW@>c&=WlTgh_Y{>d*TGj80#`OPul;`+G}J8*+^W)u?s>i6xL+WLgF~qJH}waq zOG3Y^px1D)uZCzt;dD8=kP4+2Z9=m(g$3$&%kC_SMTP}x#QB{^F zKUb3MVU}1W|2uG6=u&<=yOKwp8``H|oY`@z*8Z5W_Jik36M!Atset&eiSFjxVGBb} z>bFk`%~s~#1B}cXyjF^WsvfehUuhV8XFe<3<_~$Fej82^5#>dy%N8M`FChqf%~6eD z%j5=H3Uu`Ayxk;+EdHbqR^2W~YRZd7r zWY2}MG({X!YZU!R#{luk;W1`!ReS1GScJV+Vy8%#g|NaQvTW4Q`CKkrx!p0p zeMe+cD3kz^jc3`WZ+cXH6|^u_ezCNndCDd<)`0}=6!=Fff=Kb1>3IsmjG;^d^VjTZ zbUMA@WKo@&zS4;J=oo)xrU~zhi(Xh9mppABFmdFf&{L-Z(F_)cNio;jL8;U4cX^Ku z@rKaraGN@oPBysh9P{5->H>Ki10X}cY|r-Sv256BKl;fO18urR$YPvvb35M;89D>j zc6KQbN7%S}`-Yc_(?UE`#SG^fc=4EkwM=4J_mB)4n49G8idWieKsZkhD`S(BTqf$! z>GP6FG$AE=ov(^Xu#j$*zg|(&WniwZp*}s3eYrc~?$!sMhBS;)V*i7{rO<`DB@?!Y z&r{LQaT$&}q-#^^3b05%I47n4?ps0$oPA&{r=Wg>qeMK5uUSuw+OcBo{zTbYxxT*M z@-Mur`DffY`LxpXE^dJM=uF}r#Y@MQ**Tv_8H+v}e8?D{80dF4bFb=kI>G&zm%^W}>V+VYX;PB++=Mdm&rHi24UK-SA?LHJ*7h2LwZz#jd^%)K8E#~LzO}w-P6T*lFY4LA*KRkjtJ%@ zmU5@I%zD(A72-_g2JFG6a7Wn&ce>XN$|^St@UNmTy{6 zMN^q3b~kwY2oJY>WeRHRi{Lunn}4xo()`)qmfWNd+=mnMj!FmD^<&X?VgF~yc3r;K z8rG6W+$K24KT4+&K&h|ojxFROAgnS)Aq43f^m`@fE)6>fgE34=j8!{Wn}}9es2LJk zR~K8Yx~3RT*BX|w>Hdgm!E`b$_B z%Ak0Ehl<00d&(*!I&p)7|0*x=Net+pY&u3Q+@DQ1`tY=gHIHwJx8+wL9r90e$G|7U z@$tV#!v}A%QXGaK--3mbTO%0c+VZXlX6XEa5!VfdS%ed5ZLj2xKq~%)u&m(gV4i-qp=KCj+3@cW>3l<9Zk7?1#qBnga_`uh!uQ^KRcp&JJ2P%wEtvPX?z3 zSFBUwalqpvL!}nhzI@e~VjWK>IbcuAoXVw}|Msf}kN_`{L-$TcxtpAI$!}I^CKl?|E>$(=wRLCr$E$0r>ISp$+C?sM$ zp}_Zed;DX~(f1*Xa@--hU~jYijgfyST&@D^Kh!qlL&9tPgSC;mrU=M|#i?l~tPjwaj|0;jOBj?Ny?%wn!1{Cm}a*-qo*<0G0gdzus=Axe#p z38w8ar#`codpsB1N`Z0xtXc*ZU^(}A_JthCKRbyrbc%^NbNTG1i8mqmX_h0qoF@riF14IA}{Dv;4 z<*)Be)$X6#d;8Y*<-LIAb9pd}CUvjFaZ^!BxfliF0Z(go_;)gMamdbLpiea{>;%-h z?Yqbu;Z`B;zLJuYJzv#%@;bfFDlMQj^zDmeFbnU0g1#o|SCjcYMfx_#$^)#ewsV|G zZI4v*?4d2eXXKB@8+RQioHdUz5zKpjv3A!g5QnyPC&zW_Oq#V)L%i3{8QoU{Ey zruoj}cwkEJL{jIPvxEQA^j!3}06Hk1ZSg9I0I5Mqd2at-DvzGZ9j7wOOnfUd$bR@t z_d0}K<=bugi!D*u$txgTxyJ#Hw1AO}?M!o7D*=d7gVf?(-cPq*eQeLvqC9R6RmZ8q zAn5imbhgF@KSJDSyhTs$y}YuNmA+^C)8?NXlK0}vdJ_aUsSG)%K<$aCHAHaA^x3j& z_0_TQAkAvc(zGDtv`xQRhby@g+g!m5D$%@06KwM}EFNC>{$eX^hS67Gb1&3O{={cg z6=s3m89S7DzIwAX$e6g<9^IfTKJDUADtwb1lAF{{`To#?AS}%0-E=4jG?Fxz<#G-a z%V=^)8vJrMKTv!L2jN=HeqM73B*XWEm{%tAxAd$7ZN=Eyi#$i$6V< z1c;e9kYvn=x&QvV{_CbL<>oLp*|r$Vwz!NAbl7+~8A&GSm05H@H|7DDnKz^Mxsh^OmZZ)mKCFE*d{v4K@HA%lOUYTybwEx?5w0-@Y5=%l3 znzd~Uh8(&kQZnj&ng1nvA;_qRg*jn#n1R2=kh>fqtcW)wN@l9 z2=-?#ROcXtWD&Fd#ob)u!l3(8SOeJG1Dv(C19r8v=;QN)fM9}s497+}HIHh&8)-p+ zC3V}00Db;=)e5Ic>&KV+204W89Z7=CAPvS2GCdOX{`o1Fs;SmEA*b9 z;+Wx|4%_%d$(%|wHH9$y9YSd26B#UnchGC*9~#!yqrk*79ln_(nOcazo|}3m(RTei z?{@0D1dlq`^}li5&xxk9Xbz3A?x3L|mV*jZ6e0cHKE?Xy`rK&IoEa>@RC}<%nk@Jq zXt_scgH#5BZp5>&VBKo@lPS2boiE)FV=!f{ijRA&bMADoOFTUEFZ#oIcv!MiK*paZ zWH{=9iz<#yzpP9b4+{jbOgkA=kJ`|`{)Z#-Edad|Lhq! zdI7G>)K?ZR>knxj0x41;rbRh=VSS?2e>{c@jBjHa=h*KgFAL^6?o%UJwFL z!2R>%-!iG%|4e~A5{ij#QcRk3zI$I>` z-KvTUdw+W5Chyx8x5=lq4dp!n-I<1yVwMp$f*O8RoxJZtctbXH>Z5 zadFm$Z0M%i*-u5uk#4Kb49>?gn6DdaL|(rKA%?u$4mLnpv3SM%c=+tMQ)0n09avY4 zZ1!}L+u_^$WW%L&%L@)_@kSY&J9Ye54StQEtfw9CgE?l|DdxMn1K*11C?Gi*fn5rg z% zn|=iVi0qW%Pqfp#vZfC9X|7eDys;PF5PJ_75gPl%e@;RY#${UBvSgyFaO<6^?VWq% z2CBaB7)~{`k1b3ZjcvYHbnzMMPzawVg77}Zf8feqQQNgnnf5wc881>cJ`zEc04nHs zLm3c2Of`I>T1J$t&G)wyO1W#MQ`4Yu@Vhgz{l(f&IWpaaf9%gHSeOYHPKex{9G-HD zA&j0a$nMQC8u!zxq6h-F&4!XxE~vP;*lR0&iH7NxD6q*;p@KlZ!=7eM{;BYT(QVHO zJF)W$CJz6P)z|&YqmdqSE}~DlO+ITIm())N+Bh$PwRqt8*uY`b`1llWbB1CU1CY1F z+X9|%YUeKn^G`X_F8)p^CY^buHa>x;7IqZv_7gIT_iX(f+566f#mPVwWruOm@gw(O ztRPZ~=!BZJKSG#+j~jI}Q^lmPDC`#AfID~OHin4@lmc#q0?M~|_mKv_7b$BQT4IPn+AKWlg zn9@mrmeu&)ceIgq;0rw>B<@ZF4~k67d8P6Eriz<{6KG(P3|If4(U6#NK~U%1c>t=X zVATzJ;KD5or0^BoM;Z}c+eA9d7rbp?9-@!J?;F5hC2WQ3Sb>GWd0eKPrp_f;*N;sH z^lDY+Zgfl-3XJ99Zej-iMuuCwH`t)sD~WBf*Rtjt@BXLUghu?UV$!Q#cel;`uXm=ZNT`cYKAb84w}lhPvZPbHcm$OJLWvBlDv04xJ5M^ zmQB%}S6vU>UI20F!_(e2LMP;SwFTv@)wy*LP_#ozz>`f{eclbR^OjQ?P!KRDsbGS zV5{j5gLh`Ms&`3Y!V^dTenC5{iJ;3wRg&A$y`slhZqqMwduM7-kuW+?9KG;aB`NhgQP)Q#ZG*OPLKZ)t zNoj&%0`NF(GOkPpMG_dhw_sO;DV@H#Q)_~m3SuKL@(mY-bdKreaQ4i*=O zihZiyP5-RhzA7j3$3Y0^;2=O{!z}J<@ErhyR*e%RGI(dC=3YB5Ro{KK0L`jUO=5gq zxiZUZ@+B>GBWWx9}bTt5Dy7M7tXaC&D5d}ug)U4AF zekj^(OweGr%$nE79doPZ+Y+nz{vhX&I=N{+`&A}WJyvr|EoSTm4YPJqLDlzIw~H-L z3L7S+YKE4kByoRT9&%9~gpkBd7?E@-`Xj?1Xb2`i!(G&HJ7YMLy^~T4=oT#a0y>n# zue-%D33aS+Fl7C=M%2D;O)cLZQ9Awdk(6K|t;Ou0eXcOYq!cRP*3#FnBixPAMEOwr zbxD{cM?f8;r*+$P*^B&>KFGQ`((00gjttineLr*?XmKKwZ3ok+?qyJ%A6ff92V>UY z4~+`Ut5(BTYeiorxq8T?5H#=f@8QS#7Xvk!_(IKPCZUYY8jiUIL|Yva*Kj6gB?}v7 zPulFW&`cTn@WXWQLk!83vO)(B#RFPCg9c<6n<4;H_wL4a*%+L^luxZ0eHJ~*N ziE2WiJFa`$yjyBNHR>o#%?0tTuA%3>mI6!ubPrzW_ZNIB6#{W0HY-kmy?|C86sC=l ziEIzEe#Fe>$F*d|^x?{)fK~l^;ff%*Mc%KGWH@qV5e_jWeSGnd(>H%DJA(wj7Zw(Z`ANUx>i72&r#30Fe}%Iu4|VC;8qyDC1d<`Sq=O`{ z_YAMV9^xB@Zh}!^A2Y}d?P=+voopS+ST=LAk19-g&(f+_+XzAU^lVcaVH|K6qv?J@ zqS^|8RhJ<9Qd7r$z+IOwiNJ^HhpTGRtXc-_wl4Dg^LLfmjb+OcG6HvVdSd4gW zWK>yO&m2=^b@K;p84R!FJAPR@7?p?Of0Snh#^wUX%t$a>l{3`Xu2V}@jlN#P3O~st zc2q0EpJBYyCZt*NeBMT{4_0bfoPkYXP=0p@iQIZ@w&Op{CKZMI0|n4ZM>RU`f#@qc zJH6<~_F7{xlooAdbVx84B5eCB`Iru}ekjFWC5cZ;{^^_WuFe0F9Q}oNUYwU(S8Bjh zD|#OSp*nIcyYHTa%AOHp8DKIvPE%g#zn#`%+}XtJnepiFNiev0Ib#M*$IDj7kMESq zjWw@)V7VXuO;PmSq<85>>Ct}wQ0yipVJ&(agb9QBkjcGkYMRG`A+ULBi#BanOwdNj z7N_UNM*c7anH5Wn>Bf@BA_wG36IF_QQG>D#T%Fj${hs{pHf$;H@1hs2((1 zw?N2vFg!?-f*wW5JuBD@Re|uSE0^}S_#Ia^u-i@je0#@RuTwtbRgoDhdUAhk6Nwfu z_^8Ry^vFPrNk!HNBaxtEo{nvyPcdj1EtSdbU5yc}@U@68gDZ_7u(iFNnwa}mg?d!$ z{;?KG>s#}`FY?lH&b#UT8teK+kG+Ue*aN&^DGAmWUvWaCZ>;EmKB9EEI9Jy4@Ga|F z=7Typwmx!$KO2tPwY?rSU24_)uuZiG3t0t$NXdr<>ORyNYL>y@1E)fG2W9TwSy^p# z&0Q_D8Wnk8p@IhFr0K%9Z5Po+57}F<0y&YMPe3#274%N8ZNUOHHT6vK0or2CrV=lX z!46b(9-pNuDyoo&9{(;KNLYDI|McmG{Ok1UKJ3!w_ZNK9GL-8NO&e1NNGE9n`ztpq z2(2|gO!57vIBT>RSGF!!4ZvhJiTNJ6M=OiXs?7O8Eq&e#urwRz?Gi>XY5L9gdq7Kn zW4e1%yJNM-gt>;MO7r8nH`{%$-EST`7*M#lj`1;mJUipyFD^UTnHif0!2$U*z`OO) z&lg|J4SY~iIm0r1&C5MCNJZa&`YfB`hhJxF>w`jFs4k{$*fI$O9k6wTs^Xze#P;3 z;hyR|3I&QYVrDC2zr|70n&S{gR{ zAIhU`M4M>e3<7#6?Q0OVe$hj=3-%BNKk>T_)KO@dO#!I&H#G$jofAbSyb12tej0?2 zkBk^W#1SlfH3xqW1YPRNKO=vA*Eo+63GT(Z1hasD9(kcjv=g?0^2kcA(C zXoYfF)18&i@}@IxBe^i%i~0L~_Gpxrd72m$H}G?p2^dgyhuQO&CS`YYfImg^G4p)@ zUI{iO0{vf+|1I<>XSVYb5ZiYo7;Mr6tij`9GwZL Date: Sun, 4 Dec 2022 15:24:34 +0900 Subject: [PATCH 378/433] [jsk_fetch_startup] always take photo in smach --- .../jsk_fetch_startup/euslisp/go-to-kitchen.l | 30 +++++++++---------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l index ce19d61d15..1f53a3d8bb 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/go-to-kitchen.l @@ -171,7 +171,7 @@ (room-light-on :control-switchbot control-switchbot) (ros::spin-once) (set-alist 'description "電気をつけたよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -185,7 +185,7 @@ (if success (set-alist 'description "ドックの前に移動したよ" userdata) (set-alist 'description "ドックの前に移動しようとしたけど,迷子になっちゃった" userdata)) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) success))) @@ -195,7 +195,7 @@ (inspect-dock-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "ドックの前の様子を見たよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -205,7 +205,7 @@ (report-move-to-dock-front-failure) (ros::spin-once) (set-alist 'description "ドックの前に移動できなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -226,7 +226,7 @@ (inspect-tv-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "テレビの前の様子を見たよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -236,7 +236,7 @@ (report-move-to-tv-front-failure) (ros::spin-once) (set-alist 'description "テレビの前に移動できなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -258,7 +258,7 @@ (inspect-tv-desk :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "机の様子を確認したよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -268,7 +268,7 @@ (report-move-to-tv-desk-failure) (ros::spin-once) (set-alist 'description "机の前に移動できなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -290,7 +290,7 @@ (inspect-desk-back :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "部屋の後ろを確認したよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -300,7 +300,7 @@ (report-move-to-desk-back-failure) (ros::spin-once) (set-alist 'description "部屋の後ろに移動できなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -321,7 +321,7 @@ (inspect-desk-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "部屋の前を確認したよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -331,7 +331,7 @@ (report-move-to-desk-front-failure) (ros::spin-once) (set-alist 'description "部屋の前に移動できなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -352,7 +352,7 @@ (inspect-kitchen-door-front :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description "ドアの前からキッチンの様子を見たよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -382,7 +382,7 @@ (inspect-kitchen :tweet (cdr (assoc 'tweet userdata))) (ros::spin-once) (set-alist 'description (format nil "キッチンの様子を見たよ。~A" notify-text) userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) @@ -392,7 +392,7 @@ (report-move-to-sink-front-failure) (ros::spin-once) (set-alist 'description "キッチンに行けなかったよ" userdata) - (if (and *image* label-names) + (if *image* (set-alist 'image (remove #\newline (base64encode (send *image* :serialize))) userdata) (set-alist 'image "" userdata)) t))) From eb84ab215ec589e25ec6f777323e9681dcbaae9b Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 5 Dec 2022 20:01:18 +0900 Subject: [PATCH 379/433] move app_schedule config in jsk_fetch_startup --- .../config/fetch1075_app_schedule.yaml | 52 +++++++++++++++++++ .../config/fetch15_app_schedule.yaml | 33 ++++++++++++ .../launch/fetch_bringup.launch | 2 +- 3 files changed, 86 insertions(+), 1 deletion(-) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml create mode 100644 jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml new file mode 100644 index 0000000000..b15d843c4b --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch1075_app_schedule.yaml @@ -0,0 +1,52 @@ +# 'go to kitchen' launch time is temporary changed to 9:30 AM by yamaguchi, 2022/05/20. +# Recently fetch1075 freezes at 9:00 AM. +# I think the reason may be the simultaneous launch of 'go to kitchen' and 'time signal' +- name: go_to_kitchen_morning + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("09:30") +- name: go_to_kitchen_noon + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("13:30") +- name: go_to_kitchen_evening + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("17:30") +- name: go_to_kitchen_night + app_name: jsk_fetch_startup/go_to_kitchen + app_schedule: + start: every(1).day.at("21:30") +# time singnal +- name: time_signal + app_name: jsk_fetch_startup/time_signal + app_schedule: + start: every(1).hour.at(":00") +# upload notification +- name: upload_notification + app_name: jsk_fetch_startup/upload_notification + app_schedule: + start: every(1).day.at("03:50") +# check use_sim_time +- name: check_use_sim_time + app_name: jsk_robot_startup/check_use_sim_time + app_schedule: + start: every().hour.at(":00") +# volume for monday meeting +- name: volume_zero_monday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().monday.at("12:00") +- name: volume_reset_monday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().monday.at("16:00") +# volume for tuesday meeting +- name: volume_zero_tuesday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().tuesday.at("12:00") +- name: volume_reset_tuesday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().tuesday.at("16:00") diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml b/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml new file mode 100644 index 0000000000..6fd9e0c702 --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/config/fetch15_app_schedule.yaml @@ -0,0 +1,33 @@ +# time signal +- name: time_signal + app_name: jsk_fetch_startup/time_signal + app_schedule: + start: every(1).hour.at(":00") +# upload notification +- name: upload_notification + app_name: jsk_fetch_startup/upload_notification + app_schedule: + start: every(1).day.at("03:50") +# check use_sim_time +- name: check_use_sim_time + app_name: jsk_robot_startup/check_use_sim_time + app_schedule: + start: every().hour.at(":00") +# volume for monday meeting +- name: volume_zero_monday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().monday.at("12:00") +- name: volume_reset_monday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().monday.at("16:00") +# volume for tuesday meeting +- name: volume_zero_tuesday + app_name: jsk_robot_startup/volume_zero + app_schedule: + start: every().tuesday.at("12:00") +- name: volume_reset_tuesday + app_name: jsk_robot_startup/volume_reset + app_schedule: + start: every().tuesday.at("16:00") diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 206a047988..6b7136e3fc 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -183,7 +183,7 @@ - + From 19ed453fcff74f9d3b49c2dad1e5b84f17ac8d03 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Mon, 5 Dec 2022 20:13:22 +0900 Subject: [PATCH 380/433] use enable and speak_enable for volume control --- .../jsk_robot_startup/lifelog/auto_speak_volume_lower.l | 5 +++++ .../jsk_robot_startup/lifelog/auto_speak_volume_reset.l | 5 +++++ .../jsk_robot_startup/lifelog/auto_speak_volume_zero.l | 5 +++++ 3 files changed, 15 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l index e3efe68518..48c236a58c 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l @@ -1,6 +1,11 @@ #!/usr/bin/env roseus (ros::roseus "speak_volume_lower") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool t) (ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.2) (ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.2) (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.2) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l index 89685bfb3b..a57c51c262 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l @@ -1,6 +1,11 @@ #!/usr/bin/env roseus (ros::roseus "speak_volume_reset") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool t) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool t) (ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 1.0) (ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 1.0) (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 1.0) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l index 6f89b26903..e0bb7d2c43 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l @@ -1,6 +1,11 @@ #!/usr/bin/env roseus (ros::roseus "speak_volume_zero") +(ros::set-dynamic-reconfigure-param "/audible_warning" "enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_warning" "speak_enable" :bool nil) +(ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "speak_enable" :bool nil) (ros::set-dynamic-reconfigure-param "/audible_warning" "volume" :double 0.0) (ros::set-dynamic-reconfigure-param "/tweet_client_tablet" "volume" :double 0.0) (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.0) From 486633233e6ddd53d7b2b61c1c2d3f74729c596a Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 9 Dec 2022 12:12:10 +0900 Subject: [PATCH 381/433] [jsk_robot_startup] Change permission of SmachNotificationReconfigure to avoid build error From 789051607008e88f9af568df2e7833d9bd97fb74 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 24 Mar 2023 00:42:57 +0900 Subject: [PATCH 382/433] launch zdepth throttle node --- .../jsk_fetch_startup/launch/fetch_sensors.xml | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml index 2649c370e9..7b88454973 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_sensors.xml @@ -78,6 +78,15 @@ + + + + + Date: Fri, 24 Mar 2023 00:44:51 +0900 Subject: [PATCH 383/433] record zdepth instead for go_to_kitchen rosbag --- .../jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app index 2577fa0141..b5a69c054e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/go_to_kitchen/go_to_kitchen.app @@ -40,7 +40,7 @@ plugins: - /head_camera/rgb/throttled/camera_info - /head_camera/depth_registered/throttled/camera_info - /head_camera/rgb/throttled/image_rect_color/compressed - - /head_camera/depth_registered/throttled/image_rect/compressedDepth + - /head_camera/depth_registered/throttled/image_rect/zdepth - /photo_taken - /server_name/smach/container_init - /server_name/smach/container_status From 645e0b590198c3fd16759c0cfb0417d1853ddd87 Mon Sep 17 00:00:00 2001 From: Shingo Kitagawa Date: Fri, 24 Mar 2023 21:59:45 +0900 Subject: [PATCH 384/433] advertise when no tweet publisher is advertised yet --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index 4053c0c081..24d39ae856 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -10,6 +10,8 @@ (tweet-topic-name "/tweet") (volume 1.0)) (if (null (ros::get-num-subscribers tweet-topic-name)) (ros::advertise tweet-topic-name std_msgs::String 1)) + (if (null (ros::get-num-subscribers "/tweet_image_server/tweet/goal")) + (ros::advertise "/tweet_image_server/tweet/goal" rostwitter::TweetActionGoal 1)) (let (prev-image-topic img) (when warning-time (unless (numberp warning-time) From 098c08997c773e47c7e4d76a2e6a53753d3961e5 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Sat, 25 Mar 2023 20:38:36 +0900 Subject: [PATCH 385/433] load rostwitter message --- jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l index 24d39ae856..2e082e481f 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client.l @@ -1,6 +1,7 @@ #!/usr/bin/env roseus (ros::roseus-add-srvs "topic_tools") +(ros::roseus-add-msgs "rostwitter") (ros::roseus-add-msgs "std_msgs") (ros::roseus-add-msgs "sensor_msgs") From 07811d98d10f5a8a9b92be9101ed1b6936b7a9fa Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 17 Apr 2023 12:56:28 +0900 Subject: [PATCH 386/433] [jsk_fetch_startup] Add ros_google_cloud_language to fetch_bringup.launch --- .../jsk_fetch_startup/launch/fetch_bringup.launch | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 6b7136e3fc..fbebd12b3b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -35,6 +35,7 @@ + @@ -408,6 +409,11 @@ + + + + From 6bde249d8ef4c9e988656d899992e70b654fa880 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 17 Apr 2023 17:59:35 +0900 Subject: [PATCH 387/433] [jsk_fetch_startup] Add download link of google_cloud_credentials_json --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index fbebd12b3b..8760cc5f0e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -412,6 +412,7 @@ + From 98e18b096d438061f5cbf6c9c53de1290b8a3fc5 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 30 Apr 2023 23:14:25 +0900 Subject: [PATCH 388/433] [Fetch] Fix jsk_recognition branch in jsk_fetch.rosinstall.melodic --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index cc1f06db8e..2ecfc0bdfb 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -65,12 +65,11 @@ local-name: jsk-ros-pkg/jsk_pr2eus uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git version: master -# we need this PR for fisheye vital check -# https://github.com/jsk-ros-pkg/jsk_recognition/pull/2734 +# we need to use the development branch until the next release. - git: local-name: jsk-ros-pkg/jsk_recognition - uri: https://github.com/knorth55/jsk_recognition.git - version: fisheye-vital-check + uri: https://github.com/jsk-ros-pkg/jsk_recognition.git + version: master # we need to use the development branch (fetch15 branch in knorth55's fork) # until it is merged to master - git: From e3e4b1ddfcd5122ebc1d81fcf6614f8465cdf131 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Sun, 30 Apr 2023 23:17:46 +0900 Subject: [PATCH 389/433] [Fetch] Fix comment of develop/fetch branch --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 2ecfc0bdfb..08e5b87b75 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -70,7 +70,7 @@ local-name: jsk-ros-pkg/jsk_recognition uri: https://github.com/jsk-ros-pkg/jsk_recognition.git version: master -# we need to use the development branch (fetch15 branch in knorth55's fork) +# we need to use the development branch (develop/fetch branch in jsk-ros-pkg) # until it is merged to master - git: local-name: jsk-ros-pkg/jsk_robot From 9ad1b5803098a859efe7a58c2c04b0292d1359d1 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 5 Jun 2023 15:06:13 +0900 Subject: [PATCH 390/433] [jsk_robot_startup/lifelog] Add replicate_on_write arg to mongodb.launch to search at replication server --- jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index 489da6e5ec..7f7af07807 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -11,6 +11,7 @@ + @@ -25,6 +26,7 @@ output="screen" machine="$(arg machine)"> extra_collections: $(arg extra_collections) + replicate_on_write: $(arg replicate_on_write) From c72dae604b8889dc38bd921405e7e074c6894369 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 5 Jun 2023 15:06:52 +0900 Subject: [PATCH 391/433] [jsk_fetch_startup] Add replicate_on_write arg --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index ab52d40cc4..3e80d8de9e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -3,6 +3,7 @@ + @@ -13,12 +14,14 @@ + + From ce6500a0563b57f24c22c0e3370b313ef780445e Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 7 Jun 2023 14:26:20 +0900 Subject: [PATCH 392/433] [jsk_robot_startup/lifelog] Tweet randomly from uptime --- .../jsk_robot_startup/lifelog/tweet_client_uptime.l | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l index 1dc3caed3c..4313e8faf7 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/tweet_client_uptime.l @@ -18,6 +18,13 @@ (unix::sleep 3) (ros::ros-info "Wait for /active_user/elapsed_time parameter ...")) +(cond + ((ros::has-param "/active_user/tweet_random_range") + (setq *tweet-random-range* (ros::get-param "/active_user/tweet_random_range"))) + (t + (setq *tweet-random-range* 600.0) + )) + (cond ((ros::has-param "/active_user/tweet_second") (setq *tweet-second* (ros::get-param "/active_user/tweet_second"))) @@ -34,9 +41,9 @@ (let ((st (ros::get-param "/active_user/start_time"))) (setq *waking-target-second* (+ (- (send (ros::time-now) :to-sec) st) - *waking-tweet-second*)))) + (+ *waking-tweet-second* (random *tweet-random-range*)))))) (t - (setq *waking-target-second* *waking-tweet-second*))) + (setq *waking-target-second* (+ *waking-tweet-second* (random *tweet-random-range*))))) (setq *volume* (ros::get-param "~volume" 1.0)) (setq *speak-enable* (ros::get-param "~speak_enable" t)) @@ -76,7 +83,7 @@ (let ((waking-time (- (send (ros::time-now) :to-sec) st))) (ros::ros-debug "~A waking ~A sec (~A)" *robot-name* waking-time *waking-target-second*) (when (> waking-time *waking-target-second*) - (incf *waking-target-second* *waking-tweet-second*) + (incf *waking-target-second* (+ *waking-tweet-second* (random *tweet-random-range*))) ;; tweet source of robot-interface (unless *src-lines* (let* ((dirname (ros::rospack-find "pr2eus")) From 0c51e0ec46422d754f3ca14995f016febf6aa3da Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 19 Jun 2023 09:22:14 +0900 Subject: [PATCH 393/433] Add labeler action for develop/fetch (#1815) * Add labeler action for develop/fetch (#1810) * [.github] Add labeler action for develop/fetch * [.github] Fix PR * [.github] Fix workflow for temporal test * Fix * Update laberconf * Change some * update * update * Change some * Change some * update some * update some * delete unused workflow for test * delete unused workflow for test * update some * update some * update some * update some * update some * update some * update some * update some * update some * update some * update some * update some * update some * Revert "delete unused workflow for test" This reverts commit 691e7915220e93887627b8f1bf06460394ab90de. * [.github] Fix target branch --- .github/labeler_conf/develop_fetch_labeler.yml | 2 ++ .github/workflows/develop_fetch_labeler.yml | 16 ++++++++++++++++ 2 files changed, 18 insertions(+) create mode 100644 .github/labeler_conf/develop_fetch_labeler.yml create mode 100644 .github/workflows/develop_fetch_labeler.yml diff --git a/.github/labeler_conf/develop_fetch_labeler.yml b/.github/labeler_conf/develop_fetch_labeler.yml new file mode 100644 index 0000000000..e0fe1fbe40 --- /dev/null +++ b/.github/labeler_conf/develop_fetch_labeler.yml @@ -0,0 +1,2 @@ +develop/fetch: + - '**' diff --git a/.github/workflows/develop_fetch_labeler.yml b/.github/workflows/develop_fetch_labeler.yml new file mode 100644 index 0000000000..f85a2a913d --- /dev/null +++ b/.github/workflows/develop_fetch_labeler.yml @@ -0,0 +1,16 @@ +name: "Pull Request Labeler for develop/fetch" +on: + pull_request_target: + branches: + - develop/fetch + +jobs: + triage: + runs-on: ubuntu-latest + steps: + - uses: actions/labeler@v4.1.0 + with: + configuration-path: ".github/labeler_conf/develop_fetch_labeler.yml" + repo-token: "${{ secrets.GITHUB_TOKEN }}" + sync-labels: true + dot: true From 8dd287b812acb22947f8549f130cc3953615d9d5 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 21 Jun 2023 17:35:37 +0900 Subject: [PATCH 394/433] [Fetch] Switch branch of jsk_pr2eus to develop/fetch --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 08e5b87b75..491417fa4f 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -60,11 +60,17 @@ local-name: jsk-ros-pkg/jsk_demos uri: https://github.com/jsk-ros-pkg/jsk_demos.git version: master +# we need to use the development branch until PR below are merged. +# - https://github.com/jsk-ros-pkg/jsk_pr2eus/pull/495 # we need to use the development branch until the next release. +# - git: +# local-name: jsk-ros-pkg/jsk_pr2eus +# uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git +# version: develop/fetch - git: local-name: jsk-ros-pkg/jsk_pr2eus uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git - version: master + version: develop/fetch # we need to use the development branch until the next release. - git: local-name: jsk-ros-pkg/jsk_recognition From cdce6e5b42839a3f99b0673a20376e0b8b43630b Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 21 Jun 2023 17:59:06 +0900 Subject: [PATCH 395/433] [Fetch] Fix comment develop/fetch --> master --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 491417fa4f..3e43c99a28 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -66,7 +66,7 @@ # - git: # local-name: jsk-ros-pkg/jsk_pr2eus # uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git -# version: develop/fetch +# version: master - git: local-name: jsk-ros-pkg/jsk_pr2eus uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git From 8b02a04838118900976a00cf3014b17e19a8dbd1 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 15 Jun 2023 11:42:30 +0900 Subject: [PATCH 396/433] [jsk_robot_startup] Change order of git stash and git fetch --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 053f0fcfd3..15da544cb7 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -80,8 +80,8 @@ TMP_MAIL_BODY_FILE=/tmp/update_workspace_mailbody.txt set -x # Update workspace -wstool foreach -t $WORKSPACE/src --git 'git stash' wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' +wstool foreach -t $WORKSPACE/src --git 'git stash' wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall wstool update -t $WORKSPACE/src --delete-changed-uris From 2a12115ff0d0aefdea02f17628b462c768b8897b Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 15 Jun 2023 13:15:07 +0900 Subject: [PATCH 397/433] [jsk_robot_startup] Add dry run option not to update forcefully --- .../scripts/update_workspace_main.sh | 29 ++++++++++++------- 1 file changed, 19 insertions(+), 10 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 15da544cb7..3506151739 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -2,7 +2,7 @@ function usage() { - echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-u] [-l] + echo "Usage: $0 [-w workspace_directory] [-r rosinstall_path] [-t robot_type] [-s skip keys] [-h] [-u] [-l] [-n] optional arguments: -h show this help @@ -12,6 +12,7 @@ optional arguments: -s SKIP_KEYS rosdep install skip keys -u do not run apt-get upgrade and rosdep install -l do not send a mail + -n do not update workspace, only show wstool status " } @@ -22,9 +23,10 @@ function get_full_path() ROSDEP_INSTALL=true SEND_MAIL=true +UPDATE_WORKSPACE=true WORKSPACE=$(get_full_path $HOME/ros/$ROS_DISTRO) -while getopts w:r:t:s:ulh OPT +while getopts w:r:t:s:ulnh OPT do case $OPT in w) @@ -45,6 +47,9 @@ do l) SEND_MAIL=false ;; + n) + UPDATE_WORKSPACE=false + ;; h) usage exit 1 @@ -81,14 +86,18 @@ set -x # Update workspace wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' -wstool foreach -t $WORKSPACE/src --git 'git stash' -wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris -ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall -wstool update -t $WORKSPACE/src --delete-changed-uris -# Forcefully checkout specified branch -wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' -wstool update -t $WORKSPACE/src -WSTOOL_UPDATE_RESULT=$? +if [ "${UPDATE_WORKSPACE}" == "true" ]; then + wstool foreach -t $WORKSPACE/src --git 'git stash' + wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris + ln -sf $ROSINSTALL $WORKSPACE/src/.rosinstall + wstool update -t $WORKSPACE/src --delete-changed-uris + # Forcefully checkout specified branch + wstool foreach -t $WORKSPACE/src --git --shell 'branchname=$(git rev-parse --abbrev-ref HEAD); if [ $branchname != "HEAD" ]; then git reset --hard HEAD; git checkout origin/$branchname; git branch -D $branchname; git checkout -b $branchname --track origin/$branchname; fi' + wstool update -t $WORKSPACE/src + WSTOOL_UPDATE_RESULT=$? +else + WSTOOL_UPDATE_RESULT=0 +fi # Rosdep Install if [ "${ROSDEP_INSTALL}" == "true" ]; then sudo apt-get update -y; From cb05a6808be0e0a9f5266a21f549cc54620f6101 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 15 Jun 2023 13:19:41 +0900 Subject: [PATCH 398/433] [jsk_robot_startup] Show wstool status to mail body --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 3506151739..3656f4557b 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -84,8 +84,14 @@ TMP_MAIL_BODY_FILE=/tmp/update_workspace_mailbody.txt { set -x # Update workspace - +echo "" > $TMP_MAIL_BODY_FILE wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' +WSTOOL_STATUS=$(wstool status -t $WORKSPACE/src) +if [ -n "$WSTOOL_STATUS" ]; then + echo -e "Please commit robot internal change and send pull request.\n" >> $TMP_MAIL_BODY_FILE + echo -e $WSTOOL_STATUS >> $TMP_MAIL_BODY_FILE + wstool diff -t $WORKSPACE/src # rostopic pub fail when wstool diff has single quote or double quotes +fi if [ "${UPDATE_WORKSPACE}" == "true" ]; then wstool foreach -t $WORKSPACE/src --git 'git stash' wstool update -t $WORKSPACE/src jsk-ros-pkg/jsk_robot --delete-changed-uris @@ -115,7 +121,6 @@ catkin config -DCMAKE_BUILD_TYPE=Release catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail -echo "" > $TMP_MAIL_BODY_FILE if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then echo "Please wstool update workspace manually.\n" >> $TMP_MAIL_BODY_FILE fi From 62af4c2ab84fc84595d6e4661ffb2522bce7ae87 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 19 Jun 2023 16:04:45 +0900 Subject: [PATCH 399/433] [jsk_robot_startup] Escape single quote, double quote, and comma, which have bad effects on rostopic pub --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 3656f4557b..61f259b844 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -90,7 +90,8 @@ WSTOOL_STATUS=$(wstool status -t $WORKSPACE/src) if [ -n "$WSTOOL_STATUS" ]; then echo -e "Please commit robot internal change and send pull request.\n" >> $TMP_MAIL_BODY_FILE echo -e $WSTOOL_STATUS >> $TMP_MAIL_BODY_FILE - wstool diff -t $WORKSPACE/src # rostopic pub fail when wstool diff has single quote or double quotes + # escape " ' , -- and add change line code to end of line + wstool diff -t $WORKSPACE/src | sed -e "s/'/ /g" -e "s/^--/ /g" -e 's/"/ /g' -e "s/
      /\\\n/" -e 's/$/
      /g' -e "s/,/ /g" | tee -a $TMP_MAIL_BODY_FILE fi if [ "${UPDATE_WORKSPACE}" == "true" ]; then wstool foreach -t $WORKSPACE/src --git 'git stash' From 27ffa4fe5073b8b5f0557fef92804a8f6a57f998 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 19 Jun 2023 16:06:21 +0900 Subject: [PATCH 400/433] [jsk_robot_startup] Use html to change line at mail body --- .../scripts/update_workspace_main.sh | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 61f259b844..494c7fa795 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -62,15 +62,15 @@ do done if [ "$WORKSPACE" = "" ]; then - echo "Please set valid workspace -w $WORKSPACE" + echo "Please set valid workspace -w $WORKSPACE
      " exit 1 fi if [ "$ROSINSTALL" = "" ]; then - echo "Please set valid rosinstall -r $ROSINSTALL" + echo "Please set valid rosinstall -r $ROSINSTALL
      " exit 1 fi if [ "$ROBOT_TYPE" = "" ]; then - echo "Please set valid robot type -t $ROBOT_TYPE" + echo "Please set valid robot type -t $ROBOT_TYPE
      " exit 1 fi @@ -88,7 +88,7 @@ echo "" > $TMP_MAIL_BODY_FILE wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' WSTOOL_STATUS=$(wstool status -t $WORKSPACE/src) if [ -n "$WSTOOL_STATUS" ]; then - echo -e "Please commit robot internal change and send pull request.\n" >> $TMP_MAIL_BODY_FILE + echo -e "Please commit robot internal change and send pull request.
      " >> $TMP_MAIL_BODY_FILE echo -e $WSTOOL_STATUS >> $TMP_MAIL_BODY_FILE # escape " ' , -- and add change line code to end of line wstool diff -t $WORKSPACE/src | sed -e "s/'/ /g" -e "s/^--/ /g" -e 's/"/ /g' -e "s/
      /\\\n/" -e 's/$/
      /g' -e "s/,/ /g" | tee -a $TMP_MAIL_BODY_FILE @@ -123,13 +123,13 @@ catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then - echo "Please wstool update workspace manually.\n" >> $TMP_MAIL_BODY_FILE + echo "Please wstool update workspace manually.
      " >> $TMP_MAIL_BODY_FILE fi if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then - echo "Please install dependencies manually.\n" >> $TMP_MAIL_BODY_FILE + echo "Please install dependencies manually.
      " >> $TMP_MAIL_BODY_FILE fi if [ $CATKIN_BUILD_RESULT -ne 0 ]; then - echo "Please catkin build workspace manually.\n" >> $TMP_MAIL_BODY_FILE + echo "Please catkin build workspace manually.
      " >> $TMP_MAIL_BODY_FILE fi set +x } 2>&1 | tee $LOGFILE @@ -148,7 +148,7 @@ if [ -n "$MAIL_BODY" ] && [ "${SEND_MAIL}" == "true" ]; then frame_id: '' subject: 'Daily workspace update fails' body: -- {type: 'text', message: '${MAIL_BODY}', file_path: '', img_data: '', img_size: 0} +- {type: 'html', message: '${MAIL_BODY}', file_path: '', img_data: '', img_size: 0} sender_address: '$(hostname)@jsk.imi.i.u-tokyo.ac.jp' receiver_address: '$ROBOT_TYPE@jsk.imi.i.u-tokyo.ac.jp' smtp_server: '' From 84c53ce01fcabc3d0cce3d807c1a0850cbf9992c Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 19 Jun 2023 16:08:52 +0900 Subject: [PATCH 401/433] [jsk_robot_startup] Use bold to easy to read mail text --- .../jsk_robot_startup/scripts/update_workspace_main.sh | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh index 494c7fa795..bb8fbba094 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh +++ b/jsk_robot_common/jsk_robot_startup/scripts/update_workspace_main.sh @@ -88,7 +88,7 @@ echo "" > $TMP_MAIL_BODY_FILE wstool foreach -t $WORKSPACE/src --git 'git fetch origin --prune' WSTOOL_STATUS=$(wstool status -t $WORKSPACE/src) if [ -n "$WSTOOL_STATUS" ]; then - echo -e "Please commit robot internal change and send pull request.
      " >> $TMP_MAIL_BODY_FILE + echo -e "Please commit robot internal change and send pull request.

      " >> $TMP_MAIL_BODY_FILE echo -e $WSTOOL_STATUS >> $TMP_MAIL_BODY_FILE # escape " ' , -- and add change line code to end of line wstool diff -t $WORKSPACE/src | sed -e "s/'/ /g" -e "s/^--/ /g" -e 's/"/ /g' -e "s/
      /\\\n/" -e 's/$/
      /g' -e "s/,/ /g" | tee -a $TMP_MAIL_BODY_FILE @@ -123,13 +123,13 @@ catkin build --continue-on-failure CATKIN_BUILD_RESULT=$? # Send mail if [ $WSTOOL_UPDATE_RESULT -ne 0 ]; then - echo "Please wstool update workspace manually.
      " >> $TMP_MAIL_BODY_FILE + echo "Please wstool update workspace manually.
      " >> $TMP_MAIL_BODY_FILE fi if [ $ROSDEP_INSTALL_RESULT -ne 0 ]; then - echo "Please install dependencies manually.
      " >> $TMP_MAIL_BODY_FILE + echo "Please install dependencies manually.
      " >> $TMP_MAIL_BODY_FILE fi if [ $CATKIN_BUILD_RESULT -ne 0 ]; then - echo "Please catkin build workspace manually.
      " >> $TMP_MAIL_BODY_FILE + echo "Please catkin build workspace manually.
      " >> $TMP_MAIL_BODY_FILE fi set +x } 2>&1 | tee $LOGFILE From c15351b57d1a0f92c51c8a2be747c5f803307597 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 23 Jun 2023 11:14:27 +0900 Subject: [PATCH 402/433] Revert "[Fetch] Fix comment develop/fetch --> master" This reverts commit 1cddbe050e2e7832f9ae0fa5fd6e4ed37a0c8bcf. Revert "[Fetch] Switch branch of jsk_pr2eus to develop/fetch" This reverts commit b8041d2746767a8da5ddd2566f6a2510663ebd7e. --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 3e43c99a28..08e5b87b75 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -60,17 +60,11 @@ local-name: jsk-ros-pkg/jsk_demos uri: https://github.com/jsk-ros-pkg/jsk_demos.git version: master -# we need to use the development branch until PR below are merged. -# - https://github.com/jsk-ros-pkg/jsk_pr2eus/pull/495 # we need to use the development branch until the next release. -# - git: -# local-name: jsk-ros-pkg/jsk_pr2eus -# uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git -# version: master - git: local-name: jsk-ros-pkg/jsk_pr2eus uri: https://github.com/jsk-ros-pkg/jsk_pr2eus.git - version: develop/fetch + version: master # we need to use the development branch until the next release. - git: local-name: jsk-ros-pkg/jsk_recognition From 5aa87b00aa321ba47c0e11d35792b43dc7d10b04 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 26 Jun 2023 16:07:14 +0900 Subject: [PATCH 403/433] [jsk_fetch_startup][jsk_fetch_robot] add esp_now_ros to launch --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 5 +++++ jsk_fetch_robot/jsk_fetch_startup/config/config.bash | 2 ++ .../jsk_fetch_startup/launch/fetch_bringup.launch | 8 ++++++++ 3 files changed, 15 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 08e5b87b75..71db5a428f 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -185,3 +185,8 @@ local-name: BehaviorTree/BehaviorTree.ROS uri: https://github.com/BehaviorTree/BehaviorTree.ROS version: master +# we need this for smart device ros system +- git: + local-name: sktometometo/esp_now_ros + uri: https://github.com/sktometometo/esp_now_ros.git + version: v0.1.0 diff --git a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash index 4ce9b16dc8..1ce371abbf 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/config/config.bash +++ b/jsk_fetch_robot/jsk_fetch_startup/config/config.bash @@ -47,4 +47,6 @@ elif [ $(hostname) = 'fetch1075' ]; then export NETWORK_DEFAULT_PROFILE_ID="sanshiro-73B2"; export AUDIO_DEVICE="alsa_output.usb-SEEED_ReSpeaker_4_Mic_Array__UAC1.0_-00.analog-stereo" + + export SMART_DEVICE_PORT=/dev/ttyACM0 fi diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index 8760cc5f0e..cdef8e6b09 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -47,6 +47,7 @@ + @@ -422,6 +423,13 @@
      + + + + + + + Date: Tue, 27 Jun 2023 15:12:07 +0900 Subject: [PATCH 404/433] [Fetch] Use bugfix branch of executive_smach_visualization --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 71db5a428f..0ae3e5a75d 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -151,10 +151,16 @@ uri: https://github.com/jsk-ros-pkg/coral_usb_ros.git version: master # we need melodic-devel branch for headless visualization +# - git: +# local-name: ros-visualization/executive_smach_visualization +# uri: https://github.com/ros-visualization/executive_smach_visualization.git +# version: master +# UnicodeDecodeError is output without the following PR +# https://github.com/ros-visualization/executive_smach_visualization/pull/54 - git: local-name: ros-visualization/executive_smach_visualization - uri: https://github.com/ros-visualization/executive_smach_visualization.git - version: melodic-devel + uri: https://github.com/tkmtnt7000/executive_smach_visualization.git + version: fix-pickle-loads-python-version # we need this for eus10 and roseus_resume - git: local-name: euslisp/Euslisp From bc4ed34bc0bf532903e3cf3c65662530db63e2dd Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 27 Jun 2023 16:29:38 +0900 Subject: [PATCH 405/433] [jsk_fetch_robot] update esp_now_ros version to v0.2.0 --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 0ae3e5a75d..3d91fb7c09 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -195,4 +195,4 @@ - git: local-name: sktometometo/esp_now_ros uri: https://github.com/sktometometo/esp_now_ros.git - version: v0.1.0 + version: v0.2.0 From 5b521c5ef9885d8d4d2eb964a9b4da6f9da51bf8 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 27 Jun 2023 17:16:38 +0900 Subject: [PATCH 406/433] Add enr_message_board capability to kitchen demo (#1830) * [jsk_fetch_startup] add write-message-on-message-board to navigation-utils.l * [jsk_fetch_startup] Use write-message-on-message-board in kitchen-demo * Update jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l add package existence check for esp_now_ros Co-authored-by: Naoto Tsukamoto * [jsk_fetch_startup] publish dummy packet before write message on message board * Add more message and debug output * [jsk_fetch_startup] fix error * [jsk_fetch_starup] get rid of dummy message writing * [jsk_fetch_startup] Change enr_message_board address --------- Co-authored-by: Naoto Tsukamoto --- .../euslisp/navigation-utils.l | 49 +++++++++++++++++++ 1 file changed, 49 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l index aa4be969f5..2ed7414721 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l +++ b/jsk_fetch_robot/jsk_fetch_startup/euslisp/navigation-utils.l @@ -8,6 +8,8 @@ (ros::load-ros-manifest "jsk_recognition_msgs") (ros::load-ros-manifest "power_msgs") (ros::load-ros-manifest "sensor_msgs") +(if (ros::rospack-find "esp_now_ros") + (ros::load-ros-manifest "esp_now_ros")) (defparameter *dock-action* nil) (defparameter *undock-action* nil) @@ -427,6 +429,12 @@ Args: (label-names (if msg (send msg :label_names)))) (when label-names (ros::ros-info (format nil "Notify app that ~A is found." label-names)) + (write-message-on-message-board + (list 120 33 132 149 126 152) + (format nil "Notify app that ~A is found." label-names) + (ros::time 600) + (ros::get-param "/robot/name" "default_name") + ) (notify-app "object recognition" (send msg :header :stamp) location @@ -455,6 +463,12 @@ Args: (when occupancy (ros::ros-info (format nil "Notify app that the occupancy of trash can is measured. ~A." occupancy)) + (write-message-on-message-board + (list 120 33 132 149 126 152) + (format nil "~A Trashcan occupancy is ~A" notify-text occupancy) + (ros::time 600) + (ros::get-param "/robot/name" "default_name") + ) (notify-app "trashcan occupancy" (ros::time-now) location @@ -654,4 +668,39 @@ Args: (send *ri* :go-pos-unsafe 0 0 -80) ;; face the front against the trash can success-move-to-trashcan-front)) +(defun padding-byte-array (byte-array target-length) + (concatenate cons byte-array (make-list (- target-length (length byte-array)) :initial-element 0))) + +(defun write-message-on-message-board (target-addr message timeout-duration source-name) + "Send packet to write message on a message board. + + Args: + target-addr: list of integer to represent mac address of target message board. + message: string + timeout-duration: ros::time to represent message timoeut + source-name: string + " + (let* ((packet-type-array (list 42 0)) + (source-name-array (padding-byte-array (coerce source-name cons) 64)) + (timeout-duration-msec (floor (* 1000 (send timeout-duration :to-sec)))) + (timeout-duration-array + (mapcar + #'(lambda (order) + (/ + (- timeout-duration-msec + (* (round (expt 256 (+ 1 order))) (/ timeout-duration-msec (round (expt 256 (+ 1 order)))))) + (round (expt 256 order)))) + '(0 1 2 3 4 5 6 7) + )) + (message-array (padding-byte-array (coerce message cons) 64)) + (byte-data (concatenate cons packet-type-array source-name-array timeout-duration-array message-array)) + (msg (instance esp_now_ros::Packet :init + :mac_address (coerce target-addr string) + :data (coerce byte-data string))) + ) + (ros::advertise "/esp_now_ros/send" esp_now_ros::Packet 1) + (ros::publish "/esp_now_ros/send" msg) + (ros::ros-info "Write message ~A to board ~A" message target-addr) + ) + ) From 108b56b6691fb3d70e3696775717d0056251cc48 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Wed, 28 Jun 2023 10:25:26 +0900 Subject: [PATCH 407/433] Revert "[Fetch] Use bugfix branch of executive_smach_visualization" This reverts commit 3ab128325e7bf31bdaf05cbd4a10ed1dd901ce59. --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 3d91fb7c09..d7ca64262f 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -151,16 +151,10 @@ uri: https://github.com/jsk-ros-pkg/coral_usb_ros.git version: master # we need melodic-devel branch for headless visualization -# - git: -# local-name: ros-visualization/executive_smach_visualization -# uri: https://github.com/ros-visualization/executive_smach_visualization.git -# version: master -# UnicodeDecodeError is output without the following PR -# https://github.com/ros-visualization/executive_smach_visualization/pull/54 - git: local-name: ros-visualization/executive_smach_visualization - uri: https://github.com/tkmtnt7000/executive_smach_visualization.git - version: fix-pickle-loads-python-version + uri: https://github.com/ros-visualization/executive_smach_visualization.git + version: melodic-devel # we need this for eus10 and roseus_resume - git: local-name: euslisp/Euslisp From c22ed40d1f086fa3f4b2e7486b582519fb077d98 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 29 Jun 2023 16:45:37 +0900 Subject: [PATCH 408/433] [jsk_fetch_startup] Add TimeSignal.cfg --- jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg | 11 +++++++++++ 1 file changed, 11 insertions(+) create mode 100644 jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg diff --git a/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg b/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg new file mode 100644 index 0000000000..e22d48bc1e --- /dev/null +++ b/jsk_fetch_robot/jsk_fetch_startup/cfg/TimeSignal.cfg @@ -0,0 +1,11 @@ +#! /usr/bin/env python + + +from dynamic_reconfigure.parameter_generator_catkin import * + +PACKAGE = 'jsk_fetch_startup' + +gen = ParameterGenerator() +gen.add("volume", double_t, 0, "Volume of sound.", 1.0, 0.0, 1.0) + +exit(gen.generate(PACKAGE, PACKAGE, "TimeSignal")) From 016e764b24a4eb69db42e60fa9b7b9230aec0a0c Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 29 Jun 2023 16:46:12 +0900 Subject: [PATCH 409/433] [jsk_fetch_startup] Add dynamic_reconfigure to dependency --- jsk_fetch_robot/jsk_fetch_startup/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/package.xml b/jsk_fetch_robot/jsk_fetch_startup/package.xml index 70d3f9eda9..f83da9e637 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/package.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/package.xml @@ -12,7 +12,9 @@ catkin fetch_teleop + dynamic_reconfigure + dynamic_reconfigure image_proc jsk_fetch_accessories jsk_fetch_diagnosis From e6a3526d77d002a9a01c2e9bf32c40cf01d48899 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 29 Jun 2023 16:46:42 +0900 Subject: [PATCH 410/433] [jsk_fetch_startup] Enable dynamic_recongiure --- jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt index 96d03f10ea..41d435037b 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt +++ b/jsk_fetch_robot/jsk_fetch_startup/CMakeLists.txt @@ -11,6 +11,7 @@ endif() ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## is used, also find other catkin packages find_package(catkin REQUIRED COMPONENTS + dynamic_reconfigure roscpp std_msgs sensor_msgs @@ -24,10 +25,16 @@ find_package(catkin REQUIRED COMPONENTS ) find_package(Boost REQUIRED COMPONENTS) +generate_dynamic_reconfigure_options( + cfg/TimeSignal.cfg +) + ################################### ## catkin specific configuration ## ################################### -catkin_package() +catkin_package( + CATKIN_DEPENDS dynamic_reconfigure +) catkin_add_env_hooks(99.jsk_fetch_startup SHELLS bash zsh sh DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/env-hooks) From cd0e41fa7edeebd5c2c896ac0f10ecc01cb9b811 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Thu, 29 Jun 2023 16:45:09 +0900 Subject: [PATCH 411/433] [jsk_fetch_startup] Set volume dynamically in time_signal.py --- .../jsk_fetch_startup/scripts/time_signal.py | 22 +++++++++++++++++-- 1 file changed, 20 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py index 321714985a..083e12c658 100755 --- a/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py +++ b/jsk_fetch_robot/jsk_fetch_startup/scripts/time_signal.py @@ -8,12 +8,14 @@ import sys import urllib2 +from dynamic_reconfigure.server import Server +from jsk_fetch_startup.cfg import TimeSignalConfig as Config from sound_play.msg import SoundRequestAction from sound_play.msg import SoundRequestGoal class TimeSignal(object): - def __init__(self): + def __init__(self, volume=1.0): self.client_en = actionlib.SimpleActionClient( '/sound_play', SoundRequestAction) self.client_jp = actionlib.SimpleActionClient( @@ -23,6 +25,8 @@ def __init__(self): self.now_hour = self.now_time.hour self.now_minute = self.now_time.minute self.day = self.now_time.strftime('%a') + self.volume = volume + self.srv = Server(Config, self.config_callback) reload(sys) sys.setdefaultencoding('utf-8') api_key_file = rospy.get_param( @@ -35,7 +39,7 @@ def speak(self, client, speech_text, lang=None): sound_goal = SoundRequestGoal() sound_goal.sound_request.sound = -3 sound_goal.sound_request.command = 1 - sound_goal.sound_request.volume = 1.0 + sound_goal.sound_request.volume = self.volume if lang is not None: sound_goal.sound_request.arg2 = lang sound_goal.sound_request.arg = speech_text @@ -153,6 +157,20 @@ def _get_weather_forecast(self, lang='en'): forecast_text += " The wind speed is {} meter per second.".format(wind_speed) return forecast_text + def _set_volume(self, volume): + ''' + Set speak volume between 0.0 and 1.0 + ''' + volume = min(max(0.0, volume), 1.0) + if self.volume != volume: + self.volume = volume + rospy.loginfo("time_signal's volume was set to {}".format( + self.volume)) + + def config_callback(self, config, level): + self._set_volume(config.volume) + return config + if __name__ == '__main__': rospy.init_node('time_signal') From 00eab7aeae4485dab9dfa1038754a5026b6590f2 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 3 Jul 2023 11:33:39 +0900 Subject: [PATCH 412/433] [jsk_robot_startup] Add time_signal to auto speak volume control app --- .../jsk_robot_startup/lifelog/auto_speak_volume_lower.l | 1 + .../jsk_robot_startup/lifelog/auto_speak_volume_reset.l | 1 + .../jsk_robot_startup/lifelog/auto_speak_volume_zero.l | 1 + 3 files changed, 3 insertions(+) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l index 48c236a58c..6696fe3f16 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_lower.l @@ -11,4 +11,5 @@ (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.2) (ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.2) (ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.2) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 0.2) (exit) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l index a57c51c262..315e9151af 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_reset.l @@ -11,4 +11,5 @@ (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 1.0) (ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 1.0) (ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 1.0) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 1.0) (exit) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l index e0bb7d2c43..39c58b530e 100755 --- a/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l +++ b/jsk_robot_common/jsk_robot_startup/lifelog/auto_speak_volume_zero.l @@ -11,4 +11,5 @@ (ros::set-dynamic-reconfigure-param "/tweet_client_uptime" "volume" :double 0.0) (ros::set-dynamic-reconfigure-param "/tweet_client_warning" "volume" :double 0.0) (ros::set-dynamic-reconfigure-param "/tweet_client_worktime" "volume" :double 0.0) +(ros::set-dynamic-reconfigure-param "/time_signal" "volume" :double 0.0) (exit) From d53930a6f6d3352c35e23bc575a48b25b7400645 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 3 Jul 2023 12:06:40 +0900 Subject: [PATCH 413/433] [Fetch] Use run-name-entry-fetch15 branch in app_manager --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index d7ca64262f..3cdd4ee529 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -5,10 +5,12 @@ # https://github.com/PR2/app_manager/pull/50 # In order to run multiple app_managers in one master, we need this PR # https://github.com/PR2/app_manager/pull/54 +# This PR add run_name entry to specif node name when we use run entry +# https://github.com/PR2/app_manager/pull/64 - git: local-name: PR2/app_manager - uri: https://github.com/knorth55/app_manager.git - version: fetch15 + uri: https://github.com/tkmtnt7000/app_manager.git + version: add-run-name-entry-fetch15 # we need this for proximity sensors - git: local-name: RoboticMaterials/FA-I-sensor From f6ea30c509b679bda1456ac3dee177157fa5cc8f Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Mon, 3 Jul 2023 12:07:08 +0900 Subject: [PATCH 414/433] [jsk_fetch_startup] Add run_name to time_signal.py to specify node name --- .../jsk_fetch_startup/apps/time_signal/time_signal.app | 2 ++ 1 file changed, 2 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app index 6137ee226b..e82fe5629f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app +++ b/jsk_fetch_robot/jsk_fetch_startup/apps/time_signal/time_signal.app @@ -1,6 +1,8 @@ display: Speak time signal platform: fetch run: jsk_fetch_startup/time_signal.py +run_name: "time_signal" +# run_name needs https://github.com/PR2/app_manager/pull/64 interface: jsk_fetch_startup/time_signal.interface icon: jsk_fetch_startup/time_signal.png timeout: 120 From d2aeb9c87e9d89866a106ae8da49774a25944bbc Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 12 Jul 2023 17:24:12 +0900 Subject: [PATCH 415/433] [jsk_robot_startup] Fix mongodb_replicate_on_write param --- jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch index 7f7af07807..2a60fe5e16 100644 --- a/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch +++ b/jsk_robot_common/jsk_robot_startup/lifelog/mongodb.launch @@ -16,6 +16,7 @@ + @@ -26,7 +27,6 @@ output="screen" machine="$(arg machine)"> extra_collections: $(arg extra_collections) - replicate_on_write: $(arg replicate_on_write) From a369716a0dce30eff1d0486869877660acd8341f Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Fri, 22 Sep 2023 12:22:28 +0900 Subject: [PATCH 416/433] [jsk_fetch_startup] Use pubsub mode in google chat ros --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index cdef8e6b09..1d6c89734e 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -200,7 +200,7 @@ - + From 0cd411839a05ee236e8aeb55c0fd93ff917d8b20 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Wed, 11 Oct 2023 23:39:20 +0900 Subject: [PATCH 417/433] [jsk_fetch_robot] update esp_now_ros version to v0.4.0 --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 3cdd4ee529..955cac07a4 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -191,4 +191,4 @@ - git: local-name: sktometometo/esp_now_ros uri: https://github.com/sktometometo/esp_now_ros.git - version: v0.2.0 + version: v0.4.0 From c7401adcae4a6bb7721f64b557ec53af01317f49 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Tue, 25 Apr 2023 20:45:03 +0900 Subject: [PATCH 418/433] add sample launch code for database_talker --- .../launch/interaction.launch | 50 +++++++ .../jsk_robot_startup/launch/lifelog.launch | 137 ++++++++++++++++++ .../lifelog/lifelog_rgb_image.launch | 19 +++ 3 files changed, 206 insertions(+) create mode 100644 jsk_robot_common/jsk_robot_startup/launch/interaction.launch create mode 100644 jsk_robot_common/jsk_robot_startup/launch/lifelog.launch create mode 100644 jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch diff --git a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch new file mode 100644 index 0000000000..8c9a76c6c3 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch new file mode 100644 index 0000000000..b2645516d2 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -0,0 +1,137 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + approximate_sync: true + topics: + - /publish_trigger_mongodb_event + - $(arg image)/compressed + + + + + + + + + + + + + + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch b/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch new file mode 100644 index 0000000000..6f0f1e4a28 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/lifelog/lifelog_rgb_image.launch @@ -0,0 +1,19 @@ + + + + + + + + + + + + enable_monitor: false + vital_check: false + + + From 77a922feeab4902605fe971cb5bae4ad557a5769 Mon Sep 17 00:00:00 2001 From: Kei Okada Date: Fri, 28 Apr 2023 18:18:50 +0900 Subject: [PATCH 419/433] use override_project_id, to work with latest commit of https://github.com/jsk-ros-pkg/jsk_3rdparty/pull/460/commits/58b852e03b6167ad33daa990a91c368dd1546b1f --- jsk_robot_common/jsk_robot_startup/launch/interaction.launch | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch index 8c9a76c6c3..338b246d11 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch @@ -1,6 +1,7 @@ + @@ -12,7 +13,8 @@ - + + From 5b94a6cc0fecf78b53ee7f6310bf21856d043dab Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Wed, 31 May 2023 18:51:26 +0900 Subject: [PATCH 420/433] Adopt to fetch1075 default environment Author: Naoto Tsukamoto --- .../launch/interaction.launch | 9 ++++--- .../jsk_robot_startup/launch/lifelog.launch | 17 +++++++----- .../launch/sample_database_talker.launch | 27 +++++++++++++++++++ 3 files changed, 43 insertions(+), 10 deletions(-) create mode 100644 jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch diff --git a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch index 338b246d11..06ca7361cd 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch @@ -10,11 +10,14 @@ + + + - + - + @@ -35,7 +38,7 @@ - + diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch index b2645516d2..ab1123512b 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -18,11 +18,14 @@ + + + - + @@ -75,12 +78,12 @@ args="--wait-for-start $(arg image)/output/compressed /publish_trigger_mongodb_event std_msgs/Header 'std_msgs.msg.Header(stamp=m.header.stamp, frame_id=m._connection_header["callerid"])' --import std_msgs" /> - - + + + + + + diff --git a/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch new file mode 100644 index 0000000000..44540e981b --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + From 132109c32df7ea0883d2e2c62f64c1ad8d77eec8 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 15:52:52 +0900 Subject: [PATCH 421/433] [jsk_robot_startup] Add override_project_id true --- jsk_robot_common/jsk_robot_startup/launch/interaction.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch index 06ca7361cd..0b3487d7c2 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/interaction.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/interaction.launch @@ -27,6 +27,7 @@ + From a8014fdac77ac6d1563160e31d478ee1fa69f5dc Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 15:57:38 +0900 Subject: [PATCH 422/433] [jsk_robot_startup] Add launch_common_logger arg to disable launching common logger --- jsk_robot_common/jsk_robot_startup/launch/lifelog.launch | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch index ab1123512b..ab1a30fe52 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -19,6 +19,7 @@ + @@ -42,7 +43,7 @@ - + From ec86b97fb0c1ff7a784e127b241f314db47a55de Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 18:17:21 +0900 Subject: [PATCH 423/433] [jsk_robot_startup] save_speech and save_google_chat false --- jsk_robot_common/jsk_robot_startup/launch/lifelog.launch | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch index ab1a30fe52..7f2146b68d 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -15,11 +15,13 @@ + + - - + + @@ -55,6 +57,8 @@ + + From 4ac1afbdb0195d36245c6b51093fdb7a6b573234 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 18:17:41 +0900 Subject: [PATCH 424/433] [jsk_robot_startup] Comment out lifelog.launch --- .../launch/sample_database_talker.launch | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch index 44540e981b..6313364c0d 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/sample_database_talker.launch @@ -1,14 +1,13 @@ - - - - - - - - - - + + + + + + + + + From 69d7472fee82d4c4af7cbd0a3abd377b48291d30 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 18:20:03 +0900 Subject: [PATCH 425/433] [jsk_fetch_startup] Launch lifelog.launch as default --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index 3e80d8de9e..e3fc3e9cab 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -80,4 +80,9 @@ - sound_play/SoundRequestActionGoal - sound_play/SoundRequestActionResult + + + + + From af11550263d872e07e1229885c45e879a25e4307 Mon Sep 17 00:00:00 2001 From: Naoto Tsukamoto Date: Wed, 25 Oct 2023 18:52:26 +0900 Subject: [PATCH 426/433] [jsk_robot_startup][jsk_fetch_startup ] Change nodelet name to adjust existing nodelet --- .../jsk_fetch_startup/launch/fetch_lifelog.xml | 1 + jsk_robot_common/jsk_robot_startup/launch/lifelog.launch | 8 +++++--- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml index e3fc3e9cab..4c61e45da8 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_lifelog.xml @@ -83,6 +83,7 @@ + diff --git a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch index 7f2146b68d..ee310515ba 100644 --- a/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch +++ b/jsk_robot_common/jsk_robot_startup/launch/lifelog.launch @@ -23,6 +23,8 @@ + + @@ -63,7 +65,7 @@ - + @@ -102,7 +104,7 @@ + args="load jsk_topic_tools/SynchronizedThrottle $(arg manager)" > approximate_sync: true topics: @@ -116,7 +118,7 @@ - + From d8231420291021a809c7cc085bf9fc3133e74d37 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 16 Oct 2023 00:18:14 +0900 Subject: [PATCH 427/433] [jsk_fetch_robot] add noetic version of robot_localization to rosinstall --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 955cac07a4..870546a1e8 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -192,3 +192,9 @@ local-name: sktometometo/esp_now_ros uri: https://github.com/sktometometo/esp_now_ros.git version: v0.4.0 +# melodic version of robot_localization causes TF_REPEATED_DATA Errors to noetic client +# So we have to use noetic-devel of robot_localization +- git: + local-name: cra-ros-pkg/robot_localization + uri: https://github.com/cra-ros-pkg/robot_localization.git + version: noetic-devel From fc4b059cf70abd1d95cdd418b31d0ca6e5a0b00b Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Mon, 16 Oct 2023 00:18:49 +0900 Subject: [PATCH 428/433] [jsk_fetch_startup] set permit_corrected_publication to true --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index 16dea4af56..a3f3529442 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -111,7 +111,12 @@ false, false, false] odom0_nodelay: true odom0_differential: true + permit_corrected_publication: true + From 44223c2e5a481e7a3f56fa421782da2cfd437cde Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 2 Nov 2023 10:30:00 +0900 Subject: [PATCH 429/433] [jsk_fetch_robot] use 2.6.9-suppress version of robot_localization for adopt https://github.com/cra-ros-pkg/robot_localization/pull/595 --- jsk_fetch_robot/jsk_fetch.rosinstall.melodic | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic index 870546a1e8..4fc3e3e074 100644 --- a/jsk_fetch_robot/jsk_fetch.rosinstall.melodic +++ b/jsk_fetch_robot/jsk_fetch.rosinstall.melodic @@ -193,8 +193,9 @@ uri: https://github.com/sktometometo/esp_now_ros.git version: v0.4.0 # melodic version of robot_localization causes TF_REPEATED_DATA Errors to noetic client -# So we have to use noetic-devel of robot_localization +# So we have to adopt https://github.com/cra-ros-pkg/robot_localization/pull/595 (Using noetic-devel causes some localization trouble) +# After https://github.com/cra-ros-pkg/robot_localization/pull/840 has been merged, we can use upstream melodic-devel branch - git: local-name: cra-ros-pkg/robot_localization - uri: https://github.com/cra-ros-pkg/robot_localization.git - version: noetic-devel + uri: https://github.com/mqcmd196/robot_localization.git + version: 2.6.9-suppress From 23037dbfe66757052074a8109ab61875a73c3a4c Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Thu, 2 Nov 2023 11:36:43 +0900 Subject: [PATCH 430/433] [jsk_fetch_startup] set permit_corrected_publication false by default --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch index a3f3529442..f06beff91f 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch.launch @@ -111,7 +111,7 @@ false, false, false] odom0_nodelay: true odom0_differential: true - permit_corrected_publication: true + permit_corrected_publication: false - + From 0c5c3ad5487aec67902177091a80a818e02e7865 Mon Sep 17 00:00:00 2001 From: JSK fetch user Date: Tue, 9 Jan 2024 16:55:36 +0900 Subject: [PATCH 432/433] [jsk_fetch_startup] add smart_devicE_protocol udev --- jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules | 3 +++ 1 file changed, 3 insertions(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules index ef16f14591..f80fad6045 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules +++ b/jsk_fetch_robot/jsk_fetch_startup/udev_rules/80-arduino.rules @@ -5,3 +5,6 @@ SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", SYMLINK+="a # The following device is for arduino nano every in nakane hand version 1 # Please update idVendor and idProduct if you use a different microcontroller SUBSYSTEM=="tty", ATTRS{idVendor}=="2341", ATTRS{idProduct}=="0058", SYMLINK+="nakane_hand", MODE="0666" + +# The following device is for M5Atom S3 for smart device protocol interface by k-shinjo 2024/1/9 +SUBSYSTEM=="tty", ATTRS{idVendor}=="303A", ATTRS{idProduct}=="1001", SYMLINK+="smart_device_protocol_interface", MODE="0666" From cbaeb70432424b359785f5400e541f8911351e19 Mon Sep 17 00:00:00 2001 From: Koki Shinjo Date: Tue, 9 Jan 2024 19:26:49 +0900 Subject: [PATCH 433/433] [jsk_fetch_startup] add tag_id for sdp --- jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch index cc9e267077..539974b2b4 100644 --- a/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch +++ b/jsk_fetch_robot/jsk_fetch_startup/launch/fetch_bringup.launch @@ -427,6 +427,7 @@ +

      E}MV#csMm2Lm=8!0D~ba@9!+Ze)xV@lrTo+>Me3@U})&z zZxw5&hM36wiLL>8Vr{qyxw1{K?;IL=f1BgKSHP?NG(~|? zy+=I8-q@)A2?20sDlrN7RcpYY+w77N@ksXgJY!fhSm$+ITwT#U#}1gm?ZtyTngsA% zpeMY3gXmc@T-UzvWxsAEfb#yyiw zXndG35Y3c+)WkMdx^A_D>??1R zrMRsp@y!ez0Vk7<+*HP7N)j*Bnc~!$V9e=A+t*gh+P)Yj<_HsWo`z@>M}m{FH`J)6 z23ZfMh#&K?c3;@>Ow^d^Cgb8nwDu$BVnD7|-b3ZO(7kxd z8g#Cg2PriTbvrU7zqhh-gy)2n!93p`9JmkdxES9hZ!!NT5!J|XdQMjDx1ag6+P>hS z{&V+Y?oG0`k2WpY^W8fkU8aeV8{{l3PR?ngM}af=Bd%_6l9I>V)o0C8N~<1)y7z;I6+L=({H_I3zHtqb zy4$(1de<8)Y_? zP+RnT;NJ$J4(5R)eI=itVrxusG)HmRD?WOW7u#IGZXRhkw9rffbDJZVQV-8lc7Pj_u;$ zyJfn0K~L0V0Mtq2K@E zLpVrVJWx!a$Om2-n!#=`+6kLP5dmkeUMjd6r^ z^+e(EOGw0@o<0M7On|zz^6w4p{HiKKI-@YKP*O!Rf>EU$(WVCMwMy}h@g7}Y3rV{$ zgS?-`7ZBUxgVaqR1p1x37cd%Fr689S6cu4xO>))mW{GLVkp5XVIg&599v{66v;2M9 z+#W5b_Npgmnwi$Jl_En*mT1WLJ&C||p+|B>L9a-WAIp`K+Dj0;dulpp^9jv|Gi^3%himM{ z#~q#A2I_1n@`G3S9i4L`q6b(Vb*8awJfVl4bxw0h@WB-;2KF~UOJ1xWo7d}^E=&t zVgt|c*&X|ZU0%YQONz1+YszI=(k?##AbcfO z_+V`}Et=jPgd#@mwSz9Jl>yJRKsH=TL$SgG8b4h-IJqkw@6vIe)-@^9cKQ}X=>7$* z@xMR*sT+R#z1CK_y=t4uA)SQ8&sT)D{6V+4L!+BF1Tc}69B*Z@XT+&%{37e?JS5^j z?C$%~#3Z;~KY=UsNsX(+S@mp6<3a z@Eo^{yZRmHbSUoq6IETU^$Bku$mC2K97*Uw3Lc3yxcc8@XSdK>dG;5&0n>uph^WU8 z_01e_!X|DP8Wpdi*3hxkr$7G5rCRA>lW2eu23-9g0c2&Lq$Nf(a9dyOom7}C{U%bw z3Cug-y&)#a@9fOel=plb>40JrBTRq( z$0mJzxTVSlzV&&JgfaGS0s|}RDEl~s0?t_miFSX5|8TwWi9iGlXH_=!xZx$)cK?K8 z8Oddk()gb}fdbXooKZ}a z^4Gy_i?iqNBo6MqGY=%Bpb0h$Bk6|(hR_j83?=e9LTA$I60P!bqTdAZ7r#!O-nUOH z$L%ty{Z&TzXMO?8qlRo5>4~k$x>0LCkjH#>(+_@WQlU`nPpo9ILRDR@ODCGwm!dZy zy$saaZNOdkI&y=5Zq3ykSQ`y(b{Wn2-M5#ZI&&F8v*=n^RDf5C!N2Ob7t4~jR%TUkL2Gv*A z%X42{e2&&fmFLq9XWZ{oEv@R=Vyo_&7v|Dln8)zD&$j)7XO&Mm+RCoZs;?V?5nmC; zAHFuH_`M$Bu)P&xNq9m75@SD}Nt~Vy<_lnQ89k0d=f0J~%FH!t0A_+C-Ueic1eR}6 zkbKMWUYH(hpw*ak9jKyKHnbwUII~&=~wcUMsfwls?DX)WBf4aVN(< zzF@8ZC@5~ug1rwqt*Md<*q@1H`+`qQVMRr*W+|xiT{X(+*O+W594~`+@oS{PJ@I>& zg@uKa&VfYI8`2b_-T=%=Q$vFo_*H<*?Etj7S{ND*Dl03uusv8NCIMnFaR_|zk3cf| zA*f6y-Pze$Y;*$|l8H;9H-C-l>~KW!;SM=om~2czKq}Pt%^~kA?O>`CW3)AxuCQ+t zf>;~{G~flVvF4K^&v-+BvgZ9q^c+q;xxOStYbSM$2RUPf)zw7MZT(~0_2IBCx;=T~c{evVpitJm5KbFH#%fzy@_qwuoe(mBS&41Rcgh!q#7c6#T$z+3 zvWmO*8o?+~DRGJh_0uPZC$p9}!g~^~qo!iW0ZcxPrh|`1Rn-txxLdaN^q9~?I~uE# zAA#%s5rxK z?L_mvg)~VJH!7+`OgSzR!-sxwRK$Bw?%rcOuI>pcFo3qZduMi~Y!bFf!LY5YSyV5@$MWhUbxpSz^Ldeh&UE;q7#73}AFf=CJI14MJY7YYjvbta<=vLf5P zJc*e5a5b%pMfgUo?ysi<@powGbUH>}{qFb^&B)4)#t8I*gYvUN zw8KYNJ&0ryJT6YX4pq(lXIUJqra8F0j$cNJ{me>3$zkxJWij(9DWwS0@@Yg>aNb|& zk^7)OoT`JsC?7{J;9pKM?F>KqaqVQJS>u*GsJ@xBHpUxzFOzT*QQG z3C(QbyAJyPq27Sa;(sM7v50a&dU{Cm?gGZVMG z=hT!o;5`BQQ?9SJ&Q7vvCK2rTM#26FI~WTA=LO_bZn%4j z5!O`m1&RrnA?LmH_ra&6y|40BnBs|i_9}Cxd2CWtrS+ei2l`Tp6HepBlDhCdXIXAc z(al#FR1I2n=0p59h`XNta(=SQ@~UB>wS(*XB~_p2I-a|~EbEaCpti!}QRdUpo& zJdbYPnPrBXQmAvmg%ME}3$V-%e2Ce9<=ddwZ1rBx5?v6smh@j5(t{p-dyUEU58oP@ z7f3rtzWN|*?(bV`@WryR$KSn2Ou{|ihXXlY6&lhc6yvwe>Q}$af;{ybFuB zcm8MzDj8KY62OW{(O^Xp%jxv8EIyS`Z%uwW-%uWIhjzr2Q~W3yYkv?q!9XSE=Q;YF zXjv~$8rEnlCx?zzSZ?+;K1a}3=e-loOSj=jT|unx4;pPpfwT&G4DF$jbnhG8ak=l0 zhh$`T7UQjcqZSlR?kI(h7WB&VOU_g-ZWzT<#UhMm0cmd<8|jiSGKw*V&j7cx=q^!y z+rztiPVn~mA%<)4YB5gU3ogxFT-*mqcxugLG$TSy5sS>B;%g&u5MNZ=lt>dTVnO=f z)Fc1v@`%}b=YFP~%S-a+Kk&@uSCg%%rneBS2vSb0@S#fSOKoxj^~s9E*V9kWDM#{^ zd-$;Y)-)*1!|S!KaOmbQX@oS=tJLHW9^vH4Qm1pPh86+#rVk%R07Y+Xi=$NDD)TG{ zN>wLOslVACAcv=e;J-h`QU6|SYVfR@PrTDqWuQ>%0mkmz>5+aaapk_|Wn1f1X| zPMww35#kgc_6J}u$T`rwHFw=|L13!y@ISBtuB`~MO`}HFJM=U(k!}lOTSaO6>uFjO zi!I*8k8jJMwH{?~uUyR3fokt!Jx%eb1ZjR5jCBn^aElUR8T8Hd%3rA*A&Ey2&NV#; z51T{EDmXi(h$F!24JyvZJM}pgd*}xF5@`mBhU@ePy{2rFr5exP2JT)I&B|ek2oN&> zu>M!ZHuNXrp?)N`WqESa0LDn)@0AIGQf%xeu4q84(^xzn5MaD1LfhbHu_CSCr5bJ; zl44Wgtf%=oCVR&Ejxm)Ib)px$Fb}rqJ0!JnB&Fs23y-BBsS&Bo69(r#ufe=%a8H@~ zJ5G|R^woR5&(|O7A|>c>dh=uOv%NY^-2v9wVggN82~IEHvRKmgtzH`&DK&Npk6h@&@kI-WZxj0hsJ{xDKEJbMY|kCY>RwqT;Q8Hq}+LuU11?1`9I&;S!-l9c_cv zn-WoNnK?q|j%WKro6lA==$BsTjb8GpNWooxoD&9}{qz6`yCp_tUV_o!HnDRy{DnB5 zK$U&P&D+P1KF}ofyHyh{k68ZA{*xU}_(aMR>b&0IO$IS0FvX+J( zHV3I6AKdK1=+_#D{4hzjFLIS5D+`*WK`X}{aynT?)|UX`e5G0XI?IgWASZK#H&?D_ zg)get`nHf-voy{-2{6t;vp-=1>v@850B|o3MSQ}9%pUgx z-ufwB23FOljx&`8PJ87EJb$nV0LcNF-)lp)>70jl!gi~wE^O4ZA^w61$;Yz9DNyzhd1FP@l|Y7oHxQh zAXcU0Q;5XN^Q@BcYNOiKE`S;Btbt!~gbdrllOVCRk~ef^&1xm;)A65}3a0?U2Xd6~ zqA6IB&F^nnPq7}h#pZn`_*{BtETu6`@4b0}IS22vE8PqYd((=r2VS0mRPN41+0C>( z!||`6fvy&eVU;c~vEz>z*t4{Fzj9Sdl{~*r=XF<*WvtF^aCvPwbc7QSxuu%Ayus9% z?4pXWHx{?*TX}NTCw|X&td5&1n!`c9Ul^?`O-m|xx&VJT zlGSniV$9}9ZZXW-Zh4NC^U+YjolA7DkPSG^{WRVv??aOfGh)lz5d#Z1OyV@D;_mi^GKGKM|Sv-v7MBHjW?ddx$Q@JG@`=(t_XAi5(U`Uo7J)XKx;kG|R}2r9jI-cPs6DTdWOc z+!A|ZAgvDR>hk{isg@@fzlM=q!SoRv?*fd3EdXu5LXX&R(OWnD7#rhmOfmD$I0Crv z9}Q2WX-eP})IqYq#f>90911#)2_ab*mr6T*{{{w7fpi$Mmg9|05hc6Q<_n@YCGSnX z64yqXJ{rmGQ*JYo&lMq!Lv?h7oZnu)4SpS(+UX<3i3_pO51ao*b0Lp4*?W>23YgXT zj}$6OHFVJUBe7sK=;EuZiho3Y9pPF@(Txdf1@N|Yblrj7Qz2P)EinX0e6Ff&+?0Iv z143t4{%3phVWv0RtTgp@Bn7pai^ngr52gec+M~bQ8*S9Hgg5NGaoZ`z>&l|rmdBqH zF5~PqVtUcK_m5fg!I~MLP4m`LXKZGZ6dd;hGr|;NSw!2lv!=S^Y4J{KJ>SX#-D~mC zm_mVbxo-uR81v-M;#GTnAXb;)7!!%7STWXbM5IevQwQA9+AsPtRXGnIQAWI4=+R>L z{z2E{^e$wi>}BoiiUE7{pGvHFgX#}GTooI((6ztHU;o`pUf#aBG*&3|u5I3Cy8hGH zS`(O8DOv5rsh=$VQ!HulRn4+z2znDZdp#?4v{Sx*t7p?ctQRkrI(yp`JqE8aO4l4@ zE=f+$2$=;O#0zN6$DCcPODDpx2f(fQ#dQM<#n&|-Q60L*8L6*0pN@GE!aqO*ou5>P zexF`k%vs41)GCx0VGf@As;mAr# z@;_1Er%p4SS2QpUE6K`L6|NXEZT{j(<$rKeL0FEr>yNhAkt|ynlx9$V#%J+CRkqxF z@H7D3#ChHtL;%*VZ)m9e;lqblD)$`02?xqJpgM5mVR~bao zYb?a49xq8G!E8<}P`^-;zB>%?Q)H51Lq!nBAhrZXU!l}K=?u^FmQeDa^IzwCmrvQ_ zpH39pL@0`SED223xRE{I33BuuggJJF-mJ@b9{%3=W#+>qeVpo2Qy7>@xnK6y@m@FI zmmJBTvx`~%nF2P(N$5O_Y{On(eJzz{>&QH>4~F-_bDknfH~ z(2GWbs`yghjd9vOpFDj326KMXBC=jHP;eLY_rgk;ro2d*+-QM*@!5>zwbIn|;Ts-x zgVcE$bkv=t^UKmjd+s^EC0o&D5c+32_x-#1?A)BAX+|;bUo3wohHyolSPg&@#uu!= zi)m{h1eBo>`M+cUB7Rp85C>+Xz^QAaM}4MfDB`NbiV7eqe-dua2;p^S5Jkxg{3AO*ms~j z9Ns{qC7XH+c+$s~mdPME+etp!TBRbTqC)&5VwGjTo+Gjl%QjJc(k^KYJBBDjv($iT z73{9S*sxMxz=Qpp&V@Q+&9iN{kEQvSd1lX@o%=en^*J^$HSD4(G2j91-`XewW zn{I{-*Cs=DMBGz`K+Va%L^J}R7jFnNTF*U$%sb z@0j?|sU&xODp^6`Y7-SFVvv)?X5g8ro6AI@)=ih5clgP0ZM%za9tN~seinhO=fqbl z^i8_Vb&;AFF+_xZkPvD!{jF0#r0@q{XdV(IWLJCL^HEN6Qnx!El_Y*rUxN?NNR2iz zP4GOz(RR+TI?DL!KgdGK^f*+qyaEMA@R} ziuVeQ-3L?pI&Ao0^(ZjEi7r|DN|GJjF71xzU^x@Tw7_-(#Y~u;sI>2f4C6bO8g4p& z+*mfNILn*M*Jj=cgbs?*-oIxm6BkG#~g<8vNrq{s$E0 zTPM-he0hS{M_E(?QZi{nd@yaWV%UmzT11Vp;)A0mf^c&K+#i%_!0#|Z1LBTXb8Nvq zb^Y$|tzC(R<{tE)udy8%w}7$sld5oNB9|S(wXC9s#@A+%_g(ekLC6oiEBElekHyU) zsa zFg)~$4}zNz=SBR_pHGS=oq!bNi|SwODET#XLrFZ{xSqJ1mEnZL&Mbw#K0M}-(I@r! z^&=84OTf$RNrF_g_^d2Dnp{M?75aC*9-8=Mhp#SGRq~W@<0>M;C_GK)C+)>XC91?{}$Vm)r)bbw~Qr#yMoi$5ZsmTe7@q#M$g{B6wW&t0(v7$Q$~AJ^dwy z)E((mwBk9LTg%H~mHk8`p2LurygBQ+l+Jfe$$!nVNZinX^_7@@ox_h|L&hX64jL>X zD;Hc3JO?uvT|@lquSUw986Z@a!ug!?ecy=Ri2*6-x&lW0xo?R3t7s)_Y!+A()v5DK zTCj!RW3orn|66Vq^XgX>J386x@z@KI4R5&bjb?ysOk5SC$*_-zMFp;YhV~~HZX#_B z+sJOW7Ri%OX{czH*snX`C0n0L(v~v>VctOdV^7g%5FdYRL@G-qa|Mo94f!!uIJDeP zX=%0(+-IVVA3oTlTcz+mH~zJTMH_z+8%%krUKGkGi`$Hk|Fd{mFqLW5p(6pufut9w zq%BX1sF@X4zK{u6sz8(}*lXXve-D7sDImxI*zK(#1Cn)Qyd1Q+HQ9Bap0(;f9r0EW zu5LdydCkfZU$t%2AJH_m;-EW_p81 zc^`BRS5+lJsQ2#)AY#Ip^89>Q0V#0p$cqI-_j@0rOwdrkT`>`@Z;&o-3_LYd2(%3{ zdI*?0UG^55M*UB}ImoQs&BxSTJfrjncD26GX|r8_mR^7yM-n>zlL6M)9tMj3V;o1! z`E^Y}l+NXI$zR?-)8ERR1q&igmrtQCjdck|y{%~sq?>8YSD{xbh?UE9&v(QfXFI(4 zE#)Kto_RnQ^ovBCkBw=r(VR953*E>l17ks&U0zwifA=Eu;O56wa#`j3ZX%Bh3IQkh zb606ZJ3(W5n60T|IB7S!yFHAO9IHrZrL{}aYV{Y(BNzng?nM#~=Ez1{+(d0zj#tUh zH_3BeT8+DY|J@Oo7#{StYhLv2O8b>&)Tr&_NX#%-hiq0?E`s(BjMR+D@%n0_S+fg% zV%irVj%0KH_^35#kHgNy@PqyjLh858bFwh+Tg+F@8it6yc99Ok$HlR>aqaBw@2h;18Hb6v&_RsAAZ#aI0cr zVSzmw(9PDKo+-d?d%Kma9*6-BT1SYw7~ECkj;{cJY)AOAhJgUMgwZyEtfc(a4`R_h9!+Vk_J?VJ-n$kp>1mEsuj8jSon~{i~53gsB!&1m!`%9h8 z31^8(RhaiAoFhjvr63ae>{1}sWMw}&WiDS}?-AOgpN2Ypx#8xH$$VIT~e0?yL=593gTRfI2^kJbk3Dojfyptwmr+(>O zK96YGZvLxDqfGk&-|hXb73imvZ11*SeJ5HMJC&Z!9l?UJ6YVe=_|sn~v(5DQZhWS>5*)$oupe`<_7z{1M3#dC zqQCH;UuDQegReH9UKc)pM{y?gzR`H{8zCu)P&IAP&ldCM^@&kyxxsJemz}|Pv4t5Y zyl8~Xqf);<_AvSIrDHjszlhWc!VEb~bAdIN*UFV(V5cDgz%ml>?_x9C#MD%<#K}34 ze<+K1N!|rG!7sv+307|2s??(eXfo{U%7FV|Sn)FEoPs~|#)3Mx9f5^&s1K2GH>g37*pke+;tldKr2 zD%^TIjnR_UmfyHkb(d&lI|73+nFLauk5!r*naCWi!zkgDI?CLIEt72n07G$kOAv8I zeYW5C@Mn%~cQ^)w1T5B1_F7zX+?7Mdr)lT~tR1$sR1;ebV0nE3l~<@G@|Vl4gpu#V z5opuHPwIi-s1$4-EnaH_TJZ9{QChKJhe~Bsxld z`j2c^R9sj5(};gvF^ZF(_a%`o+znwD}p2y8H22H1$hWvYUel`ofY949m+NUkIx~1xp2w zIa`Bbi&S7zR*6HyFph&!JuF=n(&qE9P}aQBbpjp6qDXF(GU3lGL~w^bAMt%=lL$5U z6cGUd3Zp=F1!YR!HwhPbT9~8w^5aIkEt5h9IIpf2hrhdWjzyTUzD|w)F&FN6RQ_v8 zCNb3b%zA1j4@tjt$>oQ?Ui&GM-0Q;^8Y}C|c{u}X{|_GMvmvK}+D_yl|MG4KrtZr& z1ea&mWtF3Wacg+B)DwGT-=b~hx@l#dj3V%R80jzmAQSSz4-E}=QH1oHIpRrcHx&5T zKOM5Kd^v--aUOrdP^jU#PQ)9o%d#>cPOV{2U$Ur>>a(kb_$9A&{Y}E`-mrrE0Q;HZ zKVRSgi8UJK!{3@=v{CFX+jlX5K8;uG3v$GkvA@R^zkEEcI!G0>eeT}~C)ay+0**>V z)%H_XYrv$~QDFkdXkMWPBi+aS0>EejyD2F2{snU88ho~NJxBNj1mwX8rHjszs-pcr z-vf}TPf#`$7DfOmm;J{W?ND;GHwC)0v$Mmmh?>#vqm`k8Fr$bkkGJ&z9G4ezxg`Y# zsovL6#&cI(7SzB)G|{E&-4Do?yA=iKCyuOl~%@O<_5oHm#ZH24%;ZN3x7 zDdxqV;Nsw@)`bSSpU;LW18r`{RjvnGnWC5ok-D{~dSRqhCz?h)NE_!oEL|1mjwPYt zjV-Tyfq|wU8y4;KO(lr{4ZC;c@wc-gQa0j+#{6joSW)d+dN8D>I-X^xy(+HpUOEH= zfN5XX333u9>o_{;3-A1JUoDybT!NaNe&`WI`_7d*ulf3~ql*k|>Ei!*I?J#q*EiY^ z4Fl3Cje>wQNOuS#DBTFsDBaCak`e|jB~l`wgs60?AdP?^jUY&OpL_QIoU=dpVPAWD zDf7vF2Rz53I(C)Hr0B+x7$3z^3sHnHQ zdzTRIM*1+Bq3`2=`g4;~Qpiji`~+jv;vOMq+vG}RQw*Zg^A1gOs2%ks*XRq{6SY&| zhBPG$-gY2erKy+16kMoi%58H>g@O1eYfDQ6*smaw z2u~|SWp0DZox2ibF?yZmW*6?4R^e=mhKb$`(GZfim`K$a-Xm;IHXQsa@?&u!NiO7* z??jkp8s`JzeX*t!cf^mcL_`rI(s9mt`soNG7K6=S`UV+1LE$`KmFniR;E=3}JCzee z{gax-q}q7gr4@iwWv#-bF#19*PJ@RSEvU3-4hX=*bm;eR9rS<9zqdtk^JrOOFd&R% z;(IlBEfH26GBWdCq^+|1{z;M&VPy-i+zIo?%>xd~GN1(*^7Mo`f0@tHcsO47mW0ME zh^o*3d~$1VCRep&UD@H?yQ-(fKT!B_(D7DIhQWV~~y|8*`!jgI}r_n{e?tk7sy_+-^p2fK{DsUPwjz zt2+Z%-rrBCmQ75yd6`S!;9wcWd{SE>x;SMv*n$<7*a>A^M<*k6fL#b?cSqO&Ao5@X z1?i_6;2N>90m~MQYQUzvh8S-Omg0(I`*BTq>I=LzviFj#lyBL8(f?bH!~OmJbt(~B zvJQNXsFkmsEI?I76Afia!@>CE8Ddyrb_a6~69rIfuw(!T3CuznJ9BtkA0~MIe&$<$ z6p2~R>`n24b*4u-vnXYT9It7LvtQ^&gUz>RSZI>?x5S0=y$V)RXXHykqr|61%H1cA zcr=O_ayJf05>{nGmaiN+ox5MfzMQ8%@WTNUIi!`hvA5P4KIc_Gwr zvWfxqH&SkAaZ5+1x=CR*)SUUEMz`&*_7|8TtmB+Huz4JYOlG|Q5nx1Z<3)_5Sp-c? z7Dq&ccj$GUrd=AkuYY;0X%b-`7`W(<)9Uhpho(i=<=7qJB%pJHsZ5KjMVnnsIfDqv zjcuS&uGH#GSd^kt@}2^pIo{%8zSzOVB*8Ukx7g+GTP}&uI-^2gCKbA^jSwwLraA4g zHyWAK8jgcwND^2@?AdFQH) zYd`Ii{9{_u>n*XdVEL9O*lwQD>}Y1bpItp0;%&}cte?+`j9p52&tR%UvX{)`-&#WY zK9_U^8wK5%A)gSfWzfurEngIhUu6YtLbKVgVWL8(8U;%?XnyMH>lgXgpI1EA{~U6D z5^nHDH}+AV&s!ZIzeY6*(`SDk>!P#olq&90g#4ANFM!CJUtAn5z6{s#>lhw94;p9z znA&-EybG>MbujZ_BY1gvJ>&}7VB1;t_AS=zAGX+R_E5g(ADMW1*tU856dZJ8Top2? zOPL?^Q9}qstOg!U?+3OY!b5h(EDrCZhQb!Z9&%EYo#X1qGLnw!<7;RDvv;5 zV?L3dSPx2AWS?my(oc&Q=OQ-f8iG%Dn&B3^;tGQT0`q-ef&eALza8y_wx zetm;gPc<;Kr@)<+akGpm+&vGEkmgka$yxJm<2d&?!k~(K10v@Oj~_kK;LoEjrCTtQ z7hgte;e3U6SVImkbDI-6bL5N6_-FnqIq1g_*vu8N^4vYQ!)ME(=tZ^`k~04npwxl+ zY^2n|$qA6S1t2)Wm@aX6yW>^jg1k5i-%YVF6rMN!Xnodf`JEeocZcQTNJq;tsa_Iw zahyniyy#>CSCk~pEYXxT#)<-P>Y_I=VEs!GUq;`Go0?=XQJ^QSuC8Lv>bRhfC3vSn zA2t~o{KEeH4xp9b@KQ5+cAJeX_66kMweR2rw%sTEz!MJxUyotzeylwv0@7lRnO%q~ zK;}xqy8d7Wh}t(yQ@z6tTf+y7EMf9!L6`-eccb?BRx(Xm)8FEY;uy2&1p5?rZe-KY zNZ(B%*RZO@SIBp&CpY9hJ+FaFI#eM*_=Ow2)8tnrMBKR^ z(und4KR0>R7Qf{OX48g33WTMp52Bi8<81)c{x zxY9f0o*qHEw$B*pP&i}?yIm%Rp$DqscH8uW=R2a2f6BwD30j59tg=QuN|4d?RR21Y zLXIv!oxfbiMjH5`u)$hd21)h1rtr@%0V0Krp20LXhGNb%lJ{oio4(8PIcs>!K~o-N zp2u=*OYQwNTh-h!D+#`u`8?8JG9dC)c~uo0M-aCGE}7)3BG7k0sfJx1B&>9SQ?>M1 zA5ye6+~8dOmP5%}`-cJzxH$D-;Zk{&(tKST-Ly|P7nzqii zr6SJRpof*StcbNb6p`{7)+PLx{Kbq&o|V0WL+FBbbaZxpw}f}~Og>y~L5nhq;3qb6 zMgJ&`@Q>0(_XnQ24_|?(psf74q9^@shs{NE)LQhBX@?zK9bt4kItN=AfnNt)wd>Q~ zn!|<4@^D>&Z1gSB&jw3>y(H~*vSUb-y1{RQPU5!!l^G4(>X$v`fe`1bYh|D8eq4pe z;W;cwzM3Tt$P6eVs9-cAtP_5VNfkx!Cnvdx#|?o%MG8mVa`P|L=u6Fi{(iNRVqzj9 zEnsb*oSr%k7O3pdg0=bjh!JDA0!&E%S<&LoM1|p;qeMnQoiTZ8p%rroN0ehG`3o)m zTgx~Cn$Kfxl{;c$xZ)I{E?VwSx-~BPsIAc8@O<*o;#SG+HV>zfE-$m=3=)hC85Z-y zr$WWAD@+hk2x^5yl-&fD>4Ty953Nxj%I_Z&@noHicmCDaYb)1kc}0dQMy$NS!Om_M z5yBVa!Es=%cyLKjE_?iR{AXh~eM3sGwj59Lw6uVt7d0mKElr9dM<}|_{(sL{H4n7@ z-Z8+m)?iw8W3120fk_9Fuj(cm(w?wc!NLi9Xa z3`g)Mx1nBjhjoAnWt}bSPz@4*N#SBpAQ?K#ou1fpoub+|tUi7ZmJgpP6s(XKl6&685(}Pm+$+T8qUW?V6>X;5O3c6_zVv#i_Dr zZ4O-<-dK?#rJik_4ifkGhaP-II-18wG(fv81ad^UX&M?(NCVh3p62>-y#tbqG6tizkZp(drhc0 zM({S&1k7d+L$?nqqUjUUZ#8^Zv?LCG8GU`$e|I1s9nK4Cbj};D-K1pR9vy>nqruC; zq>#P%=}%HjL$odO$?fi_%HZ|qh^xs=0XQbtMSfhPBd#(@@IB^yVfv#d$na>d!TR|| zDs$W6=a%=Md@HfO6jNZ^AK zPCP$7L=TQ&b}rRJPB>8m9IeVZP?1$;u5M1QdBUVaMpvKeiR0V{l3;A#>3zAQT&WF3 zrC|oQYGwvxOgK`$glIM?&ZxOXvPnf5$skNvgjio^1SZyf#9`n0bfYhSLNDi@+m(NN zoXES%S_ETezdmcYN0Uf3K1LRNj>Xu{DE>76x=y!`C5n{cHD9R3(#EOfxv-FD(OE9NH;14~76NY|Zk*(p`Nxj)#!B0p9c7J=5KI$5S{Mk%SB6IbBQ7Zf^$Xq_0g={IzJj(W|C)AlcM0v*JxB2s?Eg_H~!m^iaSJD#=NI)u*5PSqjBe>k0 z@tteRJsZ-m(LL8`7>So(@E1&sj9{CO<(F|Y1@CElFyNs*!%RV23Ol|!@zlI*eG+IS z9yFVw%g6Q(4xYibrcs0l0T;ioO4Wrfk)*QQ4Q?6TC6<_)yER;tBr-Q+dQ17zUKyvp z@#BBSCLKwoqU|(kz|gHtsiLh@s^Jg-^$-aR`top*O&+Yx;^ zPPB-{iWFzY@T)_p2_DPx2w!P*!9d+Uo0Yp@%x#$eoZVt0O3a~Rs;Ep_pnePiN36#` z%UcDz86xWHM9~9{Dx)_g2y25=Qw$E4av~y;P{TQwVV~0q{Yl$L3rW`SjuHn%NF=HP zp>vk^ sRf@S&QbhAD4)-skf#-v7spbUvu7V!XoiMRjs+pnPBYrXb#|Cv#2J^bh0 zLdC~yOKs^MbE%JWD}C$&x|NFh`*-@@Q{w7l$QnHO{oa|-WQ6KA$0Iu52TRoEV-IO@ zFLsu{Y!~hF-M0IOvl38vV*dy-E^(9IOTUIDk(@cl4-z$HmHQF;dAY=8LC^pkRMpfp4dS^0WJbi7MahhrVk`qMCm}4NP1)mK8klOtkvdto z?l(hC_RSe#1X&Yz2Gf7Jo-U6w?Xargs9M8tbDFG!|C`Rbu7I=7F*A|A=u^+9yB1yz zyKV^ava(+r&eipfnLZ*{sSM1B5#1u1Ip1vjfYqX;d`~oMN!(#{sl!T;DXH5Z*lU%g zrE~nvXF{$H4zqAp2Z3l37(mtV=~ITUm)91wW@5sRWU0>C8gNTzO{W{}@HDhLPd<4_ z>j!1=9nAo7R~YlohA)g+%_Nw9pm@ExXSbVziYUge$XR;oL0%A<=EEKcB#LNaf%x*# zwYW2$#v1M`L)xzgFaUtezw#5m8Xzc)yl<*XkuJDvMo&9w{y+ zPng%=dW(Q@ZA_;Gtofu}C1Pj%!`AAjc#{X!q35pHCJNrHF4Dl(#?^xNLU7 zYN_tVaGkTnt|5La-^g+N{#hwwf?!QeO&*-JH?rN@>KEV`okRZs!CZV7KENye(!0I& zd5UIP=>)HCMX)h{ftJPW&pJy>S4H>+ zsDk^#kJqP#<-W$1P?pouGPDi8T155<%?uPT?&etiK2ssaBW<1jErl6;sr<@0cbI@> zZYa6ub1I856_o`Y&oGLKSc!l!X*tIq;VQoDOiOzQfh{mlj>)Awx$xAzt2P4s-wO8j zH~PdEh|U(|F0Ms38M3ciwu=4AV&4i*-;`1VmmEay)Z9YDgAuIX4Ipe z24;r+BsNK3LD|4{x%nQk=|7rYxJZ;oxBCkEeQ}27rr!rE@5r&41nr>%X^1LmZabP= zNkMjltvmj0egE{xT=uE)71*n4TtV2-K8g9VC@Aw27gRnonXiwVuMfAyPa;qt8T#|! zZqw6Hj9*yOKMDK%S(3QEJWhiHiw(#ey}G5806vC*tWmuiD=<(6V8f6gxZ%nlg{5X; zk*h%_eR;Nvu0_Ze%vrkoem|m47e!h9ZkOlgs`T~cYmyXlS&9S2V!%TLNB^7NZv@fp z8TSWm*v*df)h$=71 zcl<_GEEniojBDfm&r3qel$~&tgyyXk`XJhSkL3Op66hGuOFxsA(4#?6apk`{sA-m!Kh@rp#fn!;lo!dIWpn{Nit@O@e&=P|1%1&i-aB-W#0 zkvC5w5!7dGjkfJtO@Y@-dfP&{n}@g4(kw#g;B4qde>tWCHydf;P!Kc9bw;Vkx_N>- zVYZS)7Q0A*wp7-^q%eW$rdrsv&e$A+mgriTmKTPs=O|VEvFRm-=5W_&txmip)70sy z+-yNSzq06i!T|9<;eF4M2dRDBUtg}eSAG-H9eA8N8`~{9zo^?sY~yq-C)imeGQagf z$sAFyjTPqPFahnA;XfB0@lqkIEPd)q@3OG+uq;l$+i!hZYhJ*JCOY7GUr1T%3??wb zf3RnWKWx4{7l%wL`b`3Lg7@*oGmE(Jx)o|8f*7)vEq}c#;3U`M(#!FiCqQSA>euTg zx6tSS76(E4Nd>u>(9z=Qr&-O1RETR|_YM@FMwS_=)M^CIrQ*D6!X0?cBB|fhJ}l^R zx@y=QAV;D$P8uLGWnz+O9oWZ3G z+29TL-S2B_YsWC6qF)a%GM>Fjd!Ptgt6VYH92!dsmGRCusiY5mHC}Xt-4PalM*J} zqMk`80D@3YS62ymg(fB@0JY-0`jmXOtQxa|GwvZRct@jTxPdSBxng-d8AQ#l4kNnNYOZ^a$$sMy$q3CHx^giTM9c4tXezbJf61C_k(HE z8isMWD6J60!B=4fC3eFZK-6R2HZ*g`fk8anMkqG-{GYvFx70MN02olTE`SSAr@go4mQFADEED+plvPPyapH62;4eCD%P?`#|p zaW+`Ii6jLNne^U(oye_``HAJ+a3*IwN9+wFTYN?XwlZV8Nkhv<|6M7}W((2#_g(2_ zAL=gF{cV&9K2CQ~*}RVE%^D-VWkzCCT|w(O=)%KEzSSi%Ro&Jt^n-Hb^BY8g_-=wO zyIL#l4`i}pjXv8J&3ZTVWXDuO=P#`AyI|Go2FUICf_T1XEGnW|FP&o?dg!brK1;!K zeIcra;woU=`#3j$^=y3>iea~#4jW0(#Uii>0cc#}X3(;f-}#!wrVO)i^x!SJ6~X77 zbtFjIkX^ZuDB*klH=k`2wK4Xz{NOp7bHvu=jn-z>SMhP9lqYODi6XhY7=O?%kp)G9!PjBb~pegpfzp@%}$@eswkXtr#{l;B_l9|O8{;Q2#1 z^%q@9miu$>gLgINQJhA^H3dCS11zfJUz8Vg%3bMaM=~~@DDz&oxW2Oguk`;9o=_1} z#Jnx%Hj4m_hl~t!k6i_5-f$N4h#juUy5WT~gXO`Ti1`7Zp6er}Gyn;4Q z<@RyIi4Itq9>(UG5jo%>PM*33VcnNI7Xb`&*k;J#7xDF);YHM-08y!UWm%bx*ALt; z17{cw6>AcCQT6aDyxnlvxY@ZGdKn1k#2lP>jSaU2DOM*O8FwC&_mb)B3uda#9Z|jA zVxBqYKuHQT;wD;SB40XgXs_bxz7w0+#7>f2#GUnA#-<*L5AISu`adqosXAv|ti$1e- z$@kH!qDbX24u^(Jw8sGbABUU_=UVk;OOQv_@!YL@Q=QL9$=}tU)R^$(iRb&duqy*5 zNq8|4ruRlE3r&hX5|<$@H`{@@g{$e#IDzRi&WacZDR~*R8tVAYe?e(UK|MMu+Ud+e z>ED;yo8?k43(8g_*8-n+NnB3WY0gX2T3>h4!jWf15$NlG^JHgx_<_Yt{y!%FwRh@` zl%$xb{~4blGhO@fccm-07%I5QIZP>BA4wzs%sW`48TQjxL=U zyg4q&tZrlwU6npgEo2i@_4y1B7Y1i;6DmE3Uf=ww`=g+_4xd*s4VtE^1R$jB}z z%soy43DsY1V6Xd-$)SnKaiD5H)h0kJ*TGf zvO8o9;%CNy{rufOWYwffeWrSNA8xNFbL$0mJS)*eTAP+?ltR`g4MvqZP+C3HZ7RJR@PfA25=(E)JWSVSavLV|dhUXqDhS z&e?hTOF=Mpsk!2Hq9l^}WFUF~>f0cl90XL`mprC}7lZ>6g0QHZ}_Jz+>kqA zttp}c*i)S&Ze$RoMJRDabWiaV=3a08y?N2jb^)<+KlDU*8R)7*MULFE zzwwXBeucETE0tfXxe*zna#7dD-eI9Je7)H-`ckYvPOpX@+E}D3D%Q5l)NFW`Ym39p zF}8W<73W~pu7dC&XK=f9^Nivi^t>S~LFtRU-ujIFt_{)T%*_1|j(6iO;NlYE<&!hl z(O5lQ_}gCETaFd`@k|9uRz(yXc1s4t2uODmkhrXd;#<-0y3RV+TcfnSEz&ws+h=f7R??*EG__&a>|RYN`&LHR`Luqz%vC&ET} z>o1m^pBDWRR}bDZLs>F>uVgMkS)A*k!8o%;ggP$`6phL$K&XnLp8g4|Jt0XkhQFW+f+SpXzJIg{ z`YX2~S3AFyX3+)5MH-e9zSo5oRmu<^8W8zPd{fgEktd&2)8@`o8A6?BK&ozOMhRs~ zwyz>KbE=H4{MDSM*FWxI35Qm`z=kkt`pb&c!cgI3p-X)-tom+z+N+F&L_uWiS4$5M zRy0~2IMWEUuS!|X+eUf$3k^J4Lv5)C?H2LRhsR%NH-$#4<0)YO!z{!>3HM7=z zZpWT*yzVKu_AUSG8A75LC1@|KU_SpZISjp{VL3agw^ns~iqC(Z^zb)J1Jc}k%>Wbi zwzA2@M+8$4kA<0XcF0=!27t@i$LQes1P9U%=dEWlDQedNCj-UsgM2Nc#fX+CPoBUI z#rPOI9AY6ECFuy#Smj7^o*fM2HaWh5isY+A9*d@i&4WqTX2f&Pe|I-$8(Ig&n)mq; zv_sZhq*;INJ*9{lZ5^%WV)Y~0GY7L!tDrC!ivkNP6;u3upV28i9opH07{hZT?aB)4 zEG~b9B@#2Z2~2J~`vD{cFhV z^s2!_+_i!Ta^Zx#X?&eyO$WE!`rL;##qz7Gg;gCkwBAI;EKra!`E9w1UmWqFq_k={ z#tlA;Y~^!yseB6ihkZEt#XjKrBCcGRxODyD;>+KFvmy|@Tee~r?|N^lj#WaG#cHpm zCCxguH`liP`TP?B1GqQ4FrkPW4lm8a_s4>ae@-gRxh#HsM8kE3`C=>jy?sBE(^Nef zT!P;db#*o#R#zpSAvAbPbiGzfi|6~KHakFw{`t=IMwf?#i$-*TQR=nH8TzIj&xT88 zS!`t*rN=I)ly3&DagQ=`e3Zvh{?a293Eh9_U$RW5BEpb}*&@eP66vj$Gib|6ur)4o z`+-vRBehgw9eBvLPH?0ncgDq%S+s;8x5|Z8i5^7?CR>x{u+8yy7J`G;S|?ho@KBYF z%x@B^>I+~2uyA`jRPt5o5GFV{c0%yqA?4cHLjSSD7!=4hRDJBsA}G#h;M(7`(F3#IPQppOdiA29=QV-v*3Lio8MBD zEKx;{5)pkjD;vnslR9t$lB)YL4zfK7En{^rRv=H1MyqNNx3GR05oBL#wFkB*!fg8Db$>81_WEXXLsd!2$ zubOZ4qgs>EK0FVNL{?8+NKVoZgXwk0n>(^8|58agMwty8%2uASrNoH1JAkw4uM}Ds z0$cx8TH3rfchlfq31a&o3|fQG=Xv2pg7Ls8HA;gcVt;K6i?&ir`eoXof8 z{16OIef_2Ku$i}@9)o*Lo!I4^zXRs@7NH8@+Bu?iRNc2WLP~7h7BTb5yKMT*|XJVMo7so7F zN|}Y9t6=wI<^dl>7SZ!z3);ddKy{?+Ch~iSMM?2nX)rbJ^a!xbbZBv!$$yc|%xh5P z!}%)_@tm&tp(?uhZA$9itZ4XXkY&?xL$9JrzRK66>m^ww+P=Pv^AyshSWNL}-N=yFjV35-PWZ$P7(ADGyLTrKzK8g5;DugT zPKszoDzXOczqPF{iY|(cAr(XW(nbf~F2Bs4ZWl zg(BC$qWRmzY47VF?(T|TjK?FQNgw5s+vDPuV#C2u2Lrm3K3oF z-d5^(1YTM>rRhy#;7WOU?frb1qJ|BN-zsiE2g)m#l$M5}JDyNS3z}@t+#RHuZp^7m zz^*rhw2l7{Un*>ApZ>pex!V3$->z)VbL;RXO9L;`=%5-t?iJ;)i8Jf%{006$ZjGtI zwX4twO@fE$QCriS+S-=^fq{;|yg@tVy4_iJf?zsCFM#2l4D&uYi;qzor*n`k1H*|z)yVn#6*ln9&g&~;9LFabo1xUKSZWUaZe1f`(6EeOsfJ9 zU8Z~{ormH>L>+h;Tq3+L|FI#^yNvq7=|J?Az;TqD^NBFyKcmzvVHZ!!C4#qGEm)zr zTu)~c*Y(#toYYD&pLE*L$K7F|58zCIGz{5I)v8oV@15<=!tyxs-}l8^8iJ1J22)xv zcOpueRk73})ZQUzGau2tY+|H(gjYR4pK9%}f_U^;YVb=aZCRV8sc_aRE6;757C(p* zLKKG-Eh@32Ol?zMjuD?Q7EB*D9nQg!)3N?>CJ~16Z~uPKRA$9mO>Vg72D_8|smY0M z4P%X*ObR#0xmjj=HLgn!Q8_!~a%Mk4f;VwU_;v^l;pi?Yd*uK8e(wjKzelX;q{nry zFYY%z!9fZL{?{0_ScoDe`}_G`wr6MjQhHfgg5d20!JTvxiK|p`1<82aYBEI7MEZfJ z?A^PUEh=cAv@xp@HB1KtjdAeVLmuc?YSFM`928PRzl_Q)jIlDkm`B9K#N-HY(`{++YK? z1z1o)KNOFONN2?6%8Gno;Fp>ba*_m3KJ5yy9MC>dfCZF3wk8{*LOd#(O-e*fNgyN#Lq=GWHh`@{(I ziY|xWccJ%$`osl(k|~m+TLJgT-eAu@$9dC<+p3~~#Q%F$F~H$-&d-q^Ob;biL>yiM zP&ivEZCbSnF>D%`t{XKb%VVhs6Vz^q6K%}Izoy|+;w-}#f3Iyz+RJLM_gW&&q;*$q^k;?zbRMg z6-t6x%ggLkYO#N}J6!#68l4v@p~p6}{YbyZcEbpRx5KagMRUvDRY$Ep=bkBM>@M`7?L z^kv?{jF7)Au8ckDCDj*tzS@m=OyU*%IpP+fmeqsh6+K+iEyt>hMTLz@9r_`iI{wk^ z*G6_YSlN`b*9E;lM~|FFTNmYvd0|S2FPY!n8h_sZ>8GQxcm$^%32%=g3^o^=mlq^Z z0mE=lV(CRT!#wvpiF!7V4>;}fQ2EyxhK0Aa#2;#miFfSiGc2bjC;t4?p9aFMt#|WaR{Xo+ zNL{zlV`h}Ih4;lDBcWEw=a2rq*u=LorE}Q7Q4n}4?678(=rQgYnbhHf)J* z-O}S38v9}TcazEJr(&F$o6g=O1)hh@nouzyU?7m=sd)RgCxGII?jt>o>xF;uM9!=- zAqC(Tv4lmF)6*^fn{bi935ifT`$2o{VL6KzVbrxkTVtUolD6@ zZA^WF(lW?&5NK;6BnmRwt`vf+8v$(5q=U_w`{8ry%IK9`Y`s6+$|WeyF7}c@3)E-p z@?ONEin_Y{OV{wwTgU2q@zh+qd29Y^UxA9`-Bvtx3~E1|Nds&r zz3`w%e9zl5BJXIkh*$p*8Ts5<#Y=xTNdgU%==MCQvM+Dk>Sqc$?y*1@Lrg>Q@OPhC zt+Efz)Nu|;ox;taNIaYrl|5=D`6C^Xakb=2!2_2--!8i4`ENIvqsqj>r0k-CT?DUE zcRn&q)@vSV&v#r6xJ!1Y0=mDP1BrT2wkE?{dj2_KcRqQ?7ClT?nKi&Q`Ay(A_bK|l z*WYh$^^?n)!q_@7CoYqsBAV^yzQ3cO1Qr|i-{B0049NA!G4<`@F5}cF$hx0F>yH?E zPaxbUu9RqP|AE;fg9>?qw_xpX(2r< zcg!P?oN>>vpq59_u(2z5e9SERcE`2(o(k0GKza~gK@*WKY)=fg7_i=>%|as+f8#U{ z4-cPP>c{w$g5nR8;cM`Cn|6Iv6nY48e~Ard@bycWP*uP0Ez99a@=**iiCgiDn$0?z zes7KU%6HoTS?1L6@HKrcI3-IVi-NkFLB^s2UQi6YcWU6fA{gNYp$k%#iM*wNLeXbk zkt!e$n9m@}(R^xY5R>GXslnM5XPY3XUOapP%bD>&cy}~TytTPUs>E&hca%{e_+XbA zyNX$Q>+IXva1Dk5p_Z(h7F)7Ft3}wA5G*X&orCV;UrjoVamWKf7YPh$j4eG!mZ+Cc z48{QZ6Lq|sY8iO=K%l5My*k=b+YP;^j)ke5Y|J9GkzT-`dwn$QxRk!j)^S)C6HG)#G;l^P8tP{9zlYn*!QTi&t?dsEOejujp(xpM z_E5;5U_6CE{mDZu2#)bwLa-k!;As9M`T_c1_bnHW2p%qOj3*yNjhI=7H4C4-HG;B~f!z zWHALducFqyRUNSK08boDdKpPC#*Cpl<{5sr+Tj-Vy+WaX06F9S(^VxFM29nDAX4BPyKYzEM;YR{H~M@pIuAIX zq@?gK{7-+QQoG9uxNApk$!;QEzV_6+*yXa5=}}X7x864WyWeVbRV=_dG2`KjV`EC? z$V+%rcK!C9c?xjy4BzZrS2JE=k(h&((SoGUuw#b?Gqki%!RF0ZQl3+PI_!$Eswy4LxRX)Tyc(2mYX}8Z+E%{ z#9(N>#s=f}>g*ajLNd+Pg7F4_VY(+_Fy=24p*nv|!@CR0UC0sWG}|%*TG4~v+$$s` zXjSxSLV^~=4<7|Dm-xgsc za+Ps;FMmx^SN|n=zQLV71-hqaH=}Pk2I;}h2h4}M=}c5(`%+AMxIqde8y;auv84!o z+9R5UaX~sut;LJ)4-8fh8rp*IEn@5NRV(87k*UxHUm6!jT8wnj5hDMP8)(ZEiN2GdhKs=2-T0iBIs7$_-lHEet z6TXz#2-u-Pn^PEY|JX9;6%Z|;C@skkR2o9K6w`kfa`uOW&q-5k^w7INN+iKHIR^p> z1&$?NY&0abS~< z7m)Wvarmf^0YxiMc1Z458WuXYZ`ZL^@b6`jQf2u4-Oe)9bGJ@m?VziqA9*?RIpqnr z>OMA*nKEZd%xMVfk|5CT3Q!x|hwj|CL*1$I_N`&hh{~d~RAK~riyc$FsY!-+c)%fc54zuMt&V57p)>|>;`Q~tX|1;i?Ew2y!-1WJiGwXd80!d53;{u>NjnMx zhhKF+pf)>k0rEwCgJn>H3;Y8O3^Kt23pV*G?nuqjONyj!R@yTNFoPxcjhz*c{t%XM z`;~AG$*;4}7&=|B7!1Y#IR=}z9;(rx9~e~6r<1{rDfoK!FpP@i;rg%I9fc!Dei#AK znP|4+;KPmI=|H9dIj4|G1uXDT!~*+_6|hFLBfi=QT~`+IHt(l=Oi+<|?{@ON~b}Jne_opsjf%C%#akpU&fAI=UwUk(}H6uz~qnnEq3(uIw8P!2V z%U|@H3#+_@@+ciO(Nb(usj+xXt1A4yo5Y)c5g5`r-G%8VwTn|2g1AG}3&MsEo?L!e zu4HLTAnG$0=m_oypW%ZbkR_=$Encb!_QZdUrVJY)2|ZFeTXzjrx=y~$qf#82>|!iR zso&`!9R(o7X+~w0Rhh6KR{LCWXTgfUa^=8bQOh*&})!x1dL)}Idlqr-649FA@os)} zS(lgUr)!sV_l?B<&7@uoGJp==6V1`kU$asyN`!&wh9I%Og z`M@jIJcD3wU}b#+%SLWd=`4eh|CF})eu7vF-L&B!%cAkmU(HeBY@gCv?qZOucVnpI z-Ncl0JC;|7RJQs+D}HirJ|)UOo8 z+nmUIyM-K4%6*y7_Uvng@3BFJ8CO`vU)(IGq(|q6&2sUVhdFmKI9ZCqc6IP{sU+|D zg-S3@vNDuXjjOmFN_O{5b1h8uNYLR z&;DKh>^XGPzJM`kfqo_i!l1nw!m3SDqk2j0#rW?v5l4H)a!fWK4^Vy{XTtZ zICHD|x<@)iw&$l_EV|h@USFMgdI}ULPZ{OUK2y)P2hl7i8J<_LD83#L`N5#ANp=Hi zt^`I^=>K-Q*(U)jhY@uRj^`Z`s-~t{UYDfZfMJ2;7z-PC(}rNjleOT-CBkrt{Xq44{ap&Rx> zi&fly$rX�k*{`jeG*_6jN2LOscr7jn=zZT=Ix|0&3&f$<%5#6h>ZKjqr3W&Nf5m zbw$0phYJMEDxaTW3)Ia|g_UukhGKiFZFKIejs_%C1LH;dsH@tf}9 zHT|AF8C}5)fWw53HEwu+c$(eU^wg91&-!IM^Xb)`@iUspUuj<~Rci0QOI2U3En|^M z#U^bVbE%icGsDNW*~L5u&A)bYqPn=KqN1;c=kC6fvgbJY1#LNLdzx@wo z;`Z5`)`a~fq=^1+?Q9YHmIA6BTN`l2?-;$PfGreeAzDpYPb%O!E3PH@@=FxyAmz)Dg|4T7ej#etccm$NbBtxh7EU_ctNQY+gp7<8I#5MO*c8Ey z_`MV!88&lh3nx6KZ4Q5XpB4vr3u*l9`&^M65WLjLbAmM+p!C5P<~s`;_|P=|g7W&0 zTQOH1T*^C5r!Rb1KH+_qHLvdXs#>ig$d>ivQn*YQ`HULNs#w4~O2`&O(Z30!WHHL1 zd@=6sw>T#^kChhe!4MSe7D;~2~zQAO~A4_J8PPw;!YwteJtID0E(8g%2 z{i|y3dvJak%yfA9_kqA0rn(H?g5aCGjjt7#-Q7~pz!|cI+5g?)!^P}vZFHgTSc5@^2{zm-*@l??6 zj}J_S#+1>%WD8mtzhqBVUi(2>h`+mZ_&A7>nKNi7gIOWSQcQ7OwY^s_gKAXg4*j=$ z2g&5$@jaKvGFpuxyk7;g>_t#`%t3AnckkZ)$zQ@{L=0W7YKQ4+uNA8}Ba5P#v$uw% z(k+yAheZg0q1dVXNcG~QMJ~XiKRBC;J1u_2hE9VASIfOH+>HZ@YPf+8rmPGJSa?bt z+}yOLla$#Mj;#@F;m(sfdcw?SaQBDD;2YT}HfpT`Zsf(7>5YBb!b~_CPnedgxjKm2 zz%6sbeiqPnR>mOULdEEp&!5r7!{}BZkOKfGtH)j3mm!RY>M7YWef9*rmM4^$0(Y*H zYb=ry;EbKcEn|>xMNncs9QI}`5RyuK4X3|7TDu5#bK82xa?MD4uqkkt3PD+Tdq}=D zk)QKal-`nzB*hnLp?=3wg_SWDvn^9)@?~nv)-08i>3dtQN+*AXAIQ#H<|S%kq&>A@ zj~Y6;*XWKhySGpy%;#}fRON`n)sY}I8`l}z>hF!a{gpdpIXo%&pEZmT5kY;!1hP|ugnTBa{jT;^WLwZ8_T+>f)Ex%gd;LpN+AIl)6 zKH`xc~L~|7MaXWKUHc< zxDb@Va@dIH382X^(Ccs8^LHP5}kSRIDY)s9q zwv2qr7mp-_;tPZdaijAi|IF^(Z!%4!i{OJj&4YCHHzMX^&dp7cj+qPT6tZcF?!PE7 z6XcnM70c~upPc1-qR;RT^Ektb1gBTF| zK1DL4{|u@B*baZQg%}Ke?9pva}DtxZD@-XE@t~3JsI%a`;>xnJ{|* zw_Zs&K@T|sY`QvZO@N_z4neoGH^Vw-TL&*6sniE6|Z?_cTC zJmab7MJPZ0_C^s>rCoG?pRZ{!SuuE**jGdElQ*pc_v6rri2i7}X9q2Ll?zLvXce>Ijk7H8N-B*#Y z|4*IAce>@4*_(4or2TE~)==G(uo+$cPwaGVgh66HI~|82`u5LIi8o4P2Y6*L5G|Iu zi{cIW#n&5&TqVaX=I|JS1+pgSaEp0#!(Fx`;;Nn_DN@zErF8PW0!ia;LG(UW1Unbsnnd$$^ly>6VqaIpvfz%c{Ik z>B@%GUs$nFjkP%NClF9W`WSn%1|S?h%b$`z#R0aq)zb>PRau>Qn4`Az4hT)7SBkKD zysH0yS*e4XRHA=D1d(wU;Z={1Sv12m(w`gd<^l*ymHuyS?IotZ2v%kIpYwPst5Uqb ziUDKEr6D>@l8FZa0voI}$}N<%e01?(Y0I|7u@y-x4GOtw7+$?(X1N~vkwN?KWc{D# zHaxYI8j~@{1hePpcUZ0}-cBTyuBvspom1>|{ffohJS$oULdx*{&bsENfots_?Zk7~hU`g>W#Va7;e}o4}E1u6ShfYt*AAPo?3Z zyJHFea{WAA7ib;|E0e|vmj==(Q4d|&4l=(yOepZ`kF_T={y?TErgak@lKax-8C>rU zaE*YXvV!FYkaPPZMwdB#nn#L?2RN;#>(b#;%)~ts<>bYd{ci@!iEi5=$wxf?`%}Z4 zll61QTkxu>9@Fj#W7C0&!d30(xAYEOltHsc86z-nIEx+RHwf-yFV+XF+t)J)B-(`iY6EZVO6RMN=hEV>RQ^;!UBLg4g!bHiw7hYR`xU6oR>XQI3Au^;I*nRfl!234tM4hmnG^vd4&0tZSTaH#U82dUZG@d-Q=YT|C78 zYK~Lt#06cCMnu4-SrFS+D}X`MEFq8a-!Ba9ES9a)I`d&KE?`YH%)Sx*BeSZFq&-A) z{TZ)S--R%B@v$c2ppW}Qw+{Xapae^Ck{nI|l@R(exd#Jl z4i%;{V4$`!nF@yHe%xuAKEz zI!jkg4@=^O)*Xv|c|k8alQGGxk_+Z?8*{VMc0D@j{H_)=Qq=s=;%4WLb1OF>5G2XWO4c|fPwgd949=Ufx@`?o+sPeJ2W)4JoWeJ+AQS)z>OGKDAZ{2v&|5R!$P z(r0xO3AoZBJK}h&P&)AbQAtTjrLzTR2^TtdLsAf@QONgV&|l&MDNszQam0{&-ANvL zWdh-1AH(LaQzD{n)#r{go)82_!6r4GjBso%PN0Ntoe>v0) zszEJ#XdJZ|vncZmwq;nFHRH1tLtAx7H&+fZ9p3Kl&{ha`R=|G&vMYAWDPD>7VADtA z$Z#;wHryqyzE*VStbcV$AR7Ft@6KWA-&V8XA&$~j&g(zUeq;N%WRJFbk1b5%wZp}d zSGt9$YJ;@v*VHU&sf7d|o1o*#Pq6h+*&1&+OF{c(_yi^9sh?UDr5v9fJ~Q$-x$uX~ ze)E3dI-7mdB(Hd+xtUoEV82Cmbv_@1mMWb0NI$Ew`_BgN&vy`u=GNq%B!-+U{`xaT zEcNAQIIWVwKUOu-ecXZ8eA*H$jX7f569I+YzC@Jg_L!7zDk4w${^83=&Y%bb*BlYS z#Xde(bjJ(2&Y`{VvUyJIU2h9o$&hbz!c7aQ`Du{_TB|6;%Kz-U>z&oGWTvq4GFof_ zBS!`Wv^W=O{R1A>lL67q`ez|D2X-Guq=@NbZ{-DCkDxKJ&YQ5IY@&rwf^Q%EMCpXg z#a^p?t~zS_u@w?4rdGG3IfT4Qu;4S z0GL7bCJ@Xlf6C^vpgr4x>Y|dj+9HVQr;8O1yy0;v(+W`E3Md@NHj76_z(>xlQFt*< z=a_=P$jr=ah;;WuD3Ao%D_oxyRLPQh3Aeaxutq`n2@o`e2piVhjj4Hp*_)^v2eyz~ zHUQc9_Bka@;6e4Hrwqs#nQx3d@t8f(L|%x=hPkP=F~o9u-fAk1(w--n4v54r&=p_O zQ!aK-BQm9VI5bo7hg)t$L-??MarzNc1+IQf-LRY~oAxkLs9{ZMoWbUY;*-Q6JNW|9vJxv(ZME*VLWrBy z{$XOEuaL}~wt0Fh@NO&+zFkpPRwgby;E>nJxt&YT2w*(hB^4saz(1M=%Ed7RuP8jM z)w&*R?1(h$4V~d|bt-ZQpV1BA+CdUC#NtL3l*ICEFW#^>u!QaaFcU-1O8-Olg|84S z!FLa_-%MjXRggG|j+f!}Ie)Maz>b@~Gr}^3^`*OU)mGuj zE!)3&rsZ`A|K#N4#%jeIjMl;=smRiM6%RQ9Z)ykFLvt3lXinIF;3Y?x?fvV#^)-|! z>>qB=;Zuj`f~e4d1RGpzX<^UX1oSP3R6G0R^PwSL7jD=DcSNn6B(6UsXASYcbop)& zjqq!h>be&85;`Y*W8=7KQc62#A%u=~a)Z5ylJt>12hG>`2ba9u*8lmmo$j5h`V6Ri zD{HaSay_~cWR<$A^fU_fWzqLl3yN+ScetdYDnDR38;lGUm5C-7mfb1I%tu{m;8;fk z+IaP~U9@wP?@8OeHn#KqXH$jmgd)=iu}s>FEc-7uRiQfHI1Em1kABm~?wJoCw-#Mq zL^fdF9fWgA>VJ71$(1pWv#2gcXmTjUo-7?6588?r6ek^fAZDlz1DvtGSr9Gj@P zC#h@nvAC&9TUqyikeibcJo8XFFw-2sz{prQG<1W6oSYhC4HdfeIWM-rZL+cN47!_> z+;SRM%PWezA`pR-h@6-!r;a6o>N(93iGIfvk;aN!j#HOsc1ooCEO^l+8*LM?hI@ZR_M zE*aSZX?n!7n|2*fKk|#Kdk+59pC!TUzfjEi;kz!D9-K;cFXk$KBIk+^Jy>~rOrAe& zdzCTcGOPYf`01U2k6XOYx{0&=lcP}2o^NCebBA$+BQq)lgd4aWL!un>#M~VAG1ZaS zc-NF_of(_w)ohBBn>8&TnY1Pep_Z+NnO_3|PTO0__$>yJ#un+5p*ijTR zl6&0$+HUc&hWujvSsTM1)o#{$cGt>(UM=hr;j18u9M%f2X%`dyFEi@WiyLvr$?j|2 zK=nl!cc{L1QYL7ZB+V+Btt!H;P}E5noKy3L5Z|CyrgdA#-xUqN~+GMVLaD5{_B{KJE_j*m|-JR>sQ z@Uq=2Z&Tse=BC0HoJ-^K9_*zP&mh5$He^*|W^4Yvd)B}kW&`HiS-|!$vL?o}4_EX_ z84Mbr&)+PU63Fm!pQ~2CRv}g888c2ac)ra~JYh(h5{e(@eSB2L-u1ofsPFgfMTXbf- z%mIdT@YAQ>kUW(_rD&CKsCohFS|D@4ScuN~T<^UVuSgrAmX9Ru?!qi21b1JCBrEri zByWgnT_7BdJ`@DnyFb0(zeewqg{!8{;h?`foISN{mk-M-llIaH2&2R9&BDHAp;Rl} zfz1;|^flH6Vc?9SO9~LUOlM+Ic(~s&fW=LBdO$SaapyMfNJNFr$z;2-o366%_{t$* zd#bl?-Fh3r@I5!=X=>N`LE?EklqO%Xuo%rPZdd$Ao9O{8s+hx%4XY22W-DJsIIxNk zm*22i^c;{)BX->QONglLkmf$|84hI~n)X+)w0ww&lfILD{?uT(R)~n|!?SQ5rl|ZnmEJ z&kkC^gIP(nz;avs(l*YF-&jnf__y4e!5|?F#LBMr6QAqZrB-5r$84~{VDd?HvERxK zr{eq-4cOd8b~~T^q0r5ElJNK7((rZxqd4-y|9Hv<7xBazf1Kof9V={eb93)ien`{n zmKNAKdkCtD4Bzv7(IPM@GT!gA_!38;JKf-Ko1Jgq2$;@Y|{N!&eA|XEo%0! zKZWAikXfN$-f9m)vRXr|*Uc+3(Z<94{^L@jrM+eyar~&c6^MqIoSB)C*fuO}4GVGUb_z?)g!hgsdRinzziy&a>wA~HRaI$2!Wa2CJAVG;7SH6urfay{>BVgEzsig3TNSHp<0iEA zbP}0y9~MeG4ly$S*eQiZq5B{fgq|_({Sja5lu$9sUWlYawZkvskC)*qfsD`|&Le;& z(|B1Jz|Nu{WdE1|?2okAVcH&8hI-$nyGrTdzroG#UPew`CuSSH5|HDTGqkfK398a_ zOWab|17+v8r>EQx zI=U`#fuDXfHgq@>ZK4id```HK?H^S2{0di`i)1^~@%+2-{HdkOUbJWs3UFNe>OktU zhpG*pVSj+k=qWd;C}#CPP;Oe+21Wmyg+lAlFqa4IyOpvTU;n%=P-5wsTdz`{&}DF; zdc+u0^$Z=_f;Syd7fFb+)@$ca=oFNXHomFYy3-xnJv1vH_IT5a`P;c@DBRk zQ7_YQBXdCCcg8_si1tfEvPfEG6E!trf=JqOOZAaj0|Q)xaS1~MFM~e}s;UW#u0Hi4 zVv1@K*=YsQ&K5b)rkHO`-_Fv*QB~r4_bx6ax>o4_84souAY*qk;;L;@kb<5H!KY83 zk|?l1?LeV|G33!AopAX#o9h7ifzb;BcK$Q-d`J^mS|!30T&^gW`4=9Cv60hG)A;@H zr9UJ*I2P>va-c#ElUim7tnus9Zg6$fa*n++13^-$I;5Py6(!)y3;(tiFPt|9d29lqpL|E{iZ< z=AYWl^KWc=y2gidw+>m>{bPbYa>d_KrcQm3B^VZYpF_1Y<<^~`Pnou-60@2{{Seun z_p|Xvbp+jlo@;V`4a3mm>xql+ij!PA1QQB#r$}EN&@5=u3!3@P|ExcC{qtomeg8#T z0P}-?gpCcvTp6Y7b*p6A?qT%}q%ZDLbmX;mdIshwa`12B4{zs4JmR_< zf`-AwbJFeAJSO&LC(=HWR)v7!5!n>wL7j9k#YhY?{PdoZQ+$>lY3wJI+)4+%UBR%K z@t2E|hPum^BYyv;zs~}N^Dyrfm;SL*wMM0>TIrN|>wS?e-HW+2R`Ten@kN!gW`bgU z!SdB?ukA_|y6@s(@XSidFS0}u2qsw;+_o&4m^P1@+BT&Bs#JE);&5j%+ zERm^+;6ac=2V5aQnca_|I)yk6Qp5`W@e*gAf`w^~RUPjXeptTDjqHb5r}z&G!`YTk#DNjM(ngX3jgZ z9e*?M^-N|tRt|&^FpT#O3A;O0i2pn2Q_FE)M`r7eC_5L~uunn~Lk!B)_`D){U6oiy z_4%9{_N!}6kIgG_o2oiRmhI?y^@pBzia4=HDG7~Y{df}j>lc#QDq|{YbGmwt-9xME zcBro$rx(0xgjsNM`rlD~-@HAI=M7@t1>5so+h>>aYq5qygLX~j?hjw?!vBgENJj}9 zq8?XPq2e8?aFBzT^W(4VZN$DLga}CbS60o1mL(3t1Qg;dr=lq8jOEJvE|2efpbCjImkW$NC*-rm+(7prme@Oka5_iPio4_t`-$S!P^h zSf*-aFba_j+1ZRBkO9$LvK4JEafL*QkivgJ{WU8Sw8_y+LqbqX%Oi7DAO00BNt&^Y zUn;wPyIh(0pBXH7K57=cl;Kl~42%vmecN&%*!_Nlb{1D5pdrF_z#q25Js)&uI}BpQ zSVG0v@Prz5_&^)sOMbnvF(rbs-l4`7Gkq_Az3E{sB`bSaG$(hVDu9nu(|af5T?^es zxk&S|a(=8(r7|wn*Y;*6l36G5c(b+>|LixdKlw5bdhAnJC^eEQmRH?XUN?`P{-kj7 zJO3>GoL@IqF{?fZsP_M58O$BVN=|a!zNn!Hd59Zz`KLN~zXzH0JVK9c3yk|a#jei1 z7omF>H_JXZvZ0_IoZy2k4dtTJI#7dcExr8SgZSr5^BtZMyPInITlY`4Zq1_iLxY~J zU-+>czOfFONS>Xf(!GaQYkTRWyd#U}L8$ex+n>l!hwvc%U%Q~KA9WZvl`vuZV*x?V zicUH595>`2Lsf96Ha3OOmkb`PFvt(9y#;D!VNi`W{Ar?fXG0G7jMXUcn2qbn>mwq} z-i-&pAMX?+>9bH)rTO_vr-~4P# zn>KxZv-~~dtCA7{4XNzmh^gDz6`Tim_)QH4O}v`1Y3oG(S-G zp>%H1!L@2OkJGyS1Hyu;Yf;l%=qnpxZ#K}w_us}bSiD%&A_%8%`K5Mne%5yG@l}pW zE0&c)8`VBwd*&VbVzyfv-`s#)y1TYge zf=I{I>>(>*loYlVwaQ#&-B1U8>qa#DgG6H*sBJ#0vM!{)e6ZBSN^-3;Z=UjG`;{X3 z>r-R%2VEwV7S9z%B=u!vo|?N0&m61{AV>)#nW&!FKU@R~>K)ZQJUqTP+Mw%p&C_2I= zr=+sn4jlsr{(rsTfZwjJt*OD04^gHLhPtL7bY6|6R3zU8#6F6m@pNy>IldPRtxiu~ z#u=5G4jLJ7?YUpU3jHDx3;a-(%39~P98l_i-n6k|vbIh4U|4u$e;{}Xt-Vymz{d9K z@nga*Idb5RId$Ofpz>m3W9xyzGOn95U5jV+@875rw`!qy&~W}Nf#03g4Rr5!NJF4s zr=%`~M-K!y(sGxUipdRc!;Lfm;{A;Z=dWxkN*@Ik*B|azpmfm0i+h8zU2XXt@ZRr{t-%(8tWF>$I!jHe9g}j zv2vGc#Uk!Ew4DsJb;aBMjlUSJtI@l-4<}2f$JxHwNWH1K>EXtuhPmGd<~Fjgcv;qd z*;4m-A&$al$5+pv@Z~e5zE-o3bPoaph+n@KZFqfh^gRA|^;68d9yY9;qS&rnll7*} zZBOFkWTwB5E|{38n!Xdo3Day|c_fX62nhzYV`f*|YpM`3uKD~6T|!)&^~89iN)g?D zRKGS_v{S6t_eYM?vvSokw;Wm})%tH(*xVGtuc+WRE^q({cn6G-Z%QWdQ(Y6DJV}~d^@0Z)E_bDE8>?y*CPl=><&pP$W?-cC zL1VjhD7U-6|H4WnwZsivg(_E`f7N5(9@lOOfY8_PW(`vEp z79kGdAEJy<9CX17MViMVd#wcdsSB}dth?#4sn?OFO+Jq!?d-Ye7S6%2uBn;5%gw*k zMB{$$bKbU03Ku-IKW2 zH+0hr;X_qDb-WPv^iJ7eY|s3S#JT1bIkpPC!uLzIIN(E%JNdgY-= z`=Io!9C5qiWK@p&T|5(IBB?@yDFtI(@{GeP>&@GU5~nINyN<5z=-KIUjYBsP=p9Y1 zjCon-;~?i-1QJfM(uRvx&)BXvf+-Bk#q`F;PcLJ6tFs@Hy7p5I5NGsg2Ozi8j=5=- z%?+LVJFORHa0+nVl|A_+66UnDK|vZp<;%DGRF1?U;ayDe!YGZmE@>G4{Gi=@I?eVo z6M@bH(nTm$F{!N zvp)~b1ma-~%sqL0dL>EkqDcuPtGA0PG&08O-k|II5!3lawquH1_8Q`=a|?7Y;kxbm z_i5Wu^@*#0&BYOO6}|#7l^f86+{E99ZDw+E9D2sQ$d$;cAVbj8P!!K*VQnfRi!cWr zjjfY-*L$7{V-oh|E8w%R%HSp4(ky#R+0|TI8$q8l-d3S0HC`TPnM)^>H`gRG@VwUW zqtIi+v*)q`2kYgxa#H$=KgmPE29Jk>ws!pV`bgom;*aB?*@rDYP3xtrot=`%Ld8k^ z;^JbL;mcgn3Qn36qX}P(Zd7O>1s7XDuN$%_?p?98Q@a!%$5j?={5JUS^!wBUm9=j* zk(yfYZ$f*9cfhFh-ANp{ArusDkeEVb3RvZe-I!qcB1GV+r6t0J@&3!_&m9HW04|C= z9qnI|$S%>GChiJWAvj8f8*5pHj5c14G^_-nV!FM!)q3*qz17#L$;mEAwQj-2C$nOi z)|Y>RZ%9DiR5;%~VTJeUuZIMhF#IAbLdUUX_+^rJ8HKz0?Xotm>KC6+S1Ndz7Ai{5 z^6`|EVmmrm2XL=E;|8k6jNU7~N+BpYxi=j%f!zUJReWD~v^uhOE& z`JTs8Lp3!D@t^oGv!-~dCT;7}2=l0EB)jSl6Iy#y8_7R)<@+QR5k(5=g2TdGUq=%S z1DHZj!`m`LDj3-vxWHbrivStrB#%Qo0f)_nou^`igZm$Sx?;F z()U#8T{qYVv}Q4m#Pp$4UYy;z1?_%@vm0P8CyGN-q@C;>Q6Fh(-JR7ya0R;!l%m9S z7oGI^0Ln`Oif{waYC!dpk&zKN4!G%$_;`6^w|@aZ43pFczja=W&pYEjao);&$+LSM zEPm4l97e!3S)xr0I&Vqd?YK>(FFs3X_AXeA9yc@pS5pGyqcknV338*CF@!88y`GXX zOV!AkZ|&DF3Sf8&-7h=+`(v;9IXgSsVx_B#_rwpd$BXn_Hemjw%5(oo61E{XY+mOw zxFZ^}89#exUHL@lUv2Zp_WcosQeYwg*@cwgK=~QAT2K zj=S8l!pS`OA}G%ZTX3U#HjMP-pL&FBU)ZP+=&;naN)Tr1@lny;V8(Ap6n5URg&}rK z*Go;DnWs_h*yINxm$7bh-CivL$`vTgDrL8Z$hi zQ7ZwK^|@~P0m>xip5r*@P&^yHIzI0nr&6eIV1hoO3A61Ro`zp{$&Cd<0fN7F_uOur zVkmf`(!!{QT~=IN`R}EJ?of{(O(qeHt5$f%{b@rlKbIX9I}(+a`gYWRQE2=dB{~hV zKFuGz_z%N&N`*Px-Qp>*fPesBni~YNd*6g2CY3_=aRn?fY=|^5H98kEf4^;}%w3UrYCF)m)Vm(ka~s8sFdyv^TE@j-5Nhb2Ox@6X! zfAYHrwR4S+^4@8P6JJ*l>61nI30q>t&4z0iRGO-Y5lm7rhD&a$JfLhAFuv0G5?dkM z1$SRHU9PO;Pg4oiy`s4Mh7k_+iJYHq`)2%FIlHVHvj|KMbh5AmeIlW2-z%9$4ab6_=M6M#Ta1sL>w+)h+)1eW7z2wLy3`P6ZwO9fi-x@#bbJ?q3De z0KF3)kU%v45%NwL-;^px#kq?`%>I$Nfg97EtVE0__yzawS>H;z2s8um`V8K=d^0)5 zTP-^0m1Tz7OT)+T{#)9I?9b~!v%Ja+j59xV#5`T|3g2Eu+>H1@)p&Z1fTKdd*ig5A zt0+UyLMtzh2PNQM7F^1mli^$l5WI=F>9O5qLs}Hpi3FX34fw%cTfL_ObtaUwgj?LX4>X-AfjJFK)gEktQ@| zw!ul=7yU6EU8E zBvWfIY=0U{smXJwaq%n>f@1_qa)F{v`(dXEDYbmI2A&Y)OIT#6RciGukk^<$ftP4y<*z?~ zuE9lsfrgXQsm{WIRtEuAmWCOi?lt}9_0QvzF0;ql= zli=n9)ny7x#&CABI8wU&ib6$SPj7fY*A@k*lhOjT1-%fk)HlCyHDNqe8Hprkb8_<<# zF#Hbb^X2t&R`3}(IbvO#YPfduwHGsfiJL>(2Fgu){6DKzkA$sG}xeMcaS{W`Ij-w zQQe9*S@@IOa3t#`L_BVyZGP2GCwij1Pj=QZQT{Rm_ilubwCNu^HHsy963J@I)H|ne zZaM8H<$OG|k!M|rtG9_;h&3jdr=!5*FL!+Q_3KxQ;j5J4-5du@V#BH+9E0|X!p~eA z3Id^vAjTAR^z;2tb-ex4YL!jBGY4fXWWE+T;AcJYx{)Do1(QGQeYGx4!iOKh5TO67 zYDyYd(ioG3O{BA?lh)SO1=vV_w1%Fa2}UZ9dUmOxcN=$7e8RezzAZBT(j|_vO3FYqIwR5q zmS2~<-oHsbBf6YIch}gL`dg7q7x0DEF~gFJk3R3+aZnFCV`W#j`& zFDobYTUf+LZ>OfFHfs`tD>=hSx&`qF+wm0-C_{^G-2b#(UeL`wX*{vawLU@;w&)si zV=;zKg?;q5=oJ6~$Yb)F%lbGXoeb10oYcq2i8wr$(#;mYkf0D&T`_Rdxc%mQPa8QZ zlofgFI+R$Mu<6K>bKUPe&?=hJ*EGdy*4caH-pYV7tu5Gp=G?7$@Z_CLx< zTdv2~dK#)2X-y)=C0_PO=!?HHse5!K0UJ`$qOy3j`{~tRS7qhq7LVyET611Qk_KHg zPg~x+AxEH1>Zk5vE31Mjq{p7f=MUe0;s6kpm=Z|)gr>^MOGgmb8gmj7E1-zj7#Mot znO?h(+HHxUA z?|7W-sx`_<3%#BFbpv8krVj2W_S0M2vp8hxQCH@Xc5Rz2symZ!`H4ojZqg}VL7Ktr zt`6K?so+%ZG^>nQ#8p3-I>T1J&+|;_)-0K2*Ss~;h`gJQRCe#59SbT;G4_QVi>jmhUn@5I^r{5jQtR>Qxf(|u{U%!BTQZi0lW*3VEOMuLUeCrr zyhMfR91HmeAVDhtIz8KRx+p#Y8v#ExVR+^B8dpfnQG52&Yo~7=XAkJ#<=>P`>|ffd zEGJqnvD=6c6aaQ)r8`ZBm(qCuHu4spJI$)^Gc#m(f|xKqDQMcrmcC(V+tSi<|LkzZ z?7p}dUvy4>g&Zw$GQT`sSX|SM882pxfl319VDb6&&36uPVPS8?n4hOhR|2SL9in1w z4})y9dP~P?raO&9GI<2L+wl9@B2YxUm*@ZuFVm`#fYM5k`@1w2$+n>w(u)sgzE@ODsQ7qel0A6iYzn*CC|9@vUT3 zKT%G6=F!COPxeGjuEy8+;t1#LgpR-ccg2Nbe|vndu{R|Ly)oykN{uQ0CBKiq7~PP? z^#~k$rm}<+D^%Ofq%B%yUW0|P2QB5YXuajaA?bWGa`5R^E17GBoqCW^^0@t`Imt!l z_GdHRzGDtOSJ#_;)Hstpb;ov?dq$%uNEE8$@XMxYv##yFI5M#|Fc|bg3-h|~;-26F zro*$;ERn5a`ZLpKlM8SAss57Iz>UH4Xwn|^?~$js zNYTZIkBV|c%}h*WodNb6L z$dF9y2aK4a&$zo!nIhT!rr%S4@KeP5;R^h9d{$1PRN2VOqg>D7!G=5f?kxY>_9y&* zCC`t93ts&-d=5#|7aem6DxcnwWf<I(whfM{YQqNl z@srv$f%L1mbNFl&ck$U#pMZwJpq>{f+6ELDO%X;gf`;Um zxPj7Ase^?`yWmj@99YUSKq6$(|kW*CnM@zL@C=|=TC%=tO ziOzCtft_5{rCRHkFokOAf{nSciQ0>lm%BbUjnAY>TH^wSt|1gy9fEit+~PM|w(oGt z5`KF?*iO-Ua43rVI0sL(*qtat`DRNXbQkCCtES#_8W{3-o_jWXQi8+Kk!2OU{Ln`C zL{jlyU4EyUmx<6%`2j{J^8>F;l_*t2Op+9tXHz({fO}BQ+{BqA#M)<2>RY4N3zAjX z5M;9~cMsq@zjo9uMx`>mjXV{TecmY=vPH};&fYfz+&#y#AIGcB8O6}=mCQAxvN_|5 z|Ju&aTKD!IK(ebf0a}=;_DY0_{FicqbTR65W;)t*`qG6r`Uj$KSNBcV2af+V-GKQq zU9FgtpduJ2otg=GdQ&T+`@w7Ir7EW)Ff*#QQw8A_0A)+t0Zh!ysv?=G1;XlLxe zQkeI04}F)-y&LyD)ZJaHA)J5%c3>uuMw`mmxgfT*|SQ;*46gvvh7ZgZ~ zePp*db;phj1BW1X5SP;U4}wbFX%Jr zziZE+_r><;b7*^}z*-c=z0|PBF81U!3pE)`supuAO=M5LvMN1U_%M5H(cMDKMflTy zX*>VC8K)C-!5H6_w_pM^16H2Lusv7{6w4= zzguw}nNhS+d>=K3>9AUoNdOA4^fiNWdSqo<*ymbw5G_gu-IHqg5+p62^{UlL(iK|~ z6&u;>5%kT`6n1f_A#qtYDcw3wX($TeWf-TW1NzhZ-ajigcGaW8+C5m1+!S5M*(q?lF&Z_M5i$~RNzQujUH-!q2N6T3Y|VS^8mq={czejA*$QW4ba9v6tlGr(`H)V zqm2MB(IhRa1sO8XW&*@QlwhG;S!Qh9?)$?(H1zx+l3c;x-m{k?V~G6CWb>w;4T;?( zK2?rN(eLo2(n}n+1m+youAGCGQ>rcNwm8r!d#ii?T)OI?f$fHf6}b|9>skGI%COb9 zp~bQMv$r@jFWlpLGo0Crt7k*!u-Oob1$PI8J#^EyjR1+|qbhB~`m5@HFJZ>-N%u*A z=bNCl3ba4L@VSK8F1(Fp14lS-e*LK60TP8qaFsdhjQHo0cVRh9ik^(UL)}Mjs{Z%5 zT|s4G_%H9-HNOoIgIzGS(8%CqhY>deCw?y5>V&?c;1bH1`!ojPfExAOJ&Me#;#%9Lf z8eS7~s6zQ%Fhu`ZGg?JH8pRpg;mgv_^TRWJ{+4p@i;TmjOXVa%TaHS+{k?l}mV`~N ze=pI0@c0o#yUpeo^4+keba-bv|Y0G^!ZKf4dL8z8$3!t2xp+D zVIt@&ym4eFXHS33_T{aKSt=c52X2*}`u|LhK^5B#3XV>+*Qs!^2>4tLfF zxjv@#-$_=S3y+Dx_T2>sE7mLv#6A5PZa25*-uoHjam zh8#xa4N*J$`(`_PVvYh8VKNEVUK+Z64am^q!BKitqSaqYOZ&+F7x+h_!R7dB%q!O? z(&x@WphWF%#ycz0_DGX^rU5m?>?rmp;~#lkQEs1GIV;x(*H{gIaLGl~AF2=!`y#=} zL)J5SvL`H9lyd>|nkiWAdvAB@(rW|Nj0N$bKqyjxcYz3z4@m$y<=Mpu!choA?6l zjT3UXeU6(VXrEbWNz$3DX6h5tAVeP)-*(!5KCg7?i>K_f!4iN5vpDvKjALG^kot#!I=yB`y?0TY z!c|N?X$?|PjE{^6Ef;2SZyi(&u;1G7snS05>+w=C8NR}#gll3eIbJ@lAT-eNaQ4{d zyW*!VjFsz!dp&uEk(V_+Pn`S1bgFQBBU6v%tG9GEM` zH6Rk%Kgj))E}FnhAe~cp3{#R#VpwWLn^R(-ke~P*F3}i9rk#(^PMO9mRk?>2>h}md zHEoxVG9P2;mZDfr<+gSr?r9cgkDulxH)~tyN#3J%=jEikX)%wRP9sN>QN{c@^xz6) z*_?(d8MUDsGOiwl||r+z-LNQ}~*9@=WzKxotZ@AjnYHgOwtJZU<-L z-SFr_flN+0x0FKWH{XXEIKdyzcl2ygNF#^lrDr9C95{LV%`5X3!+~^i!|^9}PCZdx zpTV9V%Ayq8Rja(P|Hk%2JdEc4^PDev%-=UoP5Nt5Nco zpCh)7@c0{ZB5o=Hh~oR;L6NZlC9wvWVF9~O8(!g0*P;~M15H1M)`pr;HwOom2u_Tc z5@wW~68rU;mSQ^c1D~?^3m(mzv1c!?)2q3LD;u%v`?i})i_sQ^P)z}fVuu<`mDN_ur&!CU3aAm-H`NC4$sZ}@V~q300)vJ}1bA5l z`b`}$N)8bweD{3nrbH31Epp|8rMJ}IKDQ*s2UGZ{ji4Fg&sb`4Ts*txc3ZaRBJucQ zt3PaRIY*m6i4?;3u$nZ%LMK>ELk4#;`LS#)KZ=%c529vL&++fAo1& z^#@aTXN$6tWFkO?Ee7~+gdd|QZrCwZ{gGv!G;q?EZR)L_x!$Lck_&XE#uqJlZ{vJuw|nB&FH%fEbl)3`|VPvm_E~R z!OK&pW~Vvb4=6fHm82?mart1(1|m@^WzP~hCRXie>Nij9m00X-BMA#)wrQ$V|{$Iugak z9&K}j-WWgWyIm36b(2m`#ZUudM&GTUV z$$64YcfWZw&OdT>dHOf&(hafqr(8m~6gIl&AIO7cvet8w8(D?R#vCb~H|GLz+S}<{ z=cu25R4MnL%UUc>z0u*5x1BqJyy@k%!Tr6l*oWP@%~l^KC@R*5FSlW>MXM;sSxBC+Wy zh>@`3b$)uw=459VLOB)a-6`g_<;h4%O@0zqo{2-1Ej)Do{^q78z?`#OeLyjgR<8A2 zTdnl_m!;WNcOu^2pZQku^D<;G5h1v+B&-iSc?o}IsXrZN$y&*mASp6JYiWTt79_C& ztndn}Emvvze&SbVoCAH54FR4~V2c2SyK0TO*X*%m zE6K}Fe|_IPWVvr0b9ahTTFt2^ZIeL(G(121m9tD}F`Wj8znCM7iF2ZXX18Gug-D7p zz}Sk1o5CR!e;-lr)D9p2Qa?3i`zM?rRO>iMZUcgT=EX-6na2UF8_(BIu)-c?v7-Ew z$HhfRu|2PElt{O6BO)CY-<)?7G3UP^L=fHKh+;Li(7Hh+wQo2n`*XcK2S1W>e2s1O z{C0gzR*6MTuQkgx&k$x%_{+Myo=%EQ(&3$#Nl4?r>*kg$>jV1~GM5lx*#o8lj5BEp zbf>PcA8VzQN6Auo|X*Qv|B2|;H=p_lAghN>4^^{9?)x;2?OmMjU?0fh?M9NJIlOR{l>skKw zw%#Z5Fn#WL-3glPwcp(q49Mo*hWP0j#8Zz|&zg8XY*R3deh`y#_Q~tSx%5{MamvWeQWwQx$z++JRPjNirPGV*S8F zN}_{k|6BkzTn+LUU%RT4N?(s>R6CtM61) zIVbvzl;ukeQRalKtPdaUrK|2f2cX$I`?(IE0|}n53^;muc);pHC%G~N-xnP>vMK(#=_TL}v6wb$wS4m8lU%XmEI#_CI5qS)C6* z5UF?w*a5~SCq)h4l$A-uNo?q1bF6gRd?btKuhVwYpU#VrGZm6v^M9nlWBC1prwz~3 z{w6ND7TPi8qa4Y=eP)FCPJ?;4B;Ho43n!VGi%_+PmyL9{z)0cNTYuJ^xht{it!v)@ z@J%O#37k}RR=Sh|8@wgJF*Y^(0=M`+5jRvs8C|o?_sO zQjmXNM*LcRc~3HWm|rjwQ@C^fJluKuQ0WaFGQYLo2>}QSaOwl4vAuGS3VG+CT{0=p z$Tk{(kEZOktyDn-H@c(l}k7`5Hs}8&2r_FfryRIxhHj{*?u5WZuE`D&r3! zUduf&+86eb5Kso~uD*i7-(0uN?HtI^2$9jz(N2~C*uVLrRPzjyRq%Aai~`nH@tMR| zUy93)l^DdlaR$#`3)f2O5DAR=oaMAdq8!Z+K;dvf1!O%Bk$(?2{Px|>Dbt4>+cZOtGl!B}*;J35!>y+n=qAcfUu$Xcw=+OL_RG<%m_4MyEFAhN}a`4Q)l280y%_ zfSH8^tl-*ANtoi%dWRB#E_(h!TCIlMqGuUZBjV2UBY8d+>-}4b0$mRFpUhXd)Qp=^ zBs0Y!NR}OIYJob_9U(??`e9O$Q_bWO6O=K8Tldu@Km%W!F;lODQT%mWLJ(A)BetMD zFsrmDGJ9kX=MK}0RQGAMA-4fbxsGF!2;CQ&Hsdc`9NXs3m2ai z-nuD;&f`(J17=ZGiKhiH(1ZS$hsUd*1p6*`^JHqr&OAe-0BI@a87>-!@0B&pU|gw~ zgqAMF(R=|8N+%r4#6rBdEJKajQ<->sR-@{+Qe%+}22MFn)r~ra2P33H+*yPsVo0#r zzu9j`wwhfw?UA(m$h>^tlgdT)2?pd&@M(|=Y2eAaS}9G)(v?l~M{tphXQH+wPi7@W zKHg^?>S>F7=(UawMTiw8|5Po`t<_N+o*^5G%y1*Z&equc;6&@p7^i~_Ze}(?l9~z| zFIH8sIVF78%dVKK@_6;rAs&ZDzATZ(-*YMA!<3_{%fpo4gTBmcCJYfGnND({8NRI# z&xO`XGAEFw>*I%iCpj%MQN=JZQmU$Qe=iL!vSM}{$Jr9E%@$$8lO4@%lR;cN2>RMl z84>1$)KK)+xP7Hr${jC$Erpi=F5%*wo!(_-@q!zHho>$xXJ`=|D!8guv?S00xUG0p z?=qD-DImA>basFSXIh7s7|7~^9B6V0d_rbj7jun{3)udy=Q&w|xGVEXM2i&3= z(&L;G9(Bom=Wc9rN43IZ26_fifyV%PQQE>6E8OuJ0DhA_E*_8?fc=RH^Q2EVuLi7r zL^K>)?}|m?IvlmIv|I*-LJfo&XxiPnV)Ko7ui^PL(yCQ7RhlkOMaZCyGP*@;Hu8x4 z(F2tdW-~)c@GL0b?Af?QeIj>27PY7#WjToydhdobv<~SPeEjw4sg(~I{H^?b>@aiR zkzypA9}3-h2ZtH+cei}ky`esuFu&{TN3!^6jiImhWzQDBBM;VFl_r1HNa6EyUMNko zoxBI$>dOml*rG)4T_l5kPMi5#u=3Ql7{Y0N5ML4@ zclmvA8iEC(^2@{BHGL3tDNGf&VWavk;YHivqe01KB7RHZsj;bzYSAzjr-={PxXhg3 zT3_}ASdMzG>>C1()O|0QrViQy-KA7g>{zRKVIF7t<@0QIqjugE#j2)}v> zN*|ai7Cr}aV7)5QWxqGOs$hznAvm|EO0>vFz_hiFl9_kOsuEK)mF)tB^Z>s+{d+7Y zYlij=MW+?h)Wv-38^(VjDvhPf-mtG~or+$a>-k_riLhCa$@rVy^=Go>Fl0s^<5Pg|wT|K9;6GPev!CY0~^UhT=E- zw%Xro$Ev|0kdyY@V~*8k>tB0#fh@3RccPsuwuQ_qX~ znm4P;0J$I*fcXzTEIx9aBXytCgTk(w#)Iw|V8eb2y5H_(Kv=?trsv(e=|_xWy+&fp zkfD21Tbl$f!mhaua(;HLLbHYFpiq=Q&4hn%&E2tx2l%1+W2JpyZE7XX7p(zw3R#ZH?JnV|X5i|*@ z=-%n(auZ`a!EoYVwYqn%Zh3P4)WdZ-E#LU$!TBvSlyDks6ZE$l3I3HBqvR&_Ol2?G zX2jv+_bYSSv3Km0hac@zP_;C;2f1|r!fqUG4Rr%v)UHq?b_A(Rp0-o_E=Xe z2Q)uJ-|UNO7aj5AJ4AHqSTNC~Gch;5Y?1l>b8C8~3rkMfOa@DBEa};^&DkNaG5INo zrvQ`vOV`=&8rj7n10fV8^{C9Nvb$o;k&fnyv5kO1geb1aK$DOV};z@oV8K317#A#inP;Nbw8uMn}dm&eKDGxwJq=+-{&#^TcgJ($MMt8 zZane5rlqq7`FrlccdFafU!B2f`m~zP%xOf)3$R*Y$%V^`g_sjM(@1Z;zN#VTx0L+H z2!aS$=;#2>D_S`x=G4|j36xJ0podb_G@uqH z1+5`PD>5v6YXVR#V=qIgB7sxRfAq^QU%q^0=~4HJrS(}`;6=aV;0WI7yp|IxQ@qRw z*NeQ;d}w=LG@~{q!;IFtLMK;EY^RoDPqA(?MMN#pFL7-N!kgwWyf=;{NK_PuUl%Ug3)4>RL% zyXk2wW!Zz}F10^wSqCKjf$T}j2QHUO!Z1g4)gq!Ow7T)3EfLN5*q0<*X{%GgnH(R-<|_0ag1HhwfN;_*E%U1k#x+vckl2k0APoBS7?D> z+$!`jk`jV@A5b6fHnfOK+abn}a=Zq~jxWGRiS0#kbf+9Ku4o!a#yl87nH!C>IlVJ4 zcDmz?E^KHx1FnIO-QB+iMW6ONOxC0c{K|nZX+(HGlv)nzDFW6p$iv_D3&8SR+K7b0 z)?lPp>bvsZ<#LOWggh$ej^~PmKOSA0xky24@6u>w7Z)pi9(gdOglt}iBa#wCw&9>-s5 zp&ud2z1{t?S@9j|H=DblG{gn<+*c(kPqc<56=`>MpLL#hZaF%OjD{&+F;k5D(<$|1 zc;<#)Ziy#B_UWGs5#DTi6mWIpBakYY*9`04Lnw=@2(l5-81V#uon=z~J^%{1+VP_zcFEZxrp5KyQ)nnH z4RCRA&}hC7+e_!)b3ocdL!+UU8(vSk z8bh>UELQP3?}264$t>{g5 zpPo#X8t-L~N8Nj1r%*>`(v&WEHG57!Y0GeEJ?Hy}|FoOFle=@Kb!9c^-1diPRe=HJ zq_*!)I&WbRfWXS+T4)6FF4TBkwkU0&c(6RQ>fjudU;DmCU5ZEjn-4+@QyNRugFDuD zLZP3ro+3KJgOxZl2p?IlS9aDUO1nt&i2&?^#dX3ct`6@PS!+pM_UEU^WORK@P^Ml> z^?JZW`T9R@z(ZWbDBIE*kFG(Fvq*Yux>N$l>vwi|a)xe#yan98AnAMqzuwuMMEG_T z;CxFH9+#m48dyM<PyFp*S44#-&N8SPb zHZ|mQ@D)F}Xiz2ZHKba4i~^$8sT@=dP(R#X|1r!#+pr)SM{?C&&|G8Fze+e zy}w~PBGVd)BzN8q+j~At-T&z!fnT>bPiTBk;`LlyeS#WD^Igurx}&dDM}l71;xl+p zK89wO60;A)AUQ+vq%T@E`I`~vwuUOuMd(;dGa`urPK6q=PY8&oBfC+ zJqJdKR_`Krv|Ox8P=7!E^cm_Qvc*JT3;qHNpK(J#X~Lf$)B1v`T13QZ;w>f$^Xeq8 zCKhFC-1?M-Xq3#Wfn+iC=!3`->>1x`s77U=x?9IM2jy!f@STuLn0impKv=(zVjtFg zIgmRyN}lG5d06q*ZVFN!VDJ3 zyd4AjB|LJX(qZ5xL19t$+o;kkjX>iq28+iRH5?QaL;+~zgd6hmasHJPhdeb>>{vB{ z-0?qWHHX)>E4sGKg7`v-efY_m2>!cb5oSX*>4_Z!(Tj=y?s+>Tw~I=g_Kt7cvW5ok z1A))VXUolT(dr#a2&!jimp-v_oRkcN%QYu|=zM6V_^5Py^V*ilBZ!ti;q#KNGDgM>j zEOblId3%w*+gs+Rz9C%-6Vpn9uO4(a{zu0_CWcN?AyQ&o+?Zfx4*tqQCEN3ZK;3E( znjEvjg&h{wGSD!7WH~AWd;%SU>rzk6S4$UmJRlz0@`5BNJKz8d@tFp0N_Pi0VjAWD znAhfKMZCJc*YC4U$l$(7WbgB?xA&@jHI2U)9A$AzK|9H``Lp=%2(Kefx$vmcX(S@; zD%zze;qzq@e17d!Y`PLmmDM(+XwaE$q>Gv+u0aAcPvR4H8js`N+0XqF$Z(u`GpU>U zBnfSI`&F6eT}<2yDj)N24=5;m>Q%JgjJ@zQ5VQJC%HlHin?82Ns&SFs`TeL3(L3r>7Fhfa}6{-0RK!+0MQ)@TN+USignI;e+x|3;nR7W3G@J@PF@3g=zriS zot?dXL}q}M@gau)=89b63tzUz*e?5bwLn2^biBhk>LYU0)6f2Zmc-@%TzucF923$W z-u|2jeoK^2KF)iMF5k`ipC>FeTn5wfmr>RWtH5NxpOShdIE7&E${(o3#7KpWhG`|XR(*>O{-HksIKToW!ql6pb#IDYRIc&gD@h_+ z57$$e)8|z5v&d$&sJ;(&m?_pqAWL8G9qtU{TkHge{nHL3Y<7ZpNAraRa8V za59q<&_Aby5wt@0TU-JuBveWA>t6z27QFuW!O=1jlm_7x#>ZF0uaR!9?iY(BN*EX> zY~TFrIZ`6W${IZ*84MQq{!?h#yl>JDA7*T?OdKf;VL;+K?z2B_{#v73X;$hKW%w4c zH_vGFmi_b+l=!-%Vw`ebxm2xzZC##b8EHy;Us#%u3c;h3(qUbdYfYc?<2p|umug%$XDPW=9oy9)2Eml>cYHmD0IS_P~m)tE2)K0UN4zYpE17EF-@1#V_ zI(t3*Dd~C4Ki&0lh-*FQ4@m(Id^Vk{Jl=fTqWHe@lS55d?V24J<)Y{Cnqg@X17Y5<;J5fxOIw@m7mwCm0RaIaFvI}~aQ+$PTZ>=2 zBENj(AzbDuOHQ0RE}1^QlV5OZGmpo>N)xOAX^}HIphQAk@Q}Ppd>wS>G6bRctb$GV z1ZXwv)|t(f2kU1g>eg={Z!0bkCDYa1ysw&N&dbV3K}x%5I8JMZm0nTw5SnD6CES`+ zDv4u_CMEjtY#U34#}#w9wjbg`Qci7wyO>EtaKHsGV{U}tsd`=%1pN@wM*a?%*-v`i z{D!UDMH$n^#CS;a2sIU{^^wSQqC(7dY=`dK1~tm-xAx0F$Fh&{CMQpJl>_wHoX&H8 zj}LGV>^UlR6&jdVb-G;R5h{VSN_F%;4#)=e>R}L=t0C#)A6HwMxnZ8i&07BA-OIB8 zGe6#46p6E?yXAv|SR-BI?D?kve_1$!nDoWa`O|#YEF;PYVVc^0^u92oz3$`7^q@Zk z!%VE>wQs;E#3m4fdOuc;l$#Ls%t%5R!!nO*&3%o}BpdnOO|XY_0KhJ*Hu63uW)4Cx z*SPp~MD_oh+CTwYR0u&l*_k=e2#u_RiCv&lO!#Rxnn}p?z6wjw??kwysve(Mke9)p<8wlIfnf}6})_WJGoXCas8Wo!?W- zeMOXg29GIae0f@_#rU{tusOJlfnHd2=ujVe0-fuuVqCL03CP?uH4WMfM(EoojeCtu zjtneSQ6TPn%cZ7gZfHoC)GaC^GWNp4n85qi(_&+ly>H@-jSaUxXE@PiEK=2pFQ-a@ugkOR?27+rg}8tc)Yx&}(N9|&0VoYp!= zw;cQ1r4#G7sSBKOWPuZSoZVUDMf&HJ z6ZbX|W-5#u$42I$5x)7K{Wx^2uFSnh1$NnJkG&30zj=f8V3~zZWBa#1fBrO2JYUt5 zcxf(ui=`1ult;K!OhvP{lOsBEC(QeO_DI3n8N~^_0p|HC-hhQxOv|8qV?I8jr@TLp z4X`FeY22G4U_x-VCLg1*b?>^*%e_hsc-Pu}e+Y=RYu;0|6m!B~#cQ0?FQ+^Tk!zMS z>tzAzP+VVW8|4o5TXS;M6v{fb+y)Oyv5&Cvq{Kq30S59SV{Qp`H|SiGnV78P4F^+t zstS+T2FknMo>LRM(#SfbPLHD>t(X9vK!QEUGlc&_Ue$kDC5`i`7!Qh>Krc|1epc~f zA|haNlg9UaPQm5YslJFYaJ;HC^hAxD4s-#TH6A}Kp42+S)$JKy+GB85Fzg%L7irh{ z4Z)}jr(1J>{JE*}j-}M^CvA&)*BS^FDwuoPEs;~;b6wy=W=Ypr?9N>htFSK%X}X>GME&?;JA;%x8N#M`!AC0K zBRiGYk@Fo;e1hyhPtXHa0;|Y>U?PsWn6fFYh5y)RaCk-NK0Wte-}kD~ueRTuRO{KD zhF_^T`}2z}7vrAdf<#;)6Yu4pk8f{5Z&?s?zz9a^Uk@H~m6XmHrD3vobO&ZtbC)9S ze>DGO99LBW)@`BmDB*WtwoSg3Y>SkXVM2lW+e}Ou#vo9lxJ0xzU)}hai^u$`^n`ug zfOXnVl3Oe2c>A^hhQ$>m;!L(Rpk)Er7~yJ*13L;B_u%*#&XRSP0>J5iVS`|CK=Hr* zU&;Z1%tpOWel@~g2PnZhoxg3Zo^EfMl8 zz#A|8d@%L3D=3GdOjZjmDVznen(LiPxg;r)}K-6L2-fQ|46N#s?Wv_K$ zEcjC_Qsu}R^AmPF!2t`xPY@FAFnJf zrZs-$9?haq{q)C3pd`^|^jtISE-tNk@%q83*l{fRw_r&m)Vcw?6 zSTP3kQ~xan=1HUNE2L_Pa}|w6R(z)Lw0`h$&8IE)uAF=AnhJFx30*++_Uan~RL-0L ze-;4bg2Q}QS2H@ZAfK^zl>7PMwR~L(W^kmGBK(kIyY**%y<)x#FihsI4j-=3Qdi(a z=`q+;+6n((y}k(~9|FBvbu^5~HGdUjLs*Xu!<_ZvATas;hYw(yI$0fYA5Dt9S&_hLhS3-3=R4?ehb6rP;p2 zr%Q85heNM9DULh|527EPznWtzQYeakBegmW3j^DJTaTWQN{?@gqq!Z&7>UR|mAUS` zk=u;l?Co#iAw+k61cxSHing5D8MrXy=bH5z01r`N+v#&Ct+DxB+vg?uvpSOL1?r?~ zT3m&>Ci)m-W<1phGcjWQWpBtb0Nc*VHkkqml2ef1)O1UE8sz7;bw;u|3xPM&*#;fX z<2LM-qe}`3*9P2Y>LsA%*eI{3_aC*0ezb@o`^RARYcavF`WlK8YEJkI+qFN+!^ME; zj^bWySpAtSN`R4vtPm8Q8{|2ulK!9XJU9{*My12?RA_n-c!tyBmu}|mY_3mR$--~> z*^~w~=?VOUA1HF(2Pntc{7ax6p@s%uZ**D6U^H5m{3h{xyJsZH)^lHC##Rm88!$uy zQEh>A^iT`7%FW(DsY`UXQ!%NyB~|Xc0-d4_ZWrLlwecI#WNN$aV5i?`|0N;ZYQkT% zM*GVjt6ixSj*@G#-*X0c|6-TgY_BU~N$3;S8Lq$jIZ|5rrE`l#UEqrTpC1f&HrY98 zI2_(uH?bqOtSRs99lAeM4$XZ@lCrl-bfigqgfFCifnL_K33hHBr_LL>QgIh9zD#KQ zd5=^-is?B$0#Vm{U{n6`eSG}a*P2^uuZvRMiXnf2y8RVl!VCs0LV0UKv{($qbgjB- zT1FS+kcG&2oRa!j>fVaIr27PflOQ*WH?!hN(McxPfx2J_X)=IxWFVGc3I!{stpVNu zocQ$WSYT**< za<6uX%(AE^FG9sD4uMfUfe;sd2EjVOv1n*(Kb(J!W%&?F*cL-5Tw4WfBIr*lL6Yyr zkkDnzN^CVDYx34Yb_-1R?q|_YB78lQbw*DEKVOYh-DLc_%$DpLb2cV2m*nc*$6TIm zjr5OeV#X*U#)AIr*N}`8=QHBdzNbvprdp38;R+ua>5bnQi}gl-IzE8U<#uoJoE&8T z)p?5Gx2~`pstE`de`#h`Z>#FTwF$Ye1(Nd#G93hmRo-6KPd-PqXJ3~ zl7!V2XvAxccU6v-+9kK}(Io%^T+8LD`WV9fqzGVCpE}CPnpcvymmm0_+wM9|3bx+5 z!JkZ3avb@l@l7^6ffNC+ht{rC)j>$(Ywk-ok>LauE58gHYu3kaO4Rt#2palMOCdO; zgUsO?zq|lG@PG^v(L3hpbRw#i$?@bTEsKHk^&Ui+yoKE00koi@k7zLyi-;+%;LupL zbw)FYNeC{>&V)nAPlw+-s3TA!nqnq-AEm|a82*hk{z)$T)ER9L)u)9u5a+{0^;%^H zri|MCh3AgXwf)g$3Rj5*0d9A7aUsQhYZop6nHyhwKPCype`30Qmr^`QeNh}v6|qzv?_kND&3(ZA$m^f2s;<YbN5x5Apu8esvZ1_^aC+|j_O*2$9(k$>n$2yLMb4GLFK?X5E4Iv8H{=w%<0S4m zBCU|iX?w6x|m z4flmIzZS56HAq)2Cct6%CBndc3Ph=%f9AkR@$41x+jFF(vT<}GWyPe!BAgiLgZ1Hf z6RT({Li-yN7xti*=ayw`E+(RzW z6!6|w^J4ue=$*_-v_uh*NRZqrqs#WyyJ!!V<9mO zXi>S4+A(Y(iN1kD6(;?3Nv34V0(+xRE_gPa*S<6Mi=Y)GZ4bn8B5H;r9)(CZ; z-ryLf!y<8RN&%_iy!jlTX*BK4W|f}EUu%>GUu%>S%r3YvIo0FitH#(FRGRUP%DCrm z1A+tCF`~f?-!lBT2FFeyC?K1Lggel$L(RJ>X3L>E$1#}=@o3(63SPOHPI@B~NHqQzi#7$gsmrq80e+}Q zJK}Bf?>=_mf<6KHO{p77^OM3zChdB}bAGoU^|lxDh-OKA@kla*8ZgTD-X1S1d<-5D z9}g%wP+_6HCl^AOhcET`>=kscjK9PA3;wt2_Df;fI(U{?s-?PEUq;#U4Q?inrfric zpMLS$#q6N<9^NFGBlBo=JlshD_s=@cJL_?dgQF9CRT2$<&Rd0SkK?!=XQF3`a~k16 zXM2VFEgwqn_}>B$Ghi?8;X2gRQ0H6tyX3JQHX7d^Ocr^o9kMKhK68y#U2RQU;U(F) zC&a`(v(;AZN;%H8V||x8IqA_rg|qfo-0r3ZQMIju1L3mYgOQwZ$WX$?LxMg!0LqDz z-hEP_V6pPT!yhk*;6Ek%ZT3R2a{8qRWS%wR`g{vMc-n>BU z{DA&#le7JC{rK0z&d?==HgAoN+l^#X$H<^$m~L zQTe(;QO~XHKtzPE({qh1gN;h$;(G`{-dHR9{Xpa_-r}naM`^EcSWe*Ym{Qk%?Ru@1 z2ZD`<1G(C0h|K7qj@jPNkMV`+?(S{^j__k;rLD7~hIpSST2^*;dSI8}eS$x6;#8cF zFlepmDZnj+-3Bfp2EaRH+)vv>hWV0w{BRe3kdm*7`_NC?muoH&K#4 z)7gTWacC4seRM_qTdBko31Ah!d=Vfq_Vkp5p~OHW9gt-NfxN0NRS4}ZA^+a%%^?-% z1iGS1vw7cK=rOfLdeACzk|0XD6a=R79Q<5SO2#26KeLR7ELOqHXtnwCygGcd+}hI* zh(r%&5mItNVViZ!_TqV4qyses(D9@DG;C8h*L=sS|;nDE- z;{GWZGjOkXz@WQzB$OxHySQNRWh%w4*CcAxNL_~06IXT|HHN=9Jsm7fpt_qAqF#v5 zo4@px$wO7xq1U_1>lx1-k6miNo*waHHAS0q`Dc}5|H%!3QG3>y?qE97VxEN(3}&GO zdykq}V62baL(ou|7(Wcor5h3Cif!J?eYs==XF-PzXT;q}c#JVdMTFhn^Y+19S4Bed zEXV*Wz?76+udvXm&arvtq)Sw*2;Rqm<-Fp1Al5Lrd`|8IX^D}0UUsnF+N-|QO|oXV z70SPA6XE1f&@VHu34OU&G`aLOaQ;;&r9pQX6#^`W@`wk{0l+8FlWO)soso1~(`Av* zj4ucv)Y~}yb59QWmPizBCFouMftF)pOGzV=;;Z`J^oFBk3r8#E`{77#$<~)HGvRqI zJT{sgBg^;!VyI8#GkE!bOnswv%=_>7j32LERFZu=we|5WTkrP`+7~6pb_ni_A;7iu zdG`sw!9rL@4k36ANuI2q#~A2F$mbMmZ!3%Ra_C>odVTeTq6R(_7N|>WsBj$>z+G=C z2=N8Ul6c~jLA^(M3d?-*+Rr*Qu^g{1kjmrzB6cx4Y{1Qvve3i4 z{M4VIRmOUwxPRfg=I^t+AW#ULPvIPuc_zj{Y9YglHb5whL`3FKjlX?%ON@8pjCa!` zPj65sk}BRZY9$F8KP8!r#Y@QbRn@Z^pQWFQhA$d}62bAHAO(gC_cIXXD6ilwy*F2H z3EjMnYF$hG3a_2m=>tCXL9NXM&B30d@M1CH9IpPSUZ-4<3D@_{PT7e@gqCf|;%k{Dp=$JGA##Dz{>I3Q+Z1$OMlVQ5x$PdDpUT!>coT~zN73Rx zdmRUm%h9;aF;gsQdD!u9+y{js?6{%hWNvbkOoFWuo16XQu54WG;cA2T@%BVytk>V_ ziCH)bsL&lpY#EN4yS06p1?uBOHb+mEC-bh%b&Jtf{9EK%2~ouxd~rLQf&?QsA}S&m zbNeJNSUIUY_?IY9y`v-3(@9~cyJ6i+OBlXp)P4sFT|+lc%~a}$fa1U$frhn{-Ii`= z|<3U`i@ot|v}&_Udyz6Jhm< zs!QeF&^b=dRk-%GAi{-!E01TnEJO6If|l-hlG`sD|K}oCi_zSh0Y^cywy;G1sv}}L zhoJ2%F>o7tMH4=8gD=h~kn^&FLSdD@zrW>wY#a|vJqL^G!#T`w~{5$+H~Gj)gg0Y>33kIUh(NJPuElt;WvpC{79-fC;Tx8_ey zP83(^@KCpH%Jf-r>O7uZ4y|DbufZ*Q~eP#J9y5nB8g91v zqvh*LO*AS}mI34O(YsSoHJY01oPt4H@Ao(h!!|OdZm*iVbLA&1<-?<+xaz0DfFo}k z$LOmU>e%gtk8NeqZMNj5O^|m>fJ?K3knQ#Qi6&}5Mm}FM`EW-2UcevU!+ScH$dKeu z^LVVW6&pRwR47*B(mT|DUxw5k(Ps#ccdYY@RoNy!e#{S9ytgK6{Hs6XUE7ZOOrO6| zVm(e%mW_RSAb(_jbXhWcOB4nK$Vbf~Ql(%NcVtoHNkQAOLgoi}I3eE;%9=|Hak-5W zPa)#k2;A$0LI(#2g{Pk&&)~uZUU}YVS~$E3faJm{k&1&V)(lv7a5icP3t>OEtpH+wgYC)ZJp&&VD z6wVRD4El=PPgO_-?YItof$1YX=_kdDfe&CxT861(MIc|<-{2BEqvsDFZnQ_*77-Up z0tx@tDN3W zQ-1~`NyF4>KbG;}E*i<&_6jHU(@%m`=NyP=I;0@pX#G;y)+InK_c{fY!(sC*Vfbnz z!7|9)~+=l*28DXVO_Cc0!hMoCR$!ZCo=&rm{E|(bi1v5B|biWK+AQ5 zv{(`j=77qxWxub*8BNyw!VkgbfadXv6n{k4;b!}zYemT3i)0uKtE%3cM7vf$cteYi zt5~N9rZl_YWjKB^^0kTlGIm#yX7YpQQ)33019_{{q6EpPcXomD;l9#$rw|#Qp0?q> zX(7g3R8m3#4ndrTGmRfwWMfGIS8&uJ3qOES99|)a6n^CsODPl?PriCAt$P!;G7v(1 z>cRE6DqE7$@#e=giA}E!K7C1%i;Sen8(G@k35e>8e?|I$CFG9uWe296scB0wZ>j0D zHO0$>h+;AewVq*gKz1_!(10xsg7Y(t{P^*BD0txleJ<8|@ph4;I+6HZ!{fw6dr*SP z!T+ryp=-fS7c@5y%-HnH);TGK-)>?$vt5(Pv22z3 zMBUwotGTh2GN-W5c-80j^b>+125IwOu=FV4P7KlVM*8x=L3a>zJNSetCRc7W{lXqW z&1VNxlg67uR1N&ln+@46x6x|#PAJs8ud+ej84D`3J9QX;`!-VoF@8qRQ`z--{Na?L zr&$XOdW^R@$!|?;K;@?$IG6TXNtC(p^aR=!nae3mTksyrKLAtXn(g23)d536KMDG) z92#^`=J({jkr5;>@}~8xQM`!dQ{i#9E&C#yoAz-_B6P=2Oe{)M_SN^6+xGT68P{Gl zw%#A(YuDhqWHETjkRliJCO@J?8pV!JY+g5Ob9^r6@?xcxdD}R2NZ%AmPYsm*5Daq; zIA$RG?kXwXLKCfeE~NLur{OCNs^*KZN( zT56n>HZ*QU^=U%!4bB2*W?Wzvr_mntZ$$gHzRK~xk6qRUEAG5p!xPWi0ShB^sCp;U zdgkJ1uBYEv7%y_-anU}mc@&#$KT&6L_Liy)Z-vj1~ zIf(X=h9)MP;}z4*KqXEB(=vzK(_2kzAvBO-wl^=RA{@Ez5-rWq|I7Ep?0mb&+GPv$ zl?!UA52g$7)@c)-<%Jbgn66}$cn3-duHeewydYQo_H=WIk73cX&erR9Ig)(VPm@mf zl0YESb|0$#dUlQRnDWp@Z56^9eF$mFcTWeZSC?Y&E}If2x67Y-7(u8Eq6pvqy@7#8 z;IFrutf{uJjVeZr-mc_*Pa&0AEPjo3qb!@p<`}!BF{#Aq+-~Jv;-N*C6G8(Fq=NKR ziMc^7SxfDMG_`mf0Yy%Pj|Sm6FeM;Nj{$23E&&yE(h!E$wxxLIYlYeYiNKgc7Rjv% zey{m@36I8&kFQ8X7DSh^*lYs3>_5iQG+!(n|21c@&fRORy6$@OG#v4<;PA*koi;RR_7V?JhZZ36aHW*=11-7 z(`q4U)1@9x%YtV3EH5!(8`@m3Od1q&Jw#8RFgb$YADkZ7gdKn0Yb-C`B!pG56n*)3 z={v8bVeUXG9>-*@U}@XQ@FX6pbYl;D*P|F0zeTCoC{45J*CJdSNtrrPG^iJ(OiTlI z3}O=8DLS~GLKR1j`;GK^=bsWCHp8Gb(YPR63rX%$pdN1DJKdi>l8SX8GP^r;1$C9q ze9pX>xWS5;w&RS=2Y%La3$r{NETY9b*@OrY87-w%^lSLKoBjgMzUlU;|lDgw8h~1EYIPk1(VZ?nGJs2zkDV zV>HJ1Ga0ai5!c9RW=4uR#08GJ!pc~zD4fj6eqVb*`l>wsJp&GWEh{S{_vvN0tNHlb zaU3Z$%Sge=yZ$8SNJDR!?%Py8j|ifwt!?R*Vod!qFfC;TpPHFMPOM!eTB}fa1;H%7 zG)~d^*zqiv>GDtL+nJ|Cly~cfX7UpxaBAbboPvE9hMH**Tp0ar+*I^mG-U+C$nLML znW7~xkBl2xGtm|)FKZV9X|ssAk`i+6*Q*pZdXbESdU5m{ytbw(u6_5CRxVN-Gew=M zm{P(3r(*rr3F{CJrj*hGv@rPi{)ui9`^o0=R zvzQa697SvEL!E9X13F&W2L*jkeWHoZ;2u=;-ASO``46Fq1}5P2{$J+Pk(MebLU>*f z%8KJE>gEzJXR~NsyiQo#wjIz>B8lfk8^h+_PJc5*_;*B)>{A{tYazjy3hw~N^I6;N zH4NOUi`eDqlfTmy5EEWFy37#D^f*M+=AnC89Wl~%4zE?{ z!hc&yu()ZEBSk3shrdN3&}YMmRl!zw_Qj${gc|z`w2h$HWiPC%st`dGP**XuWeNI1C{l>u`cGZBh+FKb zpzrWnnh!T#%WB;sC&rd=@o#bQXNWQ2)0AbEbm?TbPWxqC$IC59sfBu)sSghbv~S>x zgP{aoLl_n%e_e&72)@3KBSvE~W{3y@$9-zAgYM4F>JQ+{`Ql(qWgw$Vss`5Io<&ng!L*~oQ;N|N!?KowvpF)Tg$sfh5`uh40Lk9wQ zm=sM{>8h5Z`z}t9QBJ(tsfGG@CL2-HyRaJ2fv~(AkaoXYDtQY~Nn0fU1k(j2@gxWfqZ(6+tV_LJuHsAWd`H^n zpRD`qZV8QEL;zgo%LzSL)&OtE8NO**GU<|ViuCeXox-f_Mc3+BnSDp|jDf3hI`>3T zTVRvwA}6B#WM>>_1f4@Dk?^`RkpWM^4v5#RQPg)ziZZzg*h{eo+00Q0@V+38TZ*8N zNWRPY{E}x`4>#+ciKqyEoRQJorW8~dHf8kbSNbmM8Q~?Ue$>ns>(9dciWcE1@R*~3 zgG}(OGc-cOa&CB41`qvB_iT5bn+N&oH`u(f7iqL|(~P{do`dkgQ3;nfsvbMqf%tq~ zZov{Q;t$&~y-g;vlT}6Ss!3kFSNiaAGpEmBv>-Npk_^p&3E~h(b3GcO6r?r?%TqEe#@T``e6s7n{|qYv0E!dCE!=#O@jO@_X&ulq^vJH_hCL?)mKC$YPk65 zE4}wkF_QZee;BwVGuLKyYdvRcITmB=upmjonGN|_bp5y8<_}x>2XHUmz11nR8%5jQmYDozcv@f634vV6aikc#nacp^1`Jx+SRASaA^ z@|Vlb^vPX|C40T(^`Wa6wuG+2&m>-%7gBsJW!En1GGsW0U&e<+DRUJEX{R!#0;Cp>6#9giS6Hm1qn4b|n#T z@cd7dC1NUL+&+M_VnYQ&K8WnXw=LsHK}iJX6Br4HJ3FHq(Uc}$nwmgoP0PTw7AR2o z`5~Bux1k!>=hjo;;e|E$vc8jOXkS(pWR>$wgF4boIsW=d&88?-UuW0j0)ao@8QSReP=cGcKrih8v|@nQG#qI5>w zz|Ci8^&Ui@zPDIn?6{u5e-h6Wus8EC>AFcUCjmsLNlWbgP`Y*2jonY(>wa~uEQ^_G&={XnuP~+=Bzg(Uo)WTB_4!NKl7CL5UTd8FT0TE zB=YP=y&D)}WW#gC31w^fy$GqvLkIcw`+`~39HTz&3vUUs$8gsHtP4Q&gunUKw*B(5 z-)TC0e64MLnHi3~%*pWl{rvrVdC>oB48_HYg@=d7uReswF_`a-kx&LiGvUsuEv2fs zy=`)IiHO@C8~Is)(%)bU;qQca819xjsLA~{eIC>>@Vl3xf-ui2c3dk17Z2pcUAG0k z&CuET%@HuUS6>(HjLRq9Y%^?IGE!VEZ-it8lU!7>fH*P}m|Y1?fw*=YZ!kW%r0HBB zCH0+Op*$&|_!zJ=`tDMZKWYbO` zLi1BzL&i?C2N_D^orlBYtfFr8XF2QO?Z6k++?0%uj*mg7-r%J9!`N2+aXk5^qNkdm zcVRp^@!8tqh*+Jsg|_wh#LOtB>*?;55A<#(scHD6*pPBhD(&6pj`~LcXc1^fj7NSU zswT#mx7@+Upg`rtBWD^j2#@dbF^+i5QiX0Ivg_P6H}=a!(# zYTr*`@Q9IW-{h2-+^n%;3_(Wvq?)wQ*XR?RTV%C{&bl@Y?;q-}$>wDzon}(1jk1 z=HRku5bAz9?V5_k%*AAgic{L_(N;E^Vd2f4?O7n6D}CEUf&Tljh|Y-4ykI%8sN>oY zBF6>`38lD`JH7zZZ+oC`+@csE<#h%`=MHRWZ^e5;a#y8#n* z?O7Y^NQS@SM7TvkHdUP)Kh-7t`(b-0TgNS9<-T6ou!kR-x8LqTY$+Q&J9;k>4PTrK zgl|$c@y%~@;4xJeu<^~jDvSB%%K2Yvx(?oa{3%$x_&7$zMkhy5@tohEA>>?B4tP$a=0O zBU4KB9A-ux5t^YYZ<2XWnz=O|tn8@_v_cUGKP7VsF|ztP2v3jyD~KoTk*PbdZ;mI| z9qsvlB%NhcRoxneH{IRcbwC;f=@LY`yOEM^M7lvjQbZc0q(ML=B?Kg-Lpl^x4kZnD zo$vbFp#%0_d%ZE|Gx>1?)mHH@P~kTK4p-6syxpu8uFhk;FNS{99`@;N9SUA!uIy1^5fOb)q}gNg+A6EC;ts{~EBjpbC_)o|fB%iH z>%Rw@@23@DBXf>$@2@!HC|3QR=CU~6ucsqSw`b8w$%%gRs$e*=cdV> znA&KFU$XvN#>23M?DVIPbXM;Xm&E)Y1fPk-0CWlGJCJ=B)ws4-UJnjba73Hb|hTEeoswwXgaf0@K> zkyFyqxjMPHcmtPABv&4(_;>6~g0u6>?I$k!`asZ%aO2cw+~d#e&-f956_$eD zKj9xKYv2*81JG`&D+SCvShm#oVCTCmLe_@k;$N{zo2E}iQ(j;g#$ zau1bpO2M58rsNIMu56C2c>Q5-y9#)_`VG`%eV2KiP+W~NcDUB>Bchq8$8Vca}=VK%(7c1Qx*&;Kwo z>!rDlyqsC1P(TMERXvyOkLo;lCqh$FQb;HmJaC7Vut4GUs&oS4vxA~@|p%by37Sdhoq$T=31UD)`nqIEC#8 z7o6U$&8sTnZ{Pwb8oS?bT3DnVDcq8H80Xd5pADB;0J7_-&$j30a zv?~PqeeiOxgk1l@;|_K77TfJuk_H2Bu%=S^P;bQ%0QSA>ch`s6$@$%+EaJ{(Xr{oj z4elvSCU6+yUpPYrin_O7De~D=FLzPHn}7e=c>AF$q~aP#6U4i3|F}Q==HI*TIfsH` z&Tl&3^KD#K=vykoA{u8%T>a}q7Ci@^Ad3^NbO)A3mL46{9(jKZp>xsQ!dd7ypaT`L zJ%38~+|#8G2qBVxp$4@Br6vd(1`}3ci^~zik-&8$HA$$TAmV9$KNa7dr(um5O@O1x z%yo81_dus6&$^5{qcD5K!DT3jX1L-ncL_Wk8XN={qr#JgEFTL@zMgF zWyk*$5xk>X_FcfTq0e?3vB0d*#)fJvrtrQRB>jG!0q1ZyT(86&NesLrER6& zYqP|>lp#Q=33MIzHg5F+CLus19Loe%!Of>fqMPH6?gUi~Zq zq(nQrD6xWbfL!Tg9&YeF`Sx%$$85S;2|POG+>5FY9e+yZa3J7Zfvug~?8z`7COUDL zpfzZ=?niH{O$0g!1IgY zq_2~Q#{OroDbpI1O6d>aAy=#3VU(r7IkiuO7!-wqwc_;c)tT|^Q|4F21HJ^5S*(vV z@>GWT)Fe6aez--fo*C}ou|t`H6JDKjG1fpayR|qGA{tS6pK~iMsVRLrsjyzk!6Val zH{%OETF+1|te^eMEa4fBjV!rA;_N2r!Z~9^41ou61Q_?tpu-57r6tw6faR#AQ}pP= zi*iHdcj~RIO0wwU?V7TVW0#nEt_5!8QV)sOx&7-^pZQvY!663damUg?kPE;Z82m1& z3ItPB2dM*NvKhRpP`yOboR8m6BoQ<>YU7!zgLfxIOgwx+2OmBfoHhf}nCwU{VC#Pe zLpv;{RE_ucSi?O%kco*&+}aR@h7wpOXkGj3ArnuWfN}b)u?vv2jf2o% zVyJ`M+x(e%Y!6@e#fUew%_xcYl;YnEpJqorOLS(>Bf>tZg!xU!aEe!<$>k)Bsy~1K ziPj(;dDB=D2sRff?WO4xXCM^-7IIp`px*ojhy}}MYj-286c9srWY?qkZm)Yd zWyXh&GaG6DvAd-MXE>Kc0zzQb)6gUjRwH001d^NC_>}CPVi0<=jRPm8S-w%qo3M97 zHwYcayj{Cv;pU3>ZL#DiEb^IpU9sGK!{mO860N3i5dFy?VuR>d%%Ii8pNEH7!QnsZ z8Me=b+V{Qccu3@j9pGTZ{b)D8*H*&#cxVv(AWk=jprjNq9TWpcJ7bZj?VL~RE-(vyfO*DHc7N$NzMpm&| zgBd_fl{0xE)YicasR&y*&ilSI%Fj44xs!r;VP4ius63<0%dK1m6a9@mjXY0x=Xgwd z3zdMpA82KORx{N~>CwCL{~Inlkbfec+4vEFV*doiP&?{mwf$3?j=fi%Z=OmR9hC$r z>1J|ibMq`Legq=oRA;^HbkO8JVOE!Bw{(QScEY<@1y@6_M5}5)w)Ox>X_CMmWSimT z=~Q~e;d*g+xgqoGdE2w4v#_@)(X0O&jON$2*AL>X;$m$rp6Ll+f3vx3(1#)Y?9-B6 znCDc6WFD@(58_eDsCvMFkgXu^(WW`jqZI=833liaMX0A5tN(M{L8*)N$RdUpf0oj3 zT{Z$+cAoSjBPZtyNnD*T6li*jz3eyfX=aCo#XRnL*yHYmy%q2@lV{CmS{_9UYga1)0Y-%Z7KhiwB z8-L zjDZ_6VE;i5M3%bbw<;%q*9&H3%6JVx^7i+J5%43Qx3*udjc%C^lEzVji+Vtl1IUS(a zJNt5^@?EI4Y)Drn;)JENIUA%rcaoY#MwVYt7Kk_2sG@uIk~b}Ervoy}3*5cx(H7n< zS`7cY*o4t;#(Nr8_C{_FK)+DhsY^##lv{-dZ;$Se`R*e?jLc>Z)|~iy+sU{DcYZj3 zehHwkJ-u=ysv6OH;Fdth%}9N0X_KaGl=P*U!9^^Z%JH$x+y{v#=xWvw89858S0fsMf168(B;rtqs|3fhTp7< zLSps;!T7;Y6@D}!(4s(wQ7 zb`l~)64l#pBQ{|QvG`L?@87ZCqV3&22V!&UJN&jK%ow>VHS3Bn?A^1UrMEtSpbK=|By7;*a!whsJ~esqLnD6+EJ%WTn$ry2i9 zTxfWN7FS|3sE(SrPn$M9hmlC-XlwY;_cgchRlMKDZ#doMWBX{dx|d2m`C0Q z>XNVdU1sSTA%hnG8nfxVv5t@IlDE>0!IEli5a3<>)%08H3G7AzErkdo|B>`RAExf_)YKS zi%ES(Q<9(2%ah9jHSwN1xhjGa`k%GPx8Rz84fzOl!@iGTNDKT-w~*u zi@75Tu7M(ZQxyO}?DV4vksq!FpYRkGuT~`lex5cXDclm%NsiJ?2o+SQ7=ct3b3hz1 zV2`R5e_g5p14Ha+WGtphuy2(s{TfH$t+UYj;0eetPYovZg1Cd4fTNw*;W*k_FJaUP zm}VY|itdtQM|;oqe!K`9x({4xih(dw36+h*g;quq&<^<|Avas37ROaKqf;8i91g(o z49!ugNSbw-Km%C~dNLlV$0ZE6j+dHRz2~8|mG46k+}(>2!>+~}63Me* z|HDX1;t2F|V60*?4MYI=IN#Gx&E$Xx$ab`rZ7!X?!r;K@;I>VTC5$>>WdqKP^4G*9T< zSy>D^cRgN*Z%X^K5vK7VuUBEOjw_)Ae+KE_ESIo=@B}4+i!yR9L^T0!X3$U#pLE7> zyB-+aY7w%ofG>BGkFNQACKSEY(K|~D`x;a3gjmN2t1AGjx=tl&B?Ypq5(D0S9Uunx z5`)-7f`AB+nk59|RL+$x|ohit}kbU@9clod!#boW6Z384u|?J_w?eDDt* z>)}cFY_w6F&;Iw&c-s|Jm3hd{4u`fgx8txL_ZC(o!YJ%y0h~OwlS7B zn-pZBv7Td1V*E6p&- zI`vMx&e)=Q0L6)8k6j53&G{PRW7yb^f&vP{r13~6JmJss#|e2=(E0+R6`K+8FoXnN zf!#CO8Y&T3Q4vGGS3kc6UJwQbLkBD9ykB_r~#@Z~ucv#I^l zXD;jhPo8C|>@|f{E;dVXt@o4V2KTL9FxsUgaM;XX(+p{ciAy(I?yAl+tAe{T6WK0Aso& zJqItkRpz&RdQ0_c;K==t<1dS=2I7gBnbkBjR7EsfWC4iw`D$l--+g;+;#;?lN@T~n z>#nghvSdAK145Iar+Yzypf^x~v11VFoLoZ@OQ$zgP z!&PVtC6Zavr}&Ab?()GloPb`3qL|6)dyqd?1M_Bu*l3WUGaVTH2S*-W?u**An} z$g5{=MJ!9~j<|?(0HijEeg*L(KRYa@%z+&l3|lW3v+Rld+4M{u95_HYp1z?bDDZS7 zm=-`Eg&9^;WmPZ#jUi{$3#^mA9O`q+kT>>d`6uWe*j=KZJY|~)6WV8quynix*2E5qFvMAqq2y9-?7hA!D50RrGy3>qaR3?gSuWD2m==T7Wm`HY0qct zf+}SQ9D{nMnv4nrvr`;PZLE2_*A|YFgM+@gcruyCa_&I5>!)}J+`DU!2Qi2c@pP|^ z0@^FEj>K*!W2L_|r~`eJ&^@340BN(BxKZnQ?Cm5bts@la@yR z$EOH5+}h9dBxX( z&E)&V5u`U=g=mV^9bdg6?7LSQ?CJl21M_v3ee}%LM(9l$MZq2lS?kLT7;GOGbHL{A z>+;%vx+G%GJ_#O<5GJ`j2%XcX^ETmj&fdpK3L+A%45FTLYqBAfAF2`hD3kpwN=!XSm}1J@O;RuGecDb z249=uUQ4-CA6N|~p3Y8)d<=mAHMeTG1*rh%^%IfH&o5uTgcvhrW@yd7?ExMBlW%9U z#nH|hs&~e9$FY8_tdW{ExdjoH|3{IQ9y|hTS%p}P#Lzx7b2h#ebjgMps6M1ye3?(^7~CoO2V zyxNlxr2%?E1_l z(WtUBH6tV~f(nZkO*vK5XSYfJOw;OT_D)gP5a1KdKTHvHM3SN&LuYVVYk6bY0TMPjf}rC zxdBXv`j<6Oj0 z^{fi^qyscRxrzPA5Mqz|s}m5tww0ip5$wB7Ac16-0?jMc&z=NvWL%qf#$Cp}feGU5 zWPrTV3S?sWArmJ?Pm`%BS3pc}@uR&62c+RJTvsQL1pcGs=sR84GqI`Pj-jqUpcS5u zYlFfTHhd;(OKV-MR_TV9QUBun>g%QMBvw zP2kqsRS4oV#ouL@sKu}{N@{Y7IxN0>!Ac$AE_SYqk~(lX@dFpCuYq4YrhoCf0S!a@ z+rLmrH$)s%Nr-gX16))@j`PRoyOSoO($dNC@$r-6QzthL?xQ#pNLmqb*dfd=jZQJ> z4=vFr@k+4BdJq67;2>$rI3v}P+YNy^3Q!nE%lm2}IeV-=8hTNx#qoDpPW3-E0Nz1Z2=8Hk1iNhx09fxkh+0{%e3AqhbJqi%sR z2rU#;j4;gdNo%^@=bT&c1*JMt|Lr^(Pq?F&)~+qpnxeRS36%Ma%s@&uxv)S9h6+Va z)Ik43L}YXnnL=?osz(?umaMByToOjyXvtw^$$r68P4-h4PVZ`ERd@mKCm^WgTq=$% zw_+st*IE>M#zpwXjO4{>AGY6~3DsMUVRAo}-d|=w;V+N&MTb^a_}0!>JyIkcjX%uL z>}6R2VNCt;(0EQ6O}0XyKz94f%Tdd$c`igf!zp22(N1tUi5|q*$VsIVDnk>;&n8;u7G=!P&g%r3^hGq8}(`d^18xkWI zZy4asMPh^@f*Z(e_Z*X#5fSF2$YSx&t!3x$Z@cde#|=lPq)*;VMEQl}KK3wYd`2ne zFfA_YMB8C4s*z7-Y(|F;+$0&kisskSidi+4JmW5TP-!#v|E#DY&;;?u2b|@gGaR!V_;=zys9SuJ!7g znuf!9zy_gep9=Qh#1s$ofaX+G^BO}0SC2pOJ?vp|F`GOlf-K(}?&I&DPKXTbDE(ky z84vapqc~n57zI3i8w+fM8>@`>;A#V_*(wGAypeZ{4ul!yX1K4KRWZoDjRVTE!{5IF z#YF1My)&mHp6Z$gl?fhWj81!S2Jz?Ao&=NLRQQcwiv4?WGI^ZA*OBzE=*IkRGnc(5 zBqBdQRncHTsHs@#eok4aZ+BVlmd6D(Wp{hRug`%Kk!*dys~(Z`1NCiKZ8R**&&Mb7 zb)m{ql~+b@XTJqQOCIHp$sg2^&jI8V=VR24EBisrWvl(WL$pYUvH4HOE865b>HEux zSW!0?7iq0DjrV}9d5bUCSO0uGWoSCP>$Ge#SV+d3LdpS!kU>#AJ<`o_$||nrQZ||c zYFh}}xx}+;Zpybt4g+&^b}*Vr0(#%JO{3}N{W$`0I(@^(dg)GcS9#H`A@J&sKarOE z%rD_;I>4r|^e;_?6;yF(!O75#2HGrm|0@&T{+yTIMfKZs~%M-!75u9?$Dc_Y?$ zSNynoNXJu&hbXz}=LufoXz{9*35ExuY27h5jAztYtZ;X4w(&m^mh^$LD=~J^3P4A) z9nE`TUolI7w#mkzpFbJ4z7x1wvn`b5`3>oc3hBD#T>*MpgIK8KDB8pQ`GXBylL`V7 zoP|$m*JgDEGwbLHn-mr|eF+!EM79hk2bTBL?Ph-~^gaL6uL=kVFzxtczopi-YYNBK zAP2SfovZOXnv?^Cfhs3IAOBC_Mw{*E91c>(hR3<7U7Em>{}$_as7fustc9zOcBhMvM zNuhN#MkN-n7uMY;0X#2197_Dk#W$kL^V~&KK`nHm#0dpncnBe&k>_pJhykV%iA;DGE zL&2y)FGePpE4FAlE6JL5{%SKzU~o}k5w%B|7_M^{XD7%dm)OIAbypBXU2_8_F+AzJ)ec+^X7K2YfFb#+<&c(MN=CIM9 z?VSc#De0tSPEj+<0~P;nB?v_xZR7;mCA`^@uFH*f0|2+op6)>#t2SL4AUV#NUhbs_ ze`UWO@zhCJy##zlkAXzabY$mP>kO(1)k10g6MEj1FM?VKsn5SXtl>7=ps|iAaQWnz zDlAlrjZI{5Hc0%={j)y#=Dow=x2>Iuk<+8SJd=)Vx3Ayw38SJ?86#ABKQ zw`xMpKF!8qq)d86@R#RhEIMNJI{FzN>KOd-B`M;rt1a*QzL*|aSay3YFYig8ixX9l zC);yvYlb}aDVgfg3^`6$^8CB4n!*=ylsMA!a9mtgz4w$u+Mb601=L~Dsl{1iD8P(S zV@%t$Lqz#o2uY{pj#Uf?VdNB0pFTSoZ51qro67XDe+-G@hM}es&E7G=#J1-M(z+8m z4d#8Pn4o_C!h??W7OPoj5l8^lhzVq07oxE+gA4&c0i`|*l7cu;7i-s(PzksHZi^8R$hJH``{0u9^f9Se6{)39m{7=y%M`@gJ*s0FznQgr*(bI-QUj z@98~Ex3XwaPbqLYhT<q*aRN(Rz|;Z;nGhdTv%B9YF$y;hrESNj&8Eo!x#RdV}6 zlTHf}|NQ{?xFYIaDeVl$%BJrM3W~@LahSw;=)QjRD&e8gOyaP~2lCFOY*Y?#SR+;p z-L474qHC_0j*lLf^x9cq$(1frpESdQhZWx(pC<`O9vDwxV~Xq~BnZ1QN@lqF`*b2_ zwEb=zT|$3RY^cO4-nd%TSpt6Nz5l9aVFw2XwwbEYU*qs0rYB1g5Y~FQz@V?W1MwkR z;%3F9@T>Saf>80*wKaDzSag50U+*#-V;la4>Rw$l|4GmcO`xj4c;}}f3{E55-!V2f zYWsfe96e}dM&?M_XanZ4UtXb)<3T0B20D)9@e{AEitzxXq`6&w%4QGKk_%}|&7_Mi zYila?77-L|w35|rlULF2>-f|m<3eJj-p#OE<=44k zMrYT4-`?e(k*?Qmg7*zzyj1PUhR4-KAy3O+toMC?3n77dXa{*{!{nWj9!FLFgz4G^ zEi}!@A4ZWW6MZ&FXa|y6y_AnBEj;s_vP>UM`!_!SFg)HV?{>`LswetG>8(Q2(VL0j$6uJFx?}Fa zoZK9>C|bc-o}K8}dLmy6XZOC8lDda!6<5j0re2dTWKjrG6E)4p$t$kUMS4pW>x*e}BUSrWNY-X1mv~o$&f59u#tkGI87C6%pX=+E*KVkpEy{D^G3j;laONiHSlQp*Y?8C+vOk zl%q#D<5yRP;uK|ww0JWjt{K1s=Yad9{f|~wzEol0_bmpjo`^kd0;3d`pwLedWOS^` zUlWNqo~6Ef+RV-+`S?edsk|9E(Y(2DEq+f=G~dhCf;js_g3N1UCCgC0HTIx<41m=L zq(^v=KEzu;%j&~wYV+LP5w0#l^+-Z&JxdyxFTwVgaI z{!>yw5!$Q%It-oGI8e|Z>nBu;L*5R3`_E(QZ`)oGs8a>u5pn{#i3CU-B-lvI~ z>cX@nW7o5-z;KnyP*>%|Lfmyz#wSh@78zseQ9(L)fU^>bj;@8560|K4@^{a!wj%u( zDliIb0nEn?uiw$ffnrj*Vy~z3zU>el{!Z!#B`AVIVg4-Z@HU&Z=0|WzzGjRyzxg~% zyAY*qxS7*u3kSuhozd)%gpSx#i5`Yuz)p#&U}sDY zRG=B%^{Qpazy%t||M20^^JV-tPP|sqmDzmwlCY?&Im@LM+Lo6F1YYo7uQDA^@N3w{#%h;RIR1eI5tUtSoTxG4Iz}x^ zD@rKm5GcTPh9ya*Em^+Y51b>z8JXio5&*n3O&Ny}MOKTHAH4AwxV;oy$MFb@9k{8a zfPN6kQ9xRHHDX{G^{p3?0!JY;{slvIv5kdRp;H@hLBA2tvOr!~AnfA^>_e>joPB2?Udp z`Qc>MS=Y7Nc$O(`F*1O_#rgE~Q3P)Y<2A4u*StShv)(VTMMOpZ2+MIRQghod@OpLi zL7y+^P8X_qY#U5m1HrIOA=_MZmvVF~I#Grf85ahN7eFxrLUb+kp0oH8V&-F#*Jj1R zad=dZN|rx!h2g(Rk_ycCjWSyJf3AKqn*Hz>DPo zmxieOY7!Xxw)!7h0O|k|*wBI9&e{I#&w~RT{3|%zqka{LF;Ty>Tshu+v}64ii)zB^ zGB^V2o4Y$KmeI!Mjg5`LcmAvG#IlxVJ>^pSgApHjQx@u};k&s@T~ZSrSg}iDH}~nM zPrl7hURNb3p`r3n*O%S4J9jPQ^jxprF8vc%!X}wN12R?&NgxJ$fMu1>4yA#Yi8TDm zny?0?2YB43geIS8@G33GI+0>x!`uF0mJ+;gYgXKvC@c#F(c0)O_+`=$N1kVj3;x% z4>7IrH)w1P^_smcHX3n>93N*(VV8&?^=*wVj%iJ_Ry>-GilaRj@+JTQ&CmYfi@Tl}~J6qp0L7yL-D z5HQ`n`f7XErOi8!$o0rf8xrtS!9EG(3uw5vHwb;o6*3A_$ekS0%0fHYE>CR|3=2o8 zhZ|CK4yPE-G*f*ot+52M_6+vmch8?cuW?w0@mSt-RN3lDW~ZBdgy0BHhn!?xRn^!D zX5=k<{!LOh>N91loM!}qi`d*X17|4o7+U?dAKk-YrSdD>;QK>1= z;n62w`UCo7@K71Gu2b=y6Zd1q;H|DrL7&G5k{>0LobE)$3sc#u&HI)gJaWp72@gl| zx3SqYx_qR0*!-4as@!%S*(koy(|_1M2b8{aPoY+8OEQAbhnAB!@=o%yp)#X{&3a?mu1ra!KkQYcEpKsiwD$ z>7hRRFRFN)MN^D?$ZZLI{t@O6VH5X775x<92Xt6VQYx9<@j91({x!LqsQPJyuvDMHI$96Sz+5Q(%1K<3|StE=6eAUoMRe> zz2LLdM^0R2rCzuxz(IGg=Ac@uj1B>X z8(YqpFpJ|X{ie`aezy!W^ox7(mMrHpa820lq}<(w5Nb~j^icK#MhZAaxQ-8)8JWSl z>ml6MS{t{aYrQHds4JRHRpLl5u7RXLJ^c0mX~`JrLN;4!;{4| z&ec2ZC)9?FpfH}IV!*N)wZ{}xN3yu6z>9y_<8>X&`16z-X7t&@zj}868E4Pxmv*D3 zAj&Y5V@ZC4w&VdzeYx0K0Y5p29e(wc_a73v;i4}m;Sa;EqdM2jtj;8Q&2@z{ZAk?~P@_8rA)a$$@`fU6T_#DnjD+uRzGYu`M zPUEWKpOTQWew;Scwf{th(kBCm;N-3KVrXJ0RvQZ+hPclMUOiT5ay2DsFU!M;jc4uO z&b^ajAaqWcOYsXaZw|raSMU(=(;;%&(|x}D81UdPqjuG3RFgaj&I_&1CJwFOS$6#gr~A`k}Ugi3ls zV}?$pV)7O!6yN-8B63WvJ&@y4`)ol#$W2v4_<*U^HQgx}u>L&v&#oSm$)a5<=BB*t zD?ys+?aemAR{Km9xtXFcviDS+zB(h5>0QHECIGncpSB>J9Zm}fCS z5QFt`HK;mOctoU!nu>}G`K-TZ8)FW*ioNmX?8{QXAOYF0iuK8k%L!1NvOzR4ZKAf` z+CJA(ax^NiROWC?mXV?z7LHj$C(m~@5dJ!Y^vy>kkFqPT7ef-ONb|nlnagC1G~BB} zJb!3Mx}{Nvbos*kix!j=5wKy?*R{W8m4wQTL}z0EI7ku+i(>;Tw}y{3j&trHQeARy zQA>#6U(TatlJ;9y&~ zPl`FiPgQKaWGn(p;oHAkCh-Q(y6p^a~lWE*M}UFa@+NS)S-Mo;xKAtivtS8`b@_ZJ5Tk!A|M$QKCDSs?PlZm$;Ve(ak+Yu(*!0TVde9e}I{ zM{I!dyzRqs9m|4xamE$e8__Lp87Uu<4wDQa(dr#(`k)hVCf;lRQ~Qef?B}DrMU*f< zo^hE&CuR+;TxhBF70`T3&btHx{Z@3p*q9o8`4pQL5&Dfg?`usN(|6DuxOO|rafcq3 z81#)-VkbB= zC2LKwCC1+Pfj(B_NZCbPceHTj1!lhTa_b@-&j0mVRgsdG7GSW;;R2WxR1k=_wVR}4 z3d8P|BjSAqu8P-s`ijV8+Fz9=#EC#A;kfu7>UIwD6Qa;jTY*7-A)#qxR?KyI9_}S6 z>Q|4o1ems;L^mf`Q|i^tD{*06mI;_W=dLmwa!|8R5>TJ__4n~p99YfT-IQ5N5m?*IiM4;D?_`cQ2p%3{Jj7)!-N;ix zQX~vU6;w`*(5nu4Pzy#>Q7L|&J7s}zS5v4D)0JT1KI+LF{cb@$c6jVZsmw!%67Jk*|#obJ18B0c^(1Uve%pP3i zKri&n>hrJ%8rZG2mLJrY4{B2_MC@6>PqVhw^$U?9zM!c@ zle_VLFpKgc*vCH5C!FfkIIgK6{CNXnyp=%ufz~g-FUx7~C4U`(zGZo1=Db%J53P&I zIvUJSIVu^xqLuy}@X}e)5kxvb$~#Niv;MXp(pGDtqb@M_Y4xmjrFIXwLh2?Adp4vp zz3%1LrxxEgKk2bWLhygxFQ~%wb0qlD)UAWHjjWBK=*K_M`Qx@yWR~uAzP4?zeah6S z+`bfl&+)ef_#u9-64)uR48G&gq$cu)6NVx6^GEEZ{5I`FCO%#ZF~zuqP<_lfE(f|6 zFyvYo6VPCp*hsQ1Ca%A%KX6I5U3|xN9+C4<22P)yfWl8C#zn zm?;ry|Ew8P23UZl?_Er)3VoPk;9D0VnhHuOAiiTZRld5uHXW7$GXN8r8yFUtBkgwZ zR?i=VXVug^;5O1TpWgv4K523BcGZLkqpQTW%fpeKNa$*PmS+7b?Yr*U3*W>nU(S@v zN=a6jp2q992kjt3{iA!xhc?R$eSJ(TPhdoB`?us`N~|~=J_pKkBt6>4a;Q*Ja`G;+ z$5*MvVv#31qF+Sreudsr$lQ6_td3%vN@YZnk~XxIhM^9u86YPYFN|t`I#5^kbwifL zqUgHOAE|R7@&W3E^Lwr8S;T+yT|vf(=Vr~?W-|{UIy=?A>>}{}As77&t$H_A@D2ID z=Te7(cax_J?quX`a`shT%46L`P;layG9Qs za7L`9pD<&?V2VfKH=pXk2p=OSoYN6==n}zhO$X)GF4~_E%%?G6jtGdiJPU<6Q9qS{ z*V*3MMqL}5xVD2ZiWV@M9FZQODmV>aw${JKW=;i^)12){5^`znlP&1GkNHR7cgU`M zQkDDmN3#=M7`EAR@Ar(GI21-6R{rq3-E0&{q3UDi?-j}pEN96$VA*G=HpFdVO{faP zh5|sdK`*AE-%Ch@rmy{(GyOr$M=)Q=92F;-c_-w>kl#H-^|r z@t_(B+Th0*BKhDRC<#2`drB1Ms9e@MKIWnY*Y54xXzOJqT5B>$7J>=sCJURrFiH&m zSmpfsscw#$Nq z!&4Lm!4`;bmezM-@oU7Hc?5O?s9DE~sDj)OhFqK{U>;(~DoHGN1_~vEi1+6!ZA6Mu z2(K8B2E{Gyf_&8Br)4^m_smd&{b*L2)&=2jpnnkrRhkos=6WTpZYwBDG?zXr{0crt zPUJYV%0sExoY74_uM1_qK7#HSfVF zW-@lKI@8C%xF}0>O~sGlU;tq2LTshfMksqhELTodn^R#>t;QaNKbrQqGHgT%Z*!4d z`nXd@rWk-%2N5p98&M&leh|=_vbbnGD6ah3fg!m$s9yHkH7`7!})tzHKz?rpTNc>H1W+*N!?kIN*)9 z&;Px19nzk{LXEF#gYd(Fwcw+N9?0YU*+Fm2L^=KfT>cT=4PedkW=(tE_qaglguW_C zVCLYAyz;wW$Pl1uE;Uz{Y`)(M6ubW2w9(;)lRBkQ%0jzbRQXGAt?!0Zo1sBLkh1|S z4GQ<{oF~$h3rn)+U+uK{Peg4%k4$B0=j9{li z%$b_XHtYM2Dkl7O-7i`IYXZ#9aq(ruvvreI=Q(kB`FqL*5|&*}Gf+<}PGIz{6WkH* z9v+rj4(3d`jg#R}pVpQMAnef&xW~BH2wZ1A*O37W0({!)1XS&$sSgex>dS1Azbw^T zM;^<*^G-etIsbG~aDT}FIX}G_=#+tnm-j{L*M$qv{m7K;J9kAENnLk|R%QBrej>(2 z98QYGEzLRZ#nqMg%Tm1w^fNH&Z6GrSKc^TK%J{)<>1MHO~z z;ysCM^fBjH_cPv(pUg7{zGWZWzm4qf-pKrGcnFErD=xpqk@y{sZCUK&F@VmcWc%ju zfp(ybprFpLgM*VVp9jPX4AF>`UQ?Cb5upndXDCwIs_~)|eqd;PT~_Y&-~p3YX7q$q zZ$A`cO)2Lear4gJc+4{oDn!H`F|OMs35<=8H|kd#fX;&-0Gm9w2FYcbKseCc`2E)( zlz_RxLZVZq%}kfJC%QlCW>4vr+U7FP%dV9s@wctSwUKzY763e8WC%|a6BRQvsLony zOzY+&zY}-cMPJMPl0@Y)!)Ey(QC}Gq)%S*b=G=qk}l~^5h-bqhM}apLqJME zQX1)&4iONf<0nW<*WL5KYu)?VwRD^_XYcoYGPf#d9kf>*i@$*pG3yVYRr5IBk-a}%mG>k6nCGO#8pqjY{+%m!GFeP0?qlI;AU~tjRX2e8c zqgSY)gyc`1MOU4vh1k174@vO-KdNlR<}=t9ZYZ zKR<=l!9yRx-Krhqtb?FK+|_8U9NnA>kIp&)Q9`1}aTTg(yFrJu>O<2*xrn#j z=pIGhQ5p*jf^j|N-yo5j(LxlN-^W0!P&)a2Fu>x|W&jTYagt+1AU09?1O0Q-H?1>e z2OzAnK`AB|h|mdTvw>n8neIye?r?YY%+0p$Rh)cilvBj<5r}-kNYBa3dmGCKlviH? z!Y6#}<)#^GGB#CyOs~7IV8TMB+e`mOdFx|Nc6PQ`!IwFE7rHl1nuFwEVnvJxR036l zr))4$2)%JF4Hk|eMLRe|(v%0z#S`2o^vf24PNYN*uZo}_J%ZFCm43>8uiBJ87PZmH zciCY)W4+B~y>^`yB>LG;j%|gsav$HNnK%4>GXRW2@Iw-B!e>YL*G3-Z(e)p97|X)VyxxKsMtEQYO>l|Sk2AQE|7vtJn`^)>#>h1hSw;9mjW zKddGOHy<~q#~tMO9^=r7d0N&&){InhIHMg}*8UT{d*|(K@JB#R9hP^NyUU6uO^!tM z`21o1RR=}4NH)32G?vN2hQJ`X_&ln`8eiaTM0AGxMj$mUt?=mfSEA0z-r}r>Q`NRt zp~{$9MGVWNggfPHj?6qFd?LH54d^4eB#<{4vhsHMmYOICK7li9smZWJD{G#C!R-iO zT;P{#>EeQ4YKJ;U-0O@1=n_ddE&XSd9Cih!PJa5@I`D%t&?WkaE@b7`=wcofn;b^l zAd3ueN}BYd1c^4LNbH&}|7$mJ-P#LMN-su1Y+y{@{Up)-iRMCGG1gy3d=jKQxdQ_w z_FyJGcdV*#_)-6@{yXG$`5gJ|Uf){_4YE;}QR3;BhMRgB#W`fUd}p z7YqsI*Qay{S4o;`dqP`iWcL;Hq@>&H9)Ol925tb7Sj>4|_}m;3+hM-4J7>j%4Mt&` zO|wZ;>T&7Asi94;_^HBPMwBioA*WK96C#zk{?1I#?o+KLxlpOMDdMsQt$?gE8)fo= z4$U%ZYKezenYJo=)(j8+@Uj~~RFq(voC;jsozWz4vAjTt3-$X%rc4{o_1c}94EAA` zw!YElQQB1NnXs@vp;Ra~xndPv;u0_N@f2J7!JuZ34A{>Eu&rnkx$aa&$S%Ya0B?De z1>}upYhv+zAg*_-U6zJB#r8uCVPOT=Rmbw3xs%!SOH{Xgl{cJ=UxJ^y!n-!Ar%GFbXB0ztA+Kf1^~iWmrr!fo$IZ zCZ649AP8ii_eA?D3B&D3rKBWBq#7FKUS-UD7Zc8U$2N9l}k!bDEx+O_l#mDjEeM3xa_TQ`QX26C*^?S zo%b8AHWE(~e1Etei)$UCg|FUx4!U8v16ZT;HMg3U7%#8JRaaj(vW4du-w?8EU9>y< z-5SVw4dV&;qk>>jI^&Ebc{Rrqgx@WlXbiIn=Q{KocYg;_u{b%bIJ2A67^e?VSZ$>Y z2}ok(52>u{dyUv&` z=SlT*brlbwFaQItcg!(NA1K^-)-_9i^}e>n(J`hz?F z{G*sxHL6bcyK%dB2KCsZ`spxvq*$)==5C+bE*7PqMe~|G+P+(vgF?{d=8>eg9sXF^ zVG!x%-|YR$V2nJ-kNXq+RrK*?quW`j60zss)CP z#JWeW-^v+eBPrOC`#tDtX3H0123kTtN*m*s(xjI2$K|=eLnEcduA<5 za8*dzH&SMpKa8Fh7mCnP%||qoRNoMd&=$rpu+zk7FXLmC{YU&)?oS^7pvzImCI55+ zTLp7rB9YHuph3HX7y3ct6`-C*R_2?~h<&4x$~Umzq)rH`MJAJH<;%dxUz?+$p;ZBm zO6A4w5q+q4T&WP=?;9ZwD0RA)n)pb9l%pV#u0`!`hr6nhqx_>+j&+M&AzvM>ydBZX z{l$FDH+@kJdc@DbJcI^3L*=6y;Y6e)BtDG9;pa4EaHHoyDBsKDW&dh_kc2o0vShWl z=h1c}j1)Wn4e(r@IVv`*Xf-CNOO|YX{cjKHxr^48QXa*qSE>KAV&7a174$DTOa*mV z36f``3!V3xT=S)0r51OwT};Umg6=j$k@+zanRgl-mzsKgsN^r;S$Gb)AO9KpJzVdi zvD32O7gW1@(^$?$OZy*NIipqHLgTV0g=Mt^PO-wl(Txu2XbCS!PPiadRn<(Oumeo+ zf2pom4C7PvmNW`-VxrmzE*=gP1iEA!CH^grAh0U30&Bv@g%N-${VIGCKOiS`HJb5G^Emv3oMOymx{QfzlLI3}^*hngt znz#fD`F-Bku{?QJjcg%EOMK@7W1nGMu`{OFsF|&+2qA9J+w#OFY8=xT$rnpg)lLzQ zf4^b%=q>sIb>vuFcuHQMqBzFy5_k?g)+CcdNP2yoSK576TEe+Zm)blXO3&r!0)ZiS z)A{kjIdu2K4Bb!-5vbBIi>hMDMf`k$@6ka_l=~lv)bxF`H({||cUVgmh0?u_1Q)Gk z{oXT}p^4uCS-^bRO7oTK0bHbX{A<4Ry;pb)Z-GI0^30tVOM$k-=yYh&*$M(3(Sp=N>u%@C z5Lxd`q2<~q>IHl!1Onz?3glK?TRGXKD4V0yIF`SVPEO6V5G}Ph2f)L!Z_LKFuRXq> zB!5{nZ2`o0(wYdcf+q}rN8j+uaGQZdJHWd;i()r9PI3eeBkRD^F2~N=Ev8&BBIxE4 zy}0ivC@2u%$Ybw5|f}t<@P_D-uXekJA>H75>+f&3?>qC{Nag6IPJJv@rYaI8q@uSlG;s zJ`&;cO*Dun(SbpPpZW;;}4 zSw>y$B= zbH1~@qlMRTSpjuO)}Wgy8Hj2FC77>#MzoCv^+l{&oX)QAY0dA^VM>BjPuAcvC6zvr z-EI@4dn5;5jc0eavcIpI90j`OqQlQNa3x-REt5ffY7pW5Jh`hkNP1E>oC8F;Fgv?368}IJM&kYH6oTmHU$=Hdv^Bc zqJS$A>tq5i=(}mdk2yJ35O9#}rJIpWKQg?p?CR1Me>Jx~O27KFB?8iGg4uLt)2JI;sMI<^ELP=h_kq!8MJpj&#Fovee@^VQj_i!DzxY7EMR_(Jf1Z+^7yb?< z)X~!D4Zylp^&}xR5wKLFf@(46?}pMop5(?_gip1QIo7$}6+ovRrg-G@SOu@`vPB-@ zcDPXY{2fE)kT#{|4KoXEU9LlQbc#&XVVTz$!B7 z8Cge=#MPX-UB9&e_kQ)htSnWsFDujg`^U{VLeA9*i{3|BpBU)9*`e` zGzl=xK5=eOV)C(@n{$Xx$IC(nS*N)H7mEl6^oc~*kLxq|Cy)2HmuOnoP7qL;omJ$0FhO0%qj?7|lN3 z>xSU1Q@JZGplquu5h>*GYG`T2O;g39^0{Kh91Xk>13rX9@4mHu1XlL_@dKlJi!s&rk4*L_k?xY(%9DwuHw--L z(Pq~z$bBhj`}a*He0Mpg$?kO>sz#a;!Ct*7-HKLx?u1DAOu4;~JupgKlvM}q?+hV1bNEmFo8g2vutLDzP(32Diq^Oh%`mYwxxQE_PoxeAj61IB;x5 z(39!-6V4+-`&sgWXMNExKvavYPDerufw*|<(nsaJ&V|OXQqr%4L6da;>eX$rL6KZ} zq;Bla+uxJ7^EnaiCfHWkV1%RnA58vGl|oA#yd=7tOGJTA)^rueM+)h}Pk3X(sN(Mg zR@m@zFL=-6XH@ZxU;5R7XtAf1f){Z@N-bC%@1lNt#qT3p7>F(x6Iqyyw?H6FBN!0; zdAmL)@d|IcrR@VU^+l&G{eP-Yq$)92@Pmm!Pz~!poHyYrd_1#)NF=K3F}>FfbUzy$ z#cZ$f*TU8+p==ZsOTuxdNv2j9{fNo@z!Jy+HxMUjH-^ZW)F^S~qtJmvz#0vY=FO=W z;xIlfLoW!yGxlbcl?xZ)eQiQ9H|_Z`?3coifv4l)Z(zNW!CMLIbNis;lRZs%@ax^$`*#xKe{e+5BHcNDA_-v)v`cB2-Sjo^=@*qfibm0?cbcbx;lWzU&WCWk6wC$ z$^d((&|cD?$O|A?^Men1K<>W$yeGVp67P*#O7hpix}6*)yuQ(lP2<%E8W{U<9EJ!! zp_@jTi^fMqfqJE^x9)0&($S3CS^_psscWi7gF9TW`g6E_l+MJs^7~aA0`9;J-4g>c za;oR+k3ACt{#qf>d2{G3%qVBVm?bBHV2%(;-Oc(Gh+d*DJ1;w0gY{%&E*C*~drkXQ z+%fYZiZEtkVQq=`Cc@U|VB=>sm(I+dmt)`!9Qk1B&Cq!gjAF?5G?_zYMALX!aB2A# zA?a;1^2%8|>6&zz8Bl6$UA#;}^Fr~ViU0~^?hK`^ZMRN!S*~zYOHQe+>)s~k)s<%} zUQ{dwpMQ_e6m-a@X{SdC0zPs9Xq`b6bNur?)=JZF&s=^2kgZ3W1Wo#1FE%!|Y&@W& zd-3i`*+>lw9%rb&w5k}2TLS*$|fy2r*8fedC|b19QEU8+;xIx z=_4`ib8>gv;vtrLYh(8qlYZ+@TvkM1VTYu(cVkY7f^MHV2IF6BfBsQKAV4;`uJS4y z#tSpNt}o!eBE0HQ5$PtV8Ey`z(;WS>{StO0e0LWF@wS{J9i+^W+DCJXlQ`zml3nR$Oo6uII!m9F`D7=xqR|@yW4949CSm{>p$xu z0(Mh&VI|@{+D~Um;Df#_FprFu)FNx|& z)UCoYnw;Fg4FCEOJVzK+N>?j!1Dq@GYXfQMP^==L)cm_Ea|G<7z+=c`mQ~%tQbn-d z0uqP9wmIghF}+Cu@bZRj>|||-kopT_a{q|Th#3j{2F-)q?;N91$7Ak$Cu2unq?+4B+M%GybwZFMtr^{ zgq3E2%BHTBOw*itri!6w+lJuak1Qn_c$ebf&!W`Y$Q#A@Z}5q8|0syC>sD&S>g<1V z4W{Ew_y<$s#xh=JR*sslGA672;pJC~&btq)M|;6fBc$sLV(V`K(*%~p)p`QbgtW`s zhLz{#6)do=G}4p6gh_?EDLOgjjZ7@);!#HEf9d zsU(3j0&5szWbTjXy@=X9g|dy;d5;-$FSkUL{O?+PX;_M`^dA(7(N%YRh&?df;?-oy z$;mVI4d^EMDy|BQ{mFDS3DB(2VVH~Dty_d3&KyJ+S#KQJ>gXa{RiYH&2SrF@P#h5PMqboqrj zx<`HFt)Oyjwy^PRy@;p%xYs}_oi!#uH@6=&3sS*|E3yvy=9kpEZhX$#8g{!g^9VB) zvn{?rtY1g7E=Y?bm$H+7@Kmg!(z}?VQHmW;T;2;zc>iT{G3609fBHql#Ctuw<#dE& zy?%HS3md^=wp4AQ#nmdYmb3|(km*tU9@I}XMmk%46w{P>0QV6haBiCM>Pc8|ftOn3 z?WU3cjXN#c-X)AoS1g?CTBq-9_Sf@gwBKePm8mt|I?Q%cQc?iBMa(=IdwgE^U2ywZ zA}=`|l*pR$U9j&5TCeOEp!kwjX{4L3oZknke$XtYzJ^V7TI_~9DGJ)3S;6+T#J94i zH%4bn?q_RvkIs{cT$YHo3|4V*d5x3AxQb%@=j*@*p+ZA3Rk6!XEBikZ#;Af_WEW1R zy}-Og0u-v+tOqWQcv)Ftq3FMx^S*Jq|7z#5^cIt+t*N5x?;9G4iywGdMV)-~!!+jC z%w|2huLY{Fwsvd(ESv+Zrdc@Jt>6I|{+i{8B-q(VdVX_&;#&g@XUmwreji_W*JZ)k zlB{&DsHkYvc#g0YNN*y$?l^vNvR!lcB)w_@z4->Vdb-Z=B41s?p7sPoAb9zglrN^% zoAV^i$<#wD{?fkkNyLSO{KpOB9?vX&j$CX#_-!!&^72;E>f#iYw=WW!+qb!-yA8oF zVbDNh{q|@G?GC#L>-Uezy!-G*z>}H#Kwni|sQW%!C=msP0nWhD~uENqC?Qk$s zY@!b`l$jbfOA~b^DB}jj=kTB;IW&SoQt2m=CS&+yWi4CDDm%1YE%9pqZQJ*;^VAJ%W+0$y|2e!=5ADT5cIo*3CW&)OI*)n$ z=NAWdaAOg3okvTKdI6LlVBKDncbZQp-#uTjI>oc^@~~)Gy%^N|Iq7=tF18_HTRJ z5i2i4zDUzWmlL4?(e}a_%jZB{s;UK--0BL5PeQw{V!ATDsLNh$WxL<)CUjvWEO@Z* z-O_{^K8s1wUsy-b;YI!7VBr1(bK44F|NH09cXLzn6BQ7N=o5oIpAtC_In$5k$!A5T zAzzo4<%aDzs*XMl)N$#XO$1t>qpTmrBy%VN{aaUoE#%j2&S5P;*E)R3Olo8#_h zy3bIt=_gsvg5D!88;NNOvE5wvUkn`p)Qsi(0P5DDOu#9dGG6hDic%KW^nj3$?-V3e6o5qXwku7VBRj>CSndx>qL;%??FE{niX7j>BA8@Y}o{! zkdF>baw%Bd@~y?2w~|+UFv_)G7Im^e**1v0u3N0+tK_JSUbHzr9e19|Onvi_cuh{< z2SnWld{d5Qd`K+FU_ah*>ce`t!STLU$;aWbIb;)cf(ML-oJ~qfMmEcqfayhKudK-B z=Fev@HD4@aapqwyvEXWc1JCU={S6czZ)ul@vt(?W*gnq}Ky1jeUIp?eY)_qReG#;X z-;)o}x8Z(Xfp~L=j@to?*~g2I$|}2^%4xb6w3Tru%_P?{qpXLvp4;3IJ3L3Z@lsZL zKLS|LcbEoGGFYI@oSdAYYgV^+qL&vW{Kirrj=cbQud4G3IQ;|wROv4YiU}bH{W0KA zI_$VKW46LP5jeyzBp}&}ipH#S)%;0tPQW5n!0~zp?z?R?vL?))ZDM@m>#^n@y;8-%WI09}VJgAb1~}$k5+@f{?%W>wdxv`(97U zc$nCM*6C4?Y_s#e{d6uULb&}RoC}wohv@rWAD(0^5QJEGczCQl@eIb41ebarXp}P! z`PNIC5fyO)Uclo@n-?7Xb%eVK?(xonXF1*@+Ib8J7}q*l!vQPJcMlm5d2Xx79I;&m zy<(DBLGH2?wgo-e#u&}D-bhoxDP$qs`F=cTqs3|-ZO+^W$v@ZK1h_%Hmp5tV5%ti& z-JOmuAqIgDL=;%6RlX)vwkxMZ`t)jJi?#*Djj{R2_oj7A3wNG|B2YAOkXg-icjtX{(WC-p67_w0(&pX#FkykS1bSC!<-Hy=Je+rV6sSUew zR(FBGyh}qDg9+b zFzaEELIhQ`+~(!*iD-muinN|xfcB6HQSfwEEkJxekk2QE{(^_w!(ZARlS*jmWuv%#U;Em& zwpB7O0x?A|^*E)_^>u<=%n>=~6jf$vPu>?q@}BXoZwLxiPd@DX@{MlRv$V*D!AEQ$ zQOZY>oK+>vmi`T=C1JJAtifg`%o9VvZ*`KpEB=|ug>2V=(V)h6?#nT#jP;^PETAbC z`S+OMfAzwxf^lYuD<{n*Io1o>m(s%e zn@y5;y$Mg-^K>$=d4hQb1;g?m?{HYCZ=n{lbp~HTr zK{lPzC(1&vW>1ca+`IMkhsnIB&Evy8GfY}Ho)*IXD13xI5&ZO!iRaw*8Tu8v-ug@PD7AACb5nTFULer^FZu)40Fi>H```?Yl>*C-Ln)k|C9vNeI z-Y$y8Ac?*S0kS{%{ibj*!Cv+UZ8+9>7vy>VG`s>KU|xz3qC=vt_ylHmg;?M@-6IXt zVEp!0V&blM*Y()?q&Ofq?U+SwLZU1c&AoKACpLTa!c+Xkdaz&--o+2og@$dO zTxW#_1oy6>D`e-_Dd|PsTWA9r}U3c z-p~@$5uyt|h8y7=Ucur8y*FziJAdy|TrvxgB7vluoi-<^VmOV|a&DrtQ(~csdTRqv z4U*|rvc!uh^s{2JNsiz!L#NPYZsV1KVXmCSd#!Ilo$)nC2Jf!Kdvi2d9? zqD=tCW9aW&elNybB(2mI8xUDjppsr^n=~eLlWX^uA};EqLC1S6r;hX6o`Bz9grj5m z0Ik^wh8b#jRTd=5%pkriI@!ZFL`5{*O44-9yuw^<)X1*E!>cCX-8U>cG%mavt6UNS zPn+gn)Nyj3X<+X59JHd1bAH%ugqWqOaRwV`mffedims0}-XI6LR~2h;T4&#$*j0U< zj^+PbF1b;YcV>ULxt(#r-JX7h1>Vogbs*rxtuT7rHh+-omkHlAlzn*BA69tqGEfgw z5?xS9pc#NFVC*t6Ug^EKXcnif@#|adrXiz~vka$xkQ!)f>{C8+mrM}q)kV_kr7c11 zZR;=~f`#2Bzu3Dx_HARCX|3eYKu(Q*z1!K$M-O~?N~r7!I^jhMil8u03clBH*3LD zzFg}GWr6}QHH6T0e^_(eKq8Qh0;DCaV)51o2{-l3Al1#!u!6mCXjUb_R&^zQDA!k_ z^I!OA=xsfjGx31&05GMjFIXiE2zQ>uk>Dtuitk~x;z#Xgh%;kmSJE$?n=-}kzbEua2JWRC?;N6<$eavw z{;f?=>V~`xj*v*$SMA0pCiV*33Qf0P{`XiH&^WnC$IiowIfecuFmgAn#%Yn^m3=ld zb|0upSUwXcO=nIc5h~hwTEPbP5Zr?DyB_ks<>g#fLR(`^f_Y?34~4|C*@XB_%SIzLd~f7cEIZmU!A%nv6fI%sx5k&>8^xt8Li9nwS1>49ay0 zBq*{QY+{>9CD7t*>_g?TSCzbrgp>hZ>wx_@;wH6#J9rfZ=jbcU>O_0Ls?aC!Q@TCAx%vmCO$DiEfk=|#vCNMb7A^wAD z2VSne)D|1WH02twhpxdm@}D**QGG8%(pR*^?3C9l6{3n+%okaIAcE3Awm;q?{Ox&s zxcltAv8j%5E=8bp5sHZK56Z!#Rd_lC-`GgmM4o_IqtkMg; z7-+vQD0OX#k6G`*bh@2whEzXEh+>R$daGfI@w;FmBCT1Bx6yC+&F_1ff*ha_^Z1B9 zE?gxYNgzG=8k8uFW4>**;tTv2`6ekqg80A_M+9grIQUJ3~qKH0kcIbJ)h2zmUIuZk6Clwn}Q^FS&P% zbrnfR5oD3`byx zz5QPAoe6{u?Wbuq{h*0y*&<715}m}IU}pXCJpVCxDF2$cW$yRXIpL2o&1N*j=MROd zKCB7@2|v1(%pRU`D1LG(+|V}_uy_@Zl-bSW{6I1xzB%pkdnK4eW-poV1N{5GS{Rb} znQ{@_`zr^c0qxM@;twYY5&!GR19j1G0Qb-5{CLn|6B-<}hf)(+?cnlzN9bhVxD&U& z9sB2h691Jh?u4s>E2*=!w{5O3@Mr17tI6?kI|6ZH1eYm{%>PKyqD;g_{HvQteYDmi zdP(*6h=1A&w$X|*04@iaE?nHk@Vmg682#=ASVUBvf<|w0_k1q|)%xOuS3uiL9{}%1 zCth5dfEwjc&lCZ>`BVBLexS0(sFleCqh8a21w~eVVOLjvuP%|Li_Fg?lF{^0>+Fvo zbt`NPo_Rp1Yu;;=VjEOaU-M6Q-VX~<6s*L(>d00|cEryt?W^PLZo_)~SI)DhmSKVp zlj`^Vd9>H&w3gU)(O6^Y?M)6uNNFTG$d)gJKB)qg>Q2GdHGnV~^r}rLboBp4bH<;% zJoQ_>x(Qml=JBNv-$!ui$R$X%HTRjWD`n7(iHK&8CbxLGp&VU&rgFU=4yhXhMaoa{^Grb zGGvKD(obV&RwfbJ&d`PF)xX`&XkoKce%eZ@$qEWti?aRa;9si)>fmKiaVK)nFiZD> z4s%~Rky{xbR5OQ1(DOwn{WtI_WqH#0t7k&giLnfu5MY z(fQX*XgZBbTPa2%cbl~{L3vCeDHvTKeamg|89viimSZPNvuJT2z6QolX-L&Poizx1>2DbBiLbS-z2QhDlR0^n#G@C(z+Rs?=*FlK9PT&)-c< zjK3B6x8ei_;YSFBp4;|ry(0SI;Xx|-ho>pC6qe>5gL)+0SSkY6tRQge#K>arE(4Q+ z?+7c~X=GL#u2jT6iS$d4zn?2kgSD#FMuyaJ^@`Dp&ln=KYq@7VL>ie5K$_e=nwj5p z%>8Z5IWeOP6^r5rcqrCpyx8G?7-%wGJ8_vlCNto#xS zbL`$?{Jb)Q1X{N7x_XOVtpJRqz|MD_Djp(&`oXLB8s3Wz2$ca47bV*c=lEd1%ycy) zcWX9V$oB;5Y$owsmv^|z4t^t4X>msiV2LqQQN;O5P06pbJ!#VW^5=B)#^vu50<0m- zcrjhA{v?)k~ivEf300M8&srRK$@I=B2`~N4%v+p*{abrmG8sTB@4r}cP zE!09Foky52UVp2l)E&hLg|nN>ie43lw>9&Z1+y*@J3tpcufu=c5?~O2eSdQf52gxTr5^gTcvfckN0q!R)n&3nvbzmus6e8P zNWP@3nDwtBu8s&q7J6Sw%Tw`<45*W_6v9XROm(z85CwWqi<6xhl7>cqqj33rsTRDC;lyW2z7{$1XJC|b8u6(W4!=(zE5M|5Ox(URsiLyO z<%>H$X2z*cvDM!J>Fkx`Ks1RUi2T`7sxj+$4u4X7446M8wx|gSOFmeRafBz0>VR;$ zQ4AqqLcEbHP>SD7Od$3F@TfHtS+a-=C7RUna9@(XOEtSjEJ6QJ`XXcanW`A6rDY5I zS3-xu#e|pNX~2u%F4WzDm4AH~v=(p_=-|XSZ$D{mB5Oj&vyc+oJ&gH=F zD;@gg!zIi7CdDgBydMiFaaeXW-Xm1RHcFU58#fKbB*evUvwUKh*6I|`mfF|dH!A2D zQ%&S64&<8sWn-0)$14jY>d2&UnjcPtMUIwPt}msJTKq7L$sfJ$PKMxmo-0re!bk|C z<33EYt6U6ee!tECck%3HrEwQ-W75Yd6%-b*93pVvuv>4}m0KHT@3)Pip=O$okM zjihlr#Snut1dqn)a~IKWrWuCmb23z~$v-5zV$jmzLfdYOReE0n_7b0W3wjIC(NlD? zRtk_xsW|pV|2&WzMP*xY%2<+`U!M?y?d2b@CzwV#`yZtA+*8fBk~VpSdY-_N9}mO7 zE2DL_t=ov~|Jm*SxP(%${1cCb=;;CDX8BCQ8w4RgzSUSqI;_LbY@3BA6LFgSmah(w zYH1~}^3B10-;N&gE#i!UTZAfrmSDZ&OLZ@pzCh%Kcht{Wpa0r$GsG(mg(Ce9?424Ct(!oZ{u8Y{LTHvfvBH ziVl0rVrfi|Kd6vyNR#JEGQP%ow>l(eUtrTAio@y;rVr$;4%?kCktaGstTr-M$WGM zm?J^(J`+HHr8XzQ_5J`(?JMiRFXN9WXKEJ?7>(PuN z2{*}q%B>=N;Uvsj#zO;AC1Km40UM>d?{8z2(P{B5sG(@a6CLQSECNL=AIK^YpN!cU zumE9fbHp2dNynp935f5aMrMJY5(x!EhZ;O0fY8nR{M3W=hyP{s?lZdr^e8m`RL;e-i?f5{>$5 zSBMIkeUFWh={5#I{`;qpLWil&V_p33Qu&9w4Th@yJs#9Qw~kx~&F@GKe_#9k(^vJD zojNc4TF6VHga8SyQeywha2cX*Ugw$cW>~%nurLxGJb!Yc)Gv^P;-ctF%L1`J45^zJrvS{4u7_9< ze?7PJz)p!?GaJ3E<>6-kDYcCe>J&h%s`sOj*zoCwTr+v_Lfu+bPlLC#s(@K_jOV2d zH2k$P&^7lf+BmeEE%_tq&ZU4VBkCo37JWHO8e?{avDgNT)^$}&3$d2LN3`uIuiy!j z!DjPX3zspUL?@APydNl{KPMr_WUZ$>A=L0zc73^{X~=n*}iaAq{D z-o2AdEi%`9;nAkdS2E|NiZrWS%N&@X-6Toicd;B&lwgE2RJV47rMa&8VdD$zt&jeqlwQ!Vj*W)cTZ>KLPbVG-EwegKA>X$z%F7HBvWLBA{<-z zyQsGJ7vt5I4^@Yu%Z* z_mllb3z^iUdWxVpd|IqIerlJ4jW@O&a4P~F~QD`5J&Yx&pfn)WcTt;~-?$$DHzmw9*buI0mC( zm#MG<^nYhcd8@6Sln~NW#usdSQOO*C8lFmw%$}Ac8YCe^9V_vv)t6NCf&s~g#$;X> zN$2Y6W!eZN-fbm^rr0bc_C7Hy{R_j(L?xf*cveKGQ(J^jjBBqh!xT_CGOI%oYMFy# z6khD<{FOYW%M0oe?YXb91Gsl@VV*E{-tPK8ZQ8h~?-;pmBNVl7--pow*# zlvK-)#_yKgu*DN#bXA+$epH z!5(BarII7T-$wr4G2Gu&)RP6J|I4klY7QQLmj@^~?9Lj1h1ym%z0{9nO?>%1TZxF)8FXR;|*U`7smOZ%Q^nYn$Bgs1<=sRIY#34ZTcJnEC5UL_*G8=ifo8LL(f z=@P+kvZSNswq}A;G1(S{E9{;Z{IQLFMBvbO?*A?J7#U-JZql7#jpOXNI46c{2p8zBZ)DulUG3J&61_J)7mowZk>c6R|AW;8ap{O@i>_{gYrk3+; zJg1@kF?^YMPml_?`>|H*iQwW_&dk!q!W*!5)pM%QDW>W$l-{d9i(u1NhT1n; z30UY$Q};cw3)n7vO;_^>O18cfOkhOVTS#Y_n45G)Gv2QepKu^-Negh)+AzcR4!rM~ zj(Vz1g)PqNo~*a3Nou<2Q~l`?T@&FZhdmylt@dX;-Wx;IFrmwWNrmYzoO&g_XanYX z8!j4eba9jluJ{sILcS&}dK$CON&RB;*YH|lpu4_cUAbv9l(xE)==LGk54z52IlRq3 z*?cme(2O~Cp(vy&C%t8P_VnlL%L(Uo9A_V*_R!`}d}3%$shAScy_hji^kKo`&=eAb z7s-n5R$U+yiriLhC3Q_${wn{xr>Irz_X8?0frv)zw^?dDB``1kk3I1*T?|`L?Wwt* zplW@0?+>g%C+c@WK!H5G4!jY-kOXEB1Dnmkxbk8Jt7`?(#iKW_%v0(?jVa6yEV7Db zKUuiwf&0diyr+i`8>!Sz-oAr>@C}Z8^?$gwh$I2yP#Zee>$lTc#@I8}@`g>xZbhPc z{D~DOWnS};&?>vHg{|s6O^$GWnCay~KM8G+&1}{UvOCK6}8fAQT{=Sj?H5rw~u>A~tgC7KhvHWiE zyf3bKkbEvTY94RIB?lR7+st&bsFg6%R?WCJ_V5DMUjOx7+g)g|=CHp#4Eu~B5sg^P zT3O5JldZrF#V41)q|jOicZ5-|cbe-&pECWKR6OJAXJ0C2WHBZS=C9cdci+H;2{7%U z14d*4gTk%fo~Cd|P*frzLod+$hkOM1m31Z3W}8!OhMRS`M-uP!27v^fW%00$jdevb zU0p}#gBzqnoRBC7g}uQ|oDIQ0`98P7M4+^?!-lLxcp2dp_=MtqC%K1rr0msS#N1og zMKQ^EG};yt8;J+L;7#@xj`-L$Du`+*xEf(T@RHL1QfwY!EL11}c&oYvNqT(D+DYsN z(W_F*Ll8A4bP3A$k_O3`%4!RoHp?q&BPqE!@Z^p1RV}h{Cq(Vh9+7#;fX=J&YT#8@ zh;AQ}3pGo!QfF=7q==2QOPAxQ{IdIy5QuwO#rr`c@3|#GUTR2H+>5F5@r#hQ$*jhz z(QaEcUD;Nydo)AaJB7eSre{DkD2F0{9F)HCBzWC((5AXSay+i z*#Otr?;&PMQFQ#B`<61CWthWm0>h=CfAdnNT5!O-yn@}=KziC*vtB27sn+7vN=Ol{ zt6-q#EbZ~YiQfRqo;ckaU(|QFUDyo}o)RrIBs~C8WD^NCD|my1To(JEWu=grU1Z zkZzC;k%sT^et)_6Gbi@hd#&}{H^ncGgAZNk3_SQUdt(L~jCLgh1`5w)O72T{JnWsY zwhx)9@E7>T^q|PzDe?A9z>5=o^YaR?#dBY&=30d=pW_~JQ61H+Se2v{xOkqiB6bkF zB-ul77cHfiIf(kl8U7E7fKgF0wk+RBp5K}`2Pp4>iRFd>@!^Dl-DE&Jt&U2M)rfA4 z_G)@57fIrW2hhx)om9=u%mT<#N=Xm;fS-Yn$`sTGr>f%-;-n{41_>xZPWY(w2WQSJh^EU33Y)Z;90&=(k9Y=8%efL58p>M{xDui% zC)oMgPasdUm%r7ygR8F37%|HYWa0|Y9`*>AxZZxWK*ST9%vkN%)%MO{4By9I=wC93 z)M=mwtG~VexeBg^mPS#}*XPh(OtH4AQ4{AJMX31FujtZiAZzHx0=y*F%VW-ZB}X2h ztlL(0oR`!u2T~WxLH{B_PIyf`Zs!IdE#P?2#G*WX+M?_GbbSZL+w4qIq?e})j&%Xr z@9V2vmY>v}!Z?5^lzo3SEq^X3GGCcaA;x&;ae#FcsmOt>$f0oP>_oqF`H(BY60+ex zmDU0eD@LR1xf**uOa4O8WG(PEXTRra2$4C0J5p{sBTVQDImN$=?@ZT?E7UyaMwI9J zVFQBE!}UP07`X>kpLTA+O(;%3T~Mqm)E-b=Mksj9p8?Fvr%apz?+TjL%OM*Oa|4By z2y42W08iH!WKEw#F+zQf5bIC=e9~Yo=I*R;N{YYrCuaQ{59?Qq$89gZwU$>JbCNcJ z)}PrQM&N}3Zej!$>fRteBmeil+@Tr%sUCNm_HwkY>~{_$RQSKRSmKD2nc|jzuEbh_ z!5J*%4g_Kl8}j)P%B5dHZjuo6wF#hYv;y!M|4a7t_xSby`tf-m>kEoZ%J1L5tFT!O z|4N>#N&_n>G(qRb09;`ia73+ReudsijGX0fkJj>#fixfx>gX*86_84L5nIXbR=J-t zMvUc0kg>k0gu(bFe<379pb;ajom9zlfYbg)p#9>+)(3wylu^)N^UmMHK9nVTBg_9Q zTFf?xg8zQU`u54zC*b9|`vqj-pkg-w{Q!H{pt!4@JZ%=GCAJ4vrna~W8#*M4m+A;m`y1%HAetyo}KRO9cjQ!1k56^PyqDdxr{Yz^$9$QoI)sSatpa7c7q5ISRqU%lPHh%ge_%QjjG0(Pm{4%g`_i z{)GJG{xcj8rKaLgA9;yoQx<5J>vPk)L@Qt-SgBS&BGC`2sHWo~I+12aZ~YplIP2?5 zvmFZ4JNi%#@a|5=6-M{t?gz2ZK`t#dUj(a9=K%y=WH@StEthKKlD;xmu+Adb5DNTA zPWJuKr4!wrl zd-7G0%gXJgCy{WD->mKvoYDUa;OE@CNaFR9hpqYw1bH+-vu-b;FXV3>n}N&k5l+5L zLZt{u2JyfD;X{PNl10!7oT}Vjoh)p0b>66xv|9=szVi)GvwK|vPPGx=T|=vKBUM#j zGLsDI1F@x-N5V^af$_wppU|_prs;)+P@s0QxPk}xNxMZ0W<(_pv+vOWTig5Aaw=wZ zY}0uwXEHYc1D&SzUP1#tzL_qyiG83?hE`#gM>FepOH*XQpLbs!vftPZ1-LsQGU1N1 zT)Db~McpA9)bcz_b^!;HL{<9*AMKeoj(aoLF9k_RJVB{?9>^dtKQ>w~GbmERD2fAE z(&JcD6-XBzAJl=;LGSBk1wk7lPtcK@kQ=(F8n=9;${`~2Ytr~P+$eQfB@ymtaya{dISGw#4=Z3;P3_?%kis?dR2((ETh|jSa-$du?D1 zAQLJjCW+YwpWAIUMcSx9{jKf7BTVOUh-u*;%oHCTLlIN>g|&!$Kp(P*hJ>Q;1x8`tZ)NVfNnnC zb5=UW3w}UCU*jok?=NYXo_MWa-*;oT0D)f;NatiAtdeQcF8|wWJ!h!!NVe-kpy{>c zNGRmSy=FHYOrP#&{dt^QBMOg^64j*5r!)XaH9 z?HWc^uXXbi@TLEir~^V(`J=Pgb1O2CvEvbQvU%`^>HN!j2Z`(26DR+_F;2ti)!=~x z*eNd35^Y9wEyG|IZyX~mW*9ALcyww@*m#0B)xTJ|V@7(nZB+5QkzC~)h}BB`k$fEx z8MjDUiZmFLje=n|Q!suP#J!umYB_4lnUhMg&VABuQ_R1QXV5L87V%Ed2(~#I@II2{ zc!+iocPNXq1FQ_5IGBpMyHU^IB#agIh`e%--Pu%6(eVb zo6!V>USYR!k0Jqz2@TeC+9|QEV;$-VQSnab*?!qvj|9kFbPcx{BV0bZaa3hO#c320 znb+ZYe-QpAgbytCp3~a)7m`2G>)yOPVS18vfNgz`MkO9`N`r9yBrxi52Vneq?D;X> z=`-JU-WR)WcZa@UO!{6pZYrLNI-3yi@HD7`m4Wy4%tl%0&~Dz`vcxiBn@0t?Eo*G_ z5hvY=U`bs!jF-npaEZb8UoIAyAQ(fCdg3IN?aLYr&Q=oz#_&%TOmhwv76uK%DV^ ze3MrO%jh2~zl1k`abXCPyoit04VTT0yr0XqJ91@?K+ zlSuz}Z9n`Gg?*Bc=}IabP(K45S)lL3al7)@M|6VDdv)j-lGQt31gt=9Ru;P=JuO2i zW<{{-t&ceML0eV3L!?;N^$KA}NcNl{HVi}U)s_n$y2=AyF=*z8teDdmq~|*L>e4XJ z9+N-Qia7YCvD-YAx~yWeT!0HU{A{}^@-`XY$^k!DYyNsyCNd#{AEu637jO8!qrEw! zf*N|2s=#6^g4S&?qD%!4;nBa^qB6=hR=(;r3<3H`LnDv;QQs_1Am7r+>2X3kg%vRKlA70M6c%p zAqbcy2N=O9?CNG}Ybe(1%T`77@#AWXpdD_!n~_bS-R+cCm5FyE-Ni!Fw4K+sDOfD007RbS~7=Xel;J_y{)@!Koyi&&V#!vD5$4L8;1H$+5Q=@G=k)0a?@e2oSKqL6 zFHor3&QcS9UU?s8;cgby7-t&s3j=_pJhuZS`$l2=S;SAJIMZgT#6(0gq(Mxc4(>Uj zKxLwT%Z8AQ3}Fh;$1+E93;^?M>_Br0MtF&|(xs2G90zakS~3X=kQUG_S5%R*Y?YIrr>as$rI)a-wE3mEr*|yWrC;%TE56o@8ragrytXExA!hsctOg`AZqv-Px@LV67`1zFv+%Hfu0`1&m?2jg7Yh1tcl`cb zYqk2e<18>2n*GUTE9LXEkna7SrreFS8i)A8bwR4p3VK(iXJX(QHs0!-58s}2ymcG_5Z_SZyr^6J{8a9t(d)`(Y?08V4T z!4sYgfMtrT)`xZy)!#S)z>bt`?6>9i7>lZ&%6uI6(I}%R7CXrLV;GK}&8tOV8?wO< zy-ljaZ_3+9mMoE6*`Dr{$d>3R!D4~@I0sVNgY zTi^8h<&$gM5)m1*dqGS7)DPRH+t+%fhj;P4{Jy=8ehG}9#_Bj$w+;L~sGNJxd7SD zGGp|EHM{m&7n}DzZ+D{?w#p`bKC-uyJ9@qZ4cr1BFnF`qPuOC?C~XGonAp$Foej>* zuJ!ie1Q!oO^3*PlA#)npU>go&lDGieQC6nuzhAj8UK!SAW_vXqSp3a#bP5L_aeokO ze+rnS>6wdK=(q~nSL4(#5KA=qWZ}d1#Qpn1iRVS!IB)yr$JhAB1{rp8f((@aGZ3qL z&7iCB0^#3$aK|l8H8k>z0|)J()Olv+3&HxsGsb!D`ZFah?f1Y#|B}Q75xABrawrZd zzC?$EFU`K6DQ^u;(}8S1lu7?ywBr(wZD4!Ci!tpZ2#T=spqy(d%*~Zn{66EhDYct` zS)Ke>DLSl?#1m_`VR(Erprl#*Kv;Us~tiTpQXv2TI|XlYf4W2 z%f3#9rf&W`d-3eJc}m^Ne;|jx5qiPueE9j&+xYV2h{?a$M0Y0w``-ze&4ia@^k=gqa{Jw>1i8`Dj{1EjAI+S7;tqX{QTzsrtZ;PY zrzAYTFjRzMfiPS@JQh2IyU}{;!NR-G^&AdwW}Qj1INjDL|LygYw4j~?GWe1%2fetLnxx{& zobwi`Z5bsWDt-6O(et51Meq~`6s7~VRB820u2Umpp0T^u+5YzOY6>O>ui3-M9~6;N zUFtg6{H~gv{&imQCiMdyA5m#LHy=$019YgYtbZ|^ulw z`kPPQ1j3raez#o@+2=oF?l`zJH|(wb3_^q9L9%tgu$t#RXhR;KQeh;(E(F$@+uW^j z6b`6Jp$(HKM7o?j$sl{KI{{Ez6-#Y{2#wZCEPLuIwcrX%EZ^s{bE%NA#IC+61)Myq zDYFF2@G1EI_Ij!5B{C}5?0~0nqLoJAC+ETm*RDmRgU~evpt9tqahu+4|3%$8?r^ns zNmoW@K|m3Tb3y$OI`OdRTv{}bp<)1!O%`}+FxGJx(YK*+^p9wNY8(tA%SxA7{Kvz? zpM-#D|95Zu!XLv68wftIx81m`{QKT+cU0{gU9Ecsd%W2CRo`LVsYXFCbdN@a0;}bQ zu!9Fe(+y3-&%2?bz<76;EDK-l_UG=l0$5gN6@^HTe%W68T5^SRn4iL8g{r(aNV%Wt z^a$W9MwB9?h&Pp&J$GhX-d^&@jgaAKCqtA)QZAz28=E_ghnrHKexK^|S$?1W+Q(0q zYhZ9==^@V&t=Ke>=Ok)ytAR5I0otSIx)$(ox*DDPbW7`XvMkiw4Z97R?(nfyn9Z}~ zKldy^v8H^aFjnXq)8agL)&o*J-IOq*K6X!S$!@Dmll_S~&piCQ;dCNw=;%ZISix~JIF6PqUMQ`^2JZKg|FT3s|3Uw5MTKm zn#xFrSns+m>V(*|XH(;xYoC39rFjEd*wFddaTsX#6EW`y;g_{mv@>x|sN;k?<=T_K z61dc8P_L`|#`m0f<-VQx{AhhGKmg+;bbI=dJH`;y&BkFvHK2-3UY{)9ft7UANaW~w zKJ;}@^BK0^-hwQTy`v+*deC-&Nav5kSe(IyNTvT^PJ7Ug}urZo0w*dqJ zq*R4_rJB{)kEA9DHRsG@@XnThdSQ)I|h{4TReF$dTf=o9QW0OI#B(h!)sxAT3&2cycf_{ZlGkx zZ8sv1&#|r>H(gIS%nQ6bV-n%^6W}x9FYt7^PB0U0E5>#`7n$~#GK0ofO($CIdlu|J zm`OvQgty7GQeY=(>=bNe&n!JgIaE-&rVMx59kg=mY}f`-fVB`W5Hs5cL*2%tqDXo~ zCf~v9uU{&aad0SrV9^ULIhxX{r|A*oL0MQujRuEIbR#032X*n|DBX@;ffhklJnZiS z;stKDCWKA~a(*J(@2}o$V>GV@E}t!uq8Mc^E1n^4|7iBO##Ho~vv=z;R_fU^{G zGPs$xO%|N|H3XalP6N^U-4m{)KUuWoC<&K$bD=@wxV2yBGn$J0Q3gOf@jp6H{35h| zys^gi8OX4J7xToMDaIkfG6YDKtv1^=0IxY;5{UShGcu-;w@fOk+u#1Pym?zGEIu=e zesCr| z8p8(+6{&Y>iFtbGSz|otz4*xigdxBmA%GFPk&h_F!O4l}a70L+3;jFCMaV;l2qokJ zl~|6;<#MuP%Fp(lpF12B`y7PCTp#^1cv@;)Y&#*$x}s-z!mz-cg9 zDq8g)S`=ZUzOuJ~OERb4;IMbV4MOlNR6w|q75) z$5*eGcX&c=!W8UzX4TzJ;YcopSA@TmMa_SGsPT9ra{FtXi;}nVFr9IRNWADh8Mx^D z(o0Ch8zz7eZ8$k3$ltIJ0+esYHt5^NYH1Z8q2BAG87nE{|K3FVW5Hq>=5lV(&~S9Q z4G;T?OL|Z~G3PFccVc7Y$73jqR2`Wa;t3tcxPl=j-v2zv%%kR$(e}D{bJ8owySpEZ zWccbGcpJ#8ABM`^-!FkFP-NKK|EW^{STwK}rlp7-LBU6*KUAzEdU;F9K9P4N3(}9< z@6O2yklR*pkiE>aM_6U{&omWgGaSD!tTlW3C}d|thog=GjTc)sogpCt{eZ1`zd#ab z23mm8MrW>AWA-*9$tV%yJfz zx$jPnG@NQ_9OVhv-7Lku_w?Kr1dTb=0(c;b?4<&2wqM zo_fg;9x_Cb@GZskPl+WXn6d9%bfV_&)Uj3*M1r0t9^#DiCf8t7z60C6%*_e>Hc7wy z1RB8%=8HroGX*onVUC^actrtkcwV4Ax)q~=|3=REjk_dKdm1*?Xax1C0yf6QdWl|n&%U}rR z+BrNlMB>3kLq8*^o|EXWd{iga_u-xX9xf?#ewo`sdyEIa{Pd) zaR2@k?y~hAj0>5KFn5NZ72yV!kDAwh3)zsPNENId%oXo(hF~0&5RnjZ8%=&z`R&11 z(ax(S?vAY|bKqJb6Tx@;PHyKLerB|bNZI7w&pB#aQng)HPWR-F^%Ml18)~W;F1t_+ z192!<62wl$Z-ruWIU5KTRcj^*&Y9d|{%Z8Hb?w8+1K!)~;Zl^(ZY+;TCn=*4u*k{a zx8J%6vY~{79lN&!q}(DB;#MExP91YK%|)KSAiGO%UFbMHE1(ByCw{=$Sg8)&_%S%0 zTR=fZ&hC)3Gf()Ptz4G9g=_k|y1 z?vAR|@YqIPxu4kJXR6mZ>dxR)8^{xjP=JzM+5}8jN%%jMT;;?&^awa`30--I=(8kM zF}D*s`s^?|6L5Y_FJbUQq4~h~X89U}g3T^M-;hWS%V`*ek$%}{M&f;r-`w{1 zWGYkMW2ux8v})@ZC!}EWT0j50<6D`k=#QhW{gE>uS$N@m^r8b1c!|-4BzxkdUi)IQ zETO|crU|yYl5D?}ki+2B&3=Gw9^=O7c8k0eKLclLmoy?o-9d?;hD^?Hqc}>A?h|Am zE-N1`7(abb&*ozgmXI9IA@FL;8j-+9FA-1ka!7PH2b_o?L@SsCmbWcfn^(Sz07BY${Se*Bcb>yzCD@mQbwmAY4OE@C~P zX>Y6CXIBJu?Q@RBy($yq_?~pZTR~C-n1g%JzvPJqp19SpX#S}I;Dc>diPp>Mb-t5V zP{N~docc;J9c73S9rZRirrpMrtPbujCIA?3iT{Fv)+&!rO?Gh&zxVh8WJN zAJ;>@&Gwl=&K5MQXOwL6yjuB1QG7OknEOfmjQ~MX;#vEN6WuSJm^btcT^fgICzuGJ62>=(Qf6U%)LpJ)Mrm#WN*_S=XbT6i^xVs)5FX69rPx3KXc@k1GA6gReFCNZ&@h}o z^sDME49J(UKK~VIK(Aes%W5#nM?QjFNwGt~g|nntS0sZ@|Etwf#xv|a2tVnfEuS@# z)*C0M#7dOXE*_;LFDREE8k)2m`BOHWU`fO%wM0f}@wUH8_)}kR5$?nHnY`hewE!u{VEZHcOcpZIH#=ifPs`RKsGh4d zSep9zmpkJ@wy0@G$I38HeOJ%Mo40>)(7(-XRvUtiyMtBd)EuyLZ`Z@MN+;%Tz;Vz0K792+z?o z$&@T6%jpGKI*3PNRg3MVU~X|8CV{XW9N(p_;+DVX!%Z_Bin-tQGSFMmD*Gorwd zvd5uQvN{AwnPQ?F%bWF5RzQxhUcnN!Px*|FpP)C{d+2xbumHfSg2u zlaQ5(zW34l8>8=m@bqK6+Bv>r0Uo{O*aIg9UR)&}ri_b%M6MHdjc9jfZ{G>OeXKSC z9$2>G7|T38$k?Q+W+=m=V&dL2f|a@8&V*Dcenx6kNrv&g0}O{KBmZ~mbvQPK~1#2-+nNj#-d@Gk{w{2VR9wibx0>P)*WF3`|+s@ zQ!AYE?(evhMZz%bbde4s3%_Zd72atVMOGW}{dA%^x(L8VZQY#cHfJE)qs@tRv`#!onIPW@;z=qNlGr)*7b*H_l16hV}T-{EZnnyCeyAI{| z44I||m+cgqjGC7OrgJ%k3{Fp)jP19zAbnVLRBgQ4sZI;ZSVMUt?c$9<6#Xc%WZd|h z996*x#hZHBi7>MApaw`k{Tf-Bn?|u7>n0~3J_Q6s@_MTtD^uJR@{CMObbr@SomBwN zVMwD`-zD`D+}7TJIPP%wVoW4(*)g%4^kU(4EiwikuaPW%6db_GJ7v5;p&&q3iu0-# zzyzUTV5s5d0lCZaU-5H)oN@W6XbBp7-D`pdR<#H17dJNY-au6yhd(xdb!SbgYrqXz zJE$Af3#yBjcRy|}HzklUg^#QGK{s5RH{l!KGlG=7U|AxIGk-)QuYo~qAiA4|vLJIU z*@ZY7bZR(ams@@Zz!X)idNw<9{HDT76H`Tt z>v5vyKiKM9t>8xf{9!`b9h0_#Q*@sp=b_j1P)2NMrel*v*mWI{NR`+o1=A&CxktFr zqQsHki*96Vw^Mgo3^(uo`XSPAOY>BidZFLQ~y{#alK zrw;>!G9Z+@tHM&nKx#l4h%=VU5i&eHti}83zpy9B7!43fd~ca4N%w!{bOEdocw*fy z9|4JYW65~a5T!I>^MnGa&FsH2QgD78)hj`ciYca+qp57opfH52Z$TN)UE7IjAU74Y zTI%iyl7Q}i1hxSiA2vJak2+NbwzEy!Wp?H2O!EWA>?!Y02tEPr zqt@?wLKC~20Y=BafwCmOO?=$S_Ll78$9Kfe*3;QB*2Z}mE4a^)A!BMiUK z4~3~?3@$1!MJl9%`4Fz-V_@LNM;b;iGwbm)Mz$CRi1A=piIWC_@-S)doq{?mo$}8C z$K`Kq<@_LR)0gM;<5DTZKQQrqj1<}f@~Z0b)TL^3p;_8ZT*zAab%X7*?AmJ$1F%vB z$s%?7QstiQV#rqCuvOKe67je@j=I}h1Sq&7kT1FE<@C5KUE#Y@>grnb2qJrTpWq)Q zkVQ}$A4+s~frtbO6SIWTvX^sos1$n1-#;hT1_n@kSci#sU_Td`RuBu9LZagaBr(#W z+hE2eElrc#NWq;%Z(*1nEuo)9Tml}GKF8qOH~Dn53WvOc*%-;|A5MIRb>rjX5|rs2U{ePtirR8c4&NA(*;)5$j{qdLp;8mV-}LY zU{moqZr{{PDecKUaqwD)g6MT6Z5~SjZ!G#6sHQJtQUEVl?$>1(WrnyuE(M%9WNP6U z`pys@MyjeKAO$S$!X=(=J-Ltwa83ayFc3fdzM@}Zfpn!r4bRM_5LjXZ3UV(ddZhYtreY&#AkbhGE#U8XDa@O0*O0>)n7Y8)p zfwem}uoJw)?sbNQS9^fo*N_kaD}E^Xa|B|6!!0021Pd!`PgfO+3ZmEP0n?SkcHb9K z9mpssv*U8b zhaZ!+p9p;8C5jO0Hahw5>a6etaT~mt)6QP|N$3?8IY=EQpfq@X&EYf$L2cGlfd%Jw z+7f;-BWVR=mGx2HmTjK!fkx|36boEv#`-i8#j4>SCb|O=Vf~DNK#;Zn>vNzyXYc;2 zKIa35oH7j1mkN0`YK5bBcHk6L)39oZhy&ezAg`^gP3d9N=O4ppirgH@J^;8l7o7Es z?diJwW#!Uug=q{8Y{`$+^dHhkZ;18?D?$b3XvAlN z7%KvVxld74sfo)o9P`Hc!X5wWYl}B> zzAHf{fNQv(<_`~YN^#WTJJ}o+ zpx$G$lw|b9#A+Pv3hpsQO7h!xXJ%B2sRJO1pQ_KOQ>IzJq_8MT1T)u;6n1_KMGseM zCPlib68Byh24H{Lm_N=JIpV2}Ei9zVN^Nk)sn~y7JZX`DBy(guGScG%7>bc1k}+Kq z3dAZ7#?6@%#w%rXt1Fm1z&Z_bY4Niz7*axs;)eOFj3_j6oM2qxx9V|g_9{-qRNt)! zs+|5%PMaylN~k(`m!@e=uK^{4;Ia>~NbGOM6n0@C%4LvCzzVV7eB~D~tN;baZsG7bv^%{foWjZGPvX=0lc@<&nV1&JqD^T#Z%pu6!{Ls^>Cvf` z&bJ(d#iJ!r?wINV@GVnp)$HT76igTZ%U6d`e55%q>(4gysprm-VZ$Oy;;=GNDhRAebO z1E;MK+gW-Ezgi+wQi-6e>eL$b2OXlidcFAMsiG$dqkOigq57I9#yiG236ht%vm4mP zYX8=}FhZ`4O)IPyERnPD1s@N7L~wNx1T})C!A1Li3}rz;kLIxx&$%J)@5qJRhf+U( zrCbuY^uphHrq=9i7(TCEU9a6vrR$o0%;@J+g`8t&EFAnHzT=j#MZk=(qK|>Bo=H&5Bsc_7=B@ zr|TGb3FYKv?ENAw?`w>5q@(6mF<9n%e_m2 zIzP~2=I>}Rp4*nSI(sPOr1x^x&t@4lX8^AR5YdCf6}G@{<|H9mW~xCo9pJqQ3j@Z4 z#WO>4$?JK9rN*q|*f`$y&r3(u3j09fzJ*-r#bZSJ7A`4(@^o37vqJ$Y5~BJZ9&sPo z#pQU>pIV*n{T?6}v}m@Ygu;C~2SyCw?&kt5;9$mxaDMKWt<8Qg8xJHt!Q#z%@AzYE-M*JYcnJq$%!dgF}tavRR&{ffgvQ4!h=RRwi%}CjsDCbPp6Rd znaIP4malOzrnq?Fei7HWbc?9JcH_B?5*iPwzMrUYv6S395K~83Ao@Iy9OABXBwRe-L@kKBsWt=GYd*Fp?!%@T zCPWnG5x|lSJRH2{|334V6@+0N+A8sI80WsC_%^x4d=0p!x8an^VKJ1!FI>9|?s$67@RqLm zNxAhW$r97+7N%$BEiBhh?GwR|ynlqy=aES(bs9&StTSD|ZVxRTPF2B+SBamCU@SJV z_(l4u0XLminu~Xzx;X%;V&Mo$E+oFDkGmzLK+br727+z=ZXY8j@EiOr7hmN&t zemZg4s{9_%E*hL=DW5*r=hrXlkB=(CRZ9pB3*IZ2Mp721cXL9Z_wZ7pM`W0RxX@^^ zCFYJM^57u5Ghk~RnUohDIOMc7dEs8D0jqz?nr>=dDjL_@dP3sNYe!XQA5%bxmvYp` z0zup~(S2ljR!I1If5+MQAjoXVSWdpQa|{-y1fj;iYyK={r@}tK&dp7*vo||C3w;0o zJwg3puRt-oqp7pNJO~&Hu^$* zGgvGelTmLWy~J{-+1~)*p3^5H=Nj7wkPJ=(Eb_f7ty)noR?~preP-w+X>e11RmAECf*;*sbP-HPQ)Tqq_JiU5&7xNCuI2q$Kb{#!d+5qcOinQjQP; zmM2Qs4_obk=l3l+ImSn~Nr4+`9_t@zfl*QoAUsVyXS`wI{>0ozldY`gIL!fpbReYeOV0lF4Q}4l2U?p1RkbGS_#bzE)xa`t8 z-{V?=TV4PY)hbV|8?(`9W_iNcF?{RJCR8DQ&|R7bJ-^W-pnz9Z`tCZ)WLueTJ)zN| zJn~DFo&?sUrt4GZ*WDDD@ZT{c+$cOD^sK)fP^wU5+kO7qO2}{f9l3)zIXITaxQR4J zNe`|_FY&9_2iQVE2!J$#fAZagJ5+&EQ|fkv^b*zQkT#Wae?P=Jj-4^ZC0*Nd0nA5l@&7O@A$+mZr9 z>?Z8{@igHM@v-QbRsXz0)BSsMlgNK@J`uVQ`xe-ZkHd;l?I`SDUk@QFEjYJSRkT(C z%~Nuv@ek}AmarLB4Fu)v!3OZVEi9(CM~QxT$b-_?d#c57R?Ql54aOx9gg@@V@R(gJ zML2#%Mr1PB`#qOJ6Ee27)ZcIzcPZ;Nl>3O@VW`LIt6P_r|I$MG^CuVq9p#G}u$^EK zX5@!a9(clt{&*!AT~UNyq*}J~yJ?*2@)yWyBWqCg@Sv@hl|mxzMrDd(u_>CqY{q5T zJW2#8E<+dru&EKLSq3dI__hiW3_}8{O4K?+J);g27okFrl%+$Me=&`C0g5H?QCYUGbd)k->l{f7kZgniV!(TpjGmBSP@_ssocN%3N$5vLpU<8YW^uO#f4KE z-_>if{1MKI#(NUf0sz>H9a_EemOBT%8{X$)7wQlrGV+O1R|d1lGQUH0bZ>^E`c3$| zjS|27jd;AQR1ssCsBpn@TX>OtA_(h`J2O?+Njd(EC0ThGd8(}EpwZew(zZB6(TR-Z zk8|nyJ)Ox$!I0YvQ&~aS)#sTrJWx0CoKNB;ClKcl^_toHFKgX{E6^{1Axwn$Pl1tG zjrtZSmc;-Hx@{hL#qv+PoiKf2_noV4f~jx-9NPr5k39;6ghk#;CC1F=uw8lq9Km?M zS1lX?jbD;MOYJpwG{7D&zq4N_YTo{2O{d35fcIKp1rB{5ZP(6Eiw=kX8Bxf zofLjatcM-7f$1q76~$|PP#_X{%&+cEE3hcsI?I<%{*6K;9E)E^*TNYPtt7=t@8Lmdd8k~awre3BBG6WM;soOg9mXPqAWbh9?=~9V< ze_N%P$`7(vA2}M<8X)qcuFxN8t$n=UkL4H$V1)}Ao;szv&3d#s-Vd(;70ib=F_POaBFOo2F0rWA@XE_@KR0{GLl{bt;u9U{! zDUUOgLnrC;Bu=3fQ6Lg#GW1bWF8{HkU=h+sO8})B&pd&%9Sc`2?`4Lwt6da~M0>OV z(_(9^FjEWrSAzOQZ)3Th>(pq{BFrK8O+pbLTr}dS`a5?Nvvh&i56@+Ye-d`~4Jc@} zT`DQI%cwsBa2dTmOC3lAx;Q7$&~sbE-58gnNMNE38dNG7*Nxh$Cpr-ghBF4(uUaV| zlu{soqLbOmH3)=Yj0WgfD5(BkUr$4!!c=qsIJdVVlG+ zn6#bj(oxo#SG!f$W#?anB5(ci#tuG~!tB(KfIOV=5)d5_j8<}-NsXsE9Bld^ zYMH;tgEj+5X^bpd>BwZX19=e1q_YVsuW4lOtJCY2$P1tMIwcZlH)(dio zhz1XLINJq<5+Iu@J^NDFasKc5IbW@dz~SL(h}JF|YyeFC#^w?;5~YKMfzt315Bd$x zi63!*BN;?i`WFm;ABY zQ(i=Wyva^&WrQJ~y)3m)W-I8B%+gnFWF>d=rjKULQkt!vW!XEafrW|@lv<3YSo*e# zlgO&_Ds}lovO%jn9J&-n0W zv`$!DU(2vA^KK`N+Lacd!BLuyRXx5bxbAhRwR5c(`=uG4wd?V+?_kjTW|h18o46z-jNalQu7Uxe;O_gQg%~!F z$OAblh$7&Fb+Qir$RcV*&H_gp#c}FR#+EwjsjmBTOXuf)4kBpGKXrtn8N`Th>z77{ z7~FQ!Pb*c(ADi6prIwdz>k*%GxB%^_L^h}mqD8-7G6bVlWXK#=+MxUo?aNp)p}9!f7A5_6&GLI1B;(AZm`~AfsFi(;F2HVP9-3`*+-JQ}P2+|EACEb#Oz<2Tf{@;ukE^Zh-*I=&~{Gzo7|w&z{;SMuZzZiOS#m19E?_gXwmN@>3q9Awfd3`s45X z&9fmlw%gz=MHH3-6_oI_pt3x~*pNvnqYNsBvA{i#A1$_RH8L%>DxI$A+z21!5`n=W zPyqpiRSboo9;Atn=n6vH1nhYLK!Z_?)*BEL^fhhJFP`MIoQg(TDYA+Y)cglhgWO>o z!QmM~yb)jI5u^U|d}SmJiSAIXoR7tiDL)>7#HkJW>0K(zLGDhF6P~TJ7X5-EO1iuV88&=H(I0hO#h5 zF|h_pkf=5!n&L$>be#;y>r?*J4Yy)l4$B3V;^Qw1>vTLlNqfzq!D^rXD}AhDSRrqr z_6Np$mXRP+E^>WsyKQw$#(>M&7To}AwsbDgdU{F>&xlaPbPZ$>`Rp$$@Ah2Uh&WciiLQ6M^_t z0GU5BVOTgU9dMVTO9()QlKkPtgt-YaV<}iSua6epY)T{UZH&k5Ud>P4g2RLxZaM;I^D(QjS|?uO_O$ zc)=l}v@_*4^V-;D)$2S(sQaO>3P`jSG!1vDKzR{(p)8n^psEb{?#`^LDnj|Co~btq zEI5W?2|g&f-F~c_Q$kCrCAAlAgdU)}h8+SAkpv~|hTlyW@DXC;SPtv3DqMeLuwK3S zD*Xy7bR;j(0>u)Viw7w=4p2VMOrTbZn^XBm-$wiIXBJ3mB(PUPef3JI&0hGI>)q@) z!&pBEJrJ`EKqgGKMBp0nEK^Fv2#-rUpPEvX`7CQ-K;qI7PU&p%OBnZ&9mpZX-m9;8 zD8MsAV6_{woY4JOE!cnL=jR6<+I`u*XggW(f+THX;&KfoK+)5bnySG2&~;O*VHL9` zMh@l$6&R{p@`eYRlCO&Vkz`S$gj^(S+Qi`Jb67wL(pFN;Kwn&?{^+Zy{m{S!X z3)@aFnWq@%Tm5oXk&-xZq!pA#8iFix0G>}(owGXID@Y@Ok2{Hohtck!(aB1)OW&9M zz3xr+xKDXxUr+2RNam8TpzO;=MViu_GqP%q0{(=J_!Qpg*RSZeM|!`ZC7G zJ>chS31U4#oScV!H2BFr0&B93csKn8TM#IZf~KA19l6Z~aDgEtTPS{z$6W)NE-XCa zAq*AH*>jj^*Qi#P0nrobP|$2h?=&t)_Msr~z3vw_`W1#D34ivQ>Ko|-x<&y2F*EY`zL@Z?xQ!b=&Y!!YSO8KgxAm3FO00HqNCT?nCEsL@-+ zXs?6di|z!uTQcvBJ#|E=2?Dy^mLy3On&amdW{LGVFY=TH`z{oLV=SW(a(nhiyUY0J zm+Qdhv%P(MI3fT|ng9Ya;^8!L0iF^f=rDlgn8R+mxofh49IWa{(CA9Vrc^lb&t_}< za755UQl{YZzB_a8tU!iRZxWl3F0Mh04rcn|t-QOt8y)lJgM4}k_pBwFRPK(+b|a($ zShc>JwlRuAo(qR^{r%6!bs|##T6%998M?_2I|Ii;C@$rD0_7)<_X?4x0X8PrSc4-7 z>`MIG`i^RpTFt2s5`^dyZd8}?rD+>W?lUirw!QrZ(IKRag8`N z%C&(lVD&nzlmLv+%gnNmI}u5!%D|2iv$+N9+LC1zp|T;ejk_k}8X?WFu#jgO5l~`( zM%GeZbfKk;#kAJ~-Vtn|wp?@pi4~@Q#ymlU{k+^P`*(IZ=!~oc(O~If5n$^dM&j%K zmZi~TI5v+aKas}*=LuuC6kG$JM8<23zOYBI2$2=a83n!y_yKfh2xBArFuRJ?;G1aK`u84H`qe^x#bn!xVA|FMnLiPu`A6z5FTCTkDWyhlc>`_ur!>mhjO|v*a7TrXsuMo_Gplq@BoLFup@F4p7(c##7koM;<@qmmxH73 zUh;l>GLJl38lgXwrDUWrmXsEyq)3ZswZ(VGiOyfmi$~WwwaxNJO-FmJzml6s->oKG ztGlN#j+F#4jE$BchGQ|R1SBCUMvx0(L8OY(`wWeTk#D{HoPF?Htv$_nRMFuLeR>R@ zJxe+d)#s}ZJ8pShx}E%^jkPEp$^&r6Wy@CK=+(Veex0yk=(;zo%y6z$KY!yWMN z_@_cnnhQCnLr>v`9Q0Z}4HSeTDH9~O$U}`FBGC5s`{gE^wq=(@vXfC>US2?J5@MMV z-ax8ePi?z${n1>V-SK>i0udS@HG!n0gSTnbt&5(nK2ni*6(i)+)xCzw0&+5QYvo@#g12SUkTTqsK zN1qG9aOAI-8g`IeXJ&j(_Ix{@`_Qf6nF9)yH@jyxcKLg!)80N-R>9CaXmZ!%ZGcD>t&>8D%a>`{iu)#-O; z9~6JMFQ{9onrt)QVVOgv$eXR`JFu$q%&6k6+2~j5nf3NMLsyTA7QVvt795~OICcAeRl1{tCwMH(t|sQ=|TmnDwj!jn_w z5oi0EPwP!l`0OE11bBc2jqzA4vM~O=t#MzA1diAVM8V8U^;{iB`yV^^0Eav~f2BqA zmhCwTx|;9WI6U!W#W+f9QS*cBh3$1l1R}NWQ+>$r3_ykM3Zu1iSO4{EbVvwXawQ6x zB3MVONIk(ATn<~o4Wz_x-U+19pPyP;__ANcJ)TC!!K~`2(b~XtjI+sV5;VdDH2G78y75950Qmg(? zn$_P!ZBppHJx{(x7HGwg~Ny)fu=w*DVR-f(;0)!m=&PZ!doiL_GSip&uo1M{|-gC=Es z(_8dK7qw-CR8PR4;%5IydR;TTc~4ASw}Ap(W@*g8z))1v^K|b4*&BFF$bM9`%6!;k z7JSuPlN?CNgPTf4gGsMBy@kziXw$ILWbD0)8tbZsf7FiNlSwf0?YeY?_zM?BW8_Yy#W`|>?sLJ4W+=0P1o-(dgl?-@+^Qy z@mBU(4?BCX*V6#%OixJ4-F^6WAQLV!WTJnD&SmMFXQD`CdA1qV7h6_h z9$4J6HJ46%-_@B=ivhZZ>Y~==A#P(sG)PeI5KFByb=!mYfV5rD^oVwS6+V7-;rz!BWGm2r` zoD1y=e+|=tTGQ7EyFhGWXq>rSpS(9cx3Mz(D{wxmaJ1TA<7z6TFo)AxR_G#LS-z|_ zq>m6NOn=na?6SWUX)VjFg(CQIKO0P=beK|KsfA+fcKs;nl@5!;-62w99j9T*ubo`M zvqrM~1F}!M3IcoC<(ji)sRmF{R4dg!u@OS>ZKO~_0yj(;@uKLS_4W0?&CDpP_(vyU z0bY@vg+=HHBKVTb3MX7w;%_!4Bt{`NG5=M?!{e#Dwzf7_q~N&=FDR%F*@v)&cHWX6 zys865SYe?bIToaJ1s0sgM;X$^zrja(-kz=v^FY~LwFeo^Ddsc#UBmkOVyHoV*;mzl zYY5lOMcA#Gfom%tNo&^{Pi6hRJjjJNBTXgouT&PtziO)BY=7NsJLZXCKj2OHrg_{| zL87(%j+lk9Z0&~T+hd#^Cz?_41P%QIF4r&=6+O&UWgDdoKaHDe(9&z6jFiDJFOj{^h;nKUJe|{G zzyt1w2#=Th>mZxQWd=>@V~qG6gc%gIG!Ce(<1sKf%q0f5vg)gW+1s|KU1N^5D{ zgNZRoKu8YKMESCG=nwt9+ym)>YUb*dYA>Z97aDi$$LQ0g7CErTm&-&?q~vBPhs(7B zt=Lm}$S~J$`>46+s^UXL`nn%)R^u!ey(EmZnyGTUo@gKlGx!k?!=?!8ieZLgQ5=)j zbn_r0cxH~rdVz0PbAb5KSIs|95BJHed-xFPsNyxALp$|gvv<@xa?$JBS29bM*j=0( zcLk3>ub7%TC#!2_PaCWsiMH%tS?+ipLJLiQ^GV6*{P4|Kuw&P!VR_qfi=aI5QI;HB zt4qDVzj1fFrMRomG^!6)x;~#idV{`Q; zjo9wRLtJY%c(P7j#P@<)FfsZB5~)7AbC7N*OW~`M%K93 z>8B5)DfH3m7f91Gf?O5zbo9juNeLD66}DRHaQF<;ysrb^&EIeCe@TVFN^*0OCJH|` zKqz@K7>0kti)0hSG|w0wyB09=AT<4S)pfo!V`tz*uCt&gCM!~qP zew4eL_sk&??hGH^L;Hha77+|sat3P*9=kg2i67!5JR@}(;$npf=w^nJv>K+mEQtN+ zJA_%`r%`(zh{7oOJ5#?Oe6t@U3bS{e>52DTyGRq$#NK@Pqd&(84>#0w!s$1O zGyE9ZVgGjJ>!RzUwgp1b!R}qk%Rz-XpeHNcyWb}>EdLR@PL?8N2Hn@#cV10H&1W3} zQ);Y%a?@tM#1b*|XzxZ2nwPL$Eh*!tU7QbY7Km3yR_EDC9HgFPL7lN=1esDmwUw_} z*ZO%~KPN4XYdmae8a)&dLufuR&2y8RH1Q+G2%0HR;!>93khTJ`j*(*1K$T`~^>yp) zm5P9NH4Y`bZRB(I*ZxvUX6VP^aDEJd43W7VMO|= zy40S}`5%Tj9}<2L=CTbZP3l;d0rF!&3zeTxhdtFZ@ov{#q&VDOS%&~zPg~YUKL@1n zoCj!*zd@vkG>P9ao=;weoz+^o#~Q%UhJKjMs(MQixZ!?GPA*FE?4M?%$^ry;`eJ+7 zC}S77S7b8o&4IQvTv@o4O5Hf(ktPc?MX+Z5?EQp!qt=YI79JiR4i7l^fxMYduh6wP zXAcP?t(&M27<(i7<(97`5x32MA#p;yiK<+(p4bN zvJ=N`Y|W=*Y5G>LHl~y*D@?9R4im*5%jD@T!t{pmfyK9ufS3-n1^Qx(TkVolz1n(9 zrKa}hxqn^JTT5{*qw6bN3nc``NJ3y^O4;JeNh*glBQS~}&d&TH4?fE9NX2?YS+N4<~4n z(@V>Ra&nPN-`-hm`es00mepV}F2|T6O78s+jec0}lm>KY|IN+KQ9udkRIA5eWX0dd zDC18?H<0xI)?=kwm@S)v@-GtzdHau8hFKK*p$r9aZxdX6REbcXzUMLsEdD5-@mXOX z=pIJ)E(hDYpR(;7?ngDcm8Havf3_!PKso3x4m~|Slw0N*Gk&7TNXzB-QV&1@*e;F> z+%#r|E|Y}rY5{^<=uwA=pyn^|#R{&4`V}o*0m{BI4MeujD^bDH9qPL1s%Gf2Gtf7Kbrq06Ar(_T z{ck~T#ryAQLUh00ZK>*^;Yon)<$)OTe!yGVo_ko^I3vre1v!>|*3Q|($Lp)y#M-qL zP~||c-y*dcO7`6p9oK!IM;RL%8~MaG=<)a8zpq$Ru>Qrx@4k%fNG?_%pPki?Jp#jj zFg6ukAdBpiT{g0-o%V6yw>OwZl9qF>4sDjN#2!n_${MWE>zo2p7?Xm}UquYLK=57| zjr70^3Se9x4*mfR>#&1`ySt`id6@0$ApGJxJ7ZS~Wg3b(-4x5E22Oe6mAo0O zY1>DQQiqC?hlJbBN$N%y3EI_}6t=c1<%tqOG%6QO5NvDfQK8O%(pBt0Lwdj8lE3E* z_?dDPzxIdjQ|r&zKI^5@#r}`YfKai2R2K2TH{FuO=^5`D0DBM5N0{`3QF);9N`U658R&4;Uj-Vz z?&VbKbX>`W39ih^HGo$PNS7khWD?etdL;>M98Mr$u)_;Yx}aS;|EPV|dEISiZlIlQ z8O6al`{O2aZCE|!m$QlZS%txx@`mBeJI@h|F%Oi_4We^~*z z$~`*B03@Z3tJOcfy!2vxVEtQE=|rEKkE%ENjxizaaNmX^iQ_W+w-(fmjyJW#E!B&? z2a~;E(sU28loUTzu^OI5w(y%a4tckLozcJ2nw(QtLI-Pa`Rta&|9T!I5s2^xAbrgR z9wbjF2Flv~ojql!upo6l4>tuz9ibTgqy?m(b_Q6YdCFlX0vfr{w~O7&$r9HR7eQw!XeNU2;Kpw?IaE zI%c|TsB^Xy72)qok1QS+WN@wngNDU8lc9RT&;Y;>5G?9Cz4BiFTxKwhs+ey!*0F{d z#*|{2QGzwqWcvmI{p}#=(!?<^f$AqbTy!pl()p=(Yl|GPIIJ8TaAdFm|2+8F?nJJN zi3@BBz<2%b?+*kGl~zw1NgHAUwGVCpqQQ7h$o#o} zf2PjVJmHDsOTBVH!G6)D`AihAX?kI{V(FkG_wKrqh=k*)Y*MBvpRQRjFin;MmMj41srE6fVkIxLMrj%`b#?=$BVr2hwu zH}ulNLK{Hu_bs9km%m$2L0UXPEt_)M0C?mF+26%a?Npvp+DM^Hp<2Ur8@h9se8rae z)*2gu=vJ94wCxlWmo5tp?N-PFEFj4VZ-7*GvkDhcG40;qHJ6C2KJsks2W`;Wd) z@@`{%eouVj5)$AfEmNf{Ct3%<(|JG2{?U<2UJ%nmuTV%Vl4eS=zI8T&kD@k5Q0$?q zW=aUcTX&&)nyZ+jX4-rCKLIQ!LG!}tB5Z7I1w3XPxoWE|N3iTJi|AtwhgFiq!%7d` z`oYw~u)>BXOZD4nu|+Oe-fRLc8g9BgJn{XTyZ^q@v{ zBKolYG;p^q_~gX*Eb^)dL!`IfmMiwvYD<&GN#n|1vxj*8@9mKb+JEC=0zrPaXMQl` zKD^&rkH6*q+kAAt*+*J>T%>q^kF4p#e?I!|uCjryJSbP2x8`m3&-W(XB$T9LpjvR? zj+qm!BYGnQHyq1{?ezc}eKd4*uVUrzpJXQEcZ9}I4N!(fs%s{t1ok>Q{smZO48{^K z+oW7mix#$A|Lo9YsHwx>F?G?Ip+N~;BqM)O3rK2fx~$914#J@GDI%y=l}5GGDdr!k z?$aQq>aj~tg6t16*jPl)9TWqP@(0RLh87mhCQ@gL^ApCixP;^*z1>lM*^mIOK z>q>E^=Ygi@nXd__^e0~2a)YVUq!8A7{~=bz-+`hpYMivqqyCz%BVTQLw0OGa&g{(t z1yZ+;u&4Wnjp$9==c8K|K4%Kw&Faq@s=DwL?%r&0h`McoJSpB@i-OV7V{V#q?HoAc{mD-*3oYYU9n_ob{x8 znNs&$a0vV#Ys3ai$990@kKFzDWE%omN9VCibsFsM?w0=ixfT%q<5T=W%de)=usqq; zTf{?B&W~!yDy>xaJ*sMy^7lG(_Q(*S>5`?%f2>DTVzH%1gZX`iF<=6cgc^h<%fQ4` zWB08X}~ifR2d?4k}t?`#QaHdG#qr_v>t?qV|mK;S8`Z79?qLxAIj)3v40= z!mRaM0M%|a`~bdPJF$Nqj1u-40{=q5%_kSrVAA@FAO_U^{J5O-XI&J`0#Z89t2`FL z2?K#vMNJAdEL-q4mwvwDh=JEh^YGR`D5zd11rnG#MCxryCx1$wEC%JwObd-AENj_` z#SDM9)xSYJXInK;c*Gs7?DM)mPl@r5R@TGunf_e3tC64?DWApwdKyTCL%a`8%38x$%6z z)A}(y^PIQmKKEhOfNevxjpZ5-=W#0sEU?=t;zP%&#%c?A72!VPJOFwi5^Ri@!;#7eIW$=~WcB7?Xx~ z?=~s$Pz6ns<9SGXeH#FSF!vF@I`=4;eX%l-<+ZbRVPY8X+1EthqgG$~NP+p2U^_<7 ztNm%7{4c+L>4U<7>~VuF9hH@%Sh*bWG*6YTc$D8}wL~O8PnthXtj{pS7Wgs7;)qn8 z$M4`PZTk>*}*Y?6-bx=sPL5-@c&aeICR4uVfL|kxKQwEOx+(Yr!5_$K)XS<1^YJujG_ZI-5C40e;=Y58;c4#A~e5}hBnrZ@TnD5 zS!6SHd(kz)t4S@zSr$}d`@mH*fAWl@Kj!yAUK7dODXFQ+-e52qIm^&21bi__&&}09 zMJ8@D@!@`o^NKZvgErqBwTxKY1#6dPLP9Um67gxo9anstvANflNG2r`msmMrk z(Q?wSCb}hk2;A9PYeO^J>IHM-9h$&5uQbr(4R`1d0qAmGe` zMoR*}12-oLdsrSy{;ja`(-%ta`arDk`mWvEP7l{1ZR|_CTT9+375tWEyR8+e#5Zc+ z&K+T?I;LHzOY2bt{0e^MSJ+sdkB%3nG0RM@Un7J&f7+ zfY<70#C!0!qkystT%;9{G~4{0_POv^P;&&B8Es~TpLC&cDr1tTXX5tV7;?%bD9l8_ zqO26%2i5H#q;_32q46Bm7lPIl!oeMS-Am-V_fsIl@2DeLDPY`n!UM#crO;i+E7RS^ z&AW==FM)1|`f;Pc8H;#I6QKTo{;)+36^OX+?(J!``R;Rk@OIRcZB!ZulO;F{m;TnV zr~{;vmnHcFSEdE4Xgf*SHkSQz60oi<`T>u1$_TARCIzM9~m6~wcSHpsr`xzfdy8szqBfoQq_^oe3| zQ~wbO`bh`}n=n;k{_?UGoFpiCXC5M*9>6@?j2!!wcWO9rjYXS@E4Bt_KhDW=V^|<* zFOU|MeR+j+Ms)VIMg~(KR#X%;{Or8EozPuUrL#qDS$2s9oxb*fuyVl!>`BcL=Umy8 z3v*MHC|;D9xuM~PO{Y(T6D0fSZ?%H2|jIi&G6n3iuD z$B|qRlswb52u)E$UfSz$Y*=eEHzvSpX70PN#x}0WmiBh8GaUQq*iiz_xkik)9a{{Iui|D84;D+U!R1wLIrm_?vH;h4EsN9I^ zbI95NLh1HwUbh^i+u?m@O7q_1h+1ESUM%HucIfmZKT1QfpNVsvF7(C_A#JZi0^fC) z-hx;8KbCBXJDdMmAvu^wy<5T2gQc7rEpRxD8SMHOVhVF0^80gdZqIY}T_!pS1Ql}v zj&nWz&m$yM$qDW6Vd8q<(xBV+^Vi$BfPWm4F*YFvVG=rUs#5d z_-=Ii+%TQA;W<F>(m$^t$V=rNabe%q%-?hK>`U&JFGD>+;oMAz%in%qK!!6dc`0ms=SGH-L7@ zfTwG-{rFspNr&A`BjYA8UF9d7-ElNN@^XX$ zvB4O0z)?TpQb^&XH=*D&il4m^bbUH?bHgrCzf*$2{f^s4&6y{EiF}Tj)s?tEv?O7k z$4R8C%cm`~VM?19g~-+pegI|f;SdNJmt$;=u6^_tID;1^y)zs2#GdAJeB$}x~0Mq^p>`p+C2dWHc|MGI$tDBpd zt1I@%A@YN<%RY5F+y>iB@E<&Ue6T@2Y2noyTf+1TpIDFND5ey9+Q!BDUx+C&rB>J1 zvua4UmzkLoL*e36i7OC!V%B+D(=|&v)9H6dOz`AZ`mK5#E|esSuc8r;w*^+IwaUHO zN1G{;k*qQ$W3^OiYW78Wjc;rD&c?MXlHj)eWT1#CXWh;qY_l`~y|fjgF;P)ibyyB!C6>@FI|}U z`gWtmL-HJNfO`f&9>82&VPWCmLQzNE?(g4}P`#&Xol>dM7N6ug!28g~FVl<~nnFC7 z`cUzn${7btZWhiZ9~@X-FTdc>p6>+((aAxLGPk;lvJu!r&pd!v`lEuBTn)Ov3Ryr{ zi8Sa-RUMA#JPatyFE1}${rsN4wE4>Z+y1*{5(gtWUx)q$91-=SMU4lOtCrR#3)V94 za(VRpJKO|}&9$7RG7EH024mmr8h79jbKq(W+s?T(-uwwTg1Vu6Is=x$DZtKgwZo!6 z-S+kqq9_~1)!x$p$p-$@+9cEgv3)4QruwMuPZLgM8A@nnXImnv|9IJ~FUVu?v3vtO zNZGC5J<7JZ90A{642l6^(S-M2T|YmzF3ic1x2YDX?MZeWe;m`8?<$s z0`ZD}6d7Vc-Y8lOSB}bQioVa5$L?7wb}};)Kbbt3EuCkTs1E{*ZHCqV1FOl%?WSbYB5^Nb21Wi}c+AuY4i5Q3aNk11^B@EV}^3cEV< z23m3SmmU|*QOH+Ex@PhJ2Zu7{B6^d^`@QY&7g=A3MAq#1STQ6Mg>KRKgZo{n|vHG7n?8Oz{2UbFq( z+|Z*1mGG(A?pq3o{dYotXYBL{?2T{-4_i0cAV~CPs&9RXj8Vq7cf%#&p-IgTF-8RL z$Moy{cO!Z<_!DFt9dGp8S42tlC_mM_izkO-`L7zIE~4x`7`mLy7B1iFXOSBrput6D z({)>O8A~yhqAd>Bw5e&^bo%wWKmC`RGDmQonJ=|`gy*v98}e!S7S%S(&y zi8BC1<4w%z3EHfhL7;`?N<|R!tE9Lka&vOjS3v-LCDu66>(|PpvHCaDRl*WY$0i(I zKSCA5y3YZd0$eZkv?QGHlT=TD#%Tu7cSkGP85zowOg0pPiI5Sw^rqfEj)DU&j3^C)jFg8V*(IZu)^DcJXZ^1M^wmXLO!gY*0+ow3jv@| z5NZ1?C=)K%r#%z5(sEaZ3KHux)(jG>5F*Eji*Qrp@lvd%h6}KLBF7>6O_4&n6+Oc- zTs3VgcBR==DFzoV`+qjQSP+I;UG8bUH);h4V{KE>H}p+HUZ-W~0Zh~GhkRG~j}$5Q z`B9!*nySKWtV_37*ECpi|0!m7*nLtUGk3fBijpdWPPryNks$34IKxGfk`tQp+fR(- z){DcLV0#`&6v>L#)1`S}&R0wYrOu`<_G}ZS65`yi1M1s-|L=PkV6O1xr~?E_0-3vV zISz2E%*f4^C|1T4K?Krp^4!T;Fr&f3&;N=H7O;PCWWiW7e2%{n0b0AtgE^k$Q-!Qr z#hJJ6FiboOGO7Iwx?l{+(peXT6OSCj-u_!3Ai079 zi3;Fo5UvtasQ}2tXQoM7!$4!OsQj)yWgsm@`vy4xBwgkKqt!Jvf0gz>npm5vabVH z#c!kEG`$aFS$MPQd%EXab6P|Ys${OTf>_4oeaB+=_2OGcP$Y8Pelrum4yB8+z-L4T z;tUyM)*LD0U^XyB1!K(IK6bcX{XwHGE*NdAL0P{AL`(7PL5C;l087!?L(=z8S-MPa ziXz1Dwdv{e$^;@2!yz>5Ze~)ozevVFZ&vhlW0t8F(!KN8B zUQqDErvnH0xngExc6Z66a33%V+|O#qqhD3BeZY!;xzF4QLy|TJ4A2ekQcDjL_T&Sx zPk@s21)ZE%F8>sQMhKgS<{xe)C3;172mw0XE0;y5#|<~8N5nwGkZpv$<_;z}7*gFs zOjszb6tPgFvPjs;%Q-iQA`K28MrX=5(sFZ$0WjLITm|Hi&Zj@yU-RMY9`p0_Qx*r? zISPw{GlZU4z*`dvcbW|-dta2QU@5bcvM5sI6>LhA-1Q<{4H_IM)nQqxvIk+N0O?Yq zej^*u%Ymsjmt3gccBj2IDsfa))UwIcl$1k^-2V}Wj_s%bLrg2dfbKq1!GIm?C+iT0 zQ!Gq9mol-&f7H}lr3-5X z(Jgp7o7F(u#hix!ux|Bgl@r%HVaRNiT!gFMrJ4H^-%OznX407ET0P%eQn&dBNg031 z|5o}AVZh$NF-dRx`}F{lyZYv_yq94$HCV{{ZLvPEvMJImSAy#LM1dHHE0T$-jz~rm zp7bQaD5aG`ic?o*q96QRyX4k27v!YpyLkO>00H25xqOq@IeSVpwWQ!K1XrnY`JAN~ zPL$Y|E`RQ1;_1RPpkHH%_#ktekWRNVb00xKGa*G^zIrO5!{g1#z6lh+# zVqtC)UX7_|47lzb_rnxXrHGaHelW=e!KM{mu^I!dp&)fmmcidDdn zXFt4OfY7citN-^3ir>Nq_QFI%5pkVovq*g~Hd1AQ*~qZ2p$*o?6_JiO4{+7{9yZ}= zNJ=InIsqMRQ+ELR$IX}j8_j#5*IfsJR)T+HpySuej z<2%zn`h9Kpy%iki)zy_^5-sL@si6prPGaagnmPuQP@}3|3}YC&D`G=h$C$GhAR`E= zn(9U5WdnO}@~8d4t38Np*zoM;kK=x`?u%w>|9=n~aY~kmR2a?rg#rhKr0vzA(;Jwf zG8AFGQ;3zxwTx8emNG0e6Z}4w8@FU-X;1RW>-Zd$!q13Kvl188rE&8yL)oDdY3`SA z?1p)N-5lK&x;^6gZZG=cxpjFqaGE{5{iir5C*=BI}NVMr~}_K6iC})MP&uJ@K)@^MfP#=44f44{ZfV2?rXgaGR-qR9XD4WEpcD~y4Aaj>&@BqhmUh^CnmH~$!7!5w62Rog!&B8=# z1!G{p+U}0_>J?@pKERuz0ks;*6D&>Z09>nRC}Ld;Z1c#qt^0ZL=BvUBSU|1a+`$$8 zGHfXZnuuHvQrE6qp5A3ci1lAWRIy^1Jv_&hZ%4H%hHbxF=Q`?3X_8Wrn}k?Kg0WQRk`3 zj5{~tkVQl-nlm;nDl4zv1D{g(c#t0bl-uvXokQ`PyYJ@2nYEc-8;X7lmVsxwWS?}?_OGz_Pn&?$M5>{o<1o$@-Fge64k~(zb04mc zFq&z8uR-HjZBK-VP%oTZCyvnuLhhcq;+Fu?mPr`v9g zFL0UOGdxW}GNALzxfGhgrt_hHP86Rd;_Ufpy|@1usi-yjV~3ip)fAbvt(r!h9U|5L z*fnFL;Cq}2NcZ)eiao#$0FB!Np(`!K#KR*UbpW!OYrnUTFr2MPgR@l8ghsf9 zUAVY*j&#k3E`sQuQz~C(MDR%~<#!Y_ERT?A=zkhiNj;zIc^Sx8yoMqUDqh$z_Dz|M zcJpqe-=3K65qV}tf1Eo-MDM^e@;5EjKOVX#t%-c4BX5TiUq5y zhrg8%3*IC8_o72kH|Pzjw0f6a`AkWgT`6mp1wt2n&N4|;Cwk?%Noj>Cp%VNtSQt^t zz0vyXl(M;FMt^)@@fc6O8!UZBi{rbpi$>ku@CdMK>@M3R<-(7aG}F(LpPm4i>7t9HYP* zp|G;=FhQ@YJTT!{ul`^FO{xP?gRKs~?xG7bAZOs;EqzzkiEULwP=*M#>xSB{s+Oxl z=HA}%#sbFq;|rQa1`F^+s5v^qwrXHc35W~8X)lxMek#LIh1vUOxvg)`XfE|pZgg69Tk5x1v-?n zl+%CzkEE*%i)vfLLk}U{T~g8|CEd~>ASK=1&CuNq($bBzN^?NEK~O0X1QC$#yTvGG=?zn#;r=&asX~Ts-;%l~Pay1V|q91>aLr^8>YAx~s*KmM- zllE=O)jDx2zhtUt_U(z41jQ&*Ph2i^YxOBzzY zVapeGpjwXn>1xBl!65|=1vv)&v~tb*bx6-VNpOMcAxW@#z3z|b_yk6Q8Q2b_Db*sfT&f{HKMy+n|Jn!M<|-U#huo}HB|b_m=fue(&)2oxXVKg=LZZw> znK;E(9R7-bX`zOzoKlCzpWpSN&D~#RE70toiDdD_=3?lX_*t=Lj{~*#7hGvYV;TBD zG{~^`%u9*VKa`rf5!m{!YUEa?$Lm;3t~;>8j(x6AXW{E)Ml%!iqwP*?+2e^Lnrpff z7!3xdc&c>B0Muw^90c?TjJ!51hFd~HT^dUH!vFu_MRQU(^Zd(gNlxVeW%T|%x-kp=7jHYlZ5;Et>0JQZ-N5MJPB7{h@@!gXpgT$ z#1oKkf+*!5y?vd#x<+2q^4hF^V*dY~{{R#n zkgOw~Qg><)mnutm&d6{b*=Eq3`fJiMAjTcH$Ht8EtGZKGHvC{1+o(!Z4IOimNsJTW z7y+pR0H|<|2OwzmN0Ic;Gk14lAb1p=Zb8&FG`9qXGzh~*92^`(HsYSH&@%#=TO?~o6#2hW`=4f<+2J@w$>o{L% z5G0hFf3vP0-)+G>Ku3~AfCY=)MA{4}MJ1}ym@G1}Al$UDer?+&E*8UCYZdu}GuVuG z74i31qlIY|$@sZ$$d={rFA(;riilTd;UYtHjk!;jEuNC{)TDYJC+)qA! z^zV4>Amdl7dOc*pE7vk6bP?`%ojX~E;2_Dun&-C~HHRP}b+@tP%kS;U5jt+%b!z@X z>-dmY7&$eu@krKWiW>dUXB^@to)5$ayS;_GtR2ZJOl55NXMz5Hey_=NWdZwzK`#wF zy+De<8T(rERe#qDJsnvxq6)jMhufo(7nfgU5*cyw%tl&=(=)U{>D||m$9wze0sle~ z*Ki!#nyb%fU7ejQ-iNE@9}QlXBKt;KzEo=L~rin1Y0jxXRF zhCosGR|S%IyIK0ZG@ZcK+#?^uD*lSwK7;h<8j9|?LMH?7H?O{2x@y8$FHr;Khns|#4$9xhUa;6rzRdy7H4r3fP!Jr@XoBHB`c@-~l&qw;=1He!P z@4WNi3yE7-G!~*h(uj_(S7Pno2yZZiJ3`^37}!w&f5aF80uyNpggsEN0}H_&flkLQDq73W)_E2#3Z!FW zyQjR_ZE&_ZB(Cm-dXLG@F0BVD4NpvDvR*qJKYuu&LDH9R=*8hZX6U7;+uE0M`l_7{ zHx`&!n~_2T(PK=+&KDaaWBtT*zfgi#y4;A9*?9R?In5^0Zz6L1yIgG9Vy5S`!o7~j z8hhq>AKx+w(^7oW&jOLz!JQ55z%&X#a%1sv5fVp*F#{sd{tSZL*fQyf=Nak2R?_cA z3G{!ScUNu@jl5KUxN4+jDojT?79fH6(i_K{gFqy!(bb!QFY5ifm=@aPbM&1klf=mw zqoB_5H8Iv;-}g@etZ^0G9$TN8i|Ry$3N+pJ7g*)U%rZ4UiA9JiUwU~N>-iQkdj`zm zzOF%HrySATVbJu_6#v||9#+zqlJc6)am{` zHVoXZxOg>-_QnqrPJB`@4^KK|;3%Yvfajc(>#Df^X%G$E(+Bqk7@$5}Ne%;riH=`% zQfCwS9za`l6?%V!Qvz9!_!VH{K}FpL5c^{o0VB^l!%FV5u-RhsW__D3{Dv|$<wE@^-H=4D2T#*-{`+sYXZF0^Rw|SL9izIL%-jcZ;(<#6`5F-h5!I{ zZ9H!(M``+>0SrZeuJend^itiBHHCVCA?K4W{Z&E|zRf==?z4Euu6XBcocq^_ZZFcf z=dt5nj^~I!*UNufFRkrFE;h4=6;#FmGYsYKwqan4O_{RM6!D;x8Qc~Uy=VQQg&iij z#I9u#NBg$*q4M!BGX%M%Ye8h$3h|#%N~zU7SrzD{h+U80zj@Lh=KCi%0nZ53IzN z;Cg#loNm36Au3xb#RgTAli}eHAdxtq8eZQfg{l z68I3X!YQZ6G`Ztm^Swf=nuYN5=|>`6b}i){oq;2OYZaUwmx2eJWhJGo1jv4{M~sff z@Q8^8=HOIrE9nSzU8hR~K_!WqT%`)0#WI?|j9Kj$6tPktYJT(0Flq^z!$2r13leXQ zkk#3jq}v}ciQMGmUA$?2>2)cfb|;C*N-?}e$;LVSw|3X<3T8CEN$P{H-+j^JebWRcQRLD`emtOaWGKtFMy zPYli~QKtJ6ZTj%$BZ-^>mgwI(?H1z;*pFt%HMrxcj z$$6j3y0~yzy?_05wVw)Lz)b0M6=mR%E74~M$=raI1?&lc0xp9<96A<1ZZ_=ra~pd+ zzz^IJVhbIuwU0&UPNnfv>wszFAEgxdXDjb3rLaF@AJ*F*EEb>>O54+IS+M;30TI}| zf7!|Tm~-HbSQ`l$eA9iaMkiuA+u$%-UaX!f8_+j4EKYNn@pGZU3<*+lwy1jMCpKZ42Ro(AFv9k(6W zWVsIdCorxf5tyAYp}hO82U&<<*q*5b+bS@I>GP^;E3!u7N;mu$X8U6d&q}EdMMHL& zzr;?nX(|#`NO7rKpTlP7vCN;y$P8B(qspig5I-P5f5a{3HDTSW=GN8-uw_B%;Eg&! zr3oiBn)TlSot3MJGbt)aH%bC`0aZr-$_i;>Vqz+|34Hz-(IL$41-6Y<*pgN0J26P% zR)Lte&ZC}NLRx^$w>y7RX8$NGBBIPb0H~?Pq^*fuz8oMoK>H7Zf`;iJ-^MCLDm6DQ zWf{RdM1rw=YLuh0xR#5b>PpEh6m;Wx1cH3LC?zFjnaodGYtP5aih}S*6P5!H(iKY` zlwN&ZA3h0s?=&>rWc!h_?buE`7qiVHm@`XWY6AUe95rX}r=Vcd6I7Ny_1Mmb<^H<~ zBO#Nxm56a?-(hcvVBqvY(?)As(;V4o1DBsj|Ga{as`y-|xTr8J@%z~6NDCdYOZE1r-+F=qVrkqDX#caHK=Zzzk(j6c z_zV=e)_{d&bGsAJ&Vmeue^O=Lj9_jNB9mgqa!XG(5G*~}^KjlMfwW<{fT zZph@uHq9*oM1Uks$nj+?wB49u`f-y+9NiQ#bhly7n|JEp9>-4*%9VOBiI_8-u1mUemGitHe)PCT0CR?qBJ3n1&LvmxYv_s zQr;1R6K~dIg%-M>Ls+<5eYbKd#zq{kEQkOB&|h;?6U;X11}>A3kQCSxyHAAz;FkQZ-1|nwOO08%PDgRzS!x1RVp9r3$ac z9fVVDW*Iso;BEd#;Zi5#;K{fPgtGv955q<5GD<>4LnEp+_xCq&tt5(yPo~d6Vq({HC+NFLd8Dc$`d*iY&x7$UTn`;Ck*9_fn~re(EA`s=^Sr z4h2HN$A>9~7gIuEzXk$wpsG)W0(Hailk{ zYf2iG7HO-X=<%x9ynf?}+dT+B^4%3(M;~ul=y%UWWB#e7?D(ZcZm|&pxEKjMJdlm$ zPfri9US3s#-KoXGpCFja#LGyeK(|c*EFm@jMX4+52t`OFiv%7k`A}9SDH8-UUm>J#m(ug`H&y;#A8|&iq^|@CQzC3~=43mCzKX83g#r-7Z ztFNK+yfVTc58t)5kk^TW^r)?2G-7YX_~N$}dQi$jNDB`H{M7%2&nTJ?uOL7aw~KnO zI3O^q+-C9VPk;p?Q7%uzYoYaY&>}O_WZ4J{4YQ4n#unQfS9qhjB&%~7MpMP79k#aA zkKuiPEC#%0Y=$}`ZW$>|5>+-SVKf_jiUnf?AR;2}71-~Tl&g^iva_=f zkma5X!tC;{ZkBr+ek;*{^9scrqEU=un9Up9C!JTH&tt~Twv>5^|5mL%D#MkYnw+#685x=09M~>S3g#5RYasvbcAPo_{x(#sPw}fnTIY(X zTxIrirwQ?fXZp+7rp-6rtQXr(Bu%!LogzvZ>3i7vgs0bz=tB;zB2uIRPs+iX*zMMx z{)=h(_QHh$X_Z7!ZqEpukTBA$|XnMM?H?I*;u%#_q?UxKgf zGfygMAC+<&DOsQ#2q!j>ldKOJ_&0zGuIBy9-3Y_uZo-OjLLg^N!_}U`+p}|i8EnCC_0m{h?wMqat z&i?+*4%j{`UNV3y!T)We<#K?Re{P_eO$TD>62pxBJc2}a<13eCuW}O-LKE7#_Co+G zS$iLS|I`FxKV>$XJ@4W-39dKRUm()LwpYx8TtP~P<=oOX~FEWLIP!bw#V;Mig#_?5-+bH|>dTXO_Y`*!xAr@SRe;6hFrI*5q7F|lCu`%}>* z7GfdVAR);i1~&(RtNPaN<90IrE@?_=1kpB9SYzOIK7>6dD>K96A2Za-r=^Vk;W?%$ zwn9=*6I05JvMYA}r1d>0M$7_&B1g5~3W_xjzF!Eoz1J*JMP%l+p}jX7HUktLc;lu+)oY7-Z;bbkj&R`g zn*d7=M&ByF=C`%(w_0gCv0r8&Hl z;avtP4GlBr<4iRJaMx)$Vzjd@YH+<0stGgC>8q9t>%lJ^t@ z?2Y~1o@ubn>W58bISA)Ew6VVxWhG>CQ1xG#xi%?HMN z3IyWBA^z)O`n-wNCZ_YAbp7`Q7RCa)~HNOGUwBl~OIPPzSRUg!Sn^6L(b zg|S`HAk=sH;oxXZ&s$;?l6e$#qJKIN zU6SdV>feIZDq^n`>*#_V+6&k1V?j14iQo2iP=4XsAt55Hav>I1CEeqRj7+?yKJ`mPuuOeJ9Ph=`?c%q$<0kS z3g+XqEj}OXnE~~;kgQ|{h5uSH--0*OzRiB!cRMk9Flhg41^>H|w|NFb9XKyA&#+jA zxPVFvNP#L;*6BCeaJ3g63FMe}4TtJ&jMrL0)w{aC^=6Qi zDxI&s-aKzPq1t`ie%Q_E&Mp-Q#jsB^9EQU zq-l_|?IZC!#Y0`HQ(rew!A0WU_4X`i-83o!RngU1|GAL75%>NIfu{U0o1cev0tS`s z%-X`Y7eYdnDE9t@QDzImCctu)`OISxL1W%urCe($69bZQFarEQ#!2h*^Mg~l7<;i> z2+~lX{jXCjL(IDaT1tA-)&M8|7Y9rIC>3sX75ksrF;Uq(LlyzFuyqMU6@%PZz(_C; zP9y+?X1@3Z+y!$rU|9vjic$xg6_NH@d$kc~_$xK9?)alyFBQ=3SI5cu33;f6eJ8%w zSZwYx$ZV}W;O9hcKYTY^uPX}k5}a(UTmAgFz)XY64K1Z@W>qyO07=|U47!HpM7q*O z=z#>|?O6J)=^O1o@$ie{75R$gko$_`{fxa%y_&IW@m`ivG|)|&sB_#ECa#LcYm6)= zN70$HHpV=ooJSt>@I8F7TqcnnmLXN}!pP8u`Rz8OFZ%HWy^mUMLl1#*+wULa>yL*_ zt@T0}a(Y#ZMuQ0f0wn@qZQIvqE0r zrvr&ieN!~u-;sAO6q2cjL3w8LPevqCIO|9u!7;8i5ijo;=L{iwhD(V3=`P$yt%K!B zYH_zg=3q3=HrPyc(CUF%(G<+!adBzmJDwSsvJv2o19lFLQt1+yc{3C|h{i_s5-q^B zY2tmtVk}Twj!irMyu?Ha>W2vdA9)SVmY{jn=aYy+B+Kj|o%P|aUjYKuZ$}t?*Deq{ z2{mYiVz>Ur#t+Z2em36VJNM0gfRuS}{&$D5sc{{eIb%mzTWHJ*LhR4Jn)8mOEdh`I zRH{tnj}zka{0@v!s_s1K;XRX79D_i;LJiqFkyE?j&Ya~_}L<*N1x4%9Ai4+DZ z?b%(bR4PkfGj&;53?Xj+Z~u0xMFfl~W3M0#!F1D4^;D|7;>=T;Go$bPs&F!~bGI-62)|ZUxbwjA(V`uTNQ5JHEJ-Cd z#Ek{yC>o(e(onEz7J8bR!|zJe^2$mDFMKYKhdV!zJKILUz`y{14fJ?-R`WraRy%Vd zH4;DtNGw|)qEp#N+*m%Q0CxIROp}Fh2slh^0cnsNdAr2Z$OpZ>Sc%nUnGnOYaU~2r zVDhPB6m+Xt8o1=>3U5V}_YAj^auSJZ#q{LgC6HEalQI@tclc#GQ(ix)qzb_`MxYmw z*gkoa%*%L+S5vt5%yh0mPae^M<9xQ+)|33 zmH$qgCCp@KAGi4NLvl%$gPToop;ILhY?YL33c#S(E9Cq<#>Pn{51 z3eqW~59~9p)N3x>9*K0*suIh%ltEIDp=qtX1Bw5jpbIQ3;7qAO2U*vi#@VpEEQZ~F z5CPDZ3fM;Adw#_Ml3~5bqTpwWGSul-dEX37C=M8Q-htQ_QUm-_s%!0wQu~h3rTUp+ zAy0$YhL_C-K!$Aq#KFL&GrLokM-(`hL%i)ron4bMg*E$yIKk4duo73`kUkw09(@2g zF_mQbzXHu=_E{$sB(AOc_GD<&yO$U_y(BH_ldC?g?Gt`2_P%_t%`>EC*rRWYP>*15 zN}#O6k4Upef3Idc*pTEEA|V~|y#!&*EXVU>jHQ!=OTr!*TDB;I#C{|^?kG2z<% zUapNgBGmMY^+3wMZC?LqiuGv=JfQ_U_>V>o&2T!VW(=*mni}VahG#jyig#fp-(|lQ zlOy7S7-NxuIn=e%^R!dj!tuic144Kl%15LsJfsz(2oHVLpOUdQE%K4Lh`*D538_(y z@<>QD{`D|c-vTp+m!D{FYY+0pwnd#Qy)>-a1wdj@4qa2236PCIdUD4jkOF zN8=br#DjmvU|<9=yrOa}ko<}OqfG=ZMhTwu2Hdv`oMr5B08F-g|9Z^&{g5*an1TST zpQ2U?Oa)e&V*`1>eFIp@?&26=cqAuc7aXvCRi?N1=2;|eS}0~ujN@9?wAiW2QS#$e zvcwZpR%COLho`ZwyqBMoUtrN<;#<2fE1Rby;W-KUwAR1DTXyGQ@3q!iQ;YhlY5i>h zf5Fp`A~$DVL{gsQ4as4r;rz_r-P`tF^)@tA$qhf(@yrxDI|f$^e+>L7PAoczOvHx| z!u%BW0&PzNv(0rpgPpi{e60PkkB#3^qGc?o{U3=Z3&!muCH?O+Nz&HLbI=v%YqGnI zo6SfXCDrlW|KKmUyr_8D_s2L%Q)a$NNN*G;y*A6MSjb8}_@v)xUY|Yn6FRP833{F0 zGbHjphSO?X*E_8#i)o{Q41JK70tx2eW5?X0Ze0(&&ymoDpYM zFB}3)`do^op;nfw>EC|9n%IHYe#kWXA7>aptW^87xHQ+4|37XlFuvnNnXzOHUk06b zIJ=aplU}{ou2hq1jNSx(9)1al-YrCSfO{$}04~`2eVPDUr#!Q4C7{+F*BVaWS;=x3 zDP+Fqt_|a&A8!d$F5d!}+3@7`R;g`McU zZpY%7I|t{wAP|*U{6?m<7YO>4;UFmZ%vFJ>P<6;N*mgKYUDmahdTbbxoj~!4ia7^BKDy5fz3q_Y%(s{ekN*e3I%+x(ccPcGGcp z!tp=C)aH;9!|*fc^AU>Yhh~yaoA@P`YA1c2McS{o;jjNAk_V zszYP_+R>tsh|`)$$*V3q7)HGZfEn>;XI>L&e!!FLHM-px2u;nOY_Ua$k(bN&k^*U4!xNxSt!^>M0?XO2Gtgdm zd40_2^)*CGSwAW^at9wfXa_fiT-9+htrMA`jX1l+8xl`C%)j=!$D;PLP+#cJRonaP zTPBa$l~zgF-50BOb0;P=p+|%DgtQTo-k#6gEjpym90%vRJbaJCLlQf_UN$y4+#1{R zYaZC9nUPmzhB_7=DCWouO;xx~3aoKL*nmqOdAvpyU5#1-HHK0VHTLA6Y-ecSXZyG( zcVun-dh^(XTpfGJJfqQX(t-HJbQvuaS^5Gw9J`LJ-xLAUSibJ17jue;o61swDFJHG zix;{Ca|>idj%Sbshyf}>Dh!#qi z9;TTC{@9$`+|g0xd=8k~^;O_WinQ|m!2M+F>8az_<-R*LJzWOonZJ*~CGt!yftvg& zs!FyQZJ5Ni&o}(2gVexvG;Jry6|n3CEt>=!qA%Ero=o&eAGBY7dYp%}P^sqt=l&L> zrxW}9t3Jd%w!tuiZ`o=|4AdGGL8Mzdz_1#eP#`1fwwApwBier{)|ttMC8hY}3B!jS zZ~dUPlf*`e@O5DR=wDp>BfY-&=_+sbH4eq#w-tl{DX;}1d5Qdi{R=y zyp+0PEhDereSMay4QYXKrP31pn|5jwjCwF_OmP>7%K+9?j$0K|eW+2iMbzj!JO`{B zR%_mUu>uY+n*Jc~Hu`_=eR$r=i#sJ;29wi~rMB#!NMtqd1e-eAA~uzmpMP zzAZG@?gWr`d!0oq9FTZ}Kf55u4YK@!>y(JE%!qRy823^pt?lgXl{3foIH?WZ)a*l< zC@6(ofhTn-^~o6t5>WwQY{mEw6k~fl{vSv=gi#EZDv)g%N_f)(N>KFnra;LGTr^Uy zt;tRd4=w~=Z{8d(hdCjBs+zZohDw< z!iYWUqK$RcFrD+gp3x_=H<%oQ^ie>nuE){uf%GmqI`y0Ti-hmr^uWx=Zc28-yx1070vTc=pT|OK*hNq@yUiq^^EDfCMXM`_ z2Q(d0(`$A9|08Mge(!b>F1R1ITzX*!=FUR{KewZQz}H%M(7pi+ArQSCD1(BI#n-rZ zFC>bWa`C&x<#3UC7wYskk4qf%Bcu!B${RmK9Q!vMq=9|mqU=V-WBn5BMg;MW{)N%f zC4C|3RXov;EUsQRd)4~nIdB~Z>BOU~v`bo_kz2|)jC55Ci(Ty=4gP3&u}9TIaujqFE_5+~ zMGFDJD(?m_1A&>a7ZcKj$BX)W9)+PV>m4G2;f+PFD&@nC2c$;e!^Mvh8Ths)yB*MM zhSYR&5_07U)fuv2>6?hAaQWyq>t!sX{Mm{IsB*6w>K%0V%Bk;)MJAl|63n~5M`G*O zwYk)7;(n>PF|pAFiyJ8};1jLDZE}-uEPfW46SDy(t^86W&UhA6@M^`B6M4o)$qNf% z+PQz9+KnS4KJpzA73zq}Xvu9!uCPX#L?o&e)CH!F3+>E6*~8a>T?BD#8LmG8Q-S~i zvN%tWyVi~QzOphJ9A)4pNo&vpuqS*7&V&KMgPENjx-_&&9^|2feG~6=9=QyXi*}<_ zXd&Tv&#Y0lrNPovn$nOGMCUcE2cgfO^atVRT>(d*E-5zAc}4MbtBvoS-}HmDBxY3(q@~yNT&uq-iSAY9>XXd4U{@NeC95wpEZ+;AI6nc7I4m z=#z1AX>ae~5%VZMW>Ht4Tx9akD!@Yecep(PR(H#2|IKWhE&XY%>$EMjFbR%;zOeaYxIellY%l$#x z=3X?3LAVjnc4sX(S(2{C*)dQciUTxXSRNR*faJO6hm3Od3K1nB{o*|Pia~c4n_dxc z9!~udc3cCU-<`LAKCn);Bb-KPs;;2cO-qV(6DA$H9kMEw=5ZKt* zWadxO|C-e+(ILD_m$%2Se!tPUG5#h16)2$E%>}M{l2<$1 z-9CLFBO`)HU>rAl9k7_M^}CL8lDvcNWL~Kt z%a7rM0HKI4JmC(+#2PxpipxvIRry-$(564yz{~{_*dJ@`-iWo!3q87(XG-Vs z{`2*E@tAbm?Xd~#3g7pvZx=R^WpEvxs^SX&;4k>uMNl|6iCyusGk?j4qI2Ph%YD3` z5B5LovVtm&I(@-*xFTYiEE);9!s(6a-_+Z#@4Zl);L0*31y4URK?dh9y>ECNW;!24 zKKly=M6eweZZ7fLu8$%$Ah~Z_jw=;A|z?eQI43Ne#kzlL% zJpMQSoSf`<<0~=j2L>YGbG;cL;1C8*Z@>V8#|N%*@a?Yv;vXO;gcAb5M#wE75DDUn zfyL+@-1B5<`Hqu|MB3EcyfjG#E-=9ell-OKYWs5a>~qo!%yxE6P>Ygh*mbhlKcl~T5 z;*?lHM&utr%m^JvJ^#4bJo>gyI|dJOY(o=BDoMQb)7|qW=z1gQz?MvG=Vv$QdEVX? z_~CXD9hcy_e)^F0Z9{LL4XjLyhoDNF$Vf!Fyf`P+DqE)GYsX|_ z{HiQqsmxSf0M4VKao>our@#A6AbeM6Hq?#Z!oz+4dq#Z;Hf69rw^~M3pb^eiNa} zUUxn|+&23hnY`L<0Zp9cq#}ZX6&hs!uNN@)^vr;m0%!?L)Erz~1kX}<Hb~@s=gvs^BgB3*>ShU%^*$+elab&f+snof!7oM0s!FzUJPxha0wTlK5)7&rgMi3N}OKQ#+tT65- zfIT&))1~F>$97TtC_HhLxUThw2aCrriZ|y+$9a0aWXY6QBr%~%mLtq&xlCdmX?O47 z=u@^+XE0Gy`&Q875%WNVm`O*n4%<$0LV`|Kc6NQ!+fYbVS`v5VHi98}6kQ~49bSpM zcmdUH%u~D|vZ&^tm$EvQiJP}Qt?Vxa&2{#=3H^h|Xd@d``yDYx+yKx9Hbp>gB_<^S zDzO!CUB$Wuu7AD?m%jw@+mV6d>Ti>2B!VfyqT-cA3#Sp13V?9??068zV!6S12)pR* znvYBoy zAIu;jCYaT%OQ8I+gQ zvqOwQZf;>=B`sxuZOwr6m|q2aAb812ALhW5104j=m!h%@rTm^WCFaef zYF|GRDOV*(DzSpzrkZZrd-}}_(*C&_egKHuibk1@c6D`q2iE$VT-Qg7lLfQltw!oQ zewY|7eqtP>iJGY#mKEIscdZK%%HEa;4+11Hha@|JbJ+S@M=h0q7SxCT=IecC-WUBx_t z2Xo214P4i&srF}uE`QlOBk$4Y&rA8c?nOBgvKdL@E^$*Pal=6;TXOMgcZcTA;(n;I zH_ZJ6xrG7gI7p)F{nHa(Bz6&_BoP!s!8|KGZ3>b|H#Z(w(#vw4askDSo{}UosaTN}V7NXhKobYF za{FH;a$faw(IEq)d2Ed9k5N1bnBg8Cf&pt^0(3!JYDOj|6}Y~|?p-R9_0CbEG?G+1 zkz|Ak>^%CLekR7>k{{ye4Y2fWNeVNx(g1MaM!9| TCu24?7W)8eMn*e8qj`cF6C zJX|}#W^sNo@6afHr0kEw=4Wrx#a?qFNfAohCB;8!Yvt5k{G{l~Y9RjH;oM2vm^=(8 zlZ}_5jQgfxL?UqSh@1b){-e|Sn-gDREe@^%*(~Y6ptU7*&{cNwx2NSDqoQA^*~xOq zCG@}l)?w?nF1I7~JTn69ovE|oAVKEtkkKX_krKw=?0jxOMxOmpDN|g9yq!uY_%=OrP&$U8Yaqh6v$7!g%5q zhuo>(=3)Mae7e3*7B;bRuAld8GhqEH{HnR=&PnGhZ7Zp9wQMkJgnHY_?dmr}NCsU> zf>|F*6v{#TU1P`N(;I)2aP^=w25vNOx)&m-y+(-m-f%0dTdv%OUsKe7uD?f@PX=CU zo0*Wz+foU7f~=4UE_QbPD9u`d1rH$;rU^bW#uyH+gv zi2$Ml>E*(hpC3ddOI{MVniy6u#PgD1pa6f(|3eq5r}=Ud@aGrKS!19e&&c!d4F%E98HM6A zu(3glPUi}gUq)VwuWIfAr?J=%$PDm{5u(FJ6iMoa27WY%U6=tmGXN*ove^L@)ucHy z4&f_38D9v2>g&f#g_Wy;HumuX@Jf9=Y+vhnQcOmgMZ zQFo}uLdwBaWc$E>oycR{faW>irZ*R5+yWqxJxcB@Pt1efhWh0r zD{Azg0UK;FO^UZNBsks3ZuE4V6XHIHlqecebnLLSABG6R!MIBgdHQS_Cs{NPE}gfF z>(QrtZXu)oih!H3H<|?dx6GFL8mqBR!zfY zO3UnIqJ+3(V;+{)xezjrC$lt0&*wgX%aahUAAL=7BjYZcLkJeTQ&mu0;@(`BNE2M} zV4fk@&($Dls;clWuEake01h4^;8B9Fc+J5)5Vo_vMrD2K{d=W^p93i895IX)J%|!a z2Vrp)VPtqWQhOpq-88k|(M1MJ_1Wig`E1}JCcn>XN;LKL;f5*jkZI|`ZUc_3)b120 z5+PkxNgsxBF(WcpA8q7Rjp?+3d@Gp0gF`Xs;PaB#q`*GdRF3#Px zR9`OapiA+^K^gHDdD<@rh+!sE01Db zIiQCFgMY1fPbU_2LTw9=F`c( z?S&sd-p!?1GN%BKw;>+B!CO)vG4nVcQ zJV=TJO`r+@xJT9SxX;PW)pX((;TI5)1NjUQxH@I0JDsZ z6exRW>sABByjqoa`dQ$A9xEy;I_d&lT-2D!lW`WSwx$>ll1!sSKJ+n*{^wxlwv?VMY)5;z>-_6p9!(yNPf#(<3ufiOS3`7VW zR4BOaa;Z=-tf1qo5w~5!eUId(QmzB;DMb&LE`#|;w{Enwmdp*&XNbs!MNQA(YsE{! zz~$(@wJ@9BYXPyxE&hnAE{0)<7E4Dm9DW9B<$m)D*;Yn|F<(=&@lhXM5b;J%l(=e+ zE6w$2+xldXJ3}6&V^-0dcI<*Hd)$%~^;PXFKtMmOAnSRF$_0c4bjZL6ptq;(3XZQ# z1-|^SS}ORv@b!f!>M)SxHFNv|IG|}>MNQtZSmRXpSsH2ixdG*OHz3Em!AF)V7)B3h z;zbHa5kN2n1DY2nErgJKs4mV^L=^}XfMwa5TV`K`NOK6i3O#jiiSw%(DE@gTrO?K| ziv!3@09sb zKONnA3jG;Gp9GBW(^lapbad>H}$Eg2$bXYFH z^;Y^*3nc7=OdGhpJ5$j7L5xx1uGHh(WRCpFuow+?VjyN`1EIUX?(vFx{DyF%6!f0I z@@sH5;CcRB@A-8Ou)bnp&>=gn$?FGcWOwk{mSEa}|ELOC=?!_rD8S%6hZk_6NWnm4 z=qz|LI;xmH|1H%U#?DfLR%zfSgh&EI+WFbp40wMJB;!E`9eA;T`~gE4h=1X?6b4EY z2Ag3gxHa^N?l8h&03Y!|kov^jAl>O{wLFSK2CjI%^v|P!9@u*6cJ82B_3pxRM~3DG zi?)4X%nDy~k})lYC)dd4+Dnc})C(!LOy`~9#z46)m%c;q-E|~^Zj5j=fC=eRL(aB6xOvyCl4bxv={RCpaV}+I9(f-$>as~PR zSEe^I>t!#r#uDp63wy+r4 z7_>dwFs#!TWM&$BNz{%sHRAIEEN6Gz21_N6G>IVVeh_UhPP0FcP$WI<%}2`JifSF@ zn;vzL{?Zi;3LV~x|I^qktb^+VxLtywMQW9Hz)mh30d$nF9{RT@fp(b9NBI8>2NVLr z#;}0-<6o|_z5@S-SdkJ`M5BM{9X%7ODf?@eg^COu7|vIIRS-xsqfQKZhd&4qA3$KB zhTs*&AQcn>xIc4{&%+o2kD>(m?5u1Me73jB#u~CVx=q${RNXdtKe{;q1IC6jo6Kyl zN3LZ=I7p8y0_xk)D%A?euV!iPXB7tTlXiX|&$sz}Jas|vZCh=SMHh=@TvgPyFbH03 zv_rb&Q7itbg^JCIK&MW(kyYCiz}tlC(zhOTJbe;J5e)Ts`4p(MVVuIxlPj2rHz&4U zJwHO-i2ff@2}uD76{I8t3F(j!X$5JN21${U1`(BzRzOOm zyZhYFe!uf)|8onjwdTBIjB9j_|D$dWpPO-aTl?GSmLoo)gs`gS4Q@LfS{9VulSz~E zrCF^u>GbB!eaN2x<5~-r`9_9>*%!J&d-B@*93Nf_EH~|bp#>P9mL0b2s35IGQLGS; zPiJlzC4R2k+qQv}p}jv+%kg^kZasUMyleL;)2Fa$1bKa|SmRiS4tXZ~l75k8F7MTR zmZTW@0cnBH@-vsS!6(ii&%nS?A>3rGh;r+_iKIx z5(imYmW-HKAFlnU-gZ6`L_w9m5wyF^xR@_Rp~j1u#>vU~5*Vz!z_EF2(^=8%JBnkv zmK#2hKX>h=s`4=fjiwBha*{l0Vm@`CeCRJ)KHPZ|3V+)qXGc-+FcnNAL6Wd^1`76$ zC*Yuk9jGB6MF-)U@P8BA2miU3jWsyHwkd-I3L`5in3aQDv%+HlhTy2doH_m^|I>1V zG$)E)&a@M}{-4(^w@Zb;KMvJV*tER8IrxP}_2WgDk%C!p*mt=Td9Xt~VnpU}JLAiE zGKINlQr}!4%@qbK1aP-GU-qzkTiV05(ZK|URxSvlBV$&J-vla9zsTd4<;SoYvIUxN z)804UFsI6vBlkZ`5`oikmSyv2R_6@p0-1lQAdo#TSS5MAe3gzQvdYezbd7CcTW!@i zk>*##QjgI6fbX(V^GYuR}2h+xNlupfd51vhO^kHNWc zF#+yivZLaa%<&b;)ykE3J9PsJz>Q`PlX7gJEU0#1-C-Z@3fPIU-}$L4i<$fH9n~UJ ztof71N3hIe{qfVVmFiy{Xu;R^^4eG*8t;Uy3bZAc;kd7rnQ9cVcU*z`K&=+fKmOQ`VA8Q|Q=-f#73zcVhUqm{=eoUJBf+GeQ?@o0~}9 zNZ#^nsZz8Xm<&oYXFz?kCrt>(R>~H52*6ORczO|Kp7HK(uI;9VX4oEKmjJ*O?&CU$ z59z1>PedSA#!z50IQ7}{JcvjH5P0Fel zOu`DjL(uSiV^Ou&moH-kUd_O^m|=tw1hy^8oNv^Id4q6kaXwmXA?>`1WlK%=Lh@wk z?$_7@X7%iMaICASk7ihNlsA608!v3Y|Hdcw(;e$R`M?VAPF7Klg4MO<$?u8yv1(j# zG}SlzQr`DLsSG?U8#A3b{p7d} z;uUi3WgbJyRGV<7evWTvHfaqKLDF`8gw^$#BfC0Pln$0;W^{1$^WVHl?dPBtrjU&iWhBa@Xrn%S$o%oS zYu4M)fv*DiNd4G@djfS~*GJN~&IBwlzH_YjMbB4Tq?waRvuFg!eq3au|x-JD4PV*-CW3Iift;R}1w&|h$TEwJA8G4J&*0+tR1j`m-wTx4HVGz-mnQ3T-8bu} zL))&_+rFIcFYlJ<2H--Ibh2jBc5mvMs-2A4vFnf5#C@|23tt82wORKUF82`rnNl*e z1GM}E?wWS_G%wms2Z9;x2bA1MY4XX}-mEQ)~W+5FQ&E3fmP&Z?LfLl7Sgl;?)Adh{zp3Ivup3rPqb zVYcKSh;U+Q1l$b5^L zR!0Ai`yRMU8AJ@)2qZi{@T@3^2HrJ9a3q5tHmuO^@OfH1S!fmCM$rqlaaK*#lsBb7 zP}<+g!RtNJTE|UEf}QX80-lQByJ5wASqgs6Sl@bZN$ilruWIhCyXXidpE*my7mL~# zP3o{$vvddy{4?5tLmxaxmlT5f%sEzdWr+FI#*3^9UJP7e5QpJmbtHNfj8n`2VI0GI*4Y{(qY2qDEcb=ztNxC2}e0?CSltox^6)|T+y zW1Fm6Xk5Boe=4<+Bs-9l0)$Hmig%!RRl$%N zDDG0FV!o^hWd7O@+`}Smnr;DPMz62=kxBu+k=t-JO|E0#@s~kcWNyu1n+b6KvgV(!;zql_K17Vcf^{GH! zC-uJ+3zO)_HL@5%gPbzcRtt9~oT5%#2|msx8+)Um5xuaAn2OU)YE|+=^_Xghn3uMvv!P+ytgjHDoEYX7a*y_BhlE z=8(9a$dv7arFD6Z5BP=?MQ~LC-495Kh3dc5j{k|fixs}-%G}uRc7T}fd_2EZO5~)C zr(o_5M7HHa4G;XS?r2g0P`}>EGRXR|kPhEWbR_U&%ScU149Vm>LRo*jvo52=xoXe2~1S0z~g}V7D0xD(BzYw=AR6KL1t-TYFY)>fQ>!o@Z5x7y*b3|CL+VdQ8ip5 z?F!Yb?>hLI^eu4%WWLw1)k9bcc<*Df2DcIUE>l7e{k{UVIqe)wY1jR*f&A`e3B&r2 zz;E)Th3*P8+cXRes=$v2=`oyY?1&Yp=3x^ig*+;!dSSe?I+UjbHsm5my-SkiOfawo zOMG`M-niz1e-5W{S*$Pps|rifk?FP|Inf&KM~)gq=$d-Tb=-(K_=8^9gp3~pcfc;I z0_o9!+B`G^?F}5#5e%YheDrD7kk&Jb?kL&>yM+S{^8*=dRNKv$I}6Js#Nm{#aGa(z zp8m_A1ekPo%pzL}qrK_+`E20zEyP0`SE29qP@|wmS>X$BjgeT!#3>;H3t~s#IPHv8 zO2;ss_RUV|C9wF1hPp{BNo9R`{%4;d6C~AgJ7{tUkmM06=eJ)=1+&w+${pkp_B72( zZ~Qr2TSrK^$sC6geC3Ft`NjUSxAouy9;e8Qrz8U^J2PO=cD(U^;`o`czg(~lRdEAK z#qX;Cx0is=vBYWH;AoqGAIMgztIXI2-=(WQ`%LIgPA1NNaoX0bP3Q&kkJn}|ckD}7 z-?J@u(qQtu91`X6%ndOk`;k8f9H}MdS8pcT9@uL=xt(<3y-LlgIcVX6nTC@&?%)5(WuQ^Ixc{GMm2u$o(olo)l?>(HkxFw6>PdQvho& z$4o`aAy3*-4P2{GE~b&iN(qt_r9KhRBrjN8sZ)v?r9k@lZO9<%!y!FM=Bds|K7jH6 z{n>j{FHM(yVCpP&(iHgjC#S-eR#oJgd|<*faWZ%&5I4CB#fmS-#_Ke6l*J}CX%(I%w^{+F+1UGcH%=0x7K2Nb8DaCa99MAXrPSuS8)|R+8W{)Au1~?TT z*5%8s4cxFmjbouRG>|Rx5ozcKQX+PG=XNAY?NJBP0o!Lr4ebn8d) z#0NVKO^~CU8x%~Es1l(I=+ycF!#i){^FL9wk<|l3AAB-3tNrk`pw>-Slzq*HK6Ey? zUpl(Q2hjakcapWb7(7{zW-I+b<&Q$-GgcP(`OQiOM<{{%S1@2cn92BazyZ7Yh4`zL zcn|}Rk`ng1kNbz}DytV5AcBi>0-Fll{abL@rmFtN41ag&u#hs!At1=HOKx;%B8 zz3nQ7t9-FTcr5_ooEnV_wyf<#Gfsm+~# z#XnYfqYKVo&)jELdkc-%aK|BaAWtB(!MMzbA&87Cq^eu#dvl5yMv;?#^H9`yZY(NA zS@aX3uOU&aQTGix?~yktpvjR<^awxq^JBxauc1a?F1`?72Lz}JNY&69cHFXgAqO0{ ze_;F@jhdPobGSSNJB&9B^*%>}KZ)Rr8UaB9SuQwrZPC`cQD={L(-tRsnf|Q3-pN324@M5p+&k`P)mEMT{DbXbW z_A7GGW_^T2&>*{VjyTdUy%%#<{$%nPZ?$Pss_NmhB*EZYP~UohAZX$^t?CoyzUQpk zBs(nQ+n(8;Reuc`UNVH=#pbYP9({8E1<6qG_|XbrHG@tKArrV9q4? z)-Hb8=kx#((ooL3nJoN+R@>32{zd2D6(v(WEt`tPNCF(KEYV|_yyz8#ljgh8@$|t~ zXp~G3(7FOp5J-n{Cm26abf}VVYPiq;60BYc-}= )>TXe8`o?-H{XVrhuT1$F!2A z)TP52haUf@vXIdohjb1I#j;xmL-z0zj;U_qQ)8JNodN@Jpq4=T4bnr9S;}Xf9Icoq zAE6i$g$-UbbYgDtei){MSd`6DeM$fyK3O39jJ^){hzo?)hImlYVnQWPZ{>=8tpCgL z_N*=deWD$OvcjG0Kr79Bo~Xv4e@0G;X4}LWek4e-n<6?z`jK@L+U$AD?0Juy z$3vDEYO$h;{Bx(twGs#2sn+)u~s0eqC%^(TA1wr`d5vxnP`>MD&YOr=8}i%q^ch~~_m6BMLS#o#>mZhJZkb?K3yy>%_OgU^6p${oF0~%GI(4Tp~y00HHATVzd>u;mQoQLBNT)ReEj?%#>UMxJ^}|Qq1an%Uv!2Xc-xTnS*d3mru5hye7JVH zJ5m-$9puEvvq9G}HStesxtnenBHEFa!|=KZ-}g>5Lg`#gcNQduG36eYH%S=9##Qyb zbALsU7DLy*K>Av<0FtIm;Ku$Bz^H$N$zrkVfJU{lvk&96we4LTwDTm2T*rhI!{Nqd zWbW5Hz$e{@Iq3v^#^-)M{?$Jo_vn}q$-{F>6tf1AS27=Q z((r17NVWs#f)>LFWi3XeR#>uL^(xFBLulO9JmVD#Gu4rIvP&w_KOu?W#Bj9YX8xVm!tikq@zPtE=! z7{-Dl{HqdqwB6vO69%4f!^kYUM^6n3BmW5*})t-C5$%r{r=pV3@J|(`FuSuVe zjY3pHEvQHKameht>3ig|@86~hAx~?qVM893C6BiV`FbwUkYLJ3&49gB;CWq&Hu?TH89`cTwRVEoU-!uSS3qiPb}IHW zSFMNEQRRQiNHCa;DeOPofz}1tg+TEFomf2b>VzJDSpPk+0KDFnj+L5PSfGcIm7C?| z-7VdUM8W$M9z9MdIHjnR3(NfBRT(L3;?@he#t)Gs!Rw+O30v~9iV6F+B1|G&8YvNtyI&b_s|av@fy{m0{95K$GcXR0qLiRW9-x0DJD zI^r+B#*a#BeDwO5KJc?w_NaO?7&jo$V`+;vcmWlEg(gDsvuCMsm(!GSZ!jsE zCc^D}v%WIz_*J6N!@KuCO|pV|oC9zn9Bhe0j!L72;wEt#Gw?{#>1kXGPCkBFB`%viU``&lJk z9Go&OHd^i#zLx^OOlZiYzJ~%ffLW^`iRT*nqG~<~t0iwtE-?5);kY*p{lx3@H=687 zc^!lub6Lg!2nI}AId?K8LSU)_Er_x2K2$t#X(p$T0JXrxI$}V&k?IMfI~w`N8>R0! zlwp>S1rA9p1|NBP5n}F_!^JBc?`1)19P7!l<)HB7$r^UA-8jXL>hGe`1i;q{;A+cLP; zAt-SYf#shp*PE}GgD$9p1sfEQG9?n6V0Xa|v?g?`^~e;Gx7iE`ZvX9!z&ifj4GQ&+ zxemsQ4#qj4v>HUajjEQ<7BxbDTEm4UTuY&?D2w85moMIlOvWW zI8T~4KUL}eAh%X6&WNz!k5pp}AZt5$*;YKDRo{-w&5l2!+_UdK!W%>;&#>C6y+HK_ z)}GxofP|#p!nokRIJCMVMRXU=b{9|~{n$w8xH%UY5y!sf-OxHN&;FPM>b(1WrPSO# z3BXXwtLE}-XSsLOvBVkp%Gk7b2yztc=GGLCe2-MhfZ_&$K;EJVm}-|uWrBDUp=aH5aPV+C3oX80RT++)NTjh`A3IarA{TQ%tlkRr^Ok>QQtm4Sj6d60 zUuVrds)FFd|9p`bb3N{CRAvozr9MJs@B zQ9w$nbOk~gknV{|yiZ__8OW4GLr8dU(Loo1gy&^sD1l8MK4-HJ#w9Skdxfi-?@2xe zkq{PD?-QHIxrKR(3&{#acur(KBi0==JkbXP@UMZ45KtL(xz0!!KNTBhq~9Ejj$6PZ zdr_Z*QZA@2SIvW*SKmY7=buQ5^8u^Gyz{RR`_@ycKf42Mc%HRzXX!m_P;qm4e@eCK#5j+1Qc0Am!!b zanIi<)(hg-=hsDhDH5S5(=a31Zd$M4g|8vw%_9s0%>qf{M~ZH76r$@xeA?{BKXb94 z-hOtTTl^l2MH}xbQvvU4s)ldX_fO2UJ~nf}tcmlD39m;m9|=SRKcrX5JtDH4xQCA+ z799naQrKwg)u=vzjRR}~@Hv6RdY?hjKog&kaDqUOuMTLp48DJf0SOWuE%W?nXbSLT zQpJY=8ZulI3*N;Ky(hPxG88CAT1q>6z*m}y6ahDTy#pd@uq=fHq}H>M+y2Y9OY@6q>)J)XsJdjh zUd_*<4!zXo&q@hKY80}TeP8p$hVbs(il=Mu6BeFtxtZ;Y%GrAi(?Q?=`XLNq!pS`| zd&S3M1w+)N`f7w9q|xzhs~R{ei<*5!xX$&C3g=JmVMU41ScztF*D=N|7BBuJU;wn% zaB-DOh9~b3ybV=b3-EhIYz3DfCuJQh>7Vgy`F%EQ=lnf942;B9&dA#KZ@0bwMuGDpbs`-*LAA9qtCAeTC%Z zD*>jC$A;CA3TF_qb=9%mgvy%=X0y0O^{G!Lqtxz~iC0S2`8wDN|KHVW?UR@8e&tg% znAO{MvA@iOSrMFJ`Wm@Tpd@c!DSXzA`Q)xTQvgBWvB@>3ogJlh`U{UwQNkw9jVxf*zR^8S1l-(iaRzs zy@WEL_6}AdBbv8JoO%i--!10lR~9s#!RU<70d}T{UDE6?PzL75d-v~y#gRD>0O^2K zC@_cy(a0(YaU>vw8mUo(MvES_27ns^U}2%}$&L+-zlf5t^HZQ2jI3d2XZgJ8;@Xwv z{YRthb%5vd&$Cs-@rrqf39r|H>I2M(E(*ESk~`?7-`%5tUR?y1=~CpzQP(*ww+NHV zct(P@jn9WI$Fe-VgAKFJFS^@XTsJNkwUM=Jv7L%=X_=9WQwg(x$F}oTBWtii*;TrYXtU z=YO^XM1Q1-1^dB53|HMzxcpakg&4<_rXwzdqdrNAIEp zJm5f@C?Z9o3{T7@g)0T;h^SugI(6^y%?g#8uwub@uYSQKcVw;MquyrsBL_dGWrf`;<%l7%?Rl z-cgIsVu3vxRhbTtXMiSyQK#;Ok5AV>8Z%N7>Tc3iSQE>=pU5c00S3e1^6o_2l~L<* z-d;H(cwP43(ZS{^7KzKITiKmaR1#*zaC{3=Q}wIxH_yAPA9$mgXT*kjD^2&+EJW1t6I~dK z>%7$K!mZR;C|=@-qJ&d6kFjYQUt|<&z&3IGCyyXed@u4qentR6&GI86zjOfou)6X- zzGDCFkQY6~c>WqRtbKB|=q=4>)tU+BDM+EnDxP!u6hP z>^$YE-wHRQMR<1L*{W&tvk#d}E0MWhO#=8&f+BVUJlh&XJ<)E-9$E$OGNe^gF%{-2 zL=X*KxLke53N+7nA1)X@eEhadNPky5ila+lu8H5SKRsfm*;|W*cVkfjJBj-y<>#$g z#E)R|S_JXiP1Pu(dFt3l=?J~<-m6R6y>zNK2CsBP1|=3_kunt4;xu{r&ADs-e&N?| zZk#s9Sg&Da*qz0@qpt?aQfgb|D)6XR$r=U_jy*RvJXuXN7~5{D_>2{7%BKqa&xz_? z9}E6g&SZ_fJ{;I}hzJTo;;rU*7tkZo0g>RM1ltZ+tf(8Qn48nq)zyI{9FLMezs_mG z_UhvFuP?(JJ~KrG&6gxu0#TLXus&w1BfYk8O~WeNP)?_~#SPBXhlNEgEm;Wb{eS%i z8pNOBIDuCL1X0jzU=eE=b2G$$fA!@D*=%i6=y@=is>TuFZi`goVgvPk2-U)hxxoJM zW*3JfzPAPbiNv#f|GjNHst=+5GQd`<^A2Thd@u;B9lxFQu;YlB1)kNsLu?dHrX#uE zGqJ#{WX3th>q!F33H|*p+}+s~De1wklA>&$S2qb?CxznOMz^El;;&Tsn{PfgHlE5S*B6C5q=S}`o}S*oj5yYraM`Dr z+Ue@waZqnPgnm#(G`d}|eZ+pg=jQB*gJl+(@#Wh0T;G>nsz+sY{e)aR`&yI*TZ3H(N?njp?F^3}*1gz$v%sD(f z46)QDjYi*%dx#lx{yZ%Y-i=UmIYZHiMTw-FcWoc$i${=%vucl!6*}O`GLMoG+5KMF zZK!>IymbMK)8l-H^o&b1mXu$Wx=r(igMnD>*d!5jb1Il-$fvZUt3b3+B7vZHZCQI` zFH|n`q0<;Ugj83WIOwE{@xtjOPv78cQk`0}WYujcq-n z8@Tg&%eozvDmp!SMV;6mr zdaC^5pdhMu(Lf(2bKwt#G@_M5qp-o{`42cduy0#}kQ5NnUi_ z^t8OTACXl|{YM}3_Gdn$(AVx_T9%c&^ICzq4m6`j@%=9_xEXVou_RFl5NdAj5?Z4*pa>N}Q0*|09cRNXh!0BUCaMj>q9FV5ln#t~XYWh%cPMKL2vEx;8^*dgrPmC2eyP{$aluvp9^yc! z*%P!m;NBvFCzI62Mob(hb7TsTe-FvEwKdc-@P)xFn&gIbwwpIveE^pwnt^)zJ2(^b zIO6H}>5O~Ja&=YSn-1qjbDW!2)x4{#dp(+FaM;@1OzZfJZ#xR6-U4`{LPDr4onR`4 zo)C7@d=!jqjyVbcZMFW+8rj88-8S^XSYGkV#xgeB32`=iGcz-jb$dDU=@qJVx18x` z0o^ro<3BjULP619MN(_^1A)N1QB)Z(n^I5{TvgeWafuk0wtMFI`iodL!cFUN7mANz0m%bR+(u zPvgnLOZOgflW@Dhd%88FfA&9Yw~`0T3ni!3#H1nL4f>U)8@(S;qu;v?)^92GFt5Bo z5zk-8nh?45{MUEPo8L(QxM*TT?EfGlG`$8}#b*Bb9k-<3zz>Yt2GUuh@l24%%}7@< zN9!$CPJDX&P>B1kT&M%1BY~#!T>dxB0v3(%pFj0M`bSOI;X(%oNe^!1h! z7;yd!1e)V@@l}Z65!uk{{6Ytox7xDn9O;9&`gwPLgcF&5_Nf+GpVJ^D?mHsfTKw=} z$3HYIstW!fcq!nKD&D1CUJ8%w#?!Z)%v{T$-xSA-BUO0~ zZ!UA^NJteu(^LGd=JV#s@iDBKAtmmWv1&X->)BYP?R;m%j_Z2%{LfZwIuMZW12PO<pAf&o`Z^FnS|SK#=Z@jTjR_T@L)XuP%;WUY!hG<8wMn@rQj?|8Urs2`VJQC+mT zOjX>~M<*xue=r0RHNeD#5@G%4voFH&<;8R& z^munlbunC>uFNL9-hQKYK7XvtK~Jo#GNhOMK+|%fXShIXeL;8hi0~Psi>qr90j=2A zUdija#zwOmRZB}t2)}vnET#qB2U6Cr8$qLg4+baqJ|sOdgFW3r3AlEW`ts#(_Jl!Q z2Ps7ZEp>caLXXO;AHOJ2 z;s5jB2V}^^obaOn1^e^T@7H;Ennne808Tz6q?#sb9c&G~ z=ywgokiV?@Q8IPJ93K4k4x)JOI&hy7f!z}ya_r>fR5qPsvt=SChQ@TM-FXL9@bdCm zms%TkyNXb9>}VSNl@d(OQz3u+$pSBj!Y1pQt?t`*b%Wbo+JcL01LWMo4Dnh$QWwT? z@@tWEy#b-}xo^rl!ov^f4szP8n$@bFJP6ai_7d_-F$XCKc#sG8AD*%DZv2|6vf%&T zaQ7->QGx}EsNcx}Bu2tIz3zWy&hNUdtFa^^9ocZ7e_ImToN1;+z(yGx0gx|R7tMEJ z&7@JqcXaX!0~#uL?@Eq+iboqeTuXWIn}nPvbdzykGK=UvBhEV-Oyxr;tJlyfrjA5Tg)QXw-zKktaRr2Osg zvpmi4lt1j1ZEbSC7rVWL&pbV)yIqOL^T`lb+v4%o$E38@{nEHkMxW9^(}JxlxLOl( z;5>cQb6Y^_en>^+vQ9@>fSMW>GDTKNDDQcx;QVecqsen$!q(uUOZqoAB^d;!<_O{t zUq)TdnI5%mWql-q@Oj4#tTS z5B}>LZ7Rw-$JPt-6NlEBT>k7BhOaSb9WiBTuWuHAOi;poPJPym0e1=xGbqcyjzUyi zdt!dfWpKGl7|!eTLWNgsOVs|5j&bqx$9i z2A(lg*w*A&G0C`69ZMjSfaLDmL4QnXNnA7v$EoF*@ApyKyOnzq|MrZA!AKABquZqI zDp+oLNNK7K;dZuK#AtvT(^mml9|DQ%i~Xg~+4D2+Qv&4A^Plm0L8$pjR9(6%mpkz6Z&FRu(%!ZAoHbx1c(z3Lz? zpj+(3VN!tgi^D^b%&3*7J0Jx23Q#Nk5&8bHsaeNXd8xF za?C2P$N4E{uLk^L37@FGbHTLWG%!LotBR}=Mp%A#Z(m(R&RW|aTR*l-=9%B!@@}Jr zk3b}xDDo!tdsT~xsAxcB$$jh#FLWqwsuNriU2Y?hzs2`Gt&<}b^~EEU;swIC%dl(u z&bMbfY+FmWf*RS#ZY*7)AF2F!LGAE;_JN7F9K*f(8-5isdkr!0*S<$Vy!eOuxaYj$ zSf|K~-lpX0^xgq7bPM?7;4d;dWrA0)p1m7QyMj_uJnN>p zZ#;g@&c;Jq^`DARBN`^vg!&!PxncVHKQPOJP469Sno zlFJcc!>&?bkO!M^HWHj+5dtXfp{{F@D=&rX>EeiRzUhgj6{M&pIj4O~D8b@GfT9JK zeA(EKhpySe;Y7}qygV2Q+R{~2lpKl1E|ep_I_Yi0wB|S{o)>`=keDVJM+)U}=bF*= zVlv)6E=3W`S^F=IeuryK8k086*8ZVqxJtBH9(+1h&Yww{MYIxgN*pJ2W|E2;bVaq=a_O&VyyD_1F(@_m%l z4HN}C@k=?^w8hcxQ{<1^bf6Ok#;rXf_6N@6a3o+!#=hR&{Z=geGczqMK_jW}p#fX6 zMu#IV$E^l_u-*VnqyukuLkneeSQd@hKz`2b=M>F8ffm>avj>au(}qyTvDZcxZ4FBE&Ff z26Gf2W!qM#H3ys@6>9M}{?#85@ji`@6neSzrgSji^j!WCr>(I0Tw`LKF!F&JCM+`D z=aV6+DTw_*w{nitpD$s|SDemn*xqc+TW5K#=P7iDRN$_!3=KGRpHGmICw z6}6;&)H**uBQHyocb#ZI%uc#FUDZDP5maQ=zFc6m&+;+H_AlKxfBy!y)g)e(xOQ3&q)F3g*GqeB8HaiZ>ZA?ujlbRnsR}i>e50 zhTX;*U6&)a0k1d{i}Tbcf>Zz2t(G{sE1w@}f?@S<%j+yBUgOa^HuOAnV2q@Vd|j+3 z{#eh*{kKEW&kyx~?xkJ{+7HlytqnH)?9AbwypKGeJwx_LpIm48XXP^b4H9e&rsUFI zEo2Q)*OixAV;OI0Erel(coL4@lSD_rNKYM`nX%r*ys1Tqwbz;Md*sD3H86!f+4jWb z?CvsrQzk+0+GFqCHbWHECDCS^_Lpmj@E;8Kg!%KQb{$SwS*g*{ zQJ|`7oP$fP^-FR-(U+Zo7l{*=`;P5XuhOWM)B}ei!^@fHQNJ#xt}~Vri>Wr0DbQ&- zLdj?4U~pGHEf{w_2$yB$MM%u%!ZD!>dMryg<$p!@94Su4%h4Y!bI<0V=9F0mT~tI= ztts`3=v4dcF3iLB4^p#zEu1jkDYLuJ)w^y`vaii*^`Mnajg7~til*C8De8AlaPyti zRjg~qXQRl6f&(PVWePCqKps_6H^5p zFr1IX#P?4+DaQ+JQAL~4|MPoBckw`HRbB|=o-tvwQHlJsX8W;AO?DnnOEo@DEsDQr)5zh^fl#lTeojxIdM$y;xlh=@7>I&1HZ7XJ9C&K zYr6V4H(GtB0@A1gQApYb5GeR+HNZY`S|LNjQZ?vx+h|QJG?>pwy~CM#kb!riN`|OROr14nI_ZC|hQ)0XY30!-oWIY|RsB zmuj7lt&??hMvk=3=V(4BrYjm5J|67!aVw6-O?Q4bg8gb(4lc6abxzf8^NI$GW0UV~ zVR&kNRNUD37U~9A(yW?yxG+Ma1W1TS%Bw3YT(D`|K!fjTG%!y!2G>}t+g7mSFS=Iv ziM5f1b<2MqZ{jpLK`#n-?BizJlS|B8MvQr>U^OhER6usmQVv1wu78vOI1=F494i~1e?lv3#35?lS)aWe<8<#7BwKRvA2+ifQ?KlLm{jWb%72k|7Ev`A&sM%@ zH-koqHu}o+=?$`^j38tke(S4y0-p%VN^h^+saM+owyw^6z3<#37%{j(q9ZjM2Th%K zv0z?D3gH#~p#y`q`bO$e2REbaYOd`4qH?{QZQ94*mff?8&P<9wFj?I4&?({J2^A~| zoZ+Dyhj}LG&NMlam6g>wl0Sl_79sELEe^YKq&E!&z?iqD>py-3BxnkHPoYl6U({=O z2r4QF~f_=XW>)^{PT9_6nbWC6c z+!T5nD>7zCPL2?G@FiBt3yg=Tv%vvZWR9M(jxn9dXhs^u8(Mn+>Ijd}rCYL|Ac+od ze$X4YAi12mpKvXsSUb3cw)r6E3Ntv6%^a8M_WzZ3I^%!BubZ#quj*toKM@ATuU9nR zNn(tAN*-!5=`!_&5XPrN*ifha5Rk;A=mWW(wq!z3i)0 zIEnaxEt#~}b1QJy&D=agMo7r^MDy7ycZVj%>wE+g4-4*%~4(w?q|g8@82;n z0k9BvO6M?FJUP8c*U1p;Yx09l1G@aDfMQ2nYpdT_q~wEF>VZ^I4SiQcvD}t552HQl zEURrJ9(sCO_QDT`$7j)yaN^CNjTaH>DLw-W%2>NTNJp5Nc?I4xXy{(I$be7|x+7q$ zz;PuaCWbjszLat6oEQP=W@*}}f;zPW?@?pEp%TzNs@9Do6M0~BngDhg83BQW`=6Z6 zT&qnl9u(7Nt4n>XY+7BH-!PrjKUag-H+y~PFuk1KVfrlM{6df`^Yt_1tCrJ#*9u-9 z!m03KPIg#)V@-J3q}y@rSukkbxlF})yzawXdimVu%Lney$q_ke>D@5QV?wkGbiUo& zkqwxd`eUqihyIRXS>4GHq5m9O9x-{{_P>m(KbJ}f!JtGgf!U;Wdj_Mv1|p?nqrHtX%F)8) zYY(OsJHHWZIMJ89!)*E5J`TZSWIU1J2?#jU>pnVSIJkmG|h)|f% z!JbVIOtqi@1WWDz&Db_4tIvAu2`#xdiy7wy@*6IKWetcXqp!OCsm@KgMsD7S7?y7nZwCb4hJ|8Hr@h4Lk z09KrUZbbDEqbTU&BIH$Z+%snVAMH=ymk+}Wk~}2Z5Qo0s_yKS*3B*{M;g z4fpkQRF7@VSk6n|JNwpN(3mi@DAwIu+U9O(QTiZ>qAn^oTegTlQQr4335x9Xe@N;U zGA=Di>JC<4#L>|+-0{im<-Q1lino#k;n6WgkIyAMqH(=gE6r*P^GZYELOCFWvb#S+ z4IUyo0)E1L2O8MtvMg#!qC5mM@G=%*fv2snDkb&KoL5khQqL5yid^P!y?DX zichtQe+un+f3HDrZemHe(W#x?`2)jDI<0W^@aV`c6_$&<8U3>VT;J=>@y!2S1ahVhb@c@;P(p=1=%QEIe!^Q#sDOjXs?P!LdQ0nP}~+gXf@ z7bL{;OUQ0eg0)`Xl_aC6%BkETJ#<7abeL_zOVn~A`BuQH*7h-B@X*_E@0Rm6gkhq3 zkpfGS2Xb}Oh@-#|YMt3*qs^DYpT>3C%_++)cb6&| zrz`$IdYQaPUaLQ3Mh?+cQ+ObIB#qJ?bJEYq(6yqB(Nq!f@us871$R+qs5S@MZ1Co< zylMZvxqlh1H(paMZttJVIin=_jkj7Mk6p`2BSLk$mt#3CO82ijdGt=t4xtRRc7}^% z3HC6_Ev#vtkMk9egDPJVEu|3l2-H@zD6!K`3Wo;p8HOriGn*=)u#dx%e8MZD(BWO8 zIP+0Y9)u{QKl7kB1J25ex1cB3{^SDr3El4b03$*RhGz;m2m`YYo)}P=ZOGN{M!&GF zR@c5$Wff7eZrT>uGQG8-+W||7-Fz3u&-X8!n6nlWAD&O!uWa-(27Nw-(`eF~N>$f|G@_uC zDXkE5>d>usq7Ch@T^IkSo6quSgmszC5ht># zww}*yzmTy-L;P{?$3SSNQ5dU#IKMTat)?Kk?!IU?jATO%WW!!x8r--xN?VJnM841d7=jRhCc>E34+jDcd zc_bt;j2IZ$Skzjjibfxy3UCq>y^~@tozmnYw~b?D`TtnD?szKu_kXPH>^-wrB|BLO zA$wD{!jVuZvSsfPp|Tx&&!jj;G9r6rSF*DA`d#Pw{{DZSdUfvm{(P?MJ+0|OfJJe= z-+U}1u9`IfXB{2Um2Ym$;2!{L;PJ&==iyF88thDP2m$;G&Bj?dIj{eRFF1k~b1vwf z)(J#Cw6ov=x5tQldKg5mcq~(u7P#t6d#Rx;vhWSuN8u4TzFA!w;-qbH7Boe6%7(hQ zyadr)YQ54oh&u)u9_52%NJ3gV0`wv-eV!)bE-- z%J#0)sf%qWbDFGkP6y$_Z23Eu5Rt6HQf!}XTT3h*6@ho#<{L0(!MB6Mp(w(NKR564 z?&WbT%V}+#akcz*eC%e5t4T9mtR%RcH!2~%n?8g>>t|6}o4c%?5NWyGhK5x(er1aI z?}KW1Gs4S#c9zc1w-l%Q0JybaG2MJjLG!q%YhA^ zunwCnODnALc|ZIk*svg}E#S)W~yPTP< z3IbS12L}SULd2w`O!5oB8jXc`?(Tjiqkjlk{{WEim{nL|Nw~}i&BlHrYnbvcr5RUB z9Fl7o{c|HmzO!2PD~ne4g1?>e4}(N*fnuZ5ghW}6gmpF{TUdTFfkjsws%dN*U!SVa z(cvTCXn`RT4muFA{qD0B$3vhA*){YkcE8p+i)iZC1r!9~F*%tfa}WD+8y>gyW^m{h zt=2DOn2*tXiO6XL*e7)aAdgYmqo6LV*PhSq-HLn?;}+c|07Sx3yV zb03r-uk;yTfBy7iNOD12>GDiQD;ry!dR}@G`UCMWCS#=*Et~7~=}&V%)HFVANeKv_ zzu^#aGw3sC=zg`Jwfl+Hhgw-a(KF{%o(RE z)x&jtV_!4s&M8^``={O2RT)gT_j==$9uRQRGu zf4?BrCZI>LnoZ$bipI)9$s(i!J;`ovo~;n-*}35H4ph|KV-IdA;G~yYzr#%f49qz# zGCJ7*E*|y_4SMO=nQiSV-^Fz=(x=m4<%g^sP$Rz4;8``3KeSIOnY;h-L5TLN7B}XI z4x4sV>d$>NnhbK3VGK*iC0G2GOU9uHMItYGJNjVbG3e0IjJv0J|m2Pm{usRQv5x3wj-n2{rhS|Vi>$n0IFT5qi1F;Kuk=h zPkVHh_FSsB2sv;F-%DYFn&&LpQdrg17Cu(I}k!>(nnc#M~ zQmgM;Wv5wL({}ePf_}@8Caago+*o1AfBn;|%@3b0@W1s3+ZyKxKE-@XoHD_eJ+Kvs z{Cw8BCZ(utbPp2VHsPM`$n=i&acn|HlyK|D$=?_cadu+8Ouzk#lnzZQRu9wRsG zG!IKfV2YL#FXO~;ZpEPYXA5}3jn(VosA1xh3M@9WDy1+@Kj_|Y8xp6xU6>imo zFUbDfynN?_g2L?qRnq|fw|LY$8XQGCG;Tz%A( z0R6v~5E~N{C@awYyNc^t%*{XaE32zGR8%lckJmcU`KL*8Qe;6Yn3g%31^?$Z*0A?& z=FXc|fHkZ+xrO)=BnxA71o#Ys=vcz8s} zYzesIN?79SYer5gWQXne*YL>OlnO=m=tl6+QM_0ha{-p8gBhGbJEKi0+k0n( z_b$d7(pdY4mzDXg;pzlGF&)6;QVil`ZY)C=Pbxf>__BNSNmydOMU1rJil_eOxEKsq z;ft~Iz6M*U@#_BRA*J-{#ig-g*@ zNA~0+VTjRbHGtY@DKfnmvFSYbIT=`?H(ly7M(Wt)cC{w~mG+)uYGB|>YHo5eZ7RQD zP)py3TLUvQ*Sx&^&5lD|iumD4KRzokDz4Hds7>eej4MoFK>$flyf^cfZ=~`$(k@!t zjzHqk*2YMp27Q9R8WiPCr#0UUPvZ|}88p}ef2Fo28AAj1H zqccAxLY)1mE!=SY_3@g`cZS`A7q&fAKIgXhF1cOEh@2Q{A{Z4<-*54;OX3pdR@lUjalc|C~TH!6wV`O`c@Hu(!u1$42Ws+ zQRKVxnzpnlzES6f8AB?P?)v#aR(9mf&Urr$y;9W=+%#;;QH=0Yszw9v$c_9mt7oo? z0YQ*$?!@3=plS6ZmVNBx5$X)!Ykrw9be|jtAKkOumU-TLL}zg6*!pXJT{zG47I)lC zx~)(67yZ2SipbYn^{Z76dwzKWjrA}?dz}vdH5@{ z=M7lceT1G|ber=fwP_yDCAZhr)vdttq&Eqa9YbV?jQIR({aeGo$ds+Gym7Ml@HB9Q z68$E&#fz{_7*~EwII3~>Y^$lSMgL4ju5ds{+=V`5Hy>W$O_^9geRK>DAEz(Jvgv7} zjd1>_JcZw?3djF78)$=g($=)I{xKQdBe>GSlZLrX=$tJMEx&jlusR=3%XFz_wXxrQK!Znn~tTH4P6%*6_ z3kq74VVVQ=->;a5h8^F&5iD#;eQH#nB|^-ZFz}($z~0fJlymx1g+k&>nqr;r=Bnn< z8(FY{^!{60d;EE=s>heqDllyKhXIX}FbNCpoGsh240#4=XE^g`n7&y!J@kH}P zxsSxK=vzL`R8Kbd1xqGxjRQVK=N=myTb+=twWWa7;zFoP5E`;Vh?^k4DJCOeLOAf( zGYu8*nC5Olljupo7@|A2pV9Lhx8A>?mZMm3oY)QM&q?BnglxS+j9UYKArRw#bAGGA z!=KniPH_eNh)fPoJuofMKPD&Dfy_-9^OG2O0P=MMeb`2W5E^OwH)!0(?@s1NOuZL6 z28eNzPOs=?&f!a4hM^p!ov?Ke9Nn=cLb8M;jV$Iu9z>Pk9y-Og<}@K zS!6u@7-b@4M91H@&B9m6hQ=|CF4f&I3=Gs3j%nJ`rqmTkvH@c0xt83~FSZbQbm_F; zqmk)Nfm`uNr(mXd8q5b2c$-{7=u*9mfuwIxKuk(62c>D@-RX1<&@C9zLJwAdSo)1uFK_qaDYy<2@;8WBe8KTaEV} z5}6hPYZUUy6BH~zaIU2!0nwqSB`PHq1`6b#mhC=@=k`~o>X<}qPE-641+qFCQs3yA zM+_1T>AV;JzMJcMWSTrQF){ICIq$6;ZstOviwtW8kLi5d(BQ?boF+iM0XNc*OgSlj#U6Jrn7 zxbImaKV#M>gJe z_;P2dF6&I!+ZrWK78jf>cG5ntg|~2F757qv5&xD}-`eHu-^r!K##ddFB4-#Vm_hE! z0DyCG!Q*^1mx` zkVquttKEgqAESnMNDG16-K@re0?0VdSeZb$CnFH5RGL~nxJcZSBE#a$)y7@lUyUdH zP5l1${0ENRQBo_JjCL=imJFRQ=Eh3y*K3`ZfF^+#e#DZJBs+b3B(yos61#B3|;w4eP#C(axJkzY?3-_5)f4 zA7z|$lL^cH2p{iF-Q+M-#ypJ&MX>sR`8-cWqp7JGy7#UkZ2^4Miok4L2imtrrozYuG z7eOm`D4P5PVu>uI{#1$<%*-)a&eB|uJkyh7tn~q2vfwIP!Bwe^{DQeg2$d8_Qioec zNeRA@wIM9?u^aHdLb)6uwV$b9u1|9NU89Y}{B4s!n;P6-E8b{o>t1iT4m8rxqN%FbR7vw<%h_I$JS1Wh=E_nvE!f;Z02C%I#7{Y`s+Pof&W!?;<*pmiN;{oq7K7oDoP8gVO$d6Y#V= zyONUP@C$Q`L)SWztI&DsjVf2z$k}_1uBi$Tvx6K5#$_x-F~8I@j(?3jxuO+_nQ_;M zKg>xV!QKFxP#ySFj|lYy|NzKF6SLGOoK#wryRg*@6qzy@LHYmmW< zi;L^R>i_&6M8`mmM`3d_n-VUMpj43snp z2;ylk{4<+tO)no&p1DH6+66rW0~)k>cfjTu3Fh~N$%n3wA?Q@ zC(KmY3@JsW03!UK!gq9P3Ij9+ktg8l7?LB;ayS|)m>vxO?i{X*$*knL_>hrvex2u< zK`hb5vk0r=(7_eRdImhxF}-j!4EgKPum4OD?#xF5Q53)SMDFM2n4TThA;r@bJLKZP%!;63x2ySM@D$?Ah}uj_b=IRk(OM% zK3P`4BpcLi3QAVZ&`h)nnDa|81ddQgzj}B0u_&B}v7x`Qthm$W#tGZS;oY7NI?L00 z2(1(g8YM2$>as6?zB_I_>4W4 zVB$E^|Fp5eR;o$oPVt=-GfY?+7gw0Ype-*>$$jh2tq~`at!?z$hmFr6pKu@I78sB} z?fw1Z1c;j@;%np5cC%KGeVg&aNqk+H6|M&OUk^^(Mf=hRm<*i_Z*|)j6t5a62b&4P zQ>CFPGP4{K1IGf~v|=(cQ81@!&>pI!BG{+o=z#$x3RX1#L{J|tv)O`EA#`uF=U%c< zyft+Zck2)f5l415R^&6xkyR)Vrur`k43LSdje}?d=OYIf7haA83!0xjZMPl}1OO#? zHL*+enI=a9LoFgRfyP@QZ^#iXkE75LTerho(Eb=yM0QgW4KDoSW7Lry;81&CDma`j z(7&^yWpNS2H6+&Yw;R9N-iL%Yugovd%FjHh?q2*b2aKPi1%~ z#&V##hdb6(l&07Lu%V-Lu8)RVHiwkFjwGw7LfLAo+xx~{Om{3Bnarj?7k9%M$ldiI zycpuZVLC|gto{#XNfe?H6lkEy)hpEDh>u%ld%uR(NcrzhDk@~zp4;uZbR;QG8sv9C zrj9;Hk)bjfJ|xzLt1rL0`q@`#=KJH0kl_%y99*=(vT-it&qdi~Laj^-7YHXgb{gxs zm5h{>hsPxqKbxvY-x>XE97FWpBhxNTU2mN|9wkPQC^`(;ojq_UAhjm+KJg+u3W}lY zmaw*20A#Z?{^pR9H6;&GaGLt-=dw>LBgp3o{86hFf;9Bst1I_I<-b~wyQ2TGFS2Zeri4i!q3$`T>YC#AhW7B_WGI41C>3 zAS5*OcfWudKsGmH?!ctS8}9C-sz{Kv+Gt?ticP@eT*ON2-Tyeln*R15?Z!T{GpYsqDvai*b9HYi2nc>?6A8sSa&SOS{>ga zkdKT*aUSsbfmHL2tu6hW>Y(3E>ua>v%mP;w$ZWQj=kLwkylfLJqcah3_oB{u@TfyH zoo`wCPk+XBzx0H}n-|Yy;R2hd5k2?Om&0j^Y^vi_lF|#gGtZHvj*Xakx|fd?WG}a7 z8B2iBy7~J}mTk;U6uce|Po=Y0)POH5LH=<6AS;xjIzv1Gy(?@KOBbt0$2eqUcue7e&f4F zxUy8i&Lbc| z`2l?fPYt8~6p-}b+%G6CjXpnJlD}uF@xP6}P>1gahV23L1s>NWOiMI7klvt>`$r5X zD1h9KcDa8@`b*hYF8{_Q9}!btzh`4?a&cqXbUveLP-jRUZMTZgxU1t9;{vMK^F_9c z6gMd8lEJn5wfwlv@1Iox%O;)W@diSueP~PdKkWeLrCP!F3LFf?;iz$A@|W)JM|jN) z$oP^#UKUJ7QV_W?2`4x|&1d9~=LNA0<_%diB30GR%NcylL@UnG%}240S!+029gX{w zPFNb>O$O)er|X>Wd*CLQ7x0TcMCwysZ43bjfh*IjF5nc~`;53g$9_YYq>V&VbKXne z0kH{s(-)Zl|62v#=B8uxR1?14Qpg4|!BL!s$lQ>KU8@zS89kBx<7HnJ&(mRZ!!ehk zWC(Or>vtdo<jgRWU(>!JP<2wj}l7kPu}2a!CQgUxSCUi%@e2UVot>p_>Uc zz;rgi|AnPFRPkcnY+@gcj4&)VT3^bcG0@i-+}|oGzM8(57m%N(0YSlIg&+pSe}^ms zkB=1o3(%9pCky~5c5;i5Sq*`bL8tWAGi z%1wP1^HgiwKM?a64*tEId#NcpsW ze`3!bmbuJ$d>ra}^429Z{T*4SaSV_(0F2x=Y)Bcg*zA10`L&|5va&I7OD8I+1l0hc zwr7m8@2@mT$PqdGa2?1i$NQQdL=$UmCX_{t6?lm~hV8r|*`HFh_eb4LMAKHZ3rYE* zyusZ%`A+L>4h^xTLXGx3vbDcDL3XZw6M!Wju^J_^4S+3b3dCGM%Y| z*UQn+!2%fubQwoC6~m+x0@We`Y{)MGNZ^=x`~8)8RdPW-shBsi0`ODD_b-Lh-G-o5 z0a+#}O{tv5>c=^>9}?qsLyPY`H`Lc4grkmw-Kt0p{g)a%tWNkFV!oO#F6B`I>yTBX zg;)kbJj&4liR8Ev^!SWikv*|X2PU8*qP|K^F3N;V08A4yt$3n#USSbD8pia7DX}bu zTsqTSaWed>ZD`ma{z^aH&X-tq4^)5e+yEgtAE+uxpZr7AztFwuRX=-_-jASHDyk*8 z5o{cfk%P`Vl6j{s;4#O>#&&lk_JtfZ=uGu7&BWu4?oJ>4TG5sVPWl1& z<)4ZBQ}cWk9BNY>`O zNdu*^edPf7%dFExXt2XrUMF2_8Ir^%Tc=!lK#`u-%68EXuJW;Z`+n9Tmmcy&ati7w z3evdC_!|EdTAZ*+o6d*5GMcP{KOw+shiY-!*Ke4r`#d}Q+&n*XMbS_P$VF(w#N~ww zDP=$lFWNk0t~q@NTm+~yE0+jx`9RCu|KrO7)I=DMb!llS)an$*r(vv{HJA?y(kE%P zj7rV$%*QJ2x+v3n-`Nxu@uP5cw+voi(?$Sz)yrCmyAP>r1)Mi9@k8_>x(61JYlMJ8 zA|+tuZeh}(w{L6(+x9v+); z_fn#dp2jcm1cA0~wJ~?Kamh0sbZ;fkpkI&mLOg5z?idX~nsxZ6Q{s|1qmK!+5oWnZ z7_qZhCp;TRSv}GAEdUE zYkFhu6i!_^`KvC6Cv|DsVXMJo`&-*@o0$s@h{{&AO#O&x)^sU&Oh;e!4j_tZ890^S z#=|Fd_3nIQSicbVi230UUKf1-NoIK&azqoDUjOwh?aZ{d2mQI5@HCv$iRsIdbf~^O zbyfC1X;htG!Q5D}I_ZcL$Dwp{a)L8A(r(2rJQ~irG57b|^tg#Mzn?O^|Cc4e4b<#EY6H z8%}?GX1~=+eBB$;ik%+@a+Q2Q<8LoDAKzK?e9B4be7CLCC|l4Q)>4%Cb5j3Rj^sYU zpB?DLic{8~67)t795&OM+*gfKku=Gc*mS>KJkCLk>XBhF8TDglb6nVkN5AAnZbsb#yRHwvo-h@_#`x^J?#^udZ{D z3i2391ipj~AZ!@cmX|B3-Gg@X6cls=F3nJunCT>uN1I7w`_hp5oDW|V3h*0@NGH+< z&{CLoZY}BF-{k?*L}*SagHQm=Z1~5ZoN8yu(Gn`)%?& z1HyO1TE0-Hp{xPxPq|@x>3f=ZBq9?oDS$7*xtN<4$f*YEKNUgavd0A|4@RYqH(9y) z9R--4atVzKfDp8*#@7wBEWGtKlbpc_)E>nks=B_;z`_DGBb*OK;8N;-0$&nbfDhg> zXQ#($JP^MBRe%Tq&X%sPg=-H0BiJeMw;9iNOtW$!GK^^FO?_y}no$t57zX{k(hzTT z6N{_HM-A7+H+dV6&YNC=s&~nX>pliH5JM@3R+u9ybt084Dj}5O+*LKgjMWQM6@g}R zQS@@@ETmwSJU_XQwHts+t&yiK{*LwKplx=f&QSGyP(#Ap_vrWB(bqTJPN)6HKE zDqoK9MG%>_;)FrNkEr4C*ki#+U&b-vD^}<1NpIP_V}D-DIV`1z?Z4A6-`rm%G=Czx zDPIst{m_Mo=f*gbqOPi#SO-Z06*@VVJ$~Suf&ShFvD~cN`;bz$$GL@+^pND@+8Az4 zUv-voUw&KwUI^f-Dx&?_bcr(S8qkry)>0eb07bNbMef&O{|5w;v=JO~N4Lh>9%p}q z6OAZ_;=*pKb2zn5Gpk=@d2J!))<5<~{!(X)uxE1{8fN{&MVNq2$1|OG=OM$IAzFkn zxvydf37Ga*o{|FiW~gI3K|TP^gJPlaVj#RtX4>$JUs-`}?dVn_m3PahvYs!r+jd0n zz1?|1>hUt&VZS|J=9ns9ifC1Nr z5(`{e==_7}K5v=~^U&k_X)abS)i<9x|5YwsZ3K}6!0Bjh-)*WR6MA7E#p7H*Q-9kG zKarnk3zMzGnu!mJ1SZS42&UPif3M}XI25HckW+a%IiOX}`d3*b#U|+{LiV;X8fvV1rbqQNCEB&f1#d*jz?K_eje#}HH->$bG`fB zAHe>&et|s1E*5ME`Nb$2uc`yvCYX9Kj&0aA!R`Tg8AKoe(~pTjAg2K8(@m-!&aajt zFdjS{#HZ-$!#OuK)ECyhVXhicsA9lO4xC$IqyVY96L_?WBKB6tdIHQq)iGXy1-uV7 zQyc=pl<1IlDS2%3Dm1rmSc&)7nUx}e*Q*eUBnl3cA-LMZ;chQ#jV8IjnQ5ed+aM3G z-rFOc_asjWFUYcOkc)!@;83WMt6BzmVMBj2d2pk=`^Bx#^WWKUbd*Kj;(fGu-VqD8 zP)*P!|DR@Se+aLe(NCUid+bhc_!`qjSZg9Yg-+)1G+U3E*P z{N;Rpo&9Q5DDuB6DaS05VK{Y(&eGehp#8^{TV-dJ#}Itw?vSYcJ%d%w_Q+T*d)?XORF4^8ho$=EOgFz)2!FKXWS zaLSL8(M7K_M4PZDaW9mZqzkPy#sJdL98*G1PtX1+7alC(m0V+G2vtZ+OM^KM6LAF! zehz3>0;&xLY_BLp7^pwTE5&IeyGF_Qmf3z{i^$1og)1qF1g`0$dHn^hQYyxw92M6y z0%z}Z_!uBBk^s~YCaKTQ=lukJv}rK8oJU_w-`Oh?*2JNrp<_F1vG?!YnbWGq!9?Ov z3}X*JlR?nZvPkCdr@Yu~W7o!pW%|xp(^|8EK+@*Aiysq0@!l~MmMD6Bv!^^9i|ofz zHxKKu)%z#Ug1Rn_ZGB1ZATQ&XORGUY4fEqaxzJLpLj8%vLyXrr>a)1L(Al|eDeJlW z(-vVjKVIjJS*VBbTWM75s1a{ALnJTo5kV`GZGuM~HUqvBJr)u_r>9vWJ8U>qrG!l> z!dOdpQV343QOWY$+w&hh2e;|5hj88inOs3}ZNoL&3k9R5wgYMdn(b5OeR!MisU%jh z;dwEdB`bs28qBxAH2}I@@Zg&M#|J>XD8aP_PE=5!>4D-+D-YKnh2jBMFDQF!;Hc!_ z=>4DKO_d-3kC>L6!WuBNDpre18@y7B&y2;!=?hlUP5Jup*v_Dad-?{F&kl_0s?()`I$WeOQOR#zjrPAL1oo_emf;W`6 zW)93RvxjbfJKPQDQob4}maK}PZ`<%YI{ASTOG9;f*Ey?m=s``D<;9*QycJr)*r{+>(|i zK!Bkk5X{ClD^2z*)0S!>M3C(*0mFcW z0Kt30dn-R89!ZTMc+d%PI-iIG3F^Ex@ckkRRSjf*BbauJ<}BWi6dNyA^;|37DPrdk zGO1ALwn#}uIyzqYx2OBTV4|1`*7|c2|9eViDJ3aO zXCuqL@{j4Q=3GKk^b1Ef5a-z#v=L-$#sVSM?zgU&N7TIzD(1 zePrH)Un~gP)5vic(4pu9PFRCdqnmM9ph>J+hqQ6a(RZIee+F48xZ_k5zTedyb5~1v zX7(Efk6irG)?i|OhwQ?Hl_ppD=^MXQSTFpg*$uL7x)Qjb+W&(N7K~Ib-T3~M`}I#) zo`3#>oC0cUEus5XlBocXAclb*7zp_H?}=UYe|M-G<2Ue<0e}p6u?X>7G6fDwBuO-- zzJTAgw>=!+`YK;P7QPg!O$kQJ)o%yBOsdo2AXc~~BlGy$g9g`yb}H>ti$e_twU>uI zGrNQc>4atKZ&U-SUlw&%@M6z!t+OWrg|SC)Ea(^?DGFS$HZ@*_1QGMps8&2K0UpAun-&j7)wm^t8S?K z8J2%_pLB6^ZS4pH1H%C5ltNO+mo#c&J{DDB1>jAoe4)YLu1bkYvEsfo zW>He&U;fm1gm#Uaz)~4~P?Qk(nIA#G!w)_LEo!j-F;MFPX=y!(}NRM5e=oYsRRelhs_T!7~VNgFxHqD^|l#~$qXg;&zOZDqnIhip) z`H~-`rgd+d$Z0+Kyk~T{9YH|(|4=f1=4_cm>iDrWa~X4JfXGRan6%<_}Aq<``Rzo8-#nFKe5Y?H7W!? zIPvU#^xY2izE=FFf#BCGw~D-Cre zRbvp;ArKo59ks>lN3sq3k3r1?qMjqEy9w9|US796(?j7N`2nWn8!j_4&~zEIXayRr zT$E2m_Ckj6!25)hA|*VQuo8ka0^Ed6RCr zm=rnDlw>>|`I-H%#)o(rOzOA0iznod2V%j=naj14(bz{c&-;|Xdn?kiL{OE?_XXkj zdBkLCh9{jrmc!5wkCr`VcHMS1-yOa%q_-#iA`9Iy+u7f{zm;6NX*tvbOuCjxZQJo7Wg@7C+28c8*Bo! zm=o1U!Lma#1$iPy<#je7?o%v;ZEkqroPF!}#*&scyW`_xqzh>PmT`$e_99qK0N1ao zM(PkS<`|8Cc|1WV^~aO9ZQ>KtBbgiP`*(R0nvO_^LuS}osY%FLf+ZDQGxD)1Pwr01kBQ;JUh*lV|R>nWWr z9FgZ}a$*>}3)x1`J>hrEfm;j7%s;L$#ETO&d2L>hc_j?rd<MjYp_q6l4%E8Enfp?_U0uMiSwOsyZauM*)04^Nf+8cmp6WxS3!nfD`ra z#s*kpvj1lvx8#PFLIRg$E zY=l)gCU$k`|8pIdgBq>dF4ff6Q(-bT1^^MmsFGf;!9O2Jg2GRq{&1yh<@19=DVFF7 z*8J<(RIx_`DJ65i$i(r2rerGmEwlUT!Ra>s_KL>ZJv8r4(J+DHf?W+yh}WLL#Mbzo zuG0&c&L73Ayqw)Zu=@SF-TtUA_wA&Yu91~fF3l`0 z@^4!+UtRWIvlajNBt?xa-SXSa^TkhCQRuCPXb;A9X`oMT;%Ab{-#_S_w7qi3U3q%~ z^f0c_9UiRW&n!~)U0w^5cc>mHL}JrXgM58-PumA;*My2EGYgo<;e}>>uyo%3gINW2n-nwX)STF^(sg6`*@851jME)-H`m&P z8MXXjInkbMXh;Y_fu~__y6k;9%Q5$YZDwB|8P)f4iYe2rexW(U z)h4XE?gYWb=oCG$JoEZh%<~+WGlX0Lzfy?x@SgRJMf%vz56}-O(Y#_92E6c zd#`1r{ud@$E|}iN|JX^B^}5WH%gH5DIRAb;F&XN8hpiC(K&@u(?ZL%moHp*ijaZVn z9fb9o6=|(?>-@J0sT5VS7cd^EXW_zgN4fpnE*_)^I_g3mPNfuy0wV$8NaC%Fe~(fSCu`u@H*qKnKwS)1VHlxCOz95mhcX&{n$A5OC$E!zW0L5TjIKyZ(n@QJVG5y z@+haY&n+DlvVr=wn6V+x!q9&0Z54fFhuwMy@wZd+kz6t(^$MiLv;>lrKtW&wA0Ho$ zBvKJc&4ru>P<$KMKu|@vA-}u(^3{hfO9DVmYn zzr?Io{qjPSEjZF6F`Ih5A0|bB$N%v}6&{F_GvO9}1r2PN{R8lo!DTTB$Wx7t_+LOG zu$sXA>Bwc!)j2==bP2>YSPGk;Cp+7FnW*zk47GAaA^=g znJ=0kDJ|J;^A1Px31SWq6|Z%ljF3XqY9nN&!@fMoe52P;c#JpEI3i&)2KW;4hU1}M2%ZWbuxi7@N+l>OvJNmq48R@%I{>(<{wG({ zdZqvW@`3Io!K_tj%>IyA$j|ex$||BqApf(KCAWadZ8vs9ylUOsb?OgG!0QAwkk%Oj zX+eYdF*{3!=@E>3uZm3LNv(!#^IoePC#V@vWEa+1(FDs^a$o$K4|g^fx?JriWDYLS zf~!}GaGr3)yWUk%SpY$Ljd6*IoA#zx$W7hjUcc$rAGA*y3hQ#_CNC?RCIFwN7<7k3 zb4)j_0Ax&2qT1VR#QAfJZuUbc&BLu&zXu27xvwiN>5GvOn;dFR8?sK1u*zkYn613E zzw11o{N9d7d4%hK!+UXR^>m%_A9ExPjWx}Mb(_06jN4!%{^_w8okeNZ2uje+#(M~{ z91&^S$(xw)gF81f9sO4k;hu*FOmdOu0|{)(EMEftV4A~ZA*dY;64|$jvWi>_?w$P* zi#EXy@F^nJ)08sYlfrh(Yb>j_QGB&i*#FG@?Q?V9k)c3+stKw%jQz85SXrI|H)c`6 z8EvopDeW(XK@Xtxrcm7*3(9{A1SqI(h=_1}CiP^hO2SksmWY}vR{{cU8d+CULyma- zv!Sx@jTdlgK-7fDW1MM1JqgYc%=$&6okJ}8A3zW~Aen+_Es6l22V{29w4c+I6zNbY zG%STq2wGVRMWGyFf#B90f?QHn*%tUFL0V7*_?!mM!^zO{G{oJZiY^|uVc=_VXdnGH zq2&%L5S{#G!Jo9OAN}a`nU5Y0Lr>LvP_%jffzIKxPZ~VcIVyHYj$YzqUE-=v({gVz ze-fK6dQ~Nn0nFq{W|DTv3NdE!EI>Y8DvSHtPWwEd*BokkP|G@45ya8;17{?En5F)d5w3SzeHSoCf?G zV0fd^^041?1+~EbPU!!@l}-^zqErtC1ASa@8>FEmHA7RovHEMQPVTynbi141Tn3;w z`Qb<*|KTW@MgXi)QW}T(cUlWP5)f^b1xjsKd5U*Apn=qT_H@J{&B}nkSm4m#eu6wh zwI~pXIP}C9q%?v2pNvDjK57|j(l%F?&H*6pMBbXeU|@0zX>68_&2(&8y!hL?WbDWA z>fh1kd%iME65@~@BC2za^kDud(jxHa*(6fAn6~dB+|BeM0g&n7ebi%_9Lqwm;Wc}L z#8p@Q8us8@V@zaBs^;O?Jq!FOIny0f%9Hn1ai20qZ|v2m-SWHtWxIwh>*45D!Ttd{Oc{w8R=nf6aHE3o*k3>E^L^_l zw@M&d6V{p2bG_L+)_E#z5zMA|f?Rf7jyl!>Uk9@Bxdbw~d}R!A3p3Vq@9G`;`eLxV zQ|{W*JKP)%qc(wxWA20QADko*3ZQO&(CHS2oiAGz{|6+NVw$guvSD%`1_2xNYpi$k zCnBrvf`*@h0)~B(J?W4@Z`YQ3&193LHSfy^sxb&T{gQy z8Vd$tnj$0|sSYH2!NYH0)W7k&Xs6Oj5B@|5ww&(z+xVpIbY6+WdgJHE>gBcS{u$ri z8=a@48F9hVvLmNPv3@5lOS+6}O4+3>b>`73F_`b}tWs%AH?;sET(OOUaD!mU%$;A0 zA2z)6-y7f>H&4976uM&|H^r-RPPR6sf4>}keTfLml99ujPV?oz42hN#Z(bMdTAxkM zVngusSI8TlyV(xLxRtO-e#0of8D2~P95*2i?c@3v@0%`;d$8Wj-<+vQ|EUtT`IEj~ z%p(Rz@WR`BzB;3Gwtg)Hg{2jCmF=;>M~8vzN)V*EHGvFumz1~bARm$Mg=!03(}P!j+VC`XKZg$f`hL-R>?>%s&ca3Z{Z#$S~cH59x}7$lzlly9@^dxOUGdhVz(1jYg#USi<2{D-Ld#Z+WHl`)|~w&&cVeg zmch@oG>#}GqM38Zu9XH~-@NC{n<(yw+biIyBRmIriK=L=P7IYMPFS2K_h$FAe(bLY z8a+yoIG^qWXD6jI%ioP7rkQ7FbO*(;tp&B?3Og9pDi}{HbzEBbreueQ$t>{{LaYh6 z*Izr)n&uQNvqrbD(yy5h5FpjV%;dLLO*FGc4OaSnqg5+SNSKwo_vo(+K;ubP6vGLe zY+tXkoxd!dN`@8yDP6s3ZDzH}!9hi^wH@<4`Po2mDz~yat~A6OXs+K~l)S<6A z2{nWgL@G(?FD4ypUhN@EfD95eDq&A<2gd{Wy1)X-zF!0~?tJA)T5xtN{~7(Wlad_1n1d zOlks@8}<$kd^f?Ovz@?w@854H?S^MQSZzPHHbb<2`kXlbi0luQ)eTpP!+dj|4vjH` z<5K=4GZ*KAr#E<;?r|N&`!3(JY<2P7c_*D{pKh`SF1N4V zz$SHRclo0nMKuXR4KuHt-4=T9(>`_5Em-btwi9h1s!b(wGh~F?+Sh1b_~>uwHT<}* z?GA(?jw*Daa9}=l=E7YdBvv3k-wPxgiE!v45RZA|hLPGsZfF}T6VnimBb`XZ8?Xdo zlbXqqt8TY&`BHfhT@XP$y_f^lZG|o@>*O5w9{2biz9aFmsxP;081Z7kk2n0kMo9Kc=BIUg+b10BQpoj?+^&X)L^2#%44UCrb z!B!-vaFY?pXh6$d(;Na-k?}d88~xq~&`F{rkTkjIm#p)4*yGFd-{Kho#xv2wC8@4C z-ykB4LnD+!iWO&#cWXY@oIi4`!YFUp<|)8@KnV|;Bwpatbs2@JF{4a5m88vf8cx5L zJegARW3< z&Opc(#qY?d!$sYC-J7Y_=v(_`F^3Be9$Y*s=G)t^?<)kxiZZmi(-sQ_k=vOj6C4`} zccImZGE#1XOg#A^=okX&vP?~3Sum?#rwqphkE#{at&IA?M`7}zpLovu!*AuMBX=r6 zI}8$O?c3sbWA#9@UP6GC+hb65kTc82Mfz%~PEMk#GUrEPQLXog>{V$f8$LUjjSVKI zqa-^9D`g(KLZ{rtEw71*8G;{xSYN|f>r&uS@0efN<51ZkDUB%MkFY` z43%ALIc=ZFD3`o zdNh9Hql$~6^Y5>B;AmYDKk_>GM*H_Zl`as{Tg`B>K+oD8giK?s1_q4aLv@Q{H#F}3 z6*|qhAF*TkuWxDxQ%kl79oEHfm5;^%oc^l$uzzBDn%%=aLsqwIxSDIFSkNPYWOoFj zg9JlDQ?dWpb^T#Pl{AaZs?_r97Ngh4Cm^_$1GTeBZ(vgLW{7?M4R}7?sJ|$#&8u%i zglP)3h3b%G`X*s?UCldsinb$T}igd%3-MW!!5@gCu-7nmJb}?_RHBL+@|ymJ#m<3 z43+hHl=jv1zann^y|1qTX$FF6qkJ{`sQ16|G*>ZCGyh2ww!5+%Nk8o0FKr z7?gGxfW8l;2b2k2!Wj;k^75X_46+RpQJnB&AgOj2MK<=P$6wZ-)=|Mk$n4olESCqA z&dj}9?QyK6U}U&i65S{H{pgI>>OCU?o#lr5`n$t+uDDYbVT56D&OW1AA|*w@9^BO5 zEP4Lvc|;pmz`syEWlg}{;9UUXPDq{fUFjk^QM=)a3SiO(MsV<8fuj=$4b*5nFS{K! z;@cc4^vd=wl8T*em^M4FFyZ|`9zx$(%l0AUr{|8}#geGBLaQfJYdKv4Kk|5u^Q+;d zg~~F1i}l~WXwqa3mk2rKW{0{eh%kChThbl2^=*DD&isTig!S{=B8M$?*~SDL0m7M< zy|1p-sjJ#li@vBI0@c#$38w(}xHHn*LnuvqCV+~_3C<2!+TXzN_=r>zQ#n!*u{+ht}XN`F(5HQdH^Av#C>@nbdv0kdMy;oh@*Yo+uLIq zmiG`RB|m3sx*w)p1ny2I(`jU~meOli=5C-xqIW=mNty;r0I+o5zsEp-_p%xD;q{&e zICvV#zMsd5!h@#i0GzmFm4W3 zI%E>bX=!R|Zf{mpw-4n~Mf^aOt9NbKH0L|v55eh;`?^~|@xS?huPo29Z;`;YtIxF= zmHlc66p$s^jFazw+a|!=XAnVT~BbAuSahetDary*Z!Pncu#+ z40u$+DbKl;V*=hf$IM@4wQn6SmwnCdH$*_%3EP{^>($KIN8&T|dWc$UpI5D90;yZcELL{y0lOJ!T+WaFB0@mpwV{rJ zpb>R>d01vi1>U&Eh`P)~%DE{UmD$Ex=;17(r7E#HIP!=r#nzAj7bH){Qj?C?R|+`` zARkt_*`td@p}KJrkZYKUk;RxHgf+k|fZ0??P*5&I?LlJ*0@&$1qM4!uh7dl>zq9=qU=2(?0r_QMh;vVj_@) zBY;SeQ!@ZJhs!l3LLNR@pmDW=RD2aQt=U_xk2gl9R#p6z5NhHfPJnMzb@f3+@oFM5eSYE^u@(>3ij&Qub=+s!+znzQa+ zz&x`BwqHnQ^z@{-Xe2x;=2uUBt6Vf~A(DlmrK?x!7z>J#kGCf_gn%SB5(TyGhk(*v zB3Ey=Ta)4*@K`55Wm)Yl_Z^t*7N>8^V@OV^Oxl#=Vzv}*Hs2VkbGyDgwg!V$Z%P&< zmxZbe$6zDp6+o>a@jw^$HZZ?~HEVKqHV)kNFy(+0v~a}2#Y)QGsE_RPWkr^DBbjw~=i& z9CPdD-h%`++%3uJQ%ltb|I-^yzPX93j`fGV_TN5(tf0%Ody%g9r&ZSYS=V#y5Rz6$ z@=U2fQra2$eVT<*$TQ*LCc}tbqj_*O)Nz4FaobqWf5)yCf*m=lnwD{a6{qvGQ7I*r z3e45JxW4>N5pom~9{ueGaupz&!d<>YvFP1#fz$3gf`%aS`W)5T*uJ6ey1B8lBN|SW z`QzUbDd~BGAyIPX0n;NM)TF<5k%ODDB^9MwXs9*8j?ot#?|y5gZOGmdXAeTpT~8wP z+=zFal|l$Wy*30+7vFRcHvJsh(7q=Q=_iD!t&M{)$@QS=~=C`oBc?!~b`8 zlg-TBmF;d*3v*gqiOl2WAYzH9C zo?i1q0Q*Hx)|!|gd6yJsb$QfHG5e0pmT085+)!x zZ?Eaefr1tcdkoQtkYNbg+edKL0LBL6B&ht#^nN6Lv{t}a@QA;W`=rr%XWDfw%YlAW z!CR0bCHj+)`Z2_Q48(i4uFy$O2suYbAJjaOkzlf*q7FKoRov?vsS1B3eIt?XrW2es zOUE9S{>205zM+w3s_Bk(&!}f9C-GSBrl}P>=BMKWh=VTD317#8o?32bSO{49)^f2^ z8uhqfaCQ^m>nPU3oZBhDFdaaUBh14maJL11`XM>Fab$l0>E{wbc(zvq<*f9DZIa_((RGW^Z9kG3u5n{N9+P zv0o%6ekc)W%*lw=TsBXZFt4kx=~mfyNbzBg`?FWF8XHC`*}GUf^H_Oirb}!nX9heg z1P71#2VcrFST?~~3O_C4JcW%Aj#u1oi1*S!H1r2jJH|Q$hvserl>8tKv+e&{d62$& zcD$-BAGH?Y#n z^AkE|!;*`hELs`8dX~L5AU187Fs7|8Y+ai!^kY?u_d5KRep*+crIv|5K@ZU@+mApL zQpEMe5AnAA8Lbbo$PHPZn-0dg*C-WcbN-~sOZehX2b?u|?EN1_4xKZP-(6g&WIr9> zXF~7FmJ1@6xa&JXV;1vvy^U%uN0Ps!Rult=a!`*tBq7W7s+pCm8<9%#+T>|WHYu%3 z8IPvW?V)aDJ<9xiB1GeK^2gsF-|m_n*+)0d+Hd;nl#9YO>xiL+l)JDA5mcE*=u6!2 zp1ZPrXL^i96^S{G_xjW7=@pQ?bNXCqLIdtXRg_JK_l3vw+P2ArBLZB|f^pM&cTWz% zB>OK|VnV2G5S!3+T7g9xuZMpX=_D-Yg0QblNIrNn8)+=+o1+K-A(7lS)Ajm+3OcgQnJGM;)iwpSG>KL6g=j>1@uHt6pj!WG?edD#kHnUp zbEe-J-Isk!JRxM634Mb-K)xx@ojOfdrJ0d8S6Q$0ConQgoc(?ab-ZsON(_v}2Ow2u z{9p7jWi&P%G}zfWAlgMi0T4;}3J-Svr<-@HPIaD58Pg?|3D~EA6bneld_h!DH65Eq zPFwvvL^HzHsC&OvoYF+-_xbWwjgN%c9C)yYkQQm*No~c;vD}&H7krW9@!Pf~rWlN& z^5SSqK4T$B*C8kTB-$AqXutb*f{*p75GI;xIJOGvOj<2^3#W%ks6J0sk~v253L;G# z^4F5Oo3D@WJUdS6=0DK-!Yizvy0Z@sNXpJ7*K;>hLk)S?j!UoXXXDC(vD;e7WVC}f z5FJ-vgVA=i=&9q3rI5Fr+mJ}gUq$O0SMK?P#zz;v2l=Pwe8Hzf=j*Uo!98VhcAKF* zGwk9lR8JaL$exd#dFhdknz0AtXyR~^`l|!z2>gkP3e--px2fSwW1IPM)aG6kCMRRL zA8I>020}nUfN6ZA9+F=ZS@fsK{-}O(FN8r4i8#F;8iTAzu+NPFHICBoDhb$XM*xNY zfASNM*eAXP!Si$(r@_02Ol_RV#3b32Wu@a{F{|j<2Tw;AZ{U@4g*~Mnu6!dM+#YZT zBIgtpK#beA8^QO^UsK8g%&jS5vocf=Gy+~J-~^hWRImo%03-1!tyFSy_--QUoyJ~} zlcHj8l2eSo57ShGP%(|Ck2xZUU>EfsNTjPo64~1*S|oDe3#iLDzatah%%Pp^Vo9Oc zP=s(eq9C)_CL?bq<&V$dNq&nom)gA*jPG;Aj%9K%e=x`$ax%u@eJp#Yq&k!>Tt>nL zMQKr2bbdQ&o$2rW33TEmD6>QcW&7ewshL-Z3;?eW_G(Cp&pG%cMn+tSvWuJwa>JKI zastDw2%WZ3M$;DrXGP^XAI# z)ZLVqgLrIQ@WJ2D{urX^Utm>dW&B14lT>C#FExWJhoiJjy4*10f2F8;9Ax%@O(Glx zb6`h94T13obPK6xli6QyJm&h#T8KWaWLx3!Yah{C?u`?G%+<4Y9 zc(b5<7vxo}Bm1k&cXucaborI@F~xRggpJy0vOmhp_X)|tSPAoHZ<{o7iPJ!2NC!(* zLNP{jDVlIK?&AS?*UE~DBBHV3Mn%)|@I`xvijgN2tb(C_E08jLXrpe_JXgmHO$+we=?su2}ynDYI^A! zG8Xo9f$_kBcYRujP6kivVz3$&!83%v5qPYAAbq)^dA{RJw|u#BW+Us&i^MV)^{f5J z!L$(&e($owmt{^|b4VH9NRE3B!CFT4e zUN$D4A(HYsRFzm}VjN+IvEX(S+D4wZNeZGV8EBm*MVzdni+v|XAS1~))W^Pkiv+$i zvp8RirSUT>uzw{vvfQO@_FW`Ul1XQhZ*f4uTstgK(g3ruk`p8nct#6LyfxCNQ z{6o!;_rsvb)(a_T?@iihPDC1yaX5}i1e_WGfUa+B)ba3m|3?;TqEHbaTua$B>f&U4 z(h4>^X!+JD(n;ohUtSI+#DEZ>CUUN=H&v-NSCJ}amJ>^a(po4#6l#`%^aa9yZ9GlF zy&k61v+aTYd(N)@v)5;o^`nnu!Wn-@-WVWnT5R1yIEmzK<#E&@g+#g^Uwre_E7$M* z9)lI^Ntq*EjRyUIxSJ)CZd=p{IgvM=E!Tf5WgKX}$OjmYsGAHZSUtv5v7X(PK9<5p z7*lM6x~FA z(QIPGdc#{Sx8wLOwpbSAn)xZya_DMEVm`eFr+Jw~V>-3P*De~~<{K<;ZKeIhTel(> zjPp=B0Z4E02Z;Yzal6{kU0dkKI2jkF$iV+bU|Xb`Jej$#ux-B zG6_Lki>!p%2rl(A5Sk$z=T07o1grU;P^wg7Dc&V-0tE{eiPU}yZzZq}yP)D0&B954 z6lA=KoX-AxaT~?d=X(jiR5R(Ik)o{L8~gfLLU12F^+6!*mq~K^$Wbkgg;_WieE&o<>2;XMxomm-}r+%AalLc4oJ=^(EAV7y=#6(m?m#wt$x(D zG7w056=~*+&B1v?&mY~1NaTXBoS*Hy4f;GUp%qUo5iO!d>yZ+6P&Wj0!%`3QLSYi< z#7+auYD5)a|A+XYKZ@yJA45R5)_;9Zs3Fd?jrkChiae{3;!pdf=0A@JQYZ$&8-6uigd z6j)Bl6$wryADivE-t+pCz6T@7#iQn`B%);EM)QbW>+cAQ@2b`4TJk(u=pVK5l#qw> zsjYeqiL#!*cb8J{?!)z@CZQCUYyx{Pn`+m=ImNjJ5mO z&>Xwv*p+{I?{`1~k>zKzYoVsZ=kkxR9$+@RUG?Sej@U`+p^%yHgPug%{ph>hF=!X> z{5sb`zvNK5#T`xrp-N9S?Byj&>B+k~@R%T7i+%yMdS6I=|3p|WIugd7vF%l@>`zebI?odTo8WG%ih}4rM@-^__ z9WMk+1D5-6`cW^|PcUIZqbNSClE^d=h^T%d!W|O>gDo^YBHtqEzT5U(5rj(6 zK!`qdx=fcuS_R|OgVkdsS7(C z5Yy>3|G+hF^Dbxsf;fV9!>gp4H)n(o!x4LAI7aUzA*b?Ad3bDs34O`XlHJ123B6~c zeu2Ap6TaM=8j+C~6d0@HF`_KXA#fGPv12dqCbnHY4b zAPPjLwn2aIlPB^0{rxtQ*htU%B&ea^Z7;w@D)@>9y51y_Vx^z|YQb(2IZvjhBSASu zrpT;4=0?uebpLrdt{J&egQGr_B6S$pex8gsnR+h=DOPE`)jWh&|E%D~C=PLJCFo#a z53Mnbpf+?gqJUN8KM@Xu%k9vct!pxczqmB!@wAddJ+~uN^-wS3Q@_elV*LYO401k* ze;zR34WpD;3?9DU|Lt-*b7!eUx(TcH)p{2!`^Gj8kzN8$$>mNpR?FijinH(D?wwdm zKj6whrwfabuiULvH|q#GCqVRD%nsKx^qJ0L)D0}oy9QDEpFOaodTgIu*lK*(MHr-& zxHV$aL6n?*2l8WvV48lt*T)w`oS}vZg3^0PwK-KJ1Q2%48$?AEjtX^Tm@LMMwv%wX zUTTj1evDnfvBUy@j~kZv__K17MuL95Kbh#S9Bpt5=_P0)EUFfZvsYDj%|9fX0BhB*0S( z!0H6R0c2<0BEf$Za`GwBM*yxP6u+&%; zrOL#<`A{uw&<1mYAOGAn_zv{vu%@qO zgHKmv#kkPf@DYm;&RmgIbA88}^h2zhf2s5ANhg+6h*fR0cgOi0Pz>X_08903V&osy zc5J<&T%uVx*=C^qNETT(=3jn#q0pFvYy1;DOLs7Lv7IG zJTqEDi!f9Gv=5qw<1Y2cQ`Hmyowmkv{{>h9QFG^Ac{!-~$JHrj*7==`C?IWpTCs?W zTdY8@4P`WJkfCcGea=T8%M`FrV&x1<_E1Q=hnd)b_jM}r((BmNoUgCZ#AZ_ZoT({! zh>O5seR}f+X~zHI<&|oPuY8?!=IuCy*Qf5j>UbUoLlsXJu7?v4MqMFbWe$v3bucc+hE`ECaWKwIq$})uv%bcLb$bw2wq0WNW-N;q9s8 z*(m8s{n{hqJ8^ti6Z~spdJ)gugg~GUL!%5|@-cnBF31}b@j)}=<8(XrK%vB}D0?FR zK{Dj(LTu?C@*7;y(lV<LUc zLtvKEg>WprV4QiocR64v8>daJL_OKLxPYvDk|^$JyYaZ!Vx3#R^?TmG><|a`>N#s^a9GxTDY94_jQy$OoBHv5SpbZdA4J zIY-;B=Z#O`^<>X;|6)Za$zVkgP6t{fTub(RcL9Ukp0bNsk@zSo+6S+id?N|^D2OLa zQ)ya?q^Ys!LWTcp)Z;mC282>rcT)Gg3sOz(1JL$sJt{&c7ea>i{!7 zRUKIDfcPaKwv+8`{($PoB7 z@o}S>*L-NF?Buc9nfQQv;kd+%Rf-y0#8z|NE9kqwuzAru+2`26C5dK)G2&i0Xrps> z;|P*{L01S)OPDyxaWRmUO#tJ>L_?u74npL~ObApqsw`)+BBan zObLCxgWq%ixjfNTR@Ii7_?s#zfLZP=99DT>3POrwrL)HEgPYX3dFE{^>?gw?T%xA@ zXtPyT4Uso$88!hZI^XX#iUyMKPQ{P@Bx27lF6;5cNW5E)F+I0ymRDbC5U;Uc7G>%g z@`pBHXMQKY#Jj0+PVQgvVtv9oI7h`m=XSYlR!w6EZ&|9m%U@VWAyBTr?RY+poZA5M zT^Eb9T)IJmSLDl<$~b~4tIeXURwjNLyl{|e#l$#1a1JC7rwgFLq5(cl-q$P;NetsE7}3T(=^iycK_Sks ztW-C~BqByqkz3Q%uUDdp3N+Na@K*6*9^M!oRumGhls>K^_B10W6Phw@t5AKR?a_p}^$$xDKTuH0!9q2GhGI4CC62fC!c0XC8WPp7ga9(v(M1deg?Q z1buT1ORBIR?4#fOw5S}M7f#f!L`)302SjRhA5NQJ6Cmh`H=?>tQjf=MU9SlL_$|9C zHI9H={sEc^a+@Lh>4;H#b6}Yv=@Qet)p_2 zT$mxdt~=)@&c)<)t2Yr4WsZY@&@o_3<~{IfKZJqq<)>Q@fzP0-8M06Y7f3Q3s0lSc z?Unhu7{87kHSyf)dbuZLW%5(ng4BU+wtrWj+xa!>c>O0aD4KLYRO>vj`i1)BN7Id+ zj-|#Q4VvNp>PxSZ)Yw+c0AiGE@%k&6&Y`t_-t{Bo5jUz$C(7lmuz4?8eXqCcONbn@ zgsZAz(tqoO-|hkrE%j<>E!>g{QX7GQGH_z}i1;&Y2*Ym}W#sob*d>&N6#yIu;RXEE zVJk`>T;{-fkq9J*ZSHxQfmJWaMj%li*>^J`r8ekvBDc(gg4{>0LCCD&zPd zeLUjZwS-M(@e?dda6vI}&wRMWmzbjn9I74>=5Y|TPTG~O99I()EBCz7<5~kL!!2ap z=AL2eGP(C@>d4f*p6F0-@o52&Nb96~)Fa6kZT&_m#Ks<0zi-G?g{cFao-wd@Ea zFxxi2P_7&pnj)%Qv6csWg>tigm%iebnV`M+9o!K$H}@P-KibO4GZeNW27(5kzfR_O z2>8eVvp5goK}e_2%3YlrSvH>i7A0(br$gc8Z~DblFf-~#QX{0-{x-52V{J~k6` zJ{z%y`OU}GA;fV?NROeo5JAogX^vHD;V#R(dcgz#1%wg0d`t73QtI=-jQl_4V=WYri|Z?l zRuq7HW9Dlb;W)70aOSD0sS5y70*zcR)*;Z;Uo-AR!J=Fn9vujcn1cEh`k&XH0>V`H z{R!Rv;L}?gsNf-&VO;A;q9w^$C%(5Np7`FJ!SF=`emPHo$5(N-m(d^_s}psd|B2LO zNl1VtN}4WY?Vi}T@1*?rbf$BGO^d>YXtmasMwkV^W|1gALrv=bezbn!bY$^c1&bB{mfMlivgFdMuP`EUm}K>>JS5AiC9m2&%Fr zNP*?o5Z_=0jXdCXf+Upxtcoww{Oshrwh(sN8O`f|JM|$1<%K zN)|YKqx8UP58v*;1<`@ewKO}Q0czE1t08}30`Nh_( zVfjH`uP8`!umkYP$gJe4O&UVv!?noGWTsL)`#ur`Zo-wslGFoYVsb@hqdh${a#?-g zFssS|HlkJN$13(qw!o}}r2p-?7RWJy{5<&L!CZAk>xlXZ=vc^FfYlbh))u}xWqRfN zm7UjiJ6~5;%Qx%y*0VjPe>7J#-`lvwr0Ok)KtaJ$k|Uxc_NKe}L3_a2#0^D|kt^=G zcr3Pj=N{eT{*3V`RIcea8g%U2(BgXH|!m_kvmt5C;@xJd?D+a3T|O73v6k6I>8sX zCWHnfsOZB%0rr>cQ^~f8geD2rg9!}5_nQ3-x^L2jy3n2{l&$*_o!*)`dA_r4C9~R3>E*ByYiCmrqvWxH`qt4VXI8f$%!m>Am-0c6wO(ecFG9USH_)WH>~-m!I*Vj)g64vUWWD1>q~xm?V=!ZHbE+7dPHtVmCKm5RO0{ zq~Lzt>$X3O^KJeKH8F-f(LDtZR{kZ8Y8Ff>GW!LodAaNTBUqDlXH5b-UctHEHJ}ce z#lji()R9b{rb)c+=()I_vqI_)vtIQaNw^p~>BToQ?6?Lct??6AMpsu^5uJ5B&`(4r zO;0Q4mgnHlttpqsbQ*o^8T*}Nhg9FSG>nEU%L?8uO|Db1v90hmJo>>3IrWFj?_%ME zjcra(p~B;;Z?mUED5R-=cyrJuIaIN^;Vj{`Xk3Q|dyMYZQDg zx2muZRGH}$n6EutIYcCtjwYqKSg#dL(uWU?ni=aibVaVi39PN_gJ#No-tf3VnsnZo87V-L#$F= z{9`_&? zHHlZ54uw8X*@~Euq+~*qE90n=!dQF$` z$;0F`9y((9(Xk<7vqrpyNDOB=T~9|@a(}Iv{!5kZ%)wU6-kY6k{CJdkT55Yi%w0Fu z%O8ePH)IrTo6*@4FMAr+n`FFhUTxr+KX7-%^Z;tq_%nK{2fg|-d<)*PdC|_Tf0LO^ zZ_V*OLd5Dy_xP??KfiOuAJ$2@MjwMNSXP)AflG^JaIBmzQA1bl^EZknfzr<7#*6Z4 z|LgOG4owy1DM$VAFIcezRLRHk*bg~6V%ZkM1Vp$OiRxH5hF{p*D)dfBEYp+UR%Rkr zy*E6pl|#1KTqPF0xNBfVCg;yLvk!mL>>&)s06vOR<+n^ z<6_Xefr8=wSiZIJrItey?!#zy>G{CpIbz18b1B}YMO2-Q6n7B?5=B2NH1cPx=sHuW zwOmryry~Fa0JeAQd@>)DW#l{95 z;(FjNhv*zg@POS5mcFuaY3RXtMknw9fa%zWWDUmZKN@dKj<7^94i_)TeaY(focoj{ zN1&l7CnJED73Q(cZD-z}ehf;Lqkx0A43|5Qk^5#zL3sY1!#Ux%R#pv-8gsj}+YioAU5wydy9bUpB;q$q=*>sXt9VOlV-ZIZO{mw5{8wlC4dABsqE3Ho2aippc&;W&E9~xeCgu;&ZBJ z{x%pVK=8I6X9AoK_#Gio2WBDw36)NXC~z@=F)w(IMM#49(qG)Pp5yQKZ;(9|btp|# z;ef`$QkT}2)&W(I_BH93x9O#{G5W+Mze@)RiI=upc3d(GU4GPa#&YZHF*0{UF)We- zTIgViul*$81;oDkyVxcXM?XJm6;zV*C!qNaCn=usrriJ zg}+9RmvkBOQQge)X_oOrhz2g-P$N@K_jrJCqQXJz>m}f+h+MKpFbb2V>N@$9%wlb9in078HtckDCj8D-Iv5d zm|BN?M0IUC5d1TLPij4KNM=>F3z|Cg+YiQ736Y&nuN*SDiqH@o{l<9|Z`DZT24Q;feL&^Mf-sW=vM#m8&aFAxakHQ#(kDJsYu`3@>I;e-xvrd;#!!Yp`lTQm+bVHXveAQ{&|aI zz*?5exnaO@mU-y>DeZ}{9X&d`@+}x@zOLP)f46O>r*hBjZ^AW^2Fd!7q`Z&BSyoaz z1|H>`*t1VWLiYzGEILO16wd8idOt&%$F4d(k$x~RP1@!owsCmbubj*mbfqHExMr5^ z*U#0o((!!fbX2X)a^@v`mFeyc;7z0OWk*)ed)~YHd+*wOvS!%b{H+AxDwfo4XdtMH z`g#6fhv&&&u&!#KPSFv}iqCT|I{4^@U!s47=z+@{dwuS-%JSpx*~Rma>HPwiN^1+U zh#H+$hd=6V(8F)ym!p`tqSa=WB!L2@J7jMQj4Q`s5rMcINJ9a|!o=0(IjCPA02^NK zG|kK3KRPv~03cy6)qMaQkvEulmM*P$Kne^ zf90S%Ej&NLjCgpdw0`k%T|%0U!Vm6|{em}o8}(`v@df@b$JDY>ix14*`B`j~KM_6A zei!qp&2XYV&vQ|^WMUXb?R#d2<%R@TgSi)jgxz#chVAkRJihiPp8pUHq)n1M!+Y4q zy*TX@^YO8c@-5-uK19Ad0&j2A&~ySp-uqL>M>v7yMR-*Jwdnja^2Ke;>G%~ZW9B0C z1F3-3x8C8i8jxk*Cm^u5%%gI^$ZT@^kYpv-BB3X$kmYf@<^fYz`y{~7^F)HcF#lm9P<@%e79eSytm_@|b5H7xzpg@(Q z{D)9d2ay8WN}(#oP}~GZ;CmyTvSi5ppfEt5sH}Ax8IG3wq>|niVZl_z^2PoLJEG}t<80oR zIMT?PI!;c`^oVBd>Bmpn2EO`G4`^Sa z3?-*rY0$(8r_F&1Q(Z$t=VxW3eq7NiBf`cWlO=}3n34hg?O&A(fe(NX1;4l_wLe1h>0`9~Wt zm0^v(QpFs55kv92ql&kH94t+8mG1g7v^RVw{=uF|) zdPxc9$ARYkfk%nx57A|1Xhc} zbF^`4e0ts;^9drzg6magpl)7A<)l3cth4ZGoT;(AFIILyoW!mF^$zh8G$qGYRWQ6A z7lsHxB5Qo`3HI#n@`HsMMJU@=w~P$5*CEjsMikHh$uU{2$CVGsb{Y-t?6XZRl`80a zf#wP+a?^)O14ZfZHliSmJBE7 z11UOkq_p}2J$LQeaAYVRRMD;aAyk#*;EOx?Q-2YwM*Igt%x5l3>IP!;>Jx*E=B_ic2&vfqY1|yJ042{QMqnUaQmsC(T#ZV6oo2;(EReTn#Lt9 zAJ7tR{S43Vh@i}A+=|RlzU8UrrHem)n7^)r5Z`TmKOa)|w5=;U6Dxy;xE4fUhUVu# zrs*L=Gb!J}ICVt+x3;W+7K;i3Cy*oa*Xf?;9=0y6%HOC4@)7Rg;6!fe7 zHo_Fnn6^oLJesQWK#IKFbx(p2LRxT{mUVpKaW_{fw!uM#YR5iZGVmi$2)*SPFDv7O z6T-2Q4EOz+%NS*Hc9oXZK*Kv-x3SZ9~WyqiT$>spu;Yr z<=z_;US1ur#{F!o@`H%7%p{@Kgb;r}vh&U{fm{FXM@WE08s0f@J|Uy9zkgST24m=* zj6vF*oSfdmKLCo-HgOPtlbDX2N^MU+>y#nC%o#&#g@WOG5=qfYTs>5Mr55qZ3&$+s zWA52XLq*R_E1$fvdFzzgW4?HrJLir3GkVv*gI+Y`gSjvr+I z^CGz8;scCBC-XmPEG~$PDcc`K)z%Q6drO5^2k+0jG5cE8ate*{f7T=Y2HQO**}%1Q z!1k*V#3AS8gGO2V0^)m_KH98llLAJoSc}bw_lC=VUHuqDE?o?*pAcT!{c1K8z-MWK zIFKla&Z&26r$xk$b*f+hvudq$rxzm5~J%A-A%;>MjaIVlPTGY5mfciv0 zUt{zgj>r2Gc$#_r-^oJ#vN!FPyjxRZcwUwnzrf)H)xDO5h1^_lD5dXpT2@Lnk zua5^Cone-R1ydccV=u_m0Yk2-scE5~ct4eh>wG*ILSAeV?|fXRhfG0%I&`E^4e*vk zDFA6gJrW^ydxzgO_U+4n>>8{nQj$_JV_bs@bXK8Cm_H#RBi|bYdr8?=SeTefDlzl( z^U*gT_gwk&O@pyWgvCO8Ah=~f%<;C>ECSp-Y7?xUcO@kWY%dDz)gmon$8`~$&_hI| zgutzmrps%s#>GB&B4a@nIq50+nf<{RdG^U1<+Ox%4#te(FXRgk9Jz)b;xZLFWNt4m zS}YaB@%{*gaHAl@Q1bn~U_F^J@1R|T%hhB_Uc(zqTvS$g;L2YWP7~4I`U@QGoDoQ! zf2|Le^B4T@DI~BL#tS^H12eD8XO{cS%)gDQ*O_FSp zDyeV^tH()j6uul=(YqdHw8dKW&9PEOkF=DpCOyu!|Es+Wmvk~^?!O`}w#>bkN#IwD z!FK;Bfk4(Ryi{0I1-D9ri&H~e+6P8!d}J6C>y>;sWGyk$*X5nbjOE-pq|x zPu4@#R z!@<`Qed56+G}XMb}4ZS#g3?ZG%4=y`Zv1Y zbeC|SF7&iXU(!)o4@kmdd&6{^@m3d}dXw})yL8XYuH?zG^aWl0%fuhQd)(OAEFT&$ z?<>K&8JKH_KVEtNksI~)=~Bl^=GK+eACzA^=qE#FM|FG1{CNp+@p78Td@2%cT25=V zQ?V~xgZ3y)nN{4Fn2CaaSL|Q&-`cI2XT}bTR?hds?!%4Ax{j*bj}|D<80I3B0${Az zAz3q5weF66iQ zq3b;J_DUQdu53Z55ZWuouZwpMrieDJiVTB*M z751UBdtqS@<6?VkZZSK*OXp3+vDh=Bv!v=dY{m#<_p>H@Gi8;+A36xJ`J+Tl`GIdM z+TS~GKCf~bb6?mGC{zpeZa=h5r*EV2zPkMTdvmZr@Qf(CR{8gh`!4&0 z5DR8R)fTZBF(D=FiinVmjGNFQ>E0+``w-f}Au_PQj2oXJTIG#ACbcp{IaE)TT~}`I zEY~GrG6r+p*74Parz(;Xz`>?a`%uE_Is?us?O{NLaMk2-V7B+XZy~YwG_G6T$aiNI<|n-Tx1O%}7JC3XQOoR3eCb%5-G(NR%Eu${M##mXl38QbD2k zyk@|ZSnTi_(o5u`EkrI~uluS;m;1#7Y^fG|;#tqnJNdWim->W|tDoPGU5Sx^5&!x9 zA|gGD{ZM=o;&A(mmzsgYTcH-1Uaq161FAt?$U$m?cfr&0@E}j*J>E{ozhSq$jM?K+ z3@qjD=6#L6A>KfipUYmqBYjPtNN=3VIATZz&r%8q8KYZ2F~eWGDote{wy+mxC6=fb z;FPpoQ$G1+Slwf@XLs^X`kL-3-g~zj68LscP>UU8ej6{}PliW~p@f1ij8!&IkA8)Z zX<&kD5%eWYA1&+aU(!S*Xhp6v>r+WYY|D0nTBO_$SF+;K|WN#umBqMu^I7!)i?^Ria>?@QC$;>P= zLXu=vRz^l<{9otZ@9*({JnrM(`?%e5_`E-__v`h1J%@3{H8a>6eCX?g8;#!^{Tdc9 zBO?sZ(hh>L{K9lwI57e?d4#qIW={mD6w58-A_LJWRTnCniLT*Bdt)fmLjU2y+0vc>ajVFAk>x8XAZP$0m? zK%xP$eguCu&|(2WcD{XEA}s|H2qP}BXIMq1MF^CddzTk+a(U)A-%KyOwd@@^DC9^& zm-?}#eA&4q@v1Z}ae+c&7&b*s4dki7!gL2VEK4BJ!qz>aqjp|bV^gNX3Rmg+1Ha{< z?zFxyRt~bQ$|B&pO&_ID`Anj(zi+6f54?60V+m*KN)4JpJ{*3>AR_$9>dS2PyyC6UJ?Jn%J z2NijA*fVfx8Mr1+DZTj5Q+V>2CH!ntqHR`Pi9d6ca)P*Y61}*P+eFeK!S*m;g$mXm z|G|U+4mJ1WshoT7Wbjx2UuZrSW}==#0~Y6~JkDBoPVpqEa^kYx@K%cLLPJIve5@lS zMjK(MC4d(Oa#cp)gNV|=ghq4t3B;WtNJ%r$PXyFmyA3|lME)v&r1j%(ZC%~v-kKgf zJB}P1_X(n+JH5gI%I&QwDsh2_EuhB3GeE&dl6B&hQ6EL*Qz5CXcbSZMscR?vR4_ZK znjEG+;|>r1Hny}Jk8Q@%zE=wKikgy>i-D@C8q$Q$rA*0qS1kuXp{y)YU>t315_`Pc zb=;}X=_9<6nmJ75!CV;7>+~(Yzxi5OGL^FAiD{GM6?>{1Iw6lDcADoUu~InEB!>%; zX%LVYV5RXZwm<2DTm7O$LgJxl^N!V2>-%B-@Z7KA?+5KXOPs8;PDMQ6g}OX~ACuA| zS7i!$g%19`PcxfZ>E9-kb3J7iGBARlym&EunvIP<%7(b|+ex7hL@!>@KK`hxq9ds4 z+x0Xdc6WdGcG1q&fo@?AMrbmg3psASi{IhKlWWP%5Y`wQ_r|;n6|`7ffO)j-Cm+XM z3Aby-XitqWF2S485u8q_U^V6p6A2idWasAcB6=L*fU&=H87^4}=8cHKDHyRYf@zpi z-Q-<1AWb3Do*r@IM+2G@dHhQ1xEG(?@Wt;<42Pu_8j@gnrj9QL9K(OD$>jBIK9mx; z7>Rcc4iBrgawXE!ae?T#z#t!n9O%VIhKIw6$f)z*ykP?kGQmRj8ZfzZhl_y82}LDo zF2yCA?gMmIm+vEJC4kg==&oxkdB&Iy*_#x$Qh1w>ZSz00nA&lu;6E4j_JYe~#&Y#W z6(p$-N}c=M9C+~dW_8mab8rXn`1R1u(y7GCDo2562=A9koaWp@z%I^I zw{BaD{z42o@>=%hq8%x{q%8)eqcc#()WUB^In8M@$hhuo);l`~mQq6lOc7jpJtGv+U;4QPm<+?Q@yUm<+LcnprAvhUV{hFv7073`Ogv*YL`idH9HlCJi z^*r6ae$Rsml%24_VqnbkBANN2lRKpbR7>MOkC*lcI~g3rv`-}${e%|zjM`j2Wp<%% z&XtmXiXiL{T$@3wRe}>N7a3lBX{5Uex;92NFp#68GvX}nlLFHe@vamQfI$4^mxD$w-1>^)*w-nS#*MPMW=BCU&HhslpP|i3u0^QPEl{5c z98Yve&aH-WacxRdLjO!y+d$~wJvEXg07}5RNeq1!$_9u^(u*>f+1b@Vzzny=AS@6; zenME*!{df_IzB*%y_;YT4NF{m(^HX`L}Zfax#HsXi#EdPNEpwY zba?DM4>J(E5NUFc#;w8=2Ffuqc_I5V#PeiRO)N^Mx3eTNr4^{8yeE;tsFuUtsL+xs zmx29p;~O6fToR+&HxGNLDoac0@44^N)++3umuub({+%^(tD}5Co-y-F`1^Gp&#uz^ z9R7$~A$WGO=QV^@fUeu4j=E{n=y3jGOM?F7q3F`IIOp6+RO`PhaflQRasw7;RMoOx zGyU_+e9vRpa2(>3Jk<6t`{&F}X)`<1MQV5PKh-O)Kk}>6*-`4tYXP5jxEN_`DDW=Yed4<`HBcTRRZy_A2Hp$7<=#k0N>Wl4 zbn1UrCn={>qOE}{2}J%AFc%XT<1j}$do*Rr*`pBxk{H?0m51U&;I_)<@c^c}_N+R9i@Os>ps#l=xopS-Y3;18C#7*eV!=(G;VBzS z`46ESfA1ZbX>s{?>p)P9N8o%g3TeA>S;5Ed@b&(NVt3s9)5uGIh^3Zy#Rj)-Fg+Pe zPCVW|{q=bH9HPoFwD&Y?y+aAydspET!q!x{Xiq$T#}FE70)$^+6* zLqjtJ%G|-u%0y|jl4{43m;?Q?-rbW<79AcC>X>adzm(bef_v3s$S)^G3u<0oT)k){ z7(Ei5`Q2Q2epHpuzr&yJmB`}-_+d^TC`6L8{Z4;zwWT@MK!c9 zI`7W)+QQuI)&JUtxzF3;!Ie@O#Ij-((05(1fIm2vx%Q zR<3?&UhUnZU#-LHOu4a4P1CxEi}7PK->;Q&O^uVcB4Sj!dWB|QNLK+HIsqTD86gAR z{22zVtKqLb#dQoBg%|u#>{c9(Y0}YH5@ZnkcNdk1r5s?Caxh(ru<1y`h=$Xq#1ye{ zrJL@V5Q|%LVV{I}aYR(p(_Y0!tlJ4Md3@yK3hv8)vYaZwAXAn{9Yox`UR^aP+r$uKM9HwEn5s4zf?HP6a6@;?@ zjUUK+i4izn84wl)Rh=Nahd$zmjWVwa|an|9^#GI5b~+-t)c^2e5wun4)cJ$hY|#Hb_jJp7?^(saP6HtR@Y zW@aX&!+in@K(1G<^AI<1dBKqDDUbm`7{yE{NRENc77qet1ttJskplc@o$wr}JA{xc zx>T2J%nAD<8)kMyWk3BR9)DJ;K6na>7r4w9~i_Eu3TQ=kOrKbb3^e|Nmy zWR944mXvVm9@J+(BnF|P-088yZB5k_+toVGOA$(H2r;FeHp@+_d1Y+7q-EkB2c2h( z_Sdq|V#=Yh;n;`G0p~0?vlTnvm2RUKD356jl`13lKi}S`eUixw9d>&GxVD;Ej@pDqL)qGN}5 zoYs3d?T2EXr_Bc23~TgefxJFoR7sC0%K+gA6l7nm-~X$_Crm->yum)=`upr{)3o zTLi7}pgV3#yo^f+e+JgQd8Op^(WyX03QD}ip=KDKDwc|Q-SCjy> zkS$22X{M34L;tzmICI{k^KZ-e$*}%SG91C@pqLOPP7j?!oeE9;r#m!1F40L*+n@wV zN$iB-?3AeYc*gXqGf0L-(56bM>g*L!#qIK$eLSZ1yYAV~=pR;;!5fhR(1pP_Wz4X` z>;UEX#QTKwx7~utz81iQ6Z2s<`7E=TGys*;xnS}81n6u~d<@Ht&=z4 z)~99fTN4-H8fLcph-W{gk^0Z02(BVk@h)da$0(J$8)99cg`Hbu8`_}`3n`rGt5Cvl zCcZvzmmm(iv#Fg|r0<@f40f9bnC*m#&oFq-L{AtQCKI)S%3P;74VH%=KsY+J{TgzJ z?QBkB=!SCFI)kRey`rq#zl2_F{P}42Q*aPbNeiRpB@!P#LY(M5^Fb&> zI=8(>iY;eEa(ayocWFonb}K#w|4e1F6el|ZI(x&TQ#IoEJu(^+&*<-@11IYvSHwC> zYig&MRt1>Va{>8HC`g zlmJm>8iJf~ba=X$pBtRritUiu7 z=&ZH6n6pY2p*%b2Us`!tPDu2#qG-94Q+?X_y~fGjmcX_7`q{V^(wfq+o9r3722hG3 zE^X~SCaUnK>x$-R_s-jO#R&DS4Dt|@VN4FroSD<}2)-CL`)7`{2qVXNSD$G*dG^uT z>%DS*o0j80M4p>~ybTWoo;Y>RRkPqx>sRvn&Ze@Y6*Y(N_>AbF`1gb1Wl3^jUluH- z)A_VK#U{gUv4X!?l#5iFf=|Gg^n||zB3Uo{4INJ{=atf#;kT z3yc?PUpcA2W#Gas?hwF0|8)|CLgyW5>!6lj$fqn#q{F-V}+{h$Yp2QIJp+(H}U^o5*AW;nP3G}`( z$jJo>C|M3m{l^rV6Z0A!Z~V6k$*`3siRDX82G!Jm1P%&#cCANUga%ct3meh;KNVk! z#EY*lUFf0i#KaKTeK3$gC`s}x9@tO>^arTcu=)W1E5nz3ggxBYvg?^NxU(SEp&L(d z2z({^ri$&{<9Sew$8AKZcBIpKjbB@MTD7eI59Q4d%1NTGgYn(>|5<(>njzeKyB2&1 zrXeLM@bIhGz~9s_Bb$GcPYm4p<~!dq_h}%Ilsj1CPM0JBZdH!cW>z6HXyp?X2t_-dj0=@K5`-;k`x}c~N&yemi6uD_q?lloBs}N}MRU8x(Tm{oC`LZ>WM6 z$I24)-ex@xotK?Ps1n<2PJDJ@Gv+62?^n6_A+t!o|2DhgJ|F%!%yRV4i7;5%feyvV z?O@Np-7O4>Y?}zKEZvLX3URmY)vG-~BmI`YUdlKw$DCr09M&Mu>|Kw^S(ej0Kz-KF8?tk zQ_pk)*$=Fq1>b4H4;osAg2u-LA_Ck%luRN;D-(5^q}h;Gam#iK-;W=V-^m9f9ER|t zFiMep$QM1Q6DoInxG5ORqZbnA#At#av$zKlGPlrY8Qzy{>A+rxZ)&G-o1%>kCM3x7 zgHSanA7C|2K-+3>O;Y5i&QHMVIzb!+s$Bocjm;`GfKd-Fo&cIbTqgHKEzl$YgasPK zu+$>#YwVdx%TLRLnG%fVSIZd+Aw?Z`RWZ9Hl@%*9ubfFMk@GlVFb1KBpbedR_TnMP zwzwixOq>#>ac1?Ih0k6J_xgTM)$~(1oS~U|0mtFP=DvQh>Tx?w@b}~Cspg|#o4b#x zHV`G z*_V;M&-WhQn`4_gI!2IY#kz(SY%UfwjAKMvZ58#;geg@pV*E%yBBC^%7=B(`EKSMh z&*gKWYdq@#^+{x7c!O%$vg@{&w|nBvy{Bb4&;y#&2SYcxZ*U72&h(F%q`6!JR_F^x zAL^}s$@RRcql=C6H92-6Zv*-?*+loN?ls+XwzkfPQ9@y|M!4GhTV(>jxt(nLYqx;Y zo#QkK;uH>SLjmR%9u`u1Hyfx}Si#^$HdH&;>;9htoJz);+Hj+luhGl>tNDD-dB0s3 z_!;eBihB;?KG&t|0aIt%#UK);Vx9dgz-sJ5DPXt&N?U-4h}~UMNw;LXfWGR0Xx+V zTuAW!;^)tIZtMkQpg}=pBKyd3W`3IMbnMu&x8uZx7w$Pgm%|TBu^_7rA`m-rRS1Lh zGtWJq7oVtoy>*hbl>8`p#+b@DUUNbc!+eFFdoyWD^ zT;S2w{qW~_O7iGLFv&7E5>oP8K;e!^_rp*=%I9_i`l0XX*OwHS75~t@mRPsRypXce zR>Q|+Gw|(qyFhiYv!Lqmiz}S1Kc^;7^!*Bf2r?=)R1qhVhGlEMl^+tyOeRga_!^x{ zq%w@9A`&CUN+G1k5BGv2Cf7z9vs)FuFUeX-Tv6z;$hCc}LA&R9Ib$*H6ZvYi(!{MY zt<3dHLpDFJ&9h!GU^GWV_a>k_pXNC)t2Osk6dehQ1GD`v% z?kmhzRm*<%Vdb-Gb9#a7Po2-dAf_#&PY~MX5gEdKkVuyOp;{cCKO@OxaXpB|COevQ z-%v{ade$9@F8e|0%WTB~)3o8-W}L?y*(D@1!;PuUgLQH@D2>NO(n1zSE&(pMfR$Eamg116>GmzrtA;LJ(r(Sw-9*Rm|Zk;27VcqCnYS#`|v6fw#$yCJjr%0Ilch%hmy zy|kgdT1O=9QD0wzO}67th~@dLXbIeqG5XXCR@RXj60*pnx>b4RFPj!yB8!^t&S$pn z2%&)Cx+HzhVh-_JU%K90FvJl5nnZB+R|4nX>AQ%x(dBE*4}95mf1(yil;)9J4ZqVr zzqltCXZfgir4)C)d9#uYl~7=m8|AQQt*eyD5BMN6Kf)Hm!l5Hg?NBb@P#E5N&Zfjj z*};)iGTot%!O0+3sLhM@He;3eLN;juIM0z<%%2ER#W*)8)yl`~`kxxtJ!NK2M%=gF zWI{D)5UtG_GK^fvm9_s6x;BCc&d@7OTPH+Yvb^(sQk3Rb3l8O#)D=!7cinwGzbVJj zes&=67D@;l%cK+3)L#m$B6La(ENN27A{(k!W_*EO zTIGT|LpH*0`(fb0#&0QJPVLi^FL}zR?p^9^i-X|PTnC9PtqL&u4EnolB`L`FsoIKW z%=>q|)nV9T19iX5-Cv*EEVrI8DeJ^S)S5UKG1%0x(An7AN1T@PNvVXa2JpiH8gxy7 z!axiL`tnFD$=Qd!!n()S(AxmZ_VK_xD&%^_wJzqlq&cxJ)&Qe+vCOJvnC54EE$Q2# zERlxzKRzSeJFC{g)+`%F&;Xu_bWXTSHv#kJ&xWc~PR7r=V)&TtRCLP4yOMg!XjRs+ z7%2qc>YEUwm!7P6W z(~dh{>)~sMWR|{*n)5&8N521wqd8=`b^K;xhTW$gZ+vW0rpm?q!Z;=5I{QXE51!4L+y~e&Y}Nxdxq%)&k-a6yxL_GBhy)I>Q)ca+Zg;1!&@! zmz6sozV|s4m~VVXY*=~eWW^Kj)AMq+MlU4#an6pxUr%;Q&^cKJz@g3g%zmfvmW* z4hc4Q?qoa){4@R^EIBmP#%%Zbwbz+7a9ad*7B6;&CNKIIb*J<+z@_80A7Wyn5j0V& zw}lh2x??S*lm6V@`g3PC!SKQKllcDDkM{@K zvMKw~DX6ffvP8YG=!7Ku)odf&fPfCF+AMtX4JIVHs#dX6t(^4(`Fv21J3A++M;rA6 zmkcjKZ}rNovgD&U1HDRTENL8F!7U#CP3QX|0!U~KT5lLlg6Rk)-QG1GsQ=W0;5q#aiH21}$qU z?hmp3q%3lFV<#^l*VQ#1oZQ1Duz$r=+!N0o3LF%^WMfPqkSlVLFk_}K|K3*&_QK#W zQa^8djoF{gUcYzbMTF453g=rWcgkDSo8H5qnTS#CFRg!m49U{yFv}Nee8*D1?HbM} zaHoEo0vG5sYt_8(aOk+%pCThMMp~4(A|+$dCg{|(Syt=YenWEU5^GL2D_!`>=)q{x zYSS!B&d&Lgb>vjDPgxb!${9zp$LO>Z);xzCqjB-B4pawGUF#KOoZX6lFY|nM9gVYW zoE;VII9J!mba%ijWS`!%q?C*5?D%!)@L14-VGTrY>L^2ELw{6vsFhO`kP~~kQ3WjQ zVr`f;)>D%M?Dd;0=Ora2f%n0uu7*o8;U=9COc21=|1O~l!^W|?H!0fN^%$JJ{kgb7 z^zr*4KeiLWnDSXoyM!cx6&?|C-j@usTL%J zBl(uqXH75theHADwuAYm-`DABYhs++WCJ7M45@v=An=FzAt~uB;OOhreqcsgbTbM|5WP^zH~!3{|)qjr5pey49j-R zq%2W%KjcVuNV)qHYGg%c-Vsys|GZIrTP zPCbo1+IW;lVdWpxl3jHZoIx6@l!v9IX&#EnRG@TdS<`#EW*cU_r=mHpa2NCTm{9Z# z%gkPEF8nBLxS-5exO3B@XiDs}TStzBXV;T~N*DI1f^hMq%1crBcr+3`_v#Lm`*6F*MYDL>Bu<20RTKM|K& zzDxFq)H(E7FsmqW(U3^TVzNIHqqHo>iq{UnC}*P>JL>hh_MEpxsaWK*a*rYJN1%2X zmI5;sK~c&dz0qI+0z)4w8=LBXR86E6WJxIGKVR6Zy}$Eey5R6z-~xuIMosdYwdPAp z-C@`mrML-?mebHz21Nkj-`FEALQmZ3%}reJ!XMc$3@Lt11fOqJomi{m{jsYQ1kKH7 zzK1u$AbMAfix?)?&*M&ciNFl~1H$enAe^fN!!o$n-TeGyVW!|?1w$P-z|f0_7kgej zF%iDqTVv8>>69RTE1O@ED*Sa-?~O6W%9AN(m0e)!`0t)CD=iSVdD8Q#oZv$CRg5ah zU^O(8m{)|vg_f`0`oyZ|R%U4qsfyYc0=vf#EMgjOL0>T+8NS_!a=YQ#qcro11s zr*eKuQ0cX^U3wdGhE3}-?}U=`5edR;YImvwH9S(_U>Nd%Bt@m&4W}CDc&Yi%D>85q z|4XHK(8-^`o~h8+ZewbN8k^cxZrrRsk_fOQ5e*!=^n30gNZw6=<`ylBc$Mayl@14tLHaf8p}EzRoDkAM%LvkL|Ctcuc!92tVn`CB)W3UN@o zcf;aqHC|ACd}jwO0Qa>y37UTwgK<3f5&KGGLwu2Pu6sd%po(=k$oP#)j;oe&{{C-r zb8~@7jzR#QGJ~9L(5_x}qqn1iS~>zkT4>&QiwPVvU?3a7_)3COElE}ekmGsD9BDT5{t%m?7?oR;>4L|fS};=r;odQS!zNKB0GFhrT#{_6*N+kz=N zAxOE_{p=zcrBg9(SPH^mbjYsyz61E<2UUUzD+b|@fQ_p%t(e}heJ1)XE3VdA%u(~r zZZjvuq}#PQDQspP*8}*m319jwo>;IySL%Eyu@n2mUFw;>VXN>dg$*k)Cgjy~@r4Ij zK7lcU6ti{?9ufkTr0Cz};VYPa)o>H9RQ=|7( zc2o@_ViFf3=O67{fJh~p+3@QYM15|NhF;jM4rjoGf8Kuf$AZb&oK@_>^nm4Wz*QoNBz0w4rJ40-ikf za%yAYSc5*y4@11#qSn`AmEu5<0%AVMsM1i}$8no0pSr&rs#+cbrUMz@>GVm+{b~3V zOMN!9F}iBPo*-d}0x_9AeIdbZ!WD2{Hdqsb)!%&;G`9*+S(B2I1b%?*6Jq1eZyQ5p z^7&r2w8+}sg4N#h(U|wt{xE*QzlMRfUF=^*!k9Nuy{^M1+3N4obzmfb8>>aY?@qn0 zY*@K@(dnaP_P(b>m`oe=sLXUTv1cAn1OETEua63bQ@w;ZBcV=c6niKm(Q%#Jb?!L@ zssFS|&)*pHE`deE;fycGrksAq*eemPn@?hGLQQoqgkx!KSYy`ZL~V_MNRu3OwSa?@ zI24?O4?%}~#R@(RXLeTBVyB$sS!OaV^t`+WW6)mC8gd)G{af3)JI+5C*eZ-A0l5iN zhqLq2J7GJ0z5ZpAc+tiM-LE?>Q<0K?Fqu`VbFB5&2vbNGii?(&y-%W%!{yQ2L{w*# zG(-3zx(sEc;oT5bZcB0yO=Ii1W9jDSNqIrOo}}{~i`#?@ardUv-dA?;R-I$@GKlm1 zOd8Waec&u{Kj-G=P!VgfOEmZGF{`_R7Y_5xQ68MRv%C>m$akniOnma38o)>BUEd#T zrkpxjJ+`efj5q5tNyF6u&xlEJJ(PyZeX?QH_+vb6f&o>mX_El0gn*HnfTN93pW~fa z(=>S_9nG&&hT6}QqfF`0457;nAm_8G*UU#!`87yX{-{wMV&n$WpYzhjO>w@LMGtIh z`Pw5XAms$NRQm*Nm?FifxVf_+!o{+h9)W*q6$d~u0%_-+=~mR%)>aSXO3um*_)^2U z0smcBojoK3Xas%>1<`}B^lM(T0};fXwWgg5#Q{$(n;Hav@bs7XWD9aCg~^^#>g4o) zBcDaAHY{}r3}Jhm&JFL;YgccSr$znx@+uzH3V4Stl!kCrE11?@g4Rb&LgH-N&HDl-opbbDdKZJCOg-R|nW;njjd|Wl#>OV>X z<`iNN=eDZ@FE#(2%8uJz;7D~eCcA(-;CCBCe@MAB- z3Kpl?rKI_G@Mz3Ulg!Jl2eynRKiN*B)zO|6~64o4g$mIwJR^ zy3e(h0YWfuf}e@%pGc#hSq0@KkRpRqRb@#=ye7fNZe%19^!3_kq)vH|@ERUB{$ z)Sv)?k_r5pvB<*WB8bTS%CtAyWV#9aK7uU$-zD;8oWjZc*fPR%p5jgn- z)C}-E0{0F!Nx#AR6yV}o@PKWGUC6fV*BW7f_?YK&b4uRn4%@?3{C@Jr6tva6K=@2}0HKm(U=wZDwew^6K~fZpBqR!Vovpu=-R<9TTVa5UF2oaP;t4 z>sweT+k+44Cy#h3*j+}2;7QXW9=3d!JDk?EB0CK9jF+4yHv!V*z*1TjrQOW9$#Fq1 z{$MJQN#)ry?Yx6`3tm^u<0P+G#a1TYik>4WGq!+_A??j{-|uwQai3I!?lV#*9^GQB zYo_)E=gM~;vzeJDp44e4ogOz((J1~ojd+jHB=EU47p3jXpIvX%s7ZZ=_VAsvnpvJ| za8ih6xO&dyS^iP1et@l~tE&zaY~3+$l2dYg26X#Zh%2#?w&H!KF284nhi;IXrSqn;lFzu42)z~f)Cvey9=d=GNbbsC!{Kej>Ix;a z#v1H%xliyjs(%?BdknfI#qVNyZ=M?dswr@*(NQLk>v%BL;Lpn~|p4SU^Fop6l z?`xoqO%R8iTZxZGkS}o6!$Y*3^B6j9?sKCsOb#EweECBr^vq))m4d|7qzVH8tQs$@ z74xO65TLMFGn4K$PrWQtOBwtX6+!zQSYND?#TJyWyg^GTK?RgSuwiDjP;cX>v5u)E!UWV{7e{%at~qTPaLlX}j3$OLIZ7 zfh^g5B6{+G+WO9uh;dy8LQrfe)_|wmu)Jx zI(V7GvwyzH9o*sC!0NT7)T}ZN^1f73xOE0&m_ph=;rq!E!QhM6-rqxiXr>L7C^g!g z&+On$v+6KZ7-?)!_PeE)b-N#iEC&8mV!SV@nXclfoFZwyS`Y(pjRKV$uLFF*;-nE6 z*-%+kkwKH+Wc1egZ6roMmm@JW8TgYh)A?uOt%{`X)$(di|F!h6^ zaV1PB4B%I3iA`$VSk75B=N=uj9AA3B%E#^Yt&xS|>B6sHMS%MdEFR%-!ZrBhh6s~I zKj;KO5)WxXu-XLXCkO$4=h`D+cdTyOf!NDFGT!TsP&Mru$;SVZP6CdS*w&c$WP458 z9Ch2{`SV%ZT7u!E#zUTGsXs^;n=xr7kGcyMOX&?yzV>qJrnK69`?uO}wBpDVMDhE{ zB~h;@cY@Zv8dvllqW;{@WMK=PKjW_qy1iZ<9r8;LN%Lo}1>Zf7C^-jMI#A}mPz?#Y zi!pG1wqU|guFcE!E*V8pBV#;#^ZTneRh;L3?_Qqr2%&Mk8gdt{#_sgt8m*FN)Rfz| zBt`#DE7Z@EnTrfP`bjb{&~0HOX(V&dxQg|vI*TYc29_ZX1#-e7 zV!2_pj^F=f|3fEp(c%oC8tI+=JI=wWziHs*c&)OUDbK3Hd&w84L*iGq=Sv%$P~s94 z(7)DDl`ybket>wtfj$23!hc#~6#KzGy+NeBSylY3?HR-3e?_)2;{32!fgy_UlLoLD zIBxfK_&|U)^aDEEj9)_lZM$A|qu|>Eo)xysgkFoQ7?^7h9Mltb>o2A+H~gO*lcMu@ zhk$Bp&J&mU{CQ}5txWr+4oaMg2xMUhB4A7c%$Qc0Zm_i}f27LNY#{Wu#v_D<@95{B+-w~>@#Zd?hi`Kv2eKNvN?P>DIw?iqA2F(ncJe>;Nqz;gGm zlbh2F`|;t2M4z1r1x%6gTV3=2u7!VWu~S62v-rtq#c=t9GgxNL>49ogQN|sN!8#3! z;zYK9@<*;clB*J4+Di*ThBxMR2RM(=Ye5HOAzMPu4G5oO2|Q2+Y$TcFP1Ie*qb1R) z`0B&Wa_91~@hf`dglbajEMbL2okDrj-D{7elZLI_sG3Yuz1EYq#1NzV&O@htJ-p-e39;i{1@_7_bpS(7^r>Yyw$8cXWCF*lLm)xp;h+ zOs6xj{`;s$)G6Jz%_h?OVn9aPFMMEi&&FG{GwB@7+_uM&kF?5}XG*wk$5dX={%4Cb zr$f9DQJ+rp>1$Dg&)k7fROC46f#!^IM=ct9j=vEFOn8bj!fVaf6>YmY1*E-O&mfNg zI251shK+8=3OGuEbAUvmv;kchx-wt=4vU|z6p+R58VnV^Kyj(@G8UT2TQ*%`7XPx< zm~svO`KHhX()k+_T}2>9pW+D${`IP7C$QWldn?dNqAMe|WJ^vT#9l0RHI~)k;{4tg z9%)GtIGT;XyxC?3sH;F`gZ()OJJkSg0~$M$4_mETcaVk_{7dtQ$%xa-|jx#H9f4TYH;0w zaMMRKGd7boPqCy1YA0H3S)-TB?(5OL;qbkVVEcWgj<5CE{g{Js{m?i1InUti)q>AV zcpB;R)yDWjJQ5~e@^ekkE1@vZ-wMq zc$W4~N2PZ35HSB6x#IP&gq}Wr;o0kS>+SimzdV_UfL5&@uDfmRQc3D#_BTu`7As|( z%sOdGKrg1o?JDT@64z8bJ0e=f9~|$|M9e?{8dmi@2gdc-OD0QSQY!`%XqivooiCnVTn+{ z2T@_ji!zFo64&v~evJ;M%9X}E?P3Am5)#h!LGO*}2gU!f0^ShQ3bf{CUPleUMU$739khRrm1l zFnkM<9RwK`i83;<=?Q*8A0g};1P=uLJ^O==)Q;4n)TH2d{JZVTT0N%AH1)tnKTo3e zT=?Z+$T)r!2%oHt3RP6R(dA!VBwFy_4nW5yUEC}G8+_ksMOZU{rdd8)0Wnafk% z=9b4It#afVTx3(){dWjY+~U=365|1vOlDu=u^T(diT5SOY0_mCbfUDei07ZpBeW8Q zu}D1jUjr6Qk(lo3o~pN2!Rys*SQ5JdjMnc@bBzO%7ss75oo=@nFdsu{kI z{_={^nodXR32$Qxo=!chD^a}t^VPS)!W6HrV7M6VR4_Akcj*U|VED7_u(Il(^&aYY z0-AJ#@?Z=LV|K~uPh=P_?w=86zzm1K7}CwRPlE>(Xm3#|K(+;7Pq>$x`)x;un&H5C z35hUhm?(-2`fiW%fHwEs#>!l7VO`zBqKs7ElBLQ)rD$#|fCarfGLk_zPh6xG5@%P# zpuSw*8ux$hWE}h`Q*g5aQYp0RAzn!Y#Rc6YA%zo^EzB-uzz22)mG@A;nE(U#3F86- zthz6>hwwCk^K0<>27jc+Kb`;bLYeJ;Z_xm}WiP=3yG3yNd>?!L$LR`nu7X!)D`Ix} zuhuL%5fp-Gt0^0OR?@~BoqvEnIrc+6{2#RNI`8X`l|;1}IM%3{(PeK1xRv(^34S?1 zY&N$&e&~xXWp#8y*0(*TqAy!*Q!6cpkB(DM;almSfr9pD69(8gJWUHyMot>|r7RB@ z_RrG#We>GaTP2#%hEOI=`ggBG{t4#UK|%a?>GTnDMWW~}xy)LU2bV}Vn>X5b51GJ} zdGp%l!sHS$D3 zb@{-v-|26FYZXVZKDVs!Xd%f~%qg&r+u?rFqhxq4K^#E8k(+4_rofejZR>w@>E4=u zp9j(h~enUf;d)wE^BlmqL)1fOp`Vd!l>IoRv-qGvEBzI-%c2DM4>V@M>IG zS>Zz#z!Bv>-B;)Vp$@32eXjH1giwQ`xf=JJkD#2oR`AjaJ|%4By75{%EHbO$UY+&M zzDVNr)iP&iH#lVvvUK@lXpD67J~e>%HQc?;&=;hCd|R%*XVf<<#lE=c=q2Ttpbf5G zFv3D>M+pt%Tnht5WZPcSxkMV1slB6t^(XP)kQfmYi_@O2bHSI@s@YiL3_O2(f{aD<=_;TM46jBIaAJ<#z_jkikJhn2(O=r zl2mu%a}F44Q?3nVe5T9e>`qshCHGSs>1cL-Z zInzCM{v2D>%t5oL{6Kp18W3$AXo)>qQDSvuEyyq+w5@bz9R zC8Edcg3&(z*GOewG`vejDp6CSx73m~`TB@Wzv&3_SNsgKtHST=Yc1sFK?h!+DGz4G zay#(C<@9b-j_aq%jIVQuJ)G5h*i2+aF)Yuj8@Hz}Xk2Y+5zuS?O`_3j{)(jAVNOUa zk9cDHB$(q-OAf0^s)m})*Gu!JQ_l)=%;ZWtKjP%+dJ^;EteI7X!xd2$yJkO2w{NR+ zf|*=1H!o~c2*pWJo56Ovyzc;-%o`$S+9POOviYH0ftKv5N7@HR&~Bu-PY`nRz^~#z zzur^g@BYp5BD~fByo0TYDviP}76^xe7__i?Z9Z%7dXh6->~3$9%I`c+-tYI1dH3Do^e8ZV@<}ckB^^>M@iQw;%NWAQfYnc)Rnry-~=B zTT5C@)9->HA32wRMsoa1U+|Q1Z8g%3mqrUmq^Mxt$t2${xF4GAV7j`s_0qD^SQ6^c z@I$>}Iocp6nW^KuZ7i$D+o$Aq60W1P+J3DnH<{^Y!qWP@(+fkT29d2KIqU6di{L%W z!_foQJ9_;xhgkf8933k|zbUco!hV4|ifYM3a|B5%=H11;-C_G?pjjuy5!_>ts8U_# zxxv6;=ybro$#T7Np%?KyA_*qRN8hwzDq7}KOe(sPNfc^+&)WMgx{)&2Z)o}VhqXfw zjBdYT`s}~fWdI0rKr&l0Uj(-Q^+tZkMiIt8v|d!57}wDjV?yPet4Aj<^572B2VZm3 zPFG9zJes;1sSGRi0Fl#|zr?o^awhg(gDu?|b><2koDOcMVy)`a&1?-wenI{pQD+@h z<=RF2z3G(hZZ;y_(t@PK77>tcL_|askd~GX36YXgkyJ#a8)-pOqy

    S+AQ$6tt^{vpTV>A+ysf7ko}Ud$bta*HVYLW@8levR=? zL_#RrAyRLVTMOO7wo+bu;qt|p93PW!D3l8SPtrtC0(qQxOs%_|dk|X*i|t2yx25i` zZP5Jwp%}gAHF5NwH^vU-as4jt6IP6ZIbcbl@Z`TvoSP2 zS+yd9AV+x4iU*{q2h1^|Sq3=1-B{mrn-Ihe914z&4MKDz>1IuCbUg>wH-|(I2K|D5 zZmvfW=9CV&M@ehYQHpy&GNTg$QV2JrT}_2X0C zwR9KE^6wK|iPn6zwz*H=EpP=tVQ_Tta`Uhu-7n6FY83h`4@MoS$XgH-L1+^>m? z*0)!$_U49|=^SF71z9rhp+0y?TAOE3L_M+rb`00Xb(0}N5XA|pzg~T@wYgndQmuS5 zNs9^b3j&64nexM|7km>QxY3I}iEp{J%#kvmNgqA%D+dOL-{~+)91exy-<=%@ptPS^ zgv!D-7HBfu@4jPD6?d{&IS>LC!41%$4nTH^Oich6uPN)~*<8PNO+EN}?!zM{O787y z-FCL=a9E4Exw*`oAyK;IAnkl0K)MR{Xiqdzjlbo3Stm_;+>cmYUyY;l^Rc$RqAb7; z2>yh#R}iK$xIEud-(<}UhclAf&(9?xm#5e({2PB;9S&s6?Ag2Sxm)X6a~@>uasXIq zVpOJCS<_$q`NtKQC~V5{xwmdF$Vif{^4vi45CJNcA)`uV7+uP~|@nC2RVtT5_EY>u&`? zd!HBixH5PJ=s@DU4}swhPSq%)#!^??T!iZOci(kS+`6?8Z+`rq_)q`O6VcOa8^J!e zAM1(Xk%9QpAO2p6WQi2nY)S!@V46vyoC8Wq5=&D_6db`_0odMa*RRLu2onKu7M&Oy z9ryP!PmSaY8^AtfZ~WzFJ`=z6OTPw~Yr>n9Als6A-dtT*d5KP_;UTwOvlavWJ>o3j zP{~Tg#gO1r_Vef3aXz^R5Jjzp$i&;Rzq1i98Scaj{gZL^+SO>TFUNcCIjsq?JtLFx zxz>I>x3(FJ3(N9BD~ro9Iy4Y(zUR*P)bb`qPJtchr1lE1JikkY#On7~kcL>9hAgEx zp3H??&eg))B_TQ(lHEz6qw07l@gtWV4mtp8pIT-2|I^8lT(oWg$Q~+jFHQCZ(OQx1 zp_`AhM1X(|Vl9FBc}64(5)?zdcYRX|sO#HXF@D#}@_VYttI7b-op>8j}WwA5B7)-+dV*`?6vjZgod?~2AZ zeEr)xVrRAtol56Geepm~WD;b3HVk$up8Q4+>cQgoY8Vg>4u^bXZpKW{+e^xpa9lvl zL;V9fJRDNV`R?tgtROge7vhm?Flr@A30<_^VU8~@En9P7cQ24e#+Z6sFa6Q(7^ut- zgO8)-aFfk&&D3ppKpb$_f(;M%^)+Lh_CN+#Az#}^zbd_~u)S>nc^?o9v*!=W0@9(U zUPku@&^n_=Q{4*ZQd|X)01kiErBoAD%aNnlY83=Ip;m{}=8J$z!*|rr=|E&k%NW@Kfn{%BvUt@JXyTU@9o>(tZVMT6J1QI* z0U5@r#<*Je!}lqYZMFfjA5dnrgMdwJ9tYP8YE&>X2a`c4bn>`1oZS&wTl6SoL++a2 zKnrVMZ_Ldc5ds9UjQdq)r)&0kz%i;6v$Cw`T+RyThC!(g2KEYQ5!cUi0CCE5^K)_Oxl4M^+#9G9K@ImW`SZcS7#bkhVqf=Wa9{** zc-V5#wEC$u#d*)#vVstCq0s*y(faXB^*Ir8{_}J5adY8z7j7TbS%6^bK$2iUXJiPG zC%5de*E!RL92R5`vm2zN_z8S3gof8(fDQ&{r6TO%*0(H4h+EX#pMf_4u;+19>0)GT zEY6*~Gq%<@V}52hE?v1Tl))r1%0-HXlm&j*cfL1frrfc>nI}M>nwZeKN+UvLpq4lV zRqq$Ut=*1W3yX4OPTWWYdShaIR4S)*DI7U6mo1FI?ezY4;`4v~O#H$x{+sCQgSd!t z=8Qg@#ARw?D*A9VAh{%@*vGMP@p@1Oq%B5HD-t+;*dTC{rlVxYYp@3`w!{ORr0xV+&q+6pMt=tw+vaxR|Q*o$^ALjle8 zu@;0;HLgRGctIxVKuX69*-~xlB8g@dHMt1bgVItdHODT0AxV9*M^${)v}Xq#B{#0X zB1_DL$Rt%TxeB&tB%KaCJbu86!VXMoj*-d@3e=2VYRo#)%yj+iZpZnrJR5xzC*str z|86u#PO79J1V>!BmIgvCUVb{_`A^YRqd9R(!G?GkZWqbYOh-X@lhX0ZGqJz5 z6?eYmHPL7wR7kSWtCAiP{_9(<*xcEV-~EZlqw$Wv^X3jUVCvXFuIkkeIvgyPgVQgW zVs2WQN*W4=20?H!$*f-xlE@bcQ4+Z!p2ScKbO$ISDA14taE7PpcT%xJTxL)Q50qjr zXKPCkX9$CD=pCoyOs`*ofZFTGfPmLjBeG5aQ78A|2%H+Q_1}R^$;zmOn`2;v!4A!n z$4FWEO#XIu=7?(W9BerqEjdCjgChG#p{>8y0a7aV30BI@%;qA%DAhf#(HW;Dd~rZB z4zzS;ARy>Tn*4hTs%oH9!SuXG88&ZT^95KBcafMxSdlLV7{hHL826m>Zy2>=@f&%7 zeCqMja5GBDP9(fRhFLjaDZ}9GlEBHqmmQ<;&$6u?W)oAnPD)xLEVlO4cFOmHbycTV zcIS3Q!Qnk2Zh>Z096~XWj>YlFD60nS8TVBi<$6*6<2@*)%}f)t)+lC6hMRz52+Vhi9~z}qly!0oj%YIGUw5D*OM8ko>XMx-D- z5gbij%ymHLfM>!p2TfX9UX1CfDLrEkIWsDSy5T4)bo-2#9u%5LCe1ZU8-u|(H6KG| zMc3?$A5RHw5W~&eaeQnnF0`8x_99qC#`)I5<+x{jEM9hWD*n^Oh1lEg#LK6r;^CRG zxVp0yPwx;|Sn~wuWm0Aa3jJ12RgJ$^Hifh*I50|P!J@+@fo=x|wxuBWECX5f(Sd<# zlbMaXjnc%^>X;~92Y0L-46ibX;PR*S6!>0c6DOV(Xc1cRa@#LEa=m|}5m&EYipmF(gy+ECUn1m{mdR zC4+P}Hr6uJb2mV>e45UhNWqv2KD`^GUGb|HvSfHDvk5 z^=fZb3_8zLtbg<(s2^{pz!Xt4&bBg? zB8Wm@!vWDk2wK8@DY)5T9Smhtb9WKau%bzv| zGf;w>>!G@OkI@jd*rj45??qs%C|!(xvSj!2W0c`;V3>IZltK`_Qfnz13;mWrMmvD( zs5NKLbGWTF0>4D+?7AnAg^`i*IC1KvRpB5v@@&}KyL;U>P^t4Jv1)8+EbhMhMEv0& z*a5)Y)-!_fEb^UOD@_<}>)LUmB@EWDIS+K$xD&^ttIh283=;=7AO@@v4oE|<_FLjI zuqQR73BJM_rN;pUz#vCguU?LmCr@?vipYQiMzAnsI7Qm|NWK&#x$^=A+t=Oz?CN3Q^Pv49@#rM6;jrDgKZWta%6|8k%uLD}K)I@c>8uxfA2V zgE2KW5+ei6m>lejAAkQV;3T}MgV8HxEy5U#D+Yk|;}29yW{27yCX4v~?XQXB*#(l9EVncqXa1!|IT z88Z9ibu7HK3uybaEH4JK0xP#_Lb`(_Y6HM}nw05H&O?<~(TCd5^yT(2dl0G;47 zwJu0qLtf16l)4sVJ~E7|n{&W{dkuqG=%k`u*503uNReyH=2Yyd1`mM=C+8`Mh8(Fm z(~1Z@S}-Wtl|`IV1VtHY$K{oQ(l%%bbu!t{`;3g;ghBH?T&^)nr5Y$IV48kO+ZB7n zWg2?xd0v<)?XR2$S}lHD7X&g|A%{mi!B7)Pxz`ln65(*aqdi67!hNz==-{coc90YW zMk5D;H_J;)dbZV_K%hmfp8d#ScUJ3XSLFr%-@%@_7!ulw&^!bjc1>1guMIQFv)L2( zKm1_qZ0)9)6#ErbKbOBad)%|jOuZ5_TUods&s}*w#zrSp24qk2dd@+iPLvDy8_IY% zP`;)oCgb+2Tz5jFx}BybHAWtK!5-?g z%})G}C%zcJ@$dgjjEqji*r*c=t<#}_OO=VUHwq0if%BjwfNeG*upQfr%klDK6LBL3 zVtv0A+Z*d~Y-cm>pXiU>_Fg>M8i>u|(RlvS3tE%y&5d})xjUk7e?QI}+)c+T7wpU% zhniXig<|rrh5U$XB7Frrau0Iym+nb=3IG3+gi2982U5;%4J=`SL>RJgq}O&Q^g2p)wY<(85fuf;i+9r;u}KZ)tQvwUr1XC z4-0zkb=^>gTA4=%1zkwa%xPt-WNgUmrg#a;WCR0TCkBf5sf8wB!szozanxjLytmu@ z9Fg;$7!nP6!VpRW!4kBk>i{DgLnzkpU_PXL9|s>m+3SX!2Q9(LHDLs#6|uRQI_NxT zpm1k<4kDb@)d=aD;Hdg^ZHOE;rD=s~y>gq7f}C!aZ)lZH2@Fxy?9?Ww^J#-p8_?~- z780pW5P~)glKBx9paPzzE(Q^m%v;gAh^jsylz!Brn$H}=PpQMREqs0K7b0Sp8mtqr z1{Y$AVI&@Tz&&J2 zsKV-M%+bP&hDVOmX8#CMW?i{Qj!jR~(@)38q~@pEc|JF;u{0ut6rm8hx2y9&7Y%{6 z346}GsuV;ZS91gi5O`h9aKI6A_Smxyl;{HBzz@X`j&)-rUi{LRO4Q7mJqO!pPVEhcDA-fTqbC9 zfIDg;s(3z}8_%(jVHKLuR#sk!56=LCG(o0ik>QiLZqGGtZ#sc-*<`>779v+08xjeF z%fO5gW$7u2epsGXr4X3^B3IiPvfJvsRB1r_ZMP*3fO$@RdfnvItO96ZcQDW;L*0(& zEM)QY{GJ@JQV z>qXO|G)pMEvA>YY*F@3`hRY@>fYcajX8@Q$XTPr!nrk-V+4Gm;=YR26HLS{x-?l?S zMcI1Dc~HA|)=mmS*S;@;Uv8Scjd9~7hGQP9}yxxd?b^4*!N|H&L(N4a|g2gSclXW2AYc~f3xW5nv z+hU`_T8sRfj3KNzn2y_MTJkWmzF*}5p#rJR;B`qnp;}#qPL!0S1A*dGRF_G0$7qGS z((059`juE=3wdAmmUS6Sw#9F7fA$$p_g=X8W$iJ1&XHrM)p=CypX?`*7`1lI0~!Hs zw4G+`?f1rg4?h(5JaAVWn;nZY$B)LjN``g~Eo)L^LnX~I>O=TzWXyFFvfw$2_ zw|uZSgKMY7vc7)frVK6yqe>J&uvMo6V!{|<^tmYl2gBOVR0nzbMo^|xDKM`RE&o*_}%VHrNBzH11d zdcC0A9BGY_@@8{qfe{X}9B)eY4wLXqvUKYf_gj-A<%B>I1a(@M-Xn(1;n2oWCf)AB zzSWVy^%F#S(>u$oY^( zkm>!$zUO_(RN2qGXN~P;UzTig)yQ#dbXQ36Fj?xL5}J&d#6R{e{1*ZUjes2(h_iRz zrRP97jke91*;%7^dZuodrEEg*A<>}iop|=yuf*oYT6YG7iL3`AL6AJ95i-~x;~*hf z#}}h|Ys)gN8Ki<1aX)i&GqHGkIfkS$!P@V}1ly@a%MRamo_|Of!5ijW$v4M zbV-)d%_7h% z@xZtz*{f`ughN$Hyf`zeLOzC2*S}5ZS^lYP&iyp(ElGAb|%Mt==v&na8Bd* zsEnR-?_k4IBfI~eL`icSZ2ufdD2%j1a3UGL?<_f_lP|QR0uZAI=E>D(SCZu}5ht<^ zIxL8_-!P)ey_;)NL~Hy-4vi}jw+wn#7jMV%@@@H{(TOPqswA#lyZlMcl+m+S1)&{x z+W0bYk|%d^8?^{c9!53{1MSO+B%uH$vDl!`=`*Stby+ z1&H*48V77;JhBj#BYMGP zAP2-nnCNOJBunz&^E21a`zh<|aw^EitN~CE7@M!6{R#ru7z8nuk@21wT{fYn{0T`x z5zE=Xf*i^#r5T_$PLLU2Hx5cV`q}GWD2BT!+`2_6z*#B!{U+szFg9rNqDJ-RJPp-a z<-j2rdPq}^($?5h2xeIx!5Q+56y#-zhv$h>9&J=8`ymO-`&4FFL`w|{OO?sP3V3}3 z1agLVMIO{Om<*{_O0|*Na8)M{sMU*1SQ+YBwM-JQ_9T*DglsG}=0X+KhN8^bnKG)@eU`H>U|B8rLaD~)$Ff=R;1nw1tkl>yB zMX!PK8D+ClkCUbe&TL^p5W2d7B%=)kydzBlWRu&C{b&O5Z>`7Vn7Kv-n$+19MDM$t z!=cA<;)Galf+`RNen;CfdzIj)N>)Z(i~zw!@(hq9K(4RG%*?El4W64-6%dmwJ+AQuV8~9;lP3BqI6*eqp}Xn4t`mPiIJdGbnHqs8_g&*!q<`W7kF(E zDV0PX%uaApiErzT{YEEx8a_jO)zn~@IC>Pw$v<_aof%e$pV;y2B9e5WO%xT3WJ#lF zWH?^-vKPmR6Z7%%zxC1>;O|KSGvHt?%!r7XJ#yUT2CMbiso-4cGC1f}wxgx~YE?6Ja;Wq{$Aigw z&ZZ4xO9P&<&kzoDy`BdkCyN&S$f)X=I1@5Bu8)JQp43uhtCB;uF-fL5`5b(fIzMVu zchj>2SZkBr5<<&iTXLehPdjLwmJvAD!Adv>XJGQ0?|+wpE7@u$32OC2lO>v{X6}Qp znZU<}z_Q!!YA_7UK_=+1sFk}X4hB=X%usp<96~v|UI&T$4I)+_B(AfrM}#&=vE4pq zL%i%UAt&klXk|p)hdoCC1%d&ZMUYq7F|ab|2F9D9f?&7^klH87NG4EWjf;=MT5%0H zz?-*kxxG|Mh(ivBQzrus2liRgMb-F ztr|B`JhM02?Re=cUa5o5nqvU0PU;DbbH`3d%AEDsW%?z3>^;5l)RRwmoVt`wjd+x7 zw?xPKdbAdhA>j#3&&)`fQRL-5YiWQ0aGfgO^)*GHBw$BV3;Lgd(} z0w0%otjEB9H5}C1OM=kl?t~YjGkMpL<^C#iC#4_K1TpKB|^M_VdK}r0iq` z2}-Pn24iY+S~!EVUz14x!*BfO__I%ZF2=@(J;pj!3|WuI-}+T?dtoE~>Jy)F!j@`* ztbv?y>L)O&{T@ z5hw!O=NYLWr4W@um$gGGo0o%RKe#1P_OC>dRD#I&+uxT@A~|C*3Z<%WpyovwgfLx=xPG@;&K@}#jd#5L ztsRUw2SwsJW5b@bwzeKC$eB(}E20*Jtg*(fanjOMhn;Q({-4*BSdX$fNrw8uU9WKv zz<07b9vDtntb5vzc7Xmu16;<&V2OK3Pd78%+tq8>_&lh}9u#HegU*H(D@*C1LTDq) zcmF)#sOlKSO@Ap(gtAMDeWU!kK}KPKft}= zaLG{XIz92u*{&pZQ|yM{Nh^K8ijHJ6YPAb19ai+oA@ytBGKL`mov|2J=|31=E`coR z{;PY$Q7D6Yx+J_5p`nvNV@9)W6KB+g+BL@4@T_`%rH1J>bUUDf7p}`qXS$Pv zIUIJV63oF-FoluURSb02+++myEW^v%nULg2nk>%249@}qto;~Br!9vjsLFym7$!bz zR*Y|7uR8!b%EJ9j-QnO_8J>hF(yP!AmyLujFduyy*m)7di`1d z@x*67t@pwSN|JbL>Y%nyTPhqLweAiI0We2ry(|8;C&2~cKt_VLV-3Td zgSD#t3mZ`79O;Ebv#DgH5ZDSX3HF?@?8oz$FUQ!(Sau~H+ygohNTgE& zh2z8f@$8)STF-xK=7_aIG$;=Jl!&Lld@26@n=Ukg64LuV@SU-~u^J!!&%Yb1 zYBA4_F}WJAg=Ca-jt{c|eKS-|+^u)mSW}KLuiQ(}P5k@auz8YWH#z7h( zaC;)*;z8Nq0PfGDnp6dI7sW=5}ID1$D7hT4x9hboyg;DPDdT;3uu zc<@Dc$5+4VWt!d4hD5A!2Mz}KqT7Wsx@=ibL)|^hiO@I#2-1^Bqw$tETXB&MCovMi zB5nyJ(<;)H+L4qI*}3ti7#3bF+16o*kFG^wglnDxKXb4MHXt#PbqgIxr9e%(Q`y1O zA=aRvejw&8IZ>c?PgU$Fat6Kxi2yEF#E1IZ+PZqW<$$skl9e)o zl2b0lQYLaIK=E`!Zxl~Rbnvp78uym9r7v0X#z@a6J(^2;bMyjG{4vcgG8V4N% zrG!YPU9E%sE!V`R2HoM`APjM+33jMai_NU;z-?Ik;DE%$P?JRAfw<)lqTK4rx|}V+ zAuMVjR*)B-J;5i>700J6tG73<-?$#LQ|SDAawyLP<5FcKf`kFptl>}ifZ@mqRNd-o zXKvKP+28auGX_lT0`;gGZ*|SEc1Dj3y5E{$Y8kv(2*t_oli<|S}) zCfbfKeEta=r~DiQw`w#uK^x@^K9Ar5vK=Hzu5WbIWfcvX+24<~&FwgS^0?rxkoenQVive+mrr*QU;bx-3Raf`oWTc?MLp`@9pCakmwFXgw7+TRM|^ zW?B2DtEQYD2#HG$7Fpw~0zKZF#A0Q#@L@J#0cGSrh3F*P~vPAHt+en;fb3NGDslw*q}a@C4UFI>?+ z<@p_k*gbB#CnhGxWJAkQ)O{(7oSBV*Att#(-c3?*E8-*n^k-sm6&Yd3&M1`b$AgdD zA7A?7(`wNzu7YCUWCSXyDMF(VLhF@S${d@6Dj+CsTZ)3Q*N#C5-~<#so{2-CFW5gj z=%gv2&!ba|?mLpvN-1DD+Ht!B!nua#oDi5ueKxxul+mYNin*aV%%1llz_eV zgWJz*R)vv2q0%5FrTEw_Q{-nAF)=^WsCFS5$VFYg^7F&>OQo(YpI8E(fwvxqo; z@=nSPukQe#^I%yFv9|jLm4Q@!Sv|&@8E>t43?^9}8=XUI*uv7uWPj9viIgRHlzqIa z_Z(8nlJU+-i-Hcx5>+>Gwhxpjh*hFOZkZB9Dj8kZH*tU}k@OF^W{(h(dgQrbJ9e1o zyru^ESZW!iG*95FOk9ppVlrfzj_kO8^9%?$%x+f3lw1rl2RnkC<3M(q5i3zJQ8vz% z8ZduLfI@_}v9_TsmYQ{u-B|n5PheePZM)1tCc7oXf)Tw;pHx_ogd0QJgWdK}qZO9J zF3}o6up%@zEwF(?U(S>`h>o-FwQqGtpmo*UbJ7sX$*9;`C^==@Vi{kDuyJ*c4ef zYpyDtjEuOwF3GKiq1WTawaeWpj_hf!VfKh?`6L1g%xP!NA!VRXoado|1G20+2AeTM zaKE-Hf+K4Or{Ku!5kuXed3rCj;VBPto?MRMx(E&|jSaD`CG=-@76$v4&`S0Pr4kJ- z+i$CMK+po(K;}O^JrPTbE9xF%Ur9uZl7f^``(-m&Q=EY~7R!_udga_8gPMrk5mx|h zh2nz{P-7qXoEtZ9bf>b4=hW-=GT>O9r6e_pv($z|v!jldDj!y|qkC-a$F188OgjV{ zx7$*Tq@8eeWl^%;rM3rbtPn@-!aXrFH*ZITooF=UAAIlwp2(*e0{r zO3Xvs?a=zwU-`}W^S}5Xx-Xm=&Pey288VPHnvFv5MD}wj#n85GgMQA8NP<6X}x&&EAbcAk~g zV>hwS8qR0W+6@@w$azBz{3BcUJJ4w$l%g_zb&xfqh17DY>6+N-KtPB=mW>@unSiVR z0{`JQMUfQ`2`(Kbd86*i>xV|hVsc_A?z-?5DXvack&$s zO-+&?6w5Bm(dsOO;|!a>da$vfz7cuR*jk`!dZ9(~H3F{p0;B3mOHT)e&59Y6uu zC_2IaCCDt{JTdFHx0M~NZ7`9GVKReq?#wOV z+I+ZytK4r*+ZX`?tw}`sn%zKa6PdhP7ALPMjCv?D7e@>M!XL=U50czp> z3e}MM+d4J(a*$-`&P;0}q9bg>%>FVFMTa)a9hKGcKAPpA46mo#I)kv#;htY0u^N!2 zk_&2y8Eo*`ASnDj5vyiLbleh!@x#e*O)4G1))om7@gsB>hJ2quQtIk3XFxoY9Fxob zD7YB|Q>}Kz11Y$#*!n`82vmk#_NeJ>)&?+15NE`2tL@!wBN4kk;0l~Hqrs&SWvOc$ zVmh-{5a@V4&RbbwP8FR!azsIegKW?wI}G*}0V*L&3c848MX9Q?U4&_mBtFvIz?jDmwCnofqB>lX)o{;{CuAj3?a)JFY zFUP`O1Tfcc!uof{svr-Mp%F$|yT0!F`GHJ#B|+i>B@vlDcx?Wt)|4(C{Z)>wFOu_( zn+q;2>jG>`kZ3-B{A4_T>7s&c%iV*XHFT>TksT4?h$WlcVv6zxOA)7olm%4Jl+xe^)_3mk4RD#Nl9} z5LgcmG}^2n;}Ch$30ZbNVfR(W=1ehK9E8Eo`f!V+l^1h>Qa*#y`zU0?!HLVlZ3SB% zcqg*%*l-Mu48%9R=j-F_sbkS5nAK|;=;XxM^3fpkkcV9&Q&STnWpy2QX0b&k6l9)}Dt{{me?Q2I6&mSEC{}nWZ&grHq%5vk(#gqi z6-f+(Ha;N{9}Zr9o_f1;TB9cn?g%yD@5@+=$FRGXogMuO5)ek>bJYJ$83ePCFuFC001BWNkl=9I0d zQW$3$!wRZ4*w-IZ(^E25ATU;-T<((O7(OEsCmI-QYcVrDt#t$i5Xz()xzRiRZVM@M zP=Nsl?x09yN?bok4{OD`@^3pyhQxU~XkOE^q+I4wfd^9Ax0AuTzH1qGmrPZL+}bw6 zr|E;1<~F&~%CuYCAb7MC;%0L89wz-3`w7ev=0UZSW2kI$J2ecwQjPJ?M|8<-?b;ey{ zWdE70@ccL%1a8&p&G#x#WcCwt$BuTj2IK&7V9jRy%+LO-c>3w*^d5%laqI*>?lN@Pv`HR3xnYaEhGG+8`SJ7TsuN`t`JZFQ}Y$kmtpmVyXg(iU1c;#Jp08jOPH!8oE(lvoYj z2nC;(#4Gv*3%3`fy}r2yY~9g=FQrBtq6|j1j)~xxGY~Ks1#`>MVI-8fqh2?p#aLWk zwt8WXH)UZ>0%ODDa1D`eZFqVjYa${cs$n?|v5<=*HS(R3f`v^C$?^yoj-w$^*~Nho zlJVMi06@0e$tjv**OEJklO84 zmZ9m7QfRccgQDN8q0`d1K^=a0NY0{0S3kHJw@MQk`D~)7~-&)-7q~fr9g(~v9r4^o&YU< ztOK8`gVNrYb0#WBq3`OoTXF962?blcC$Hmk-KAm}l;=!#4CG8%sD@5)cEtHePKnA) zXo>J_GW#}3v#AUpCys+;t$BWQ0I(la@6Ul^H7Ke|T!tF0ZNY0W^30e(?Nr%m|3I9* zXsmoVIV0B0tl?Bou*(rjp)v#tJ&ferDYZ z3TN#H2Hlk~Gdr#OoR}mybhgV3gJ;j5*BPX1fWU$KX8uIM&7AR-m32K^N)6l(ff(1K z39xC{J-my6n9R_mMLH6A9|B2+DskpYc3CI_!@2mprA3uqxK3V+(Z$wKLUUQx^5@j3 zY0H+}yaEM7y%GyMlzEB(nF3;(ehS14&t-HXhQ*(P7vk2n5C6yyN*v2X(aqT1-qCYm z=n|WVWP#Eb3ZPQdOBF~ma!R7&tvkF`b4H+LFlZK1hP|*@;AmRHr zi{WGA(-PHl_eQEK?sp`$|DhlJhz7@zL(89JLMF5bA-g0D%Hb+NJJ4CMm-nm$!R6`1 z?4;G2z`RWbPAVJH!cKXbK%=Hm*7pp$D#0{w!Jk#=PbCPt4s}4d1(l3i{&3%7cRASf zP#NV=aG-0;c??q7Y{z$f-}_>0Vm5y2$A4OZ8XT7@(^~w_>?T(ZZ`44h^ zBVv4JEZ+3C*TqX7xIY?_2S9Jap%HrnlyD%+r|ctjCn>N^eok`ic%6bW-BU*awRi~F z!A``JPdpXB`#T?tE$r`pD=u7lRvkGnd-<#5z2EY-m_2sJNCLx7FnU0Q7=Nx3qhfdz z{d&)u$59vC9OK527V3Ru7i6yx1o;~_nRNmzbcBHF>Oa;(&QHRNW*h1%8o8a5V5I+3ug_XFwqy(>o6Kydkk(F zHIY#@Vq{xA&Kf{QnRt?KKS8b8Aslqb?0Cd zX9YyUW1h)WL8UBPOK@rF-d2vabu`bgErLyggym(rZZ_iBv158Ife9Iu2#cA?iLFn2 z8^l5a6Ta{4#`y4XT)TBM&YnH1z?J7g{S{{=>Drt*q4uXN$2jwKsR}DpnKSzY$BPqR zT3k{$i$qX5p=-s-3ndsExAI@Btyu;IufT& zpB2Q+z91N3?}O-&^-DTB`8(`8&JO|Th4bfQY3Y_qb#(?gJ3Jo@BJaidVqzTofD$0V zj}ruE;hdi%M=ao@*3$t9!Jfzo&wv1ib4jZp2D;{4@YxknMaasay*5x1Q9}1>*f{KtF5hP$|Km0@AlZvLz*xLrN*oyi2 zIq{T=`@?5pkIhdo0i!qB2WqaVz3CfA#;4i!a=; z{C8_J+D-N-6o8Olx^(GM{KQZFWK53t#L;7Cqw%IUJl?6ShC9OeVMKVq7(5KNX2#1N zIs&S?Wc59JtZrLTtJ}?7lf)pCP4P2OFp!>!GjNWQ@xT}PqjBAsQ0wszuoLHZEE;*GE#6Ug%n;U9xWi8wx;O-cn3Gc-h-4!tLL8r*p zaNxY2AVKi(*0$=?K$wdwYih+hefo@^y(E-%fIX)Kg~!t7An4_DxCaa6#$g9>Qfb2NVEQ(D%hZCpInpF)vPglj*sK`b*Obw{Pz!O}j z5vOc%>B2>2MFj0NwUt1fAc4Sc?LE!t7#=iHQ@Q}HmK+g36Eu5Y*%_hNFf$FwbW4G&$_V@W8pd?>Iz&Z?mexV3 z5yPt*an0{dTIG4v@GI_*B#E!$cN8+EXOO%Pl_)pew#i;m6PbFlL1>&rsKl1MCZx7? zunLUNw&Ib|aRo~r(#A`gar)G$`1^nVJ*s;%>K7+O2?uFx*41s1hMX%<;Myu7!nPyXG2f1j}R6RkqPv=*Gb9O)R9t2Jd1gq(YMx5ZYY{ftN zhd&wccPUw+`BAs2;2^mMoVnsJ6#3U&2?r$FZF0T|+vjA)DghKMpTK#B0RE=nBCoZA zhC&ibh^Yvg-JnW|XX)$sI>onR1VE}ymH=S!^`u)PXYA67F1gSbq4_mD3GEa(8mLRc zG24lI9yl9!-G44#_M!)4xDO#Drm~u2Mu22V`lf8R3H4!(i$haytDG%yu58(sKUe2M zBLdZU~`Yi#dyPX_EbiT8}Yj$5xK5EB1cUYARYQ7P%$jZ1C_k7s{U2=|N2{` zh52{hzao4L#@6mhYA>ff3O=e9Gh-QrB{HCIpjt}{htS%(B)T(dSOfylHnZFj`@Z$->RJSi18$q4Ky zafH;ECk^FBBl!Ui4yZwMJ!k{)IlK?|#QPpUeoR@PNn38gL>`)*g(UQr?-A~Y9_8+yQ=3ZmB%fn zoWg;z125vL+IbV=)5z!EUO8p5Xfp2`H*X3OSDW6LI|lfBIh$5VqPuU_;={5CCX&ErA5mz^O#a`trBz z6V5nJb!BBK#s~s5ysIfR%_3YDow}9f6M`JyC&Ag4v!s+!E=K^QN*nCNIHd-7KCJI{ zPGp7mLZV{yPbDMZX4;eY+bX5-xkj_BQNWs1sfNFC(%>M1`{jDd$!g$Qdq1{!+*zcu zo?4>K?k~bAPSt3i$%U5T&7SzI?cl)2#!cMjdU+OadE@KiYrf`DB|6xT9m;5}R-8F~ zT0tqQm~Is`mqPO$Qc2c?JtKETR=slhs@9N_PC4#!jG#1(smIQ64eSAH3*^iM*G|+e zMcKo)My(9pc?r)xdp>^pr~aizUDJEd#LN29eW^v z+Q?xjh#lh~Nn|l#7t}I^QwCDybIM>8Q@+{~-S_GTiy;Eq!4Z>5S9U65VX6#z2+yV> zD9cA1g5o;J>VbjDM64MPG0!9;AUY!-lr4-{Y^`JHy?Dh;=K%qCbEq`VHX6#vR8P&o zM&!1vfngxku9+f6W~AD2@;f3!z63eua1!oIWFhL4l3d-AVd3F%eZ016?;Bg2f>JrK zI6(;{!7&hz#G*ikvJo;O!|v~jH4Pw`(QL%x(vl!_{#_)$J&dK54v=~g!HJ4fdM94VIN$(cFlxJf`f)@ z@9aa26ij)71)yD!7PsuVKF2-sK0GURZ72(B$nmZ$uLzpwcf2oqgzu~|Ya#>7GZ7S= zT_Uud>e;$(h!zL;&NHt`i^VzMdboa|Y@WYr@gND&(Pz8figpNMO>M0?@IPxxse{R< zGHJO#IA1v7(a~{pFT~f`jC&t=$cS0Ck2xrEDX-3&4!o?CRbRjO)RQs-WZua0_6-b0 ze{WNnEk==b;qNQ6evxjvkA}rQ0H!DI1Fr|DewN zt%Xb=QqA!6nbYz7rRRk#@~nAwI57}2qeku`8Km`kb0g-DppW5MFI*SeGK^!7D~>4-Z+TFyU?-yXR>*;8svi z0D+#ukoP)Y{JgQY-YxkkV^88Y?~9HCqsLuZw`K|ZsHWsrh6v}%1V%f@LKLd>g39GE zO0*K?!HYHHAO7g~M}J>+23ctlWb*XsQwq8WNU$0F-Z~aW6RJM1GDHqs;}c2t2%L_e zIFGWRU)BYdvQoVtjlmhG^tu8SgzX4}ev(^rIW zFylvAzljr`2AQpy6&&j4{Jk|7yr*i&l~jGz(ct$fL_=Ky*!|X4+;P{bIDPtLJo@O1 zV-)eK{(d0_;)rGUATglJIi5bro|AGdG6MY!Mx^bU7DWimzNVK6WDqE?@Har^D@Gl05D5xTE zMdfTdW;|qTQ6US0o`C&P)f*Uy0hsCQ8*U>S;d++M>PC=-7CH5G8(JlM)!(Yz;De9B zC|JA5L)Fs9^@tRyDS@c|S!v9M%k^pwhR_ee@MHu;(bWdz_AC~N2g$+1fQn(iy)CDx z8nOg>92}Y8rXIWPPFxnH+_dTcf=sTzAsa3OvG z*&eNTz*0@OdA2cx%mC;}s6?$Xs;4yFAC0U+1!alQyaSyRB|Hl$-+mI4aq`lpx+ zu(GC34?X`u0wrqkkn`NBfdQs8;eB8o3}w|>ir{l_Vm0)u7|VBUtMsVQ}cAZ}#dj@25KVS&=@?24Pf*=0>C z+eU8#odjAL#r27f0(pWIf`b#sPQN~uM$R8hC8?!M%{MP^23L}bkG|2*%>n`81T z^4^<~5#RTI?|YW#Jm)!OpFv){cI~>LVfGY30$-9jS6S1Y1Gu^j0&{e{NS4I|4h{?j zr3a6KcNWe*eZw#Pq(y^ztS7^o6P%npc~a#g?Z-k^CRp)(_eCJ$x4!{rC_zbnqZ-m0Fk%mSDuD>iVp> zBr}V)cPh{Ep!%wmAj}L!V*yCh2axR8k*vs2YU}g#w5%&(0LVc2yF{RLcwLJpE5&#y zs@K8uCI*IPN}<^Hh0G@7Ba%_JrV!9Wn6Z){MoVjyhNB2hsdcHa#HF`TrrWWh;WF@Z zk%CI(>vpP&7~>#197MrYpbikyO8r^)yuTNl8`O8H(<2ED%b8KMIDOZw2vX#*mGSJ$ zY4O>#k3r0oh*P8CR-qh*QVbcHV6CS&mX?=Gt$JU^|7agS>yC4_3M8LDTiB* ztJI~*;zgXJ6JZ~DS;AE)~!r&ul3T3SpvvYH?uy9?ZLmV{w zpYIYCD}NsxsJk1b2ctTqHDk~6-DAhMU7H^sQUHXZ^tfoZgmJA1A)!o4X%C2YjCQ!1 z5hd1|XOR=*c)&swN|_& zec(6uO_1v%*pn$eF)L26uLHwKNchpr5CFoPFyCg9gKvHg?6&79-!48=lfjOl; z$d5d05U``IusknKs_pHI#ib>opd?QO;FL=EE|g&p5_J(t)82Op!>!DeB|J2WeWp@F zX;+rLlkmO;l6=M)W!)#;gY0t`bj~!#;Ze@#B}g)I5$ySM`#^gSR8N5dBsb}=nDI|Gif|X`l*(;F61;|j^bgeo z;h0%h;MA#8a)8N;$PO9q;qk}M#>YSYnfS*qJgU6`MDE^v2L%;c5|g_ivQz0w5LkYr zRZ=C15}YJlkd83dO6WxD$`rLhmAHA%MKDSzFB$_W_*66^gf5iwM2aZrN>q18tAm7T zCuZly;^a*y;+gl|6SLD3F#}SlvV~_e9KALNA+*o7qI*E{OAE0RFP@Q6uri}ZB>>P7 z63m0x-Q0;!fAX_&?dnRLyK-K#_QYU^vldj=P|H+V$O86cAOKQPxD#sUS2@+fWLFjz z;vK*JmKf|efwt4$i=D=9Jni1EiOS1f{-Q2{0UJkAvnHgO7{ub?I59*RZcBc4V~DZC zk|~DWi(|3GX4VL$F7t&|FDRzG<(vjUEqs((thXJ+lB3|Q?fk(6QXB-CPqU@38 zUI|1%KyY-aCYg+XWeX)U@hk=h9~e|cxN19d4?VAQmTPrBmlynR1TX|s4YgNA)K&lL zMwcjFEa+jpl`Poq+lG`X*lqUmo6Tv7FvwQ%;nT!dJ_ke0pE|I0HhTU-}g4#>lC=P79VP~0TJ)Xhr?2H0*K9lv=B+NdzM-y@R>J{@22m;WF zpv4r@YEMPaNu4{ChiD1jY-kM+hfw8!BLc;uipcNsoZ&+;+)aoYh}OnN(O=-+aq>Hb zyliz>cM2f(Wc?BAxj54t86Fich=43PNsx*`r8XN|p5f9x@QjOX0(iG-LhMZxk^5z@ zZ^;i%001BWNkljLcMDxT`D8YgP1yBXr^;(^vOb8cZbi|q!_|-%S2^a~C7`aZlp_gOE$VFQaVMlB=6x=p|;Dljh*<}Uw(bu zI#2R$Dd(Q{UcBpF55#MK@z@CPQhY-`w)11hyu&;h+Z1a4&%X z0n8zzSFJQ2I;5{{#H5o{{Y+dI+S4pC z%ai5)Kn$1^hr?58M;!)^6m|W|L@Za#8bIU%K8KGcDbTP=qlYu~$iOS=mmrH3?dVM5 zT1|?oS>;eY&kRX%OQf=3wV9fG!Ow**3=EpIrKycpLrmge4g||#TCV?kPKZdEs^#1G zac@GQq~eKa4$5;K8Dx6l-8z+rm~z#DT1cfSfxr=godOznT(EC*CI#w@WR(umym#Ga zTv~XUq*$IG0fy?bg@>b3Qzc?;bv@a(7|JuWG-h`ausLhDxU?KIGggxXkrTSX z{)d#woQcIn?GqGSIX83xu&20w-a}mgRXcDv5}K-6TEIby);HJG%BY0la6Ssbug?i< z#yYT9Ha8&D8nzez1;c9^f`S3&gm}uLEjmua9Vf+b!=ur9`)sp!-RoWk7?sWu?r(62 z`3s(u>-usvUhw>{jc*JP7e5n_^JQF95&Bg$8K#afBpZ+wVIdZs#5aguV&po01 zLze&Me+;C ziZxq75x0ls7|wJl0;f-;pFQ9F-15TITT2bLpbfkp$6l}X$=G=eD2r?|4%erwsf?&4 zlf!r<4?!7*GD;SMe>Wl`@|R{7^hZMiPJYn5h6gz`OaRdmTbh42jJl`H6hkJ*-o7Et zjKdp)xz4Cp`lluSRM$r5K3PkMWKu!w94L6uUMqnoebB0Jl_`*!F|)2X;w%$PPfu!% zoEbP!(*0D?<##!R_24xi1-*U!vAxsK{S(9hWm`|(2!QIxat0O>QVqURk-RWpAULUt zNmeNZx}vx!=!)oA1UZwwa@}3JqBJt8wGufD*(%sy+`Im_s$?~M-F_reu4_V<47UnWo_QX zFFQgD>G*yz6sZh|u>{$v)^J{w69%-mc-G<|^w5&I9P%9E{6=NME~;8{P=P0cAK04%a2YrfxSD7p}32{p?6}U$ zTCx|#lc99PK)eEH>x>m`5Ux$+#>QSW_jg4&Q!riX= zHSW1SFf7I>R=wnaBm8;idzlj3urpUsb=7FBEf}k>{+t1I}NB|%QU5JqB z5Dy(=2@;&(*oWwQb}<0aUOT72n|$K$atJ{lJ;Uyn}L-3YV_vu8B!py(yESbzR2 zJ4jrpg7PW=Eu9=mpir`vQp<;&iqef6-B?)Pir@XOzY#qhM8^(fds^EY@tbdcbFA&O z;++q?J1Q@F(KmF7jOk=hBm$Xmr+I|!>23kCUDc!e`qUD}YjF~^E2;m!5OIi@+*0C* zj9N2oU&-v{pvlpf7PA!cV1p0zc}NWKivv8%p>p^gy<2e%l!8(KElX+KiO5iJ%xQQk zLtwB=El{QS1h8c=i5JOukiV-72LxSE2mMEoQ1o=-$&JpQS4zROww=IEgcq87}WFQE$GmJs* zb-lCRC&HWrYZOYG^u@u+K5h;WYmX3#c@tIf8~ALxsxWj}bLBm2U(wqc;=NzvYGZYG4@@{mEJmmlSqksf`YRoq5!s# z%(BkNx{?v{>=kIVIx#%ZA9W1*)@BKG?KD*aC~9tkJP#T0ZsBx!jS?FB(8_xlXF6%F)C^!ou8X?S4ZjCVeLTOthl!v8|$kgl@T`PEQ9294c0GV~9B*Eva1-5k6u->vYbu=0r*zs)Ac5qMJkCi*=S~27= zg9=|nd)#D2g5gV-E(Ih&5mN^Tf1GD^cNOK&B(|kJ=6$v{ zcjL;HE8;!z>}6Cwi%77@FIJv?>lc+4IfkLP~f*TnE(UrbNWd*D(@L6_<7aNW z1*vwY2-mOoP(o@ycH!KmxOQ;4XA5C zYlV)3&PXX|B~p;dR+fZwUI)KJxd_$LH@)SJF*aziLCHoR?8iI*`|rmWAAMZ5=MNwF zi>SQhCC~2;4LF+@!cy%~z(4@tOvjGNM6-PjvZ42q2a&@?L;}Qt$SH96Eg>uCLpBV& zQo0gk+%+rSBaO53f!A{Ah(3}@jI&5MGl`Hq5R9bSeM*}W*)MQ85%i%RxkPo^s_*ll zl3DNU$%A>wWK2%H!KuK(^9585IZ@dqK|_+^1SuM6Flo(^Gfq&DqvlTl>6+B&L+jZS z7#?0D;Tbs^KW(+PblQT!IW+vtlN4QN+AiZ@B}!6^04TumV{?jXG1hPvGSlTdn-tO_ zjyd~@ZGcSV$pDD&Dx(zbgRO1%>}wWAftMv^t7pbA5&ym0F1DH&!5S~w4!CWw*F$!=3ThJpUR*lF(R?|c?; zyaqriAOJ}z&!DJ}VhzRnfdeJ26i>(`K$ab$D@Zdy!m}*~hh+R9KN74+d9w_f;>@e0 zRyuqLpm+v|k4cP(B%^Q&M407y6nSHuQ|?Fp?7-M^%ytSU>v8X#|D0~iGoi~Ngm}5# z%<6;Q`w~nmVoXXF%4`A7YnIXE9Lj`5)>^H>L+;MVFA}sL{-J*zCr`{4o|eU_xUQ>L zuf(&T{cJrOwd|Gsg{mdb2p)n-j2?At;viFEK{F8&+m8$9uLxxwpO{j;Ts}bxktW^t z*N611LFG7a1a`W<)Tt@c7!!s!a)2H5gjc3}YIvDgiATyGMa|IsA^ech9@a^L$YGry z9zZ*mHyW|G(}?AbwYYNWN<8bn`{dWIUb`08t}VspRwLT`l~`L{)o?1F>BPiH3=H(f zi(dToN=QzgI1%+;5fDw1)TcfZ(dmi3&aR%bd_WnMouwM{D^!e%gYLcviqd|lFodxD?8vxlBjQGqJ&3A^ zoFQmdra@-VKq9ugyB{z7XD^Rez2f=N?eP8wQSEl(^MCu-@vc9Af3!LT%LDOe?|Cme z3E$AQ>L8nr)<^X3&CI5@2nlIyoVGq^wqo6u8QmgL0HVT5x}WRaZEk_ZkOpUeFb;&Btj(7b~f;hvFrwnKN zP(gO1##{6dN-bQFk>=i$<@tUvDErjNhlbqE(Kd@6?E?%m^;^aT1I-hGk|C+SUzE7S z-Pqe#`9pR6g7C1$TmuFrC59K5R-f!rfs)z-HvkZJXRH zpX1=sBW*JXF-Z#ede@UGfsYwST9BV?nZy9|oOy=4hq6KR28K+8!`KrrFaS)j@BlKv z@K8Ka5@WKY+H>Dw*1+dZ&rHRWPhN;KXHJQ939(Pykuu?onl#XRwsN^XY;J~HAR$W? zBdNWKu`IJGSWn6doChFS_Oirt7)B$B@{vM5LT>^dgn2hApA9m`cuN^U5Bs-}gt=$R zK+PS)(;7i69sa(!?e?d+{8NInl$+%_TLljS6(l|f=A47`=g%IZeyk~LOy5%Tb%F!;lMTFRXP_CUKvv6vGizK zsNEUIShy_IYefRyqz=EW_aRv0^#qx7v$NXING+%HB3Q!N=Kv{}R2`667lUpLM#FpW zbDbtS8)a3%3UXIOvH1Mul~rj>@OlN~Iu|7(EgYh4wJmp}UI>nY>~X>}86M`tml)}g zx`*j9Ah0o{?c!X-PyYD#$FXCRo;+B}YO;B)PR!5GN*_gS+|2(N=#%{sHwGP&GLcoE zBQkQ45EhrB8w=N$V{L6SX6L43kn)y9l}NT)(r*BcAE4W0(B~cdt*$Z!Je1msNKu)B z=mrn<6UZ5JEliq(*sPASQYy&oH`n|yG6G$Y?dJV0qg<=@#f58E;^yNg4%bQ=0qTN- zpvfE`uG;PE>^DkkQWHLK8)Q!pe|PC4IR?(+z0@9B<&G>P8jPj)`LigNub%*DYjZo6 zt}n*_^EaQ5N5675_Gx1#(7|Su=w46na0r!yNR6=24=7=?PP=i(=~@g8G~%FJk1s!7 zjpYW;-w27NtDWGR7GVFK0cH|LodkK(akpBFH~ptK#J*IJB~uz}tJmXq-v0L3-s{Fr z3q6W%y!Qhij>=13{DQ7(sb#}!Pz0H^4mX*MAzB_54_~_XLqobn3=IZ{V1Udn;V~(F zfgmUvHDS!3;SLCHfU*E}&U8>5GS#pt3lz0LYV{n_nfY05G&VGj(G&UT4R=(l&WDL{ z)n<%jSXgO~azp7CSEm74d1F_Qzu?H|C__@DE)_#VU}=ccQDhduwKF&g=S#NFgLFn< z2r)@f1U1Tx)eDOup|2PMj0Ivw$D9QdsBn!;-sJT-Ka~R{Azc&uT+!&7_OgJV{v&|29J`7yCYyb1C0}`S+$S#!=dn%qqAL? zgq+nf1G%U}g0|$001k-)H)N^n*2YMq<29wsfdlDLU7bz@oO_}P95zU->;nQa6b|W$ zM;C!Wkmn;bgVr*#S7sfIj3`Lr_gELE@bPF_5B3;b5w1fLzPmfBVYAn%r?U@XVUzLU zFfvP^UY~(zN=K8$VibY3El2kJ3CJ{eQfbHz}3_)wN-oV9q5SX$d;S2#tFKKe!77bpoOrG)6o zY?%o_*@o+1-&_|m!-P|Qm;K56fxMs*px%3x3Mso;69Y7hiJ+hfWMq)nXqiLzfSSK$ zgk4gifX}|K_tWa@>3alhLXNrzF*iF`h<>eDSzUK$1lc)VMb&CdPL7G#=>GMh%g+SL z5f6`I?~IL(%h?ks^l|-#00z3E(p+>ETvNlY_4Ui4fdH+pTP2Y_!Dr<}QP!0`l0gA~ zPsD6z8&r(IIHG^BE@3Z_ldL)CS!2CfV{wCuv&9~Xm7c1K<{s^|U(=MWkG+vWGWE z&9fx1K`x1xD*#O?WKIPyW&PCYrV^2ZLY}X9VLdoomq!&Gf*R08vet-|Ya8)_4?Y;H zoU`_J9MDcGVT&6`uu1}4c?oLe(93%AS_IH)y`2~zYQ#@`_nGKxJ{i}q)0#dSwZWU> zKfL`)?9_%m^eH8?OL@xe^F`n(TT9D#{LbRqM*QyYzBM{cf)1u=l1Me zH(OemT1=KFG(oXMHaHfSAV31BYnvQKRwe@i#ETOu!bLYIOt=+yI8m zJ+DYJv*D3l-Leh=2B6+Ak`j(g>}i6Kk_C7ZAWOUJb|46jMR86nUiGqX%1L4tvGka55UhT}m9herdR#4BkVN)gbXobAc(KUSH&ZX?+q>M7NAYk~~(JtR%G#*bi!zQXl=E>bN{l zsRAMxBo)wUp>nM8R%5$xAza$Xy@^i4*u<2KQF3yW6*FVB`o~zD*E~Fb5E<9=Y zx1Tv8+eI8|NY?|RhJm0Y*n@m;wWb;@YeP`P`{Z+084&aXZIoVw!i*xo=)QRUYM|aZ zKR*{sNVAtN0?ienjhRj+f@E#fQ1FIBBS?3NVM*tdGwSRbWX-|z@%ecfWY9UZIv`DI zw67$f$78i*{j32&GXzPAF7d2O7Zv-}PNS-+n&;176f~|DHS8Biig-dE-o|HH+rSBo z1G+5*TWU{M&p8=ePi!)2vSxxI92B84MUp$w1fCb~mFU;KI3Z&|{|zdLgGSLMJ7Sq6k<5DE^ME7^pL;l=&@Idz39LlY;-@;V;E~&$vhH zt&&th3>35#Y3!UnnaKE!b+S;J+B%D}A^}ha1`6!Tpeudv!M1c`eQ`Z5eDzX%_+y`p zraA;7x>e7d=&3=LuS7*oI)fr-{`fCSCJY7RPOUm?6bb#UYR{GUk3aSFSiSt^=!JyK@S~rI%8Oq3ysnG~Mo8o#S_Lgdn)>M)xIq+0 z&#n~Tnrau63~{@o!zehgC=@ztwq`pufx z6%J=&d{pmS?JfEb9iY#3jgd8*-Wj9H86~h`!_zwq3mr(3P0stle%9tMa3KUD3HuZQ zBKpj^Pug6#h8$Sqjcx7&1`Fd#7Aqs%=Lv|^&zuF)!dHZc8fZxrF(o2j4dC%6;9jL+ zPj+1dpoq?srvMrxvX9u!IFTM@Ug@YAOS-qmbE?Uy0^Rcd&Qe{XO0*#RxwG|Au&4|{ z1`OsK05ekS%(}Xsap8c7*HTEM4r1XXpzE+9A{C@W$bjrwj-F-)5SUeZVs?gUjqVFK zI%P7H#+K8$!w{(gYpat7)jftp75xW6he$W??*(%x2ouVK& ztP%}Qh4Yd#4ltq$$Vzs}dxLi1EZH+EBj_O0uRp1B7_%K}>WnaCnD?O!nwCZG8C6u| zvZZ~G+GJlKq{R8fDM6Owtbv?l0FW~#2ng8+X1)WJQ^KlgcExSCoDmtB*Fs=sJk^rs?8CjF_P_wj97+Zn;tTKbjl$O?ZYwxI# z$_@cuK?kHwfUJ0#V}Pw;e;|;=y5Z0-T)1exhJ9z@)mlX;6bR1w^XFB{!H&Rtg7nN@ zJ#pfMS|ND`n}UsfU$Q;BW%yG;rl>e2%8n9ui*5c`m_)v^vVD`m5Kk zyX~%Ylw^rRXT1!k%B+<4ODAW<0pjRColO7-h=FExjed4=ZQBI0^3(tBM`B`p$jtWg zeu?OC-DoNByX;rZpFx*KI zr4!wXxm>!goB>gMgv*%jxKM|LxM(+?jmK2vbB9T}8UOyr=b~rxspzZE#0{B^ z07*naRR8@epNdx=e{M|g9YmWpT)GZx^|)B8#@}?h(Wv&tK^Zfxr&FdRd*3)%Xf$@> zpMU$e#VcO;wXwGcxf&(jh^M~tm3YVR{9ZI$?5Ba)qt(5~N&kC3@X@IJ#E<`I7bk{+ z)S^|p(cEkXb0sk#^?Eh7wsvB2YVt5E^t3}X_N^|6g9EnZJupBJyvQKP!W>~!6C}f7 zxXXSFs;)q!UAtOpy+!U89daT{dcC(9`cwn5CvUV+6o#7h zqRiqr z7#oZ=&+N&hHao4hBcDU310pUQb`1iPMt?UJ78ha=#{58kY)cw;RIguH zSWt$^dvf0dwh22!euE8v%bA;EWqD0T1hN%GB#f+B|2sP>Bg{_E=;s*GY#ZBW#B#MN zF(FVmwDS8H2i(^y@ulRG5G04jq;JK^OCV-3^FE2BxNgn#$zgpa#Jy`* zFKZ9&w>vR5Y^XL75~)=J|3WP5vm=B^2%5FJMqPSG0XDxUBBmsTt%Z+VIA;)N0NWq* zPtL1orhq)AlsWqu?Fc3}PESrLSXRxoYsAUV(>fHOQtV?1In}Ch;>2<7tz+}^I$v}h zhzQmbvAa#{W4{C6qSVTo5M+w?w1wK{fChhA3fsxS`r1b9>~4!2z_{^Y$c;UgEw{Wk zWt#zUAXHka+fE2^p(I$cc+eklebmZ^)A3-g6tZGHvaCfgK|re#m3UBXNk)@m5-bW0 zC>gLa(o%v@=9}%FWbdWKkioaI;X{0!lAFtv%>0nplFph(2iLki@l*fn55&Y2=Y)1d zcTgl^#Th$u%bDnhXH>|`S$@E_QsQiGLxQz*Hy%x__=-!@9`uC#^n#xE?A)x0qa|U{ zEei5>*9K=5Oc2OBQ%u&<{yxAFf0BWjR|1WBw||`lC|GW$uH6s!)({=k2%2 zue3X<|Km;v?iG|<H_@3$X_>(>`zFLt9v z;#_G*4>5~06FiH;=&WV8K|f>{MaiIDk%_XNfnt7`QEZQ#rhT;$m4lvm-gD~lf?F4( zzt$hW@uttkH;&#NGrfcAWa!b%3z`KEqEhRNo#=^&q7q+45tKz>O$%w1m4xTP6wA32 z$K!QB^OLc+ji{S-J=%@6_|O08ZLz+y6{Mw_!d%V-59ECx`B+q5{|m3{vOr?KmQAW@ zhiKRrB`s=SEEo@h2WEu9JOiLg%hy_jiKx7fb{L2&nh@yejb>3JbxUw@USpR#@qB@w8*6Wrd0W2KXVMHlg~UQ=ybGYpC(FV~ToDF;r2 ztZFs2JW?7V+cpotqEfKj1$7QMz#x+}N5Sjo=-tt==U^aW z8&vi$m|Bpp$xdWz?jdi;U=XB90IKfcNm={l{uOA@Ezrj-k6k&OzCI6T!k7b{bB%JQ zeV*QkBeH~PMFE&(cs1I1MDNEzpajC?L5!x|ioaeuv=4>xh)`hyu8*@g|`S zM@1&c=WAw0*;_m>UPGXhNC24&8T@J%f>Wo@lp3q|M7EmddE(jgZ>*8OkH(rLkIArU;j}PTilAw}L{E<(a;}TO z=)#rDF+V*USFc}{Q}OiDeVrGAU6KO_pCC}Q1G|RH^X5FUH|FN&9CTu8YC>g> zuP=I1RYg3KgQsz6c(`ZQZ z11IAExFe@VFo4tM-`cHiJo(gl*)j-{XpIm=9PJF?Gf9y69Be}R2a~5gUt(r@RP8*1;3uReY@ZolmosWMu7#ieY^T6>xKJ9an&Zw)Eb z><051vP|Ki%eMI+{`Rr>ufO%SX!lixVC83K8L7PWA&QX1$9%R%i98$%u9>+K=8fGb9pJ2HrC?VfB5G3 zgI|7QJa~RF8a+lbjB5IdK}9o`Y_W=Du*= zb~d(Tv;O$q?}^ImfBtn{HjIRAsDTd;svCiY8W;esViUM6CFcr=7)al3$vAOd9_?$# z!NjyiV^fEP3*^8jjK^X~ENKrh4^O=!Iu!w>Y(naPS!dF43U*k8JGNk5;So>ev^VU*HJq)BkYbvZeRUs8uF5H*KDBY08dD+iYi zMnvie)UzmXXsip6D@G^P1lf@|bOlM>t{hvIEI0lB{D(q_?aFbO;I+SjO6%g6P7O$0+`+x%-9+I=3oSM~r!|G4;;E=Fcv?Fk?>~FsM>jQC3z5ioz?fNxOMipTg z!mL~MFx<>aV10Go`}<>RY&@QL>bwM+5Jj4un>ieud-_Pg(LH zPMkazo14~Dz{coo&&m(bTef)~WkEK@H7o@BYAx1ZfevVXFP z))LTb3p8%+6syXL+oQ8p5l@4X6>NVYFbrs_^~Eb+@xplS*WG*QAQQ=8eF+4{O6#Bb zE_N!}dBh&q>9IgD}!10|_(Yv9CU%a>wlK++o6z4$)58qmv0p$Z&CF z$h5P!*i&i|Rp%KK6K_m+6pEq1!BdEbhekEER*sNz3|&z5fjIl*lbX7y;Z;Q(iDz&B zLNMX$C6mAL<<64~CRjKP&Qt70xv(Ao`!D`_RQo7fmPwQ)DauwuB}pnZxcHx?Xrc7t z-$1Y|PFv-GqK#AZY!rNT5Rq!cesedz_RLz`G~12O{g35%ZhJOHtM%yZi5TpyOMUa% zKmVig+24439AE83^j2bbcs%a=>F(=gGyzOmojQ!@OOLpi- zwD#kzzy79JYqWxfZ=G}aR8=PeVsqzi6c0&=@D`Zm z;7A?vp_~Vk(->V{dU4tCY#L`MM1*^>w(3L4A-L((DbJsv{?*r~ERQUREJK^0QbJ#U zT)%!@LBh#n$Ku$rxp?TIhvM9Y3+mpG&O-@eaCmSda2Om`YSZE!h=f(uYkSyWv_4GLm?#VaBIb8M{$brPx?2r|g53Q93)roC)@jg) z=)yK;ZJ4Tu({gQ+&WBp8ZmbmtW4M;zmyuK^zprOWy`La}psWpdq!5L&er%&m&#j4g zIiCT?pJYYe%j7i=ugbc33Mk>YSwGg9I<~G;*@MYn9Ntuo)3Ywx`TSh$bGQif+4q{< zNU*?r%*;$hr`3t;*B52XS!Yy42@oW{Lr_ug*JqHuQs%(8a4#HakR{3igTn&~Lgr`Z z;@tTQa%$SU#emQ$Kq-!A!^%H<2{cSfy_VA-(rfl46kZHR~jahyZV zUznOyzqm5Nc1LhAfwda#Z=t$4UN+ly@HK1jwwH^T2ES2S#FiY@#>_+i0Nd`@jBc;#J@B^26toa|Kvm z?uYw>r$CZOV1b<_Q6hlE4zR8yDeUc>Ps90F{aP1R94+>s*@}x7E(P@bzZ z=OQ~zZC<9%<zA<}zlrUPIj1Qte;5E2}=?PmO+zxuXlb@$vZ8Kta1DWyCYKQMP1 zII(j8$Y)w{)2*07fjTCuvRBgg`P^XVJF&L55_5w)ar;~|7Qe6&_x8-j0B5b%D>DB5 zum6eo!vFi%G4{EyO530f|0pW4JUJ4Jr|08Ck6(^%Ne~uSH{w6O=~rT602N6}8+&TO z|IoYN6aV7 zb#w%5N-G%78dM=Q?D^dk0#bPZquy$3E_x5-$cCX)pe(*{>Z(5@%+fz7LoS2eXvkL{8uJ?kfjHMjiBCqeHrHkQxjZ+WZh2G4}L^BQiD!)DFZyG$f-S z`Cu5=Owbeo3LOcbCkS^0Fa$@`|8X2R5Y}Q9=(z$3(lbUxjH3CZ+7~BIoQ{DZ4>hAL z6=R!&hLY=H=ip$Bpl@?^C3bhWSVx!ZXqm0cLGW zIaHG+mpqP|JvKlUym1Od+bY2QF1+{oka; z2S4>-yy(R*Qc%iy6u*Pll_`~U^l)uX$g(rSoFBE+3!XQTG21l>uqbbU2>#~Vem}Oh zO!&*7&K(&yG!?wwM>-k!BkG9?5M07b6v0WM#R`2EcE!_cY^=xX+EUDqMI3K+;`a7X z3`6p+*5j7vJTq?lwwK4{x4a`-dk1msTV4^(b|)4;_E*t6FdP?dJ{cdrwh*=6dMqw3 z#q0i$UyR#NTE1T&)M>|KU;IM+!5{x=v^ve>Sx6Nwg5bP2RS^pTH8^&rLG%n%&r*=7V0R0#;@Z^+#<5vaR*NC*R@TGFn-KxWI9oMah^OcpDY zpg^L`3K0LHZDfIVKx+5aQ?U3FUmjT1l+huxlxUA+Y)xL|u%bQAcghm{oUB9RpG$q2 z=Ya#H)<(cVHi}c$b=GR)PvjnPq)mXcU!-BE*Mr22yUtgJEoHQCEes3`!?l=&aS((3 zeF~7+k0Lsjas~GSgbg1h>)Vtq)cV)gtAK^~Lu`pZi`%fbtL&|RkV%FuO%sF{0*MX> zAYBFVJ*+N=yfw}cMLL|&`X)8K(YSQ+iku*XAc6zX4$4h9Fv`cs} zkx<}p-aF4n?)elg%kmue`lUx6j==#&8GCrs(8y3MUSCpH4vL`KIhj<1v;qh)fcU!y zw2AiU`ID(tYK9w`(#jOb-Cdw&KQBryXU^Pg)xP0Db&%wMG4VV~>s4mb1auf45-;w7 zb)!p!K!ofX+d(^?iE!@yCurxh6fn{vJV1BJHu`)*>NsOu6KAZq*CoF!0c8s&dqs0% znA|xvq4GyBK`zr7t37J3IkM-=tLGMSfuHz5*Df?mPwd@j$6q{M#655;8) zukw@UFT^{3>rZq(B&A$_B+g|)5Bx0MifC4YhiO@cx)8dHu8N4JWiA7Ii2V`5kekVp>`O>)QdtV(RwTO>@=Z}fx_@UmOINvuI zYwKI_qd)ay@r=7~mQa$~KM%Tb?b5mU%{RX#Hro;PY903;L&I>JD1$Q5bx?K>A~v?_ zy>vIc@)a-dKK;(SRNqnUl6o!~V$}pTA~|Z4DHcO!$w9+Wv!QqmQGGh5gslzh8O9P) zQN(nT0F*G95DQ8PrEi{xBX(&K_0e33qGl#|xwP%5pT3ZG^03J`DRUcAcE@H$0ETE6 zco5^JTKo}JFS3c5shQZ?W>^l<9Br4(hw$`3jm93Lm!64;hN`&+Wy(c&A+Hsup_(~l zqXXX;hlt2rkm}%o2uuV9I9Mx=-RR>dBWImeHbFg3WExKp6FiHPR`7-aF^XZ*XidRF zM)Wxjl+6vxoHblrq^6F3M31x(Ab9fm-uftexkXY+hYi}FEZT!1QK?Bn@eU!fWWaA) zNW}y!4h(^d5CjzZ2qut0hGVNAfC zn$N+sQ3#U<5yQg+v9h`m$LGl)-E&SR;f#xxUQZz;)51t|e;fwZ1LH=J1iF*Xjev?4 zE#U0cwRP=(5F)ODjN9sfhCi(u+EuoRgRV%F#m)c+&3@zl2rzKE1R`o3Z9=LYk+ZZg zS4Az4ci#Cl#{I}y@%P-@d45>8%(D2dGDNKwU;fe;WyA?wP2z(GV0Jx_IoGJbWPDtK zVRD1mU+huN3GaPtC7@VjGbig^~PCgimzIJRvYin+OIl}R#CAkiTpt<@^p z$0RmreNaZ>{y_+(t$?Uq8APP}4s02OJUX&k3Yb@ySEE)RP+1eTPD{W$Aw3!p+$dAH zOkf#f2LT8xu~~R_?|R_f@tS|}YH-IxB}(%?GWaqJ*iX5!Po{+8%}=&`uk zQ;(1I_s2qGC%*mPd{4aWdC!VY2OS^?{ms}~S&skw#$S)k7Hez*{^`@FVr6MHmRA>`ZdG)a;K4lw_os29DoTiyFgIO4%YGViIz!aqdx=Vufp%4UWtZdmfhD z1`=f|ec1e-TB;Q7dRU8x2$@`^@&u@cM22AR_X|2s1cg9@YbHx(V=xI35g?#XHbnNs zYvYzESQ7=+655iHbh{Jf8k0KvrC7PHniP%)g8%v~DT+$N*kR&7({Bc4rvzx(I+_F`#e)qABF)Yd+{k#!j}0wLg0j0>m@ z8W}*c93C=SlQ3NhgT%@~vQP^@_qb?E8vLE0BWs(ip=M_k;tk?cPiG>_ATYjhN(52}eKBB)*QO*e-7_ln^!1gVe3K?|jAWUH z${8U(Xh+O&wIURA>eS8ttR@PDNK(^H;(d`_3mG_Pz`(jZarUv2@mHmSxOjab#wNzJ zX4e+3$BAR}v9PkK8YV#zPES)2hlc|{A$i?GfHTU?bM_ntNidgzR;)L}oOpH&2?7nm zF|s#77g=NM1G2|guV0f^0i_iJQO>$#WEoLSM+SNh1$O3MJ$bUOAPQt7VQzwKb>@`8 zPpJ%=#4>9YFz1C~OLqFnc~ChI`=PTI+EYpBm0kp8BD;N?WPCzLBIWq_2sa(0mES#=v26Exa$-@3|4JxJ4rdP@cN$OR3L1hPjWrmu; zqJom9yUSenHlo1((DN%nkJ=hF=6+PIe;L>)@KEPNUwq3qzcQZvoM)&`UFmTvAht`h zCzKOZG`ZEN0-P_LGh}gs1(!c_+Nj#u%b6lj!%nk?+#l!DcHhQXiB43avAq%P{exI< zY(;AiQmf^iM@H#zK-M|MlnmFa3{dP?t`7U=^Pm4hjE+^~?t7jkd1X7|qD4^FN1Y*M z>MncP+5s**ygY8;8)$YW%e#fih^z=uB(l~=s%CEaH|^O;4Qf<9h)Rsni%ivR#107*naRGIYXIyhMc zhTd&Xs9>372!W5q)kH@!>oQa#quE3y_j@ z)>*SwXwRif30OZAjm) z8|9byx7|IVQOm2#hch2i=2|VDEtg7l{>$(u1qOv@Q2dg9E{;M;9OPWepT(6cs7E3X zX@g6Iq5AUR(5TQX2@#c1!?X;3&DY!=-})~f51!* z+m_+c0sYxFy4Yn+SFFYR-t(979skQ~qNm3JodbXyNQ}zIS(C{DcO_^@gw8VcJyAs{ zt!DL6K9_)0vnL89k(^14Q?=R`)k-%u8awfckNr*j)n`8!73T63&O!!y(qhVMP5}w{ zU<6R0#p>y#^vk{l5@3sV}834--%ex7+Y=WF^Jbv^cP@ZYi2~zt52Q~ zwt+LiebNf1E!x_THPkwXM@OpwpqPK*675of8ioV_ndR7;~#y>AYee z6D+E3KS-yTr=?Q1lyrHmwDJ|=uY+>-Zd*Y!>yU^_1_I*Y6jEOX5xlASQqIUd$j8o& z&(r&qpCu2$XOed8(HI;=6_$2jSva@r9UR2$+*EwmcYb@!&w`G5HbQbR)G{br)Deec zZgxiGUCtK>AGV!msQECID2qC(uD=8}U{Vfru{EyAOHQ8l@Isnooq)gbLGC>88C1Zj zGr;{>B3%h7K4^6&I0Bj6>6shrKP=xI247`uG6>@g5Xjc+ zHSrYWTU1`8bjgw@Pa%VTioNvBVITsNd7sE1^?Dy%3C4OBr?E5O{GKXU_|{KNHT2AA;*be z7!)1#d0Z>3bsbj7l|cRUu7)O?B@~yP0~XXU+{}XUJKTpH7~L2eP-2EPka~{z)pWgH zcncoL;x(}(Ef0HV$AMPzFEZ1|iR17&3<`V{s3hapo7-ywcfh;?1#X3{Z|wrwpZXP` zU>FIKxK`@jd=Af}ukP6lI3o^VtK|)2F&V3h$vJ|+?3-Z9^AZ738KQ$1zQ|5R9L2$F zsFBCtl8qfp^cpOWfhxAdq(6xEn@ zxI6IbUA}xxc7gRy`1k0PQlXD!R5@A{bYfu8%t8+Z1ul0wc}P(yP>>AF3F79D&Bdil zmttdcTMm_0vbDx$^!L%O?HL!4W07rU4alhZT+K1q-HW~f3;!enKyU&18U6=*h8AdA z$GC=s)OntiS(>}sI+F~mV$V>2=e{T>;T)R#yAmi%+4hurPo>nu?6r{Rl9!NVMSgyi z!0jlgIR6X69$NG^tx zB(3|zj)w*_{!OHLj6~^-0sihU&@BeW+G{1&4xjk)vd*}U6-g)-2CMK`0J?r+|RtW z3&aehn*pPA@#W@Y3j5fc-ytgz?)(p0u0Bj*s%E~awBz@P{&?q?>OypiP| zMFg_#j|Zwrlk4k;tx#HoMniv3BhF_yvo*k+LyM6z5zA!e^@)z12Pk0fhlgrkDsz3Qw^IAZIEPrn^980ME2o(Y#_;Ec);gF`Vc!5hy2(IG0*vFFH`MaFdNBF|mY)<{GbB!;!-fO9YZ zw8O@%WoIY+E_;jj=Dm_6rJzbRY)^gzvWF!PO2KPze(t|_(222Ne79TC(im7<--wHm zp4`9eJvpS(2An^eotcY~aoWU;(6B$O6q=tVR z9Ud_B&NG1n05{;+{9IgLxNf}%L}eJ?+=pnAH7Od~RxYJ%!oAZ@C^V+EFJ?TFw3@g% z&>#K09>f7yzixEQnW)+N1O*Nf>0a;%q|3JolJ4;nLGM$Pjc1S?NGepchyrMSwo z7BXc-h&{Brx+H<3E?r3M7bea!YzjmOvhQ9~!6IMSFDC;=7095euV-i2e$#=dNYK5# z(tY4{@N)_fXEJlj`j&m_%C;Rk1Wf)WXkSSi`wYms5Qob?E^xzP=AK-KdOxbHCaLC} z0izBk0N#4@&GD*NePc|F(Y@n9LjS?FD(B0kuBs5D>B&inh=C~3y@4Y(zl7Ew zRgyu=W|pNCJCn&3*Zrk0eL3ob)p+{To_Pd)wGItv z#MWjb78e$z3xG3(KSbat`%~u9$o~}Xg4gN>;vjvBLe9sYi?aAM8^pUc8JD9AEM1`v5I4iLTeTyq9Fy3PYMK;TmJ z#9pNmKmQ9q7jqMIa3P1^(cBYk`FsEDf%x1%d`a3VNzO*X9^aN49=y*@r%&kl^Y4(a z)8DKuFU2Q5^EXlXrJ&I8Tto12#4 zP*DY=?#w~5L3Ji72KJuee*Qgq3X(w<+TgN)7F`hau1R`oPjM!mL5AL=w4TTT(9Q*E zMq)GlV%(Ckc+L^ow}(GrfOCqVxDFy&8ggcnlQD8FJbxS`2gtCt`}w&CF|D_ly11># zSv~it76NfH`j#3G(yl}~k`IVX$;O?< zyIcX1;jGvJ9M_QL0Y!&QAS@*%vww@SA*GixS0el3GXNy2R^~*@Yqu+PJ2E8D8w*(t z3U1}ui#%3ZTRrrts;pheOU(h+%G!F24Ufdg*q8!3NNUs56LIYLyqwVD(o#`>^mM*# zyA^q{h-j(&w9AyleHly-8#4!jFAOuUJ*@c(D)fk2sdkpml&ueW%vs zqr+OCt!+>jTHPRl5-<-d&QK>lUy$u)qGKC%(5J7&zf=H zYA2j?u0|XGawaCz7qt2GE!$JP?PFkAtn=0asQqdQxhsf*#W05hhGBO z%)nU_s~Vy{>wwCWBgs-JW%+#BuXsj-JEzE)y|49Nr4h>ecK8~*+4qSD@q z12lNb)LsIFPk-W5@##;0Hg-Fe=97*}b?Hm6 zAH_-d;qUvNE?HT%j|-#)gb2`rI0#@QoNER!qAPB9OkoKAEQ1TYq*^*g8d#iB&hCvC zPk|AlRqN&}`Yi)4#AvSfn;cT@kybbhpN5#jotraTDT(MMmt1ihB2E&=Ybi~#Lf|S6 zk88&mR-#MIyzlQ-P(oW8@IUqRqpF1*aG-49Qw%N-Z+EvLBl{%I(hFZY65q0-$IW}JcsK2N=?UopsqpU>DmxIchWZ+0(ma3i(@VpOms8iO% zGpKX`N#mo~o95y+=~vC-JnASTY=<~9Se22_hg--FMF#g0+oo*no)L*%?G z02ATX=oM?oC~W?n=T2~prKhWBWpzpRU}AE@6DJvhG%_k@3Ti=O(Q4D7Fs6)BQ&Go8 zN*&n~1YNGNHi#7s5#{nURL*`XuV$@YHP+QN?Me0nnJ>g&1fG~9!dYU_5M`Vk3@TF*L^CWur**otvf57OK0|g=JQVH~|htxsAK5|b3A~g1D>Ysyq z+i}RLXKp?j-}xQiCLu7c5mKKAE=R1aSY*qI4!olS5jiI($F*k^RO9^Bm0*cuu0b}S zPK%)lh^`<=A}871JM8!bCd2#T>2 zsKL^rsv&Q^y$%w->7Tv0%ULJtrri(NjUN)dv6vjdtl0~u?RLc~<}l;9m_o;cl{n7u zu&1K6TgtN849=2FU?gJz&a10Fyr<7WNJH6%U^Fs7w}T;Wg0aOgWzCk)QFO<=2Eo%r ztrjtI`M_{&1_~HK;6dPh+F2B29M*xt6Y**UGp=J}NYWTiOwe|P;1L6a$d)#|nq%K?A?X^B@z&8EqyW3kDl}x8b2Oi5_ zQ&|Q|f@(vBka*y-8EZraMux$_z`4-y)FxK z2GU+&M3+~V<+PD;#@YF~xum7if&yEY8E(DhmbiNDn#u&%u3eMNy5xW>)iRf4%H1GE z-kjGF46^Pd0|X@(FJ01J#Np1(%?bJAISrJt=r}}XTwshrF(e4Jz9t?M&lJZGe+DB< zxdSCW-iHjBfOb_AAVFmcv3j6i!=4~Taz4~iR0gzB=9Qvr4^uq1qzIb6A0GME%U99X;GqI zShZ}y+6-W_uo8|*V^tela)NAfMQ0-Cm}LwUNhU?WkOmYn1_(z8#t>-C%*^URbN4uO z&;YhQ*~8GlKrAE4O1-4LFYR@*XT)gGvKNX$TOu0Y)mjXVQU}vO)L7rxR=XM*3ZKnJ zCo3VdM{bq=UfA8#`C-G8Nl53Q2%>267o3AOYJfxK5D+mVhBOk#j?D%K0mH**aF}`T zRI!5$#Pzc_=0rHVB-;VvVx4e07?tb>u*#bsK4de=@v7A`%MW&31P45*G?tWsk{G6p zxF2o<*@rU;{>&ff^1y)6lTQ?D0$I=DFdC70+OBu)x7=3dVL(>*GsNF3(rOx^gua|P zP`5pZ$;qkWKzd_sl}+ZzT$3(AmCAm>_=6Yffx4#0Vm5PR>5@Z5CN+Vk;?duz3jvh%&s%yY|;TSXsM`GfR6elK!Xbk1EstMJs0gjDpVO%+gLNIN8c;yPyc+LqBO4yD)s2nKoj5)}SBSLcAr1`m#rCdg08HlO ze7u|44KID^3%iJ02fHCM_7)XZ=onmE?4dWHm5hHoe)vQQ2# zU?=zM!sst&N~7zCCdYY`a^R`k(fjWfCq-ha2Lb6>$`;WXU_4+;+PoM%Ri`Zx0Ub&0 zqVTqD#&X}V96pYW&mSHej`4}%I5s<{y36R;geH_>91?v{{Z~^4+fpgx`kbkoJ*+-p z4QFyB%z{HoJ0uT*L_l;ZNa03UVFe zY3XF>XdVC=GCwCPo}J4;u}?%)tqCX-ZC9NG!Qli3Y8NUBpCX}FtZ?&a0-xg2L|J> z9{h+H-`iVTu?kE~l4jRbd?8nB2OL!{#bxNR+DuYL6=S<#_uv2Qm>551 zN6&CQ=@p>93qPr?ZZ2`Yq|agkq=GEaGmG|rj ztKmV^5(*(kwndnDmg{Tlat<>yb3#nc(4#szrJC(scikP7CCG4be!!G;bWl$h>5)xe zt3=NM>S853f=@8yNqZ;<$|+ZH{zPvLLBA?bAO*aOj=jTd;AquCH#XI}MahQn7KZe3 z;LhzGp#mspO78&Z2#UN(zwbSrax#7_vIVRv>1zAOO3KWKaL&cNlizDJY za6hoUf?AlpEe~wsi|gT8>Dg>Kkl>lJ7ZQm90_7U#=jNm+#yT@^foF{v5C)AJ9_wwf zE%Pm`4PYIAzQkbP-H|vC_nCYW-Y@Tw-{a5uJM{T4m)ic&;Bf4Ul;_`|E zmzQE@YFhSD(>6y&;@pMvx*zyQlrn@gqQOzx2vxH$ZIB>7nQ12J5cC84=8U@NK@?#m zCuMY?*{&#aXS0-%=aqvZI;8TTWvfBMyV@Sq87)FPsfk^(D%~x8=v{~ zXXE9se3>{{*~!pTL4XTeV-k8o`F8k3WJVf=h(QX(!HS>eKVy?6BVRhdK=dB?(?5?N z`2O#WRv{`T2f!IPoi&tO4z%|vji?OW+Edp9fu`w!R!rpUM!-~Hf^_^x+D0|4v2>3} zW%0=G9t|ZN6o6E?3}M96a^OT*N}S3>$c#b~T{t8kRGf@Zf|p$rudb!e8ryReLmbS~ zR!`aL+WCudP>p!=o8KzGJTx+@-(_!cO(Z8O&sRdKp!gA^*KjPL2n_0Vm#$omQ^!v# z*dl-*9UqO|Ml(L}k&i^>8(;R~E}KiFMX43yw5_zK*1+L09r}Smw}Rj#_+SavfEv{6 zVsdMY>eRFxH$Ug!VUxlLCV&7IMLdSz;o-T3&=Iqs*@&1JA6GjQHAAu?N8y|L85t!; zhOAfZnniqw`a6at8KW57)sqQuy1Ozu5u?Kv^5I_SJ;&*t zJb7GHll* zO`9yuuIs#WbG$jvnUz^{k03xnVn8+-gaA?iNI(P?{%HLHDg41-_$T~DKSJRMJA#S; zKnw&Y*$z8`AZeNcWsHrUtGlbKGP81?$Ln~WbSVMTG0g4@2`QZ+{R|4i*5qWy z6r)#ApEC!CXK6pRb3X!~6Xg;VV5FR3F%T3WkZTYu-p5T(J&^I?Qxn!c5da}rC3EI$ ze{a`F8psS1PJ@35d<`)tm&Ca2LOQ@SpGRZt?cj!An`Rd$=GDN7ScA05op7~ z6iX4RjD`Wul3<3t$M17*I7=dR4ky9SOE10DA8^Far^Y9RNoVI5b#&}^M~+tq!+r7n z);5b{CEF!XxxP3pfBB!jAC*3}J4P+5F^<{po5LfA=-gRbb5PjxjTfGWyLVUJ7YHn2 z6u532K{{v{YD76EhLxb=;sPS`l1K!#Z=5x7FZ-O&+}+t0-J|qE(7zqp`*NB@8|e*Ex}rKc!? zX0`=f3)cPk;IJGa;3dK`UdFqlmK86q&VBB@@8}3^fuIxwn6vuAI9#pyt%%6x3{2 zYiSj<&I~&0#pUuk2uef9`XGV~e%ffO=7Y$~QTg#te^~zAfA??8P$y&A?IozQVOp7m z08d%`5O(Aba!-u%}Sd+oi$U_Gb&xOe`sNT_x<+`6kd7hrLy^aql}HG{0T}25{bPhVI^^$ zo1ZQJ;XnM(rSrRA{Ji^P&~_NeHmRSJS>Ys4j!ulkrj+E&xLKeRtiPn!YlA4ED918A05Ri`lCD=W(y*v-vMZzEG>)`0A8 z$V+B^xqf<=Tb7QoBpU~PfZ#! zMpNQUf@9jZVB%Lf(Mn2G%9%Pnz0S2w6+_2>8%aB$B$cexIx;vM2{0j`URaW%34#7KYATyzei=*V@+{69VsQQ;Y{EU%O|e*W`9`)xxN;tWq~h5*qiN{<8~ z)Q1}zUuHRCH&y?@K%qju{0@#N4Eb;}xQ}#+U|3TFZ#;xnDvEMtq^DV*1}Unkujo`X z`VrM3dqxS7sfic@xHddj0vttvCa25%!jeH!YWg4t>3I$lJJ%JI0wJg-pW7=N>mQe& z{`fza{ax7RW0}M{9>SxfPP97q_R6O|{b`*a0Rhev65q3DAEy>wrKSnK%zRX9qZBk; zK7RH>GSliE1}h!vSec2UZD6<+aH+FeG6R8oLIF}#;1cQSy>kEl{r;rX*20T}agND# zcn^`#hKEo*=lAd5lh>eNkwmc}g>7hi1(hR+Z0*JL=`+HabNlG=Xh2e!6`5%l|??&yRof6Q^|k_HX~DQ&clKwn|PLG}Q7)z21~1*w^7e zw6By?uFE&S^{w(>{nwu@pZWEF?q}N;Sw|+dF0Twu3a5%PM0>B+X4tqrnaCJ!0f7_` z)HSY(or#xHwozWZaY5RM=v#qOLk0S6n2k$Pr%aN_!95_5!-?C)XD1)+h_~dPD~b`s zWx#!sBqe%8cCK7smb2rdvc0)&C(_B`Vfml_$3HH6_+lrHX7&Ysj08}zxGKWO+F+-7 zjt%7|nGFF30w$ewY1?HMiOA0AQ2Fk6zF#_D`|6i_(-Tw5wDJR@ZZZc6Qe>%POifD{ z12vA+nW{!N557WBz&s9TVN9|a+k8K}ZFmzQN}9yQ8N+1z*$ zCrA%DGb+x=JSGiz_!FX76v{G5j_93Da(aeDHbbc*s)WPi`#2)C;cJZ?L&f#Mu!bZF ztDc%NUnfTi1_(YJOhgvbN%k(wSy|}FGy@xVyORb^lz@OeQ-&ESBV%2IBmx?q&4ULI z)P}fscg;0pUtkIiXQ!4b^hTAj!1|VqkDGO2(Jx zL{`GHBlrvxnQ{(Fn+Sk$(D{94G-T9yB#S#bGzW22j!A2QB#7Ym>@28t+}j-|>{C9M zjF6Gqd^V1%m88s8V38~7J?XmhIcD9eIG)z-m8ghfh+9D2xC#=0&$17$F0RVMM=ysg zN|~ZMibgieRMtwy92}@UTmt*EN#gio{>n6`@X8zV43@?59n zx0lwdiAg_eYC7LX#gqB3ANN} zj0v1HlAxXE=LQU{F^L2v56%jtR7QA%)GaT}n_+M5>=>juwz%?2*cX<9&gkb)K*ny!J+xQvi$l_N~dWmQ2Y^Ba%=9+YBHQd8i4nuZcQRD(}iv;~Z1p3WS}(OX3Pu zkdPpW`4;Rybz7>?S0Bpgq;{S%*0f)feDRCFRW7fPMZXY%;;g*#(&N${ zN7QblX2wA!6L*ADkrHBx1FXY8{Fnby4z@SS*S`Msa_s;oez&%LR{z6$w3!K(H?(m# za^daotz;5VAn1r=y({{XcvJ;`aUtkZy= zDerce{)lt0t=TtNMFKdGKg*fDYtiKWoxO62?!@3o`Lpl+Y5Bnq{-%tfOH-w*;WiLB zHc4^TfWLDVu`3|7_yG`m5dMY5g*u~TR|Kn_DQpKpF3IZm|MbsG=L=u>t=_0&70Hev zdvMSu#)2H+Xj_RuksczHYRv3X7-jep&=aB)^kAMxeT%_FK=|nEQx_Y^P$4cP41KcT zDB@A;OT3gm*``Gx@j@l2GqWtv2@W5JKQ*ZE7JxJ{DtwPc;3n_iTa$yp`{8hCgCXd^ z!4tqhyyC&rel0<9zjqToCK&7Fqc8q`I%YW(eXhg zybh=JwhD0(yf$JE&zB7O1g3iJK;YV<9WfdiTGqz(XO04@no-!}3&Y~j9ffsfCCciT zo5RPRWpK3To?C9Qb5^^jQZ)vAKMkgec&Xy zKF$OJMSO1C^MUJAYGLi!6J+^{md(w1y@$sK<@MKpt-SHGpVjfy1Zx*%X=&b|k)Ry`D5jhyot5U6NF(4B>5i}s;hs}u3`*>jx~qCf-@k!D5|iy?Po?)4-vmCV@9 zycbE$v~8pA$b5~%BhReeECfNe^Il78Wat-X1^eWCb>aA=i~(omxl22Hgid}PL7{a@hkWZc+8 z1g=0sR2i+Uj0rgE=hi>%M(EHrHsV}>d#lUkwbx%N|MZ{zdbv7h_DOn_E!3fDLbS4g$b@2XbVpPb z%TFK_VftJCAUNrFdsOB^or0Qxq^cfP#3rc6O^{#!;j`)EANAZf9!DNZ3x-%zySu6| z99#~Q#lEs;>P84bS=t9>t$y?RqF4UoAAhs_@JIhxR_?CV&LoKHXe>mthrNSNO866z z9cU`XltV~v@XWH&$xK@=3o5fe=40Xe(|?^vs28TKaS47V}i%Z zU;(C!gR%v3k9M<;(FHX~mF{Ruv(^stJGBkI7Z!Y!{ zC(F(@?UG|cIM?bR;{A^=$Bcr znw%L@9ba2XKCC}$W?LBWd~Ls^U<{HFT?d%;5&1xP0|SwE)M3jy29d|nVPIVdo+uyj zyXJkc}g?`RX!oF6Ado#*TFGb0gTknaHWAkdY6agU)YoGoQ+^H=E zICSXs=iuc)QD!gzb;wj$)Qz+#OMWON0}LH?Yp$gQBCMNjv6YX(bASB!bpx{u97?x? zXhp4=x~D4}TD}NfNF&|yi#L8+-g@&VW&~S1+Z6>Qs0lxU43p0?a5|&i@5D1j07WSW z1aE0^Ng^cyGv{i-G1%8S>sHI<8rfqx<2Xx3sdLUcWpgv6KM*O-10@!M60SWhl~WEU zqr`yn-rnwkB}5EWL*FDXQtIlCnGA66a|;Xd4zLHH5l1H>Qsao(=V%geeHb*>3$;#y zOl%m0PlAQzh zZu{;xzf)fM)Wh<{-}#bz@{`Uve2T0=!h^P7YlPoN3;LZNt+PNj_Dy?n|9!pY5FGW? zzdX9TaY0%nRgsL4C+oG`4m_$%d%Mot!H9eYKFh9}0qwc81CN18<=p@6FaN6i z@P|Jsn>)MZvd8&OM-tQkca=F z<cxPqVAcMnCG)zzf zA&Z(9&MR8Dp(lv9z{ioKwvJp0 zX51&xGl!G)V11n;%KokafI9H1(1ip^>+UPBewjgl{WjuwA#$~b0%7RnS2J;B*g zp1>({Zb66G5Ac5MtYYBR0DA_cEwdD4u2=2>=bY={Oe4|+VglL(%ESAT&EL7RYB>Zg zfB06cHD8qC5R#(91N56Y7o0W7u_O>UHR`)03>b1tpLEXDXTf!_KESjDh;S7Q5NfF? zIx3faG_I9S*_-TTYtI9bR%dUpM!dHq%;O{X4re@Be{IR@XS;D}{lQQ*gKjPh`xAm) zoL=9tTK7(OQ-ivb$W`H^YAeH&iF`8l7d`=df@D%Mo}|3A^|ddZ_ARH`PqU-N9KHa& zh^iv!G)Y9uW@g-IfuKsvZduZlecv41n+P3DRfYvwd~~x%yf8s&N{JVCKsps`zyF7Fa&}d=_g*MxPSBiLAaoWcc>}qjYp;zC;Crgl(kgjzRVJsV z!z034$vHuBl!>OtCOMoHeFoxslscK%)_Kq9 zucz;{%_pGUu=V;o_`=SIW9!Ztr^}?PIC4H0G=PI@pS&`r8QudT!F6zt7_LSXgXM{^ z)BOkc?6pOl2E)&F5ZOXH6GogT>}%05eEeVO3EO#g7qBpyF(ONd(a`NU=%UT7!vNEduI(XlC%RZFD{g~ z-+Dj#-Ec|jIwQ1{HA`z4JOd=ML0@cdB;avgMamw^fu7I-f^)+N23297VCcBN%@q#sVuInq;5&y zbyW={$iZ+*T(pdI>3b2lAZSAn`Q*K~%Kjcixw*2wu~{D8zh9oM6U>e4WR)P^-8Bp2 zInsVh01vSir8S&5fhK~cu(JRFAOJ~3K~%x6NkKo0ie3sNVD<&P6pS`m^p2c`pgR~6 z_85qd4zbE36OizE&N3Jqji{LFZy2(10~io1&Z76kxve?~A>>gaU{(XI#1X~9*-Pf6 zE<4(E2?p&Jq8%7%V`~1qCWuGm#uGGC{=Dc*d6T7YKHs#fhai85a>zN_DU^U1J3ncg zAZNK{bCy9Qhz)xFxyQDTIeXYL%d?zq^+@Ov8JCRAJ%Awcef9_UOklxzF&hUp9b?$j zjsYk4N^s5l(WMjRR|w1SeL{Gn6qvv@IyZ>{QUk{>H+%ZY8hYS$ZE|&doDud{1crhH zJHfVT9JID|W({D>DxU#I!?^)fB57hTp!DZ^Rg}{!tO!Uyfh|&7kLJ|2Etz$vFqEC+tf1vRUYSeRsciaRAedM8!9^4K#YS`4D ztx(a0n>eT+5!?zn`fqT9Oxy$qp9mVbUX#W=r?%$mFZ6oOKl#ZIe^~zSpS@9zPDp-{ zO5YRpTOVVo&mOsApWDL&kYRbW@*{a-ejHd+t>$6f+V5L zcTneuB(ytHzWI&sl+N#c>34cW=a9gF))Dr}^sOQ1sbl0+J0yBmVinK#>LNe9kBWsyBUkonBj!oalBB^Iam5@yesRpOn7EFkoHY$gykO`4-rjvp1)7K1C zPOTk?nCk%IcS71#;B^cH?}OuhzP=d)WeEW#!pvhQ+Ryl17CqxcF=j+nM9VlnvNsTd zMmCFaywVvq)-D?33_)s8GJW`Dn;0r;m1YD)ew1^@62t^<#z9VIg4rpW6M?}%8OYQ@ zKyW@7>27z(`Xr9VHarMU=a+Uokm1;t3h#hvkF`yTjS|>D6Y)aiic+Dl6rB_pYp0!| zpC9!1Zfrqf6BXoyErC^k^!C40k38fx3cm%Lc z4YUaM*jq%gX8kwxshao@*oCWs)8bnAH_wfrf%jayvuf82yboCO>=96i#;JkL|Moj? zm;3kb+HC*{l58)1(>;5L<(f=}i$j)6FdW1vs8xbcIusD;5kxIJ`@0TBf#pqh-Z(V} zhx-PvkRLfG8|xbhpk}5syFfA<#L{lLvwBwumR@e_wM<#98XmcRGS+ZW`T;XUt?TRZ z^Pl{vtSm1YAh4dmhujCx2_wXx%9ATfwOl^@;Ax~;McF7L?v)ADD-RDeE_are%hv9W z=M~)vNQ*%71RDge*3U;reGLHs&ti3D#d8AUVH-4>BRo^5S4QxLpprEtQzRgT6qvzs z!2Wbb#eu5nad}xDJ$hJPY`(DMgTVqtWDm)KaPs3}f3Ob$j^(22ye)^-v)8ywatEp~ z7OzhS)0k(6pAifYq?mB1UlRDYwPaf}_H3pV5wwzhMs}Ln2Qm7b2lqfXZQ2sk*z3o~ zmSZF`*Ga3+=1{`=vK)dU(n&Qt6MYndoJv+^GAigM=aw(Zq1Yc1CY>PxLnRdUA#9Wn zE1@tB>sDr8ovX-0eLcxQY{pHSr0?C&xGPejdSFOyAv|8CWw^ksXQXme2Nhkj+bwfh zKH*!jvz0^HMmF~elc)<`oLMsDIX=Aqu#60j$!Q}x)UHfUmYLb|Z+>{k+oFL(|5-KZ}&;qtr zG6=d*1Djj(CPZc&?R-_|w>>a@fe4aM&u$ zU4#`5G~IL(l(%$nNZK!Xs2H^d>vA~wU5sTTZP63Yd&pu(Diwki6Xu2(OPt|H912BU zJnSgbO@wu92Ss3Dc?3?En>2eRW8yvzsw3k*haq%Q8!knH)7I{`&d2scC0tWJVWSdY zlMUO7cXck|3dg~QEly$LXSM^+9ioxlBm0Nhd=9n( z4I*pLKp(Oh$}$iIaVA3R_9sWMDXjdERLSlfyIV=H7{jH71wT`mo8dOcNA_C_yKz5| zXLSzA0NEF5k-RpjFhiS|(6O~?e*{&cM5D-eV`vD-Vww!{MhBg?N5BT(;NUPMF&wik zcEfODC^{FOg9TQv$Z%9tnfOxId@m?l&9;@6v^S=>@W6l&`4S#=^kNU z50xDq3oVurUgEk}R@TbG(y|)^_?ZC`2nPGXV22D+Br)72j5?YW zmN&_qkjp+lcVZ~dpI~Tua;j`>Z~OZ#0RUaIlShJbf^P!HM*8G;31kUmATY9bunj>2 zXFs77h~qGLx$b%GqAsUr?mILdFu0u8k)h0mX@qaHxGD+GGh$u14&DPt#yM>yMoDb7 zY{s=OFE1&EMgYV)28kf}r_Gyyie0R@l|)?>Mz?fI?0vI;v(F4Q3L20MRp(vNhF0rt z$%8Wj`h0@u8Axd3_v^4U&SC3(NI4;2X6i8WYa5}1p=ui;KPP}9pwkvOw!Og4A3btEMOY}@2+@N^Kd|nABTVNS_anMobzJljcFe?2fNZNH z1s8@60~4bW6IDu%_=c(R3DHE>)RxiV1X$O-l*~=wKw2GNkAmk!f+E`+BW8tPXr+jD zU9_JQL}S0PpV-pF{bQ99-+%AzvW4AdOac6mfsD~=$oJOnmNtPQgM1HEkbTG=C;7>+ zwj^hqAxiNrC{o90Xjr?0c8uJFN=nC9;JfJh39^LX7R?F_IisUzqI}~Ue^NSs__eS0 z$gGT7FR8;r9z%JK>@mHfY*Y>>hYmHXCZJ+Xla?&h+Qug&E2TdZs1=38Xp+n9CZp*K z7eShXK$AKs5IKgX1t2KmQQzcZRSc_h+S$NPSj4!hR)+&kCcd$OCi;}nEZ5i4`i`wULO+}x~U7<>B=wCH%CYdfT)&YB`?H}sYQQyqm3f7gw$lh#5h4th>ot$0D zlX-CezCjZX2>}uM?3oupEu6AM%NAhY!&P7{`8>vqw;3JW3$q~Di)dN^zq1e8$ZYPr z@}4rb+Kf5_VrV0L`0#$&*x2+wUwZj9>xGa<`CaxNs0bO6r9aM=89e2=i06P@5$XT* zNB{PbB_TtfUTP$p|H=R*d3f*j7fk!?i8|2Q(g`sN3rBekH66zMZftMLL!wl|etPiW zzVN-e9;&)#s1yeFQ?I>N_6~OC4D9V!J%Q`1AQVF+AxKc~s~#D$Zje4&4B6{C*j{ne zb?g&}VFF1AoETo-hwC6PU=K*>t5aPOK%(1%@)UMqabeE=25JM63eN;Bg!I;@rp$T< zP7X*8GRgH~liHxGh=(0|W}Cz{fea`P&#iS;@D2n8T-W(o29g~zn?>qjo_o-OT5_oN zH5qZdYHOdgK5uD>Zll!0dB)bkaY7Q7E2*w>AoRzz7SH>IlXknaq0W&|-?~=cYv%>m zj6VpUgz?HjHQ0-mCh5i^d6WcttN1kGhEBM#x3}2pQWt2K|@HKB3|A< z!5tTok=bG`!WFHILL^xv_3!NM$nj!=CHtoZnINGA@gx(id_a(3`G}H|%EKvV;O87A ze|D;#F`qDx$)YkTkXkuG2ac7ow7?xa03CkqH^&%olSJ!{ zC%_`7=Q;$wri`^iWN!U8t(S~@wnjWo#F?Ojh!}(FyoEl8f~@Z%YG;s@Dq&^F8at%P zjB-7y&I3MzBt@d>dJqYesCNQovC%VGEE3SvFgG?{R7qLbrHI;$xgKoWnb|3aD(xN| z%JHD*oV9_;Ojb$6$Af7bw_jI90Ld8#Fj=GMh$ChF2*Sujc?Q(RHSoPi;IdKp%t*Bo zy$_bFi;yF^UYse7>nn_WHNXm5Y1K=77fNWwzo=mxa%1rv-tS= zx?KztbV(c^mxJR>JyhTcM9W|lq#}e^_zF|g82P<2K00D87od^n$w*pu4ZokjFWeXy z$7C349$bdI0t=mBllyCvAA=sG6_4k`T5NCacwI=elHF%2V}xrU7QX-Chsg|U&G|F` zW3_8{=TbnP;T(B=>P1NW4e9kmMArx1TiUpHf1;4EE~|>hl+FX&_WsoxkU>P031@*&z~$KEBuBpE@UqfLRO`$sJq&??%_$4N*!o>vkg z0s&BxbRjW+24ZaH5ZS?3s{#10aK2K`r9=uE&pp#Bk3IY5H@}-8p~-cU5m@_&{Y^{I z@Q5%BnXzyYYGKvTXOE@*h%62x1&j%NolXW|nGv%;Zr;A!s%?)U@^DBZ9PPJd@VV)R zAfmalHb)zW0YV3L#;HP(z@k$VmJn21N4PPgas`?oN@acmL!ta^hrQ$;jP$FR5Yagg z6Q|w=2T3gJl`_AuU~P=Z3ZsLuw~YjdQW@lH2{k}8+#_oc3Qgc3G7Hq{sQGs~*TV6P zn|9tj6Aee`J!jBOI2*{bl8wTS=V3J%6%rZ(H{ADwhY!_X*hE07LfBCnBU2nU*puX? zBHUnk_VH#JpCGt6EO(X{3(zvC2F5nfc82!w-WZQoQzd9wy+dZbtI_AZh@4g9stk4Y z@o7b501x6)m4iYC-i{4*V6sJLd!WcyVQeB@YvKews#f+wLWC&|Iz^kCb2JEEhD2Iu z&0~3g{>Gc-rI#P~$8w*YWVjH{vULL}#oQeeh1pnNce3b#1Eelg^Ha6*n1G48U-l=h zdLTpG*TV;E<^A`bq}C_#^;%&YIS{r6_R8bOkF67uG2##j+@efJHg;y6*6SzJzDCP~ zK|j-FV{1!|00J1gR=)Vf-*qpc07}qFnF0969<8@mJrs2mC2s> z_RIYT58daScY<}!8qQatBh}raJHdOicexKlh-d@m^PjChCG?bF%WGCwR^87y2?(96 zVM>IxWSF(JkP^h|${kB`z`CsqOuJIcFQ9PPIlf2=Z~%Eu zki}AdRd)W)Y6zYe7iE3@xk0M;tcDK|u>L+;g=z(=uaifp0-dexB^O)$JWb#d~Ro zQ?`&;TKC*5FTa}Fxsxp8cl#X!w*rsw*KUN5)CH)W4>wLbp8p0#h@)--P${`o(qw(_ zcFhS2+V9hPU%N6yCPKDsh)Nr-6;8uVYh~kFB$lWRp|=NbHGW7P-i4$x2?wgYBpS0* zGm_;gJ%9AkQ@eBUsr$Qo^ivDCDU&$|Q2>~25)|+w# z<<}_A-iR^LJisg>brQbtFMg|ME1s<|=+sX~5C%xTZX5byZNsr$C*x$pfJ|Fhpt)qS z!$XY5q!tt&0fv)t(UQalftMrAoY%pDNEAu-M?F>jePwA;)EiAXfPqu{`&C|*{`q4! zkdcv7_-Ml%)|qi#$hvYUMI%Nc2!$ac0BRZ!NMZ)+ikJ@BpmnP8+INaH_33$;osMQf z8!OxT*RSd(!APPohNEE2X6o#~+GKVN+ql#y5@c|nTnn23NErjoLnAOC_#xOLi{l~l zV2K9P2@x%A9$GT`p7PGoSVNCd42G6qFpXeT8Ip#y{3ew!$Wp@IyFgKdyn z>-^yPfCBLB=4a;2VyGh%kXinL3<<~LDhL5zd?vN>1E65noWApDDL{^+l?)^CVtYqN zNtDWS0&zI0ngOf>2m)x;^~F`0U4YXuTs9!wFq?jO$bmlS#Pe)<7HxP_doCDJ0y`jG zjz1^{&xBx+wO0V=0$6>>auB*2w7an{S#N9Wy*JMX?{Ai*`xRjvkh2eg1$3!vld`f4`Fd2xLT;=F!gU-_dbxDwbZ1?d=nVKT8VTQ$OcsJ)4<>dU#z(a>eXVmqj z*ViU2HoLL46*9IYH^-L;0>AC>O<5{Gp=J8FNrWW#P(ug;n>Ij0A5)Hq3aV&?oP~6h z-7aG^2h0z&Pf9??5Ab^}un43dt_1gQdvbkm&LyY}b@NZZ{_Az#Ld(um3TWa;H3`4b zGN|9E4Tj0&eHJ&m3PDpMM0Pv4xZ!1RQ&j@FcAGTrU4onhBmREBy|b2hj6z!1N4vTN zCbz$8UfoA4ec9~*Mc;8=Ha6EimkfeiT4Y{Hl9>?k)3L)|ZOX2alj-8A+yv1pd>QkP zN>DJ!oA{W^vrEq^yo{8`Qo?Ul0Vmzojvzks8{hhN>3ro&ziV~IjfX&r%5dph4@qVx z`rU|Uz_LDOx>THa2!feh#X*%J+hbNWlEzU}lifctX2eXUq~WUBA%+eoO61IfB9Uxc z96~nTt^zh(CNgne|PsbN>+7ZoteG z14?GeJ=4YmL8)iI?r<5Q*ZJV6tgS5z_t{6vuqD~`rA$r}V4!MP^&_aAQRZ-70WG23 zWHh}Dn}N{C8V;d!gQ0{sN|B^W|l z={7d1le)f?cnDtr$D-V~hCY)`d$k)z`Ro0|(xDFC9dSS4bU0*z`O;3yV5RvvgsMVB zJwIc5Dg@R@1QVQM)R$M5%FD03?z#fU@9yr1F2UOnws+)uIu&?-G62geox$>d{r%tR zWI|@5ghq`#yaAl6B4q=EX7C{^5=aEfr)>(J$h+@9@$3kUo`7&oHXCWFd8FaU8&7CBPKq@l0v!V&2FwFm`**r#@bH)Tw){*Rnd)UA}#Uk=_yLSzt;7GT7;r)4-@53MHB z0)rcJKWiyhq>?|q_PUQ+DM$orpi|y?=dC2hg9Bw@cCO6M(gu8JnU@YW5mI$s(zVBP z;Y{%a<=PCVJ(jbN9R!^XIe$tuRXA)U6xfj@>rwZ0O6kc_rm!l{kKMm0fBOBuD4nnV z-dB1t`rR@-2xFIah}3eM?zSVpm`wElX{8z(E!P9Ra(PBCX@*cS%bWLYV{SS07!Lv^owB71 zHhoG81`yQL9eOlmOD2H>Sr*1nh}w3%F$XZAPM5xIARgKQquI{-;qcf5K&otHNRprw z2)>Y=I>s1BupeD}?ok717IBp+nzd$5W=to=)2Gig8f-$40}&&%z}a~47%J2kdErB) zVlmb@Kor(MItUc$1|S2+fD&k+D#^1`97lp78V2E~I7<2SMA#hT#q;0V0+wBh-o{xr zV%X^u!o6#&YnkMSIFmv|2x(=kGoJx>AmqvmS@IZNMgWt6wVrs&Jxzg3aiHs7KSSft zsb4_H$k~Mf3Cff(d^t3%3yupO2Ko{ZVF^mMcD6E)V`;H`{Pd{~jbP%8sfhFQg}FFn zdN>Aq-D!744bf5B$O5mIrNsr`gWz+0b5l+UXNNJylQYw0b?vTY7G47bpIReGmn?r2 z3}*@OqB?5(Zq3;K{_p-)N6GaEi90QKR_}ypTL-xiv`BU;CCZ9*LhF-{K6KA>MnQDo zXAmgj@PRcKmzNAIC{tPHF!(u9?QnH<#WiFPH3?!IZaPe;`7<<)faJ_cu#qB;EIPmc z`0>N?!G|A|jrC1CE(jt`G$^gm<2?ZpFkKT9lZd;4vLR!AW+1?4&Cbqyra)_O2-(*? zNy{J|1i4N71V|M$i_RJdV#<}P?#dh#cp0d2PKNnyJ9yAUVWN^fNKATdqPA!joMe+Cb)5M$zCZnkkJB9D1f9qY-;&9{>D;0 z+&>U<1tP(iUK0t{$QE*$gQRw75lqY3;Bcg8$re>X?DAQ4MD96(10=H{<)V2_G|Ll{ zDl3bV<{AzWn3%HGk5)Ve6U9gtfNYh6$omrEURooEt%mL%F?AXU15ht;zGQQ{#6!-4%nZfS0muF``^!9{8a5 zO-4q4JcjA~Jo*o*7bj@2l?|heG9`nP#>dM1EOqLGGBG`F=>#qX0yh{i?vrenKIo1MGhSI))l?jSvp^4vx#jScX9nER0W0mV5Ued5t)&>6zK`{Q0w#fj~Q|VkBpc z@{N1GN^1Y$umAV*(&NY8I|vDZjqSs5Wsn*s7{7DJvxuX6@4Y9YXb$-5$+%%y zbN^&*Ttn19!(C#plGUJ}F*ZIacZk>H__;1Vo3`aAPu>@aVr~fh0WzJ|{=5gTq@Hlxh>BbRAk-Y}Uy#59e z0FG{fMJo+pD-3)fomw(YFw)QDD-WV^2~uu|q_a-3{%%7BxF-Tg1f;NopZkr^C2^}W zDjHGn=HIm=0aT#!*$IvTSOfv;;>u##6(tRdOJc^eAZehjolYzg zs|-%OQuZ27%<9^zC9OspwuD)O7_~+$i={k9$H<#+zFU@-=E}^>oE!^EY^}qG1dwO^ zXMg^erSpZ)f4+yHg8kP+!ya(6!2!lcX1uEEP4qRBX`@+R!schQaR4Kl6rrVL;5*(B zkCgTb3=fACLoZ8raL9Vfq!Q43wVs#uKieTIiKB_DpxsYKjG>8oV`@zpAe<+QsKzc`;UUop(xrdLRf2>jFp2&bOSirb^W-Bvf zBz7c-o94bECqqM#_jM#Q$i#8K_a2Cnd!fckHuCVn1M9zBhc#J7-qxBih8y-d?0O@_ zg#`mS-j7-^upRYxoIQq~K#un(>SRMWMRR1Ntlhm^e)5x_l}8WmdjF_MwzWk(hrosT z77#F5Co*3a0~DZbc*+5Y@odt9NoENQs@?^ynW*_?+%?%uQ((ksvi@WQDp!t=S2iv+ z^E|sYgo77nhmZpaKFK24Qv^4!y!xscWQ=!6pU%V>9u`e;en^!##TeTy zu)8a&(4jn1;Z=;Z#`^rc%+Jo6z446sH;3`X#%7rzD&N@=l_7iH+utpZ9z4i3RpF;F z=|`+>vmVswK~@mzB4A-S4)F8)A3U|ZaDED67LnX`bH z&fMIBK{^hOdNn=z@4oql1UFk#M@B_0I6DYNQ8ppV#Q?RzOOOUzCrS2lhN5v_NFRId zI_XMcpA(R6yx1~u;(2}QQ?ENU@uQDED!=ynYnE?_+jE~s8a=ctSnt)e@h;ZVvW3$OjrM2xwtb-uT5EcDOu# z@X+&sFdM-N4#;V?SLtj3m88ps)>EL{iHRu#Bgz**ttLGP9*uU*&>)VbT#>mO?#s(7 z%L+KPCS1cFx_9?pdF$=Bd~T0ldZfX%vxze@iXAvFi%Uy6cNZC+=zsbL9G(6J)*Hd83rk zzU-D5%(&tv72N`cw8-N4;|%-nS9t(F>pJ2*`zcxt5MhPu87D8nIAlgj%6!JBKlN*6 ztUJ}8M%e65h>)=TZ@MsA7T(ZEuB{IgG%4un96!N1XcEb{B86!Dl6ci1pz24o_x}HS z-`nrmN(cQC$gP1|?H&!J8XAHU<{;&pb5S$SyvZsvW#(r^0a!zlsAtdDwF@8w{2twE zYH-lKDigGxv`~o5!d{k@BSIx4Zq*>MT%f_;Z|xm7-MXAf@HeUa(o8EI-2QZqPAvLMMEB> zvk59`C*dW-YM5d;;sFeaqVy;GahS0%iq_B)Iy|J*EXEi|$YBU63B7`}5kcGmI%&*Y zS~WRT3hbPmC1X&TkGfo16q_&#n?8f0kVPhAUo9J(TV(>_m#Ut~VqrWnf>SeT9}Lkl zh)Njn)1o0bbPgy612R*X{%NDa5D?9&<_KwIB2Z37a5LlkETSUdmWK|J zPqsb;LQ5Tx{?dNRSYhWdFhz10tS%h!}|pNNbhSKXhU}O+N&??7$i+HRH})O zFn7a13WQ>!98(72Fkixb$hcp!aD`#WcdqFjk&&Cm|YFW!71Tq95A&~;FW_VGiKLS%n4ti>4 zvTSYd_#7O}G&7^&<=J{aI%TKB6>HC(tUc}ExCLTR{4& zbN>W#(KHy7hzyC-0dR1UMl(T{5z+%CI`(_Jyci79vzs3r4~J5 zAc1q>tW&bYwxEQGFXTLf;2n*L2yW-TTJbMFo=2Z9-(MnP0;Hw#t) zvLPcIK`*L1J~?qqFcp;PXrjZ z5CX2_69K@jlEW{f2%Z(mp5ZKz5VH3Vj}o9$(&cyHjFF&I;jvDQW7r8u@9^pv)VI2N$DvNxmFXE~ zF2UQ2QtCJVYFY>@~Fatvab?ow$klDfBL50PbS4YVfGPIUcrl1W+Gi zp~Dg%wO&RRWQMc8UdAWK+>{tW46<3pL|21p9l7!l_>-UU8TNKkml9H(EOZnQm7Bq; z`yXjk>(|#;W`pbNFEoyK*8+p9URY;2U>vE9Q;U7EL#tKD8&1jdGowO>L4~-*L&!pB z+9QxT|0cR4=zwU%>!{l*-b77RB2H!^V3-InG7WCrO%iA|Dr`VTO<)Qq%onfU*`fVv zLI+LVDacBv%+6A-;kDC7mdOIod@p`Zi=}eS749UH;eCwWb$}P;@Z=~40fH1IoI2l} z`Z-(#B2}IfYsqJ*mWUB06M*+HKd+=P^(r|W=Zx!~ON3iHO87p;8BrALwzKmd05}5# z7;I9W4Tb_^*MwjoV_D0mSA1;Dfl@@id43sWg>v935PBtwHq=3GL=7l^natSgp{S`1 zR)H&=4C~XJ2us4}u$}}H5@?CaJvh@bpu<45z05mcub>6O2wg`0o}bFQX@iJhxbwQU zr`WSV_RpR_FY`0AIx(E$%JNz{y}T?hJ$!6HvdGwDTX54`&K@UVCBp{2fH6Nt|NQP= z`QXXBc_wo>$}PDR2%_-(Sz~5pVE!e)Zf%(%j}XM|?TNN=R=GZYm;FEhxFezzrvA>0 ztujvQD2QFRt3xJGLot)n?X`Xe5fJ_2}I2`VU!~uQ}=M|en zc|<$JAT+oWl{U}%a^4`VVG9tyvRr&}>iPfWjGMC^Z9hIXd%MB+t&^aykI*LzrhK8I zZXG?%Yj3v{>N6W*(sIU4X`&Gy)i*f+al0%J?my`3o20EUvh*Z_DKpbr3CfgdmFdX1 zC68Q%*TM&^Fn;~rCd}5#5!`EQ_jU+iVk3i-+sFhzGkIy8iw+2wo21SU?FhQY%pXeanuem!g)AG_OecFjMhJ!rm3r$Ia4b^%%%#{ z@ON$w&H;vz7hv3p$O$M|C?Jz?0k&Ky4jGcUEi!}s%7%iF#O6UK09eh>uA@2mzC({r zPK8TCV5E&}T2UW1*oRz_dqn@XK)Qdiii%?{&tL4BNAe86KG^Gl5F4c@r;gDTOyLM9AHQ?Y!Lp95ms7u zW7}vxjyBT(d0whsI(6F(1*ET5E*B z#}|AMGGc-pf=DMHPENX42m(;cOPdXy9U~g(HkFcR6ZjNj%&3P>#|sZdjrY9AvQR#= zE0WDYBIAAtQZLUlEf8oQG-YOfM#pH~y|TDDBz6a=v%wU}oBnubDmae!+&*+#$r@Qx z6hb9L&iQyukA=?5XrtAYhgsczo zsO{Yyvk9E@=JOZU@|!$tVB!-|j-k;ZgCv5C(c!Lgue1ctFDwd6(jvBY?{0bX=Wmp; zE~KwIxavBA8Ax9lMBo3&=LC`hn&fmsh)Y!ug!4psDFMTD8F%t&$C1fqleA)Tt~%F} zetAyJX!yljZ;AAvK|nce>&2#AAkK423zQ!~zB0X(c^?G2pgAW7ty5)!E{;9s5rjd# zvx~^uRN2_tE^BnKAW+u3GI4=()nWO#fv0Vu`rloXBxHb|7j&^v1e&+HZWGt`njf5=APS@C&$jz@-r zJRsn7-Sg)JoRq`PP*SYYxlPTJH6I=b`E+86y+&sV?Xb*T8Q1Y+dkIvYJ_kAu7l-wb zL%~E=#$MC;0Qv&r!CVC-#hFkGkGDehI5E0O6y)K|c%FhL*vU}4#4P_*o?6rgQ@0Pd z;Rc<+VQWXL_Cm;uH;RP_39&}%ohaIMWw67Uw$-~k=6Lv~q{u#vvk!L*SB`EBLTJ1e zUJO72dNRxN3zFPJ0E}P|@1taY9T>G zJA;IjH%w3}@*sh-4it<3jPJrH;A~Sajp`@sBOErdQGD(ndKW%noNbD|E#!-nAl zNRr?seeZjJUOK=3<*)RVXatUx2p8C#8=)?SgX7?AZSPu#;^zvJR0q%|h(+QQrvL-} z+)@JBK3_m4WN3;cRk>BNXp9iq!Q?pOgByD^L>HVX2P*Z{5uKGIa~&4aG2`Gh6TmR2 z;sI6liu&%VB9Z|iDGUlRKCZ)owN1ojs~5sZOt?JH;YWZ8gTn*mAabu5J&Y0e1fdZJ z$UTh%!83q_!Bez@9%DS{tM7P?>9r4O2QC8!mIocE{nV_A%o~CmyT<8m=qwz;&L7Pf zW-=frLPl7LOp&N{rM9zyYP8lHxDgE1A=`u?#eEQT@jNJ3D8o#b21F;P5ubeA|*Nk{EUs(*xffhyOe=|U}rr%83~M1Zb`=0!<4hB5F@iVx@MKRBbqd40{ihK| z&5!G1R>e@-$qamsj~!yw6v^Os2=Ri3O{RRq8h`+il`_e)4gL}uK0dalk6{$D#$*z3 zG0u1do(H^#3(HP~vH%P79+ddl{HarA43g~d8 zwKfLMGpWpYMn1QWgvK$@fEw&Z{SRaf4FkJ-m0n>>UQeQ_gsL${-htU3dr0X$2PBVNy- zAl68UR@#cIfE1r27h#}NKKgjGjEoMH)uk273zU0Tmf$eZQIQr~&;hd2?cIIPGVP-6 ztY=2UX(d~x!-Tf*-sJ90u!4(9LJc`$3M{ z>>uRn%(DkdMk_9T<4PP?XMTCzvm|kU?XKlJGgkOWwWEmF@Y)11gYsUQMg@B&!FWn% ztp?3C%*pPi{gA)Ut8kb#oOeb9nJ5Ss!BXSJh`y@1k`ddWYu1J(V{cJTp^bphHc1NYsVW(C7%+_lZPII8=y?VH@OW_2(6slZnbwN`>i;5@cF88JM(T z8?q{u-H@?WepEmYhX)#YqrlkKA!NJEaJZ@SM}vTg5jy0W+)4k-$b+h^n4g=KTZSeW ziIhBnoE;q#6QWUkapoQO&i|@?Y^6kO2LU6mA;^-qgZ-+l-#B(`rLxpjWw7z=+V3`E zVdF#)Kt#i#i8NIi=30W_rd!63eFk|kc)X;2J)DwoM#6P!0f^-H9?4IJ=Gj77g_zj0 zUe|T6Jbd_25Q#ya}2Y=9G zgOTN3o}-kA!M)TW?C(dimsTyboLM-Cdekg1#37j=rgW*1!w30Wx#mDy=uXh) zKY=M(ALx=YrmE*flALV*{)2nz^r>8j?d=z$7%CeMFw1?#fEQ;$#Evm>pN@7dO-0mb zQ2Fck-u<9FdUU@W;*@*LnE>LfEo1{7oho&BIs%vx57XU13&EB_#&93XIl$p?9q>|E zV}iuSTagEI5;&J2YIKMh5WC4H7@)q{QJo}czV`1(YI6>rJx^x=Fez=d zfw?2T!|x6cpyx3i{Sl4w&G{UgK!hywPbz8gZ5;=r;Yi^$hTyL-unq1=kOUJNGgBriVoT|mLOc!r z#-&Ig0a)6h=_ZL3Ie{d>4A~z0)-qJ-l)ar@6PeLb)E<+8Qnuk-Gq@_#L@6(Xyo~cE zfZ?9VgtHgotXOCEEw-yc@XI zS4GoWt7GE?v@%M%5Q2|1Z3WxuZ;?6`O&SP)tCbJ>JdRpki2%{f)JfmbKr141?xotr z!AJ5wnJAmiIc6gT4a@bTzjAeXroAWlWp2&zFwc(UJRNG1V6pkL%rl|Ao`hytBpPIs zWY4xoMgiV@D9_*r0%g=RKW;JrE(B#kph}Vc@2XCRzbx9h27C zS&+0fW||djWBNyR1|uV7VtT3^?;rGu8U!^n2tu9ErkJ23u7~2bbC;oB_*a zm09oSLvF0fXstGu(Y7n)_;6pRaCI4xAt%ex>pzR&#kTd(7VTmn%-Y82b!W3JGBD8q z00T`)L_t)A90WqZeWMRRHk_8T2r;$#5k`$@(u_o-7^DXyz&ea}2g?2~uN_g81z4Wh z;R_4X<>K_h?h>3j*{Us#RdU-v!AXQ&`}~=0&NYTi86L+O0zJay>5L)b&!DfdatM(PV;I^N6ktrK`{NK>&D2rH zFJ8EA1RD~_4iC#f@2ZTBqiK<-8N)X{(Jec)7t*Fz2l`+@VVF1JC)$3U;z!8=2izSq zm;#0m0han?%56lBr`~s`Om;^d8ph9AA5a18_Au$Sfz*kPhc;v#oko}8V545s`31wc zChf*hd!+PgAaO?$-JO-y^6|5$674_&uP$&plLq7Vvx9PsjFjgv;>RX3KmLrNT}bDG zWEBIZ?&w4U_c~^|bsg>QZmW1npcmNk+GjdCNV$puN(T}$Q77$m(Ef;_P1nMJ4w9hm z#R~+HP9y6y_$w|n4Q}PUu z9nYv`Gdvv9$$6Qbis~c$ro97Zxj?`s80nP5lXC+h*3?9abFZ3f1lf2(*e&)WfgmW; z1;NMOo_mGt9>fis;q*%eQBmrtgRXj4u-2#4WO}i=V|$rdcy%72PKwx#Foko#1nc~~ z>50$=hpc;A1#y(uAb+&BnHDF>qLYE3i+uz?h)xtUR)$}lo{EyO*0dLcmf;{8>PIl2 z`6-Y{8330+SBF~9H;ygpg&+axUeFT`7FGX18wg5xjS7tXhSJN8-*BlaEb9ouA#yW3 zYG=yy6Hm!yh zJQQIsH}i72VqYLFMne&o^F|3M8>j5(8IrI*OQqk_mJK{$6LQrJ?|SXl!~ z)0}ahe=~kj4fX=Q7TeiTqo?Z5sn|MjoG{`zlUiL?Lu>wo+&fBp48{2%}G{{+tb@6iAC zfB*Gg{`+U+!>zx5byxiLH_HBd^fv-k|AYN` z16wU)4;l$H{15aGhLOlWFoA)#|KCUi82#tp?l{RWS?d4a+ulJITT=czKx>SsYmt(N zk&R4>{{yW>(2KXtQ7mf>r1D2b|L?os3)?*v|DMf@qs~A_kiStL$TqK&a!Gp7r2bFw zInP6{*ut;-T&`95SwzzF_4`fncnn?nDlKmU2auzwDazZnYt_tA~{gw1Y# z)+YIyD?&&-2jOf$(>RXOI!>AgV!^>-n%62Zc*Smnt$2ZTYkwom_i2-X;2;+jNFW5> zBLXAHNgB+LaCIFM+~AVC1tTGB!kOq9>d!z?$~=FdDNWgn5d6Rhm>)ft z+dCA?wC-kmU;92C7H}Fui-UU9g96RoPN3ko_`UZNdF^mC7_iWt;G(A3cun)Z+eLOR zJ7nU?3l)N^6n$UsZ4CN0W`L?PIa<5|6(bQvX%k)d_rGc!391hk^b{Pdc8^99w+$UL z^eEgcKSa=^L0(zYM2Rid)}j1Q80E1&395iIWf)fs6z(XXz{DYFP26XlKx}J$kIJ=wPj6M@+qjk6W%C@hOfE3>Q zQ*1uYqL`@ROkTl+&n>dXGdUx|DE)gHdXZ4+X~~tPpEGN z{%vdGDxuUBdV)v-lVTJ*q*#w+8@2bEkMEWr7NRINiku{H7}wv18!UcC4%%I?`n!I* zO7*w(hh!6CtWr0j+}n}W(|eAK*}eKnuL3S;@dJYP1Kq+VCr?IGSn zcNT|;N#YJS$aONPy%Y7lT==QCccY6dGePhDvwJymIN%A6c~Zk4{fzGSiDKrKo`yiZ? z4QCrj?4p=7zh}LQC{Z!!x4BVin%r@nqG7>*I>%<6uZBc;mib<#vq6BN=B=!JXi_QU zP`y>Y8_`&cp+k02Mz+!JCW0f%A5+=7FLhdY(r>{B4~5~WAIi^&W9t(**&S8bg9bcV z6$PJ#((K14Rh1k0y9DHd_+CXtVWhl{Ct0%T=p8uS{=n*Hob-q3r0aur<0z3SveB7v z3YkK}6cg4jm~N0N*jw$V(k(bMnIy9y_(fsnAr48(Bnig;Z4X4^kBjeKMIBT+=XBDX zWandbm3|X zO~qt;LvreC=lxvjk93m09GATF2-5-OcsN7({8;lyFSU?wdEm+gMV}98TsZytV$VSc zDlxkWj-~L`eR7|G_F~E~6fKXLN>Qxz&SNdBnK?qBXLaZN1UXGL zjOa#kviSkswT;@0Tgcb-nk4pKj+`e2wfJpJX@S38u$85>=;jN9H;b`lBoGB8#O{Rz zsO^vRS0|O|aK583{l3O8Mu?@T{DzrxOC*(BrLSP~UZLOx0HWw@d-SiX89RXRV> zFN3`A3e1LpOs&dx7~N*e{M#qCe$iT5?HANFhDF3vkWe5^0mBY}u1huS6u+B!?JAEE z(qyf}Vg*c@Fg~+UPB!ms?ii|Mqw=f1d>53`ew}!RDh{utqT==E;TfujCCB8psGAcrIKJgc7qO3r(kq_we~^ImAs#$X81Gp zE~>xki1nj#!Fn0pU+DG-!~U6uH3G@VqMJbSSy#Wg{P?})G(0CO@ABZ_fd2(c2M`By zY<6@>2K{5G#gnc!E@`WnNLqVO)%jt83>VHJuO#&iu2*VQ`t8D!ck`y#|-s~oVAA?m!m#=h=yvg_PwMP!j>M1GZe z7cxEh$3gtLvr%hD)~rP6r*ZPf$!|KZC@nn);Az(P^5JH)h~fy<-9iKy!?+(ZBHAy? zsq5i#9lZs!*CU*CJVs7^q{6Y2LXte`Jm&JtdZTPPx0D?&rkly z^`&stvK&7Ya%=cIo7(-Qj#BuYQ+a+rlWs6m*`pQc#$?{ySz7`u{;=Vz6$lIfI0bGY zBhPZIr2FaB&T8qVbC-R4@J2y83Hj|?SLBZBJ546i%K-{MBRuQZ|HXfusD)lu4pAAM#>+L2;{M@vj*_UnKc-;6b|Z zXWfr(Y~DP5SBB8taz-^jQkOdP+qt6j;eIw*LFs^1%Qw5qTM_S;`!QF^R93HXr8_ii zY-bP(OE+!Ogv8vE!hb9Z)BHxn_sZzXyZL?$F~*aM>5SiPZKR(oaovuS#*H8=HT z98uJ4LKiK5AW{P3aV0rNepG}NSJEK(0Ovp$MmdVP?^W`*O57VO&>d`Zs5th5lfBnj z#z1H2NY8C9CI3BjA;_?VL)gYdiw~3%$fB=PpIkAYq;fBJwewwS>t!ikcvO>hv-tC7 z6nKr3!s&W{a7wr41c1wTkSpAo*dKdpNc5wQ5pb9Uip9nc^%Q5Ck>Ok>#u#K{m`OnI z7;8t62ZKIIK5n@TmA>!FGQQM~X~p&+ON=r(f^R66jUMhd z&lT~@l=z~xrP)Ftxe4C+=aP}fB1=Ou>6)$T^ol^QESOJ?TEvqp^?_fVb@^r17kui| zfwHeVoR-_`1h%R;)ioohgVDXRo2+k|STWqg1}%1#%mEZjAF&$ISM>_<0qGg7H&Lv=@LRIB7^*s&~p{U8i*`*j*T{fXO()s9Pkg^9s2DG}F(eKMfN@p7J&wz@6rR!}*2qbPre z(#dsx)>r36?{Y)pn0`>$_RWKl=GS5+`_-b>)de+{Ee@Fh1IpZr^>g-Wx71y5zxV2t zAaZ7=`0Nai9cl$1NIr*v-y06C^=0n(A$QL4iNhVBhsbosTQrU>RL&`iqjk2fzJ$fz zisB=ONwo&?XMQl4;V$zBJg_BSS=a9dvlEHmula(G#!q?LU1NK>Q_hBz=i83fNMERJ3bB$J_52|PLa>oYhv+SGYdSxSx+bA zSXFvf$#s0R?lLOS)+0<5^Ymod3-|X1vO@p95PW+4#EFNF5-lQs5;)IE!d3N4D>^|_ z1g+L)(5R#}&wS$Dc_`yr(Kv~G0-UymSMpECk?TQ1!10e>Ra@GPb!jaF-usE4=T$7y z+qjstH*gri;rHY&Wvm5CzRpUi44Bnaj-vOm#-amNIL-a4QM(smT`H@gB-cbMqVBGI zUg9zq8%XWa_F|}pp?|YL56H5me+K-mS+D42{7Wg0L^9^+{yyhZKFt9eU7%Lk3rvth z`^j9bJ@B!ltrYV*KB8zrjVZxz_$PYg>Go)2tgOb)1`0fW=Zldwo@J?L2Ui%Idank~ z6zH#ULd~0wsEXcKHrvsFNOPo9Y{^xWbdg&F`qj@*d)*|UWCGC}9P{%nHip{}xIj#4 z3P~kx&pqqSOi`4t%vFo>^#*~9!Z-J0{#2gPS^=O0L!f{zQ~u|`>)l{mvi2Q?DPunA z68RFnB_lL?rl8l*-qkE6(OR7!L^UnxUbID|e#S3NK6v%vVX(&UuX^W>9gayn?;(L| zS{$@l*7h(HU?L~X=gfUsR5x1Sv>M%QoA5N}691h@to%%Cuq1#uVIcT(O&#)%rgvtd z7IkTG#&_|#bX(LzbA!Wncpio2TDcRt#-k-uFON6gzvKgc)JIn=+J^~Q0bLhbOM&Ss zfwIk7`v9B}#g1YRs#11+?Bge_&SD!py@<%M0?&s1Akxmf=iJwqj<3B@u42{*gMpB9 z#Rxk}K|cjD*id|!PHHw6s+}>R`&xwMSMi-}LuYf}vtM3}vfDt21pI>+P9!O%kfYFo z#1Qkkx8E4V_K!sv_^9#=9(^(7C|dUIq_)|E6+-d1qAg9+eju`#2e0``xv)twDOWL7 zF&9Mvr@QccFSA6kXeuh8CyAy5;K4$LVcP{Ij@M{#{Wb7f$IRkn}8f6q*RRufA*xW{Inl`FAcYF%y{U5EYLv1!T&E-jI5|UVA(Sz{@R)? z*n+nAqfP85qs7J!YZG&2JJXmZ8xV%fUaIST)Jpb(V}cs}x3hL;qsQg^{-!&>+LG02 zi^eO{dVqfPuYqFa7rR!OZ|!o*Y}}+^;??_>3b9IE9Uv%1-Ed9WOX?FC?eEiTHuZv6 z@>!3{k#Xo`gYh;`0h{@%;3@4S0q-Z>^}-O?4jSGT>X%^QF{&$V@bM1qyI5myGQ#sy z#DT?o`RL1#7;(3NYc^+IhpQd77G^5VZHqyPm*H_4|3?kOYY*Z8l3po&wvRmM(WbgW zp0D~NdwZmk_k(aw&o_%Gfe7Q=(VL58<+jGuyRRp58-f9Ks+;i5pIs?J3 z8M#)89?bHO0k>9P;da`Tsbh3W83f@tnU2!p_u{ z13n?M^l7@eyu)i_PiT)f_JIvsXQV!>oLls=GaQXJ*l-=q{XM&CTNPNTiH|L}RB2#^ z%-X%y+q1xEOb{|zs1%q6Xc_))p>OS-_;;hYab1-*efruu|z_o$=*h1o>>smGnqkSNPdIImGp9C6^NqM!;l7Yerk>b*IF|IguSpI4T zJWTPi_h`R5K>S7T0lo+sibxZ0>>T`{009Lzf%(rWVFKrUo9{L|vkjPMCLt6c6#WJ? z9)&@?1x_so+*CU)W*l&U@T}W|UmEEENRLOaWO5|+ms-COzAVV!j$bTQ6AVb91{HP8v`f~5BgDf2 zKcEeW1CF#uzjTR|Kv&`GmHbG%S00$rgd^U&*5{yu(nK{MeCo;IDCR-BvdIjkdECq01>uMqgOcC?h&tgJ;rLQim(pHt23Yeu| zsNQ@p7Lv?3W59|Pf?#mp+3>hq&2Ua~T-ovm88Z70%}bFg6yeA>J}1dT^V|+$L-Yt; z*pXGzK1BXu31{vu#p&O7GVE4~z970r`IvPgeq@P2vsn=$`{7lM@hTRWZ$U;e<0}a< zh^q?Cn!t_z0=>Mc`Oeu{J+MDPT5t{~UnOyIe>4nri3^Vw_xj9^5Khii>U|Ob;%IPz z29&p6ro$NmulfGG?2NrS*TfZkA&YG*IcuU+SAq1h%>kO4sp&{m3v`xf%!Dzil@2b_ zO&fJtQ~A*r23c%|$w&7p`N0?UA(-zZ0+-!2E`w-{*9_|zzGCUpI+XYHHtkQEzG@S~ z&T7WdbDXbH2GpL(C7kcN<@7ZeX74a&)%;9vWdukp{4m9!am;1JkBa1n3)9|-x> z!NrO7kbF93K&%$}40z@-S*Vq^7eQsPgRQVPU_6<`{A^K9tePZ<4>Vw+nX!!om}p%H zPaF7@6g|0kZ_-W7J%!+PPWgF*udn0lE>SIK!^z3vL0Yp}q0j#4^}D|7gw-1X!QWVs z`5KoSDo7N}z(I=bFAd_<%uT4z!FtDQP(M(q^A+2)2%*3JCH!nVa0l15znqELCtRC# zYxJt_Iok!egW>){%Vb}<@U9@h{xVS-@X^{`AGTwJ(1XAC89i4bMx|4UhrW1>INUm{qdLeW7W*wO88~fR&L;cuV4mfjbxQQkL^0u=BX4hx0i5}*uxD(l+{mi%vuN5uMj*(uv!*lq>9k|RpF7%HV9 zItD^u>`zeM%sbtMk)8=Xey1SRL=V6?L+symWP++>0UR>&0$$HpSAn5HGGW+q_67v< z3U!UHp}IsnBwC`JvnHC-47?sktSN++U6?k6x8VriHnSMADzT`U5c1b7`ZhU&Cat#> zn1HZ+opV9EU%(SSIy_$;?>ZJoD>;OX2BS(UaRqoIOeH5 zM|bv!l9&Oq2cW|uOno(*b^1Sa@cNAo-db9lB;RZ_bIoX=NKrNB*D;Q(Z=Gj6=6aQy z9Us73$|1Ny_0Df>0$?OQ&6%DTd7BUK=0LQ!dO&h;XrHt}1}h#%NE}v#^6)>4uW1M@ z6QJOX#5lU`s!*3Fq)v*NmP@xsd|uX+=vq9$_?Q&>jL|pgN7%$jEfS5MhT*-KocaE7 zCEXKjGYa^^LR&m$3Eud&6t!i~DAl;6JMk|bJ_|g4vwGHj7pZKTEdG3p3**am#D^}g z7_D@6pj*roDi9zd``>{8W5XC&N(h?uI3*)VI{; zTmf1voT?B!y_7rj0szL1!;=STQuRgFL2~_a!XwB}|2n=UATB-2e>QX=vWWgU!H3~k z!7M-WJH?L++EB2Sw+1%;RzdMGDIfjU0OL`)@ht8R*wl<(Kuj3m;VCK4l5*Y8Wk8E_ zmknocM)^m?jSm$))diSxDhn+jY(n8PDb|a|&&=B7>*ptYYx2r5zZC|GvOWQ}f_GQn znL4}^1aHjF%L9tbn#m!UAFX$dR0W1?Sb2A^()&K3_v|mkn;E`$x*(a+cKgzblO%1w z7VU#{>g@7RZj;X7FmK)$*4edzYXr!!yx5;a*V=xGzvXvxMeIlfKrx|t>bV~!@f!W1 ztW}<0-_C%aEUN6P7PUPv3R;8@fqLSi5@xr@4FcI%f&h(7H@8f{(vxyzbpb$NDpc^U-zqV51DDqmo28^j|@_0WB9sD%-r`kIhM=|EVCwlDfb ziXmh7Rm3If$mVm~$@xhdK&Jb^s0hTOLZ3{RKQJ%k{gA#uQcvp3QVTlnoKxngOW;lY z2lWQ4_#OECy={cHLAzI=r?s$I^xmb+j6Qp(Lt8_~)-TKmJ6w$tL`=yRGz_^(?@h)R zqP_|yN%()FFQOFa`ouvCfSKu9L5ny;rD>j%~+NU7%KP+4qPHoGRV#eR# zm{nJSa_56_v7X7(YW4UNf01@vsrBR59klPl>q)$jrJ))m~^>+iginsU;h#qYJbK1%f)SS z$ecqRHWGR7PXe4Yhmt-aDa}ZEYIvp@H2fRJHl@UBz8Xa)7JM^HBL;yabC_BdW&q}v zee-{D&CeY$a{?M@Db0SdRt7T+39(#94w_0!q#i5TFC!a+<#o|bx ztDbm}XzzZ#w_Mn|jQDG<2*9-xv>Yh*q^>+SSS8bBE!@Z}@Qb7KEsfyDt8}mhUIaC; z2m%lYtRGAfUc@hk!+70nB54p86^MM+LOe}2fb|6yBwVH2z2Uq%8Qv5nk~27(Kwf{4hy{dtB;fr@kHW{~V1FbQ3>?y9{nDvzRs)BEfzdu1 zJ&^Hu`v8H}#l+!Z^TmeMDJbkADR@djXmG#Oo8Y;yVBIq)Vfy%|W^3y%_A%_uyLR8< zHR$;J^5wDR1M9x&mkqXGC3Ong=m#d}T8N{gJ8mSts_~S1daD<=WpXg3ZGL2S(Ddo? zqAqS763?8m-^o~<=QG4nPJBS&3RmKBkG&Q{cwcn$;E$X|TGLHFu!fQPnxr|z$)_KO zdR#{VPl^W9E)nt$-vvS?`SCMKmqTJTMRc*TeiBWPr%Z;1k#_rgaX#OuPj!QW3B3qd;dGC)B0of< z^aP+I&D%G7CIrnAy-@n+JI>vi#jD9Rn~V8B9i;BPIF;gGk!Xk~k3C5Wq)o)YP1Rwu z@=;LMCZ;DFe&%aDxZwrDekNc>%Mkn?%J#0Ty)H1mlEoQ>L5wAYU=BgJN_jR#f)mq= z#F=#Mts|-g_eJU;+p0Lk5zXp7d#&;<+cl6H^EVGwUPs9>$%l%tYaT0QzP;xjSug^| z<_gnaPN&5}rwI~t32f~Xbk%F;WKi`WFX3iEPnvfOb5Lwf7l#X%rc3Bi`F)eO43JCG zS^`qb`!ASW(`R^&8Ri$s0jB07e6`K&pOizZutxW~#T2cWt;_nm&ypEPp986-4Y!hS z2~vDkUdu3G(^~a>A=HlcpTTk%7cH;P3#vL8w2=8PIW^}DGK?=yn0rYpdSN>u7%?(e z9!R%Ex)(8kX{Ij3#9*Jg<3qBe+}Z9J(AxG09e1DZObH|-;3;Y{X?Lp$>9V=3+U=K% zC71MnyBGQ$yy^6GYB~q&x=;2d)MJ}lI&$H${xyHg+u>2Mte;ymDtHYY%On-Mo_QS< zy6EOO1_5w%XXDZhqcLiUH^Q6lkls~Lok9VbQQr~f29aZPD&U}+whVl$6$2alb~0n* zTs`=z+9@WWq!XEt4PrAKPk9=`qEq3wsUf_#6%6adD}Lq1fVJ^vE=%^G3>bo~=0Pj*50w5CT*uBGvX2r5Mk zr>qT*fKvd;!HwJ)rUG1tV2PLAcQHdu=cPbUzJcP=wkl#+o`DdR0gg5^2FZZtvn$p& z^;#rpY|ietTYG=^j)-24bI?(w2;>J8?A#P0$HTC{Ns@Cnw9P^qjx^s$dvSCMge3uG0Egca_}gIyc~Oq<6he36Fc{g1 zS=IEQ)S0@DrEd}p1dkanx=7=x(hrVavRWOFgjl-ip+gcp9xkAn0Oa%eZ=iY^5T zP-9?f1P!K%py4)1zvE5{dLrF0Ge&3tr~TnXS8%IX*WLa!Z^0Nl$8YsPA;3YAW*umK zP=IvAYtr;n?nDseGO;EB7Ut8y1gx-itMjrw5TK5bT;OoLz=QFShxaDkvsslS6;aGXn7Q=9PZR0S8d4A zESsUeLX`$Yg6@Q5?AZh}>nWzoY=oCO-nnq51JDLxXQTl~eYvI=I4jb;$<-X*xCG0! zkB5cb@O-UTud3+hf~ro)Y|^6vcDiK-3#Wx2xW-hxrh|`N{5St6`@{*-g<~6}bwhag z!eJO!jHmUgehsfW*GEcIQ(T9DOulvF4^mzgU77Z*W0(zHxgWZ0GXEHEqVuzWO~zw& zbB8IUFS@VSpv3%}R^>=7A2}E@vuQC@r!5T#?$^vkL*F+jOA7fgz2gRxM1qKQ1Ql11 zCkG<|ofuXwGTCq;Ix%44bQtbeY3G67Tr*@H$cmG0x$!J=S4BZ#u5vXUXqx~Ec6@w{7);1*hx4IkP@0Zj#gx5^Mo@zBG{ma3#xZ(myF`+OQuiU@CV zoc6fX*{Q`H(New;k_qUag_XC->khnLA7D0VYVdBcJi7!d>GI^Khsn%f@YyvT=nfP! ziknP}NUNw*`z7AtJ++=sbYkcdVAC28oY4le5nJ(o2{YDD#rcB03{_c__n~r;@N`6@ zlLsj*xbWPpdU8U5zPqNp9!0`JVPNJhCh)K8!WcgKyk4Ky1P__57?LY$Y-c%c*ZW|Qb4O=S&#&=mFi%5hn;9;-D^*hS^Q&*(a_ERMImi$(Hte7T0sxYSQzQ)sKUF_-V)x%NzIh*YU z!<{zKjCelK$%>(mA;E#G9LE*Wo>A|JJC4~ojcaQ=Z%$f}+ZY1{1-z@=R~jqC$Z?Md zGO1S1S_FxwG%b6Dl^l2W+6-y~w_u9D@l)Z3f#2Q)KD7c@uvLLy^wn)r`ggJfYD8-g8Ibb%#iG>G!vt&jev6*PkLLF zzNMH9eV?M&Dqp_*WT$zeS8>?zOuq&%sCAt?SjLR31@>dFw#N>H>+Bcx?)W3`7~*5w z!@fhc6LI_EoeZi$yjkxGLS5o?-$Or+ti<a=Yrg;+3SHo{h~f10e*62Tt)dI`BfB|%6>Pvq&-CjUB{S2b zT^ECjw=-U6j%i4Zx@mC52gtx!nm)ybWrd@gxZYR4ZBVA9r~5kK^KaqrU|eEP%fEnK zb98=4me$9&PrnJIY=TWAz=u1WbUFf9-CEAbh{?hYRktFT=dSYk>|w}^l~Y3eN2ahZ z9&5W+g0w`|L1zSbUHtiQX!a#XY?tNz9%}vrqo(Ym4*hr+o9fJU%C=n^^I!q7F-00b z%Y8+5h1(MKoRH{-oBC?nVjiL=Y;EVF{7x)!>=*> z$ofvYR@XqPdtV`38{XPQltf4z^foIdck;y5MO6DAvQjlGr;J;z&W*Y@-7x z*1g-Kmyw ze0EQ!=mpveK?=lh3}}7*((fB&gR<@BY$lxlW8$mVrsz3usL9ZZV<*}pSVjUN5dql4 z1(-Eb&>#Ss!o2|U1B8;-e0^girS(>L;>Nhp8LLNVf9C!wKGRIgfOeb9`@^l<={B+$ z+bQjXP75}mHW*H{8}UOG$oX~ZvLk_d&-D{o;5tOQGx)f$-x-G>pjG}vnfoa!Ehx=? z*GlCA8}sdAO{k%0!@E5@JVB<*49;gf@Iw4XG6iIg8YFo%P>^D{n)SHzAH`G+aPBgo zT50D6A;O~{_3D{Dc~cw&Jey>*yG`uoYT&A;P%mJT^!Oq9rai|t9fvg2Lwj&-f35c~ zotoucd*fmeZuZTmIsxu>^pHO~%-*Mk-&o#r?KihCNQlgOeU)W)2hK_ln9F)l`ULQq z!Kf+#A77zd?3{$ThF$0z1L1;T&mOhz`oSvz51G$v>=sCvIZ(i<*Mwy$;~p^DPD2Zh zzE%)ickY%^*N1=KF9zvU)4sh$Zc51~mtWh9IGH4fp5ApqsA3y5(ZLGJaVW3l#6ai` z_Hzr#LZ&MtHYg2>dXyhZtr7BT(x>b|LBcqJ=y~5%z*tp25o$_foEHb|k0bdbh}pDr ztRHXaJsAA$U=pMRhy0O$!z2MpEF4QB*j8i)%ZT}PA87)g{;!HWiVMH6YlC6juQ^ueACTA1L>%Gc?ICd8Npc&6r3Gl6UJTP{ zlqH30Y~ed+G&Ng(=V(4pLX8Hh{M0I895e^qG8cPiD$B_kl)vVysz7V4#2b`>T9A(q zLeCMzQZo^&EksHSkfZYyb%WBLo@$@OEKwr9Wy_sit%bVc>U@#0Fi9IGDys$P zNWcm4uz=S?b6l+jKSW5>%L}9rK|_!1)=ByEiGYVH zjw-boO$4FUiS()%N>Sqle9`n4C=Lfv;&N|aV7%Vh5=(GLE=Tl*6~X7Se_yW4X`m(q zD6uSl`0Epb8a!pfc2b*gu+;%iAa@4@1P47-tGpCUiEFN`9bCuNvGD=~?qXmkCPoJj zOo}E$9AqG@8C3~3p!Yh_oPH3>q=!bzNGi=$LV2ILq+8j{AdppY)iAg<6ZXu`K)_zb z&YGk@D8SaNlqx2m3I+3MJCL%LwMABqlmpT3AJvOSfbk$~!cw#;S>4xtp zY*Ax6WrTeGCYnUXe`)^orgpuiL>@dR-Ln{oUr?dE%1F(;+vf2Acl^clNE%7S#4@kl zq#g!sbSh}ySPEx>R)QR-sm=5V>aFDNiTmgvktV`2E1d{EZoVwo)tHi528iPG8enMB zAc!Cl%yI`9)FQWB@xd?*JT1v=eWrP@%+r$i^LTL5^A^5aOXKrw@2(|g#X#NTNq8Jo z9)m&StTEyH14*Y`nTx{obbh3Z#6ORw7ie+mw+^^BQ%ZO6EX_me!9rJ23008TokOVy z<+k=tkg6H9-EW8@n*PEKurb0c`&gsU)QQHU17EQ{R5HZPi{$^f(J?fOqP&9y02);^Vkb0*1xSv+tQoJAW&Wl z@sgCfk*25*D6Ij*?9-|js#i_VUjo(%OPR|OO7-n&doz3RkG+~QbNn7-T(|(jV#u^Y zvZ4dLirEFU1QLcjvepslgKN6QzM5>mLLe{Zpsy;9fRgnZ?D|rS_>`gZd@-5F4m$5ANcQ!`i=wM3c+=8ZR>-mOyWF46 zx#P(pd8t2nz@o@Z7C$fswlXY|k(Sl&xX-4(pn=<+!J-JOX~G3GluG=mPf9(LOvhDK6LX0yX9ZRP; zp>wMt%Y|4VOQ~I-N`S9FUO3T@H6X|QPlDw^_*z0rdnrn(w1oQZvyuLRq8|Eker^W} z0hdWTk;ML!<`BOq|B8Ky<_+AjygsUp`&Q`s*Rw32t`*(G8OjA??E|5wEL=$l`?CG% zZKVu?JCsa*5GW&9`GV#5 zS-YvweNZ4?@y=ei!%0BZ&rVomPN9%cYvKyZdkb!QK#_fmKf+NX^)DI4OtHbl2sWJ> zE}OQx{=q$CLSF;H4spPNIq6J4q}0PIBrW6vre zaYS!Nej_o1)=C6*9d$l^Uas6xFN36+)9IWf(f`~-VXu8DmhU(`(kFiXbo7wa_yao5 zD6hvKCKQ5!s$5@3QyIZvf^vTXh%nEG%!9TLe zW7{_dE(};Y?>0k5EL_HEBgx>-j>aYi?j>8yw@n=R13(QUWYwV4tSougNUn>M+>${% z2u_S{MFz{fg36y+-yid>q!xPl`E-kvO+H|u29ZR1K3tc~1-qk*JC>lkeTedac?9M@ zTTfz^op$o?7y8^cu%Egbp@P%CbgTC%F!tk+MC69e*Cn*oW->nm2$(V2FwG|*0KHY} z_zP$R0o%YvqK7yE0x~XOw8a^GufS7>x5io<1cRtwI2=|b%r!G&L?^O4ca1&{_11Xp zDrpg^c!F;)*yb3}B!Hc)+%O4T-m=_K_9gcGRck!Z(yJyco_DdAWR}2YkDpkPYB9*8 zT39kb@eNWe@w@8%FXTN^h_AetGx(&U(&tcKg`2LOTHF3307D-f_El4Wi$ZT17kM5^ z)9Z^gU0a%ndac7Z1lt@5Ub7{T1a_A!5OWcDCW?rGHOQ!Men!#8km(z`OP6JsL;%LZ zycSv7m2?&rUYzS-mu-VLZ#0{LuUK%qPZ7)K7i?33w0D@lxD>DcaaVBX2LJX>8B$4q zQ3q_MV5u(N5ZjqoKxZlB8vT}KdxL@^8Oe}WDF;xlp`WJU)sKRJz13h>mH@tlLQ2=W za%KqD0lEuf^%1Z0L0a472Xnx{hAfoAd#4o9q5Bws6BFCHokRzeGct_h$u8JJ2l~^r zQN-zS{&{h%m*aE(WeKP{#(;3~A-|1m$dE9qPt12;9Yzge{H(TMfUE;G&9TN1w0>e> ze`o^C9n*wrM&(X2f%^XVGFFmCG>^e9=41?v-*@-@$^N_+o^=sEegmX?2uc$n>FUa0-!yzaHzRf(-z#`hzH| z#VNmly&JHuv@4?t_(l-I@LzAMiM<3wS6+`%O{GTq8# zf_MEbeF38L!D|u!G0V>TlbN&ePrSZ9RtM_sV?SeG@B=w!?N`++l`=eJ>fJ@W zczZ!!6Wmy`apcZ8>UpgmLtI8Q zxI{cYDBueP09xurnO(MfeT|gS&`%FXHL<;gz6>tri=3W$IkGszTl8ns8cVA{wO6Qm zu{Ue(68^GYCBV0)=q4~!%v{i{QGqC0NJ#C1@w=Y-#Tg7Zc3hnVWa(;mACYgqpvXm7 zjz2jGh90FaC?HmZR%d^j)2Ik2W?PCB&ZBo%g90`_Us4C2Zu>_Rgr9L}DrZu3@8qEB zyw}w^>j)aBG(WWu12zHI6ZYl2NJG$xRLLKx%SrGBfw0aGaROK}GOwGQAZJBW;3$SB3GCn?phB-^GCfPy|QvfN<5zy+- zF}z|C-l1cl9<1SJ5cM$1h}Lh{<5;(7@Z~Gua^}+-$Y>3~ZQj@s-mML`R)5-?eC!i5c-m!AgARSu$#Ey8d^_NvC=jC>t&!4dGKr6+a&61VR)R{7>xb~ zoa~euIQyO@LqEa1MX>1sTODKQ98j{jEPzXt#%vI{}7wlD0OzYix9M{Kd0^Qu(n*%v=9s)~2ktXkGZ z)r(*LT5X7LsV$#f$!6n==@?Ui!j;!3V*IO9?Mtb-GKtvC@?>v8OM$W9z%upbJe2Q^ z5~=uuDl1(cAs9+0(yIUXR@&hvE;os_(~VAIUV;AxUY_Sv&fX z-1uM&RwGmyiFx7A!?wb<6cSCY;`>Ah_3piwwj|#IBI_@NWFSk=far8r_?(@Lu_eds zvBK1h!>I{Sy`E_22P^=|7h~Aw?@xws$ARY8j{~}J9^7B*s)?8jj?r#b@s8q87RIz$ zX?s!F{b)PuneV9l&J!q8oGk5(|G>vi*yDT;9@#qz>G*z^3LAlRXpTJb#Rt@L2oOPl zM`kpl0rHa2z@ruTO{hp%ap?KJaX$5}FdKLqvjI=h(E)5fOKEJb zNZvfhOV6AI9Ndeq>)v>WdO_j7T5p5pb|U^sFl4trkj1%e@S{)0ZJj)f;5g&oKsZMg z-_RV(IjhKpNAGlAnW{8xUa-hnDJ^ZruElU>M`L;6eJ?>943&;4aDuQ&zP+k~c7@Cr zKBrSy3%eo6+CGjd$hGWP(4FC_!9REyP}Mjre#uG~9&mWa|6&DU0T+V} z_kJZ^sp>)>V2l%a%lvmzPK8U)#}4-km&17ZPO=(;UMr2_i^>aE&(>pJX%DYS5uH5J z+-BNpBT&sLk~GhJz-JTy^dP541Vx=ASUF#?UZ<&kT;1EBNy`vU(EHcyqrKZsO6=3F zcE9at`xRi#-G-38^ZiiO&L=1Yckz3Rt?oAYDkhjN0d9uoJ^^G!`-rwr+}}z8&@Sj6 zS1W>>aw$X*=n4BV zKXXp*(muTJ!?&iK`0M4v+6H(#vgtU|&Z`S>%KlMJ0I&e63Oe|Rp8rFS=AwPd!P675BDm`&sQB{g0h<_2)~8b?lwi>C z@I%{F!1$&mH9S|2M#%jcRe?1<<4>Ipe34{aH3Kvx&x;sozdL+_G*^;wz0c`*Zbf+Q z2e#x<5$R;{3^nnG<3K%@j`rn6Nk;7(z!cKciUSNU_B*T?bo*?qCznuK@lpaPK)6>h z0IdBx0l?B;tvkg1I$X{mMZR+Y93z@^gg+I0}->O_IVXQBxtx_7a{~0Jn2&p?l z@l_AVdQ7;p1CGkX_tg)X93#0SYwNr@xlx3WoE#Pg`;S0A1y`%&DCJWWf{2+9+I_P! zP*f+AS`GQ{_|7J|4xWbEikChpx%;eAa`O&OU*} z1p;A(V+>93NGd0#FC_;fI|<#c3;=I4t*Dw;ackJz3d*+v~s@3Ui%X4cc~DKI$!@ zgYeA`q~tr$NN(#UEk*#9ItSit?;&^c6Qv)d$qO3v@}wZ21CxzQW~=V%8?JVP z-=nX|)R$hl>k4&}uicBi*D_FOa%3Up^%SY0`A#ZuzEA>o(+FGQjbV=x%*=>08g*<>P_I9X^zq<5)~6i`ImC zbBWK@5CiOX{Q+h$x(*P|f(=6&X^!J0@%T=sGyiEtAiWAG2!t0A_~Z=NE<9#Q%>*cwAMl;+57mqLl&CPZ0cAP*T&+#pMf zft2TXs*h1FgVfEdUg9-k`t*U4@6xWxj~i)Si%k}Y$=24rKD>9qZa{e>}=vkN0(lgu)7)Snc>Ix6E$Jfs==BJvr z)g228R8I08bVzbKY?pfv>%zZ)Es%4-lIM;o)4;XzUAgMP#Bi~ExjFivF|1FG-`no~ zaPoqY=3DVBvd0nuTxucwa-&1hmvy0tvdTMpEyyW4?J?_j|6?9#Dg*>;Ut}Z1W64!#l6vqFeC2imZ4B- zP#}j+%beBMOSx#vnA97&u)I2S;=ML#y6L$FmyhU#2(nl4wDZckXyOcc!ZRvgN{h&) zMy(*{usP;?2bHNZMR|e5w&XL+!(RgDGBf>(Bv8AHCFDihK(j`L;?)5B0Y_Fw>c5t8 z=f#7}f3|1$L%NSpbU@X?-C?jI;Tura56bQ$h_%>Qv?su~w0Hb~w?J}62RsJ=JR7)- zk_rkNzxw$2YL|?wv3Y~^BGXu`cc)?6TGs9$46WV(Kesj@MZ8G0&Q&z+#gH;2YxtvH zB?`L6g=;(z0WyasGw!v68M-KFnRVU!eU94c+wtaw?H>iyxT1j%U+e=Ah1z=z@^}RR zgiptI?0zOFOVYrzFLf_|-#4W-5sR@P)O{Pk4~CB)gE%`$X@Xb(shTK!<7bvt6 z#LW+fmFd-G;Ne$IH`YteBEp__=%$^s*S3StJ}XUd&=M*!E&@sg5YgKHd*A7!MZiJw zHGhu;+P{_b>84*V@!Qo~-%7yH7pjtBE$fi+b6%qnXBcPaZWfdEs1L#e@bsUg@zK~8Y)q*iQEcvFSQ9B%9fGd3@50zU3WyUY z2aV(6)!khz&K5DuAanyT9SA&ksA6Qed&v(9gx;=|F}iu@)wYg?9zREb;Ch$(R*vl& z+SPI3q~E9pQ_ zNhtjXvV#Me>ol>AvknB|ha70H9PsrE>=%DxY#o;}A>x!eR-XdNzFbj-X{x0Dyj^_h zW7$C=>!J@_jx`C$=r|4FfJE@*NXF`^xAHis(l&bs?@aD&g$&&*<%C(Jljqv zFyq(&fJ1FLQ7R3{xP5buAbpZRuG}@wwk#!*K=Vj>GX)Lez6;_m6DS19CY;t|0NuH( zpoLf6lY%-W!I8 z5FQb9HmS1z0AQw^LF3Y<2m6Iev;1~5+659rVkP_nLw`2ReJ6frD4vDS;g2ddJyo2H ziTd~ba692k!ISx175DkH%mRy70{PAW-Nql?r3U7tTZRVOBiPkvYxer@&aA%Q=ri7b zWWO+E*NI5^6s$G1 zjRUhSNcSavBX+TDM{6cOyCOZBjxxejlK_QqvXpvk>igu3}Jv!+Xf3XDb3%>_->R+tdTHN3)P17)FJ_a@D_Fo8sEK=5zvQ#9er|j6ybeJLrs~pDsAl=zG6^w#Z~R?`%$dHC zQ&(A`>o=pOzyWsgC;+lPU)kY#4W^6$iqyE=DFl#DnZ)*|WLurr_r_m?Vr(*sZCy;& zQY2)o5Eq-_WGGTfb7mIpkLIzkx4hWdpGujKhv6+VpfFj=QaT<*QEf)@gc_Q#HZ z*9uyyt66N|(}V6jm&8jh+V0H@=>0loEuf%z@5C|-+8Ow*8s#1av^>|TAm7K*@6UYoK74k?mKl2XBd3@4{O02&qh$?X~6uO z*}MKu>9A+D+`UZq_Ziqa+ZddDj-VI#mpH>jHt=7BJwS?L!qk8zW9jAoE?|}fPgh1q z3id+eIt;#ouOhj`)5Hx3B7^t@MFMyvQFzP*kb_5&AoaHO#>m(@B;X_h>=qsQbVPv= zcsNi(sTj@~FOJjb$d|qvzz&~nhNt*CX;gztjC>xswEFmqD7yWlB5qgPpL|$1Ti5YU z_5BP3SSg6VS~3U46F)&Z^;Bc6&JHLlg1d<(Vc{%TCJivVgj$Isuz<W;(rAX#1khtQ_*BTVg!z6IsoGUV+qs0%b>La*&aH( zwp6BoqlR0nljsiAV@6Q~t-I&CS5N|oyXU4;cA7h{GlC&kq&Y4z(P` zIX4jWK?s?2#XN8s9jZB%@Kx($BXs_`U^Qcl*_G&fm~}MSIu_6*Q~fZ`g{_e84hLTl z0XFHO;ja&0TcE@PkGbqjp_zx?fG)|!=O1V!kH(B{PF8)b`@7z-hy0~3z!lY0G7drh z*$M4vsaoX9DKx$JXZh?o(n$BFo#7os(ff`!43oTss}|jqnJ3TK{;&hYa9!2dk)StM*tgu zDpLYdlp}1lT++D^g5VIEB9IB8APJw6fAb>!TvbLQ4;suN3OS=6<%E!e$Q_{5T-5mktAX-WQ32@h`khyqKn?2R z@x}K`I`m}-!laOR^lwrJDG!-H$TgzHgJ#a$h31uf9~u5+3pzk~X>Q#cqnzrIl_2#Co)Tq zSll2%y_>7VgD?RVLt$BG&rxXTM_*v3IlR|Nxx(Wm8#|UF&Z)|iwB)^atO559Lw(ZQ%>4qHr+t7C3NYI`zM+*g6IU6HagQSod2>klDY||~`&!23| zWN6B8f+Y*5l=piHBZLFFL>m%c(6h>I0yl>ZINL7{7A|*W0gyxB)N`|;gMSUFfbWP& z6boqNX-cu-#0Z!>yne|F#lS&Lpf0+PK7XdeY+tLL{FzWk+@-uG?g zifAChW~iGg`UNG`<&G&yqzh~g*(dxCKU8+SfD~ebYKr%PY*y0mU<1(TO@0CGML)i3 zpW0Dal_vbV0=pN7^uh)o?7YWay`&>v73mII3@r-4YvDY2DKN)ubr zG>p*i-W*V)#cLM`;lMeA7u*R9n_~HGEhD*7QbWP*L;?py+)t5|@3G7t526D+{x<)~ zX}*gGXz>YNJNS*x zwZXf;zuep_mD>9xa>aFq321e(FsK1>N&-;LPvN8Ju7ae{=b@3GL`l%Z=GXA!t^n=; zdfNo@pL)8y5eY+lw8kuj<*EWbrV@I$aO6e9;%(8TJG%ed*o#*lSN$f z5wc)4HEB5VqSQ7I#k;4(qr>~z7dWqauxL2Ko8-CLa|gm4rS;~eM}>;wsQnVhN+?*n#ETEQ&f(7GR>*RG_B$I#+BPUvJRz3fp=g9YM&1d@_P#Fj4!`iD zBMr_5n%{)fI6_lMkPh=8|QU`(t5TYyWQAG&*{)E6WvP=0iF z*f~Dyk&_oAQP@MnGSoAyD76BtCvuE*$+Ku|2OM5rek1S?%-%sAT>EWY`-lL2FES1u zG%5S_wNKHK5oc->g`lLrk2M=q;~WzGVS=^BD>B)bNi5L!Ge!qcCM&>6`a7`me(2Tl z`j%xz?G>*eGj&uz%Ep-7jg0<$cnTEtkzhpcy$0w>8>Vw)gwHxv>4A|x?y~_0vO$;s zj+j7K?*tjHfWJRw0ii_Eg;^ESITB=4R^Kndc?ZfmMWf$GQ`7PD?vUa5LNx``qPvp# zE#q;%GRi8m?dS1&|BQga15c=jvfmfd44$*o+Qb9j?uY|)fJ!3LHeWAd<123U2u+kzb~4a5oxo^PJjq2bn=)-&wDmB|L{lO z|3L6+d|MdPev{u7FRaG?;Kt&39_YZ^;0&3mnM)_b;H8+K@Agd-Sb^GmJHA-}_pe!zI@|VDBH%XcELN7DX z`7!wS?aQn0lx!PrdXLGaE|MYTz7@zAV0cUE?SjnKeIdx#Rf1fd#4`m?O zEj9ms0zQ&y$7BtKQVR}{yQPUJ5I((OU(pc-1-Ad$qum`@PRGj(Tq`W-Z6a|FTa|KG z5#xA1)Ss~Ij|{h476_m;RrI0#3#HQU79&aX$Kyu>e!8r9L zLH2iu<>^(zp@!*qslW4!o_pH#KID8nR^kle4BQxCA5HyhC!6k5coTdf_<85o3q);k zmV)KQ{g5<*^wTIsxr1F({s6#Fi#PouV2Ji>>EBpo~Ov&A^kP;_o&W*a4|HE81eKJ9>)&tMJxC}9#=g5O2 zesc;MvE&FX2vV#0QxTaHVTQ%0RzPPUd9PNs&{TnmDi(JQS>$Yb4uo7=iZMN!xZGXA;iaNd<}N^&j!00TU_;v zJm~TdyUjJ2fi)o@1wiG*n42D6%E8S`gOiXh08$m|bfPjCuomOk_Sm#A(8=hGkSWcE zW%sxKK~bU?sLT2u3g3S7C~(Y{C&RkOjJaP&nb;Y=Ob*hFC>NWVSKMn{d2BE9tE>Iz zy}T_aHTE&~UQbi_m@d#4e>-SahJuwm7_sp(9@!rd-6e+ZXW?-N;V)hUzFR(G-uq3a zvl+PQzw`C^?)9u6coV<>N{fK;&mJ%G;>PHbZykj_*-C&R)^xd9>!bkYj0V`NpI48A za}g6{t*j5p2pmbirMspoLVzY*>R%aWy7JGS2`Om<$^ATE_g%>@>)|So@4Yty-8#Zv z?7f>p_ZqOb?+G)hbBw|E2N?#z0{54zLWg?=d;{jwRAUu@uH;U_0)iAP{1qV4c*F6f zKZzo4jIIz{JlLi=M|vgTFE+;evnauN&RQBe)(!{vXTAXzN4QArtNhYtb0DqJ|DdVU zHqr%zmmIAXiHhn!WLfVSemhm}8ex9~LPS zaQDhj!~pCs9Pt1PnbUk6F)5^AGdmXh;;R45S1bx3@tmRMf+i$nVZ8 z{LGY(kOe6udT|m^nSXNllz?^`73W6crF~$|gBL$@GHd!0 z>Bw(bXvh7hX&g)6C_-s@8vfU8Ot}7liyRe^UQI}Yq(77Z?+iS@f(3|GgE_*5Qbm(P zAC;(D>KL65C_bGG$Hws1o*3H_Vhd=^^#}b{LAm5!Z%K$fA%II4?LI+r;ZDHvyYSjs zAOzpr;P+d{hp2txZHFyt>wh1rnsxd7K=_x`805@*4(p&BeMft_wwQ_Kpe*O^jB3Ya zadcTn1+V0G>f&Ng+6F88Z+F4FIXngrEC6-a1ZdTV7^X=qnX=O|HYLoXOjA!E7_NSF z<7OIi8OWFcd=qGj3$?GCAwxBkCM{9}ZTEv@CAcJRNw&QEpxbs5jin4Zn9$K3f~?2h z{X%Ux02ouhIJ*6rM&};gp~KdB@0GGsfel8;#M7mmY;JpMl;44(H26rK5C#eI);9Pp zk@`3LZ%xB=V100>xEFS_*AN$is?F|gJM-slsSvlLJR za$HgDs*tw$mkp%M4=!-cRl*jyo3@VhXEk%^BbeBjwViAfnY<>W17(1qK(1mxgNE`m z0mTPiA~9{UpsY1NH|b? zxF`p7>9*bjAqP0CK`VP3SQ^Pu{rw&A0FYbC;_jbcB`z`#_ae>Vky)W^RNL+6F(t+?tR zsULQ3djK>=%?#>{v>0>7;n+F%^#YoMjpya~cXMYT=8WFaSQ z-&$i}GDYtRJnu(mu%(a7&bt_r)*ed6~a%=+tuM7~H1k>)~ zEEXX@k*aoVW_p?&(Ytf9a81GPLy;XDwtt&_76+zJhaiJmr<#bYax1Ez>jQBVN>_LR0f>fScg6|o8(=B=;Qx5WwAgk}l87$QlQ{2yT!E`6sCt1|?Y(6{lVtf_xc&^Y_}SRP<5wOV zcC?d;iG)S9FrvPbc}QS5K78j2WXt7%kF-l@uREa^8VtxCZ=iGq&w-)0Z|7Ic$tYp) zJGPNTL{fZGLVa1{Rl@1zK)$H*D46@ALE}!y#|L55Cy5Ss1&fN$tMz}f;OnhtF=gWO zz*nOQpn~3BX&fNc-yKHNzbkzMW^c(F6vcHQ1Kx`RJbc%{W9Fy|lUz&5EC=Eaj#8FC zKHnjLtj%D*el7ufru4Ms`SV=5kZbbZz3#<;6g@tcI7kt@iyq4QVqkf-)4` z){P>v2~b@*EV66+S3i`tE@~C5Aq*ti${!^ydBM5b1Wj_HjNMM?!0F*iV%LC}%Kc$1 z*FGOYQp&KcAUI2?+8uaXyQ;FktJRGS&l~Xd%l7^QVx6uM6l|GfEe-fs!3N(7^T`pxp3Sm2CLaf6LAf#8FgmKtfIsvDoC<-jm_Cs({2m@)$hL?KhM= zFl3Ew|F2a^h-dGrv5 z!D#X=ycU{)ARxUR;mUsrZF6Fq)3!GeUP(Ac)qJX%nKdAidsTRZDlRu!k`7nO!7X1c z--!_5@GkPwhW1w8;r7O5CIRHf!wW2~fMVbygU)XA*d!-<8`N;aMj8a=y%X*aHJl^) z12H!P%-g#)0%OAkJsoHW7m4viceI|iNCKhw`G*ou^x4*C9YO@=f)X0S#j8%`ctY2D zkv=+=d_$2;+Ea68oHjtl#RkdFlH+h%>hBb=>sdf1-XR>m#$7sQfE^Q;n);wMXn-8& zrIT|XYpGJsjz~Q_Q~6EM;|H1TAB0^3EoPhV!Bf&xHd4%dWS7jH{}# zY?{D;nvHk;HteWk=_>aSz-uhuGC$@%f&nNL7O7}_a{0Od861)U3aWQP19cc=E#Y|q zgXYfD(Bc9W!2T3dsaGu0G*GtITOKpLl(I-uERis7+9jG!4FT0%{JW`~lV_%EG;V@eI5}MzfE)`1PCfN(xtq&i{or`6ZTP2QL zRVSxirzDI=wgSP630B?$rE}=3-+Q78UIU)=HVU}}L60mcbH~4gnCk@VlNi{( zRz&XV-y`0rk8fg~DtmquAhg0OAD6D4GZjjl`b^&qn8`e>iIzg3x4@`gaynF`R{tr( z;U%%3nBfcPUS6fuJ41mVT*sf)qZDjcq$gX1!3uzSz~At&!6*iRDBjw2a5V~Lg=at* zB?_xTy<_t!L-^%hzvh7yfho{;P&J+R0C1b&mnmq46$^}{0c(by(1+g(;Qra+~ z8lAk>4OZs?J$V8A?EA<-viSqA4)3~LqSAfZZ<3>=1Ti^CEeKoUYp($07al`jD&WSf z6WuCvSy!;fa)q6@&SQO$NeSI>Uo?45`8Ds}+T^Tbux}EO9AHzy$w)0wx2rljkYK}w z>R@TeQkX-7svPe%(_hxV!!&%#a56dVK|}$-K9)&-15HpE;$6!s(6(;4I#Eq1-LJ@4&-vT?8<{A#~N7MttGW zMv?(5rTQ)OLZr`|R`t`x(u5|^R_;MrE?g{M z2T^`?_h9hHrlvxdgK8>uW;*W@6{~s9=q&zD4~NkQ_EB#}lLht0vjBC**Q|jhN5^2e zR(-)`#0GQgZgACKNcH-KF3PKT3kXfjk2^&Y)XzHJ8onI(Z)TEi766?9^)$x7ODmM1 z9|xK)vsq(a4YCVCY6oJ_JTy>4y1#w7Cw^?}TULQ#B?5B2&FFQ_}#8={Wa^zNYqM8?Hm#6VPP+&e}GM-Gsz15c0% z!~#DkYKp>!K{*XaOxx4Dfi-_}IKCZF*<0hF^9jdYlQ`Ve%>?kpX>xMstOnrxX*k)^ zV~soDeZh;gDZoL|H7_1hv^RIRVGSOX3FWqg-8&US6OMIA>8&bJe$4N{xMa>#8Q4Zr z?gErEv3d|>?lMJC-KXTU;IF>{?vOVA27RV*rgk_O0@LOn2zcu}w=JfssLc3encq=B zS3Sl1*xW?nJIZ%K0f`T1JCbPAK)$$@S)@xWR?)GVcYPq~`vo<|UK!1UhUNMsJ|*(D z0Imdmzu(wP_Mj0k^o4f`&~O$*=2-P5{6%1jA~R3&o7UPZ6mxwNK8*2@Pq{qCtg_hJ z59)QCR8@(qt0!Db=Msse!VNPQ&o8hj|6v}FcqZ7Jw`%rh6_fp`dg+82saX$Hs@Go0 zoxkA*P{GWfzuI*EgH;M~7^YW!liKobivae5GK{-MsDsup+?{YDnWqQ5M3n}Eo9Udv zh`n{4>kVZEGA|}Tww|W+2BMZh9AL%;L55*y^}e6hIDaNwZ9Wx9t6;z_llSK9yud>E zQw&!gNuW;-&&c|so3X0P5By}3QUDY={mbvtEhPF|bz{Qkg zD#Lffo0RNp=9=IJn_Dd&OO@ezUnFo!1OP-ykN58uEkw1z!5wfU1xZR3o$z%9&Stt( z8W+Hzwn@ZGwJOnbqBITw_LcEP}dt{*%S@la0zLC#?*!ha67^!eFpKCR(g$K?aYy*Pl;cbf?5|{cf={;z ztP(CkB;W>2qK)v(-=+n*Egww;3ZE#^&2tizS2LAGgvb(TG()N@L0>RzvSLXC$R_$) zr6}E=TM{rGE!(@uk~G! zO*Y+aj|dQnV2+;ocS@ZGjOkWY6>4YO2POUjfz@e6Ux8u|@Qy~UwinLJ&8#*fu%2q8 zcZ}?Xp_V1R&H5ApTmxH?INtRlt6%)k7eErM~V+yoFT7jBghN5FONQlWg6EvL}Jk3INmr<;Q&wj zVYO$qA0VCIiGN&C5K$%H9l$sUHg<``;$jPc?LhDQsOY!vf<{dO3gHX!Wq0OBb#fd>IV8mJq8efG@ByXhk8~yT#kGGb$Ui0rL2DL# z*hHwbl_!C_BMTF8KE8J`40L=WWG#D?3#u5sutD`u(qG@A8<4Xl6#X$ z;3`5xM1S#F(o(|+t8|gg)NoIPB>hPHb|BG<&eZo|o?91`VYy5b-V2^^cXr;|pV+RI zQC)wyf2CpIXW&nrzCP-gmc_|OBOgnE{y=hPq<|Td$?QZLSm>@lYxn{jq+=vS4OH6i z%c_7zC3}>rf8Cjp)HvVJaZp@tNf4tgLJAam*q{9w%Il7SU)h=d)Nw9<*`uO=kSokh z@x(jNFctLWgZYNCVSLV`GKxJdunGZQ85*OnQh?b-QsBDx;Tq00SpW3*+*3(uO)%?a z@>{%<^M(IOP?fYV4_v_9riD@~4rz)J5rUk4)Z!XuiO}Ye5Cu1*8d1_aV1MMKEjHEt z8`?%NQF(xvBv`c05WYD4@Kxqwp>h9Fz_;+=F?Qgn6Fh&DPTN2;f*EYgO4X&> zYh+Ym1%RuBD&UoA!Bk<*N^kJCsyp~N4iDmAka{?|9cUX*9g;6T+2D`#Q6iw%o~LBR z*PBSc$}CqlBO5;U+3+mrz;eCwnWH2NXz$S%jbQiql-z1`9Yx{loa( zTy`$e#R^6vhz=H|;NapvXUcoZJ}F1yiwuy0x&M4}f>sY_`r00 zN;=y%6{1M6%bLjdx6(Qd{Qz09zxO9D+jbcOHaIl>3wi2{lE+RKj zU~OO#2SYacDxdOwj!mM|fp7$)*D7SeZR2Or@7H$)mWK?Yf}{MtVtEqcisUg2%rSp| zk}7rqQ;F}I*~Lv8$Q=p3(IbpNnhn{nkN{po>-%=MH;f_{_a=Rda6sf#{5i|+!=fe#g+=2N8>NLmBn8OYcoTHf(ID>`p zs|%>;UCX+#Rb<{2x1!Ru$&shsy-aB^sW-g(9-71nzn;c(u8zl0Lm3FRuc`#YFB`TQ zX>ctHH}-C4I*R#Ko{gy;Q9%nc4rtu`K~X!Dky`(VceV$i>gGbW-R;iL!|^G$8F&o6 zXwmG&q5ZNf*J7b|>@!YT#NNesdMToH7>Ttk*YTYJw%`cD#uWilHzh8b7g+U?Pe1>_%}U3OaR3e2`9;`Io>uA%0XlDLu|$~~G>KqQrtc)8ZYbHG740)z zb+f5q*PbN$34YueA6bXlYz7MZ#%l1&M99BBCq_HTl4qUa6$n{`DPT;%Nj1HW`}Tn! zsh$X0f(!dSgZqa_lidb)O`J30;AHy59^om!s14IctZn{4gGi4FpMQy z2J+ItAs%O{1^v~&P&VchuY(~PpqFsgc?v^7JB$N7pUY9!x-38dLkTiX$gagM6Pj)@A{8&4vy~c>VE^4U-ao=iJoWG5l_$^+>5v7FB%{% zCy+!mPF9mrCB!ZABus=3g+!s)(qd1wO2fL-vwQ0FR# zZC<0d7a~8XLuwgagc_sm=>tPm%YgCoB%v1PiE8LMP}~3lB^93kNV=+RMZqxoN+5kH zC4zv`dM5&cgdok+&*scpv*wg2@y8cCFy_@4WwviuIy|a!gjY+XuZLSWzxNniLWQz{ zn1gmB_?P^Jic$2b;v4mJAlw_~4euog^ZJd*QcMpKzIhCmLcX-9l>w=JO&(DuDX;YB zqX`>M3w%7C&5T;FJL+fmc-q2w8h*G9yMN06TGf4PY`A+M0d*#RG>gC1O-o6~gHq(F z>1=pmoxEIiBZ3qGVQcRfvXDZ?=Q}D}Q)l|2$S)3ebH)1=VMJ z-m&4R>UOk>mU$w-pV&S;mwiV(BbY+%ajyB!lT8-SU-m`TuI6Ol_9zDW2ykvJKC-L! z=3~p8hkZ#Q>nkb1Ht7t>*lzwp*y{b>l!i67!9fG|P!yVzYQWiMM7|KX#C)s&XsLv`SM~t9G&D`j|&MzCK@VqZT`{eeu_?14pmj}R7+`^^8 zhP@#%6ze75phc0t*2|K%>GmWb4Cs!LcQ$dT+Ptr)fP8=2%7Vmyb#*U}j4~(#*^NLs zZkYU{v?7;cJC!7mc1+#d6QSOWRTy#+J_8q{3xA|s4(mwrAOrOgOU1-x+1XS!`bE`X z?$N7|Mh|sgf$ilYChuufEFsK_`2+6EW+T$OTNI zI4o^^^zmkqV|Hxdc(Fp`O+QG4@n9M9czJ$2%O<;zb<5bR{zhPY-l7BMJCsd8EMgq2 z>fO#{Py;6FuYbN#vo#{!E{tDsEWJW+KjLtnXb^`V1=oG2T3SH`qe+CeESUk>ngsms zg6Ll59+9tezaU6Z3dY4XhP6Lb|F*SKS5sprFv~MsnYDVl%)+KOPt3v|V&g7h71++y zZxRTvG=AX(FdX%*TXViz4+&wqivI(thT7ukN4=eMTdi!R@luc(2H9r1fR7VRjsDf7 z^j%I6mPL(ozrpcVztbzocWDB?$ZsD}p5IA^#4Xgktlt$LkmuoeQkiyu0Mhu=|aVS9lBZJKHK(i+?9+~~thfAon7)3(zxg5fzKrp@+Z9ezW5=B@OxxI>i|)hmRI0&E2( zXMi@y?f2$dA?xcpO^FPS_eww@l=;4XCi9Np zml{{omG$}2G8|+xFmFYUh<#%Gq2M@xgkA@xcP0GtjiuxxJ!}X}EA#IK`Elu!X3|E9 z67TNoHhZbN54^3vx|X=vuQ5s}ly89fJevq^sSxAij?GhoA39zfiZJXOyn8}$c^!a7 zLy=yiI{bED26uOsbl)dOFt2HZWKSf25dXx)Bm?DRe$Uq+FqzDlk9l@lUP2zQ5QwfX*=E^MZ$Y;s0zV#y*9yzi*svKM@rcc&`R>?DD9EszX zDyz+7q_WVo8~{}n%uND<2pLYfpbi@YWspxA<2{MPwJd0u*;9*11@0sY6K1H*hrjCx zMe*Y+cp7xy*oi?>NJOQ}SiOGN5DLW-r`=zqenwpm@1y4oL!XbKY?spqNU;y}7J2VZ zPv=2fmiYQR;-iQ8j&5RdKCAn>$}Q*m=LD#*;`l{8L5foTW6H#>zwZEG!>?08=KAQ0 z_6HI%;Iu%~Eg}#_`LrmBBuG4PKBhQFzah>vpHGfsRmcv(lZcsxywV*y6E<^N!aqq*-API{@zTX(lH!*c`OhiwUi#5Dw zKvLs0=+b~8^1 z*ihEiM&)bC1|~UQjc!|^*j_jHe)~bYMEk44vYlpARd%Pabx=%Bdc=Fn>-s?|dfr{g zTG21hjwx-nk?xWNXOYwaL>j~O2mzI${dm;{^gNv4yoX-+hgC=OMML6rfg+DUipUzd>A6-}a}flzw+1 zP6MMLh1#;R+$`X>gP#eJ{(FHPV&8Y*Z*2M7v8GoLUhA^~DeL*cruJ5TTa}#H=z9Ip zHw4J(Q`&h$rh$z`_|5dgxLzY2a$rM_GaEyA!n zq%ehe0AJ*yVs?KvEmVFAHdyiZFzr4Lu0q^1HX%8G!ub8MWw~iD!n!oUn@<=hR=-BF z@;=QIc@m6@DBByVgj`|#aUlaR9F6bf7coaCw?5n>AFv?WRv#T@vdPH=cJG+n}e1fR$4%-!U{y`tds$VOL>yb@mSUG$9P5BC(FK!@Gf zWk*_yAP7aL#r-)hN2LhKM*%^tdM59i9}Q1QpO1pMtm%WEKkpWSU{1hF2qQ?my<*~F zQXdPHNz^9eMGan%Xd@8OdK0#1F}MSJLmh@z>h+gheNIp)GHCbrQ_oY|O3#B1gL^oW z;^Pi2&4CIpU}~r*00Ytp_J8LP=_U6&z`2M%?cQ|a@627!W73lEawbym*;ZjkG$*$g zf$IOnkknLV{}8JD9*dUw64s~nY}CiXRL)`)FP}%YUWoXm@Jl%#3A|{{HQRkrTLm=# z8KgsGIqEhKlnzs5KF~IU@Vcuv&|g{(NT&N-tkHtCq!N53gIOMxl1AeQZS1c~xVb?@ z{l!xD5?1a#PWp+5hQcH{P~_+%ABr~n2lmZA2z}lZ?MmigTbd8gi9xweyPO)+g!jew zb-QG*rTj)0oZ`MpM9|}yYt(N1mkw>f`7ffQuyafq;~+8+jraQ8j?<+yhK!g5D`cAN zv8b#CcY{d(Zmt?WNl+2I-$qx>v3{I}c8Dg9XiC^*pBPAC7LC3g7%rHN465n{n52w*5x#5+0rO7*OJ?exi4IJnE7OqPqYU->9kxH%qqm6{?;mu%9b;ERFdT zSS(YcKEuy>|K{jp8Cec-IRR>YA&=;s^V@7(4{_{}dlg18O$vj@p!_muLbw)wv zMSp>L`BrN`h21Dil?A#WB~}K>M&9CZFg#IEspkW7QSKzX`gvBpz&XD$^`KI2GCZA) zTDGSrxx@{p{B~IHA+QC~_YDul#?7UIEmX7Nx$n6gkTS*vDlJvFUhcy6K)`USWXJkV z`tR^td*LGw_sl+(#`e32S>qv2B|kD9g9IMe{y{haB4pfv=4+j&ay9y+v5S|gMfISN zeT!m+U8u~w#7O>hQ?B=hkQkJ$;4>_0Gymph*`MM8jJ6ft=@J0HBf9Rd$^E#Hul*~C z_9RI2Qv?(8JIdPP{;UZVptORubFk6FM+XQ|2Sr(_>q9WHrbA~)a}N5>_5K6b`cmF`zSdDDF;#gO;Bw-``jzsi*+8MIa)4+eem?*&q%jv$TOya?G zf@%0OgBo`)VR4(4ZvG87iXHP0;{*9~f-k{i=>YO2t~B^ZstG23`A2TZDp|-Z60+YA zZGuZrejR4>uv9|+k%Q!FT;F-g_ITHQ718QbZLK{c_T2BAw2&2xV?bGSR-cpPAzh)w z2yycC6ug*SbOyO$%oD?>ajp|qaLY=~G6`9TyHZbrgLd`fPIi9!=5KvJ@mQ*_AR=sK zgmIdn;GC%-rjGkabsk!TXc!8^L-6~u=i^{R?OE7I4EQ#z2}%Qu<_7&!`o z_R~zj`D+3GF_f;P%WZfa+xz)JD_8Mel?-_wrxdA*FfYwqDOL14iFrsdO-^dwf-a=bvF(h zQCB62lSJKTv)lB}*GIO_?*vI^KOYMeiZ1He@2|eP;uI93Rk)`gy2*0(VT?Pq%5T1) z4RglJ@HXPYL9mAb+9u~ndv@Z}NuR!Zjj`4U6T}!`D@7CUq*m$`Iv4a4`UPngUD+{? zq=Ru}`>MJgp4VoCATwSTvb3w-Tc&FsvXLKiZuDqQdmUtP7{dM=>XYbfiw1w##h8}% zIK8cBhiKc4d|dt2q6zp=-@~~F>fSj`Ib?N2Nv>SNZ}-LoZC>#Ip{H4a zX`5{dp63D*HU?zmLs5H^T6&D1$F-UeE#QS&ro_has=PecQ@kf!hN0+nKhnI$(qQ!J zFKt7>p*GiPPGV|EF5e1}Rt;oGcH>#7A>1gaP7c01&>^?4#n27In)8E?@y%+$^x(}) zOq?jJO-Az&JmyVn%KaH_myzdkbMxxb307pN9aX#``eXw}`KAu9_ZiUd#fI2k8J~!E za5CcR=GM!zIzr@(e!^>bfzDX!@>s(Dv15 z%}6ssJab5Ws;fT{p}Xu4MkVPVb& z03oG+Hc+sx`H)u&GDnH&(?X=TLk+chcfaV4?|kJl03Crtca)O&cv>iL!sryd)MSS4 z^-6*O<@~_rTN#G_YG4_11+zvA>j zIP8rbWze1$?(sXjNO0l{eRtfuZW_Wk>%i1aH4qt#sMy&ljPnKv~IyG8!`waK2WXw(Eveek0h}H+N0@J8suk7@5?UU z2088vR^q2y0O5q`&45iB0rGsrV(Z}*uavsYO7uA=b#tay5Xa!5e7l{gU3dVFUl$2{ zsByZ_FK_&rIQe&9QL}U6hHZZ$r_Z^z$cJvKCqBM903Lz7fg?paq0de*90(|}P{Riw zwfpwMQpNiss^;ei;sd$x(g}Jqy}F_LB)?S2u3`-Bre<$gn1&7GHheROmA`d9_Q7A~ zv>zheXJT4X zWc+D=9<%5iD6rFlL+=5Uh^mn(z?vf2R)_uM@N(z*_$2)bEESDbrop1G+sD$)M^xvv-}4JV0w@sM-)HPkMsnUvq?6Wy(}-hp2X+7f#$fY`8&x@13+`ruT9G;v~2>+i@n4k6g?4 zcK>>E8+-}k3B?c5Bi2@zVS5Hz3ab4Q+ykyh$3`9&?voeL!U!(H&Bp?+<+S`t`9re< zY~V-w_=LgudxQjPb=cwhzmY-CD2(Y09YqNatnN?PW968>73Mw3Ufqqz*FEz4G_+zr z3=)!k@}NhhX|Nip4<~-lfYgA!UJ&8W;E8HP)jnT=;^*gJgWIxx=gq^^ZgypT28(IO z<=4YMHE<%8LRFr7J1z_)KhtsC0ch&=VL4*9wUqJpY%!_yl>~9WDCv8monXt z{j|L@J3@dyl~+yb$TdxP%u(npiIb-Z?sFnmQ+#RX0gPNHE`$W?mzHoXp>9wVj9?C4 zzHbK5J2bG_jJnR341-hTuK4YIgTn?)*l`+wmO~HDZY(etU-+BI>cm&(nLogMe*-ze zAjsgheE2gQIgY1u@d=Clxxa1jLjG`L)S>@CCR0B@ya6t54@m3WBjxqG1GskorNOd& z-ZB?0)cFC!-`juyr zF-l+t^zZ}UjG7@@1Wv}nNlUoux7#|95BLM`q3^!5CBG+Y2pxZU0ZqodenQG_MDl6` zxPiC)Q1~$2JfE;NKrGy5G8Pa*e1A2U_Tk?CYFQ#%yzhgPW|_EFU@9C}bXH%<{p0I* zgN`b8fwV47L0!IwdbrhN^D5M=_bS77bO(H90u|=n?M`&rYTv#t1Egc$9h_Hka{MRX77rqmRtlmw*`439T;f5AVv~xT#D!9`C9hd@KNZZ1_VheQBZ&_A zJHDN?odyXR@bVSSrA6Dp;m3szc?DM{=9;Lh=3K^IOt4jc$uZ_SORE#>Ovu z%K!oAk2J-Zogxx#;$+Zzf)G4;{q(C$f2B-$!G#DWd|9^M8R(L7{hcoM$^l4YIDS{O z;6wLK-KG{Y@7xA^k!pViXqEV=y!=7+0%QmS*+@^L~zKZ zw07Ts6yrjl(&d6RYD{~u;d^;Ke#wW3ItaSOb`LAYyT=JPV?)J(erWNU-?WjP%s7pB zJW|+!P|2wSLJm%ozrWUV>_UO$TQ%HIKr)nVA;=F0xLK3W4`sKC(&zV2raf`q5wSiE;6 zq#QIMy08TR>3(d!+lz_AOE{!`}iv49`T}`!k8S(9s?SU61gs?VZUoM(& z&p@ga`%tFMW)=oe3pt74Vzt8s)d?~CX6_G@pOvPqhk?9$BKOBRUc;W{dbk+eC@Xnr zzcjLE;!g6lYk#)4A?CQD>H*lz(3{-m)snyS<>UXA-}HMVHNR96lXF*dB9#a`z~t|keQFq@_J=+WApv+5DCn9s9C7n ztDuxu?bigs?F`{3D_S+cBtj_>NjMLGu~|sC_Ut~0n0*AMI~G#png_zPy23s9C^~Zvsv&d{pY0!Yy5ITb zI@9tV&%^=w{RR8|?JGM1Um^Tu?LOHm@yDX^z6TfHUHziYB_5yYKCht_9%kmwwY7YcOb^npWLLIkZggSA)2E9dUsMgS>12G|f{yRej3t=R}OB_n4)3QEotq=2USgapE=DtNw}J zLrA!@UWfddgTpg^Tn97ZX~(HD@eM+h2PJmu_He~wpo5F0v>7j z&GcPAotN83!9MoC*D#Rm$%nuBy3uPYtuL%3YI^Lgj`KedB*OrL|mpsTbQ%^WP_U zWkYv=k3WT*x<71@NTFh3>6MBNoRG498$*bkyqybWQrGo7c;rRtHcH)Xan$dkX@3>P zZ|^KkgIO(_1)~+f)6|dVP+k3ltPaN*rzd{Xb!DR4+$1d)xGOX_jk40^udv4eGi@a# z7quq~Pe(kR=S{W%((H)Wez}HyD_VM7E?o`oQo`~Ff5?9ORI<bcY5PJ$Y*LJ9M5G2{Ni-&`&3J%P;7|D-y+Ps0)j6f4i1=GwLP zJj)9|3M~tB4vqTM>atoLj5mX)2`LUIOFNKohHD&1V{n*m+J1!fz`JLK(I4*k$u)sS zx?LJzCa(PAbM7v>q5AVLnm$+de&9Q_%lV}Zw}xJ-6jh${c{Nw~+$Y)jDT4Kk^x(3M zzw&Rkqel*j#qBQW+I50ur&4*t@$lUO+C7B~(0nkZ-v|2{i?7-z_iOs1FOIt&EGzku z9mK97-pViULzIf887?ZVKKfoE-`(*(?2DvMea9JJna_NI<>P6h!hC=)vY)^BfqFp7 zGY6*|%Z$i=;rp_X_FNT6A@2fJ)HgfgL(Cf};lZ8eT-Z#W^jE^w?q&UjId7LQ;rXE} z>)okPQhMCXNjd7Ru+o=CdTMF0O;7ZZwDY(AZQGeF?dT*ouPF?u)}5*V9}ylbP#?lI zqaZwE0$QK&YMZKu3NDEF^AV3(9MF&mF1PwI>cpofXe;=vI=cVg_a`(J_K)XD_t%yw zJnSxNLnVi+BbiP}L=IF2+MDIV#*c&H3tPD>SV?%w%)G}PEVb8HeQ%{=gp9?U zn@76E$LfgzW!K^l6?DE%ASphFKs}u@`l}L)K9Dr)u<~`?r8)(SZ&>wCMb3;*;7EOp=wf3&Lfw>q+7uh5{LfNMV@`%Z}ObV z>;v4)f;Z#v1u-p{s*AR9(puZf&Yt10^7~ZNuP0RML&L@Z+xIEyN8S!rv#n+h-#jq1 z`o!IL2V}WU^4_)vd{&2+pfW3%vil6e5j=ozu>w+-P5%0VS+-dta!=e zvl`PrL=({5`9Y{{IK=*@qVNln$zE-9Cy+(4{;Ji%8+;b5kX`8hjzR>Eh4T^&^6|eS z=<~00)5&CipT-L`K$NTLF1-^kaGiP@c-rva86k9Oz%$VmA;;vU3}iLO!TDm2LS+7E zr0*5D5X9Z)BvV9MB!fLZ5;h5jPf$QbNA8cEHb3U{8)Z1-iD9)WCZJX>qb5E8M+RFW zC|~2bg^fS;^s7Cpg^B_NS64Gevx3rxOmM}l><@q(^d*6_`O(sP z%?8k?oDni-QPUu5BRpeXp-i-O?O)*lO{Q!XF% z$&DAtH38p$h)iS>el6FJ$CIPaUDw;&h?NEsaC zZt+nkb*xw-$2}FcN$z6PJ+eDCTPWjIe_D{jzE65oP{1xgD~=zkekFrP4~YoFKbGE8 z0v9zpe^V4~Pv_EI_))}o5bd2$7+NnY`;6~!K!?b;EC8HNJdrW?gM5RDdu+?30xBvA zg*gUrsUJ+XqCLyooZA?|D`(%cpA1&t-ETnbuJn9sx4f(JB<>i<;P452Hn0ltXgoG3 z81Z-GGV85&Nmwd3_q$MJ%mMvEpowTs0i77;&3e!?@&mRIjfIEPHD}eh65o*?bYPq3 z$_viFI511kzKIDn)R%AkcI}k2Y0-N8_OZ&nkMBUIz*N&?&h0uP2jlcTeQi(d-ZI!O zr)^iWP?@Ov(^za)e*9c@teUESQVbZw-`>4%#mSFI;PChF>M52LhtG%h zrSoIv_?G|*E-APJ_nW%%tCiO(Y89v*uD8!fMlWVh0g~;t6@r7Pln*y?x3XM(fXJ_5+%^&(x=3`VXUE~2qA7bAdMqn^X_(By zTTy0&nXHzw3Q_6v+nV0c`rQt&7WemvB(0jmmVt5X`RVyOy8F}v0${!1if`O0VamUwZ5^!;8o$vlKmWPk@&W}_h1{41tN=r7zI}~6_!Fi-OHQ~r1JrO zr&-D$6nE?O^E4b`E$dvN;ZWS4-#gnnit!TaURf3Y@jj^nI@FM$2Z{`y5Y;Sda#R7K z#eP$GIw>FGd|#yndM59jqDGheB?*z-*hk!k8d=<=Y80az1d~e zR!kYZ(miI)i6r(*kKSHaehCQGEtx-j4Uv=#&gKK^Il7#ZOUiaz3wP!>f^*(uCEL(o zuoZy{>T~zpA5gSDjRttR$2s_Ca7#GyAYOBV5v{=Jhph&cD zvryW+_K?DO*BlAw>V0TrZmfgPP?sF^fBvG_^XKG9Amd9XyUwCl#dcS`OZmoPt3o&@a9q_)wQm4e5?N);Dc$WWdA*hd+CP+Si0K0!Xk zHy6%1z@Y8j9)KgJ>`YgN=zhb(F5fJ8TnY|D@8}aTc|PA&%;gtl!j|-W<$ZgvNRB-? z_Mm=_yjeoiTigWMsjSKTzBcVBwDdmEcw--d-mB2_{sYs3Bd6)Cj9-nC&`9xnPcXR~ z%3%1EL+ihtKXFAk%p_HVlkN`maAYoC5!V!*u=JPE!5)Ut#)AoywlG4O&d!CzG8o2r`rs{8-v8);(AmuUi zY?B*(^Y~>*npodgKv`SeH-sqx^}1h>0G{W0&F|y6{^r5E6B>g^H{50jr@Z&OJ#Bb4 zYVlbQ?DMF{$r0m62a)sq?YOZ2iwYI`*qnc>3K_(opEPxf@hQT|NTB8?j=lVeb-}aN z`B;?llY?}JUO}#oxuBw>zSS|$gEssYNe*|CS=!ga3i7#D)+6&LpSkXJFYMJY^ zPu|p6m;#+3(x_eIdxpH5nI z)MUomOcZmhuLfq6D$aWJCvm